From c02e197e778074f069711751f2c09e92bd862891 Mon Sep 17 00:00:00 2001 From: Jorge Bernal Date: Sun, 17 May 2015 17:39:48 +0200 Subject: [PATCH 001/115] New btConeshape member functions to can set radius and height for the cone shape after creation --- src/BulletCollision/CollisionShapes/btConeShape.h | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/BulletCollision/CollisionShapes/btConeShape.h b/src/BulletCollision/CollisionShapes/btConeShape.h index 4a0df0d55..46d78d148 100644 --- a/src/BulletCollision/CollisionShapes/btConeShape.h +++ b/src/BulletCollision/CollisionShapes/btConeShape.h @@ -43,6 +43,15 @@ public: btScalar getRadius() const { return m_radius;} btScalar getHeight() const { return m_height;} + void setRadius(const btScalar radius) + { + m_radius = radius; + } + void setHeight(const btScalar height) + { + m_height = height; + } + virtual void calculateLocalInertia(btScalar mass,btVector3& inertia) const { From 5bf125cab525778f5f73395eacfa61fc542486d1 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 2 Jun 2016 13:54:52 -0700 Subject: [PATCH 002/115] fix some compile issues using premake use textured cube/sphere model for test --- data/cube.mtl | 2 +- examples/RenderingExamples/TinyRendererSetup.cpp | 4 +++- examples/SharedMemory/PhysicsClientExample.cpp | 7 +++++-- .../main_sw_tinyrenderer_single_example.cpp | 3 ++- .../main_tinyrenderer_single_example.cpp | 3 ++- examples/TinyRenderer/TinyRenderer.cpp | 13 +++++++------ examples/TinyRenderer/model.cpp | 6 +++--- 7 files changed, 23 insertions(+), 15 deletions(-) diff --git a/data/cube.mtl b/data/cube.mtl index fca828974..26b4b44e4 100644 --- a/data/cube.mtl +++ b/data/cube.mtl @@ -10,5 +10,5 @@ newmtl cube Ks 0.0000 0.0000 0.0000 Ke 0.0000 0.0000 0.0000 map_Ka cube.tga - map_Kd floor_diffuse.tga + map_Kd cube.png diff --git a/examples/RenderingExamples/TinyRendererSetup.cpp b/examples/RenderingExamples/TinyRendererSetup.cpp index d7e9f05aa..11258779d 100644 --- a/examples/RenderingExamples/TinyRendererSetup.cpp +++ b/examples/RenderingExamples/TinyRendererSetup.cpp @@ -147,7 +147,9 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui) m_internalData = new TinyRendererSetupInternalData(gui->getAppInterface()->m_window->getWidth(),gui->getAppInterface()->m_window->getHeight()); m_app->m_renderer->enableBlend(true); - const char* fileName = "teddy.obj";//cube.obj";//textured_sphere_smooth.obj";//cube.obj"; + + const char* fileName = "textured_sphere_smooth.obj"; + fileName = "cube.obj"; { diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index e249977bd..a57fde289 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -527,7 +527,6 @@ void PhysicsClientExample::initPhysics() m_selectedBody = -1; m_prevSelectedBody = -1; - if (m_options == eCLIENTEXAMPLE_SERVER) { m_canvas = m_guiHelper->get2dCanvasInterface(); if (m_canvas) @@ -557,9 +556,13 @@ void PhysicsClientExample::initPhysics() } - m_isOptionalServerConnected = m_physicsServer.connectSharedMemory( m_guiHelper); } + if (m_options == eCLIENTEXAMPLE_SERVER) + { + m_isOptionalServerConnected = m_physicsServer.connectSharedMemory( m_guiHelper); + } + m_physicsClientHandle = b3ConnectSharedMemory(m_sharedMemoryKey); //m_physicsClientHandle = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY); //m_physicsClientHandle = b3ConnectPhysicsDirect(); diff --git a/examples/StandaloneMain/main_sw_tinyrenderer_single_example.cpp b/examples/StandaloneMain/main_sw_tinyrenderer_single_example.cpp index 69c3b7db5..786e0eed1 100644 --- a/examples/StandaloneMain/main_sw_tinyrenderer_single_example.cpp +++ b/examples/StandaloneMain/main_sw_tinyrenderer_single_example.cpp @@ -111,7 +111,8 @@ public: if (shapeIndex>=0) { TinyRenderObjectData* swObj = new TinyRenderObjectData(m_swWidth,m_swHeight,m_rgbColorBuffer,m_depthBuffer); - swObj->registerMeshShape(vertices,numvertices,indices,numIndices); + float rgbaColor[4] = {1,1,1,1}; + swObj->registerMeshShape(vertices,numvertices,indices,numIndices,rgbaColor); //swObj->createCube(1,1,1);//MeshShape(vertices,numvertices,indices,numIndices); m_swRenderObjects.insert(shapeIndex,swObj); } diff --git a/examples/StandaloneMain/main_tinyrenderer_single_example.cpp b/examples/StandaloneMain/main_tinyrenderer_single_example.cpp index 77ab903ab..157ab233c 100644 --- a/examples/StandaloneMain/main_tinyrenderer_single_example.cpp +++ b/examples/StandaloneMain/main_tinyrenderer_single_example.cpp @@ -254,7 +254,8 @@ struct TinyRendererGUIHelper : public GUIHelperInterface int shapeIndex = m_swRenderObjects.size(); TinyRenderObjectData* swObj = new TinyRenderObjectData(m_swWidth,m_swHeight,m_rgbColorBuffer,m_depthBuffer); - swObj->registerMeshShape(vertices,numvertices,indices,numIndices); + float rgbaColor[4] = {1,1,1,1}; + swObj->registerMeshShape(vertices,numvertices,indices,numIndices,rgbaColor); //swObj->createCube(1,1,1);//MeshShape(vertices,numvertices,indices,numIndices); m_swRenderObjects.insert(shapeIndex,swObj); return shapeIndex; diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 77c387176..e7dfb8f05 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -76,12 +76,13 @@ struct Shader : public IShader { float diff = ambient+b3Min(b3Max(0.f, bn*m_light_dir_local),(1-ambient)); //float diff = b3Max(0.f, n*m_light_dir_local); color = m_model->diffuse(uv)*diff; - //colors are store in BGRA? - color = TGAColor(color[0]*m_colorRGBA[2], - color[1]*m_colorRGBA[1], - color[2]*m_colorRGBA[0], - color[3]*m_colorRGBA[3]); - + + //warning: bgra color is swapped to rgba to upload texture + color.bgra[0] *= m_colorRGBA[0]; + color.bgra[1] *= m_colorRGBA[1]; + color.bgra[2] *= m_colorRGBA[2]; + color.bgra[3] *= m_colorRGBA[3]; + return false; } }; diff --git a/examples/TinyRenderer/model.cpp b/examples/TinyRenderer/model.cpp index 626cc2331..f7a0bea75 100644 --- a/examples/TinyRenderer/model.cpp +++ b/examples/TinyRenderer/model.cpp @@ -57,9 +57,9 @@ void Model::setDiffuseTextureFromData(unsigned char* textureImage,int textureWid for (int j=0;j Date: Thu, 2 Jun 2016 18:04:22 -0700 Subject: [PATCH 003/115] Support the field under in SDF to make the model immovable, similar to setting the mass to zero. Add joint velocity motors in ImportSDF example. --- .../ImportSDFDemo/ImportSDFSetup.cpp | 54 +++++++++++++++++++ .../ImportURDFDemo/BulletUrdfImporter.cpp | 17 ++++-- .../Importers/ImportURDFDemo/UrdfParser.cpp | 14 ++++- .../Importers/ImportURDFDemo/UrdfParser.h | 7 +++ 4 files changed, 88 insertions(+), 4 deletions(-) diff --git a/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp b/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp index 54883298b..f55cc9758 100644 --- a/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp +++ b/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp @@ -235,6 +235,60 @@ void ImportSDFSetup::initPhysics() ConvertURDF2Bullet(u2b,creation, rootTrans,m_dynamicsWorld,m_useMultiBody,u2b.getPathPrefix(),true); mb = creation.getBulletMultiBody(); + + if (m_useMultiBody && mb ) + { + std::string* name = new std::string(u2b.getLinkName(u2b.getRootLinkIndex())); + m_nameMemory.push_back(name); +#ifdef TEST_MULTIBODY_SERIALIZATION + s->registerNameForPointer(name->c_str(),name->c_str()); +#endif//TEST_MULTIBODY_SERIALIZATION + mb->setBaseName(name->c_str()); + //create motors for each btMultiBody joint + int numLinks = mb->getNumLinks(); + for (int i=0;iregisterNameForPointer(jointName->c_str(),jointName->c_str()); + s->registerNameForPointer(linkName->c_str(),linkName->c_str()); +#endif//TEST_MULTIBODY_SERIALIZATION + m_nameMemory.push_back(jointName); + m_nameMemory.push_back(linkName); + + mb->getLink(i).m_linkName = linkName->c_str(); + mb->getLink(i).m_jointName = jointName->c_str(); + + if (mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::eRevolute + ||mb->getLink(mbLinkIndex).m_jointType==btMultibodyLink::ePrismatic + ) + { + if (m_data->m_numMotorsc_str()); + btScalar* motorVel = &m_data->m_motorTargetVelocities[m_data->m_numMotors]; + *motorVel = 0.f; + SliderParams slider(motorName,motorVel); + slider.m_minVal=-4; + slider.m_maxVal=4; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + float maxMotorImpulse = 10.1f; + btMultiBodyJointMotor* motor = new btMultiBodyJointMotor(mb,mbLinkIndex,0,0,maxMotorImpulse); + //motor->setMaxAppliedImpulse(0); + m_data->m_jointMotors[m_data->m_numMotors]=motor; + m_dynamicsWorld->addMultiBodyConstraint(motor); + m_data->m_numMotors++; + } + } + + } + } } diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 7e9624d64..4838079a0 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -267,14 +267,25 @@ void BulletURDFImporter::getMassAndInertia(int linkIndex, btScalar& mass,btVect //the link->m_inertia is NOT necessarily aligned with the inertial frame //so an additional transform might need to be computed UrdfLink* const* linkPtr = m_data->m_urdfParser.getModel().m_links.getAtIndex(linkIndex); + + btAssert(linkPtr); if (linkPtr) { UrdfLink* link = *linkPtr; - mass = link->m_inertia.m_mass; + if (link->m_parentJoint==0 && m_data->m_urdfParser.getModel().m_overrideFixedBase) + { + mass = 0.f; + localInertiaDiagonal.setValue(0,0,0); + } + else + { + mass = link->m_inertia.m_mass; + localInertiaDiagonal.setValue(link->m_inertia.m_ixx,link->m_inertia.m_iyy, + link->m_inertia.m_izz); + } inertialFrame = link->m_inertia.m_linkLocalFrame; - localInertiaDiagonal.setValue(link->m_inertia.m_ixx,link->m_inertia.m_iyy, - link->m_inertia.m_izz); + } else { diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 60b40b512..430593b5e 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -529,6 +529,8 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi link.m_name = linkName; if (m_parseSDF) { + + TiXmlElement* pose = config->FirstChildElement("pose"); if (0==pose) { @@ -572,7 +574,7 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi logger->reportWarning(link.m_name.c_str()); } } - + // Multiple Visuals (optional) for (TiXmlElement* vis_xml = config->FirstChildElement("visual"); vis_xml; vis_xml = vis_xml->NextSiblingElement("visual")) { @@ -1240,6 +1242,16 @@ bool UrdfParser::loadSDF(const char* sdfText, ErrorLogger* logger) UrdfModel* localModel = new UrdfModel; m_tmpModels.push_back(localModel); + TiXmlElement* stat = robot_xml->FirstChildElement("static"); + if (0!=stat) + { + int val = int(atof(stat->GetText())); + if (val==1) + { + localModel->m_overrideFixedBase = true; + } + } + // Get robot name const char *name = robot_xml->Attribute("name"); diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.h b/examples/Importers/ImportURDFDemo/UrdfParser.h index 1a855f281..b83c0b3c8 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.h +++ b/examples/Importers/ImportURDFDemo/UrdfParser.h @@ -134,6 +134,13 @@ struct UrdfModel btHashMap m_joints; btArray m_rootLinks; + bool m_overrideFixedBase; + + UrdfModel() + :m_overrideFixedBase(false) + { + m_rootTransformInWorld.setIdentity(); + } }; From 4b2c0f6d8990185691c482e28cbda0c1dd6c59f3 Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Fri, 3 Jun 2016 19:03:56 -0700 Subject: [PATCH 004/115] make one of the cubes in two_cubes.sdf static (immovable) using the tag in SDF add an example using 'direct' fix the send-desired-state commands, to add flags for arguments set, using default values. Start exposing SDF loading in shared memory api, not fully implemented yet. --- data/two_cubes.sdf | 1 + examples/ExampleBrowser/ExampleEntries.cpp | 5 +- examples/SharedMemory/PhysicsClientC_API.cpp | 30 +++++++ examples/SharedMemory/PhysicsClientC_API.h | 2 + .../SharedMemory/PhysicsClientExample.cpp | 22 +++-- examples/SharedMemory/PhysicsClientExample.h | 2 +- examples/SharedMemory/PhysicsDirect.cpp | 86 ++++++++++++++++++- examples/SharedMemory/PhysicsDirect.h | 2 + .../PhysicsServerCommandProcessor.cpp | 57 ++++++++---- examples/SharedMemory/SharedMemoryCommands.h | 21 +++++ examples/SharedMemory/SharedMemoryPublic.h | 6 +- 11 files changed, 202 insertions(+), 32 deletions(-) diff --git a/data/two_cubes.sdf b/data/two_cubes.sdf index 24c0854bd..10dce545e 100644 --- a/data/two_cubes.sdf +++ b/data/two_cubes.sdf @@ -86,6 +86,7 @@ 0 + 1 0.512455 -1.58317 0.5 0 -0 0 diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index 75e16b8f7..b6004aeef 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -242,7 +242,10 @@ static ExampleEntry gDefaultExamples[]= ExampleEntry(1,"Physics Server (Replay Log)", "Create a physics server that replay a command log from disk.", PhysicsServerCreateFunc,PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG), - ExampleEntry(1, "Physics Client", "Create a physics client that can communicate with a physics server over shared memory", PhysicsClientCreateFunc), + ExampleEntry(1, "Physics Client (Shared Mem)", "Create a physics client that can communicate with a physics server over shared memory.", PhysicsClientCreateFunc), + ExampleEntry(1, "Physics Client (Direct)", "Create a physics client that can communicate with a physics server directly in-process.", PhysicsClientCreateFunc,eCLIENTEXAMPLE_DIRECT), + + #ifdef ENABLE_LUA diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 31b8df6b9..914c9d091 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -5,6 +5,29 @@ #include "SharedMemoryCommands.h" +b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName) +{ + PhysicsClient* cl = (PhysicsClient* ) physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + command->m_type = CMD_LOAD_SDF; + int len = strlen(sdfFileName); + if (lenm_sdfArguments.m_sdfFileName,sdfFileName); + } else + { + command->m_sdfArguments.m_sdfFileName[0] = 0; + } + command->m_updateFlags = SDF_ARGS_FILE_NAME; + + return (b3SharedMemoryCommandHandle) command; +} + + b3SharedMemoryCommandHandle b3LoadUrdfCommandInit(b3PhysicsClientHandle physClient, const char* urdfFileName) { @@ -146,6 +169,8 @@ int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); command->m_sendDesiredStateCommandArgument.m_desiredStateQ[qIndex] = value; + command->m_updateFlags |= SIM_DESIRED_STATE_HAS_Q; + return 0; } @@ -154,6 +179,7 @@ int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); command->m_sendDesiredStateCommandArgument.m_Kp[dofIndex] = value; + command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KP; return 0; } @@ -162,6 +188,8 @@ int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); command->m_sendDesiredStateCommandArgument.m_Kd[dofIndex] = value; + command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KD; + return 0; } @@ -170,6 +198,7 @@ int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); command->m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex] = value; + command->m_updateFlags |= SIM_DESIRED_STATE_HAS_QDOT; return 0; } @@ -179,6 +208,7 @@ int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value; + command->m_updateFlags |= SIM_DESIRED_STATE_HAS_MAX_FORCE; return 0; } diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index b202daa35..37008aceb 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -88,6 +88,8 @@ int b3LoadUrdfCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHand int b3LoadUrdfCommandSetUseMultiBody(b3SharedMemoryCommandHandle commandHandle, int useMultiBody); int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, int useFixedBase); +b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName); + ///Set joint control variables such as desired position/angle, desired velocity, ///applied joint forces, dependent on the control mode (CONTROL_MODE_VELOCITY or CONTROL_MODE_TORQUE) b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode); diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index a57fde289..15c90748a 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -156,16 +156,12 @@ protected: { for (int i=0;i=0)) + { + m_canvas->destroyCanvas(m_canvasIndex); + } b3Printf("~PhysicsClientExample\n"); } @@ -563,10 +564,15 @@ void PhysicsClientExample::initPhysics() m_isOptionalServerConnected = m_physicsServer.connectSharedMemory( m_guiHelper); } - m_physicsClientHandle = b3ConnectSharedMemory(m_sharedMemoryKey); - //m_physicsClientHandle = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY); - //m_physicsClientHandle = b3ConnectPhysicsDirect(); - + if (m_options == eCLIENTEXAMPLE_DIRECT) + { + m_physicsClientHandle = b3ConnectPhysicsDirect(); + } else + { + m_physicsClientHandle = b3ConnectSharedMemory(m_sharedMemoryKey); + //m_physicsClientHandle = b3ConnectPhysicsLoopback(SHARED_MEMORY_KEY); + } + if (!b3CanSubmitCommand(m_physicsClientHandle)) { b3Warning("Cannot connect to physics client"); diff --git a/examples/SharedMemory/PhysicsClientExample.h b/examples/SharedMemory/PhysicsClientExample.h index b564d01be..a36a37e75 100644 --- a/examples/SharedMemory/PhysicsClientExample.h +++ b/examples/SharedMemory/PhysicsClientExample.h @@ -4,7 +4,7 @@ enum ClientExampleOptions { eCLIENTEXAMPLE_LOOPBACK=1, - eCLIENTEAXMPLE_DIRECT=2, + eCLIENTEXAMPLE_DIRECT=2, eCLIENTEXAMPLE_SERVER=3, }; diff --git a/examples/SharedMemory/PhysicsDirect.cpp b/examples/SharedMemory/PhysicsDirect.cpp index 72b5eb65e..37baeaa83 100644 --- a/examples/SharedMemory/PhysicsDirect.cpp +++ b/examples/SharedMemory/PhysicsDirect.cpp @@ -33,6 +33,12 @@ struct PhysicsDirectInternalData char m_bulletStreamDataServerToClient[SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE]; + int m_cachedCameraPixelsWidth; + int m_cachedCameraPixelsHeight; + btAlignedObjectArray m_cachedCameraPixelsRGBA; + btAlignedObjectArray m_cachedCameraDepthBuffer; + + PhysicsServerCommandProcessor* m_commandProcessor; PhysicsDirectInternalData() @@ -167,6 +173,73 @@ bool PhysicsDirect::processDebugLines(const struct SharedMemoryCommand& orgComma return m_data->m_hasStatus; } +bool PhysicsDirect::processCamera(const struct SharedMemoryCommand& orgCommand) +{ + SharedMemoryCommand command = orgCommand; + + const SharedMemoryStatus& serverCmd = m_data->m_serverStatus; + + do + { + + bool hasStatus = m_data->m_commandProcessor->processCommand(command,m_data->m_serverStatus,&m_data->m_bulletStreamDataServerToClient[0],SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); + m_data->m_hasStatus = hasStatus; + if (hasStatus) + { + btAssert(m_data->m_serverStatus.m_type == CMD_CAMERA_IMAGE_COMPLETED); + + if (m_data->m_verboseOutput) + { + b3Printf("Camera image OK\n"); + } + + int numBytesPerPixel = 4;//RGBA + int numTotalPixels = serverCmd.m_sendPixelDataArguments.m_startingPixelIndex+ + serverCmd.m_sendPixelDataArguments.m_numPixelsCopied+ + serverCmd.m_sendPixelDataArguments.m_numRemainingPixels; + + m_data->m_cachedCameraPixelsWidth = 0; + m_data->m_cachedCameraPixelsHeight = 0; + + int numPixels = serverCmd.m_sendPixelDataArguments.m_imageWidth*serverCmd.m_sendPixelDataArguments.m_imageHeight; + + m_data->m_cachedCameraPixelsRGBA.reserve(numPixels*numBytesPerPixel); + m_data->m_cachedCameraDepthBuffer.resize(numTotalPixels); + m_data->m_cachedCameraPixelsRGBA.resize(numTotalPixels*numBytesPerPixel); + + + unsigned char* rgbaPixelsReceived = + (unsigned char*)&m_data->m_bulletStreamDataServerToClient[0]; + printf("pixel = %d\n", rgbaPixelsReceived[0]); + + for (int i=0;im_cachedCameraPixelsRGBA[i + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex*numBytesPerPixel] + = rgbaPixelsReceived[i]; + } + + if (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0) + { + + + // continue requesting remaining pixels + command.m_type = CMD_REQUEST_CAMERA_IMAGE_DATA; + command.m_requestPixelDataArguments.m_startPixelIndex = + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex + + serverCmd.m_sendPixelDataArguments.m_numPixelsCopied; + } else + { + m_data->m_cachedCameraPixelsWidth = serverCmd.m_sendPixelDataArguments.m_imageWidth; + m_data->m_cachedCameraPixelsHeight = serverCmd.m_sendPixelDataArguments.m_imageHeight; + } + } + } while (serverCmd.m_sendPixelDataArguments.m_numRemainingPixels > 0); + + return m_data->m_hasStatus; + + +} + bool PhysicsDirect::submitClientCommand(const struct SharedMemoryCommand& command) { if (command.m_type==CMD_REQUEST_DEBUG_LINES) @@ -174,6 +247,11 @@ bool PhysicsDirect::submitClientCommand(const struct SharedMemoryCommand& comman return processDebugLines(command); } + if (command.m_type==CMD_REQUEST_CAMERA_IMAGE_DATA) + { + return processCamera(command); + } + bool hasStatus = m_data->m_commandProcessor->processCommand(command,m_data->m_serverStatus,&m_data->m_bulletStreamDataServerToClient[0],SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); m_data->m_hasStatus = hasStatus; if (hasStatus) @@ -333,9 +411,9 @@ void PhysicsDirect::getCachedCameraImage(b3CameraImageData* cameraData) { if (cameraData) { - cameraData->m_pixelHeight = 0; - cameraData->m_pixelWidth = 0; - cameraData->m_depthValues = 0; - cameraData->m_rgbColorData = 0; + cameraData->m_pixelWidth = m_data->m_cachedCameraPixelsWidth; + cameraData->m_pixelHeight = m_data->m_cachedCameraPixelsHeight; + cameraData->m_depthValues = m_data->m_cachedCameraDepthBuffer.size() ? &m_data->m_cachedCameraDepthBuffer[0] : 0; + cameraData->m_rgbColorData = m_data->m_cachedCameraPixelsRGBA.size() ? &m_data->m_cachedCameraPixelsRGBA[0] : 0; } } diff --git a/examples/SharedMemory/PhysicsDirect.h b/examples/SharedMemory/PhysicsDirect.h index fb1aeefa6..9dea925d3 100644 --- a/examples/SharedMemory/PhysicsDirect.h +++ b/examples/SharedMemory/PhysicsDirect.h @@ -19,6 +19,8 @@ protected: bool processDebugLines(const struct SharedMemoryCommand& orgCommand); + bool processCamera(const struct SharedMemoryCommand& orgCommand); + public: PhysicsDirect(); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 1fc4efdcc..b4317bcc6 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1192,12 +1192,18 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm mb->clearForcesAndTorques(); int torqueIndex = 0; - btVector3 f(clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[0], - clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[1], - clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[2]); - btVector3 t(clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[3], - clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[4], - clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[5]); + btVector3 f(0,0,0); + btVector3 t(0,0,0); + + if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) + { + f = btVector3 (clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[0], + clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[1], + clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[2]); + t = btVector3 (clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[3], + clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[4], + clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[5]); + } torqueIndex+=6; mb->addBaseForce(f); mb->addBaseTorque(t); @@ -1206,7 +1212,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm for (int dof=0;dofgetLink(link).m_dofCount;dof++) { - double torque = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[torqueIndex]; + double torque = 0.f; + if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) + torque = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[torqueIndex]; mb->addJointTorqueMultiDof(link,dof,torque); torqueIndex++; } @@ -1233,10 +1241,15 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (motorPtr) { btMultiBodyJointMotor* motor = *motorPtr; - btScalar desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex]; + btScalar desiredVelocity = 0.f; + if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_QDOT)!=0) + desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex]; motor->setVelocityTarget(desiredVelocity); - btScalar maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex]*m_data->m_physicsDeltaTime; + btScalar maxImp = 1000000.f*m_data->m_physicsDeltaTime; + if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) + maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex]*m_data->m_physicsDeltaTime; + motor->setMaxAppliedImpulse(maxImp); numMotors++; @@ -1247,6 +1260,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } break; } + case CONTROL_MODE_POSITION_VELOCITY_PD: { if (m_data->m_verboseOutput) @@ -1271,11 +1285,19 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { btMultiBodyJointMotor* motor = *motorPtr; - btScalar desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex]; - btScalar desiredPosition = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex]; - - btScalar kp = clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex]; - btScalar kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex]; + btScalar desiredVelocity = 0.f; + if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_QDOT)!=0) + desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex]; + btScalar desiredPosition = 0.f; + if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_Q)!=0) + desiredPosition = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex]; + + btScalar kp = 0.f; + if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_KP)!=0) + kp = clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex]; + btScalar kd = 0.f; + if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_KD)!=0) + kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex]; int dof1 = 0; btScalar currentPosition = mb->getJointPosMultiDof(link)[dof1]; @@ -1288,9 +1310,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm motor->setVelocityTarget(desiredVelocity); - btScalar maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex]*m_data->m_physicsDeltaTime; + btScalar maxImp = 1000000.f*m_data->m_physicsDeltaTime; + + if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) + maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex]*m_data->m_physicsDeltaTime; - motor->setMaxAppliedImpulse(1000);//maxImp); + motor->setMaxAppliedImpulse(maxImp); numMotors++; } diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 42436d2b0..8328b485a 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -30,6 +30,7 @@ #define MAX_DEGREE_OF_FREEDOM 64 #define MAX_NUM_SENSORS 256 #define MAX_URDF_FILENAME_LENGTH 1024 +#define MAX_SDF_FILENAME_LENGTH 1024 #define MAX_FILENAME_LENGTH MAX_URDF_FILENAME_LENGTH #define MAX_NUM_LINKS MAX_DEGREE_OF_FREEDOM @@ -54,6 +55,16 @@ TmpFloat3 CreateTmpFloat3(float x, float y, float z) return tmp; } +enum EnumSdfArgsUpdateFlags +{ + SDF_ARGS_FILE_NAME=1, +}; + +struct SdfArgs +{ + char m_sdfFileName[MAX_URDF_FILENAME_LENGTH]; +}; + enum EnumUrdfArgsUpdateFlags { URDF_ARGS_FILE_NAME=1, @@ -179,6 +190,15 @@ struct SendDesiredStateArgs }; +enum EnumSimDesiredStateUpdateFlags +{ + SIM_DESIRED_STATE_HAS_Q=1, + SIM_DESIRED_STATE_HAS_QDOT=2, + SIM_DESIRED_STATE_HAS_KD=4, + SIM_DESIRED_STATE_HAS_KP=8, + SIM_DESIRED_STATE_HAS_MAX_FORCE=16, +}; + enum EnumSimParamUpdateFlags { @@ -287,6 +307,7 @@ struct SharedMemoryCommand union { struct UrdfArgs m_urdfArguments; + struct SdfArgs m_sdfArguments; struct InitPoseArgs m_initPoseArgs; struct SendPhysicsSimulationParameters m_physSimParamArgs; struct BulletDataStreamArgs m_dataStreamArguments; diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index f7d04f724..2f676e057 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -5,7 +5,8 @@ enum EnumSharedMemoryClientCommand { - CMD_LOAD_URDF, + CMD_LOAD_SDF, + CMD_LOAD_URDF, CMD_SEND_BULLET_DATA_STREAM, CMD_CREATE_BOX_COLLISION_SHAPE, // CMD_DELETE_BOX_COLLISION_SHAPE, @@ -35,7 +36,8 @@ enum EnumSharedMemoryServerStatus CMD_CLIENT_COMMAND_COMPLETED, //the server will skip unknown command and report a status 'CMD_UNKNOWN_COMMAND_FLUSHED' CMD_UNKNOWN_COMMAND_FLUSHED, - + CMD_SDF_LOADING_COMPLETED, + CMD_SDF_LOADING_FAILED, CMD_URDF_LOADING_COMPLETED, CMD_URDF_LOADING_FAILED, CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED, From 612e46614ad1e9b849916a085e69308f5b813e83 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sat, 4 Jun 2016 13:16:06 -0700 Subject: [PATCH 005/115] fix (unused) SSE operator btMatrix3x3 ==, thanks to yyzone for the report/fix. fixes 552 --- src/LinearMath/btMatrix3x3.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/LinearMath/btMatrix3x3.h b/src/LinearMath/btMatrix3x3.h index 41dea6948..963c5db97 100644 --- a/src/LinearMath/btMatrix3x3.h +++ b/src/LinearMath/btMatrix3x3.h @@ -1329,7 +1329,9 @@ SIMD_FORCE_INLINE bool operator==(const btMatrix3x3& m1, const btMatrix3x3& m2) c0 = _mm_and_ps(c0, c1); c0 = _mm_and_ps(c0, c2); - return (0x7 == _mm_movemask_ps((__m128)c0)); + int m = _mm_movemask_ps((__m128)c0); + return (0x7 == (m & 0x7)); + #else return ( m1[0][0] == m2[0][0] && m1[1][0] == m2[1][0] && m1[2][0] == m2[2][0] && From 8076d5235c52333c655f42adbefa9e054e111bf7 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sat, 4 Jun 2016 21:51:21 -0700 Subject: [PATCH 006/115] fix window resize/width bookkeeping bug in MacOpenGLWindow.mm --- examples/OpenGLWindow/MacOpenGLWindow.mm | 28 ++++++++---------------- examples/SimpleOpenGL3/main.cpp | 6 ++--- 2 files changed, 12 insertions(+), 22 deletions(-) diff --git a/examples/OpenGLWindow/MacOpenGLWindow.mm b/examples/OpenGLWindow/MacOpenGLWindow.mm index 301608cca..d3b3ba31e 100644 --- a/examples/OpenGLWindow/MacOpenGLWindow.mm +++ b/examples/OpenGLWindow/MacOpenGLWindow.mm @@ -102,11 +102,11 @@ float loop; } -(void)drawRect:(NSRect)rect { + if (([self frame].size.width != m_lastWidth) || ([self frame].size.height != m_lastHeight)) { m_lastWidth = [self frame].size.width; m_lastHeight = [self frame].size.height; - // Only needed on resize: [m_context clearDrawable]; @@ -114,7 +114,6 @@ float loop; float width = [self frame].size.width; float height = [self frame].size.height; - // Get view dimensions in pixels // glViewport(0,0,10,10); @@ -209,16 +208,12 @@ struct MacOpenGLWindowInternalData m_myview = 0; m_pool = 0; m_window = 0; - m_width = -1; - m_height = -1; m_exitRequested = false; } NSApplication* m_myApp; TestView* m_myview; NSAutoreleasePool* m_pool; NSWindow* m_window; - int m_width; - int m_height; bool m_exitRequested; }; @@ -294,8 +289,6 @@ void MacOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) if (m_internalData) closeWindow(); - int width = ci.m_width; - int height = ci.m_height; const char* windowTitle = ci.m_title; @@ -303,9 +296,7 @@ void MacOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) NSAutoreleasePool *pool = [[NSAutoreleasePool alloc] init]; m_internalData = new MacOpenGLWindowInternalData; - m_internalData->m_width = width; - m_internalData->m_height = height; - + m_internalData->m_pool = [NSAutoreleasePool new]; m_internalData->m_myApp = [NSApplication sharedApplication]; //myApp = [MyApp sharedApplication]; @@ -373,7 +364,7 @@ void MacOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) [newItem release]; */ - NSRect frame = NSMakeRect(0., 0., width, height); + NSRect frame = NSMakeRect(0., 0., ci.m_width, ci.m_height); m_internalData->m_window = [NSWindow alloc]; [m_internalData->m_window initWithContentRect:frame @@ -423,9 +414,7 @@ void MacOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) [m_internalData->m_window makeKeyAndOrderFront: nil]; [m_internalData->m_myview MakeCurrent]; - m_internalData->m_width = m_internalData->m_myview.GetWindowWidth; - m_internalData->m_height = m_internalData->m_myview.GetWindowHeight; - + [NSApp activateIgnoringOtherApps:YES]; @@ -1035,13 +1024,13 @@ void MacOpenGLWindow::startRendering() float aspect; //b3Vector3 extents; - if (m_internalData->m_width > m_internalData->m_height) + if (getWidth() > getHeight()) { - aspect = (float)m_internalData->m_width / (float)m_internalData->m_height; + aspect = (float)getWidth() / (float)getHeight(); //extents.setValue(aspect * 1.0f, 1.0f,0); } else { - aspect = (float)m_internalData->m_height / (float)m_internalData->m_width; + aspect = (float)getHeight() / (float)getWidth(); //extents.setValue(1.0f, aspect*1.f,0); } @@ -1136,6 +1125,7 @@ int MacOpenGLWindow::getWidth() const { if (m_internalData && m_internalData->m_myview && m_internalData->m_myview.GetWindowWidth) return m_internalData->m_myview.GetWindowWidth; + return 0; } @@ -1152,7 +1142,7 @@ void MacOpenGLWindow::setResizeCallback(b3ResizeCallback resizeCallback) [m_internalData->m_myview setResizeCallback:resizeCallback]; if (resizeCallback) { - (resizeCallback)(m_internalData->m_width,m_internalData->m_height); + (resizeCallback)(getWidth(), getHeight()); } } diff --git a/examples/SimpleOpenGL3/main.cpp b/examples/SimpleOpenGL3/main.cpp index 015db129e..726abf693 100644 --- a/examples/SimpleOpenGL3/main.cpp +++ b/examples/SimpleOpenGL3/main.cpp @@ -14,8 +14,8 @@ static b3MouseButtonCallback sOldMouseButtonCB = 0; static b3KeyboardCallback sOldKeyboardCB = 0; //static b3RenderCallback sOldRenderCB = 0; -float gWidth = 0 ; -float gHeight = 0; +float gWidth = 1024; +float gHeight = 768; void MyWheelCallback(float deltax, float deltay) { @@ -61,7 +61,7 @@ int main(int argc, char* argv[]) b3CommandLineArgs myArgs(argc,argv); - SimpleOpenGL3App* app = new SimpleOpenGL3App("SimpleOpenGL3App",1024,768,true); + SimpleOpenGL3App* app = new SimpleOpenGL3App("SimpleOpenGL3App",gWidth,gHeight,true); app->m_instancingRenderer->getActiveCamera()->setCameraDistance(13); app->m_instancingRenderer->getActiveCamera()->setCameraPitch(0); From e46a718807d9d839d139d6c2c3f27662d5f7a810 Mon Sep 17 00:00:00 2001 From: Benjamin Ellenberger Date: Mon, 6 Jun 2016 23:47:33 +0200 Subject: [PATCH 007/115] Add btScalar fixes and correct M_PI to SIMD_PI. --- examples/ExtendedTutorials/InclinedPlane.cpp | 2 +- examples/ExtendedTutorials/MultiPendulum.cpp | 6 +++--- examples/ExtendedTutorials/NewtonsCradle.cpp | 6 +++--- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/examples/ExtendedTutorials/InclinedPlane.cpp b/examples/ExtendedTutorials/InclinedPlane.cpp index dfe099094..dceafdbe8 100644 --- a/examples/ExtendedTutorials/InclinedPlane.cpp +++ b/examples/ExtendedTutorials/InclinedPlane.cpp @@ -89,7 +89,7 @@ void InclinedPlaneExample::initPhysics() { // create slider to change the ramp tilt SliderParams slider("Ramp Tilt",&gTilt); slider.m_minVal=0; - slider.m_maxVal=M_PI/2.0f; + slider.m_maxVal=SIMD_PI/2.0f; slider.m_clampToNotches = false; slider.m_callback = onRampInclinationChanged; m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); diff --git a/examples/ExtendedTutorials/MultiPendulum.cpp b/examples/ExtendedTutorials/MultiPendulum.cpp index 8c4cff2e2..0d29ce12d 100644 --- a/examples/ExtendedTutorials/MultiPendulum.cpp +++ b/examples/ExtendedTutorials/MultiPendulum.cpp @@ -355,7 +355,7 @@ bool MultiPendulumExample::keyboardCallback(int key, int state) { case 49 /*ASCII for 1*/: { //assumption: Sphere are aligned in Z axis - btScalar newLimit = gCurrentPendulumLength + 0.1; + btScalar newLimit = btScalar(gCurrentPendulumLength + 0.1); changePendulaLength(newLimit); gCurrentPendulumLength = newLimit; @@ -366,7 +366,7 @@ bool MultiPendulumExample::keyboardCallback(int key, int state) { case 50 /*ASCII for 2*/: { //assumption: Sphere are aligned in Z axis - btScalar newLimit = gCurrentPendulumLength - 0.1; + btScalar newLimit = btScalar(gCurrentPendulumLength - 0.1); //is being shortened beyond it's own length, we don't let the lower sphere to go over the upper one if (0 <= newLimit) { @@ -378,7 +378,7 @@ bool MultiPendulumExample::keyboardCallback(int key, int state) { return true; } case 51 /*ASCII for 3*/: { - for (int i = gPendulaQty-1; i >= gPendulaQty-gDisplacedPendula; i--) { + for (int i = floor(gPendulaQty)-1; i >= gPendulaQty-gDisplacedPendula; i--) { if (gDisplacedPendula >= 0 && gDisplacedPendula < gPendulaQty) pendula[i]->applyCentralForce(btVector3(gDisplacementForce, 0, 0)); } diff --git a/examples/ExtendedTutorials/NewtonsCradle.cpp b/examples/ExtendedTutorials/NewtonsCradle.cpp index 76bbf6622..a1c51f1fe 100644 --- a/examples/ExtendedTutorials/NewtonsCradle.cpp +++ b/examples/ExtendedTutorials/NewtonsCradle.cpp @@ -153,7 +153,7 @@ void NewtonsCradleExample::initPhysics() { for (int i = 0; i < floor(gPendulaQty); i++) { // create pendulum - createPendulum(pendulumShape, xPosition, yPosition,zPosition, + createPendulum(pendulumShape, xPosition, yPosition, zPosition, gInitialPendulumLength, pendulumMass); // displace the pendula 1.05 sphere size, so that they all nearly touch (small spacings in between @@ -289,7 +289,7 @@ bool NewtonsCradleExample::keyboardCallback(int key, int state) { case 49 /*ASCII for 1*/: { //assumption: Sphere are aligned in Z axis - btScalar newLimit = gCurrentPendulumLength + 0.1; + btScalar newLimit = btScalar(gCurrentPendulumLength + 0.1); changePendulaLength(newLimit); gCurrentPendulumLength = newLimit; @@ -300,7 +300,7 @@ bool NewtonsCradleExample::keyboardCallback(int key, int state) { case 50 /*ASCII for 2*/: { //assumption: Sphere are aligned in Z axis - btScalar newLimit = gCurrentPendulumLength - 0.1; + btScalar newLimit = btScalar(gCurrentPendulumLength - 0.1); //is being shortened beyond it's own length, we don't let the lower sphere to go over the upper one if (0 <= newLimit) { From 1c7f87aff100b472c2ecc1cb383d9d12556ecd60 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 6 Jun 2016 18:54:05 -0700 Subject: [PATCH 008/115] implement first draft of pybullet.renderImage for synthetic camera remove a few debug printf from tinyrenderer --- .../SharedMemory/PhysicsClientExample.cpp | 14 +- .../PhysicsClientSharedMemory.cpp | 4 +- .../PhysicsServerCommandProcessor.cpp | 2 +- .../TinyRendererVisualShapeConverter.cpp | 2 +- examples/TinyRenderer/TinyRenderer.cpp | 2 +- examples/pybullet/CMakeLists.txt | 10 +- examples/pybullet/pybullet.c | 161 +++++++++++++++++- 7 files changed, 180 insertions(+), 15 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index 15c90748a..30da039b3 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -612,9 +612,9 @@ void PhysicsClientExample::stepSimulation(float deltaTime) } if (statusType ==CMD_CAMERA_IMAGE_COMPLETED) { - static int counter=0; - char msg[1024]; - sprintf(msg,"Camera image %d OK\n",counter++); + // static int counter=0; + // char msg[1024]; + // sprintf(msg,"Camera image %d OK\n",counter++); b3CameraImageData imageData; b3GetCameraImageData(m_physicsClientHandle,&imageData); if (m_canvas && m_canvasIndex >=0) @@ -642,11 +642,11 @@ void PhysicsClientExample::stepSimulation(float deltaTime) m_canvas->refreshImageData(m_canvasIndex); } - b3Printf(msg); + // b3Printf(msg); } if (statusType == CMD_CAMERA_IMAGE_FAILED) { - b3Printf("Camera image FAILED\n"); + b3Warning("Camera image FAILED\n"); } @@ -716,8 +716,8 @@ void PhysicsClientExample::stepSimulation(float deltaTime) bool hasStatus = (status != 0); if (hasStatus) { - int statusType = b3GetStatusType(status); - b3Printf("Status after reset: %d",statusType); + //int statusType = b3GetStatusType(status); + //b3Printf("Status after reset: %d",statusType); } } } else diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index c0ecc0a19..82062b0c8 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -448,7 +448,7 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { unsigned char* rgbaPixelsReceived = (unsigned char*)&m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[0]; - printf("pixel = %d\n", rgbaPixelsReceived[0]); + // printf("pixel = %d\n", rgbaPixelsReceived[0]); for (int i=0;im_swRenderInstances.size()); + // printf("num m_swRenderInstances = %d\n", m_data->m_swRenderInstances.size()); for (int i=0;im_swRenderInstances.size();i++) { TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(i); diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index e7dfb8f05..6b9fdbb35 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -265,7 +265,7 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); Shader shader(model, light_dir_local, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); - printf("Render %d triangles.\n",model->nfaces()); + //printf("Render %d triangles.\n",model->nfaces()); for (int i=0; infaces(); i++) { diff --git a/examples/pybullet/CMakeLists.txt b/examples/pybullet/CMakeLists.txt index 5fd6b106a..672187557 100644 --- a/examples/pybullet/CMakeLists.txt +++ b/examples/pybullet/CMakeLists.txt @@ -9,6 +9,15 @@ INCLUDE_DIRECTORIES( SET(pybullet_SRCS pybullet.c ../../examples/ExampleBrowser/InProcessExampleBrowser.cpp + ../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp + ../../examples/SharedMemory/TinyRendererVisualShapeConverter.h + ../../examples/OpenGLWindow/SimpleCamera.cpp + ../../examples/OpenGLWindow/SimpleCamera.h + ../../examples/TinyRenderer/geometry.cpp + ../../examples/TinyRenderer/model.cpp + ../../examples/TinyRenderer/tgaimage.cpp + ../../examples/TinyRenderer/our_gl.cpp + ../../examples/TinyRenderer/TinyRenderer.cpp ../../examples/SharedMemory/InProcessMemory.cpp ../../examples/SharedMemory/PhysicsClient.cpp ../../examples/SharedMemory/PhysicsClient.h @@ -48,7 +57,6 @@ SET(pybullet_SRCS ../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp ../../examples/Importers/ImportURDFDemo/UrdfParser.cpp ../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp - ../../examples/Importers/ImportURDFDemo/DefaultVisualShapeConverter.cpp ../../examples/MultiThreading/b3PosixThreadSupport.cpp ../../examples/MultiThreading/b3Win32ThreadSupport.cpp ../../examples/MultiThreading/b3ThreadSupportInterface.cpp diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 3286e5cf2..43ac64db9 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -134,7 +134,7 @@ pybullet_loadURDF(PyObject* self, PyObject* args) float startOrnY = 0; float startOrnZ = 0; float startOrnW = 1; - printf("size=%d\n", size); + //printf("size=%d\n", size); if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); @@ -164,7 +164,7 @@ pybullet_loadURDF(PyObject* self, PyObject* args) b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(sm, urdfFileName); - printf("urdf filename = %s\n", urdfFileName); + //printf("urdf filename = %s\n", urdfFileName); //setting the initial position, orientation and other arguments are optional b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); @@ -359,6 +359,157 @@ pybullet_getNumJoints(PyObject* self, PyObject* args) } } +static PyObject* +pybullet_setJointPositions(PyObject* self, PyObject* args) +{ + + Py_INCREF(Py_None); + return Py_None; +} + + // const unsigned char* m_rgbColorData;//3*m_pixelWidth*m_pixelHeight bytes + // const float* m_depthValues;//m_pixelWidth*m_pixelHeight floats + +static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) +{ + + ///request an image from a simulated camera, using a software renderer. + struct b3CameraImageData imageData; + PyObject* objViewMat,* objProjMat; + + b3SharedMemoryCommandHandle command = b3InitRequestCameraImage(sm); + + if (PyArg_ParseTuple(args, "OO", &objViewMat, &objProjMat)) + { + PyObject* seq; + int i, len; + PyObject* item; + float viewMatrix[16]; + float projectionMatrix[16]; + int valid = 1; + { + seq = PySequence_Fast(objViewMat, "expected a sequence"); + len = PySequence_Size(objViewMat); + //printf("objViewMat size = %d\n", len); + if (len==16) + { + + if (PyList_Check(seq)) + { + for (i = 0; i < len; i++) + { + item = PyList_GET_ITEM(seq, i); + viewMatrix[i] = PyFloat_AsDouble(item); + float v = viewMatrix[i]; + //printf("view %d to %f\n", i,v); + + } + } + else + { + for (i = 0; i < len; i++) + { + item = PyTuple_GET_ITEM(seq,i); + viewMatrix[i] = PyFloat_AsDouble(item); + } + } + } else + { + valid = 0; + } + } + + { + seq = PySequence_Fast(objProjMat, "expected a sequence"); + len = PySequence_Size(objProjMat); + //printf("projMat len = %d\n", len); + if (len==16) + { + if (PyList_Check(seq)) + { + for (i = 0; i < len; i++) + { + item = PyList_GET_ITEM(seq, i); + projectionMatrix[i] = PyFloat_AsDouble(item); + } + } + else + { + for (i = 0; i < len; i++) + { + item = PyTuple_GET_ITEM(seq,i); + projectionMatrix[i] = PyFloat_AsDouble(item); + } + } + } else + { + valid = 0; + } + } + + + Py_DECREF(seq); + if (valid) + { + //printf("set b3RequestCameraImageSetCameraMatrices\n"); + b3RequestCameraImageSetCameraMatrices(command, viewMatrix, projectionMatrix); + } + } + + if (b3CanSubmitCommand(sm)) + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + statusType = b3GetStatusType(statusHandle); + if (statusType==CMD_CAMERA_IMAGE_COMPLETED) + { + PyObject *item2; + PyObject* pyResultList;//store 4 elements in this result: width, height, rgbData, depth + + b3GetCameraImageData(sm, &imageData); + //todo: error handling if image size is 0 + pyResultList = PyTuple_New(4); + PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); + PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); + + PyObject *pylistPos; + PyObject* pylistDep; + + //printf("image width = %d, height = %d\n", imageData.m_pixelWidth, imageData.m_pixelHeight); + { + + PyObject *item; + int bytesPerPixel = 3;//Red, Green, Blue, each 8 bit values + int num=bytesPerPixel*imageData.m_pixelWidth*imageData.m_pixelHeight; + pylistPos = PyTuple_New(num); + pylistDep = PyTuple_New(imageData.m_pixelWidth*imageData.m_pixelHeight); + + for (int i=0;i Date: Tue, 7 Jun 2016 12:57:46 -0700 Subject: [PATCH 009/115] add .stl file support in 'File/Open' of example browser. --- examples/ExampleBrowser/main.cpp | 3 ++ .../ImportSTLDemo/ImportSTLSetup.cpp | 31 +++++++++++++------ examples/OpenGLWindow/MacOpenGLWindow.mm | 2 +- 3 files changed, 25 insertions(+), 11 deletions(-) diff --git a/examples/ExampleBrowser/main.cpp b/examples/ExampleBrowser/main.cpp index 179f18036..b245cdecb 100644 --- a/examples/ExampleBrowser/main.cpp +++ b/examples/ExampleBrowser/main.cpp @@ -13,6 +13,8 @@ #include "../Importers/ImportSTLDemo/ImportSTLSetup.h" #include "../Importers/ImportURDFDemo/ImportURDFSetup.h" #include "../Importers/ImportSDFDemo/ImportSDFSetup.h" +#include "../Importers/ImportSTLDemo/ImportSTLSetup.h" + int main(int argc, char* argv[]) @@ -29,6 +31,7 @@ int main(int argc, char* argv[]) exampleBrowser->registerFileImporter(".urdf",ImportURDFCreateFunc); exampleBrowser->registerFileImporter(".sdf",ImportSDFCreateFunc); exampleBrowser->registerFileImporter(".obj",ImportObjCreateFunc); + exampleBrowser->registerFileImporter(".stl",ImportSTLCreateFunc); clock.reset(); if (init) diff --git a/examples/Importers/ImportSTLDemo/ImportSTLSetup.cpp b/examples/Importers/ImportSTLDemo/ImportSTLSetup.cpp index b7f25c3dc..c05138ef1 100644 --- a/examples/Importers/ImportSTLDemo/ImportSTLSetup.cpp +++ b/examples/Importers/ImportSTLDemo/ImportSTLSetup.cpp @@ -13,9 +13,12 @@ class ImportSTLSetup : public CommonRigidBodyBase { + + const char* m_fileName; + btVector3 m_scaling; public: - ImportSTLSetup(struct GUIHelperInterface* helper); + ImportSTLSetup(struct GUIHelperInterface* helper, const char* fileName); virtual ~ImportSTLSetup(); virtual void initPhysics(); @@ -31,10 +34,19 @@ public: }; -ImportSTLSetup::ImportSTLSetup(struct GUIHelperInterface* helper) -:CommonRigidBodyBase(helper) +ImportSTLSetup::ImportSTLSetup(struct GUIHelperInterface* helper, const char* fileName) +:CommonRigidBodyBase(helper), +m_scaling(btVector3(10,10,10)) { - + if (fileName) + { + m_fileName = fileName; + m_scaling = btVector3(0.01,0.01,0.01); + } else + { + m_fileName = "l_finger_tip.stl"; + + } } ImportSTLSetup::~ImportSTLSetup() @@ -51,17 +63,16 @@ void ImportSTLSetup::initPhysics() m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); m_dynamicsWorld->getDebugDrawer()->setDebugMode(btIDebugDraw::DBG_DrawWireframe); - const char* fileName = "l_finger_tip.stl"; + char relativeFileName[1024]; - if (!b3ResourcePath::findResourcePath(fileName, relativeFileName, 1024)) + if (!b3ResourcePath::findResourcePath(m_fileName, relativeFileName, 1024)) { - b3Warning("Cannot find file %s\n", fileName); + b3Warning("Cannot find file %s\n", m_fileName); return; } btVector3 shift(0,0,0); - btVector3 scaling(10,10,10); // int index=10; { @@ -81,12 +92,12 @@ void ImportSTLSetup::initPhysics() - m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling); + m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,m_scaling); } } class CommonExampleInterface* ImportSTLCreateFunc(struct CommonExampleOptions& options) { - return new ImportSTLSetup(options.m_guiHelper); + return new ImportSTLSetup(options.m_guiHelper, options.m_fileName); } diff --git a/examples/OpenGLWindow/MacOpenGLWindow.mm b/examples/OpenGLWindow/MacOpenGLWindow.mm index d3b3ba31e..f4f853889 100644 --- a/examples/OpenGLWindow/MacOpenGLWindow.mm +++ b/examples/OpenGLWindow/MacOpenGLWindow.mm @@ -1071,7 +1071,7 @@ int MacOpenGLWindow::fileOpenDialog(char* filename, int maxNameLength) NSOpenGLContext *foo = [NSOpenGLContext currentContext]; // get the url of a .txt file NSOpenPanel * zOpenPanel = [NSOpenPanel openPanel]; - NSArray * zAryOfExtensions = [NSArray arrayWithObjects:@"urdf",@"bullet",@"obj",@"sdf",nil]; + NSArray * zAryOfExtensions = [NSArray arrayWithObjects:@"urdf",@"bullet",@"obj",@"sdf",@"stl",nil]; [zOpenPanel setAllowedFileTypes:zAryOfExtensions]; NSInteger zIntResult = [zOpenPanel runModal]; From d2e50d045b6c1d236115cf9b5c13558991901df0 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 7 Jun 2016 16:11:58 -0700 Subject: [PATCH 010/115] fix issues related to camera width/height add width,height as arguments to pybullet.renderImage(x,y,[viewMat4x4],[projMat4x4]) --- .../RenderingExamples/TinyRendererSetup.cpp | 4 +- examples/SharedMemory/PhysicsClientC_API.cpp | 10 + examples/SharedMemory/PhysicsClientC_API.h | 1 + .../SharedMemory/PhysicsClientExample.cpp | 23 +- .../PhysicsClientSharedMemory.cpp | 7 + examples/SharedMemory/PhysicsDirect.cpp | 10 +- .../PhysicsServerCommandProcessor.cpp | 9 + examples/SharedMemory/SharedMemoryCommands.h | 4 + .../TinyRendererVisualShapeConverter.cpp | 19 +- .../TinyRendererVisualShapeConverter.h | 1 + examples/TinyRenderer/TinyRenderer.cpp | 22 +- examples/TinyRenderer/TinyRenderer.h | 7 +- examples/pybullet/pybullet.c | 227 ++++++++++-------- 13 files changed, 203 insertions(+), 141 deletions(-) diff --git a/examples/RenderingExamples/TinyRendererSetup.cpp b/examples/RenderingExamples/TinyRendererSetup.cpp index 11258779d..8df1a76ad 100644 --- a/examples/RenderingExamples/TinyRendererSetup.cpp +++ b/examples/RenderingExamples/TinyRendererSetup.cpp @@ -183,7 +183,7 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui) m_guiHelper->getRenderInterface()->writeTransforms(); m_internalData->m_shapePtr.push_back(0); - TinyRenderObjectData* ob = new TinyRenderObjectData(m_internalData->m_width,m_internalData->m_height, + TinyRenderObjectData* ob = new TinyRenderObjectData( m_internalData->m_rgbColorBuffer, m_internalData->m_depthBuffer); //ob->loadModel("cube.obj"); @@ -363,7 +363,7 @@ void TinyRendererSetup::stepSimulation(float deltaTime) } } - TinyRenderer::renderObject(*m_internalData->m_renderObjects[o]); + TinyRenderer::renderObject(*m_internalData->m_renderObjects[o], m_internalData->m_width,m_internalData->m_height); } //m_app->drawText("hello",500,500); render->activateTexture(m_internalData->m_textureHandle); diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 914c9d091..c6468cb89 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -735,6 +735,16 @@ void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHa command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; } +void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle commandHandle, int width, int height ) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); + command->m_requestPixelDataArguments.m_pixelWidth = width; + command->m_requestPixelDataArguments.m_pixelHeight = height; + command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT; +} + void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData) { PhysicsClient* cl = (PhysicsClient* ) physClient; diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 37008aceb..b67f078ae 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -68,6 +68,7 @@ void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* l ///request an image from a simulated camera, using a software renderer. b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient); void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]); +void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height ); void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData); diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index 30da039b3..e7e02ba51 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -21,8 +21,8 @@ struct MyMotorInfo2 int m_qIndex; }; -int camVisualizerWidth = 640;//1024/3; -int camVisualizerHeight = 480;//768/3; +int camVisualizerWidth = 320;//1024/3; +int camVisualizerHeight = 240;//768/3; #define MAX_NUM_MOTORS 128 @@ -77,10 +77,10 @@ protected: virtual void resetCamera() { - float dist = 5; + float dist = 1.1; float pitch = 50; float yaw = 35; - float targetPos[3]={0,0,0};//-3,2.8,-2.5}; + float targetPos[3]={0,0,0.5};//-3,2.8,-2.5}; m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]); } @@ -248,7 +248,8 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix); this->m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix); b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix); - b3SubmitClientCommand(m_physicsClientHandle, commandHandle); + b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight); + b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_CREATE_BOX_COLLISION_SHAPE: @@ -619,18 +620,18 @@ void PhysicsClientExample::stepSimulation(float deltaTime) b3GetCameraImageData(m_physicsClientHandle,&imageData); if (m_canvas && m_canvasIndex >=0) { - for (int i=0;isetPixel(m_canvasIndex,xIndex,camVisualizerHeight-1-yIndex, + int pixelIndex = (xIndex+yIndex*imageData.m_pixelWidth)*bytesPerPixel; + m_canvas->setPixel(m_canvasIndex,i,camVisualizerHeight-1-j, imageData.m_rgbColorData[pixelIndex], imageData.m_rgbColorData[pixelIndex+1], diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index 82062b0c8..728358b93 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -450,6 +450,13 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { (unsigned char*)&m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[0]; // printf("pixel = %d\n", rgbaPixelsReceived[0]); + float* depthBuffer = (float*)&(m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[serverCmd.m_sendPixelDataArguments.m_numPixelsCopied*4]); + + for (int i=0;im_cachedCameraDepthBuffer[i + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex] = depthBuffer[i]; + } + for (int i=0;im_cachedCameraPixelsRGBA[i + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex*numBytesPerPixel] diff --git a/examples/SharedMemory/PhysicsDirect.cpp b/examples/SharedMemory/PhysicsDirect.cpp index 37baeaa83..478e31031 100644 --- a/examples/SharedMemory/PhysicsDirect.cpp +++ b/examples/SharedMemory/PhysicsDirect.cpp @@ -210,8 +210,15 @@ bool PhysicsDirect::processCamera(const struct SharedMemoryCommand& orgCommand) unsigned char* rgbaPixelsReceived = (unsigned char*)&m_data->m_bulletStreamDataServerToClient[0]; - printf("pixel = %d\n", rgbaPixelsReceived[0]); + + float* depthBuffer = (float*)&(m_data->m_bulletStreamDataServerToClient[serverCmd.m_sendPixelDataArguments.m_numPixelsCopied*4]); + + // printf("pixel = %d\n", rgbaPixelsReceived[0]); + for (int i=0;im_cachedCameraDepthBuffer[i + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex] = depthBuffer[i]; + } for (int i=0;im_cachedCameraPixelsRGBA[i + serverCmd.m_sendPixelDataArguments.m_startingPixelIndex*numBytesPerPixel] @@ -227,6 +234,7 @@ bool PhysicsDirect::processCamera(const struct SharedMemoryCommand& orgCommand) command.m_requestPixelDataArguments.m_startPixelIndex = serverCmd.m_sendPixelDataArguments.m_startingPixelIndex + serverCmd.m_sendPixelDataArguments.m_numPixelsCopied; + } else { m_data->m_cachedCameraPixelsWidth = serverCmd.m_sendPixelDataArguments.m_imageWidth; diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 2f662aa4a..89490caa6 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -972,6 +972,14 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm int width, height; int numPixelsCopied = 0; + if ( + (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0) && + (clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT)!=0) + { + m_data->m_visualConverter.setWidthAndHeight(clientCmd.m_requestPixelDataArguments.m_pixelWidth, + clientCmd.m_requestPixelDataArguments.m_pixelHeight); + } + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL)!=0) { m_data->m_guiHelper->copyCameraImageData(0,0,0,0,0,&width,&height,0); @@ -1005,6 +1013,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { // printf("-------------------------------\nRendering\n"); + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0) { m_data->m_visualConverter.render( diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 8328b485a..fa67d7673 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -129,12 +129,16 @@ struct RequestPixelDataArgs float m_viewMatrix[16]; float m_projectionMatrix[16]; int m_startPixelIndex; + int m_pixelWidth; + int m_pixelHeight; }; enum EnumRequestPixelDataUpdateFlags { REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES=1, REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL=2, + REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=4, + }; diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index fed633c1b..7c3507b25 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -462,7 +462,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const if (vertices.size() && indices.size()) { - TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_swWidth,m_data->m_swHeight,m_data->m_rgbColorBuffer,m_data->m_depthBuffer); + TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer); tinyObj->registerMeshShape(&vertices[0].xyzw[0],vertices.size(),&indices[0],indices.size(),rgbaColor); visuals->m_renderObjects.push_back(tinyObj); } @@ -576,7 +576,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo renderObj->m_lightDirWorld = lightDirWorld; } } - TinyRenderer::renderObject(*renderObj); + TinyRenderer::renderObject(*renderObj,m_data->m_swWidth,m_data->m_swHeight); } } //printf("write tga \n"); @@ -590,6 +590,17 @@ void TinyRendererVisualShapeConverter::getWidthAndHeight(int& width, int& height height = m_data->m_swHeight; } + +void TinyRendererVisualShapeConverter::setWidthAndHeight(int width, int height) +{ + m_data->m_swWidth = width; + m_data->m_swHeight = height; + + m_data->m_depthBuffer.resize(m_data->m_swWidth*m_data->m_swHeight); + m_data->m_rgbColorBuffer = TGAImage(width, height, TGAImage::RGB); + +} + void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied) { int w = m_data->m_rgbColorBuffer.get_width(); @@ -612,6 +623,10 @@ void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixels { for (int i=0;im_depthBuffer[i+startPixelIndex]; + } if (pixelsRGBA) { pixelsRGBA[i*numBytesPerPixel] = m_data->m_rgbColorBuffer.buffer()[(i+startPixelIndex)*3+0]; diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.h b/examples/SharedMemory/TinyRendererVisualShapeConverter.h index 3bce1add7..6baff2491 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.h +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.h @@ -24,6 +24,7 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter void resetAll(); void getWidthAndHeight(int& width, int& height); + void setWidthAndHeight(int width, int height); void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied); diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 6b9fdbb35..e13f97077 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -88,10 +88,8 @@ struct Shader : public IShader { }; -TinyRenderObjectData::TinyRenderObjectData(int width, int height,TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer) -:m_width(width), -m_height(height), -m_rgbColorBuffer(rgbColorBuffer), +TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer) +:m_rgbColorBuffer(rgbColorBuffer), m_depthBuffer(depthBuffer), m_model(0), m_userData(0), @@ -103,11 +101,6 @@ m_userIndex(-1) m_lightDirWorld.setValue(0,0,0); m_localScaling.setValue(1,1,1); m_modelMatrix = Matrix::identity(); - m_viewMatrix = lookat(eye, center, up); - //m_viewportMatrix = viewport(width/8, height/8, width*3/4, height*3/4); - //m_viewportMatrix = viewport(width/8, height/8, width*3/4, height*3/4); - m_viewportMatrix = viewport(0,0,width,height); - m_projectionMatrix = projection(-1.f/(eye-center).norm()); } @@ -238,7 +231,7 @@ TinyRenderObjectData::~TinyRenderObjectData() delete m_model; } -void TinyRenderer::renderObject(TinyRenderObjectData& renderData) +void TinyRenderer::renderObject(TinyRenderObjectData& renderData, int width, int height) { Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); Model* model = renderData.m_model; @@ -247,13 +240,8 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) - //renderData.m_viewMatrix = lookat(eye, center, up); - int width = renderData.m_width; - int height = renderData.m_height; - //renderData.m_viewportMatrix = viewport(width/8, height/8, width*3/4, height*3/4); - renderData.m_viewportMatrix = viewport(0,0,renderData.m_width,renderData.m_height); - //renderData.m_projectionMatrix = projection(-1.f/(eye-center).norm()); - + renderData.m_viewportMatrix = viewport(0,0,width, height); + b3AlignedObjectArray& zbuffer = renderData.m_depthBuffer; TGAImage& frame = renderData.m_rgbColorBuffer; diff --git a/examples/TinyRenderer/TinyRenderer.h b/examples/TinyRenderer/TinyRenderer.h index 0cb2ffca9..cfe857eca 100644 --- a/examples/TinyRenderer/TinyRenderer.h +++ b/examples/TinyRenderer/TinyRenderer.h @@ -25,12 +25,11 @@ struct TinyRenderObjectData //class IShader* m_shader; todo(erwincoumans) expose the shader, for now we use a default shader //Output - int m_width; - int m_height; + TGAImage& m_rgbColorBuffer; b3AlignedObjectArray& m_depthBuffer; - TinyRenderObjectData(int width, int height,TGAImage& rgbColorBuffer,b3AlignedObjectArray& depthBuffer); + TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray& depthBuffer); virtual ~TinyRenderObjectData(); void loadModel(const char* fileName); @@ -48,7 +47,7 @@ struct TinyRenderObjectData class TinyRenderer { public: - static void renderObject(TinyRenderObjectData& renderData); + static void renderObject(TinyRenderObjectData& renderData, int width, int height); }; #endif // TINY_RENDERER_Hbla diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 43ac64db9..0bac58313 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -362,6 +362,11 @@ pybullet_getNumJoints(PyObject* self, PyObject* args) static PyObject* pybullet_setJointPositions(PyObject* self, PyObject* args) { + if (0==sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } Py_INCREF(Py_None); return Py_None; @@ -372,17 +377,22 @@ pybullet_setJointPositions(PyObject* self, PyObject* args) static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) { - + if (0==sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + ///request an image from a simulated camera, using a software renderer. struct b3CameraImageData imageData; PyObject* objViewMat,* objProjMat; + int width, height; - b3SharedMemoryCommandHandle command = b3InitRequestCameraImage(sm); - - if (PyArg_ParseTuple(args, "OO", &objViewMat, &objProjMat)) + if (PyArg_ParseTuple(args, "iiOO", &width, &height, &objViewMat, &objProjMat)) { - PyObject* seq; - int i, len; + + PyObject* seq; + int i, len; PyObject* item; float viewMatrix[16]; float projectionMatrix[16]; @@ -391,124 +401,133 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) seq = PySequence_Fast(objViewMat, "expected a sequence"); len = PySequence_Size(objViewMat); //printf("objViewMat size = %d\n", len); - if (len==16) - { - - if (PyList_Check(seq)) - { - for (i = 0; i < len; i++) + if (len==16) { + + if (PyList_Check(seq)) + { + for (i = 0; i < len; i++) + { item = PyList_GET_ITEM(seq, i); - viewMatrix[i] = PyFloat_AsDouble(item); - float v = viewMatrix[i]; + viewMatrix[i] = PyFloat_AsDouble(item); + float v = viewMatrix[i]; //printf("view %d to %f\n", i,v); + } + } + else + { + for (i = 0; i < len; i++) + { + item = PyTuple_GET_ITEM(seq,i); + viewMatrix[i] = PyFloat_AsDouble(item); + } + } + } else + { + valid = 0; } } - else - { - for (i = 0; i < len; i++) - { - item = PyTuple_GET_ITEM(seq,i); - viewMatrix[i] = PyFloat_AsDouble(item); - } - } - } else - { - valid = 0; - } - } + { - seq = PySequence_Fast(objProjMat, "expected a sequence"); - len = PySequence_Size(objProjMat); - //printf("projMat len = %d\n", len); - if (len==16) - { - if (PyList_Check(seq)) - { - for (i = 0; i < len; i++) - { - item = PyList_GET_ITEM(seq, i); - projectionMatrix[i] = PyFloat_AsDouble(item); - } - } - else - { - for (i = 0; i < len; i++) - { - item = PyTuple_GET_ITEM(seq,i); - projectionMatrix[i] = PyFloat_AsDouble(item); - } - } - } else - { - valid = 0; - } - } - + seq = PySequence_Fast(objProjMat, "expected a sequence"); + len = PySequence_Size(objProjMat); + //printf("projMat len = %d\n", len); + if (len==16) + { + if (PyList_Check(seq)) + { + for (i = 0; i < len; i++) + { + item = PyList_GET_ITEM(seq, i); + projectionMatrix[i] = PyFloat_AsDouble(item); + } + } + else + { + for (i = 0; i < len; i++) + { + item = PyTuple_GET_ITEM(seq,i); + projectionMatrix[i] = PyFloat_AsDouble(item); + } + } + } else + { + valid = 0; + } + } Py_DECREF(seq); if (valid) { + b3SharedMemoryCommandHandle command; + + command = b3InitRequestCameraImage(sm); + //printf("set b3RequestCameraImageSetCameraMatrices\n"); b3RequestCameraImageSetCameraMatrices(command, viewMatrix, projectionMatrix); - } - } - - if (b3CanSubmitCommand(sm)) - { - b3SharedMemoryStatusHandle statusHandle; - int statusType; - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - statusType = b3GetStatusType(statusHandle); - if (statusType==CMD_CAMERA_IMAGE_COMPLETED) - { - PyObject *item2; - PyObject* pyResultList;//store 4 elements in this result: width, height, rgbData, depth - - b3GetCameraImageData(sm, &imageData); - //todo: error handling if image size is 0 - pyResultList = PyTuple_New(4); - PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); - PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); - - PyObject *pylistPos; - PyObject* pylistDep; - - //printf("image width = %d, height = %d\n", imageData.m_pixelWidth, imageData.m_pixelHeight); - { - - PyObject *item; - int bytesPerPixel = 3;//Red, Green, Blue, each 8 bit values - int num=bytesPerPixel*imageData.m_pixelWidth*imageData.m_pixelHeight; - pylistPos = PyTuple_New(num); - pylistDep = PyTuple_New(imageData.m_pixelWidth*imageData.m_pixelHeight); - - for (int i=0;i Date: Tue, 7 Jun 2016 17:02:47 -0700 Subject: [PATCH 011/115] don't pass width/height into renderObject --- examples/RenderingExamples/TinyRendererSetup.cpp | 2 +- examples/SharedMemory/TinyRendererVisualShapeConverter.cpp | 2 +- .../StandaloneMain/main_sw_tinyrenderer_single_example.cpp | 2 +- examples/StandaloneMain/main_tinyrenderer_single_example.cpp | 2 +- examples/TinyRenderer/TinyRenderer.cpp | 5 ++++- examples/TinyRenderer/TinyRenderer.h | 2 +- examples/TinyRenderer/main.cpp | 2 +- 7 files changed, 10 insertions(+), 7 deletions(-) diff --git a/examples/RenderingExamples/TinyRendererSetup.cpp b/examples/RenderingExamples/TinyRendererSetup.cpp index 8df1a76ad..fd3f80e41 100644 --- a/examples/RenderingExamples/TinyRendererSetup.cpp +++ b/examples/RenderingExamples/TinyRendererSetup.cpp @@ -363,7 +363,7 @@ void TinyRendererSetup::stepSimulation(float deltaTime) } } - TinyRenderer::renderObject(*m_internalData->m_renderObjects[o], m_internalData->m_width,m_internalData->m_height); + TinyRenderer::renderObject(*m_internalData->m_renderObjects[o]); } //m_app->drawText("hello",500,500); render->activateTexture(m_internalData->m_textureHandle); diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 7c3507b25..3bb5e893e 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -576,7 +576,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo renderObj->m_lightDirWorld = lightDirWorld; } } - TinyRenderer::renderObject(*renderObj,m_data->m_swWidth,m_data->m_swHeight); + TinyRenderer::renderObject(*renderObj); } } //printf("write tga \n"); diff --git a/examples/StandaloneMain/main_sw_tinyrenderer_single_example.cpp b/examples/StandaloneMain/main_sw_tinyrenderer_single_example.cpp index 786e0eed1..1fa1b0ccd 100644 --- a/examples/StandaloneMain/main_sw_tinyrenderer_single_example.cpp +++ b/examples/StandaloneMain/main_sw_tinyrenderer_single_example.cpp @@ -110,7 +110,7 @@ public: int shapeIndex = OpenGLGuiHelper::registerGraphicsShape(vertices,numvertices,indices,numIndices); if (shapeIndex>=0) { - TinyRenderObjectData* swObj = new TinyRenderObjectData(m_swWidth,m_swHeight,m_rgbColorBuffer,m_depthBuffer); + TinyRenderObjectData* swObj = new TinyRenderObjectData(m_rgbColorBuffer,m_depthBuffer); float rgbaColor[4] = {1,1,1,1}; swObj->registerMeshShape(vertices,numvertices,indices,numIndices,rgbaColor); //swObj->createCube(1,1,1);//MeshShape(vertices,numvertices,indices,numIndices); diff --git a/examples/StandaloneMain/main_tinyrenderer_single_example.cpp b/examples/StandaloneMain/main_tinyrenderer_single_example.cpp index 157ab233c..565b771e7 100644 --- a/examples/StandaloneMain/main_tinyrenderer_single_example.cpp +++ b/examples/StandaloneMain/main_tinyrenderer_single_example.cpp @@ -253,7 +253,7 @@ struct TinyRendererGUIHelper : public GUIHelperInterface { int shapeIndex = m_swRenderObjects.size(); - TinyRenderObjectData* swObj = new TinyRenderObjectData(m_swWidth,m_swHeight,m_rgbColorBuffer,m_depthBuffer); + TinyRenderObjectData* swObj = new TinyRenderObjectData(m_rgbColorBuffer,m_depthBuffer); float rgbaColor[4] = {1,1,1,1}; swObj->registerMeshShape(vertices,numvertices,indices,numIndices,rgbaColor); //swObj->createCube(1,1,1);//MeshShape(vertices,numvertices,indices,numIndices); diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index e13f97077..aebf0440e 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -231,8 +231,11 @@ TinyRenderObjectData::~TinyRenderObjectData() delete m_model; } -void TinyRenderer::renderObject(TinyRenderObjectData& renderData, int width, int height) +void TinyRenderer::renderObject(TinyRenderObjectData& renderData) { + int width = renderData.m_rgbColorBuffer.get_width(); + int height = renderData.m_rgbColorBuffer.get_height(); + Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); Model* model = renderData.m_model; if (0==model) diff --git a/examples/TinyRenderer/TinyRenderer.h b/examples/TinyRenderer/TinyRenderer.h index cfe857eca..c6f4f9821 100644 --- a/examples/TinyRenderer/TinyRenderer.h +++ b/examples/TinyRenderer/TinyRenderer.h @@ -47,7 +47,7 @@ struct TinyRenderObjectData class TinyRenderer { public: - static void renderObject(TinyRenderObjectData& renderData, int width, int height); + static void renderObject(TinyRenderObjectData& renderData); }; #endif // TINY_RENDERER_Hbla diff --git a/examples/TinyRenderer/main.cpp b/examples/TinyRenderer/main.cpp index 9995b8f66..32f5e7edd 100644 --- a/examples/TinyRenderer/main.cpp +++ b/examples/TinyRenderer/main.cpp @@ -86,7 +86,7 @@ int main(int argc, char* argv[]) b3AlignedObjectArray depthBuffer; depthBuffer.resize(gWidth*gHeight); - TinyRenderObjectData renderData(textureWidth, textureHeight,rgbColorBuffer,depthBuffer);//, "african_head/african_head.obj");//floor.obj"); + TinyRenderObjectData renderData(rgbColorBuffer,depthBuffer);//, "african_head/african_head.obj");//floor.obj"); //renderData.loadModel("african_head/african_head.obj"); renderData.loadModel("floor.obj"); From 98d2f91f3cca1a0f9e77a3cde62a4a04aea2d942 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 9 Jun 2016 12:12:46 -0700 Subject: [PATCH 012/115] fix flipped tinyrenderer image --- examples/SharedMemory/PhysicsClientExample.cpp | 2 +- .../TinyRendererVisualShapeConverter.cpp | 4 +++- examples/pybullet/pybullet.c | 16 +++++++++------- 3 files changed, 13 insertions(+), 9 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index e7e02ba51..e7d797fa6 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -631,7 +631,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime) int bytesPerPixel = 4; int pixelIndex = (xIndex+yIndex*imageData.m_pixelWidth)*bytesPerPixel; - m_canvas->setPixel(m_canvasIndex,i,camVisualizerHeight-1-j, + m_canvas->setPixel(m_canvasIndex,i,j, imageData.m_rgbColorData[pixelIndex], imageData.m_rgbColorData[pixelIndex+1], diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 3bb5e893e..ebe11877a 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -580,7 +580,9 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo } } //printf("write tga \n"); - m_data->m_rgbColorBuffer.write_tga_file("camera.tga"); + //m_data->m_rgbColorBuffer.write_tga_file("camera.tga"); +// printf("flipped!\n"); + m_data->m_rgbColorBuffer.flip_vertically(); } diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 0bac58313..41625b8cf 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -459,15 +459,16 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) } Py_DECREF(seq); - if (valid) { b3SharedMemoryCommandHandle command; command = b3InitRequestCameraImage(sm); - + if (valid) + { //printf("set b3RequestCameraImageSetCameraMatrices\n"); b3RequestCameraImageSetCameraMatrices(command, viewMatrix, projectionMatrix); - + } + b3RequestCameraImageSetPixelResolution(command,width,height); if (b3CanSubmitCommand(sm)) @@ -489,24 +490,25 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) PyObject *pylistPos; PyObject* pylistDep; + int i,j,p; //printf("image width = %d, height = %d\n", imageData.m_pixelWidth, imageData.m_pixelHeight); { PyObject *item; - int bytesPerPixel = 3;//Red, Green, Blue, each 8 bit values + int bytesPerPixel = 4;//Red, Green, Blue, each 8 bit values int num=bytesPerPixel*imageData.m_pixelWidth*imageData.m_pixelHeight; pylistPos = PyTuple_New(num); pylistDep = PyTuple_New(imageData.m_pixelWidth*imageData.m_pixelHeight); - for (int i=0;i Date: Fri, 10 Jun 2016 15:07:41 -0700 Subject: [PATCH 013/115] render image with ability to set pixel resolution and initial camera position --- examples/pybullet/pybullet.c | 301 ++++++++++++++++------------------- 1 file changed, 138 insertions(+), 163 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 41625b8cf..8e916234b 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -19,7 +19,7 @@ enum eCONNECT_METHOD static PyObject *SpamError; static b3PhysicsClientHandle sm=0; - +// Step through one timestep of the simulation static PyObject * pybullet_stepSimulation(PyObject *self, PyObject *args) { @@ -118,7 +118,11 @@ pybullet_disconnectPhysicsServer(PyObject *self, PyObject *args) return Py_None; } - +// Load a URDF file indicating the links and joints of an object +// function can be called without arguments and will default +// to position (0,0,1) with orientation(0,0,0,1) +// else, loadURDF(x,y,z) or +// loadURDF(pos_x, pos_y, pos_z, orn_x, orn_y, orn_z, orn_w) static PyObject * pybullet_loadURDF(PyObject* self, PyObject* args) { @@ -128,13 +132,13 @@ pybullet_loadURDF(PyObject* self, PyObject* args) int bodyIndex = -1; const char* urdfFileName=""; float startPosX =0; - float startPosY =0; - float startPosZ = 1; + float startPosY =0; + float startPosZ = 1; float startOrnX = 0; float startOrnY = 0; float startOrnZ = 0; float startOrnW = 1; - //printf("size=%d\n", size); + if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); @@ -157,14 +161,13 @@ pybullet_loadURDF(PyObject* self, PyObject* args) &startPosX,&startPosY,&startPosZ, &startOrnX,&startOrnY,&startOrnZ, &startOrnW)) return NULL; - } { b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(sm, urdfFileName); - //printf("urdf filename = %s\n", urdfFileName); + //setting the initial position, orientation and other arguments are optional b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); @@ -178,6 +181,8 @@ pybullet_loadURDF(PyObject* self, PyObject* args) } return PyLong_FromLong(bodyIndex); } + +// Reset the simulation to remove all loaded objects static PyObject * pybullet_resetSimulation(PyObject* self, PyObject* args) { @@ -195,6 +200,7 @@ pybullet_resetSimulation(PyObject* self, PyObject* args) return Py_None; } +// Set the gravity of the world with (x, y, z) arguments static PyObject * pybullet_setGravity(PyObject* self, PyObject* args) { @@ -229,6 +235,8 @@ pybullet_setGravity(PyObject* self, PyObject* args) } +// Internal function used to get the base position and orientation +// Orientation is returned in quaternions static void pybullet_internalGetBasePositionAndOrientation(int bodyIndex, double basePosition[3],double baseOrientation[3]) { basePosition[0] = 0.; @@ -272,6 +280,10 @@ static void pybullet_internalGetBasePositionAndOrientation(int bodyIndex, double } } +// Get the positions (x,y,z) and orientation (x,y,z,w) in quaternion +// values for the base link of your object +// Object is retrieved based on body index, which is the order +// the object was loaded into the simulation (0-based) static PyObject * pybullet_getBasePositionAndOrientation(PyObject* self, PyObject* args) { @@ -331,7 +343,9 @@ pybullet_getBasePositionAndOrientation(PyObject* self, PyObject* args) } - +// Return the number of joints in an object based on +// body index; body index is based on order of sequence +// the object is loaded into simulation static PyObject * pybullet_getNumJoints(PyObject* self, PyObject* args) { @@ -359,6 +373,7 @@ pybullet_getNumJoints(PyObject* self, PyObject* args) } } +// TODO(hellojas): set joint positions for a body static PyObject* pybullet_setJointPositions(PyObject* self, PyObject* args) { @@ -372,179 +387,139 @@ pybullet_setJointPositions(PyObject* self, PyObject* args) return Py_None; } - // const unsigned char* m_rgbColorData;//3*m_pixelWidth*m_pixelHeight bytes - // const float* m_depthValues;//m_pixelWidth*m_pixelHeight floats +// const unsigned char* m_rgbColorData;//3*m_pixelWidth*m_pixelHeight bytes +// const float* m_depthValues;//m_pixelWidth*m_pixelHeight floats + +// Render an image from the current timestep of the simulation +// +// Examples: +// renderImage() - default image resolution and camera position +// renderImage(w, h) - image resolution of (w,h), default camera +// renderImage(w, h, view[16], projection[16]) - set both resolution +// and initialize camera to the view and projection values +// +// Note if the (w,h) is too small, the objects may not appear based on +// where the camera has been set +// +// TODO(hellojas): fix image is cut off at head +// TODO(hellojas): should we add check to give minimum image resolution +// to see object based on camera position? static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) { - if (0==sm) + + if (0==sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + ///request an image from a simulated camera, using a software renderer. + struct b3CameraImageData imageData; + PyObject* objViewMat,* objProjMat; + int width, height; + int size= PySequence_Size(args); + float viewMatrix[16]; + float projectionMatrix[16]; + + // inialize cmd + b3SharedMemoryCommandHandle command; + command = b3InitRequestCameraImage(sm); + + if (size==2) // only set camera resolution + { + if (PyArg_ParseTuple(args, "ii", &width, &height)) + { + b3RequestCameraImageSetPixelResolution(command,width,height); + } + } + + if (size==4) // set camera resoluation and view and projection matrix + { + if (PyArg_ParseTuple(args, "iiOO", &width, &height, &objViewMat, &objProjMat)) + { + b3RequestCameraImageSetPixelResolution(command,width,height); + + // set camera matrices only if set matrix function succeeds + if (pybullet_internalSetMatrix(objViewMat, viewMatrix) && + (pybullet_internalSetMatrix(objProjMat, projectionMatrix))) + { + b3RequestCameraImageSetCameraMatrices(command, viewMatrix, projectionMatrix); + } + } + } + + if (b3CanSubmitCommand(sm)) { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - - ///request an image from a simulated camera, using a software renderer. - struct b3CameraImageData imageData; - PyObject* objViewMat,* objProjMat; - int width, height; - - if (PyArg_ParseTuple(args, "iiOO", &width, &height, &objViewMat, &objProjMat)) - { - - PyObject* seq; - int i, len; - PyObject* item; - float viewMatrix[16]; - float projectionMatrix[16]; - int valid = 1; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + statusType = b3GetStatusType(statusHandle); + if (statusType==CMD_CAMERA_IMAGE_COMPLETED) { - seq = PySequence_Fast(objViewMat, "expected a sequence"); - len = PySequence_Size(objViewMat); - //printf("objViewMat size = %d\n", len); - if (len==16) - { - - if (PyList_Check(seq)) - { - for (i = 0; i < len; i++) - { - item = PyList_GET_ITEM(seq, i); - viewMatrix[i] = PyFloat_AsDouble(item); - float v = viewMatrix[i]; - //printf("view %d to %f\n", i,v); - - } - } - else - { - for (i = 0; i < len; i++) - { - item = PyTuple_GET_ITEM(seq,i); - viewMatrix[i] = PyFloat_AsDouble(item); - } - } - } else - { - valid = 0; - } - } - - - { - seq = PySequence_Fast(objProjMat, "expected a sequence"); - len = PySequence_Size(objProjMat); - //printf("projMat len = %d\n", len); - if (len==16) - { - if (PyList_Check(seq)) - { - for (i = 0; i < len; i++) - { - item = PyList_GET_ITEM(seq, i); - projectionMatrix[i] = PyFloat_AsDouble(item); - } - } - else - { - for (i = 0; i < len; i++) - { - item = PyTuple_GET_ITEM(seq,i); - projectionMatrix[i] = PyFloat_AsDouble(item); - } - } - } else - { - valid = 0; - } - } + PyObject *item2; + PyObject* pyResultList;//store 4 elements in this result: width, height, rgbData, depth - Py_DECREF(seq); - { - b3SharedMemoryCommandHandle command; - - command = b3InitRequestCameraImage(sm); - if (valid) - { - //printf("set b3RequestCameraImageSetCameraMatrices\n"); - b3RequestCameraImageSetCameraMatrices(command, viewMatrix, projectionMatrix); - } + b3GetCameraImageData(sm, &imageData); + //TODO(hellojas): error handling if image size is 0 + pyResultList = PyTuple_New(4); + PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); + PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); + + PyObject *pylistRGB; + PyObject* pylistDep; + int i, j, p; - b3RequestCameraImageSetPixelResolution(command,width,height); - - if (b3CanSubmitCommand(sm)) { - b3SharedMemoryStatusHandle statusHandle; - int statusType; - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); - statusType = b3GetStatusType(statusHandle); - if (statusType==CMD_CAMERA_IMAGE_COMPLETED) + + PyObject *item; + int bytesPerPixel = 4;//Red, Green, Blue, and Alpha each 8 bit values + int num=bytesPerPixel*imageData.m_pixelWidth*imageData.m_pixelHeight; + pylistRGB = PyTuple_New(num); + pylistDep = PyTuple_New(imageData.m_pixelWidth*imageData.m_pixelHeight); + + for (i=0;i Date: Fri, 10 Jun 2016 15:07:52 -0700 Subject: [PATCH 014/115] render image with ability to set pixel resolution and initial camera position --- examples/SharedMemory/PhysicsClientExample.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index e7d797fa6..bcd84d321 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -628,7 +628,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime) int yIndex = int(float(j)*(float(imageData.m_pixelHeight)/float(camVisualizerHeight))); btClamp(yIndex,0,imageData.m_pixelHeight); btClamp(xIndex,0,imageData.m_pixelWidth); - int bytesPerPixel = 4; + int bytesPerPixel = 4; //RGBA int pixelIndex = (xIndex+yIndex*imageData.m_pixelWidth)*bytesPerPixel; m_canvas->setPixel(m_canvasIndex,i,j, @@ -636,8 +636,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime) imageData.m_rgbColorData[pixelIndex], imageData.m_rgbColorData[pixelIndex+1], imageData.m_rgbColorData[pixelIndex+2], - 255); -// imageData.m_rgbColorData[pixelIndex+3]); + 255); //alpha set to 255 } } m_canvas->refreshImageData(m_canvasIndex); From 9c5a7925f0e3f2b63ccc0a0a0b40b710b7a759a1 Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Fri, 10 Jun 2016 15:14:00 -0700 Subject: [PATCH 015/115] add internal set matrix function --- examples/pybullet/pybullet.c | 39 ++++++++++++++++++++++++++++++++++++ 1 file changed, 39 insertions(+) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 8e916234b..f056b5b57 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -390,6 +390,45 @@ pybullet_setJointPositions(PyObject* self, PyObject* args) // const unsigned char* m_rgbColorData;//3*m_pixelWidth*m_pixelHeight bytes // const float* m_depthValues;//m_pixelWidth*m_pixelHeight floats +// internal function to set a float matrix[16] +// used to initialize camera position with +// a view and projection matrix in renderImage() +static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16]) +{ + + int i, len; + PyObject* item; + PyObject* seq; + + seq = PySequence_Fast(objMat, "expected a sequence"); + len = PySequence_Size(objMat); + if (len==16) + { + + if (PyList_Check(seq)) + { + for (i = 0; i < len; i++) + { + item = PyList_GET_ITEM(seq, i); + matrix[i] = PyFloat_AsDouble(item); + } + } + else + { + for (i = 0; i < len; i++) + { + item = PyTuple_GET_ITEM(seq,i); + matrix[i] = PyFloat_AsDouble(item); + } + } + Py_DECREF(seq); + return 1; + } else + { + Py_DECREF(seq); + return 0; + } +} // Render an image from the current timestep of the simulation // From 6523df336e6925c0b7597fd77bcc5b3e08047e95 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Mon, 13 Jun 2016 10:11:28 -0700 Subject: [PATCH 016/115] Fix pybullet Windows build errors: C99 requires variables to be defined at the start of the function. Improve CMake Windows support to build PyBullet (BUILD_PYBULLET) Implement b3LoadSdfCommandInit in shared memory API Implement pybullet SDF loading binding, in loadSDF API TODO for SDF support is provide way to query object/link/joint information. --- CMakeLists.txt | 5 +- examples/SharedMemory/PhysicsClientC_API.cpp | 31 ++++ examples/SharedMemory/PhysicsClientC_API.h | 2 + .../SharedMemory/PhysicsClientExample.cpp | 70 +++++--- .../PhysicsClientSharedMemory.cpp | 38 ++++- .../PhysicsServerCommandProcessor.cpp | 156 +++++++++++++++++- .../PhysicsServerCommandProcessor.h | 4 + examples/SharedMemory/SharedMemoryCommands.h | 25 +++ examples/SharedMemory/SharedMemoryPublic.h | 1 + examples/pybullet/pybullet.c | 93 +++++++++-- 10 files changed, 377 insertions(+), 48 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b34c7f996..083835f6e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -191,14 +191,15 @@ IF (APPLE) ENDIF() OPTION(BUILD_BULLET3 "Set when you want to build Bullet 3" ON) + +FIND_PACKAGE(PythonLibs) OPTION(BUILD_PYBULLET "Set when you want to build pybullet (experimental Python bindings for Bullet)" OFF) + IF(BUILD_PYBULLET) IF(WIN32) - FIND_PACKAGE(PythonLibs 3.4 REQUIRED) SET(BUILD_SHARED_LIBS OFF CACHE BOOL "Shared Libs" FORCE) ELSE(WIN32) - FIND_PACKAGE(PythonLibs 2.7 REQUIRED) SET(BUILD_SHARED_LIBS ON CACHE BOOL "Shared Libs" FORCE) ENDIF(WIN32) ENDIF(BUILD_PYBULLET) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index c6468cb89..ae1a54782 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -519,6 +519,33 @@ int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle) return CMD_INVALID_STATUS; } +int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyIndicesOut, int bodyIndicesCapacity) +{ + int numBodies = 0; + const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; + b3Assert(status); + + if (status) + { + switch (status->m_type) + { + case CMD_SDF_LOADING_COMPLETED: + { + int i,maxBodies; + numBodies = status->m_sdfLoadedArgs.m_numBodies; + maxBodies = btMin(bodyIndicesCapacity, numBodies); + for (i=0;im_sdfLoadedArgs.m_bodyUniqueIds[i]; + } + break; + } + } + } + + return numBodies; +} + int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; @@ -558,6 +585,10 @@ int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, const double* jointReactionForces[]) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; const SendActualStateArgs &args = status->m_sendActualStateArgs; + btAssert(status->m_type == CMD_URDF_LOADING_COMPLETED); + if (status->m_type != CMD_URDF_LOADING_COMPLETED) + return false; + if (bodyUniqueId) { *bodyUniqueId = args.m_bodyUniqueId; } diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index b67f078ae..468347ef5 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -40,6 +40,8 @@ b3SharedMemoryStatusHandle b3ProcessServerStatus(b3PhysicsClientHandle physClien /// Get the physics server return status type. See EnumSharedMemoryServerStatus in SharedMemoryPublic.h for error codes. int b3GetStatusType(b3SharedMemoryStatusHandle statusHandle); +int b3GetStatusBodyIndices(b3SharedMemoryStatusHandle statusHandle, int* bodyIndicesOut, int bodyIndicesCapacity); + int b3GetStatusBodyIndex(b3SharedMemoryStatusHandle statusHandle); int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index bcd84d321..acce1dfde 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -77,9 +77,9 @@ protected: virtual void resetCamera() { - float dist = 1.1; - float pitch = 50; - float yaw = 35; + float dist = 4; + float pitch = 193; + float yaw = 25; float targetPos[3]={0,0,0.5};//-3,2.8,-2.5}; m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]); @@ -223,9 +223,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) { case CMD_LOAD_URDF: { - b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.urdf"); - //setting the initial position, orientation and other arguments are optional double startPosX = 0; static double startPosY = 0; @@ -234,7 +232,13 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) startPosY += 2.f; // ret = b3LoadUrdfCommandSetUseFixedBase(commandHandle, 1); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); - + break; + } + + case CMD_LOAD_SDF: + { + b3SharedMemoryCommandHandle commandHandle = b3LoadSdfCommandInit(m_physicsClientHandle, "two_cubes.sdf"); + b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } case CMD_REQUEST_CAMERA_IMAGE_DATA: @@ -452,6 +456,7 @@ void PhysicsClientExample::createButtons() m_guiHelper->getParameterInterface()->removeAllParameters(); createButton("Load URDF",CMD_LOAD_URDF, isTrigger); + createButton("Load SDF",CMD_LOAD_SDF, isTrigger); createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger); createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger); createButton("Send Bullet Stream",CMD_SEND_BULLET_DATA_STREAM, isTrigger); @@ -649,11 +654,40 @@ void PhysicsClientExample::stepSimulation(float deltaTime) b3Warning("Camera image FAILED\n"); } - - if (statusType == CMD_URDF_LOADING_COMPLETED) + if (statusType == CMD_SDF_LOADING_COMPLETED) { - int bodyIndex = b3GetStatusBodyIndex(status); - if (bodyIndex>=0) + //int bodyIndex = b3GetStatusBodyIndex(status); + /*if (bodyIndex>=0) + { + int numJoints = b3GetNumJoints(m_physicsClientHandle,bodyIndex); + + for (int i=0;igetParameterInterface()->registerComboBox(comboParams); + } + */ + } + + + if (statusType == CMD_URDF_LOADING_COMPLETED) + { + int bodyIndex = b3GetStatusBodyIndex(status); + if (bodyIndex>=0) { int numJoints = b3GetNumJoints(m_physicsClientHandle,bodyIndex); @@ -662,7 +696,6 @@ void PhysicsClientExample::stepSimulation(float deltaTime) b3JointInfo info; b3GetJointInfo(m_physicsClientHandle,bodyIndex,i,&info); b3Printf("Joint %s at q-index %d and u-index %d\n",info.m_jointName,info.m_qIndex,info.m_uIndex); - } ComboBoxParams comboParams; comboParams.m_comboboxId = bodyIndex; @@ -676,12 +709,8 @@ void PhysicsClientExample::stepSimulation(float deltaTime) comboParams.m_items=blarray;//{&bla}; m_guiHelper->getParameterInterface()->registerComboBox(comboParams); - - } - } - } } if (b3CanSubmitCommand(m_physicsClientHandle)) @@ -734,13 +763,12 @@ void PhysicsClientExample::stepSimulation(float deltaTime) if (m_numMotors) { enqueueCommand(CMD_SEND_DESIRED_STATE); - enqueueCommand(CMD_STEP_FORWARD_SIMULATION); - if (m_options != eCLIENTEXAMPLE_SERVER) - { - enqueueCommand(CMD_REQUEST_DEBUG_LINES); - } - //enqueueCommand(CMD_REQUEST_ACTUAL_STATE); } + enqueueCommand(CMD_STEP_FORWARD_SIMULATION); + if (m_options != eCLIENTEXAMPLE_SERVER) + { + enqueueCommand(CMD_REQUEST_DEBUG_LINES); + } } } diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index 728358b93..a4c57574d 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -40,7 +40,7 @@ struct PhysicsClientSharedMemoryInternalData { SharedMemoryStatus m_lastServerStatus; int m_counter; - bool m_serverLoadUrdfOK; + bool m_isConnected; bool m_waitingForServer; bool m_hasLastServerStatus; @@ -54,7 +54,6 @@ struct PhysicsClientSharedMemoryInternalData { m_counter(0), m_cachedCameraPixelsWidth(0), m_cachedCameraPixelsHeight(0), - m_serverLoadUrdfOK(false), m_isConnected(false), m_waitingForServer(false), m_hasLastServerStatus(false), @@ -204,8 +203,15 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { } break; } + case CMD_SDF_LOADING_COMPLETED: { + + if (m_data->m_verboseOutput) { + b3Printf("Server loading the SDF OK\n"); + } + break; + } case CMD_URDF_LOADING_COMPLETED: { - m_data->m_serverLoadUrdfOK = true; + if (m_data->m_verboseOutput) { b3Printf("Server loading the URDF OK\n"); } @@ -265,7 +271,15 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { if (m_data->m_verboseOutput) { b3Printf("Server failed loading the URDF...\n"); } - m_data->m_serverLoadUrdfOK = false; + + break; + } + + case CMD_SDF_LOADING_FAILED: { + if (m_data->m_verboseOutput) { + b3Printf("Server failed loading the SDF...\n"); + } + break; } @@ -490,6 +504,22 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { m_data->m_waitingForServer = true; } + /*if (serverCmd.m_type == CMD_SDF_LOADING_COMPLETED) + { + int numBodies = serverCmd.m_sdfLoadedArgs.m_numBodies; + if (numBodies>0) + { + SharedMemoryCommand& command = m_data->m_testBlock1->m_clientCommands[0]; + //now transfer the information of the individual objects etc. + command.m_type = CMD_REQUEST_SDF_INFO; + command.m_updateFlags = SDF_REQUEST_INFO_BODY; + command.m_sdfRequestInfoArgs.m_infoIndex = 0; + submitClientCommand(command); + return 0; + } + } + */ + if (serverCmd.m_type == CMD_CAMERA_IMAGE_COMPLETED) { SharedMemoryCommand& command = m_data->m_testBlock1->m_clientCommands[0]; diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 89490caa6..98994ea68 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -393,6 +393,7 @@ struct PhysicsServerCommandProcessorInternalData btMultiBodyDynamicsWorld* m_dynamicsWorld; SharedMemoryDebugDrawer* m_remoteDebugDrawer; + btAlignedObjectArray m_sdfRecentLoadedBodies; @@ -681,6 +682,128 @@ void PhysicsServerCommandProcessor::createJointMotors(btMultiBody* mb) } +bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes) +{ + btAssert(m_data->m_dynamicsWorld); + if (!m_data->m_dynamicsWorld) + { + b3Error("loadSdf: No valid m_dynamicsWorld"); + return false; + } + + m_data->m_sdfRecentLoadedBodies.clear(); + + BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter); + + bool useFixedBase = false; + bool loadOk = u2b.loadSDF(fileName, useFixedBase); + if (loadOk) + { + for (int i=0;im_collisionShapes.push_back(shape); + if (shape->isCompound()) + { + btCompoundShape* compound = (btCompoundShape*) shape; + for (int childIndex=0;childIndexgetNumChildShapes();childIndex++) + { + m_data->m_collisionShapes.push_back(compound->getChildShape(childIndex)); + } + } + + } + + btTransform rootTrans; + rootTrans.setIdentity(); + if (m_data->m_verboseOutput) + { + b3Printf("loaded %s OK!", fileName); + } + + for (int m =0; mallocHandle(); + + InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId); + + { + btScalar mass = 0; + bodyHandle->m_rootLocalInertialFrame.setIdentity(); + btVector3 localInertiaDiagonal(0,0,0); + int urdfLinkIndex = u2b.getRootLinkIndex(); + u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,bodyHandle->m_rootLocalInertialFrame); + } + + + + //todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user + int rootLinkIndex = u2b.getRootLinkIndex(); + b3Printf("urdf root link index = %d\n",rootLinkIndex); + MyMultiBodyCreator creation(m_data->m_guiHelper); + + u2b.getRootTransformInWorld(rootTrans); + bool useMultiBody = true; + ConvertURDF2Bullet(u2b,creation, rootTrans,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix(),true); + + + + mb = creation.getBulletMultiBody(); + if (mb) + { + bodyHandle->m_multiBody = mb; + + m_data->m_sdfRecentLoadedBodies.push_back(bodyUniqueId); + + createJointMotors(mb); + + //serialize the btMultiBody and send the data to the client. This is one way to get the link/joint names across the (shared memory) wire + + UrdfLinkNameMapUtil* util2 = new UrdfLinkNameMapUtil; + m_data->m_urdfLinkNameMapper.push_back(util2); + util2->m_mb = mb; + util2->m_memSerializer = 0; + //disable serialization of the collision objects (they are too big, and the client likely doesn't need them); + + bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks()); + for (int i=0;igetNumLinks();i++) + { + //disable serialization of the collision objects + + int urdfLinkIndex = creation.m_mb2urdfLink[i]; + btScalar mass; + btVector3 localInertiaDiagonal(0,0,0); + btTransform localInertialFrame; + u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,localInertialFrame); + bodyHandle->m_linkLocalInertialFrames.push_back(localInertialFrame); + + std::string* linkName = new std::string(u2b.getLinkName(urdfLinkIndex).c_str()); + m_data->m_strings.push_back(linkName); + + mb->getLink(i).m_linkName = linkName->c_str(); + + std::string* jointName = new std::string(u2b.getJointName(urdfLinkIndex).c_str()); + m_data->m_strings.push_back(jointName); + + mb->getLink(i).m_jointName = jointName->c_str(); + } + std::string* baseName = new std::string(u2b.getLinkName(u2b.getRootLinkIndex())); + m_data->m_strings.push_back(baseName); + mb->setBaseName(baseName->c_str()); + } else + { + b3Warning("No multibody loaded from URDF. Could add btRigidBody+btTypedConstraint solution later."); + } + + } + } + return loadOk; +} bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn, bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes) @@ -731,8 +854,6 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto ConvertURDF2Bullet(u2b,creation, tr,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix()); - - ///todo(erwincoumans) refactor this memory allocation issue for (int i=0;im_multiBody = mb; + createJointMotors(mb); @@ -805,12 +928,13 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto const char* structType = mb->serialize(chunk->m_oldPtr, util->m_memSerializer); util->m_memSerializer->finalizeChunk(chunk,structType,BT_MULTIBODY_CODE,mb); - return true; + return true; } else { b3Warning("No multibody loaded from URDF. Could add btRigidBody+btTypedConstraint solution later."); return false; } + } else { btAssert(0); @@ -1047,6 +1171,28 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm break; } + case CMD_LOAD_SDF: + { + const SdfArgs& sdfArgs = clientCmd.m_sdfArguments; + if (m_data->m_verboseOutput) + { + b3Printf("Processed CMD_LOAD_SDF:%s", sdfArgs.m_sdfFileName); + } + + bool completedOk = loadSdf(sdfArgs.m_sdfFileName,bufferServerToClient, bufferSizeInBytes); + + //serverStatusOut.m_type = CMD_SDF_LOADING_FAILED; + serverStatusOut.m_sdfLoadedArgs.m_numBodies = m_data->m_sdfRecentLoadedBodies.size(); + int maxBodies = btMin(MAX_SDF_BODIES, serverStatusOut.m_sdfLoadedArgs.m_numBodies); + for (int i=0;im_sdfRecentLoadedBodies[i]; + } + + serverStatusOut.m_type = CMD_SDF_LOADING_COMPLETED; + hasStatus = true; + break; + } case CMD_LOAD_URDF: { diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.h b/examples/SharedMemory/PhysicsServerCommandProcessor.h index dca5f8930..242a41176 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.h +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.h @@ -19,6 +19,10 @@ class PhysicsServerCommandProcessor protected: + + + bool loadSdf(const char* fileName, char* bufferServerToClient, int bufferSizeInBytes); + bool loadUrdf(const char* fileName, const class btVector3& pos, const class btQuaternion& orn, bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes); diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index fa67d7673..a4c93180e 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -33,6 +33,7 @@ #define MAX_SDF_FILENAME_LENGTH 1024 #define MAX_FILENAME_LENGTH MAX_URDF_FILENAME_LENGTH #define MAX_NUM_LINKS MAX_DEGREE_OF_FREEDOM +#define MAX_SDF_BODIES 1024 struct TmpFloat3 { @@ -298,6 +299,28 @@ struct CreateBoxShapeArgs double m_colorRGBA[4]; }; +struct SdfLoadedArgs +{ + int m_numBodies; + int m_bodyUniqueIds[MAX_SDF_BODIES]; + + ///@todo(erwincoumans) load cameras, lights etc + //int m_numCameras; + //int m_numLights; +}; + + +struct SdfRequestInfoArgs +{ + int m_infoIndex; +}; + +enum EnumSdfRequestInfoFlags +{ + SDF_REQUEST_INFO_BODY=1, + //SDF_REQUEST_INFO_CAMERA=2, +}; + struct SharedMemoryCommand { int m_type; @@ -312,6 +335,7 @@ struct SharedMemoryCommand { struct UrdfArgs m_urdfArguments; struct SdfArgs m_sdfArguments; + struct SdfRequestInfoArgs m_sdfRequestInfoArgs; struct InitPoseArgs m_initPoseArgs; struct SendPhysicsSimulationParameters m_physSimParamArgs; struct BulletDataStreamArgs m_dataStreamArguments; @@ -340,6 +364,7 @@ struct SharedMemoryStatus union { struct BulletDataStreamArgs m_dataStreamArguments; + struct SdfLoadedArgs m_sdfLoadedArgs; struct SendActualStateArgs m_sendActualStateArgs; struct SendDebugLinesArgs m_sendDebugLinesArgs; struct SendPixelDataArgs m_sendPixelDataArguments; diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 2f676e057..a038ecf51 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -19,6 +19,7 @@ enum EnumSharedMemoryClientCommand CMD_SEND_DESIRED_STATE,//todo: reconsider naming, for example SET_JOINT_CONTROL_VARIABLE? CMD_REQUEST_ACTUAL_STATE, CMD_REQUEST_DEBUG_LINES, + CMD_REQUEST_SDF_INFO, CMD_STEP_FORWARD_SIMULATION, CMD_RESET_SIMULATION, CMD_PICK_BODY, diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index f056b5b57..b735caeb1 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -182,6 +182,61 @@ pybullet_loadURDF(PyObject* self, PyObject* args) return PyLong_FromLong(bodyIndex); } +#define MAX_SDF_BODIES 512 + +static PyObject* +pybullet_loadSDF(PyObject* self, PyObject* args) +{ + const char* sdfFileName=""; + int size= PySequence_Size(args); + int numBodies = 0; + int i; + int bodyIndicesOut[MAX_SDF_BODIES]; + PyObject* pylist=0; + b3SharedMemoryStatusHandle statusHandle; + int statusType; + b3SharedMemoryCommandHandle command; + + if (0==sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + if (size==1) + { + if (!PyArg_ParseTuple(args, "s", &sdfFileName)) + return NULL; + } + + command = b3LoadSdfCommandInit(sm, sdfFileName); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + statusType = b3GetStatusType(statusHandle); + if (statusType!=CMD_SDF_LOADING_COMPLETED) + { + PyErr_SetString(SpamError, "Cannot load SDF file."); + return NULL; + } + + numBodies = b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES); + if (numBodies > MAX_SDF_BODIES) + { + PyErr_SetString(SpamError, "SDF exceeds body capacity"); + return NULL; + } + + pylist = PyTuple_New(numBodies); + + if (numBodies >0 && numBodies <= MAX_SDF_BODIES) + { + for (i=0;i Date: Mon, 13 Jun 2016 18:33:18 -0700 Subject: [PATCH 017/115] remove unused findex from btTypedConstraint.h --- src/BulletDynamics/ConstraintSolver/btTypedConstraint.h | 5 ----- 1 file changed, 5 deletions(-) diff --git a/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h b/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h index b55db0c1b..8a2a2d1ae 100644 --- a/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h +++ b/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h @@ -145,11 +145,6 @@ public: // lo and hi limits for variables (set to -/+ infinity on entry). btScalar *m_lowerLimit,*m_upperLimit; - // findex vector for variables. see the LCP solver interface for a - // description of what this does. this is set to -1 on entry. - // note that the returned indexes are relative to the first index of - // the constraint. - int *findex; // number of solver iterations int m_numIterations; From 566ed87c93cc222cc451cedac68ca799ed24e154 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 13 Jun 2016 18:58:52 -0700 Subject: [PATCH 018/115] fix a regression in a test --- examples/SharedMemory/PhysicsClientC_API.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index ae1a54782..81a58a992 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -585,8 +585,8 @@ int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, const double* jointReactionForces[]) { const SharedMemoryStatus* status = (const SharedMemoryStatus* ) statusHandle; const SendActualStateArgs &args = status->m_sendActualStateArgs; - btAssert(status->m_type == CMD_URDF_LOADING_COMPLETED); - if (status->m_type != CMD_URDF_LOADING_COMPLETED) + btAssert(status->m_type == CMD_ACTUAL_STATE_UPDATE_COMPLETED); + if (status->m_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) return false; if (bodyUniqueId) { From 4f4eb3a9c6cfe5328a5410b0cce52036f5b11385 Mon Sep 17 00:00:00 2001 From: Giorgos Tzampanakis Date: Tue, 14 Jun 2016 13:40:38 +0000 Subject: [PATCH 019/115] Fixed: Error because of unparameterized btVectorX --- src/BulletInverseDynamics/details/IDLinearMathInterface.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp b/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp index c77ba3cba..d81647b68 100644 --- a/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp +++ b/src/BulletInverseDynamics/details/IDLinearMathInterface.hpp @@ -48,9 +48,9 @@ inline mat33 operator*(const idScalar& s, const mat33& a) { return a * s; } class vecx : public btVectorX { public: - vecx(int size) : btVectorX(size) {} + vecx(int size) : btVectorX(size) {} const vecx& operator=(const btVectorX& rhs) { - *static_cast(this) = rhs; + *static_cast*>(this) = rhs; return *this; } From b06e1cb873546d940003834121e2f928190adddb Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Tue, 14 Jun 2016 07:53:15 -0700 Subject: [PATCH 020/115] Update CollisionShape2TriangleMesh.cpp fix memory leak, thanks Ilya Kostrikov for the report. --- examples/ExampleBrowser/CollisionShape2TriangleMesh.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/examples/ExampleBrowser/CollisionShape2TriangleMesh.cpp b/examples/ExampleBrowser/CollisionShape2TriangleMesh.cpp index 1105955dc..2bc8a0ea4 100644 --- a/examples/ExampleBrowser/CollisionShape2TriangleMesh.cpp +++ b/examples/ExampleBrowser/CollisionShape2TriangleMesh.cpp @@ -167,6 +167,7 @@ void CollisionShape2TriangleMesh(btCollisionShape* collisionShape, const btTrans } } } + delete hull; } } else { From eeaff0747b47c46b1eb86e239475475e684762d8 Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Tue, 14 Jun 2016 14:08:24 -0700 Subject: [PATCH 021/115] return joint state given a joint index and body index --- examples/pybullet/pybullet.c | 182 ++++++++++++++++++++++++++++++++++- 1 file changed, 179 insertions(+), 3 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index f056b5b57..e4ffeeedf 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -235,6 +235,7 @@ pybullet_setGravity(PyObject* self, PyObject* args) } + // Internal function used to get the base position and orientation // Orientation is returned in quaternions static void pybullet_internalGetBasePositionAndOrientation(int bodyIndex, double basePosition[3],double baseOrientation[3]) @@ -260,12 +261,18 @@ static void pybullet_internalGetBasePositionAndOrientation(int bodyIndex, double const int status_type = b3GetStatusType(status_handle); const double* actualStateQ; + // const double* jointReactionForces[]; + int i; b3GetStatusActualState(status_handle, 0/* body_unique_id */, 0/* num_degree_of_freedom_q */, 0/* num_degree_of_freedom_u */, 0 /*root_local_inertial_frame*/, &actualStateQ , 0 /* actual_state_q_dot */, 0 /* joint_reaction_forces */); + // printf("joint reaction forces="); + // for (i=0; i < (sizeof(jointReactionForces)/sizeof(double)); i++) { + // printf("%f ", jointReactionForces[i]); + // } //now, position x,y,z = actualStateQ[0],actualStateQ[1],actualStateQ[2] //and orientation x,y,z,w = actualStateQ[3],actualStateQ[4],actualStateQ[5],actualStateQ[6] basePosition[0] = actualStateQ[0]; @@ -300,6 +307,7 @@ pybullet_getBasePositionAndOrientation(PyObject* self, PyObject* args) return NULL; } + double basePosition[3]; double baseOrientation[4]; @@ -375,14 +383,173 @@ pybullet_getNumJoints(PyObject* self, PyObject* args) // TODO(hellojas): set joint positions for a body static PyObject* -pybullet_setJointPositions(PyObject* self, PyObject* args) +pybullet_initializeJointPositions(PyObject* self, PyObject* args) { if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - + + + Py_INCREF(Py_None); + return Py_None; +} + + +// TODO(hellojas): get joint positions for a body +static PyObject* +pybullet_getJointInfo(PyObject* self, PyObject* args) +{ + if (0==sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + Py_INCREF(Py_None); + return Py_None; +} + + +// Returns the state of a specific joint in a given bodyIndex +// The state of a joint includes the following: +// position, velocity, force torque (6 values), and motor torque +// The returned pylist is an array of [float, float, float[6], float] + +// TODO(hellojas): check accuracy of position and velocity +// TODO(hellojas): check force torque values + +static PyObject* +pybullet_getJointState(PyObject* self, PyObject* args) +{ + if (0==sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + + PyObject *pyListJointForceTorque; + PyObject *pyListJointState; + PyObject *item; + + struct b3JointInfo info; + struct b3JointSensorState sensorState; + + int bodyIndex = -1; + int jointIndex = -1; + int sensorStateSize = 4; // size of struct b3JointSensorState + int forceTorqueSize = 6; // size of force torque list from b3JointSensorState + int i, j; + + + int size= PySequence_Size(args); + + if (size==2) // get body index and joint index + { + if (PyArg_ParseTuple(args, "ii", &bodyIndex, &jointIndex)) + { + + b3SharedMemoryCommandHandle cmd_handle = + b3RequestActualStateCommandInit(sm, bodyIndex); + b3SharedMemoryStatusHandle status_handle = + b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); + + pyListJointState = PyTuple_New(sensorStateSize); + pyListJointForceTorque = PyTuple_New(forceTorqueSize); + + + // double m_jointPosition; + // double m_jointVelocity; + // double m_jointForceTorque[6]; /* note to roboticists: this is NOT the motor torque/force, but the spatial reaction force vector at joint */ + // double m_jointMotorTorque; + b3GetJointState(sm, status_handle, jointIndex, &sensorState); + // printf("Joint%d: position=%f velocity=%f motortorque=%f\n", + // jointIndex, + // sensorState.m_jointPosition, + // sensorState.m_jointVelocity, + // sensorState.m_jointMotorTorque); + + PyTuple_SetItem(pyListJointState, 0, + PyFloat_FromDouble(sensorState.m_jointPosition)); + PyTuple_SetItem(pyListJointState, 1, + PyFloat_FromDouble(sensorState.m_jointVelocity)); + + // joint force torque is list of 6 + /* note to roboticists: this is NOT the motor torque/force, but the spatial reaction force vector at joint */ + // printf(" jointForceTorque = "); + for (j = 0; j < forceTorqueSize; j++) { + // printf("%f ", sensorState.m_jointForceTorque[j]); + PyTuple_SetItem(pyListJointForceTorque, j, + PyFloat_FromDouble(sensorState.m_jointForceTorque[j])); + } + + PyTuple_SetItem(pyListJointState, 2, + pyListJointForceTorque); + + PyTuple_SetItem(pyListJointState, 3, + PyFloat_FromDouble(sensorState.m_jointMotorTorque)); + + return pyListJointState; + } + } + + Py_INCREF(Py_None); + return Py_None; +} + + +// TODO(hellojas): get joint positions for a body +static PyObject* +pybullet_getJointPositionAndVelocity(PyObject* self, PyObject* args) +{ + if (0==sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + struct b3JointInfo info; + int bodyIndex = 0; + int forceTorqueSize = 6; + PyObject *pylistJointPos; + PyObject *item; + int i, j, numJoints; + struct b3JointSensorState sensorState; + + b3SharedMemoryCommandHandle cmd_handle = + b3RequestActualStateCommandInit(sm, bodyIndex); + b3SharedMemoryStatusHandle status_handle = + b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); + + numJoints = b3GetNumJoints(sm,bodyIndex); + + const char *pyListJointNames[numJoints]; + pylistJointPos = PyTuple_New(numJoints); + + +// double m_jointPosition; +// double m_jointVelocity; +// double m_jointForceTorque[6]; /* note to roboticists: this is NOT the motor torque/force, but the spatial reaction force vector at joint */ +// double m_jointMotorTorque; + for (i = 0; i < numJoints; ++i) { + b3GetJointState(sm, status_handle, i, &sensorState); + printf("Joint%d: position=%f velocity=%f motortorque=%f\n", + i, + sensorState.m_jointPosition, + sensorState.m_jointVelocity, + sensorState.m_jointMotorTorque); + + // item = PyFloat_FromDouble(basePosition[i]); + + printf(" jointForceTorque = "); + for (j = 0; j < forceTorqueSize; j++) { + printf("%f ", sensorState.m_jointPosition); + } + printf("\n"); +} + Py_INCREF(Py_None); return Py_None; } @@ -565,9 +732,18 @@ static PyMethodDef SpamMethods[] = { {"setGravity", pybullet_setGravity, METH_VARARGS, "Set the gravity acceleration (x,y,z)."}, - {"initializeJointPositions", pybullet_setJointPositions, METH_VARARGS, + {"initializeJointPositions", pybullet_initializeJointPositions, METH_VARARGS, "Initialize the joint positions for all joints. This method skips any physics simulation and teleports all joints to the new positions."}, + // {"getJointPositions", pybullet_getJointPositions, METH_VARARGS, + // "Get the joint positions for all joints."}, + // + {"getJointInfo", pybullet_getJointInfo, METH_VARARGS, + "Get the joint metadata info for a joint on a body. This includes joint index, name, type, q-index and u-index."}, + + {"getJointState", pybullet_getJointState, METH_VARARGS, + "Get the joint metadata info for a joint on a body."}, + {"renderImage", pybullet_renderImage, METH_VARARGS, "Render an image (given the pixel resolution width & height and camera view & projection matrices), and return the 8-8-8bit RGB pixel data and floating point depth values"}, From d53d6366deebfbd223e0075009e9d4d7dce4a911 Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Tue, 14 Jun 2016 14:35:45 -0700 Subject: [PATCH 022/115] get the state of a specific joint given a body index --- examples/pybullet/pybullet.c | 59 +++++++++++++++++++++++++++++++++++- 1 file changed, 58 insertions(+), 1 deletion(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 8cd657d81..afcdcb76d 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -306,7 +306,6 @@ static void pybullet_internalGetBasePositionAndOrientation(int bodyIndex, double { - { b3SharedMemoryCommandHandle cmd_handle = b3RequestActualStateCommandInit(sm, bodyIndex); @@ -463,6 +462,64 @@ pybullet_getJointInfo(PyObject* self, PyObject* args) return NULL; } + PyObject *pyListJointInfo; + + struct b3JointInfo info; + + int bodyIndex = -1; + int jointIndex = -1; + int jointInfoSize = 8; //size of struct b3JointInfo + + int size= PySequence_Size(args); + + if (size==2) // get body index and joint index + { + if (PyArg_ParseTuple(args, "ii", &bodyIndex, &jointIndex)) + { + + // printf("body index = %d, joint index =%d\n", bodyIndex, jointIndex); + + b3SharedMemoryCommandHandle cmd_handle = + b3RequestActualStateCommandInit(sm, bodyIndex); + b3SharedMemoryStatusHandle status_handle = + b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); + + pyListJointInfo = PyTuple_New(jointInfoSize); + + b3GetJointInfo(sm, bodyIndex, jointIndex, &info); + + // printf("Joint%d %s, type %d, at q-index %d and u-index %d\n", + // info.m_jointIndex, + // info.m_jointName, + // info.m_jointType, + // info.m_qIndex, + // info.m_uIndex); + // printf(" flags=%d jointDamping=%f jointFriction=%f\n", + // info.m_flags, + // info.m_jointDamping, + // info.m_jointFriction); + + PyTuple_SetItem(pyListJointInfo, 0, + PyInt_FromLong(info.m_jointIndex)); + PyTuple_SetItem(pyListJointInfo, 1, + PyString_FromString(info.m_jointName)); + PyTuple_SetItem(pyListJointInfo, 2, + PyInt_FromLong(info.m_jointType)); + PyTuple_SetItem(pyListJointInfo, 3, + PyInt_FromLong(info.m_qIndex)); + PyTuple_SetItem(pyListJointInfo, 4, + PyInt_FromLong(info.m_uIndex)); + PyTuple_SetItem(pyListJointInfo, 5, + PyInt_FromLong(info.m_flags)); + PyTuple_SetItem(pyListJointInfo, 6, + PyFloat_FromDouble(info.m_jointDamping)); + PyTuple_SetItem(pyListJointInfo, 7, + PyFloat_FromDouble(info.m_jointFriction)); + + return pyListJointInfo; + } + } + Py_INCREF(Py_None); return Py_None; } From d6ab1ab43416df3207d5d9f48231cd9548b5ae9f Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Tue, 14 Jun 2016 14:58:36 -0700 Subject: [PATCH 023/115] initialize a single joint position for a given body index --- examples/pybullet/pybullet.c | 119 +++++++++++++++++------------------ 1 file changed, 57 insertions(+), 62 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index afcdcb76d..b645045b3 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -436,7 +436,7 @@ pybullet_getNumJoints(PyObject* self, PyObject* args) } } -// TODO(hellojas): set joint positions for a body +// Initalize all joint positions given a list of values static PyObject* pybullet_initializeJointPositions(PyObject* self, PyObject* args) { @@ -445,13 +445,65 @@ pybullet_initializeJointPositions(PyObject* self, PyObject* args) PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - + // TODO(hellojas): initialize all joint positions given a pylist of values Py_INCREF(Py_None); return Py_None; } +// Initalize a single joint position for a specific body index +// +// This method skips any physics simulation and +// teleports all joints to the new positions. +// TODO(hellojas): test accuracy of joint position values +static PyObject* +pybullet_initializeJointPosition(PyObject* self, PyObject* args) +{ + if (0==sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + int i; + int bodyIndex = -1; + int jointIndex = -1; + double jointPos = 0.0; + + int size= PySequence_Size(args); + + if (size==3) // get body index, joint index, and joint position value + { + if (PyArg_ParseTuple(args, "iid", &bodyIndex, &jointIndex, &jointPos)) + { + b3SharedMemoryCommandHandle cmd_handle = b3CreatePoseCommandInit(sm, bodyIndex); + + printf("initializing joint %d at %f\n", jointIndex, jointPos); + b3CreatePoseCommandSetJointPosition(sm, cmd_handle, jointIndex, jointPos); + + b3SharedMemoryStatusHandle status_handle = + b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); + + const int status_type = b3GetStatusType(status_handle); + + } + } + + Py_INCREF(Py_None); + return Py_None; +} + + +// Get the a single joint info for a specific bodyIndex +// +// Joint information includes: +// index, name, type, q-index, u-index, +// flags, joint damping, joint friction +// +// The format of the returned list is +// [int, str, int, int, int, int, float, float] +// // TODO(hellojas): get joint positions for a body static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args) @@ -613,60 +665,6 @@ pybullet_getJointState(PyObject* self, PyObject* args) } -// TODO(hellojas): get joint positions for a body -static PyObject* -pybullet_getJointPositionAndVelocity(PyObject* self, PyObject* args) -{ - if (0==sm) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } - - struct b3JointInfo info; - int bodyIndex = 0; - int forceTorqueSize = 6; - PyObject *pylistJointPos; - PyObject *item; - int i, j, numJoints; - struct b3JointSensorState sensorState; - - b3SharedMemoryCommandHandle cmd_handle = - b3RequestActualStateCommandInit(sm, bodyIndex); - b3SharedMemoryStatusHandle status_handle = - b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); - - numJoints = b3GetNumJoints(sm,bodyIndex); - - const char *pyListJointNames[numJoints]; - pylistJointPos = PyTuple_New(numJoints); - - -// double m_jointPosition; -// double m_jointVelocity; -// double m_jointForceTorque[6]; /* note to roboticists: this is NOT the motor torque/force, but the spatial reaction force vector at joint */ -// double m_jointMotorTorque; - for (i = 0; i < numJoints; ++i) { - b3GetJointState(sm, status_handle, i, &sensorState); - printf("Joint%d: position=%f velocity=%f motortorque=%f\n", - i, - sensorState.m_jointPosition, - sensorState.m_jointVelocity, - sensorState.m_jointMotorTorque); - - // item = PyFloat_FromDouble(basePosition[i]); - - printf(" jointForceTorque = "); - for (j = 0; j < forceTorqueSize; j++) { - printf("%f ", sensorState.m_jointPosition); - } - printf("\n"); -} - - Py_INCREF(Py_None); - return Py_None; -} - // const unsigned char* m_rgbColorData;//3*m_pixelWidth*m_pixelHeight bytes // const float* m_depthValues;//m_pixelWidth*m_pixelHeight floats @@ -852,9 +850,9 @@ static PyMethodDef SpamMethods[] = { {"initializeJointPositions", pybullet_initializeJointPositions, METH_VARARGS, "Initialize the joint positions for all joints. This method skips any physics simulation and teleports all joints to the new positions."}, - // {"getJointPositions", pybullet_getJointPositions, METH_VARARGS, - // "Get the joint positions for all joints."}, - // + {"initializeJointPosition", pybullet_initializeJointPosition, METH_VARARGS, + "Initialize the joint position for one joint. This method skips any physics simulation and teleports the joint to the new position."}, + {"getJointInfo", pybullet_getJointInfo, METH_VARARGS, "Get the joint metadata info for a joint on a body. This includes joint index, name, type, q-index and u-index."}, @@ -866,9 +864,6 @@ static PyMethodDef SpamMethods[] = { {"getBasePositionAndOrientation", pybullet_getBasePositionAndOrientation, METH_VARARGS, "Get the world position and orientation of the base of the object. (x,y,z) position vector and (x,y,z,w) quaternion orientation."}, - - {"getNumsetGravity", pybullet_setGravity, METH_VARARGS, - "Set the gravity acceleration (x,y,z)."}, {"getNumJoints", pybullet_getNumJoints, METH_VARARGS, "Get the number of joints for an object."}, From 934725554f61ee567e76207d13c6d8e7e6c9447a Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Tue, 14 Jun 2016 15:21:50 -0700 Subject: [PATCH 024/115] remove initializeJointPosition as setting one joint is not supported --- examples/pybullet/pybullet.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index b645045b3..b8bf684c2 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -479,7 +479,7 @@ pybullet_initializeJointPosition(PyObject* self, PyObject* args) { b3SharedMemoryCommandHandle cmd_handle = b3CreatePoseCommandInit(sm, bodyIndex); - printf("initializing joint %d at %f\n", jointIndex, jointPos); + // printf("initializing joint %d at %f\n", jointIndex, jointPos); b3CreatePoseCommandSetJointPosition(sm, cmd_handle, jointIndex, jointPos); b3SharedMemoryStatusHandle status_handle = @@ -850,9 +850,9 @@ static PyMethodDef SpamMethods[] = { {"initializeJointPositions", pybullet_initializeJointPositions, METH_VARARGS, "Initialize the joint positions for all joints. This method skips any physics simulation and teleports all joints to the new positions."}, - {"initializeJointPosition", pybullet_initializeJointPosition, METH_VARARGS, - "Initialize the joint position for one joint. This method skips any physics simulation and teleports the joint to the new position."}, - + // {"initializeJointPosition", pybullet_initializeJointPosition, METH_VARARGS, + // "Initialize the joint position for one joint. This method skips any physics simulation and teleports the joint to the new position."}, + // {"getJointInfo", pybullet_getJointInfo, METH_VARARGS, "Get the joint metadata info for a joint on a body. This includes joint index, name, type, q-index and u-index."}, From fd88d73e3c0d064ee0815640deb2297954bcf4f4 Mon Sep 17 00:00:00 2001 From: David Date: Wed, 15 Jun 2016 01:36:10 +0100 Subject: [PATCH 025/115] Typos in readme --- README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 711ebcf98..942500cb9 100644 --- a/README.md +++ b/README.md @@ -34,7 +34,7 @@ The entire collision detection and rigid body dynamics is executed on the GPU. A high-end desktop GPU, such as an AMD Radeon 7970 or NVIDIA GTX 680 or better. We succesfully tested the software under Windows, Linux and Mac OSX. The software currently doesn't work on OpenCL CPU devices. It might run -on a laptop GPU but performance is likely not very good. Note that +on a laptop GPU but performance will not likely be very good. Note that often an OpenCL drivers fails to compile a kernel. Some unit tests exist to track down the issue, but more work is required to cover all OpenCL kernels. @@ -88,7 +88,7 @@ You can just run it though a terminal/command prompt, or by clicking it. [--fixed_timestep= 0.0] Use either a real-time delta time (0.0) or a fixed step size (0.016666) ``` -You can use mouse picking to grab objects. When holding the ALT of CONTROL key, you have Maya style camera mouse controls. -Press F1 to create series of screenshot. Hit ESCAPE to exit the demo app. +You can use mouse picking to grab objects. When holding the ALT or CONTROL key, you have Maya style camera mouse controls. +Press F1 to create a series of screenshots. Hit ESCAPE to exit the demo app. See docs folder for further information. From 456c844a6b9d243f211971471c0a2970ef207935 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 14 Jun 2016 18:41:19 -0700 Subject: [PATCH 026/115] work-in-progress send object/joint information after loading SDF file --- .../SharedMemory/PhysicsClientExample.cpp | 28 ++++- examples/SharedMemory/PhysicsDirect.cpp | 102 +++++++++++------- examples/SharedMemory/PhysicsDirect.h | 2 + .../PhysicsServerCommandProcessor.cpp | 56 ++++++++-- .../PhysicsServerCommandProcessor.h | 2 + examples/SharedMemory/SharedMemoryCommands.h | 2 +- examples/SharedMemory/SharedMemoryPublic.h | 4 +- test/SharedMemory/test.c | 19 +++- 8 files changed, 169 insertions(+), 46 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index acce1dfde..691dbb9c6 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -237,7 +237,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) case CMD_LOAD_SDF: { - b3SharedMemoryCommandHandle commandHandle = b3LoadSdfCommandInit(m_physicsClientHandle, "two_cubes.sdf"); + b3SharedMemoryCommandHandle commandHandle = b3LoadSdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.sdf"); b3SubmitClientCommand(m_physicsClientHandle, commandHandle); break; } @@ -656,6 +656,32 @@ void PhysicsClientExample::stepSimulation(float deltaTime) if (statusType == CMD_SDF_LOADING_COMPLETED) { + int bodyIndicesOut[1024]; + int bodyCapacity = 1024; + int numBodies = b3GetStatusBodyIndices(status, bodyIndicesOut, bodyCapacity); + if (numBodies > bodyCapacity) + { + b3Warning("loadSDF number of bodies (%d) exceeds the internal body capacity (%d)",numBodies, bodyCapacity); + } else + { + /* + for (int i=0;i=0) { diff --git a/examples/SharedMemory/PhysicsDirect.cpp b/examples/SharedMemory/PhysicsDirect.cpp index 478e31031..36212cc8c 100644 --- a/examples/SharedMemory/PhysicsDirect.cpp +++ b/examples/SharedMemory/PhysicsDirect.cpp @@ -248,6 +248,47 @@ bool PhysicsDirect::processCamera(const struct SharedMemoryCommand& orgCommand) } + +void PhysicsDirect::processBodyJointInfo(int bodyUniqueId, const SharedMemoryStatus& serverCmd) +{ + bParse::btBulletFile bf( + &m_data->m_bulletStreamDataServerToClient[0], + serverCmd.m_dataStreamArguments.m_streamChunkLength); + bf.setFileDNAisMemoryDNA(); + bf.parse(false); + + + BodyJointInfoCache2* bodyJoints = new BodyJointInfoCache2; + m_data->m_bodyJointMap.insert(bodyUniqueId,bodyJoints); + + for (int i = 0; i < bf.m_multiBodies.size(); i++) + { + int flag = bf.getFlags(); + if ((flag & bParse::FD_DOUBLE_PRECISION) != 0) + { + Bullet::btMultiBodyDoubleData* mb = + (Bullet::btMultiBodyDoubleData*)bf.m_multiBodies[i]; + + addJointInfoFromMultiBodyData(mb,bodyJoints, m_data->m_verboseOutput); + } else + { + Bullet::btMultiBodyFloatData* mb = + (Bullet::btMultiBodyFloatData*)bf.m_multiBodies[i]; + + addJointInfoFromMultiBodyData(mb,bodyJoints, m_data->m_verboseOutput); + } + } + if (bf.ok()) { + if (m_data->m_verboseOutput) + { + b3Printf("Received robot description ok!\n"); + } + } else + { + b3Warning("Robot description not received"); + } +} + bool PhysicsDirect::submitClientCommand(const struct SharedMemoryCommand& command) { if (command.m_type==CMD_REQUEST_DEBUG_LINES) @@ -296,46 +337,35 @@ bool PhysicsDirect::submitClientCommand(const struct SharedMemoryCommand& comman break; } + case CMD_SDF_LOADING_COMPLETED: + { + //we'll stream further info from the physics server + //so serverCmd will be invalid, make a copy + + + int numBodies = serverCmd.m_sdfLoadedArgs.m_numBodies; + for (int i=0;im_commandProcessor->processCommand(infoRequestCommand,infoStatus,&m_data->m_bulletStreamDataServerToClient[0],SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE); + if (hasStatus) + { + processBodyJointInfo(bodyUniqueId, infoStatus); + } + } + break; + } case CMD_URDF_LOADING_COMPLETED: { + if (serverCmd.m_dataStreamArguments.m_streamChunkLength > 0) { - bParse::btBulletFile bf( - &m_data->m_bulletStreamDataServerToClient[0], - serverCmd.m_dataStreamArguments.m_streamChunkLength); - bf.setFileDNAisMemoryDNA(); - bf.parse(false); - int bodyIndex = serverCmd.m_dataStreamArguments.m_bodyUniqueId; - - BodyJointInfoCache2* bodyJoints = new BodyJointInfoCache2; - m_data->m_bodyJointMap.insert(bodyIndex,bodyJoints); - - for (int i = 0; i < bf.m_multiBodies.size(); i++) - { - int flag = bf.getFlags(); - if ((flag & bParse::FD_DOUBLE_PRECISION) != 0) - { - Bullet::btMultiBodyDoubleData* mb = - (Bullet::btMultiBodyDoubleData*)bf.m_multiBodies[i]; - - addJointInfoFromMultiBodyData(mb,bodyJoints, m_data->m_verboseOutput); - } else - { - Bullet::btMultiBodyFloatData* mb = - (Bullet::btMultiBodyFloatData*)bf.m_multiBodies[i]; - - addJointInfoFromMultiBodyData(mb,bodyJoints, m_data->m_verboseOutput); - } - } - if (bf.ok()) { - if (m_data->m_verboseOutput) - { - b3Printf("Received robot description ok!\n"); - } - } else - { - b3Warning("Robot description not received"); - } + int bodyIndex = serverCmd.m_dataStreamArguments.m_bodyUniqueId; + processBodyJointInfo(bodyIndex,serverCmd); } break; } diff --git a/examples/SharedMemory/PhysicsDirect.h b/examples/SharedMemory/PhysicsDirect.h index 9dea925d3..1e9ebbcf3 100644 --- a/examples/SharedMemory/PhysicsDirect.h +++ b/examples/SharedMemory/PhysicsDirect.h @@ -21,6 +21,8 @@ protected: bool processCamera(const struct SharedMemoryCommand& orgCommand); + void processBodyJointInfo(int bodyUniqueId, const struct SharedMemoryStatus& serverCmd); + public: PhysicsDirect(); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 98994ea68..e3a9b7f48 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -762,12 +762,7 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe createJointMotors(mb); - //serialize the btMultiBody and send the data to the client. This is one way to get the link/joint names across the (shared memory) wire - - UrdfLinkNameMapUtil* util2 = new UrdfLinkNameMapUtil; - m_data->m_urdfLinkNameMapper.push_back(util2); - util2->m_mb = mb; - util2->m_memSerializer = 0; + //disable serialization of the collision objects (they are too big, and the client likely doesn't need them); bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks()); @@ -963,7 +958,44 @@ void PhysicsServerCommandProcessor::replayLogCommand(char* bufferServerToClient, } } +int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char* bufferServerToClient, int bufferSizeInBytes) +{ + int streamSizeInBytes = 0; + //serialize the btMultiBody and send the data to the client. This is one way to get the link/joint names across the (shared memory) wire + InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId); + btMultiBody* mb = bodyHandle->m_multiBody; + if (mb) + { + UrdfLinkNameMapUtil* util = new UrdfLinkNameMapUtil; + m_data->m_urdfLinkNameMapper.push_back(util); + util->m_mb = mb; + util->m_memSerializer = new btDefaultSerializer(bufferSizeInBytes ,(unsigned char*)bufferServerToClient); + //disable serialization of the collision objects (they are too big, and the client likely doesn't need them); + util->m_memSerializer->m_skipPointers.insert(mb->getBaseCollider(),0); + + bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks()); + for (int i=0;igetNumLinks();i++) + { + //disable serialization of the collision objects + util->m_memSerializer->m_skipPointers.insert(mb->getLink(i).m_collider,0); + util->m_memSerializer->registerNameForPointer(mb->getLink(i).m_linkName,mb->getLink(i).m_linkName); + util->m_memSerializer->registerNameForPointer(mb->getLink(i).m_jointName,mb->getLink(i).m_jointName); + } + + util->m_memSerializer->registerNameForPointer(mb->getBaseName(),mb->getBaseName()); + + util->m_memSerializer->insertHeader(); + + int len = mb->calculateSerializeBufferSize(); + btChunk* chunk = util->m_memSerializer->allocate(len,1); + const char* structType = mb->serialize(chunk->m_oldPtr, util->m_memSerializer); + util->m_memSerializer->finalizeChunk(chunk,structType,BT_MULTIBODY_CODE,mb); + streamSizeInBytes = util->m_memSerializer->getCurrentBufferSize(); + + } + return streamSizeInBytes; +} bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes ) { @@ -1171,6 +1203,18 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm break; } + case CMD_REQUEST_BODY_INFO: + { + const SdfRequestInfoArgs& sdfInfoArgs = clientCmd.m_sdfRequestInfoArgs; + //stream info into memory + int streamSizeInBytes = createBodyInfoStream(sdfInfoArgs.m_bodyUniqueId, bufferServerToClient, bufferSizeInBytes); + + serverStatusOut.m_type = CMD_BODY_INFO_COMPLETED; + serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = sdfInfoArgs.m_bodyUniqueId; + serverStatusOut.m_dataStreamArguments.m_streamChunkLength = streamSizeInBytes; + hasStatus = true; + break; + } case CMD_LOAD_SDF: { const SdfArgs& sdfArgs = clientCmd.m_sdfArguments; diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.h b/examples/SharedMemory/PhysicsServerCommandProcessor.h index 242a41176..bc74a0a27 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.h +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.h @@ -27,6 +27,8 @@ protected: bool useMultiBody, bool useFixedBase, int* bodyUniqueIdPtr, char* bufferServerToClient, int bufferSizeInBytes); bool supportsJointMotor(class btMultiBody* body, int linkIndex); + + int createBodyInfoStream(int bodyUniqueId, char* bufferServerToClient, int bufferSizeInBytes); public: PhysicsServerCommandProcessor(); diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index a4c93180e..83fd91c34 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -312,7 +312,7 @@ struct SdfLoadedArgs struct SdfRequestInfoArgs { - int m_infoIndex; + int m_bodyUniqueId; }; enum EnumSdfRequestInfoFlags diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index a038ecf51..5e6da5c50 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -19,7 +19,7 @@ enum EnumSharedMemoryClientCommand CMD_SEND_DESIRED_STATE,//todo: reconsider naming, for example SET_JOINT_CONTROL_VARIABLE? CMD_REQUEST_ACTUAL_STATE, CMD_REQUEST_DEBUG_LINES, - CMD_REQUEST_SDF_INFO, + CMD_REQUEST_BODY_INFO, CMD_STEP_FORWARD_SIMULATION, CMD_RESET_SIMULATION, CMD_PICK_BODY, @@ -55,6 +55,8 @@ enum EnumSharedMemoryServerStatus CMD_RESET_SIMULATION_COMPLETED, CMD_CAMERA_IMAGE_COMPLETED, CMD_CAMERA_IMAGE_FAILED, + CMD_BODY_INFO_COMPLETED, + CMD_BODY_INFO_FAILED, CMD_INVALID_STATUS, CMD_MAX_SERVER_COMMANDS }; diff --git a/test/SharedMemory/test.c b/test/SharedMemory/test.c index c6417b802..f6b95f37e 100644 --- a/test/SharedMemory/test.c +++ b/test/SharedMemory/test.c @@ -35,6 +35,7 @@ void testSharedMemory(b3PhysicsClientHandle sm) int sensorJointIndexLeft=-1; int sensorJointIndexRight=-1; const char* urdfFileName = "r2d2.urdf"; + const char* sdfFileName = "kuka_iiwa/model.sdf"; double gravx=0, gravy=0, gravz=-9.8; double timeStep = 1./60.; double startPosX, startPosY,startPosZ; @@ -52,7 +53,23 @@ void testSharedMemory(b3PhysicsClientHandle sm) ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); } - + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; + int bodyIndicesOut[10];//MAX_SDF_BODIES = 10 + int numJoints, numBodies; + b3SharedMemoryCommandHandle command = b3LoadSdfCommandInit(sm, sdfFileName); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + statusType = b3GetStatusType(statusHandle); + ASSERT_EQ(statusType, CMD_SDF_LOADING_COMPLETED); + + numBodies = b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, 10); + ASSERT_EQ(numBodies,1); + numJoints = b3GetNumJoints(sm,bodyIndicesOut[0]); + printf("numJoints: %d\n", numJoints); + //ASSERT_EQ(numBodies ==1); + } + { b3SharedMemoryStatusHandle statusHandle; int statusType; From 03fded3dc7b6d730c7fcaad083115689387f9837 Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Wed, 15 Jun 2016 14:21:04 -0700 Subject: [PATCH 027/115] getJointPositions returns a list of all joint positions for a given bodyIndex --- examples/pybullet/pybullet.c | 180 +++++++++++++++++++++++++++-------- 1 file changed, 142 insertions(+), 38 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index b8bf684c2..17c092b2d 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -121,7 +121,7 @@ pybullet_disconnectPhysicsServer(PyObject *self, PyObject *args) // Load a URDF file indicating the links and joints of an object // function can be called without arguments and will default // to position (0,0,1) with orientation(0,0,0,1) -// else, loadURDF(x,y,z) or +// els(x,y,z) or // loadURDF(pos_x, pos_y, pos_z, orn_x, orn_y, orn_z, orn_w) static PyObject * pybullet_loadURDF(PyObject* self, PyObject* args) @@ -337,6 +337,7 @@ static void pybullet_internalGetBasePositionAndOrientation(int bodyIndex, double baseOrientation[1] = actualStateQ[4]; baseOrientation[2] = actualStateQ[5]; baseOrientation[3] = actualStateQ[6]; + } } } @@ -451,52 +452,146 @@ pybullet_initializeJointPositions(PyObject* self, PyObject* args) return Py_None; } + +// CURRENTLY NOT SUPPORTED // Initalize a single joint position for a specific body index // // This method skips any physics simulation and // teleports all joints to the new positions. -// TODO(hellojas): test accuracy of joint position values -static PyObject* -pybullet_initializeJointPosition(PyObject* self, PyObject* args) -{ - if (0==sm) - { - PyErr_SetString(SpamError, "Not connected to physics server."); - return NULL; - } +// TODO(hellojas): initializing one joint currently not supported +// static PyObject* +// pybullet_initializeJointPosition(PyObject* self, PyObject* args) +// { +// if (0==sm) +// { +// PyErr_SetString(SpamError, "Not connected to physics server."); +// return NULL; +// } +// +// int i; +// int bodyIndex = -1; +// int jointIndex = -1; +// double jointPos = 0.0; +// +// int size= PySequence_Size(args); +// +// if (size==3) // get body index, joint index, and joint position value +// { +// if (PyArg_ParseTuple(args, "iid", &bodyIndex, &jointIndex, &jointPos)) +// { +// b3SharedMemoryCommandHandle cmd_handle = b3CreatePoseCommandInit(sm, bodyIndex); +// +// // printf("initializing joint %d at %f\n", jointIndex, jointPos); +// b3CreatePoseCommandSetJointPosition(sm, cmd_handle, jointIndex, jointPos); +// +// b3SharedMemoryStatusHandle status_handle = +// b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); +// +// const int status_type = b3GetStatusType(status_handle); +// +// } +// } +// +// Py_INCREF(Py_None); +// return Py_None; +// } + +static void pybullet_internalGetJointPositions(int bodyIndex, int numJoints, double jointPositions[]) { + int i, j; + int numDegreeQ; + int numDegreeU; + int arrSizeOfPosAndOrn = 7; - int i; - int bodyIndex = -1; - int jointIndex = -1; - double jointPos = 0.0; - - int size= PySequence_Size(args); - - if (size==3) // get body index, joint index, and joint position value - { - if (PyArg_ParseTuple(args, "iid", &bodyIndex, &jointIndex, &jointPos)) - { - b3SharedMemoryCommandHandle cmd_handle = b3CreatePoseCommandInit(sm, bodyIndex); - - // printf("initializing joint %d at %f\n", jointIndex, jointPos); - b3CreatePoseCommandSetJointPosition(sm, cmd_handle, jointIndex, jointPos); - - b3SharedMemoryStatusHandle status_handle = - b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); - - const int status_type = b3GetStatusType(status_handle); - - } + for (i =0;i Date: Wed, 15 Jun 2016 18:01:41 -0700 Subject: [PATCH 028/115] implement getJointInfo for objects loaded through SDF --- examples/SharedMemory/PhysicsClient.h | 2 +- examples/SharedMemory/PhysicsClientC_API.cpp | 4 +- examples/SharedMemory/PhysicsClientC_API.h | 2 +- .../PhysicsClientSharedMemory.cpp | 99 +++++++++++++++++-- .../SharedMemory/PhysicsClientSharedMemory.h | 4 +- examples/SharedMemory/PhysicsDirect.cpp | 9 +- examples/SharedMemory/PhysicsDirect.h | 2 +- examples/SharedMemory/PhysicsLoopBack.cpp | 4 +- examples/SharedMemory/PhysicsLoopBack.h | 2 +- test/SharedMemory/test.c | 14 ++- 10 files changed, 122 insertions(+), 20 deletions(-) diff --git a/examples/SharedMemory/PhysicsClient.h b/examples/SharedMemory/PhysicsClient.h index 59a1a4e90..07b10aa13 100644 --- a/examples/SharedMemory/PhysicsClient.h +++ b/examples/SharedMemory/PhysicsClient.h @@ -26,7 +26,7 @@ public: virtual int getNumJoints(int bodyIndex) const = 0; - virtual void getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const = 0; + virtual bool getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const = 0; virtual void setSharedMemoryKey(int key) = 0; diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 81a58a992..a627e08af 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -653,10 +653,10 @@ int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyId) } -void b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, struct b3JointInfo* info) +int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, struct b3JointInfo* info) { PhysicsClient* cl = (PhysicsClient* ) physClient; - cl->getJointInfo(bodyIndex, linkIndex,*info); + return cl->getJointInfo(bodyIndex, linkIndex,*info); } b3SharedMemoryCommandHandle b3PickBody(b3PhysicsClientHandle physClient, double rayFromWorldX, diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 468347ef5..4ae1a5235 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -57,7 +57,7 @@ int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyIndex); ///given a body and link index, return the joint information. See b3JointInfo in SharedMemoryPublic.h -void b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, struct b3JointInfo* info); +int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, struct b3JointInfo* info); ///Request debug lines for debug visualization. The flags in debugMode are the same as used in Bullet ///See btIDebugDraw::DebugDrawModes in Bullet/src/LinearMath/btIDebugDraw.h diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp index a4c57574d..3ca2aa5c5 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp @@ -37,6 +37,9 @@ struct PhysicsClientSharedMemoryInternalData { btAlignedObjectArray m_cachedCameraPixelsRGBA; btAlignedObjectArray m_cachedCameraDepthBuffer; + btAlignedObjectArray m_bodyIdsRequestInfo; + SharedMemoryStatus m_tempBackupServerStatus; + SharedMemoryStatus m_lastServerStatus; int m_counter; @@ -82,15 +85,16 @@ int PhysicsClientSharedMemory::getNumJoints(int bodyIndex) const } -void PhysicsClientSharedMemory::getJointInfo(int bodyIndex, int jointIndex, b3JointInfo& info) const +bool PhysicsClientSharedMemory::getJointInfo(int bodyIndex, int jointIndex, b3JointInfo& info) const { BodyJointInfoCache** bodyJointsPtr = m_data->m_bodyJointMap[bodyIndex]; if (bodyJointsPtr && *bodyJointsPtr) { BodyJointInfoCache* bodyJoints = *bodyJointsPtr; info = bodyJoints->m_jointInfo[jointIndex]; + return true; } - + return false; } PhysicsClientSharedMemory::PhysicsClientSharedMemory() @@ -167,6 +171,48 @@ bool PhysicsClientSharedMemory::connect() { return true; } + +///todo(erwincoumans) refactor this: merge with PhysicsDirect::processBodyJointInfo +void PhysicsClientSharedMemory::processBodyJointInfo(int bodyUniqueId, const SharedMemoryStatus& serverCmd) +{ + bParse::btBulletFile bf( + &this->m_data->m_testBlock1->m_bulletStreamDataServerToClientRefactor[0], + serverCmd.m_dataStreamArguments.m_streamChunkLength); + bf.setFileDNAisMemoryDNA(); + bf.parse(false); + + + BodyJointInfoCache* bodyJoints = new BodyJointInfoCache; + m_data->m_bodyJointMap.insert(bodyUniqueId,bodyJoints); + + for (int i = 0; i < bf.m_multiBodies.size(); i++) + { + int flag = bf.getFlags(); + if ((flag & bParse::FD_DOUBLE_PRECISION) != 0) + { + Bullet::btMultiBodyDoubleData* mb = + (Bullet::btMultiBodyDoubleData*)bf.m_multiBodies[i]; + + addJointInfoFromMultiBodyData(mb,bodyJoints, m_data->m_verboseOutput); + } else + { + Bullet::btMultiBodyFloatData* mb = + (Bullet::btMultiBodyFloatData*)bf.m_multiBodies[i]; + + addJointInfoFromMultiBodyData(mb,bodyJoints, m_data->m_verboseOutput); + } + } + if (bf.ok()) { + if (m_data->m_verboseOutput) + { + b3Printf("Received robot description ok!\n"); + } + } else + { + b3Warning("Robot description not received"); + } +} + const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { SharedMemoryStatus* stat = 0; @@ -208,6 +254,7 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { if (m_data->m_verboseOutput) { b3Printf("Server loading the SDF OK\n"); } + break; } case CMD_URDF_LOADING_COMPLETED: { @@ -275,6 +322,16 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { break; } + case CMD_BODY_INFO_COMPLETED: + { + if (m_data->m_verboseOutput) { + b3Printf("Received body info\n"); + } + int bodyUniqueId = serverCmd.m_dataStreamArguments.m_bodyUniqueId; + processBodyJointInfo(bodyUniqueId, serverCmd); + + break; + } case CMD_SDF_LOADING_FAILED: { if (m_data->m_verboseOutput) { b3Printf("Server failed loading the SDF...\n"); @@ -504,21 +561,49 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() { m_data->m_waitingForServer = true; } - /*if (serverCmd.m_type == CMD_SDF_LOADING_COMPLETED) + if (serverCmd.m_type == CMD_SDF_LOADING_COMPLETED) { int numBodies = serverCmd.m_sdfLoadedArgs.m_numBodies; if (numBodies>0) { + m_data->m_tempBackupServerStatus = m_data->m_lastServerStatus; + + for (int i=0;im_bodyIdsRequestInfo.push_back(serverCmd.m_sdfLoadedArgs.m_bodyUniqueIds[i]); + } + + int bodyId = m_data->m_bodyIdsRequestInfo[m_data->m_bodyIdsRequestInfo.size()-1]; + m_data->m_bodyIdsRequestInfo.pop_back(); + SharedMemoryCommand& command = m_data->m_testBlock1->m_clientCommands[0]; //now transfer the information of the individual objects etc. - command.m_type = CMD_REQUEST_SDF_INFO; - command.m_updateFlags = SDF_REQUEST_INFO_BODY; - command.m_sdfRequestInfoArgs.m_infoIndex = 0; + command.m_type = CMD_REQUEST_BODY_INFO; + command.m_sdfRequestInfoArgs.m_bodyUniqueId = bodyId; submitClientCommand(command); return 0; } } - */ + + if (serverCmd.m_type == CMD_BODY_INFO_COMPLETED) + { + //are there any bodies left to be processed? + if (m_data->m_bodyIdsRequestInfo.size()) + { + int bodyId = m_data->m_bodyIdsRequestInfo[m_data->m_bodyIdsRequestInfo.size()-1]; + m_data->m_bodyIdsRequestInfo.pop_back(); + + SharedMemoryCommand& command = m_data->m_testBlock1->m_clientCommands[0]; + //now transfer the information of the individual objects etc. + command.m_type = CMD_REQUEST_BODY_INFO; + command.m_sdfRequestInfoArgs.m_bodyUniqueId = bodyId; + submitClientCommand(command); + return 0; + } else + { + m_data->m_lastServerStatus = m_data->m_tempBackupServerStatus; + } + } if (serverCmd.m_type == CMD_CAMERA_IMAGE_COMPLETED) { diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.h b/examples/SharedMemory/PhysicsClientSharedMemory.h index 1081771e5..a47fc551a 100644 --- a/examples/SharedMemory/PhysicsClientSharedMemory.h +++ b/examples/SharedMemory/PhysicsClientSharedMemory.h @@ -11,7 +11,9 @@ class PhysicsClientSharedMemory : public PhysicsClient { protected: virtual void setSharedMemoryInterface(class SharedMemoryInterface* sharedMem); + void processBodyJointInfo(int bodyUniqueId, const struct SharedMemoryStatus& serverCmd); + public: PhysicsClientSharedMemory(); virtual ~PhysicsClientSharedMemory(); @@ -34,7 +36,7 @@ public: virtual int getNumJoints(int bodyIndex) const; - virtual void getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const; + virtual bool getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const; virtual void setSharedMemoryKey(int key); diff --git a/examples/SharedMemory/PhysicsDirect.cpp b/examples/SharedMemory/PhysicsDirect.cpp index 36212cc8c..511290778 100644 --- a/examples/SharedMemory/PhysicsDirect.cpp +++ b/examples/SharedMemory/PhysicsDirect.cpp @@ -393,14 +393,19 @@ int PhysicsDirect::getNumJoints(int bodyIndex) const return 0; } -void PhysicsDirect::getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const +bool PhysicsDirect::getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const { BodyJointInfoCache2** bodyJointsPtr = m_data->m_bodyJointMap[bodyIndex]; if (bodyJointsPtr && *bodyJointsPtr) { BodyJointInfoCache2* bodyJoints = *bodyJointsPtr; - info = bodyJoints->m_jointInfo[jointIndex]; + if (jointIndex < bodyJoints->m_jointInfo.size()) + { + info = bodyJoints->m_jointInfo[jointIndex]; + return true; + } } + return false; } ///todo: move this out of the diff --git a/examples/SharedMemory/PhysicsDirect.h b/examples/SharedMemory/PhysicsDirect.h index 1e9ebbcf3..aaa2d8639 100644 --- a/examples/SharedMemory/PhysicsDirect.h +++ b/examples/SharedMemory/PhysicsDirect.h @@ -48,7 +48,7 @@ public: virtual int getNumJoints(int bodyIndex) const; - virtual void getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const; + virtual bool getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const; ///todo: move this out of the virtual void setSharedMemoryKey(int key); diff --git a/examples/SharedMemory/PhysicsLoopBack.cpp b/examples/SharedMemory/PhysicsLoopBack.cpp index 985352113..ada37ce88 100644 --- a/examples/SharedMemory/PhysicsLoopBack.cpp +++ b/examples/SharedMemory/PhysicsLoopBack.cpp @@ -79,9 +79,9 @@ int PhysicsLoopBack::getNumJoints(int bodyIndex) const return m_data->m_physicsClient->getNumJoints(bodyIndex); } -void PhysicsLoopBack::getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const +bool PhysicsLoopBack::getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const { - m_data->m_physicsClient->getJointInfo(bodyIndex,jointIndex,info); + return m_data->m_physicsClient->getJointInfo(bodyIndex,jointIndex,info); } ///todo: move this out of the diff --git a/examples/SharedMemory/PhysicsLoopBack.h b/examples/SharedMemory/PhysicsLoopBack.h index edc71ceb9..8c0e187b6 100644 --- a/examples/SharedMemory/PhysicsLoopBack.h +++ b/examples/SharedMemory/PhysicsLoopBack.h @@ -40,7 +40,7 @@ public: virtual int getNumJoints(int bodyIndex) const; - virtual void getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const; + virtual bool getJointInfo(int bodyIndex, int jointIndex, struct b3JointInfo& info) const; ///todo: move this out of the virtual void setSharedMemoryKey(int key); diff --git a/test/SharedMemory/test.c b/test/SharedMemory/test.c index f6b95f37e..01d0a16a8 100644 --- a/test/SharedMemory/test.c +++ b/test/SharedMemory/test.c @@ -65,8 +65,18 @@ void testSharedMemory(b3PhysicsClientHandle sm) numBodies = b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, 10); ASSERT_EQ(numBodies,1); - numJoints = b3GetNumJoints(sm,bodyIndicesOut[0]); - printf("numJoints: %d\n", numJoints); + int bodyUniqueId = bodyIndicesOut[0]; + + numJoints = b3GetNumJoints(sm,bodyUniqueId); + b3Printf("numJoints: %d\n", numJoints); + for (i=0;i Date: Thu, 16 Jun 2016 11:48:37 -0700 Subject: [PATCH 029/115] Set view and projection matrices from camera and frustum parameters. --- examples/SharedMemory/PhysicsClientC_API.cpp | 79 ++++++++++++++++++++ examples/SharedMemory/PhysicsClientC_API.h | 2 + 2 files changed, 81 insertions(+) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index a627e08af..ae001176d 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -1,6 +1,7 @@ #include "PhysicsClientC_API.h" #include "PhysicsClientSharedMemory.h" #include "Bullet3Common/b3Scalar.h" +#include "Bullet3Common/b3Vector3.h" #include #include "SharedMemoryCommands.h" @@ -766,6 +767,84 @@ void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHa command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; } +void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]) +{ + b3Vector3 eye = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]); + b3Vector3 center = b3MakeVector3(cameraTargetPosition[0], cameraTargetPosition[1], cameraTargetPosition[2]); + b3Vector3 up = b3MakeVector3(cameraUp[0], cameraUp[1], cameraUp[2]); + b3Vector3 f = (center - eye).normalized(); + b3Vector3 u = up.normalized(); + b3Vector3 s = (f.cross(u)).normalized(); + u = s.cross(f); + + float viewMatrix[16]; + + viewMatrix[0*4+0] = s.x; + viewMatrix[1*4+0] = s.y; + viewMatrix[2*4+0] = s.z; + + viewMatrix[0*4+1] = u.x; + viewMatrix[1*4+1] = u.y; + viewMatrix[2*4+1] = u.z; + + viewMatrix[0*4+2] =-f.x; + viewMatrix[1*4+2] =-f.y; + viewMatrix[2*4+2] =-f.z; + + viewMatrix[0*4+3] = 0.f; + viewMatrix[1*4+3] = 0.f; + viewMatrix[2*4+3] = 0.f; + + viewMatrix[3*4+0] = -s.dot(eye); + viewMatrix[3*4+1] = -u.dot(eye); + viewMatrix[3*4+2] = f.dot(eye); + viewMatrix[3*4+3] = 1.f; + + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); + for (int i=0;i<16;i++) + { + command->m_requestPixelDataArguments.m_viewMatrix[i] = viewMatrix[i]; + } + command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; + +} + +void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float left, float right, float bottom, float top, float nearVal, float farVal) +{ + float frustum[16]; + + frustum[0*4+0] = (float(2) * nearVal) / (right - left); + frustum[0*4+1] = float(0); + frustum[0*4+2] = float(0); + frustum[0*4+3] = float(0); + + frustum[1*4+0] = float(0); + frustum[1*4+1] = (float(2) * nearVal) / (top - bottom); + frustum[1*4+2] = float(0); + frustum[1*4+3] = float(0); + + frustum[2*4+0] = (right + left) / (right - left); + frustum[2*4+1] = (top + bottom) / (top - bottom); + frustum[2*4+2] = -(farVal + nearVal) / (farVal - nearVal); + frustum[2*4+3] = float(-1); + + frustum[3*4+0] = float(0); + frustum[3*4+1] = float(0); + frustum[3*4+2] = -(float(2) * farVal * nearVal) / (farVal - nearVal); + frustum[3*4+3] = float(0); + + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); + for (int i=0;i<16;i++) + { + command->m_requestPixelDataArguments.m_projectionMatrix[i] = frustum[i]; + } + command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; +} + void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle commandHandle, int width, int height ) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 4ae1a5235..1bff499c5 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -70,6 +70,8 @@ void b3GetDebugLines(b3PhysicsClientHandle physClient, struct b3DebugLines* l ///request an image from a simulated camera, using a software renderer. b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient); void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]); +void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle command, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]); +void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle command, float left, float right, float bottom, float top, float nearVal, float farVal); void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height ); void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData); From 53a0772257e2b1bb144df2f3129a784502652ab4 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 16 Jun 2016 18:46:34 -0700 Subject: [PATCH 030/115] fix some issues related to controlling a robot/multibody beyond body index 0 (most testing happened with a single robot/multibody so far) preliminary pybullet.setJointControl implementation --- examples/SharedMemory/PhysicsClientC_API.cpp | 8 +- examples/SharedMemory/PhysicsClientC_API.h | 4 +- .../SharedMemory/PhysicsClientExample.cpp | 82 ++++++-- .../PhysicsServerCommandProcessor.cpp | 24 +-- examples/pybullet/pybullet.c | 195 +++++++++++++++--- .../Featherstone/btMultiBodyLink.h | 3 + test/SharedMemory/test.c | 2 +- 7 files changed, 248 insertions(+), 70 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index a627e08af..77e6060bf 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -150,7 +150,7 @@ b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHand } -b3SharedMemoryCommandHandle b3JointControlCommandInit( b3PhysicsClientHandle physClient, int controlMode) +b3SharedMemoryCommandHandle b3JointControlCommandInit( b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -159,7 +159,7 @@ b3SharedMemoryCommandHandle b3JointControlCommandInit( b3PhysicsClientHandle phy b3Assert(command); command->m_type = CMD_SEND_DESIRED_STATE; command->m_sendDesiredStateCommandArgument.m_controlMode = controlMode; - command->m_sendDesiredStateCommandArgument.m_bodyUniqueId = 0; + command->m_sendDesiredStateCommandArgument.m_bodyUniqueId = bodyUniqueId; command->m_updateFlags = 0; return (b3SharedMemoryCommandHandle) command; } @@ -433,7 +433,7 @@ int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3Shar -b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle physClient) +b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); @@ -444,7 +444,7 @@ b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle phys command->m_type = CMD_CREATE_SENSOR; command->m_updateFlags = 0; command->m_createSensorArguments.m_numJointSensorChanges = 0; - command->m_createSensorArguments.m_bodyUniqueId = 0; + command->m_createSensorArguments.m_bodyUniqueId = bodyUniqueId; return (b3SharedMemoryCommandHandle) command; } diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 4ae1a5235..3813fab88 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -95,7 +95,7 @@ b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClien ///Set joint control variables such as desired position/angle, desired velocity, ///applied joint forces, dependent on the control mode (CONTROL_MODE_VELOCITY or CONTROL_MODE_TORQUE) -b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode); +b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode); ///Only use when controlMode is CONTROL_MODE_POSITION_VELOCITY_PD int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value); int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); @@ -132,7 +132,7 @@ int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3Shar ///We are currently not reading the sensor information from the URDF file, and programmatically assign sensors. ///This is rather inconsistent, to mix programmatical creation with loading from file. -b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle physClient); +b3SharedMemoryCommandHandle b3CreateSensorCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId); int b3CreateSensorEnable6DofJointForceTorqueSensor(b3SharedMemoryCommandHandle commandHandle, int jointIndex, int enable); ///b3CreateSensorEnableIMUForLink is not implemented yet. ///For now, if the IMU is located in the root link, use the root world transform to mimic an IMU. diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index 691dbb9c6..e0338153a 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -37,6 +37,9 @@ protected: bool m_wantsTermination; btAlignedObjectArray m_userCommandRequests; + btAlignedObjectArray m_bodyUniqueIds; + + int m_sharedMemoryKey; int m_selectedBody; int m_prevSelectedBody; @@ -66,7 +69,8 @@ protected: { if (m_guiHelper && m_guiHelper->getParameterInterface()) { - int bodyIndex = comboIndex; + int itemIndex = int(atoi(name)); + int bodyIndex = m_bodyUniqueIds[itemIndex]; if (m_selectedBody != bodyIndex) { m_selectedBody = bodyIndex; @@ -154,14 +158,20 @@ protected: void prepareControlCommand(b3SharedMemoryCommandHandle commandHandle) { + for (int i=0;i=0) + { + // b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_physicsClientHandle, m_selectedBody, CONTROL_MODE_VELOCITY); + b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_physicsClientHandle, m_selectedBody, CONTROL_MODE_POSITION_VELOCITY_PD); + // b3Printf("prepare control command for body %d", m_selectedBody); + prepareControlCommand(command); + + b3SubmitClientCommand(m_physicsClientHandle, command); - break; + } + break; } case CMD_RESET_SIMULATION: { @@ -471,9 +488,36 @@ void PhysicsClientExample::createButtons() createButton("Initialize Pose",CMD_INIT_POSE, isTrigger); createButton("Set gravity", CMD_SEND_PHYSICS_SIMULATION_PARAMETERS, isTrigger); + if (m_bodyUniqueIds.size()) + { + if (m_selectedBody<0) + m_selectedBody = 0; + + ComboBoxParams comboParams; + comboParams.m_comboboxId = 0; + comboParams.m_numItems = m_bodyUniqueIds.size(); + comboParams.m_startItem = m_selectedBody; + comboParams.m_callback = MyComboBoxCallback; + comboParams.m_userPointer = this; + //todo: get the real object name + + const char** blarray = new const char*[m_bodyUniqueIds.size()]; + + for (int i=0;igetParameterInterface()->registerComboBox(comboParams); + } + if (m_physicsClientHandle && m_selectedBody>=0) { + m_numMotors = 0; + int numJoints = b3GetNumJoints(m_physicsClientHandle,m_selectedBody); for (int i=0;i0) + { + m_selectedBody = bodyUniqueId; + } +/* int numJoints = b3GetNumJoints(m_physicsClientHandle,bodyUniqueId); b3Printf("numJoints = %d", numJoints); for (int i=0;i=0) { + m_bodyUniqueIds.push_back(bodyIndex); + m_selectedBody = bodyIndex; int numJoints = b3GetNumJoints(m_physicsClientHandle,bodyIndex); for (int i=0;igetParameterInterface()->registerComboBox(comboParams); + } } } @@ -759,6 +800,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime) { m_selectedBody = -1; m_numMotors=0; + m_bodyUniqueIds.clear(); createButtons(); b3SharedMemoryCommandHandle commandHandle = b3InitResetSimulationCommand(m_physicsClientHandle); if (m_options == eCLIENTEXAMPLE_SERVER) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index e3a9b7f48..33d7d3153 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -382,7 +382,6 @@ struct PhysicsServerCommandProcessorInternalData btAlignedObjectArray m_worldImporters; btAlignedObjectArray m_urdfLinkNameMapper; - btHashMap m_multiBodyJointMotorMap; btAlignedObjectArray m_strings; btAlignedObjectArray m_collisionShapes; @@ -560,7 +559,6 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld() } m_data->m_urdfLinkNameMapper.clear(); - m_data->m_multiBodyJointMotorMap.clear(); for (int i=0;im_strings.size();i++) { @@ -672,7 +670,7 @@ void PhysicsServerCommandProcessor::createJointMotors(btMultiBody* mb) btScalar desiredVelocity = 0.f; btMultiBodyJointMotor* motor = new btMultiBodyJointMotor(mb,mbLinkIndex,dof,desiredVelocity,maxMotorImpulse); //motor->setMaxAppliedImpulse(0); - m_data->m_multiBodyJointMotorMap.insert(mbLinkIndex,motor); + mb->getLink(mbLinkIndex).m_userPtr = motor; m_data->m_dynamicsWorld->addMultiBodyConstraint(motor); motor->finalizeMultiDof(); @@ -1436,10 +1434,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (supportsJointMotor(mb,link)) { - btMultiBodyJointMotor** motorPtr = m_data->m_multiBodyJointMotorMap[link]; - if (motorPtr) + btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr; + + + if (motor) { - btMultiBodyJointMotor* motor = *motorPtr; btScalar desiredVelocity = 0.f; if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_QDOT)!=0) desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex]; @@ -1479,10 +1478,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (supportsJointMotor(mb,link)) { - btMultiBodyJointMotor** motorPtr = m_data->m_multiBodyJointMotorMap[link]; - if (motorPtr) + + btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr; + + if (motor) { - btMultiBodyJointMotor* motor = *motorPtr; btScalar desiredVelocity = 0.f; if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_QDOT)!=0) @@ -1644,10 +1644,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (supportsJointMotor(mb,l)) { - btMultiBodyJointMotor** motorPtr = m_data->m_multiBodyJointMotorMap[l]; - if (motorPtr && m_data->m_physicsDeltaTime>btScalar(0)) + btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)body->m_multiBody->getLink(l).m_userPtr; + + if (motor && m_data->m_physicsDeltaTime>btScalar(0)) { - btMultiBodyJointMotor* motor = *motorPtr; btScalar force =motor->getAppliedImpulse(0)/m_data->m_physicsDeltaTime; serverCmd.m_sendActualStateArgs.m_jointMotorForce[l] = force; diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 17c092b2d..fbd070ff9 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1,6 +1,6 @@ -#include "../SharedMemory/SharedMemoryInProcessPhysicsC_API.h" #include "../SharedMemory/PhysicsClientC_API.h" #include "../SharedMemory/PhysicsDirectC_API.h" +#include "../SharedMemory/SharedMemoryInProcessPhysicsC_API.h" #ifdef __APPLE__ @@ -16,6 +16,8 @@ enum eCONNECT_METHOD eCONNECT_SHARED_MEMORY=3, }; + + static PyObject *SpamError; static b3PhysicsClientHandle sm=0; @@ -182,6 +184,25 @@ pybullet_loadURDF(PyObject* self, PyObject* args) return PyLong_FromLong(bodyIndex); } +static float pybullet_internalGetFloatFromSequence(PyObject* seq, int index) +{ + float v = 0.f; + PyObject* item; + + if (PyList_Check(seq)) + { + item = PyList_GET_ITEM(seq, index); + v = PyFloat_AsDouble(item); + } + else + { + item = PyTuple_GET_ITEM(seq,index); + v = PyFloat_AsDouble(item); + } + return v; +} + + #define MAX_SDF_BODIES 512 static PyObject* @@ -255,6 +276,109 @@ pybullet_resetSimulation(PyObject* self, PyObject* args) return Py_None; } +static int pybullet_setJointControl(PyObject* self, PyObject* args) +{ + //todo(erwincoumans): set max forces, kp, kd + + int size; + + if (0==sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + size= PySequence_Size(args); + + if (size==3) + { + int bodyIndex, controlMode; + PyObject* targetValues; + if (PyArg_ParseTuple(args, "iiO", &bodyIndex, &controlMode, &targetValues)) + { + PyObject* seq; + int numJoints, len; + seq = PySequence_Fast(targetValues, "expected a sequence"); + len = PySequence_Size(targetValues); + numJoints = b3GetNumJoints(sm,bodyIndex); + b3SharedMemoryCommandHandle commandHandle; + + if (len!=numJoints) + { + PyErr_SetString(SpamError, "Number of control target values doesn't match the number of joints."); + Py_DECREF(seq); + return NULL; + } + + if ((controlMode != CONTROL_MODE_VELOCITY) && + (controlMode != CONTROL_MODE_TORQUE) && + (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) + { + PyErr_SetString(SpamError, "Illegral control mode."); + Py_DECREF(seq); + return NULL; + } + + commandHandle = b3JointControlCommandInit(sm, bodyIndex,controlMode); + + for (int qIndex=0;qIndex=0) || (sensorJointIndexRight>=0)) { - b3SharedMemoryCommandHandle command = b3CreateSensorCommandInit(sm); + b3SharedMemoryCommandHandle command = b3CreateSensorCommandInit(sm, bodyIndex); b3SharedMemoryStatusHandle statusHandle; if (imuLinkIndex>=0) { From 26f6618f00b640c676b8bbe842c5b44f964ad910 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Fri, 17 Jun 2016 12:07:38 -0700 Subject: [PATCH 031/115] colors for sdf --- data/kuka_iiwa/model.sdf | 8 ++- .../Importers/ImportURDFDemo/UrdfParser.cpp | 60 ++++++++++++------- 2 files changed, 45 insertions(+), 23 deletions(-) diff --git a/data/kuka_iiwa/model.sdf b/data/kuka_iiwa/model.sdf index 1b6f8320d..0df20cff7 100644 --- a/data/kuka_iiwa/model.sdf +++ b/data/kuka_iiwa/model.sdf @@ -32,6 +32,12 @@ meshes/link_0.stl + + 1 0 0 1 + 0 0 1 1 + 0.1 0.1 0.1 1 + 0 0 0 0 + @@ -407,4 +413,4 @@ - \ No newline at end of file + diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 430593b5e..17f6ef93f 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -490,29 +490,45 @@ bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement* // Material TiXmlElement *mat = config->FirstChildElement("material"); //todo(erwincoumans) skip materials in SDF for now (due to complexity) - if (mat && !m_parseSDF) + if (mat) { - // get material name - if (!mat->Attribute("name")) - { - logger->reportError("Visual material must contain a name attribute"); - return false; - } - visual.m_materialName = mat->Attribute("name"); - - // try to parse material element in place - - TiXmlElement *t = mat->FirstChildElement("texture"); - TiXmlElement *c = mat->FirstChildElement("color"); - if (t||c) - { - if (parseMaterial(visual.m_localMaterial, mat,logger)) - { - UrdfMaterial* matPtr = new UrdfMaterial(visual.m_localMaterial); - model.m_materials.insert(matPtr->m_name.c_str(),matPtr); - visual.m_hasLocalMaterial = true; - } - } + if (m_parseSDF) + { + UrdfMaterial* matPtr = new UrdfMaterial; + matPtr->m_name = "mat"; + std::string diffuseText = mat->FirstChildElement("diffuse")->GetText(); + btVector4 rgba(1,0,0,1); + parseVector4(rgba,diffuseText); + matPtr->m_rgbaColor = rgba; + matPtr->m_textureFilename = "textureTest.png"; + model.m_materials.insert(matPtr->m_name.c_str(),matPtr); + visual.m_materialName = "mat"; + visual.m_hasLocalMaterial = true; + } + else + { + // get material name + if (!mat->Attribute("name")) + { + logger->reportError("Visual material must contain a name attribute"); + return false; + } + visual.m_materialName = mat->Attribute("name"); + + // try to parse material element in place + + TiXmlElement *t = mat->FirstChildElement("texture"); + TiXmlElement *c = mat->FirstChildElement("color"); + if (t||c) + { + if (parseMaterial(visual.m_localMaterial, mat,logger)) + { + UrdfMaterial* matPtr = new UrdfMaterial(visual.m_localMaterial); + model.m_materials.insert(matPtr->m_name.c_str(),matPtr); + visual.m_hasLocalMaterial = true; + } + } + } } return true; From d51320be2ce7632ea0b006088c252387d53e37ae Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Fri, 17 Jun 2016 15:47:11 -0700 Subject: [PATCH 032/115] Check diffuse field in sdf. --- .../Importers/ImportURDFDemo/UrdfParser.cpp | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 17f6ef93f..0e720a7c2 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -496,14 +496,16 @@ bool UrdfParser::parseVisual(UrdfModel& model, UrdfVisual& visual, TiXmlElement* { UrdfMaterial* matPtr = new UrdfMaterial; matPtr->m_name = "mat"; - std::string diffuseText = mat->FirstChildElement("diffuse")->GetText(); - btVector4 rgba(1,0,0,1); - parseVector4(rgba,diffuseText); - matPtr->m_rgbaColor = rgba; - matPtr->m_textureFilename = "textureTest.png"; - model.m_materials.insert(matPtr->m_name.c_str(),matPtr); - visual.m_materialName = "mat"; - visual.m_hasLocalMaterial = true; + TiXmlElement *diffuse = mat->FirstChildElement("diffuse"); + if (diffuse) { + std::string diffuseText = diffuse->GetText(); + btVector4 rgba(1,0,0,1); + parseVector4(rgba,diffuseText); + matPtr->m_rgbaColor = rgba; + model.m_materials.insert(matPtr->m_name.c_str(),matPtr); + visual.m_materialName = "mat"; + visual.m_hasLocalMaterial = true; + } } else { From e3b2b1a9693ee743e5da9df9ebd74f518681c224 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sat, 18 Jun 2016 18:02:20 -0700 Subject: [PATCH 033/115] add texture support in SDF, URDF for both OpenGL and software renderer (TinyRenderer) --- data/sphere2.urdf | 2 +- data/two_cubes.sdf | 26 ++++---- .../ImportMeshUtility/b3ImportMeshUtility.cpp | 29 +-------- .../ImportMeshUtility/b3ImportMeshUtility.h | 1 - .../ImportObjDemo/ImportObjExample.cpp | 28 ++++++++- .../ImportURDFDemo/BulletUrdfImporter.cpp | 57 ++++++++++++++++-- .../ImportURDFDemo/ImportURDFSetup.cpp | 2 +- .../TinyRendererVisualShapeConverter.cpp | 60 +++++++++++++++---- 8 files changed, 143 insertions(+), 62 deletions(-) diff --git a/data/sphere2.urdf b/data/sphere2.urdf index 891e018cb..fb0108b3d 100644 --- a/data/sphere2.urdf +++ b/data/sphere2.urdf @@ -9,7 +9,7 @@ - + diff --git a/data/two_cubes.sdf b/data/two_cubes.sdf index 10dce545e..e19b73b43 100644 --- a/data/two_cubes.sdf +++ b/data/two_cubes.sdf @@ -122,11 +122,13 @@ - - 1 1 1 - - + + 1 1 1 + cube.obj + + + 1 1 1 1 + 1 1 1 1 0 diff --git a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp index 3f6553b81..85aeb7e21 100644 --- a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp +++ b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp @@ -1,11 +1,8 @@ #include "b3ImportMeshUtility.h" #include -#include "../../OpenGLWindow/GLInstancingRenderer.h" #include"Wavefront/tiny_obj_loader.h" -#include "../../OpenGLWindow/GLInstanceGraphicsShape.h" -#include "btBulletDynamicsCommon.h" -#include "../../OpenGLWindow/SimpleOpenGL3App.h" +#include "LinearMath/btVector3.h" #include "../ImportObjDemo/Wavefront2GLInstanceGraphicsShape.h" #include "../../Utils/b3ResourcePath.h" #include "Bullet3Common/b3FileUtils.h" @@ -88,28 +85,4 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& return false; } -int b3ImportMeshUtility::loadAndRegisterMeshFromFile(const std::string& fileName, CommonRenderInterface* renderer) -{ - int shapeId = -1; - b3ImportMeshData meshData; - if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(fileName, meshData)) - { - int textureIndex = -1; - - if (meshData.m_textureImage) - { - textureIndex = renderer->registerTexture(meshData.m_textureImage,meshData.m_textureWidth,meshData.m_textureHeight); - } - - shapeId = renderer->registerShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0], - meshData.m_gfxShape->m_numvertices, - &meshData.m_gfxShape->m_indices->at(0), - meshData.m_gfxShape->m_numIndices, - B3_GL_TRIANGLES, - textureIndex); - delete meshData.m_gfxShape; - delete meshData.m_textureImage; - } - return shapeId; -} diff --git a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h index 96c061eaf..7bf6af841 100644 --- a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h +++ b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.h @@ -15,7 +15,6 @@ struct b3ImportMeshData class b3ImportMeshUtility { public: -static int loadAndRegisterMeshFromFile(const std::string& fileName, class CommonRenderInterface* renderer); static bool loadAndRegisterMeshFromFileInternal(const std::string& fileName, b3ImportMeshData& meshData); diff --git a/examples/Importers/ImportObjDemo/ImportObjExample.cpp b/examples/Importers/ImportObjDemo/ImportObjExample.cpp index a8995c148..2fc11afa3 100644 --- a/examples/Importers/ImportObjDemo/ImportObjExample.cpp +++ b/examples/Importers/ImportObjDemo/ImportObjExample.cpp @@ -56,7 +56,31 @@ ImportObjSetup::~ImportObjSetup() - +int loadAndRegisterMeshFromFile2(const std::string& fileName, CommonRenderInterface* renderer) +{ + int shapeId = -1; + + b3ImportMeshData meshData; + if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(fileName, meshData)) + { + int textureIndex = -1; + + if (meshData.m_textureImage) + { + textureIndex = renderer->registerTexture(meshData.m_textureImage,meshData.m_textureWidth,meshData.m_textureHeight); + } + + shapeId = renderer->registerShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0], + meshData.m_gfxShape->m_numvertices, + &meshData.m_gfxShape->m_indices->at(0), + meshData.m_gfxShape->m_numIndices, + B3_GL_TRIANGLES, + textureIndex); + delete meshData.m_gfxShape; + delete meshData.m_textureImage; + } + return shapeId; +} @@ -77,7 +101,7 @@ void ImportObjSetup::initPhysics() btVector3 scaling(1,1,1); btVector3 color(1,1,1); - int shapeId = b3ImportMeshUtility::loadAndRegisterMeshFromFile(m_fileName, m_guiHelper->getRenderInterface()); + int shapeId = loadAndRegisterMeshFromFile2(m_fileName, m_guiHelper->getRenderInterface()); if (shapeId>=0) { //int id = diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 4838079a0..9b6eb8ae1 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -13,7 +13,7 @@ subject to the following restrictions: #include "BulletUrdfImporter.h" - +#include "../../CommonInterfaces/CommonRenderInterface.h" #include "URDFImporterInterface.h" #include "btBulletCollisionCommon.h" @@ -26,12 +26,20 @@ subject to the following restrictions: #include #include "../../Utils/b3ResourcePath.h" +#include "../ImportMeshUtility/b3ImportMeshUtility.h" #include #include #include "UrdfParser.h" +struct MyTexture +{ + int m_width; + int m_height; + unsigned char* textureData; +}; + struct BulletURDFInternalData { UrdfParser m_urdfParser; @@ -589,7 +597,7 @@ btCollisionShape* convertURDFToCollisionShape(const UrdfCollision* collision, co } -static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut) +static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut, btAlignedObjectArray& texturesOut) { @@ -693,7 +701,23 @@ static void convertURDFToVisualShapeInternal(const UrdfVisual* visual, const cha { case FILE_OBJ: { - glmesh = LoadMeshFromObj(fullPath,visualPathPrefix); +// glmesh = LoadMeshFromObj(fullPath,visualPathPrefix); + + b3ImportMeshData meshData; + if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(fullPath, meshData)) + { + + if (meshData.m_textureImage) + { + MyTexture texData; + texData.m_width = meshData.m_textureWidth; + texData.m_height = meshData.m_textureHeight; + texData.textureData = meshData.m_textureImage; + texturesOut.push_back(texData); + } + glmesh = meshData.m_gfxShape; + } + break; } @@ -914,7 +938,8 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP btAlignedObjectArray vertices; btAlignedObjectArray indices; btTransform startTrans; startTrans.setIdentity(); - + btAlignedObjectArray textures; + const UrdfModel& model = m_data->m_urdfParser.getModel(); UrdfLink* const* linkPtr = model.m_links.getAtIndex(linkIndex); if (linkPtr) @@ -934,14 +959,34 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP //printf("UrdfMaterial %s, rgba = %f,%f,%f,%f\n",mat->m_name.c_str(),mat->m_rgbaColor[0],mat->m_rgbaColor[1],mat->m_rgbaColor[2],mat->m_rgbaColor[3]); m_data->m_linkColors.insert(linkIndex,mat->m_rgbaColor); } - convertURDFToVisualShapeInternal(&vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices); + convertURDFToVisualShapeInternal(&vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices,textures); } } if (vertices.size() && indices.size()) { - graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size()); +// graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size()); + //graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size()); + + CommonRenderInterface* renderer = m_data->m_guiHelper->getRenderInterface(); + + if (renderer) + { + int textureIndex = -1; + if (textures.size()) + { + textureIndex = renderer->registerTexture(textures[0].textureData,textures[0].m_width,textures[0].m_height); + } + graphicsIndex = renderer->registerShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(),B3_GL_TRIANGLES,textureIndex); + + } + } + + //delete textures + for (int i=0;i #include #include "../Importers/ImportURDFDemo/UrdfParser.h" @@ -41,6 +41,13 @@ enum MyFileType MY_FILE_OBJ=3, }; +struct MyTexture2 +{ + unsigned char* textureData; + int m_width; + int m_height; +}; + struct TinyRendererObjectArray { btAlignedObjectArray< TinyRenderObjectData*> m_renderObjects; @@ -95,7 +102,7 @@ TinyRendererVisualShapeConverter::~TinyRendererVisualShapeConverter() -void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut) +void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut, btAlignedObjectArray& texturesOut) { @@ -201,7 +208,23 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref { case MY_FILE_OBJ: { - glmesh = LoadMeshFromObj(fullPath,visualPathPrefix); + //glmesh = LoadMeshFromObj(fullPath,visualPathPrefix); + b3ImportMeshData meshData; + if (b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(fullPath, meshData)) + { + + if (meshData.m_textureImage) + { + MyTexture2 texData; + texData.m_width = meshData.m_textureWidth; + texData.m_height = meshData.m_textureHeight; + texData.textureData = meshData.m_textureImage; + texturesOut.push_back(texData); + } + glmesh = meshData.m_gfxShape; + } + + break; } @@ -420,11 +443,7 @@ void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPref void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const char* pathPrefix, const btTransform& localInertiaFrame, const UrdfModel& model, class btCollisionObject* colObj) { - btAlignedObjectArray vertices; - btAlignedObjectArray indices; - btTransform startTrans; startTrans.setIdentity(); - int graphicsIndex = -1; - + UrdfLink* const* linkPtr = model.m_links.getAtIndex(linkIndex); if (linkPtr) { @@ -433,6 +452,12 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const for (int v = 0; v < link->m_visualArray.size();v++) { + btAlignedObjectArray textures; + btAlignedObjectArray vertices; + btAlignedObjectArray indices; + btTransform startTrans; startTrans.setIdentity(); + int graphicsIndex = -1; + const UrdfVisual& vis = link->m_visualArray[v]; btTransform childTrans = vis.m_linkLocalFrame; btHashString matName(vis.m_materialName.c_str()); @@ -458,14 +483,29 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const btAssert(visualsPtr); TinyRendererObjectArray* visuals = *visualsPtr; - convertURDFToVisualShape(&vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices); + convertURDFToVisualShape(&vis, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices,textures); if (vertices.size() && indices.size()) { TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer); - tinyObj->registerMeshShape(&vertices[0].xyzw[0],vertices.size(),&indices[0],indices.size(),rgbaColor); + unsigned char* textureImage=0; + int textureWidth=0; + int textureHeight=0; + if (textures.size()) + { + textureImage = textures[0].textureData; + textureWidth = textures[0].m_width; + textureHeight = textures[0].m_height; + } + + tinyObj->registerMeshShape(&vertices[0].xyzw[0],vertices.size(),&indices[0],indices.size(),rgbaColor, + textureImage,textureWidth,textureHeight); visuals->m_renderObjects.push_back(tinyObj); } + for (int i=0;i Date: Sun, 19 Jun 2016 17:35:25 -0700 Subject: [PATCH 034/115] fix cmake and premake build systems, after adding texture support in SDF, in a nutshell, add the following two files: examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp examples/ThirdPartyLibs/stb_image/stb_image.cpp --- examples/ExtendedTutorials/premake4.lua | 12 ++++++++---- .../ImportMeshUtility/b3ImportMeshUtility.cpp | 4 ++-- examples/InverseDynamics/premake4.lua | 12 ++++++++---- examples/SharedMemory/premake4.lua | 3 ++- examples/pybullet/CMakeLists.txt | 4 +++- test/InverseDynamics/premake4.lua | 2 ++ test/SharedMemory/CMakeLists.txt | 3 ++- test/SharedMemory/premake4.lua | 12 +++++++++--- 8 files changed, 36 insertions(+), 16 deletions(-) diff --git a/examples/ExtendedTutorials/premake4.lua b/examples/ExtendedTutorials/premake4.lua index ea1fc507e..92ac12d45 100644 --- a/examples/ExtendedTutorials/premake4.lua +++ b/examples/ExtendedTutorials/premake4.lua @@ -38,7 +38,8 @@ files { "../Importers/ImportURDFDemo/URDF2Bullet.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", "../Importers/ImportURDFDemo/urdfStringSplit.cpp", - + "../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../ThirdPartyLibs/stb_image/stb_image.cpp", } @@ -89,7 +90,8 @@ files { "../Importers/ImportURDFDemo/URDF2Bullet.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", "../Importers/ImportURDFDemo/urdfStringSplit.cpp", - + "../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../ThirdPartyLibs/stb_image/stb_image.cpp", } if os.is("Linux") then initX11() end @@ -153,7 +155,8 @@ files { "../Importers/ImportURDFDemo/URDF2Bullet.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", "../Importers/ImportURDFDemo/urdfStringSplit.cpp", - + "../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../ThirdPartyLibs/stb_image/stb_image.cpp", } if os.is("Linux") then initX11() end @@ -213,6 +216,7 @@ files { "../Importers/ImportURDFDemo/URDF2Bullet.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", "../Importers/ImportURDFDemo/urdfStringSplit.cpp", - + "../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../ThirdPartyLibs/stb_image/stb_image.cpp", } diff --git a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp index 85aeb7e21..67b64fd26 100644 --- a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp +++ b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp @@ -1,12 +1,12 @@ #include "b3ImportMeshUtility.h" #include -#include"Wavefront/tiny_obj_loader.h" +#include"../../ThirdPartyLibs/Wavefront/tiny_obj_loader.h" #include "LinearMath/btVector3.h" #include "../ImportObjDemo/Wavefront2GLInstanceGraphicsShape.h" #include "../../Utils/b3ResourcePath.h" #include "Bullet3Common/b3FileUtils.h" -#include "stb_image/stb_image.h" +#include "../../ThirdPartyLibs/stb_image/stb_image.h" bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string& fileName, b3ImportMeshData& meshData) diff --git a/examples/InverseDynamics/premake4.lua b/examples/InverseDynamics/premake4.lua index 3871526ce..53c4fa2ce 100644 --- a/examples/InverseDynamics/premake4.lua +++ b/examples/InverseDynamics/premake4.lua @@ -38,7 +38,8 @@ files { "../Importers/ImportURDFDemo/URDF2Bullet.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", "../Importers/ImportURDFDemo/urdfStringSplit.cpp", - + "../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../ThirdPartyLibs/stb_image/stb_image.cpp", } @@ -89,7 +90,8 @@ files { "../Importers/ImportURDFDemo/URDF2Bullet.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", "../Importers/ImportURDFDemo/urdfStringSplit.cpp", - + "../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../ThirdPartyLibs/stb_image/stb_image.cpp", } if os.is("Linux") then initX11() end @@ -153,7 +155,8 @@ files { "../Importers/ImportURDFDemo/URDF2Bullet.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", "../Importers/ImportURDFDemo/urdfStringSplit.cpp", - + "../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../ThirdPartyLibs/stb_image/stb_image.cpp", } if os.is("Linux") then initX11() end @@ -211,6 +214,7 @@ files { "../Importers/ImportURDFDemo/URDF2Bullet.cpp", "../Importers/ImportURDFDemo/UrdfParser.cpp", "../Importers/ImportURDFDemo/urdfStringSplit.cpp", - + "../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../ThirdPartyLibs/stb_image/stb_image.cpp", } diff --git a/examples/SharedMemory/premake4.lua b/examples/SharedMemory/premake4.lua index 0616a8865..e923b412f 100644 --- a/examples/SharedMemory/premake4.lua +++ b/examples/SharedMemory/premake4.lua @@ -78,6 +78,7 @@ files { "../ThirdPartyLibs/tinyxml/tinyxml.cpp", "../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp", "../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp", - +"../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../ThirdPartyLibs/stb_image/stb_image.cpp", } diff --git a/examples/pybullet/CMakeLists.txt b/examples/pybullet/CMakeLists.txt index 672187557..5540d10de 100644 --- a/examples/pybullet/CMakeLists.txt +++ b/examples/pybullet/CMakeLists.txt @@ -49,6 +49,7 @@ SET(pybullet_SRCS ../../examples/ThirdPartyLibs/tinyxml/tinyxmlparser.cpp ../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp ../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h + ../../examples/ThirdPartyLibs/stb_image/stb_image.cpp ../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp ../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp ../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp @@ -57,7 +58,8 @@ SET(pybullet_SRCS ../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp ../../examples/Importers/ImportURDFDemo/UrdfParser.cpp ../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp - ../../examples/MultiThreading/b3PosixThreadSupport.cpp + ../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp + ../../examples/MultiThreading/b3PosixThreadSupport.cpp ../../examples/MultiThreading/b3Win32ThreadSupport.cpp ../../examples/MultiThreading/b3ThreadSupportInterface.cpp diff --git a/test/InverseDynamics/premake4.lua b/test/InverseDynamics/premake4.lua index 498cf94d8..9d6770347 100644 --- a/test/InverseDynamics/premake4.lua +++ b/test/InverseDynamics/premake4.lua @@ -78,6 +78,8 @@ "../../examples/Importers/ImportURDFDemo/UrdfParser.h", "../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp", "../../examples/Importers/ImportURDFDemo/URDF2Bullet.h", + "../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../../examples/ThirdPartyLibs/stb_image/stb_image.cpp", "../../examples/Utils/b3Clock.cpp", "../../Extras/Serialize/BulletWorldImporter/*", "../../Extras/Serialize/BulletFileLoader/*", diff --git a/test/SharedMemory/CMakeLists.txt b/test/SharedMemory/CMakeLists.txt index 868841237..d39f36df4 100644 --- a/test/SharedMemory/CMakeLists.txt +++ b/test/SharedMemory/CMakeLists.txt @@ -71,7 +71,8 @@ ENDIF() ../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp ../../examples/Importers/ImportURDFDemo/UrdfParser.cpp ../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp - + ../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp + ../../examples/ThirdPartyLibs/stb_image/stb_image.cpp ) diff --git a/test/SharedMemory/premake4.lua b/test/SharedMemory/premake4.lua index ef70b0139..952b4c98a 100644 --- a/test/SharedMemory/premake4.lua +++ b/test/SharedMemory/premake4.lua @@ -91,7 +91,9 @@ project ("Test_PhysicsServerLoopBack") "../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp", "../../examples/Importers/ImportURDFDemo/UrdfParser.cpp", "../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp", - } + "../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../../examples/ThirdPartyLibs/stb_image/stb_image.cpp", + } project ("Test_PhysicsServerDirect") @@ -157,6 +159,8 @@ project ("Test_PhysicsServerLoopBack") "../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp", "../../examples/Importers/ImportURDFDemo/UrdfParser.cpp", "../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp", + "../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../../examples/ThirdPartyLibs/stb_image/stb_image.cpp", } @@ -255,8 +259,10 @@ project ("Test_PhysicsServerInProcessExampleBrowser") "../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp", "../../examples/MultiThreading/b3PosixThreadSupport.cpp", "../../examples/MultiThreading/b3Win32ThreadSupport.cpp", - "../../examples/MultiThreading/b3ThreadSupportInterface.cpp", - } + "../../examples/MultiThreading/b3ThreadSupportInterface.cpp", + "../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp", + "../../examples/ThirdPartyLibs/stb_image/stb_image.cpp", + } if os.is("Linux") then initX11() end From 251fab0d75cd403ce5907b0f6b50006b8a2facc5 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 20 Jun 2016 12:40:08 -0700 Subject: [PATCH 035/115] expand b3ResourcePath automagic resource localization capability. --- examples/Utils/b3ResourcePath.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/examples/Utils/b3ResourcePath.cpp b/examples/Utils/b3ResourcePath.cpp index d27b61e99..fdd546d5e 100644 --- a/examples/Utils/b3ResourcePath.cpp +++ b/examples/Utils/b3ResourcePath.cpp @@ -77,6 +77,12 @@ int b3ResourcePath::findResourcePath(const char* resourceName, char* resourcePat { return strlen(resourcePath); } + sprintf(resourcePath,"%s.runfiles/google3/third_party/bullet/data/%s",exePath,resourceName); + //printf("try resource at %s\n", resourcePath); + if (b3FileUtils::findFile(resourcePath, resourcePath, resourcePathMaxNumBytes)) + { + return strlen(resourcePath); + } } } From c7c01e6b325bf2c9a20c96da3925b861309af737 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 20 Jun 2016 14:09:37 -0700 Subject: [PATCH 036/115] add one more test, related to b3CreatePoseCommandInit --- test/SharedMemory/test.c | 22 +++++++++++++++++++++- 1 file changed, 21 insertions(+), 1 deletion(-) diff --git a/test/SharedMemory/test.c b/test/SharedMemory/test.c index 9d80eed63..a74cb34a6 100644 --- a/test/SharedMemory/test.c +++ b/test/SharedMemory/test.c @@ -68,6 +68,9 @@ void testSharedMemory(b3PhysicsClientHandle sm) int bodyUniqueId = bodyIndicesOut[0]; numJoints = b3GetNumJoints(sm,bodyUniqueId); + ASSERT_EQ(numJoints,7); + +#if 0 b3Printf("numJoints: %d\n", numJoints); for (i=0;i Date: Mon, 20 Jun 2016 14:58:56 -0700 Subject: [PATCH 037/115] fix C99 issue, use malloc, not variable sized array. . --- examples/pybullet/pybullet.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index fbd070ff9..eb1e88f6d 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -707,7 +707,7 @@ pybullet_getJointPositions(PyObject* self, PyObject* args) int i; int numJoints = b3GetNumJoints(sm,bodyIndex); - double jointPositions[numJoints]; + double* jointPositions = malloc(numJoints*sizeof(double)); pyListJointPos = PyTuple_New(numJoints); @@ -718,7 +718,7 @@ pybullet_getJointPositions(PyObject* self, PyObject* args) item = PyFloat_FromDouble(jointPositions[i]); PyTuple_SetItem(pyListJointPos, i, item); } - + free(jointPositions); return pyListJointPos; } From 01cad7c2a5e5a3a14e78bede0e8108b50cd6c99b Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Mon, 20 Jun 2016 15:00:35 -0700 Subject: [PATCH 038/115] fix return type in pybullet . --- examples/pybullet/pybullet.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index eb1e88f6d..3731f4c4d 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -276,7 +276,7 @@ pybullet_resetSimulation(PyObject* self, PyObject* args) return Py_None; } -static int pybullet_setJointControl(PyObject* self, PyObject* args) +static PyObject* pybullet_setJointControl(PyObject* self, PyObject* args) { //todo(erwincoumans): set max forces, kp, kd From 51da3863452f6bfe967ab9a24afe3104f2e8fffe Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Mon, 20 Jun 2016 15:05:14 -0700 Subject: [PATCH 039/115] also compile pybullet in one of the tests --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index bb6dcde2e..8d309af7d 100644 --- a/.travis.yml +++ b/.travis.yml @@ -8,7 +8,7 @@ compiler: script: - echo "CXX="$CXX - echo "CC="$CC - - cmake . -G "Unix Makefiles" #-DCMAKE_CXX_FLAGS=-Werror + - cmake . -G -DBUILD_PYBULLET=ON "Unix Makefiles" #-DCMAKE_CXX_FLAGS=-Werror - make -j8 - ctest -j8 --output-on-failure # Build again with double precision From 07ee9673efe9886d87c6b39131af355d39795de1 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Tue, 21 Jun 2016 08:43:04 -0700 Subject: [PATCH 040/115] try to get python dependency in travis (pybullet) --- .travis.yml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.travis.yml b/.travis.yml index 8d309af7d..df480e393 100644 --- a/.travis.yml +++ b/.travis.yml @@ -5,6 +5,9 @@ os: compiler: - gcc - clang +python: + - "2.7" + - "3.4" script: - echo "CXX="$CXX - echo "CC="$CC From 08b88c445a2c03dcd1db5e7f547488cfafa93d07 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Tue, 21 Jun 2016 08:51:43 -0700 Subject: [PATCH 041/115] more travis/python testing fun --- .travis.yml | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/.travis.yml b/.travis.yml index df480e393..25053a90d 100644 --- a/.travis.yml +++ b/.travis.yml @@ -5,13 +5,14 @@ os: compiler: - gcc - clang -python: - - "2.7" - - "3.4" +addons: + apt: + packages: + - python3 script: - echo "CXX="$CXX - echo "CC="$CC - - cmake . -G -DBUILD_PYBULLET=ON "Unix Makefiles" #-DCMAKE_CXX_FLAGS=-Werror + - cmake . -DBUILD_PYBULLET=ON -G"Unix Makefiles" #-DCMAKE_CXX_FLAGS=-Werror - make -j8 - ctest -j8 --output-on-failure # Build again with double precision From 0b249361c243e27430838ee188dd08d9ff0e4cf4 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Tue, 21 Jun 2016 09:01:27 -0700 Subject: [PATCH 042/115] fix a c99 issue in pybullet --- examples/pybullet/pybullet.c | 21 ++------------------- 1 file changed, 2 insertions(+), 19 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 3731f4c4d..9235f3e5a 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -302,6 +302,7 @@ static PyObject* pybullet_setJointControl(PyObject* self, PyObject* args) len = PySequence_Size(targetValues); numJoints = b3GetNumJoints(sm,bodyIndex); b3SharedMemoryCommandHandle commandHandle; + int qIndex; if (len!=numJoints) { @@ -321,7 +322,7 @@ static PyObject* pybullet_setJointControl(PyObject* self, PyObject* args) commandHandle = b3JointControlCommandInit(sm, bodyIndex,controlMode); - for (int qIndex=0;qIndex Date: Wed, 22 Jun 2016 09:59:25 -0700 Subject: [PATCH 043/115] support single-scalar scale values in URDF, even though "officially" it should be a vector3. This will load quadcopter.urdf in Drake: https://github.com/RobotLocomotion/drake/blob/master/drake/examples/Quadrotor/quadrotor.urdf --- .../Importers/ImportURDFDemo/UrdfParser.cpp | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 0e720a7c2..a6ec0a5c4 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -393,13 +393,22 @@ bool UrdfParser::parseGeometry(UrdfGeometry& geom, TiXmlElement* g, ErrorLogger* } geom.m_meshFileName = shape->Attribute("filename"); - - if (shape->Attribute("scale")) + geom.m_meshScale.setValue(1,1,1); + + if (shape->Attribute("scale")) { - parseVector3(geom.m_meshScale,shape->Attribute("scale"),logger); + if (!parseVector3(geom.m_meshScale,shape->Attribute("scale"),logger)) + { + logger->reportWarning("scale should be a vector3, not single scalar. Workaround activated.\n"); + std::string scalar_str = shape->Attribute("scale"); + double scaleFactor = urdfLexicalCast(scalar_str.c_str()); + if (scaleFactor) + { + geom.m_meshScale.setValue(scaleFactor,scaleFactor,scaleFactor); + } + } } else { - geom.m_meshScale.setValue(1,1,1); } } } From f5ffb11bc55bc041312e88a3c46d5350906080be Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 23 Jun 2016 05:10:00 +0000 Subject: [PATCH 044/115] fix bus error on Raspberry Pi, unaligned float access when loading STL files fix pybullet Python 3 issue (PyString_FromString -> PyBytes_FromString and PyInt_FromLong -> PyLong_FromLong) --- examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h | 11 ++++++----- examples/pybullet/pybullet.c | 8 ++++++-- 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h b/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h index f670dfeec..65bdd330b 100644 --- a/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h +++ b/examples/Importers/ImportSTLDemo/LoadMeshFromSTL.h @@ -66,17 +66,18 @@ static GLInstanceGraphicsShape* LoadMeshFromSTL(const char* relativeFileName) for (int i=0;ivertex0[v]; - v1.xyzw[v] = tri->vertex1[v]; - v2.xyzw[v] = tri->vertex2[v]; - v0.normal[v] = v1.normal[v] = v2.normal[v] = tri->normal[v]; + v0.xyzw[v] = tmp.vertex0[v]; + v1.xyzw[v] = tmp.vertex1[v]; + v2.xyzw[v] = tmp.vertex2[v]; + v0.normal[v] = v1.normal[v] = v2.normal[v] = tmp.normal[v]; } v0.xyzw[3] = v1.xyzw[3] = v2.xyzw[3] = 0.f; diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 9235f3e5a..2a3545bb3 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -9,6 +9,12 @@ #include #endif + +#if PY_MAJOR_VERSION >= 3 +#define PyInt_FromLong PyLong_FromLong +#define PyString_FromString PyBytes_FromString +#endif + enum eCONNECT_METHOD { eCONNECT_GUI=1, @@ -769,7 +775,6 @@ pybullet_getJointInfo(PyObject* self, PyObject* args) // info.m_flags, // info.m_jointDamping, // info.m_jointFriction); - PyTuple_SetItem(pyListJointInfo, 0, PyInt_FromLong(info.m_jointIndex)); PyTuple_SetItem(pyListJointInfo, 1, @@ -786,7 +791,6 @@ pybullet_getJointInfo(PyObject* self, PyObject* args) PyFloat_FromDouble(info.m_jointDamping)); PyTuple_SetItem(pyListJointInfo, 7, PyFloat_FromDouble(info.m_jointFriction)); - return pyListJointInfo; } } From 8b96e2de3cb53f02c492853d44709850d92123fa Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Wed, 22 Jun 2016 23:21:47 -0700 Subject: [PATCH 045/115] a few pybullet tweaks to set desired joint motor targets (pos/vel/torque) --- examples/SharedMemory/PhysicsClientC_API.cpp | 1 + .../PhysicsServerCommandProcessor.cpp | 6 +- examples/pybullet/pybullet.c | 90 +++++++++++++------ 3 files changed, 67 insertions(+), 30 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index f5a339fc1..a952111c2 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -218,6 +218,7 @@ int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandl struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value; + command->m_updateFlags |= SIM_DESIRED_STATE_HAS_MAX_FORCE; return 0; } diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 33d7d3153..b2c3c5c05 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1389,6 +1389,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm mb->clearForcesAndTorques(); int torqueIndex = 0; + #if 0 + //it is inconsistent to allow application of base force/torque, there is no 'joint' motor. Use a separate API for this. + btVector3 f(0,0,0); btVector3 t(0,0,0); @@ -1404,7 +1407,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm torqueIndex+=6; mb->addBaseForce(f); mb->addBaseTorque(t); - for (int link=0;linkgetNumLinks();link++) + #endif + for (int link=0;linkgetNumLinks();link++) { for (int dof=0;dofgetLink(link).m_dofCount;dof++) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 2a3545bb3..d06eff27c 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -222,7 +222,7 @@ pybullet_loadSDF(PyObject* self, PyObject* args) PyObject* pylist=0; b3SharedMemoryStatusHandle statusHandle; int statusType; - b3SharedMemoryCommandHandle command; + b3SharedMemoryCommandHandle commandHandle; if (0==sm) { @@ -236,8 +236,8 @@ pybullet_loadSDF(PyObject* self, PyObject* args) return NULL; } - command = b3LoadSdfCommandInit(sm, sdfFileName); - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + commandHandle = b3LoadSdfCommandInit(sm, sdfFileName); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); if (statusType!=CMD_SDF_LOADING_COMPLETED) { @@ -308,10 +308,11 @@ static PyObject* pybullet_setJointControl(PyObject* self, PyObject* args) len = PySequence_Size(targetValues); numJoints = b3GetNumJoints(sm,bodyIndex); b3SharedMemoryCommandHandle commandHandle; - int qIndex; + b3SharedMemoryStatusHandle statusHandle; + int qIndex; if (len!=numJoints) - { + { PyErr_SetString(SpamError, "Number of control target values doesn't match the number of joints."); Py_DECREF(seq); return NULL; @@ -336,20 +337,24 @@ static PyObject* pybullet_setJointControl(PyObject* self, PyObject* args) { case CONTROL_MODE_VELOCITY: { - b3JointControlSetDesiredVelocity(commandHandle, qIndex, value); - break; + b3JointControlSetDesiredVelocity(commandHandle, 6+qIndex, value); + b3JointControlSetKd(commandHandle,6+qIndex,1); + b3JointControlSetMaximumForce(commandHandle,6+qIndex,10000); + break; } case CONTROL_MODE_TORQUE: { - b3JointControlSetDesiredForceTorque(commandHandle, qIndex, value); + b3JointControlSetDesiredForceTorque(commandHandle, 6+qIndex, value); break; } case CONTROL_MODE_POSITION_VELOCITY_PD: { - b3JointControlSetDesiredPosition( commandHandle, qIndex, value); - break; + b3JointControlSetDesiredPosition( commandHandle, 7+qIndex, value); + b3JointControlSetKp(commandHandle,6+qIndex,1); + b3JointControlSetMaximumForce(commandHandle,6+qIndex,10000); + break; } default: { @@ -357,6 +362,9 @@ static PyObject* pybullet_setJointControl(PyObject* self, PyObject* args) } }; } + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + Py_DECREF(seq); Py_INCREF(Py_None); return Py_None; @@ -554,35 +562,59 @@ pybullet_getNumJoints(PyObject* self, PyObject* args) static PyObject* pybullet_initializeJointPositions(PyObject* self, PyObject* args) { + int size; if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - // TODO(hellojas): initialize all joint positions given a pylist of values - // - // - /* - ///b3CreatePoseCommandInit will initialize (teleport) the pose of a body/robot. You can individually set the base position, - ///base orientation and joint angles. This will set all velocities of base and joints to zero. - ///This is not a robot control command using actuators/joint motors, but manual repositioning the robot. - b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physClient, int bodyIndex); - int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ); - int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW); - int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions); - int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition); - - */ - // - // - - Py_INCREF(Py_None); - return Py_None; + size= PySequence_Size(args); + + if (size==2) + { + int bodyIndex; + PyObject* targetValues; + if (PyArg_ParseTuple(args, "iO", &bodyIndex, &targetValues)) + { + PyObject* seq; + int numJoints, len; + seq = PySequence_Fast(targetValues, "expected a sequence"); + len = PySequence_Size(targetValues); + numJoints = b3GetNumJoints(sm,bodyIndex); + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + int qIndex; + + if (len!=numJoints) + { + PyErr_SetString(SpamError, "Number of joint position values doesn't match the number of joints."); + Py_DECREF(seq); + return NULL; + } + + commandHandle = b3CreatePoseCommandInit(sm, bodyIndex); + + for (qIndex=0;qIndex Date: Thu, 23 Jun 2016 08:40:36 -0700 Subject: [PATCH 046/115] re-introduce old method in pybullet for temporary back-wards compatibility b3JointControlCommandInit requires 3 args, but it was only 2, use b3JointControlCommandInit2 for now. --- examples/SharedMemory/PhysicsClientC_API.cpp | 7 ++++++- examples/SharedMemory/PhysicsClientC_API.h | 9 +++++++-- examples/SharedMemory/PhysicsClientExample.cpp | 2 +- examples/pybullet/pybullet.c | 2 +- 4 files changed, 15 insertions(+), 5 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index a952111c2..57121f0c8 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -151,7 +151,12 @@ b3SharedMemoryCommandHandle b3InitResetSimulationCommand(b3PhysicsClientHand } -b3SharedMemoryCommandHandle b3JointControlCommandInit( b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode) +b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode) +{ + return b3JointControlCommandInit2(physClient,0,controlMode); +} + +b3SharedMemoryCommandHandle b3JointControlCommandInit2( b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode) { PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index e12cf75eb..0f036415c 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -95,10 +95,15 @@ int b3LoadUrdfCommandSetUseFixedBase(b3SharedMemoryCommandHandle commandHandle, b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClient, const char* sdfFileName); +///The b3JointControlCommandInit method is obsolete, use b3JointControlCommandInit2 instead +b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode); + + ///Set joint control variables such as desired position/angle, desired velocity, ///applied joint forces, dependent on the control mode (CONTROL_MODE_VELOCITY or CONTROL_MODE_TORQUE) -b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode); -///Only use when controlMode is CONTROL_MODE_POSITION_VELOCITY_PD +b3SharedMemoryCommandHandle b3JointControlCommandInit2(b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode); + + ///Only use when controlMode is CONTROL_MODE_POSITION_VELOCITY_PD int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value); int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index e0338153a..a4199071a 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -377,7 +377,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) if (m_selectedBody>=0) { // b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_physicsClientHandle, m_selectedBody, CONTROL_MODE_VELOCITY); - b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_physicsClientHandle, m_selectedBody, CONTROL_MODE_POSITION_VELOCITY_PD); + b3SharedMemoryCommandHandle command = b3JointControlCommandInit2( m_physicsClientHandle, m_selectedBody, CONTROL_MODE_POSITION_VELOCITY_PD); // b3Printf("prepare control command for body %d", m_selectedBody); prepareControlCommand(command); diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index d06eff27c..0d2303fc5 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -327,7 +327,7 @@ static PyObject* pybullet_setJointControl(PyObject* self, PyObject* args) return NULL; } - commandHandle = b3JointControlCommandInit(sm, bodyIndex,controlMode); + commandHandle = b3JointControlCommandInit2(sm, bodyIndex,controlMode); for (qIndex=0;qIndex Date: Thu, 23 Jun 2016 14:00:44 -0700 Subject: [PATCH 047/115] fix loading urdf at default position (0,0,0) and adding b3 cmd to change orientation if args provided --- examples/pybullet/pybullet.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 9235f3e5a..3cc230128 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -135,7 +135,7 @@ pybullet_loadURDF(PyObject* self, PyObject* args) const char* urdfFileName=""; float startPosX =0; float startPosY =0; - float startPosZ = 1; + float startPosZ = 0; float startOrnX = 0; float startOrnY = 0; float startOrnZ = 0; @@ -165,6 +165,7 @@ pybullet_loadURDF(PyObject* self, PyObject* args) return NULL; } { + printf("(%f, %f, %f) (%f, %f, %f, %f)\n", startPosX,startPosY,startPosZ,startOrnX, startOrnY,startOrnZ, startOrnW); b3SharedMemoryStatusHandle statusHandle; int statusType; @@ -172,6 +173,7 @@ pybullet_loadURDF(PyObject* self, PyObject* args) //setting the initial position, orientation and other arguments are optional b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ); + b3LoadUrdfCommandSetStartOrientation(command, startOrnX, startOrnY,startOrnZ, startOrnW ); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); if (statusType!=CMD_URDF_LOADING_COMPLETED) From a21889e225d8020577fc5c36dda89e9c7929b74e Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Thu, 23 Jun 2016 14:01:57 -0700 Subject: [PATCH 048/115] remove print debugger --- examples/pybullet/pybullet.so | 1 + 1 file changed, 1 insertion(+) create mode 120000 examples/pybullet/pybullet.so diff --git a/examples/pybullet/pybullet.so b/examples/pybullet/pybullet.so new file mode 120000 index 000000000..59de5c3df --- /dev/null +++ b/examples/pybullet/pybullet.so @@ -0,0 +1 @@ +libpybullet.dylib \ No newline at end of file From 976e228be0c3b035386168fe415188d53468ad3c Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Thu, 23 Jun 2016 14:05:36 -0700 Subject: [PATCH 049/115] remove print debugger --- examples/pybullet/pybullet.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 3cc230128..a8ad37b30 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -165,7 +165,7 @@ pybullet_loadURDF(PyObject* self, PyObject* args) return NULL; } { - printf("(%f, %f, %f) (%f, %f, %f, %f)\n", startPosX,startPosY,startPosZ,startOrnX, startOrnY,startOrnZ, startOrnW); + // printf("(%f, %f, %f) (%f, %f, %f, %f)\n", startPosX,startPosY,startPosZ,startOrnX, startOrnY,startOrnZ, startOrnW); b3SharedMemoryStatusHandle statusHandle; int statusType; From d2a27972015ec8915810d876afc8c072a697d350 Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Thu, 23 Jun 2016 14:06:14 -0700 Subject: [PATCH 050/115] accidently added pybullet.so --- examples/pybullet/pybullet.so | 1 - 1 file changed, 1 deletion(-) delete mode 120000 examples/pybullet/pybullet.so diff --git a/examples/pybullet/pybullet.so b/examples/pybullet/pybullet.so deleted file mode 120000 index 59de5c3df..000000000 --- a/examples/pybullet/pybullet.so +++ /dev/null @@ -1 +0,0 @@ -libpybullet.dylib \ No newline at end of file From 6d1948e79e5caf74cfa2e3344ee308bd81fe2c33 Mon Sep 17 00:00:00 2001 From: "Erwin Coumans (Google)" Date: Fri, 24 Jun 2016 07:31:17 -0700 Subject: [PATCH 051/115] tweaks in pybullet and shared memory C-API: allow to reset the state of a single joint allow to set the target/mode for a single joint motor at a time rename pybullet API: initializeJointPositions -> resetJointState --- examples/BasicDemo/BasicExample.cpp | 2 +- examples/SharedMemory/PhysicsClientC_API.cpp | 33 + examples/SharedMemory/PhysicsClientC_API.h | 7 +- .../PhysicsServerCommandProcessor.cpp | 579 +++++++++--------- examples/SharedMemory/SharedMemoryCommands.h | 4 + examples/pybullet/pybullet.c | 247 ++++---- test/SharedMemory/test.c | 4 +- 7 files changed, 463 insertions(+), 413 deletions(-) diff --git a/examples/BasicDemo/BasicExample.cpp b/examples/BasicDemo/BasicExample.cpp index f5bd9486c..b6365df36 100644 --- a/examples/BasicDemo/BasicExample.cpp +++ b/examples/BasicDemo/BasicExample.cpp @@ -42,7 +42,7 @@ struct BasicExample : public CommonRigidBodyBase float dist = 41; float pitch = 52; float yaw = 35; - float targetPos[3]={0,0.46,0}; + float targetPos[3]={0,0,0}; m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]); } }; diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 57121f0c8..203e0ebbe 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -167,6 +167,10 @@ b3SharedMemoryCommandHandle b3JointControlCommandInit2( b3PhysicsClientHandle ph command->m_sendDesiredStateCommandArgument.m_controlMode = controlMode; command->m_sendDesiredStateCommandArgument.m_bodyUniqueId = bodyUniqueId; command->m_updateFlags = 0; + for (int i=0;im_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[i] = 0; + } return (b3SharedMemoryCommandHandle) command; } @@ -176,6 +180,7 @@ int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, b3Assert(command); command->m_sendDesiredStateCommandArgument.m_desiredStateQ[qIndex] = value; command->m_updateFlags |= SIM_DESIRED_STATE_HAS_Q; + command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[qIndex] |= SIM_DESIRED_STATE_HAS_Q; return 0; } @@ -186,6 +191,8 @@ int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, b3Assert(command); command->m_sendDesiredStateCommandArgument.m_Kp[dofIndex] = value; command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KP; + command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_KP; + return 0; } @@ -195,6 +202,7 @@ int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, b3Assert(command); command->m_sendDesiredStateCommandArgument.m_Kd[dofIndex] = value; command->m_updateFlags |= SIM_DESIRED_STATE_HAS_KD; + command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_KD; return 0; } @@ -205,6 +213,8 @@ int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, b3Assert(command); command->m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex] = value; command->m_updateFlags |= SIM_DESIRED_STATE_HAS_QDOT; + command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_QDOT; + return 0; } @@ -215,6 +225,8 @@ int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int b3Assert(command); command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value; command->m_updateFlags |= SIM_DESIRED_STATE_HAS_MAX_FORCE; + command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_MAX_FORCE; + return 0; } @@ -224,6 +236,8 @@ int b3JointControlSetDesiredForceTorque(b3SharedMemoryCommandHandle commandHandl b3Assert(command); command->m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex] = value; command->m_updateFlags |= SIM_DESIRED_STATE_HAS_MAX_FORCE; + command->m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] |= SIM_DESIRED_STATE_HAS_MAX_FORCE; + return 0; } @@ -372,6 +386,7 @@ int b3CreateBoxCommandSetStartOrientation(b3SharedMemoryCommandHandle commandHan b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physClient, int bodyIndex) { + PhysicsClient* cl = (PhysicsClient* ) physClient; b3Assert(cl); b3Assert(cl->canSubmitCommand()); @@ -380,6 +395,11 @@ b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physCl command->m_type = CMD_INIT_POSE; command->m_updateFlags =0; command->m_initPoseArgs.m_bodyUniqueId = bodyIndex; + //a bit slow, initialing the full range to zero... + for (int i=0;im_initPoseArgs.m_hasInitialStateQ[i] = 0; + } return (b3SharedMemoryCommandHandle) command; } @@ -392,6 +412,11 @@ int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle command->m_initPoseArgs.m_initialStateQ[0] = startPosX; command->m_initPoseArgs.m_initialStateQ[1] = startPosY; command->m_initPoseArgs.m_initialStateQ[2] = startPosZ; + + command->m_initPoseArgs.m_hasInitialStateQ[0] = 1; + command->m_initPoseArgs.m_hasInitialStateQ[1] = 1; + command->m_initPoseArgs.m_hasInitialStateQ[2] = 1; + return 0; } @@ -405,6 +430,12 @@ int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHan command->m_initPoseArgs.m_initialStateQ[4] = startOrnY; command->m_initPoseArgs.m_initialStateQ[5] = startOrnZ; command->m_initPoseArgs.m_initialStateQ[6] = startOrnW; + + command->m_initPoseArgs.m_hasInitialStateQ[3] = 1; + command->m_initPoseArgs.m_hasInitialStateQ[4] = 1; + command->m_initPoseArgs.m_hasInitialStateQ[5] = 1; + command->m_initPoseArgs.m_hasInitialStateQ[6] = 1; + return 0; } @@ -417,6 +448,7 @@ int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHand for (int i=0;im_initPoseArgs.m_initialStateQ[i+7] = jointPositions[i]; + command->m_initPoseArgs.m_hasInitialStateQ[i+7] = 1; } return 0; } @@ -433,6 +465,7 @@ int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3Shar if ((info.m_flags & JOINT_HAS_MOTORIZED_POWER) && info.m_qIndex >=0) { command->m_initPoseArgs.m_initialStateQ[info.m_qIndex] = jointPosition; + command->m_initPoseArgs.m_hasInitialStateQ[info.m_qIndex] = 1; } return 0; } diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 0f036415c..aee561d8f 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -99,15 +99,16 @@ b3SharedMemoryCommandHandle b3LoadSdfCommandInit(b3PhysicsClientHandle physClien b3SharedMemoryCommandHandle b3JointControlCommandInit(b3PhysicsClientHandle physClient, int controlMode); -///Set joint control variables such as desired position/angle, desired velocity, +///Set joint motor control variables such as desired position/angle, desired velocity, ///applied joint forces, dependent on the control mode (CONTROL_MODE_VELOCITY or CONTROL_MODE_TORQUE) b3SharedMemoryCommandHandle b3JointControlCommandInit2(b3PhysicsClientHandle physClient, int bodyUniqueId, int controlMode); - ///Only use when controlMode is CONTROL_MODE_POSITION_VELOCITY_PD +///Only use when controlMode is CONTROL_MODE_POSITION_VELOCITY_PD int b3JointControlSetDesiredPosition(b3SharedMemoryCommandHandle commandHandle, int qIndex, double value); int b3JointControlSetKp(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); int b3JointControlSetKd(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); -//Only use when controlMode is CONTROL_MODE_VELOCITY + +///Only use when controlMode is CONTROL_MODE_VELOCITY int b3JointControlSetDesiredVelocity(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); /* find a better name for dof/q/u indices, point to b3JointInfo */ int b3JointControlSetMaximumForce(b3SharedMemoryCommandHandle commandHandle, int dofIndex, double value); ///Only use if when controlMode is CONTROL_MODE_TORQUE, diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index b2c3c5c05..3cdaac902 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -55,12 +55,12 @@ struct SharedMemoryDebugDrawer : public btIDebugDraw virtual void draw3dText(const btVector3& location,const char* textString) { } - + virtual void setDebugMode(int debugMode) { m_debugMode = debugMode; } - + virtual int getDebugMode() const { return m_debugMode; @@ -100,11 +100,11 @@ struct InternalBodyHandle : public InteralBodyData BT_DECLARE_ALIGNED_ALLOCATOR(); int m_nextFreeHandle; - void SetNextFree(int next) + void SetNextFree(int next) { m_nextFreeHandle = next; } - int GetNextFree() const + int GetNextFree() const { return m_nextFreeHandle; } @@ -153,7 +153,7 @@ public: struct CommandLogger { FILE* m_file; - + void writeHeader(unsigned char* buffer) const { @@ -185,15 +185,15 @@ struct CommandLogger buffer[9] = 0; buffer[10] = 0; buffer[11] = 0; - + int ver = btGetVersion(); if (ver>=0 && ver<999) { sprintf((char*)&buffer[9],"%d",ver); } - + } - + void logCommand(const SharedMemoryCommand& command) { btCommandChunk chunk; @@ -240,10 +240,10 @@ struct CommandLogPlayback } unsigned char c = m_header[7]; m_fileIs64bit = (c=='-'); - + const bool VOID_IS_8 = ((sizeof(void*)==8)); m_bitsVary = (VOID_IS_8 != m_fileIs64bit); - + } @@ -260,7 +260,7 @@ struct CommandLogPlayback if (m_file) { size_t s = 0; - + if (m_fileIs64bit) { @@ -271,7 +271,7 @@ struct CommandLogPlayback bCommandChunkPtr4 chunk4; s = fread((void*)&chunk4,sizeof(bCommandChunkPtr4),1,m_file); } - + if (s==1) { s = fread(cmd,sizeof(SharedMemoryCommand),1,m_file); @@ -324,7 +324,7 @@ struct PhysicsServerCommandProcessorInternalData { m_numUsedHandles = 0; m_firstFreeHandle = -1; - + increaseHandleCapacity(1); } @@ -349,10 +349,10 @@ struct PhysicsServerCommandProcessorInternalData int additionalCapacity= m_bodyHandles.size(); increaseHandleCapacity(additionalCapacity); - + getHandle(handle)->SetNextFree(m_firstFreeHandle); } - + return handle; } @@ -369,16 +369,16 @@ struct PhysicsServerCommandProcessorInternalData } ///end handle management - - + + CommandLogger* m_commandLogger; CommandLogPlayback* m_logPlayback; - + btScalar m_physicsDeltaTime; btAlignedObjectArray m_multiBodyJointFeedbacks; - + btAlignedObjectArray m_worldImporters; btAlignedObjectArray m_urdfLinkNameMapper; @@ -391,17 +391,17 @@ struct PhysicsServerCommandProcessorInternalData btDefaultCollisionConfiguration* m_collisionConfiguration; btMultiBodyDynamicsWorld* m_dynamicsWorld; SharedMemoryDebugDrawer* m_remoteDebugDrawer; - - btAlignedObjectArray m_sdfRecentLoadedBodies; - - + btAlignedObjectArray m_sdfRecentLoadedBodies; + + + struct GUIHelperInterface* m_guiHelper; int m_sharedMemoryKey; bool m_verboseOutput; - - + + //data for picking objects class btRigidBody* m_pickedBody; class btTypedConstraint* m_pickedConstraint; @@ -426,7 +426,7 @@ struct PhysicsServerCommandProcessorInternalData m_pickedConstraint(0), m_pickingMultiBodyPoint2Point(0) { - + initHandles(); #if 0 btAlignedObjectArray bla; @@ -478,16 +478,16 @@ struct PhysicsServerCommandProcessorInternalData void PhysicsServerCommandProcessor::setGuiHelper(struct GUIHelperInterface* guiHelper) { - + if (guiHelper) { - + guiHelper->createPhysicsDebugDrawer(m_data->m_dynamicsWorld); } else { if (m_data->m_guiHelper && m_data->m_dynamicsWorld && m_data->m_dynamicsWorld->getDebugDrawer()) { - + m_data->m_dynamicsWorld->setDebugDrawer(0); } } @@ -521,45 +521,45 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld() ///collision configuration contains default setup for memory, collision setup m_data->m_collisionConfiguration = new btDefaultCollisionConfiguration(); //m_collisionConfiguration->setConvexConvexMultipointIterations(); - + ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) m_data->m_dispatcher = new btCollisionDispatcher(m_data->m_collisionConfiguration); - + m_data->m_broadphase = new btDbvtBroadphase(); - + m_data->m_solver = new btMultiBodyConstraintSolver; - + m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration); m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer(); - - + + m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0)); } void PhysicsServerCommandProcessor::deleteDynamicsWorld() { - + for (int i=0;im_multiBodyJointFeedbacks.size();i++) { delete m_data->m_multiBodyJointFeedbacks[i]; } m_data->m_multiBodyJointFeedbacks.clear(); - - + + for (int i=0;im_worldImporters.size();i++) { delete m_data->m_worldImporters[i]; } m_data->m_worldImporters.clear(); - + for (int i=0;im_urdfLinkNameMapper.size();i++) { delete m_data->m_urdfLinkNameMapper[i]; } m_data->m_urdfLinkNameMapper.clear(); - - + + for (int i=0;im_strings.size();i++) { delete m_data->m_strings[i]; @@ -568,11 +568,11 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld() btAlignedObjectArray constraints; btAlignedObjectArray mbconstraints; - - + + if (m_data->m_dynamicsWorld) { - + int i; for (i = m_data->m_dynamicsWorld->getNumConstraints() - 1; i >= 0; i--) { @@ -586,7 +586,7 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld() mbconstraints.push_back(mbconstraint); m_data->m_dynamicsWorld->removeMultiBodyConstraint(mbconstraint); } - + for (i = m_data->m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--) { btCollisionObject* obj = m_data->m_dynamicsWorld->getCollisionObjectArray()[i]; @@ -662,7 +662,7 @@ void PhysicsServerCommandProcessor::createJointMotors(btMultiBody* mb) for (int i=0;igetLink(mbLinkIndex).m_userPtr = motor; m_data->m_dynamicsWorld->addMultiBodyConstraint(motor); motor->finalizeMultiDof(); - + } } @@ -688,11 +688,11 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe b3Error("loadSdf: No valid m_dynamicsWorld"); return false; } - + m_data->m_sdfRecentLoadedBodies.clear(); - + BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter); - + bool useFixedBase = false; bool loadOk = u2b.loadSDF(fileName, useFixedBase); if (loadOk) @@ -709,16 +709,16 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe m_data->m_collisionShapes.push_back(compound->getChildShape(childIndex)); } } - + } - + btTransform rootTrans; rootTrans.setIdentity(); if (m_data->m_verboseOutput) { b3Printf("loaded %s OK!", fileName); } - + for (int m =0; mallocHandle(); - + InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId); { @@ -737,8 +737,8 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe int urdfLinkIndex = u2b.getRootLinkIndex(); u2b.getMassAndInertia(urdfLinkIndex, mass,localInertiaDiagonal,bodyHandle->m_rootLocalInertialFrame); } - - + + //todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user int rootLinkIndex = u2b.getRootLinkIndex(); @@ -748,26 +748,26 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe u2b.getRootTransformInWorld(rootTrans); bool useMultiBody = true; ConvertURDF2Bullet(u2b,creation, rootTrans,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix(),true); - - - + + + mb = creation.getBulletMultiBody(); if (mb) { bodyHandle->m_multiBody = mb; - + m_data->m_sdfRecentLoadedBodies.push_back(bodyUniqueId); - + createJointMotors(mb); - + //disable serialization of the collision objects (they are too big, and the client likely doesn't need them); bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks()); for (int i=0;igetNumLinks();i++) { //disable serialization of the collision objects - + int urdfLinkIndex = creation.m_mb2urdfLink[i]; btScalar mass; btVector3 localInertiaDiagonal(0,0,0); @@ -777,12 +777,12 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe std::string* linkName = new std::string(u2b.getLinkName(urdfLinkIndex).c_str()); m_data->m_strings.push_back(linkName); - + mb->getLink(i).m_linkName = linkName->c_str(); std::string* jointName = new std::string(u2b.getJointName(urdfLinkIndex).c_str()); m_data->m_strings.push_back(jointName); - + mb->getLink(i).m_jointName = jointName->c_str(); } std::string* baseName = new std::string(u2b.getLinkName(u2b.getRootLinkIndex())); @@ -792,10 +792,10 @@ bool PhysicsServerCommandProcessor::loadSdf(const char* fileName, char* bufferSe { b3Warning("No multibody loaded from URDF. Could add btRigidBody+btTypedConstraint solution later."); } - + } } - return loadOk; + return loadOk; } bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVector3& pos, const btQuaternion& orn, @@ -809,13 +809,13 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto } - + BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter); - + bool loadOk = u2b.loadURDF(fileName, useFixedBase); - - + + if (loadOk) { //get a body index @@ -836,7 +836,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto { b3Printf("loaded %s OK!", fileName); } - + btTransform tr; tr.setIdentity(); tr.setOrigin(pos); @@ -844,9 +844,9 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto //int rootLinkIndex = u2b.getRootLinkIndex(); // printf("urdf root link index = %d\n",rootLinkIndex); MyMultiBodyCreator creation(m_data->m_guiHelper); - + ConvertURDF2Bullet(u2b,creation, tr,m_data->m_dynamicsWorld,useMultiBody,u2b.getPathPrefix()); - + for (int i=0;im_collisionShapes.push_back(compound->getChildShape(childIndex)); } } - + } - + btMultiBody* mb = creation.getBulletMultiBody(); if (useMultiBody) { - - + + if (mb) { - + bodyHandle->m_multiBody = mb; - + createJointMotors(mb); @@ -905,17 +905,17 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto util->m_memSerializer->registerNameForPointer(jointName->c_str(),jointName->c_str()); mb->getLink(i).m_jointName = jointName->c_str(); } - + std::string* baseName = new std::string(u2b.getLinkName(u2b.getRootLinkIndex())); m_data->m_strings.push_back(baseName); - + util->m_memSerializer->registerNameForPointer(baseName->c_str(),baseName->c_str()); mb->setBaseName(baseName->c_str()); - - + + util->m_memSerializer->insertHeader(); - + int len = mb->calculateSerializeBufferSize(); btChunk* chunk = util->m_memSerializer->allocate(len,1); const char* structType = mb->serialize(chunk->m_oldPtr, util->m_memSerializer); @@ -927,16 +927,16 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto b3Warning("No multibody loaded from URDF. Could add btRigidBody+btTypedConstraint solution later."); return false; } - + } else { btAssert(0); - + return true; } - + } - + return false; } @@ -944,10 +944,10 @@ void PhysicsServerCommandProcessor::replayLogCommand(char* bufferServerToClient, { if (m_data->m_logPlayback) { - + SharedMemoryCommand clientCmd; SharedMemoryStatus serverStatus; - + bool hasCommand = m_data->m_logPlayback->processNextCommand(&clientCmd); if (hasCommand) { @@ -982,7 +982,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char* } util->m_memSerializer->registerNameForPointer(mb->getBaseName(),mb->getBaseName()); - + util->m_memSerializer->insertHeader(); int len = mb->calculateSerializeBufferSize(); @@ -1002,12 +1002,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { ///we ignore overflow of integer for now - + { - + //until we implement a proper ring buffer, we assume always maximum of 1 outstanding commands - - + + //const SharedMemoryCommand& clientCmd =m_data->m_testBlock1->m_clientCommands[0]; #if 1 if (m_data->m_commandLogger) @@ -1017,7 +1017,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm #endif //m_data->m_testBlock1->m_numProcessedClientCommands++; - + //no timestamp yet int timeStamp = 0; @@ -1031,11 +1031,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { b3Printf("Processed CMD_SEND_BULLET_DATA_STREAM length %d",clientCmd.m_dataStreamArguments.m_streamChunkLength); } - + btBulletWorldImporter* worldImporter = new btBulletWorldImporter(m_data->m_dynamicsWorld); m_data->m_worldImporters.push_back(worldImporter); bool completedOk = worldImporter->loadFileFromMemory(m_data->m_testBlock1->m_bulletStreamDataClientToServer,clientCmd.m_dataStreamArguments.m_streamChunkLength); - + if (completedOk) { SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED,clientCmd.m_sequenceNumber,timeStamp); @@ -1046,7 +1046,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm SharedMemoryStatus& status = m_data->createServerStatus(CMD_BULLET_DATA_STREAM_RECEIVED_FAILED,clientCmd.m_sequenceNumber,timeStamp); m_data->submitServerStatus(status); } - + break; } #endif @@ -1054,7 +1054,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm case CMD_REQUEST_DEBUG_LINES: { int curFlags =m_data->m_remoteDebugDrawer->getDebugMode(); - + int debugMode = clientCmd.m_requestDebugLinesArguments.m_debugMode;//clientCmd.btIDebugDraw::DBG_DrawWireframe|btIDebugDraw::DBG_DrawAabb; int startingLineIndex = clientCmd.m_requestDebugLinesArguments.m_startingLineIndex; if (startingLineIndex<0) @@ -1062,7 +1062,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm b3Warning("startingLineIndex should be non-negative"); startingLineIndex = 0; } - + if (clientCmd.m_requestDebugLinesArguments.m_startingLineIndex==0) { m_data->m_remoteDebugDrawer->m_lines2.resize(0); @@ -1083,9 +1083,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm b3Warning("m_startingLineIndex exceeds total number of debug lines"); startingLineIndex =m_data->m_remoteDebugDrawer->m_lines2.size(); } - + int numLines = btMin(maxNumLines,m_data->m_remoteDebugDrawer->m_lines2.size()-startingLineIndex); - + if (numLines) { @@ -1108,66 +1108,66 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm linesColor[i*3+2] = m_data->m_remoteDebugDrawer->m_lines2[i+startingLineIndex].m_color.z(); } } - + serverStatusOut.m_type = CMD_DEBUG_LINES_COMPLETED; serverStatusOut.m_sendDebugLinesArgs.m_numDebugLines = numLines; serverStatusOut.m_sendDebugLinesArgs.m_startingLineIndex = startingLineIndex; serverStatusOut.m_sendDebugLinesArgs.m_numRemainingDebugLines = m_data->m_remoteDebugDrawer->m_lines2.size()-(startingLineIndex+numLines); hasStatus = true; - + break; } case CMD_REQUEST_CAMERA_IMAGE_DATA: { - + int startPixelIndex = clientCmd.m_requestPixelDataArguments.m_startPixelIndex; int width, height; int numPixelsCopied = 0; - + if ( - (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0) && + (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0) && (clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT)!=0) { m_data->m_visualConverter.setWidthAndHeight(clientCmd.m_requestPixelDataArguments.m_pixelWidth, clientCmd.m_requestPixelDataArguments.m_pixelHeight); - } - + } + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL)!=0) { m_data->m_guiHelper->copyCameraImageData(0,0,0,0,0,&width,&height,0); - } + } else { m_data->m_visualConverter.getWidthAndHeight(width,height); } - - - + + + int numTotalPixels = width*height; int numRemainingPixels = numTotalPixels - startPixelIndex; - - + + if (numRemainingPixels>0) { int maxNumPixels = bufferSizeInBytes/8-1; unsigned char* pixelRGBA = (unsigned char*)bufferServerToClient; int numRequestedPixels = btMin(maxNumPixels,numRemainingPixels); - + float* depthBuffer = (float*)(bufferServerToClient+numRequestedPixels*4); - + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_USE_HARDWARE_OPENGL)!=0) { m_data->m_guiHelper->copyCameraImageData(pixelRGBA,numRequestedPixels,depthBuffer,numRequestedPixels,startPixelIndex,&width,&height,&numPixelsCopied); } else { - + if (clientCmd.m_requestPixelDataArguments.m_startPixelIndex==0) { // printf("-------------------------------\nRendering\n"); - - + + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0) { m_data->m_visualConverter.render( @@ -1177,19 +1177,19 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { m_data->m_visualConverter.render(); } - + } - + m_data->m_visualConverter.copyCameraImageData(pixelRGBA,numRequestedPixels,depthBuffer,numRequestedPixels,startPixelIndex,&width,&height,&numPixelsCopied); } - + //each pixel takes 4 RGBA values and 1 float = 8 bytes - + } else { - + } - + serverStatusOut.m_type = CMD_CAMERA_IMAGE_COMPLETED; serverStatusOut.m_sendPixelDataArguments.m_numPixelsCopied = numPixelsCopied; serverStatusOut.m_sendPixelDataArguments.m_numRemainingPixels = numRemainingPixels - numPixelsCopied; @@ -1197,7 +1197,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm serverStatusOut.m_sendPixelDataArguments.m_imageWidth = width; serverStatusOut.m_sendPixelDataArguments.m_imageHeight= height; hasStatus = true; - + break; } @@ -1206,7 +1206,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm const SdfRequestInfoArgs& sdfInfoArgs = clientCmd.m_sdfRequestInfoArgs; //stream info into memory int streamSizeInBytes = createBodyInfoStream(sdfInfoArgs.m_bodyUniqueId, bufferServerToClient, bufferSizeInBytes); - + serverStatusOut.m_type = CMD_BODY_INFO_COMPLETED; serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = sdfInfoArgs.m_bodyUniqueId; serverStatusOut.m_dataStreamArguments.m_streamChunkLength = streamSizeInBytes; @@ -1220,9 +1220,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { b3Printf("Processed CMD_LOAD_SDF:%s", sdfArgs.m_sdfFileName); } - + bool completedOk = loadSdf(sdfArgs.m_sdfFileName,bufferServerToClient, bufferSizeInBytes); - + //serverStatusOut.m_type = CMD_SDF_LOADING_FAILED; serverStatusOut.m_sdfLoadedArgs.m_numBodies = m_data->m_sdfRecentLoadedBodies.size(); int maxBodies = btMin(MAX_SDF_BODIES, serverStatusOut.m_sdfLoadedArgs.m_numBodies); @@ -1230,14 +1230,14 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { serverStatusOut.m_sdfLoadedArgs.m_bodyUniqueIds[i] = m_data->m_sdfRecentLoadedBodies[i]; } - + serverStatusOut.m_type = CMD_SDF_LOADING_COMPLETED; hasStatus = true; break; } case CMD_LOAD_URDF: { - + const UrdfArgs& urdfArgs = clientCmd.m_urdfArguments; if (m_data->m_verboseOutput) { @@ -1267,32 +1267,32 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm bool completedOk = loadUrdf(urdfArgs.m_urdfFileName, initialPos,initialOrn, useMultiBody, useFixedBase,&bodyUniqueId, bufferServerToClient, bufferSizeInBytes); - - + + if (completedOk) { - + m_data->m_guiHelper->autogenerateGraphicsObjects(this->m_data->m_dynamicsWorld); - + serverStatusOut.m_type = CMD_URDF_LOADING_COMPLETED; serverStatusOut.m_dataStreamArguments.m_streamChunkLength = 0; - + if (m_data->m_urdfLinkNameMapper.size()) { serverStatusOut.m_dataStreamArguments.m_streamChunkLength = m_data->m_urdfLinkNameMapper.at(m_data->m_urdfLinkNameMapper.size()-1)->m_memSerializer->getCurrentBufferSize(); } serverStatusOut.m_dataStreamArguments.m_bodyUniqueId = bodyUniqueId; hasStatus = true; - + } else { serverStatusOut.m_type = CMD_URDF_LOADING_FAILED; hasStatus = true; } - - - + + + break; } case CMD_CREATE_SENSOR: @@ -1322,7 +1322,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm mb->getLink(jointIndex).m_jointFeedback = fb; m_data->m_multiBodyJointFeedbacks.push_back(fb); }; - + } else { if (mb->getLink(jointIndex).m_jointFeedback) @@ -1337,7 +1337,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } } - + } else { b3Warning("No btMultiBody in the world. btRigidBody/btTypedConstraint sensor not hooked up yet"); @@ -1352,15 +1352,15 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm btJointFeedback* fb = new btJointFeedback(); m_data->m_jointFeedbacks.push_back(fb); c->setJointFeedback(fb); - - + + } */ #endif - + serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED; hasStatus = true; - + break; } case CMD_SEND_DESIRED_STATE: @@ -1369,7 +1369,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { b3Printf("Processed CMD_SEND_DESIRED_STATE"); } - + int bodyUniqueId = clientCmd.m_sendDesiredStateCommandArgument.m_bodyUniqueId; InteralBodyData* body = m_data->getHandle(bodyUniqueId); @@ -1377,7 +1377,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { btMultiBody* mb = body->m_multiBody; btAssert(mb); - + switch (clientCmd.m_sendDesiredStateCommandArgument.m_controlMode) { case CONTROL_MODE_TORQUE: @@ -1386,38 +1386,23 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { b3Printf("Using CONTROL_MODE_TORQUE"); } - mb->clearForcesAndTorques(); - + // mb->clearForcesAndTorques(); int torqueIndex = 0; - #if 0 - //it is inconsistent to allow application of base force/torque, there is no 'joint' motor. Use a separate API for this. - - btVector3 f(0,0,0); - btVector3 t(0,0,0); - - if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) - { - f = btVector3 (clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[0], - clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[1], - clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[2]); - t = btVector3 (clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[3], - clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[4], - clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[5]); - } - torqueIndex+=6; - mb->addBaseForce(f); - mb->addBaseTorque(t); - #endif - for (int link=0;linkgetNumLinks();link++) + if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) { - - for (int dof=0;dofgetLink(link).m_dofCount;dof++) - { - double torque = 0.f; - if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) - torque = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[torqueIndex]; - mb->addJointTorqueMultiDof(link,dof,torque); - torqueIndex++; + for (int link=0;linkgetNumLinks();link++) + { + + for (int dof=0;dofgetLink(link).m_dofCount;dof++) + { + double torque = 0.f; + if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[torqueIndex]&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) + { + torque = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[torqueIndex]; + mb->addJointTorqueMultiDof(link,dof,torque); + } + torqueIndex++; + } } } break; @@ -1428,7 +1413,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { b3Printf("Using CONTROL_MODE_VELOCITY"); } - + int numMotors = 0; //find the joint motors and apply the desired velocity and maximum force/torque { @@ -1437,22 +1422,30 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { if (supportsJointMotor(mb,link)) { - + btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr; - - + + if (motor) { btScalar desiredVelocity = 0.f; - if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_QDOT)!=0) - desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex]; - motor->setVelocityTarget(desiredVelocity); + bool hasDesiredVelocity = false; - btScalar maxImp = 1000000.f*m_data->m_physicsDeltaTime; - if ((clientCmd.m_updateFlags&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) - maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex]*m_data->m_physicsDeltaTime; - - motor->setMaxAppliedImpulse(maxImp); + if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex]&SIM_DESIRED_STATE_HAS_QDOT)!=0) + { + desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex]; + motor->setVelocityTarget(desiredVelocity); + hasDesiredVelocity = true; + } + if (hasDesiredVelocity) + { + btScalar maxImp = 1000000.f*m_data->m_physicsDeltaTime; + if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex]&SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) + { + maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[dofIndex]*m_data->m_physicsDeltaTime; + } + motor->setMaxAppliedImpulse(maxImp); + } numMotors++; } @@ -1470,7 +1463,6 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm b3Printf("Using CONTROL_MODE_POSITION_VELOCITY_PD"); } //compute the force base on PD control - mb->clearForcesAndTorques(); int numMotors = 0; //find the joint motors and apply the desired velocity and maximum force/torque @@ -1481,44 +1473,61 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { if (supportsJointMotor(mb,link)) { - + btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)mb->getLink(link).m_userPtr; - + if (motor) { - - btScalar desiredVelocity = 0.f; - if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_QDOT)!=0) - desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex]; - btScalar desiredPosition = 0.f; - if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_Q)!=0) - desiredPosition = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex]; + bool hasDesiredPosOrVel = false; btScalar kp = 0.f; - if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_KP)!=0) - kp = clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex]; - btScalar kd = 0.f; - if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_KD)!=0) - kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex]; + btScalar kd = 0.f; + btScalar desiredVelocity = 0.f; + if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_QDOT)!=0) + { + hasDesiredPosOrVel = true; + desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[velIndex]; + kd = 0.1; + } + btScalar desiredPosition = 0.f; + if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[posIndex] & SIM_DESIRED_STATE_HAS_Q)!=0) + { + hasDesiredPosOrVel = true; + desiredPosition = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQ[posIndex]; + kp = 0.1; + } - int dof1 = 0; - btScalar currentPosition = mb->getJointPosMultiDof(link)[dof1]; - btScalar currentVelocity = mb->getJointVelMultiDof(link)[dof1]; - btScalar positionStabiliationTerm = (desiredPosition-currentPosition)/m_data->m_physicsDeltaTime; - btScalar velocityError = (desiredVelocity - currentVelocity); - - desiredVelocity = kp * positionStabiliationTerm + - kd * velocityError; - - motor->setVelocityTarget(desiredVelocity); - - btScalar maxImp = 1000000.f*m_data->m_physicsDeltaTime; + if (hasDesiredPosOrVel) + { - if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) - maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex]*m_data->m_physicsDeltaTime; - - motor->setMaxAppliedImpulse(maxImp); + if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_KP)!=0) + { + kp = clientCmd.m_sendDesiredStateCommandArgument.m_Kp[velIndex]; + } + + if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[velIndex] & SIM_DESIRED_STATE_HAS_KD)!=0) + { + kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex]; + } + + int dof1 = 0; + btScalar currentPosition = mb->getJointPosMultiDof(link)[dof1]; + btScalar currentVelocity = mb->getJointVelMultiDof(link)[dof1]; + btScalar positionStabiliationTerm = (desiredPosition-currentPosition)/m_data->m_physicsDeltaTime; + btScalar velocityError = (desiredVelocity - currentVelocity); + + desiredVelocity = kp * positionStabiliationTerm + + kd * velocityError; + + motor->setVelocityTarget(desiredVelocity); + btScalar maxImp = 1000000.f*m_data->m_physicsDeltaTime; + + if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) + maxImp = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateForceTorque[velIndex]*m_data->m_physicsDeltaTime; + + motor->setMaxAppliedImpulse(maxImp); + } numMotors++; } @@ -1535,10 +1544,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm b3Warning("m_controlMode not implemented yet"); break; } - + } } - + serverStatusOut.m_type = CMD_DESIRED_STATE_RECEIVED_COMPLETED; hasStatus = true; break; @@ -1551,7 +1560,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } int bodyUniqueId = clientCmd.m_requestActualStateInformationCommandArgument.m_bodyUniqueId; InteralBodyData* body = m_data->getHandle(bodyUniqueId); - + if (body && body->m_multiBody) { btMultiBody* mb = body->m_multiBody; @@ -1560,9 +1569,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm serverCmd.m_sendActualStateArgs.m_bodyUniqueId = bodyUniqueId; int totalDegreeOfFreedomQ = 0; - int totalDegreeOfFreedomU = 0; - - + int totalDegreeOfFreedomU = 0; + + //always add the base, even for static (non-moving objects) //so that we can easily move the 'fixed' base when needed //do we don't use this conditional "if (!mb->hasFixedBase())" @@ -1570,7 +1579,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm btTransform tr; tr.setOrigin(mb->getBasePos()); tr.setRotation(mb->getWorldToBaseRot().inverse()); - + serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[0] = body->m_rootLocalInertialFrame.getOrigin()[0]; serverCmd.m_sendActualStateArgs.m_rootLocalInertialFrame[1] = @@ -1588,14 +1597,14 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm body->m_rootLocalInertialFrame.getRotation()[3]; - + //base position in world space, carthesian serverCmd.m_sendActualStateArgs.m_actualStateQ[0] = tr.getOrigin()[0]; serverCmd.m_sendActualStateArgs.m_actualStateQ[1] = tr.getOrigin()[1]; serverCmd.m_sendActualStateArgs.m_actualStateQ[2] = tr.getOrigin()[2]; //base orientation, quaternion x,y,z,w, in world space, carthesian - serverCmd.m_sendActualStateArgs.m_actualStateQ[3] = tr.getRotation()[0]; + serverCmd.m_sendActualStateArgs.m_actualStateQ[3] = tr.getRotation()[0]; serverCmd.m_sendActualStateArgs.m_actualStateQ[4] = tr.getRotation()[1]; serverCmd.m_sendActualStateArgs.m_actualStateQ[5] = tr.getRotation()[2]; serverCmd.m_sendActualStateArgs.m_actualStateQ[6] = tr.getRotation()[3]; @@ -1605,7 +1614,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm serverCmd.m_sendActualStateArgs.m_actualStateQdot[0] = mb->getBaseVel()[0]; serverCmd.m_sendActualStateArgs.m_actualStateQdot[1] = mb->getBaseVel()[1]; serverCmd.m_sendActualStateArgs.m_actualStateQdot[2] = mb->getBaseVel()[2]; - + //base angular velocity (in world space, carthesian) serverCmd.m_sendActualStateArgs.m_actualStateQdot[3] = mb->getBaseOmega()[0]; serverCmd.m_sendActualStateArgs.m_actualStateQdot[4] = mb->getBaseOmega()[1]; @@ -1622,7 +1631,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { serverCmd.m_sendActualStateArgs.m_actualStateQdot[totalDegreeOfFreedomU++] = mb->getJointVelMultiDof(l)[d]; } - + if (0 == mb->getLink(l).m_jointFeedback) { for (int d=0;d<6;d++) @@ -1633,23 +1642,23 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { btVector3 sensedForce = mb->getLink(l).m_jointFeedback->m_reactionForces.getLinear(); btVector3 sensedTorque = mb->getLink(l).m_jointFeedback->m_reactionForces.getAngular(); - + serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+0] = sensedForce[0]; serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+1] = sensedForce[1]; serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+2] = sensedForce[2]; - + serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+3] = sensedTorque[0]; serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+4] = sensedTorque[1]; serverCmd.m_sendActualStateArgs.m_jointReactionForces[l*6+5] = sensedTorque[2]; } - + serverCmd.m_sendActualStateArgs.m_jointMotorForce[l] = 0; - + if (supportsJointMotor(mb,l)) { - + btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)body->m_multiBody->getLink(l).m_userPtr; - + if (motor && m_data->m_physicsDeltaTime>btScalar(0)) { btScalar force =motor->getAppliedImpulse(0)/m_data->m_physicsDeltaTime; @@ -1663,10 +1672,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } btVector3 linkLocalInertialOrigin = body->m_linkLocalInertialFrames[l].getOrigin(); btQuaternion linkLocalInertialRotation = body->m_linkLocalInertialFrames[l].getRotation(); - + btVector3 linkOrigin = mb->getLink(l).m_cachedWorldTransform.getOrigin(); btQuaternion linkRotation = mb->getLink(l).m_cachedWorldTransform.getRotation(); - + serverCmd.m_sendActualStateArgs.m_linkState[l*7+0] = linkOrigin.getX(); serverCmd.m_sendActualStateArgs.m_linkState[l*7+1] = linkOrigin.getY(); serverCmd.m_sendActualStateArgs.m_linkState[l*7+2] = linkOrigin.getZ(); @@ -1674,24 +1683,24 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm serverCmd.m_sendActualStateArgs.m_linkState[l*7+4] = linkRotation.y(); serverCmd.m_sendActualStateArgs.m_linkState[l*7+5] = linkRotation.z(); serverCmd.m_sendActualStateArgs.m_linkState[l*7+6] = linkRotation.w(); - + serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+0] = linkLocalInertialOrigin.getX(); serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+1] = linkLocalInertialOrigin.getY(); serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+2] = linkLocalInertialOrigin.getZ(); - + serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+3] = linkLocalInertialRotation.x(); serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+4] = linkLocalInertialRotation.y(); serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+5] = linkLocalInertialRotation.z(); serverCmd.m_sendActualStateArgs.m_linkLocalInertialFrames[l*7+6] = linkLocalInertialRotation.w(); - + } - + serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomQ = totalDegreeOfFreedomQ; serverCmd.m_sendActualStateArgs.m_numDegreeOfFreedomU = totalDegreeOfFreedomU; - + hasStatus = true; - + } else { if (body && body->m_rigidBody) @@ -1711,7 +1720,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm serverCmd.m_sendActualStateArgs.m_actualStateQ[2] = tr.getOrigin()[2]; //base orientation, quaternion x,y,z,w, in world space, carthesian - serverCmd.m_sendActualStateArgs.m_actualStateQ[3] = tr.getRotation()[0]; + serverCmd.m_sendActualStateArgs.m_actualStateQ[3] = tr.getRotation()[0]; serverCmd.m_sendActualStateArgs.m_actualStateQ[4] = tr.getRotation()[1]; serverCmd.m_sendActualStateArgs.m_actualStateQ[5] = tr.getRotation()[2]; serverCmd.m_sendActualStateArgs.m_actualStateQ[6] = tr.getRotation()[3]; @@ -1721,7 +1730,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm serverCmd.m_sendActualStateArgs.m_actualStateQdot[0] = rb->getLinearVelocity()[0]; serverCmd.m_sendActualStateArgs.m_actualStateQdot[1] = rb->getLinearVelocity()[1]; serverCmd.m_sendActualStateArgs.m_actualStateQdot[2] = rb->getLinearVelocity()[2]; - + //base angular velocity (in world space, carthesian) serverCmd.m_sendActualStateArgs.m_actualStateQdot[3] = rb->getAngularVelocity()[0]; serverCmd.m_sendActualStateArgs.m_actualStateQdot[4] = rb->getAngularVelocity()[1]; @@ -1745,7 +1754,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } case CMD_STEP_FORWARD_SIMULATION: { - + if (m_data->m_verboseOutput) { b3Printf("Step simulation request"); @@ -1756,13 +1765,13 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm applyJointDamping(i); } m_data->m_dynamicsWorld->stepSimulation(m_data->m_physicsDeltaTime,0); - + SharedMemoryStatus& serverCmd =serverStatusOut; serverCmd.m_type = CMD_STEP_FORWARD_SIMULATION_COMPLETED; hasStatus = true; break; } - + case CMD_SEND_PHYSICS_SIMULATION_PARAMETERS: { if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_DELTA_TIME) @@ -1781,12 +1790,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } } - + SharedMemoryStatus& serverCmd =serverStatusOut; serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED; hasStatus = true; break; - + }; case CMD_INIT_POSE: { @@ -1803,6 +1812,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_POSITION) { btVector3 zero(0,0,0); + btAssert(clientCmd.m_initPoseArgs.m_hasInitialStateQ[0] && + clientCmd.m_initPoseArgs.m_hasInitialStateQ[1] && + clientCmd.m_initPoseArgs.m_hasInitialStateQ[2]); + mb->setBaseVel(zero); mb->setBasePos(btVector3( clientCmd.m_initPoseArgs.m_initialStateQ[0], @@ -1811,6 +1824,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_ORIENTATION) { + btAssert(clientCmd.m_initPoseArgs.m_hasInitialStateQ[3] && + clientCmd.m_initPoseArgs.m_hasInitialStateQ[4] && + clientCmd.m_initPoseArgs.m_hasInitialStateQ[5] && + clientCmd.m_initPoseArgs.m_hasInitialStateQ[6]); + mb->setBaseOmega(btVector3(0,0,0)); mb->setWorldToBaseRot(btQuaternion( clientCmd.m_initPoseArgs.m_initialStateQ[3], @@ -1823,9 +1841,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm int dofIndex = 7; for (int i=0;igetNumLinks();i++) { - if (mb->getLink(i).m_dofCount==1) + if ( (clientCmd.m_initPoseArgs.m_hasInitialStateQ[dofIndex]) && (mb->getLink(i).m_dofCount==1)) { - mb->setJointPos(i,clientCmd.m_initPoseArgs.m_initialStateQ[dofIndex]); mb->setJointVel(i,0); } @@ -1833,14 +1850,14 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } } } - + SharedMemoryStatus& serverCmd =serverStatusOut; serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED; hasStatus = true; break; } - + case CMD_RESET_SIMULATION: { @@ -1857,7 +1874,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm createEmptyDynamicsWorld(); m_data->exitHandles(); m_data->initHandles(); - + SharedMemoryStatus& serverCmd =serverStatusOut; serverCmd.m_type = CMD_RESET_SIMULATION_COMPLETED; hasStatus = true; @@ -1887,7 +1904,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (clientCmd.m_updateFlags & BOX_SHAPE_HAS_INITIAL_ORIENTATION) { - + startTrans.setRotation(btQuaternion( clientCmd.m_createBoxShapeArguments.m_initialOrientation[0], clientCmd.m_createBoxShapeArguments.m_initialOrientation[1], @@ -1912,7 +1929,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm m_data->m_worldImporters.push_back(worldImporter); btCollisionShape* shape = 0; - + switch (shapeType) { case COLLISION_SHAPE_TYPE_CYLINDER_X: @@ -1969,8 +1986,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm shape = worldImporter->createBoxShape(halfExtents); } } - - + + bool isDynamic = (mass>0); btRigidBody* rb = worldImporter->createRigidBody(isDynamic,mass,startTrans,shape,0); rb->setRollingFriction(0.2); @@ -1985,11 +2002,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } m_data->m_guiHelper->createCollisionShapeGraphicsObject(rb->getCollisionShape()); m_data->m_guiHelper->createCollisionObjectGraphicsObject(rb,colorRGBA); - - + + SharedMemoryStatus& serverCmd =serverStatusOut; serverCmd.m_type = CMD_RIGID_BODY_CREATION_COMPLETED; - + int bodyUniqueId = m_data->allocHandle(); InternalBodyHandle* bodyHandle = m_data->getHandle(bodyUniqueId); @@ -2008,7 +2025,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm clientCmd.m_pickBodyArguments.m_rayToWorld[1], clientCmd.m_pickBodyArguments.m_rayToWorld[2])); - + SharedMemoryStatus& serverCmd =serverStatusOut; serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED; hasStatus = true; @@ -2040,7 +2057,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm default: { b3Error("Unknown command encountered"); - + SharedMemoryStatus& serverCmd =serverStatusOut; serverCmd.m_type = CMD_UNKNOWN_COMMAND_FLUSHED; hasStatus = true; @@ -2048,7 +2065,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } }; - + } } return hasStatus; @@ -2060,10 +2077,10 @@ void PhysicsServerCommandProcessor::renderScene() if (m_data->m_guiHelper) { m_data->m_guiHelper->syncPhysicsToGraphics(m_data->m_dynamicsWorld); - + m_data->m_guiHelper->render(m_data->m_dynamicsWorld); } - + } void PhysicsServerCommandProcessor::physicsDebugDraw(int debugDrawFlags) @@ -2114,7 +2131,7 @@ bool PhysicsServerCommandProcessor::pickBody(const btVector3& rayFromWorld, cons btMultiBodyLinkCollider* multiCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(rayCallback.m_collisionObject); if (multiCol && multiCol->m_multiBody) { - + m_data->m_prevCanSleep = multiCol->m_multiBody->getCanSleep(); multiCol->m_multiBody->setCanSleep(false); @@ -2127,10 +2144,10 @@ bool PhysicsServerCommandProcessor::pickBody(const btVector3& rayFromWorld, cons //it is not satisfying, hopefully we find a better solution (higher order integrator, using joint friction using a zero-velocity target motor with limited force etc?) btScalar scaling=1; p2p->setMaxAppliedImpulse(2*scaling); - + btMultiBodyDynamicsWorld* world = (btMultiBodyDynamicsWorld*) m_data->m_dynamicsWorld; world->addMultiBodyConstraint(p2p); - m_data->m_pickingMultiBodyPoint2Point =p2p; + m_data->m_pickingMultiBodyPoint2Point =p2p; } } @@ -2155,7 +2172,7 @@ bool PhysicsServerCommandProcessor::movePickedBody(const btVector3& rayFromWorld if (pickCon) { //keep it at the same picking distance - + btVector3 dir = rayToWorld-rayFromWorld; dir.normalize(); dir *= m_data->m_oldPickingDist; @@ -2164,21 +2181,21 @@ bool PhysicsServerCommandProcessor::movePickedBody(const btVector3& rayFromWorld pickCon->setPivotB(newPivotB); } } - + if (m_data->m_pickingMultiBodyPoint2Point) { //keep it at the same picking distance - + btVector3 dir = rayToWorld-rayFromWorld; dir.normalize(); dir *= m_data->m_oldPickingDist; btVector3 newPivotB = rayFromWorld + dir; - + m_data->m_pickingMultiBodyPoint2Point->setPivotInB(newPivotB); } - + return false; } diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 83fd91c34..9745b8eb6 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -115,6 +115,7 @@ enum EnumInitPoseFlags struct InitPoseArgs { int m_bodyUniqueId; + int m_hasInitialStateQ[MAX_DEGREE_OF_FREEDOM]; double m_initialStateQ[MAX_DEGREE_OF_FREEDOM]; }; @@ -179,11 +180,14 @@ struct SendDesiredStateArgs double m_Kp[MAX_DEGREE_OF_FREEDOM];//indexed by degree of freedom, 6 for base, and then the dofs for each link double m_Kd[MAX_DEGREE_OF_FREEDOM];//indexed by degree of freedom, 6 for base, and then the dofs for each link + int m_hasDesiredStateFlags[MAX_DEGREE_OF_FREEDOM]; + //desired state is only written by the client, read-only access by server is expected //m_desiredStateQ is indexed by position variables, //starting with 3 base position variables, 4 base orientation variables (quaternion), then link position variables double m_desiredStateQ[MAX_DEGREE_OF_FREEDOM]; + //m_desiredStateQdot is index by velocity degrees of freedom, 3 linear and 3 angular variables for the base and then link velocity variables double m_desiredStateQdot[MAX_DEGREE_OF_FREEDOM]; diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 0d2303fc5..b978feb47 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -3,6 +3,7 @@ #include "../SharedMemory/SharedMemoryInProcessPhysicsC_API.h" + #ifdef __APPLE__ #include #else @@ -139,9 +140,11 @@ pybullet_loadURDF(PyObject* self, PyObject* args) int bodyIndex = -1; const char* urdfFileName=""; + float startPosX =0; - float startPosY =0; - float startPosZ = 1; + float startPosY =0; + float startPosZ = 0; + float startOrnX = 0; float startOrnY = 0; float startOrnZ = 0; @@ -282,7 +285,7 @@ pybullet_resetSimulation(PyObject* self, PyObject* args) return Py_None; } -static PyObject* pybullet_setJointControl(PyObject* self, PyObject* args) +static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) { //todo(erwincoumans): set max forces, kp, kd @@ -296,25 +299,22 @@ static PyObject* pybullet_setJointControl(PyObject* self, PyObject* args) size= PySequence_Size(args); - if (size==3) + if (size==4) { - int bodyIndex, controlMode; - PyObject* targetValues; - if (PyArg_ParseTuple(args, "iiO", &bodyIndex, &controlMode, &targetValues)) + int bodyIndex, jointIndex, controlMode; + double targetValue; + + if (PyArg_ParseTuple(args, "iiid", &bodyIndex, &jointIndex, &controlMode, &targetValue)) { - PyObject* seq; - int numJoints, len; - seq = PySequence_Fast(targetValues, "expected a sequence"); - len = PySequence_Size(targetValues); - numJoints = b3GetNumJoints(sm,bodyIndex); + int numJoints; b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryStatusHandle statusHandle; - int qIndex; - - if (len!=numJoints) - { - PyErr_SetString(SpamError, "Number of control target values doesn't match the number of joints."); - Py_DECREF(seq); + struct b3JointInfo info; + + numJoints = b3GetNumJoints(sm,bodyIndex); + if ((jointIndex >= numJoints) || (jointIndex < 0)) + { + PyErr_SetString(SpamError, "Joint index out-of-range."); return NULL; } @@ -323,49 +323,43 @@ static PyObject* pybullet_setJointControl(PyObject* self, PyObject* args) (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) { PyErr_SetString(SpamError, "Illegral control mode."); - Py_DECREF(seq); return NULL; } commandHandle = b3JointControlCommandInit2(sm, bodyIndex,controlMode); - - for (qIndex=0;qIndex= numJoints) || (jointIndex < 0)) + { + PyErr_SetString(SpamError, "Joint index out-of-range."); return NULL; } + + commandHandle = b3CreatePoseCommandInit(sm, bodyIndex); - commandHandle = b3CreatePoseCommandInit(sm, bodyIndex); + b3CreatePoseCommandSetJointPosition(sm, commandHandle, jointIndex, targetValue); - for (qIndex=0;qIndex Date: Fri, 24 Jun 2016 11:06:56 -0700 Subject: [PATCH 052/115] move PD control from PhysicsServerCommandProcessor into btMultiBodyJointMotor improvements/changes in pybullet API --- build_and_run_cmake.sh | 2 +- .../PhysicsServerCommandProcessor.cpp | 24 +-- examples/pybullet/pybullet.c | 151 +++++++++++------- .../Featherstone/btMultiBodyJointMotor.cpp | 29 +++- .../Featherstone/btMultiBodyJointMotor.h | 21 ++- 5 files changed, 146 insertions(+), 81 deletions(-) diff --git a/build_and_run_cmake.sh b/build_and_run_cmake.sh index 1405060f4..28354357b 100755 --- a/build_and_run_cmake.sh +++ b/build_and_run_cmake.sh @@ -2,6 +2,6 @@ rm CMakeCache.txt mkdir build_cmake cd build_cmake -cmake .. +cmake -DBUILD_PYTHON=OFF -CMAKE_BUILD_TYPE=Release .. make -j12 examples/ExampleBrowser/App_ExampleBrowser diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 3cdaac902..99b883454 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1434,7 +1434,16 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex]&SIM_DESIRED_STATE_HAS_QDOT)!=0) { desiredVelocity = clientCmd.m_sendDesiredStateCommandArgument.m_desiredStateQdot[dofIndex]; - motor->setVelocityTarget(desiredVelocity); + btScalar kd = 0.1f; + if ((clientCmd.m_sendDesiredStateCommandArgument.m_hasDesiredStateFlags[dofIndex] & SIM_DESIRED_STATE_HAS_KD)!=0) + { + kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[dofIndex]; + } + + motor->setVelocityTarget(desiredVelocity,kd); + + btScalar kp = 0.f; + motor->setPositionTarget(0,kp); hasDesiredVelocity = true; } if (hasDesiredVelocity) @@ -1511,16 +1520,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm kd = clientCmd.m_sendDesiredStateCommandArgument.m_Kd[velIndex]; } - int dof1 = 0; - btScalar currentPosition = mb->getJointPosMultiDof(link)[dof1]; - btScalar currentVelocity = mb->getJointVelMultiDof(link)[dof1]; - btScalar positionStabiliationTerm = (desiredPosition-currentPosition)/m_data->m_physicsDeltaTime; - btScalar velocityError = (desiredVelocity - currentVelocity); - - desiredVelocity = kp * positionStabiliationTerm + - kd * velocityError; - - motor->setVelocityTarget(desiredVelocity); + motor->setVelocityTarget(desiredVelocity,kd); + motor->setPositionTarget(desiredPosition,kp); + btScalar maxImp = 1000000.f*m_data->m_physicsDeltaTime; if ((clientCmd.m_updateFlags & SIM_DESIRED_STATE_HAS_MAX_FORCE)!=0) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index b978feb47..78e770dbe 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -290,7 +290,13 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) //todo(erwincoumans): set max forces, kp, kd int size; - + int bodyIndex, jointIndex, controlMode; + double targetValue=0; + double maxForce=100000; + double gains=0.1; + int valid = 0; + + if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); @@ -301,69 +307,96 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) if (size==4) { - int bodyIndex, jointIndex, controlMode; - double targetValue; - if (PyArg_ParseTuple(args, "iiid", &bodyIndex, &jointIndex, &controlMode, &targetValue)) + if (!PyArg_ParseTuple(args, "iiid", &bodyIndex, &jointIndex, &controlMode, &targetValue)) { - int numJoints; - b3SharedMemoryCommandHandle commandHandle; - b3SharedMemoryStatusHandle statusHandle; - struct b3JointInfo info; + PyErr_SetString(SpamError, "Error parsing arguments"); + return NULL; + } + valid = 1; + } + if (size==5) + { + + if (!PyArg_ParseTuple(args, "iiidd", &bodyIndex, &jointIndex, &controlMode, &targetValue, &maxForce)) + { + PyErr_SetString(SpamError, "Error parsing arguments"); + return NULL; + } + valid = 1; + } + if (size==6) + { + + if (!PyArg_ParseTuple(args, "iiiddd", &bodyIndex, &jointIndex, &controlMode, &targetValue, &maxForce, &gains)) + { + PyErr_SetString(SpamError, "Error parsing arguments"); + return NULL; + } + valid = 1; + } + + + if (valid) + { + int numJoints; + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + struct b3JointInfo info; - numJoints = b3GetNumJoints(sm,bodyIndex); - if ((jointIndex >= numJoints) || (jointIndex < 0)) - { - PyErr_SetString(SpamError, "Joint index out-of-range."); - return NULL; - } - - if ((controlMode != CONTROL_MODE_VELOCITY) && - (controlMode != CONTROL_MODE_TORQUE) && - (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) - { - PyErr_SetString(SpamError, "Illegral control mode."); - return NULL; - } - - commandHandle = b3JointControlCommandInit2(sm, bodyIndex,controlMode); - - b3GetJointInfo(sm, bodyIndex, jointIndex, &info); - - switch (controlMode) - { - case CONTROL_MODE_VELOCITY: - { - b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, targetValue); - b3JointControlSetKd(commandHandle,info.m_uIndex,1); - b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,10000); - break; - } - - case CONTROL_MODE_TORQUE: - { - b3JointControlSetDesiredForceTorque(commandHandle, info.m_uIndex, targetValue); - break; - } - - case CONTROL_MODE_POSITION_VELOCITY_PD: - { - b3JointControlSetDesiredPosition( commandHandle, info.m_qIndex, targetValue); - b3JointControlSetKp(commandHandle,info.m_uIndex,1); - b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,10000); - break; - } - default: - { - } - }; - - statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - - Py_INCREF(Py_None); - return Py_None; + numJoints = b3GetNumJoints(sm,bodyIndex); + if ((jointIndex >= numJoints) || (jointIndex < 0)) + { + PyErr_SetString(SpamError, "Joint index out-of-range."); + return NULL; } + if ((controlMode != CONTROL_MODE_VELOCITY) && + (controlMode != CONTROL_MODE_TORQUE) && + (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) + { + PyErr_SetString(SpamError, "Illegral control mode."); + return NULL; + } + + commandHandle = b3JointControlCommandInit2(sm, bodyIndex,controlMode); + + b3GetJointInfo(sm, bodyIndex, jointIndex, &info); + + switch (controlMode) + { + case CONTROL_MODE_VELOCITY: + { + b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, targetValue); + double kd = gains; + b3JointControlSetKd(commandHandle,info.m_uIndex,kd); + b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,maxForce); + break; + } + + case CONTROL_MODE_TORQUE: + { + b3JointControlSetDesiredForceTorque(commandHandle, info.m_uIndex, targetValue); + break; + } + + case CONTROL_MODE_POSITION_VELOCITY_PD: + { + b3JointControlSetDesiredPosition( commandHandle, info.m_qIndex, targetValue); + double kp = gains; + b3JointControlSetKp(commandHandle,info.m_uIndex,kp); + b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,maxForce); + break; + } + default: + { + } + }; + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + + Py_INCREF(Py_None); + return Py_None; } PyErr_SetString(SpamError, "error in setJointControl."); return NULL; diff --git a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp index 50268611b..3d0f45b77 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp @@ -23,7 +23,10 @@ subject to the following restrictions: btMultiBodyJointMotor::btMultiBodyJointMotor(btMultiBody* body, int link, btScalar desiredVelocity, btScalar maxMotorImpulse) :btMultiBodyConstraint(body,body,link,body->getLink(link).m_parent,1,true), - m_desiredVelocity(desiredVelocity) + m_desiredVelocity(desiredVelocity), + m_desiredPosition(0), + m_kd(0.1), + m_kp(0) { m_maxAppliedImpulse = maxMotorImpulse; @@ -51,7 +54,10 @@ void btMultiBodyJointMotor::finalizeMultiDof() btMultiBodyJointMotor::btMultiBodyJointMotor(btMultiBody* body, int link, int linkDoF, btScalar desiredVelocity, btScalar maxMotorImpulse) //:btMultiBodyConstraint(body,0,link,-1,1,true), :btMultiBodyConstraint(body,body,link,body->getLink(link).m_parent,1,true), - m_desiredVelocity(desiredVelocity) + m_desiredVelocity(desiredVelocity), + m_desiredPosition(0), + m_kd(0.1), + m_kp(0) { btAssert(linkDoF < body->getLink(link).m_dofCount); @@ -113,9 +119,22 @@ void btMultiBodyJointMotor::createConstraintRows(btMultiBodyConstraintArray& con for (int row=0;rowgetJointPosMultiDof(m_linkA)[dof]; + btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; + btScalar positionStabiliationTerm = (m_desiredPosition-currentPosition)/infoGlobal.m_timeStep; + btScalar velocityError = (m_desiredVelocity - currentVelocity); + btScalar rhs = m_kp * positionStabiliationTerm + m_kd * velocityError; + printf("m_kd = %f\n", m_kd); + printf("m_kp = %f\n", m_kp); + printf("m_desiredVelocity = %f\n", m_desiredVelocity); + printf("m_desiredPosition = %f\n", m_desiredPosition); + printf("m_maxAppliedImpulse = %f\n", m_maxAppliedImpulse); + printf("rhs = %f\n", rhs); + + + fillMultiBodyConstraint(constraintRow,data,jacobianA(row),jacobianB(row),dummy,dummy,dummy,posError,infoGlobal,-m_maxAppliedImpulse,m_maxAppliedImpulse,1,false,rhs); constraintRow.m_orgConstraint = this; constraintRow.m_orgDofIndex = row; { diff --git a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h index d322f87e7..2a55be035 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h @@ -24,9 +24,12 @@ struct btSolverInfo; class btMultiBodyJointMotor : public btMultiBodyConstraint { protected: - - - btScalar m_desiredVelocity; + + btScalar m_desiredVelocity; + btScalar m_desiredPosition; + btScalar m_kd; + btScalar m_kp; + public: @@ -42,10 +45,18 @@ public: btMultiBodyJacobianData& data, const btContactSolverInfo& infoGlobal); - virtual void setVelocityTarget(btScalar velTarget) + virtual void setVelocityTarget(btScalar velTarget, btScalar kd = 1.f) { - m_desiredVelocity = velTarget; + m_desiredVelocity = velTarget; + m_kd = kd; } + + virtual void setPositionTarget(btScalar posTarget, btScalar kp = 1.f) + { + m_desiredPosition = posTarget; + m_kp = kp; + } + virtual void debugDraw(class btIDebugDraw* drawer) { From a15eb3035e1aa72f7e80c525e0599bbe5d939858 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Fri, 24 Jun 2016 11:12:19 -0700 Subject: [PATCH 053/115] default gains 1 -> 0.1 --- .../Featherstone/btMultiBodyJointMotor.h | 24 +++++++++---------- 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h index 2a55be035..e433515d4 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h @@ -24,11 +24,11 @@ struct btSolverInfo; class btMultiBodyJointMotor : public btMultiBodyConstraint { protected: - - btScalar m_desiredVelocity; - btScalar m_desiredPosition; - btScalar m_kd; - btScalar m_kp; + + btScalar m_desiredVelocity; + btScalar m_desiredPosition; + btScalar m_kd; + btScalar m_kp; public: @@ -45,18 +45,18 @@ public: btMultiBodyJacobianData& data, const btContactSolverInfo& infoGlobal); - virtual void setVelocityTarget(btScalar velTarget, btScalar kd = 1.f) + virtual void setVelocityTarget(btScalar velTarget, btScalar kd = 0.1f) { - m_desiredVelocity = velTarget; + m_desiredVelocity = velTarget; m_kd = kd; } - - virtual void setPositionTarget(btScalar posTarget, btScalar kp = 1.f) + + virtual void setPositionTarget(btScalar posTarget, btScalar kp = 0.1f) { - m_desiredPosition = posTarget; + m_desiredPosition = posTarget; m_kp = kp; - } - + } + virtual void debugDraw(class btIDebugDraw* drawer) { From d339cf5b74c754064b0336b9e71f881c2e29805c Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Fri, 24 Jun 2016 15:30:43 -0700 Subject: [PATCH 054/115] ability to call renderImage with three vectors: camera position, target position, and up vector --- examples/pybullet/pybullet.c | 78 +++++++++++++++++++++++++++++++++++- 1 file changed, 77 insertions(+), 1 deletion(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 8574fa308..bf55cc46a 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -976,6 +976,32 @@ static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16]) return 0; } +// internal function to set a float vector[3] +// used to initialize camera position with +// a view and projection matrix in renderImage() +// +// // Args: +// matrix - float[16] which will be set by values from objMat +static int pybullet_internalSetVector(PyObject* objMat, float vector[3]) +{ + int i, len; + PyObject* seq; + + seq = PySequence_Fast(objMat, "expected a sequence"); + len = PySequence_Size(objMat); + if (len==3) + { + for (i = 0; i < len; i++) + { + vector[i] = pybullet_internalGetFloatFromSequence(seq,i); + } + Py_DECREF(seq); + return 1; + } + Py_DECREF(seq); + return 0; +} + // Render an image from the current timestep of the simulation // // Examples: @@ -995,10 +1021,20 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) ///request an image from a simulated camera, using a software renderer. struct b3CameraImageData imageData; PyObject* objViewMat,* objProjMat; - int width, height; + PyObject* objCameraPos,*objTargetPos,* objCameraUp; + + int width, height; int size= PySequence_Size(args); float viewMatrix[16]; float projectionMatrix[16]; + + float cameraPos[3]; + float targetPos[3]; + float cameraUp[3]; + + float left, right, bottom, top, aspect; + float nearVal = .001; + float farVal = 1000; // inialize cmd b3SharedMemoryCommandHandle command; @@ -1035,6 +1071,46 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) } } + if (size==5) // set camera resoluation and view and projection matrix + { + if (PyArg_ParseTuple(args, "iiOOO", &width, &height, &objCameraPos, &objTargetPos, &objCameraUp)) + { + b3RequestCameraImageSetPixelResolution(command,width,height); + if (pybullet_internalSetVector(objCameraPos, cameraPos) && + pybullet_internalSetVector(objTargetPos, targetPos) && + pybullet_internalSetVector(objCameraUp, cameraUp)) + { + printf("\ncamera pos:\n"); + for(int i =0;i<3; i++) { + printf(" %f", cameraPos[i]); + } + + printf("\ntargetPos pos:\n"); + for(int i =0;i<3; i++) { + printf(" %f", targetPos[i]); + } + + printf("\ncameraUp pos:\n"); + for(int i =0;i<3; i++) { + printf(" %f", cameraUp[i]); + } + printf("\n"); + b3RequestCameraImageSetViewMatrix(command, cameraPos, targetPos, cameraUp); + printf("\n"); + + } + aspect = width/height; + left = -aspect * nearVal; + right = aspect * nearVal; + bottom = -nearVal; + top = nearVal; + + b3RequestCameraImageSetProjectionMatrix(command, left, right, bottom, top, nearVal, farVal); + printf("\n"); + + } + } + if (b3CanSubmitCommand(sm)) { b3SharedMemoryStatusHandle statusHandle; From 013dbda023eb728646c98d4d666c3dbba8a67a3c Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sun, 26 Jun 2016 18:18:30 -0700 Subject: [PATCH 055/115] implement a few more pybullet methods: pybullet_applyExternalForce, pybullet_applyExternalTorque, pybullet_setTimeStep, pybullet_resetBasePositionAndOrientation, pybullet_getQuaternionFromEuler, pybullet_getEulerFromQuaternion --- examples/SharedMemory/PhysicsClientC_API.cpp | 47 ++ examples/SharedMemory/PhysicsClientC_API.h | 5 + .../PhysicsServerCommandProcessor.cpp | 64 ++ examples/SharedMemory/SharedMemoryCommands.h | 22 + examples/SharedMemory/SharedMemoryPublic.h | 7 + examples/SharedMemory/premake4.lua | 2 + examples/pybullet/pybullet.c | 549 +++++++++++++----- 7 files changed, 547 insertions(+), 149 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 203e0ebbe..e67a2c144 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -903,3 +903,50 @@ void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImage } } +b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient) +{ + PhysicsClient* cl = (PhysicsClient* ) physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + + command->m_type = CMD_APPLY_EXTERNAL_FORCE; + command->m_updateFlags = 0; + command->m_externalForceArguments.m_numForcesAndTorques = 0; + return (b3SharedMemoryCommandHandle) command; +} + +void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double force[3], const double position[3], int flag) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_APPLY_EXTERNAL_FORCE); + int index = command->m_externalForceArguments.m_numForcesAndTorques; + command->m_externalForceArguments.m_bodyUniqueIds[index] = bodyUniqueId; + command->m_externalForceArguments.m_linkIds[index] = linkId; + command->m_externalForceArguments.m_forceFlags[index] = EF_FORCE+flag; + for (int i = 0; i < 3; ++i) { + command->m_externalForceArguments.m_forcesAndTorques[index+i] = force[i]; + command->m_externalForceArguments.m_positions[index+i] = position[i]; + } + + command->m_externalForceArguments.m_numForcesAndTorques++; +} + +void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[3], int flag) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_APPLY_EXTERNAL_FORCE); + int index = command->m_externalForceArguments.m_numForcesAndTorques; + command->m_externalForceArguments.m_bodyUniqueIds[index] = bodyUniqueId; + command->m_externalForceArguments.m_linkIds[index] = linkId; + command->m_externalForceArguments.m_forceFlags[index] = EF_TORQUE+flag; + + for (int i = 0; i < 3; ++i) { + command->m_externalForceArguments.m_forcesAndTorques[index+i] = torque[i]; + } + command->m_externalForceArguments.m_numForcesAndTorques++; +} + diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index aee561d8f..8f57f4db9 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -159,6 +159,11 @@ b3SharedMemoryCommandHandle b3MovePickedBody(b3PhysicsClientHandle physClient, d double rayToWorldZ); b3SharedMemoryCommandHandle b3RemovePickingConstraint(b3PhysicsClientHandle physClient); +/// Apply external force at the body (or link) center of mass, in world space/Cartesian coordinates. +b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient); +void b3ApplyExternalForce(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double force[3], const double position[3], int flags); +void b3ApplyExternalTorque(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueId, int linkId, const double torque[3], int flags); + #ifdef __cplusplus } #endif diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 99b883454..6ead18363 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -2056,6 +2056,70 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm hasStatus = true; break; } + case CMD_APPLY_EXTERNAL_FORCE: + { + for (int i = 0; i < clientCmd.m_externalForceArguments.m_numForcesAndTorques; ++i) + { + InteralBodyData* body = m_data->getHandle(clientCmd.m_externalForceArguments.m_bodyUniqueIds[i]); + if (body && body->m_multiBody) + { + btMultiBody* mb = body->m_multiBody; + bool isLinkFrame = ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_LINK_FRAME)!=0); + + if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_FORCE)!=0) + { + btVector3 forceLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+0], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+1], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+2]); + btVector3 positionLocal( + clientCmd.m_externalForceArguments.m_positions[i*3+0], + clientCmd.m_externalForceArguments.m_positions[i*3+1], + clientCmd.m_externalForceArguments.m_positions[i*3+2]); + + if (clientCmd.m_externalForceArguments.m_linkIds[i] == -1) + { + btVector3 forceWorld = isLinkFrame ? forceLocal : mb->getBaseWorldTransform().getBasis()*forceLocal; + btVector3 relPosWorld = isLinkFrame ? positionLocal : mb->getBaseWorldTransform().getBasis()*positionLocal; + mb->addBaseForce(forceWorld); + mb->addBaseTorque(relPosWorld.cross(forceWorld)); + //b3Printf("apply base force of %f,%f,%f at %f,%f,%f\n", forceWorld[0],forceWorld[1],forceWorld[2],positionLocal[0],positionLocal[1],positionLocal[2]); + } else + { + int link = clientCmd.m_externalForceArguments.m_linkIds[i]; + btVector3 forceWorld = mb->getLink(link).m_cachedWorldTransform.getBasis()*forceLocal; + btVector3 relPosWorld = mb->getLink(link).m_cachedWorldTransform.getBasis()*positionLocal; + mb->addLinkForce(link, forceWorld); + mb->addLinkTorque(link,relPosWorld.cross(forceWorld)); + //b3Printf("apply link force of %f,%f,%f at %f,%f,%f\n", forceWorld[0],forceWorld[1],forceWorld[2], positionLocal[0],positionLocal[1],positionLocal[2]); + } + } + if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_TORQUE)!=0) + { + btVector3 torqueLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+0], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+1], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+2]); + + if (clientCmd.m_externalForceArguments.m_linkIds[i] == -1) + { + btVector3 torqueWorld = isLinkFrame ? torqueLocal : mb->getBaseWorldTransform().getBasis()*torqueLocal; + mb->addBaseTorque(torqueWorld); + //b3Printf("apply base torque of %f,%f,%f\n", torqueWorld[0],torqueWorld[1],torqueWorld[2]); + } else + { + int link = clientCmd.m_externalForceArguments.m_linkIds[i]; + btVector3 torqueWorld = mb->getLink(link).m_cachedWorldTransform.getBasis()*torqueLocal; + mb->addLinkTorque(link, torqueWorld); + //b3Printf("apply link torque of %f,%f,%f\n", torqueWorld[0],torqueWorld[1],torqueWorld[2]); + } + } + } + } + + SharedMemoryStatus& serverCmd =serverStatusOut; + serverCmd.m_type = CMD_CLIENT_COMMAND_COMPLETED; + hasStatus = true; + break; + } default: { b3Error("Unknown command encountered"); diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 9745b8eb6..3ddb11e91 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -319,6 +319,27 @@ struct SdfRequestInfoArgs int m_bodyUniqueId; }; +///flags for b3ApplyExternalTorque and b3ApplyExternalForce +enum EnumExternalForcePrivateFlags +{ +// EF_LINK_FRAME=1, +// EF_WORLD_FRAME=2, + EF_TORQUE=4, + EF_FORCE=8, +}; + + + +struct ExternalForceArgs +{ + int m_numForcesAndTorques; + int m_bodyUniqueIds[MAX_SDF_BODIES]; + int m_linkIds[MAX_SDF_BODIES]; + double m_forcesAndTorques[3*MAX_SDF_BODIES]; + double m_positions[3*MAX_SDF_BODIES]; + int m_forceFlags[MAX_SDF_BODIES]; +}; + enum EnumSdfRequestInfoFlags { SDF_REQUEST_INFO_BODY=1, @@ -350,6 +371,7 @@ struct SharedMemoryCommand struct RequestDebugLinesArgs m_requestDebugLinesArguments; struct RequestPixelDataArgs m_requestPixelDataArguments; struct PickBodyArgs m_pickBodyArguments; + struct ExternalForceArgs m_externalForceArguments; }; }; diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 5e6da5c50..3aeeb8f11 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -26,6 +26,7 @@ enum EnumSharedMemoryClientCommand CMD_MOVE_PICKED_BODY, CMD_REMOVE_PICKING_CONSTRAINT_BODY, CMD_REQUEST_CAMERA_IMAGE_DATA, + CMD_APPLY_EXTERNAL_FORCE, CMD_MAX_CLIENT_COMMANDS }; @@ -143,5 +144,11 @@ enum { CONTROL_MODE_POSITION_VELOCITY_PD, }; +///flags for b3ApplyExternalTorque and b3ApplyExternalForce +enum EnumExternalForceFlags +{ + EF_LINK_FRAME=1, + EF_WORLD_FRAME=2, +}; #endif//SHARED_MEMORY_PUBLIC_H diff --git a/examples/SharedMemory/premake4.lua b/examples/SharedMemory/premake4.lua index e923b412f..34aea2de5 100644 --- a/examples/SharedMemory/premake4.lua +++ b/examples/SharedMemory/premake4.lua @@ -26,6 +26,8 @@ files { "PhysicsServer.h", "main.cpp", "PhysicsClientC_API.cpp", + "SharedMemoryCommands.h", + "SharedMemoryPublic.h", "PhysicsServer.cpp", "PosixSharedMemory.cpp", "Win32SharedMemory.cpp", diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 78e770dbe..5cdf39a59 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -437,6 +437,36 @@ pybullet_setGravity(PyObject* self, PyObject* args) return Py_None; } +static PyObject * +pybullet_setTimeStep(PyObject* self, PyObject* args) +{ + if (0==sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + double timeStep=0.001; + int ret; + + b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); + b3SharedMemoryStatusHandle statusHandle; + + if (!PyArg_ParseTuple(args, "d", &timeStep)) + { + PyErr_SetString(SpamError, "setTimeStep expected a single value (double)."); + return NULL; + } + ret = b3PhysicsParamSetTimeStep(command, timeStep); + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + //ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); + } + + Py_INCREF(Py_None); + return Py_None; +} + // Internal function used to get the base position and orientation @@ -632,140 +662,88 @@ pybullet_resetJointState(PyObject* self, PyObject* args) return NULL; } - - -// CURRENTLY NOT SUPPORTED -// Initalize a single joint position for a specific body index -// -// This method skips any physics simulation and -// teleports all joints to the new positions. - -// TODO(hellojas): initializing one joint currently not supported -// static PyObject* -// pybullet_initializeJointPosition(PyObject* self, PyObject* args) -// { -// if (0==sm) -// { -// PyErr_SetString(SpamError, "Not connected to physics server."); -// return NULL; -// } -// -// int i; -// int bodyIndex = -1; -// int jointIndex = -1; -// double jointPos = 0.0; -// -// int size= PySequence_Size(args); -// -// if (size==3) // get body index, joint index, and joint position value -// { -// if (PyArg_ParseTuple(args, "iid", &bodyIndex, &jointIndex, &jointPos)) -// { -// b3SharedMemoryCommandHandle cmd_handle = b3CreatePoseCommandInit(sm, bodyIndex); -// -// // printf("initializing joint %d at %f\n", jointIndex, jointPos); -// b3CreatePoseCommandSetJointPosition(sm, cmd_handle, jointIndex, jointPos); -// -// b3SharedMemoryStatusHandle status_handle = -// b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); -// -// const int status_type = b3GetStatusType(status_handle); -// -// } -// } -// -// Py_INCREF(Py_None); -// return Py_None; -// } -#if 0 -static void pybullet_internalGetJointPositions(int bodyIndex, int numJoints, double jointPositions[]) { - int i, j; - int numDegreeQ; - int numDegreeU; - int arrSizeOfPosAndOrn = 7; - - for (i =0;i euler yaw/pitch/roll convention from URDF/SDF, see Gazebo +///https://github.com/arpg/Gazebo/blob/master/gazebo/math/Quaternion.cc +static PyObject* pybullet_getEulerFromQuaternion(PyObject* self, PyObject* args) +{ + + double squ; + double sqx; + double sqy; + double sqz; + + double quat[4]; + + PyObject* quatObj; + + if (PyArg_ParseTuple(args, "O", &quatObj)) + { + PyObject* seq; + int len,i; + seq = PySequence_Fast(quatObj, "expected a sequence"); + len = PySequence_Size(quatObj); + if (len==4) + { + for (i = 0; i < 4; i++) + { + quat[i] = pybullet_internalGetFloatFromSequence(seq,i); + } + } else + { + PyErr_SetString(SpamError, "Quaternion need a 4 components [x,y,z,w]."); + Py_DECREF(seq); + return NULL; + } + Py_DECREF(seq); + } else + { + PyErr_SetString(SpamError, "Quaternion need a 4 components [x,y,z,w]."); + return NULL; + } + + { + double rpy[3]; + sqx = quat[0] * quat[0]; + sqy = quat[1] * quat[1]; + sqz = quat[2] * quat[2]; + squ = quat[3] * quat[3]; + rpy[0] = atan2(2 * (quat[1]*quat[2] + quat[3]*quat[0]), squ - sqx - sqy + sqz); + double sarg = -2 * (quat[0]*quat[2] - quat[3] * quat[1]); + rpy[1] = sarg <= -1.0 ? -0.5*3.141592538 : (sarg >= 1.0 ? 0.5*3.141592538 : asin(sarg)); + rpy[2] = atan2(2 * (quat[0]*quat[1] + quat[3]*quat[2]), squ + sqx - sqy - sqz); + { + PyObject *pylist; + int i; + pylist = PyTuple_New(3); + for (i=0;i<3;i++) + PyTuple_SetItem(pylist,i,PyFloat_FromDouble(rpy[i])); + return pylist; + } + } + Py_INCREF(Py_None); + return Py_None; +} + static PyMethodDef SpamMethods[] = { @@ -1109,6 +1343,9 @@ static PyMethodDef SpamMethods[] = { {"setGravity", pybullet_setGravity, METH_VARARGS, "Set the gravity acceleration (x,y,z)."}, + {"setTimeStep", pybullet_setTimeStep, METH_VARARGS, + "Set the amount of time to proceed at each call to stepSimulation. (unit is seconds, typically range is 0.01 or 0.001)"}, + {"loadURDF", pybullet_loadURDF, METH_VARARGS, "Create a multibody by loading a URDF file."}, @@ -1118,8 +1355,8 @@ static PyMethodDef SpamMethods[] = { {"getBasePositionAndOrientation", pybullet_getBasePositionAndOrientation, METH_VARARGS, "Get the world position and orientation of the base of the object. (x,y,z) position vector and (x,y,z,w) quaternion orientation."}, -// {"resetBasePositionAndOrientation", pybullet_getBasePositionAndOrientation, METH_VARARGS, -// "Reset the world position and orientation of the base of the object instantaneously, not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation."}, + {"resetBasePositionAndOrientation", pybullet_resetBasePositionAndOrientation, METH_VARARGS, + "Reset the world position and orientation of the base of the object instantaneously, not through physics simulation. (x,y,z) position vector and (x,y,z,w) quaternion orientation."}, {"getNumJoints", pybullet_getNumJoints, METH_VARARGS, "Get the number of joints for an object."}, @@ -1136,18 +1373,29 @@ static PyMethodDef SpamMethods[] = { {"setJointMotorControl", pybullet_setJointMotorControl, METH_VARARGS, "Set a single joint motor control mode and desired target value. There is no immediate state change, stepSimulation will process the motors."}, + {"applyExternalForce", pybullet_applyExternalForce, METH_VARARGS, + "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"}, + + {"applyExternalTorque", pybullet_applyExternalTorque, METH_VARARGS, + "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"}, + + {"renderImage", pybullet_renderImage, METH_VARARGS, + "Render an image (given the pixel resolution width & height and camera view & projection matrices), and return the 8-8-8bit RGB pixel data and floating point depth values"}, + + {"getQuaternionFromEuler", pybullet_getQuaternionFromEuler, METH_VARARGS, + "Convert Euler [roll, pitch, yaw] as in URDF/SDF convention, to quaternion [x,y,z,w]"}, + + {"getEulerFromQuaternion", pybullet_getEulerFromQuaternion, METH_VARARGS, + "Convert quaternion [x,y,z,w] to Euler [roll, pitch, yaw] as in URDF/SDF convention"}, + + //todo(erwincoumans) //saveSnapshot //loadSnapshot + ////todo(erwincoumans) //collision info //raycast info - - //applyBaseForce - //applyLinkForce - - {"renderImage", pybullet_renderImage, METH_VARARGS, - "Render an image (given the pixel resolution width & height and camera view & projection matrices), and return the 8-8-8bit RGB pixel data and floating point depth values"}, - + {NULL, NULL, 0, NULL} /* Sentinel */ }; @@ -1155,7 +1403,7 @@ static PyMethodDef SpamMethods[] = { static struct PyModuleDef moduledef = { PyModuleDef_HEAD_INIT, "pybullet", /* m_name */ - "Python bindings for Bullet", /* m_doc */ + "Python bindings for Bullet Physics Robotics API (also known as Shared Memory API)", /* m_doc */ -1, /* m_size */ SpamMethods, /* m_methods */ NULL, /* m_reload */ @@ -1198,6 +1446,9 @@ initpybullet(void) PyModule_AddIntConstant (m, "VELOCITY_CONTROL", CONTROL_MODE_VELOCITY); // user read PyModule_AddIntConstant (m, "POSITION_CONTROL", CONTROL_MODE_POSITION_VELOCITY_PD); // user read + PyModule_AddIntConstant (m, "LINK_FRAME", EF_LINK_FRAME); + PyModule_AddIntConstant (m, "WORLD_FRAME", EF_WORLD_FRAME); + SpamError = PyErr_NewException("pybullet.error", NULL, NULL); Py_INCREF(SpamError); PyModule_AddObject(m, "error", SpamError); From e16082a7cd83de3bf28ac59434140d5789207f18 Mon Sep 17 00:00:00 2001 From: Benjamin Ellenberger Date: Mon, 27 Jun 2016 15:14:36 +0200 Subject: [PATCH 056/115] Refactor Newton's Cradle. Implement Newton's Cradle with Softbody ropes. --- examples/ExampleBrowser/CMakeLists.txt | 2 + examples/ExampleBrowser/ExampleEntries.cpp | 2 + examples/ExtendedTutorials/NewtonsCradle.cpp | 27 +- examples/ExtendedTutorials/NewtonsCradle.h | 6 +- .../ExtendedTutorials/NewtonsRopeCradle.cpp | 345 ++++++++++++++++++ .../ExtendedTutorials/NewtonsRopeCradle.h | 22 ++ 6 files changed, 385 insertions(+), 19 deletions(-) create mode 100644 examples/ExtendedTutorials/NewtonsRopeCradle.cpp create mode 100644 examples/ExtendedTutorials/NewtonsRopeCradle.h diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index 0af74fdb8..0546f1418 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -171,6 +171,8 @@ SET(BulletExampleBrowser_SRCS ../ExtendedTutorials/SimpleJoint.h ../ExtendedTutorials/NewtonsCradle.cpp ../ExtendedTutorials/NewtonsCradle.h + ../ExtendedTutorials/NewtonsRopeCradle.cpp + ../ExtendedTutorials/NewtonsRopeCradle.h ../ExtendedTutorials/InclinedPlane.cpp ../ExtendedTutorials/InclinedPlane.h ../ExtendedTutorials/MultiPendulum.cpp diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index 10cfe33ee..97bb1ad26 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -66,6 +66,7 @@ #include "../ExtendedTutorials/RigidBodyFromObj.h" #include "../ExtendedTutorials/InclinedPlane.h" #include "../ExtendedTutorials/NewtonsCradle.h" +#include "../ExtendedTutorials/NewtonsRopeCradle.h" #include "../ExtendedTutorials/MultiPendulum.h" struct ExampleEntry @@ -279,6 +280,7 @@ static ExampleEntry gDefaultExamples[]= ExampleEntry(1,"Simple Bridge", "Create a simple bridge using a pair of point2point/distance constraints. You may click and drag any plank to see the bridge respond.", ET_BridgeCreateFunc), ExampleEntry(1,"Inclined Plane", "Create an inclined plane to show restitution and different types of friction. Use the sliders to vary restitution and friction and press space to reset the scene.", ET_InclinedPlaneCreateFunc), ExampleEntry(1,"Newton's Cradle", "Create a Newton's Cradle using a pair of point2point/slider constraints. Press 1/2 to lengthen/shorten the pendula, press 3 to displace pendula. Use the sliders to select the number of pendula in total (reset simulation), the number of displaced pendula and other options.", ET_NewtonsCradleCreateFunc), + ExampleEntry(1,"Newton's Rope Cradle", "Create a Newton's Cradle using ropes. Press 3 to displace pendula. Use the sliders to select the number of pendula in total (reset simulation) and the number of displaced pendula.",ET_NewtonsRopeCradleCreateFunc), ExampleEntry(1,"Multi-Pendulum", "Create a Multi-Pendulum using point2point/slider constraints. Press 1/2 to lengthen/shorten the pendula, press 3 to displace pendula. Use the sliders to select the number of pendula in total (reset simulation), the number of displaced pendula and other options.",ET_MultiPendulumCreateFunc), diff --git a/examples/ExtendedTutorials/NewtonsCradle.cpp b/examples/ExtendedTutorials/NewtonsCradle.cpp index a1c51f1fe..a8b8d5773 100644 --- a/examples/ExtendedTutorials/NewtonsCradle.cpp +++ b/examples/ExtendedTutorials/NewtonsCradle.cpp @@ -30,7 +30,7 @@ static btScalar gPendulaQty = 5; // Number of pendula in newton's cradle static btScalar gDisplacedPendula = 1; // number of displaced pendula //TODO: This is an int as well -static btScalar gPendulaRestitution = 1; // pendula restition when hitting against each other +static btScalar gPendulaRestitution = 1; // pendula restitution when hitting against each other static btScalar gSphereRadius = 1; // pendula radius @@ -48,8 +48,7 @@ struct NewtonsCradleExample: public CommonRigidBodyBase { } virtual void initPhysics(); virtual void renderScene(); - virtual void createPendulum(btSphereShape* colShape, btScalar xPosition, - btScalar yPosition, btScalar zPosition, btScalar length, btScalar mass); + virtual void createPendulum(btSphereShape* colShape, btVector3 position, btScalar length, btScalar mass); virtual void changePendulaLength(btScalar length); virtual void changePendulaRestitution(btScalar restitution); virtual void stepSimulation(float deltaTime); @@ -139,12 +138,11 @@ void NewtonsCradleExample::initPhysics() { + btIDebugDraw::DBG_DrawConstraints + btIDebugDraw::DBG_DrawConstraintLimits); - { // create the pendulum starting at the indicated position below and where each pendulum has the following mass + { // create the pendula starting at the indicated position below and where each pendulum has the following mass btScalar pendulumMass(1.f); - btScalar xPosition(0.0f); // initial left-most pendulum position - btScalar yPosition(15.0f); - btScalar zPosition(0.0f); + btVector3 position(0.0f,15.0f,0.0f); // initial left-most pendulum position + btQuaternion orientation(0,0,0,1); // orientation of the pendula // Re-using the same collision is better for memory usage and performance btSphereShape* pendulumShape = new btSphereShape(gSphereRadius); @@ -153,11 +151,10 @@ void NewtonsCradleExample::initPhysics() { for (int i = 0; i < floor(gPendulaQty); i++) { // create pendulum - createPendulum(pendulumShape, xPosition, yPosition, zPosition, - gInitialPendulumLength, pendulumMass); + createPendulum(pendulumShape, position, gInitialPendulumLength, pendulumMass); // displace the pendula 1.05 sphere size, so that they all nearly touch (small spacings in between - xPosition -= 2.1f * gSphereRadius; + position.setX(position.x()-2.1f * gSphereRadius); } } @@ -171,8 +168,7 @@ void NewtonsCradleExample::stepSimulation(float deltaTime) { } -void NewtonsCradleExample::createPendulum(btSphereShape* colShape, - btScalar xPosition, btScalar yPosition, btScalar zPosition, btScalar length, btScalar mass) { +void NewtonsCradleExample::createPendulum(btSphereShape* colShape,btVector3 position, btScalar length, btScalar mass) { // The pendulum looks like this (names when built): // O topSphere @@ -184,15 +180,14 @@ void NewtonsCradleExample::createPendulum(btSphereShape* colShape, startTransform.setIdentity(); // position the top sphere above ground with a moving x position - startTransform.setOrigin( - btVector3(btScalar(xPosition), btScalar(yPosition), btScalar(zPosition))); + startTransform.setOrigin(position); startTransform.setRotation(btQuaternion(0, 0, 0, 1)); // zero rotation btRigidBody* topSphere = createRigidBody(mass, startTransform, colShape); // position the bottom sphere below the top sphere startTransform.setOrigin( - btVector3(btScalar(xPosition), btScalar(yPosition - length), - btScalar(zPosition))); + btVector3(position.x(), btScalar(position.y() - length), + position.z())); startTransform.setRotation(btQuaternion(0, 0, 0, 1)); // zero rotation btRigidBody* bottomSphere = createRigidBody(mass, startTransform, colShape); diff --git a/examples/ExtendedTutorials/NewtonsCradle.h b/examples/ExtendedTutorials/NewtonsCradle.h index 9b9e2f247..028754f7e 100644 --- a/examples/ExtendedTutorials/NewtonsCradle.h +++ b/examples/ExtendedTutorials/NewtonsCradle.h @@ -13,10 +13,10 @@ subject to the following restrictions: 3. This notice may not be removed or altered from any source distribution. */ -#ifndef ET_NEWTONIAN_PENDULUM_EXAMPLE_H -#define ET_NEWTONIAN_PENDULUM_EXAMPLE_H +#ifndef ET_NEWTONS_CRADLE_EXAMPLE_H +#define ET_NEWTONS_CRADLE_EXAMPLE_H class CommonExampleInterface* ET_NewtonsCradleCreateFunc(struct CommonExampleOptions& options); -#endif //ET_NEWTONIAN_PENDULUM_EXAMPLE_H +#endif //ET_NEWTONS_CRADLE_EXAMPLE_H diff --git a/examples/ExtendedTutorials/NewtonsRopeCradle.cpp b/examples/ExtendedTutorials/NewtonsRopeCradle.cpp new file mode 100644 index 000000000..d0a4b86a9 --- /dev/null +++ b/examples/ExtendedTutorials/NewtonsRopeCradle.cpp @@ -0,0 +1,345 @@ +/* + Bullet Continuous Collision Detection and Physics Library + Copyright (c) 2015 Google Inc. http://bulletphysics.org + + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + */ + +#include "NewtonsRopeCradle.h" + +#include // TODO: Should I use another data structure? +#include + +#include "btBulletDynamicsCommon.h" +#include "LinearMath/btVector3.h" +#include "LinearMath/btAlignedObjectArray.h" +#include "../CommonInterfaces/CommonRigidBodyBase.h" + +#include "BulletSoftBody/btSoftRigidDynamicsWorld.h" +#include "BulletSoftBody/btSoftBodyHelpers.h" +#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" +#include "../CommonInterfaces/CommonParameterInterface.h" + +static btScalar gPendulaQty = 5; // Number of pendula in newton's cradle +//TODO: This would actually be an Integer, but the Slider does not like integers, so I floor it when changed + +static btScalar gDisplacedPendula = 1; // number of displaced pendula +//TODO: This is an int as well + +static btScalar gPendulaRestitution = 1; // pendula restition when hitting against each other + +static btScalar gSphereRadius = 1; // pendula radius + +static btScalar gInitialPendulumWidth = 4; // default pendula width + +static btScalar gInitialPendulumHeight = 8; // default pendula height + +static btScalar gRopeResolution = 1; // default rope resolution (number of links as in a chain) + +static btScalar gForcingForce = 30; // default force to displace the pendula + +struct NewtonsRopeCradleExample : public CommonRigidBodyBase { + NewtonsRopeCradleExample(struct GUIHelperInterface* helper) : + CommonRigidBodyBase(helper) { + } + virtual ~NewtonsRopeCradleExample(){} + virtual void initPhysics(); + virtual void renderScene(); + void createEmptyDynamicsWorld() + { + m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + + m_broadphase = new btDbvtBroadphase(); + + m_solver = new btSequentialImpulseConstraintSolver; + + m_dynamicsWorld = new btSoftRigidDynamicsWorld(m_dispatcher, m_broadphase, m_solver, m_collisionConfiguration); + m_dynamicsWorld->setGravity(btVector3(0, -10, 0)); + + softBodyWorldInfo.m_broadphase = m_broadphase; + softBodyWorldInfo.m_dispatcher = m_dispatcher; + softBodyWorldInfo.m_gravity = m_dynamicsWorld->getGravity(); + softBodyWorldInfo.m_sparsesdf.Initialize(); + } + + virtual void createRopePendulum(btSphereShape* colShape, + btVector3 position, btQuaternion pendulumOrientation, btScalar width, btScalar height, btScalar mass); + virtual void changePendulaRestitution(btScalar restitution); + virtual void connectWithRope(btRigidBody* body1, btRigidBody* body2); + virtual bool keyboardCallback(int key, int state); + + virtual btSoftRigidDynamicsWorld* getSoftDynamicsWorld() + { + ///just make it a btSoftRigidDynamicsWorld please + ///or we will add type checking + return (btSoftRigidDynamicsWorld*) m_dynamicsWorld; + } + void resetCamera() + { + float dist = 41; + float pitch = 52; + float yaw = 35; + float targetPos[3]={0,0.46,0}; + m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]); + } + + std::vector constraints; + std::vector pendula; + + btSoftBodyWorldInfo softBodyWorldInfo; + +}; + +static NewtonsRopeCradleExample* nex = NULL; + +void onRopePendulaRestitutionChanged(float pendulaRestitution); + +void floorRSliderValue(float notUsed); + +void NewtonsRopeCradleExample::initPhysics() +{ + + { // create a slider to change the number of pendula + SliderParams slider("Number of Pendula", &gPendulaQty); + slider.m_minVal = 1; + slider.m_maxVal = 50; + slider.m_callback = floorRSliderValue; // hack to get integer values + slider.m_clampToNotches = false; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter( + slider); + } + + { // create a slider to change the number of displaced pendula + SliderParams slider("Number of Displaced Pendula", &gDisplacedPendula); + slider.m_minVal = 0; + slider.m_maxVal = 49; + slider.m_callback = floorRSliderValue; // hack to get integer values + slider.m_clampToNotches = false; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter( + slider); + } + + { // create a slider to change the pendula restitution + SliderParams slider("Pendula Restitution", &gPendulaRestitution); + slider.m_minVal = 0; + slider.m_maxVal = 1; + slider.m_clampToNotches = false; + slider.m_callback = onRopePendulaRestitutionChanged; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter( + slider); + } + + { // create a slider to change the rope resolution + SliderParams slider("Rope Resolution", &gRopeResolution); + slider.m_minVal = 1; + slider.m_maxVal = 20; + slider.m_clampToNotches = false; + slider.m_callback = floorRSliderValue; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter( + slider); + } + + { // create a slider to change the pendulum width + SliderParams slider("Pendulum Width", &gInitialPendulumWidth); + slider.m_minVal = 0; + slider.m_maxVal = 40; + slider.m_clampToNotches = false; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter( + slider); + } + + { // create a slider to change the pendulum height + SliderParams slider("Pendulum Height", &gInitialPendulumHeight); + slider.m_minVal = 0; + slider.m_maxVal = 40; + slider.m_clampToNotches = false; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter( + slider); + } + + { // create a slider to change the force to displace the lowest pendulum + SliderParams slider("Displacement force", &gForcingForce); + slider.m_minVal = 0.1; + slider.m_maxVal = 200; + slider.m_clampToNotches = false; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter( + slider); + } + + m_guiHelper->setUpAxis(1); + + createEmptyDynamicsWorld(); + + // create a debug drawer + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + if (m_dynamicsWorld->getDebugDrawer()) + m_dynamicsWorld->getDebugDrawer()->setDebugMode( + btIDebugDraw::DBG_DrawWireframe + + btIDebugDraw::DBG_DrawContactPoints + + btIDebugDraw::DBG_DrawConstraints + + btIDebugDraw::DBG_DrawConstraintLimits); + + { // create the pendula starting at the indicated position below and where each pendulum has the following mass + btScalar pendulumMass(1.0f); + + btVector3 position(0.0f,15.0f,0.0f); // initial left-most pendulum position + btQuaternion orientation(0,0,0,1); // orientation of the pendula + + // Re-using the same collision is better for memory usage and performance + btSphereShape* pendulumShape = new btSphereShape(gSphereRadius); + m_collisionShapes.push_back(pendulumShape); + + for (int i = 0; i < floor(gPendulaQty); i++) { + + // create pendulum + createRopePendulum(pendulumShape, position, orientation,gInitialPendulumWidth, + gInitialPendulumHeight, pendulumMass); + + // displace the pendula 1.05 sphere size, so that they all nearly touch (small spacings in between) + position.setX(position.x()-2.1f * gSphereRadius); + } + } + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + +void NewtonsRopeCradleExample::connectWithRope(btRigidBody* body1, btRigidBody* body2) +{ + btSoftBody* softBodyRope0 = btSoftBodyHelpers::CreateRope(softBodyWorldInfo,body1->getWorldTransform().getOrigin(),body2->getWorldTransform().getOrigin(),gRopeResolution,0); + softBodyRope0->setTotalMass(0.1f); + + softBodyRope0->appendAnchor(0,body1); + softBodyRope0->appendAnchor(softBodyRope0->m_nodes.size()-1,body2); + + softBodyRope0->m_cfg.piterations = 5; + softBodyRope0->m_cfg.kDP = 0.005f; + softBodyRope0->m_cfg.kSHR = 1; + softBodyRope0->m_cfg.kCHR = 1; + softBodyRope0->m_cfg.kKHR = 1; + + getSoftDynamicsWorld()->addSoftBody(softBodyRope0); +} + +void NewtonsRopeCradleExample::createRopePendulum(btSphereShape* colShape, + btVector3 position, btQuaternion pendulumOrientation, btScalar width, btScalar height, btScalar mass) { + + // The pendulum looks like this (names when built): + // O O topSphere1 topSphere2 + // \ / + // O bottomSphere + + //create a dynamic pendulum + btTransform startTransform; + startTransform.setIdentity(); + + // calculate sphere positions + btVector3 topSphere1RelPosition(0,0,width); + btVector3 topSphere2RelPosition(0,0,-width); + btVector3 bottomSphereRelPosition(0,-height,0); + + + // position the top sphere above ground with appropriate orientation + startTransform.setOrigin(btVector3(0,0,0)); // no translation intitially + startTransform.setRotation(pendulumOrientation); // pendulum rotation + startTransform.setOrigin(startTransform * topSphere1RelPosition); // rotate this position + startTransform.setOrigin(position + startTransform.getOrigin()); // add non-rotated position to the relative position + btRigidBody* topSphere1 = createRigidBody(0, startTransform, colShape); // make top sphere static + + // position the top sphere above ground with appropriate orientation + startTransform.setOrigin(btVector3(0,0,0)); // no translation intitially + startTransform.setRotation(pendulumOrientation); // pendulum rotation + startTransform.setOrigin(startTransform * topSphere2RelPosition); // rotate this position + startTransform.setOrigin(position + startTransform.getOrigin()); // add non-rotated position to the relative position + btRigidBody* topSphere2 = createRigidBody(0, startTransform, colShape); // make top sphere static + + // position the bottom sphere below the top sphere + startTransform.setOrigin(btVector3(0,0,0)); // no translation intitially + startTransform.setRotation(pendulumOrientation); // pendulum rotation + startTransform.setOrigin(startTransform * bottomSphereRelPosition); // rotate this position + startTransform.setOrigin(position + startTransform.getOrigin()); // add non-rotated position to the relative position + btRigidBody* bottomSphere = createRigidBody(mass, startTransform, colShape); + bottomSphere->setFriction(0); // we do not need friction here + pendula.push_back(bottomSphere); + + // disable the deactivation when objects do not move anymore + topSphere1->setActivationState(DISABLE_DEACTIVATION); + topSphere2->setActivationState(DISABLE_DEACTIVATION); + bottomSphere->setActivationState(DISABLE_DEACTIVATION); + + bottomSphere->setRestitution(gPendulaRestitution); // set pendula restitution + + // add ropes between spheres + connectWithRope(topSphere1, bottomSphere); + connectWithRope(topSphere2, bottomSphere); +} + +void NewtonsRopeCradleExample::renderScene() +{ + CommonRigidBodyBase::renderScene(); + btSoftRigidDynamicsWorld* softWorld = getSoftDynamicsWorld(); + + for ( int i=0;igetSoftBodyArray().size();i++) + { + btSoftBody* psb=(btSoftBody*)softWorld->getSoftBodyArray()[i]; + //if (softWorld->getDebugDrawer() && !(softWorld->getDebugDrawer()->getDebugMode() & (btIDebugDraw::DBG_DrawWireframe))) + { + btSoftBodyHelpers::DrawFrame(psb,softWorld->getDebugDrawer()); + btSoftBodyHelpers::Draw(psb,softWorld->getDebugDrawer(),softWorld->getDrawFlags()); + } + } +} + +void NewtonsRopeCradleExample::changePendulaRestitution(btScalar restitution) { + for (std::vector::iterator rit = pendula.begin(); + rit != pendula.end(); rit++) { + btAssert((*rit) && "Null constraint"); + + (*rit)->setRestitution(restitution); + } +} + +bool NewtonsRopeCradleExample::keyboardCallback(int key, int state) { + //b3Printf("Key pressed: %d in state %d \n",key,state); + + // key 3 + switch (key) { + case 51 /*ASCII for 3*/: { + for (int i = 0; i < gDisplacedPendula; i++) { + if (gDisplacedPendula >= 0 && gDisplacedPendula <= gPendulaQty) + pendula[i]->applyCentralForce(btVector3(gForcingForce, 0, 0)); + } + return true; + } + } + + return false; +} + +// GUI parameter modifiers + +void onRopePendulaRestitutionChanged(float pendulaRestitution) { + if (nex){ + nex->changePendulaRestitution(pendulaRestitution); + } +} + +void floorRSliderValue(float notUsed) { + gPendulaQty = floor(gPendulaQty); + gDisplacedPendula = floor(gDisplacedPendula); + gRopeResolution = floor(gRopeResolution); +} + +CommonExampleInterface* ET_NewtonsRopeCradleCreateFunc( + CommonExampleOptions& options) { + nex = new NewtonsRopeCradleExample(options.m_guiHelper); + return nex; +} diff --git a/examples/ExtendedTutorials/NewtonsRopeCradle.h b/examples/ExtendedTutorials/NewtonsRopeCradle.h new file mode 100644 index 000000000..3edbcd5af --- /dev/null +++ b/examples/ExtendedTutorials/NewtonsRopeCradle.h @@ -0,0 +1,22 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2015 Google Inc. http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + +#ifndef ET_NEWTONS_ROPE_CRADLE_EXAMPLE_H +#define ET_NEWTONS_ROPE_CRADLE_EXAMPLE_H + +class CommonExampleInterface* ET_NewtonsRopeCradleCreateFunc(struct CommonExampleOptions& options); + + +#endif //ET_NEWTONS_ROPE_CRADLE_EXAMPLE_H From 5d5e7df7c5bc93ef4b1b23c464aeb4d994e6379d Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Mon, 27 Jun 2016 11:19:57 -0700 Subject: [PATCH 057/115] exposing near/far values as params; commented out debug printf which caused failed checks --- examples/pybullet/pybullet.c | 42 +++++++++++++++++++----------------- 1 file changed, 22 insertions(+), 20 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index bf55cc46a..aa0115e95 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1033,8 +1033,9 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) float cameraUp[3]; float left, right, bottom, top, aspect; - float nearVal = .001; - float farVal = 1000; + float nearVal, farVal; + // float nearVal = .001; + // float farVal = 1000; // inialize cmd b3SharedMemoryCommandHandle command; @@ -1073,32 +1074,33 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) if (size==5) // set camera resoluation and view and projection matrix { - if (PyArg_ParseTuple(args, "iiOOO", &width, &height, &objCameraPos, &objTargetPos, &objCameraUp)) + if (PyArg_ParseTuple(args, "iiOOOii", &width, &height, &objCameraPos, &objTargetPos, &objCameraUp, &nearVal, %farVal)) { b3RequestCameraImageSetPixelResolution(command,width,height); if (pybullet_internalSetVector(objCameraPos, cameraPos) && pybullet_internalSetVector(objTargetPos, targetPos) && pybullet_internalSetVector(objCameraUp, cameraUp)) { - printf("\ncamera pos:\n"); - for(int i =0;i<3; i++) { - printf(" %f", cameraPos[i]); - } - - printf("\ntargetPos pos:\n"); - for(int i =0;i<3; i++) { - printf(" %f", targetPos[i]); - } - - printf("\ncameraUp pos:\n"); - for(int i =0;i<3; i++) { - printf(" %f", cameraUp[i]); - } - printf("\n"); + // printf("\ncamera pos:\n"); + // for(int i =0;i<3; i++) { + // printf(" %f", cameraPos[i]); + // } + // + // printf("\ntargetPos pos:\n"); + // for(int i =0;i<3; i++) { + // printf(" %f", targetPos[i]); + // } + // + // printf("\ncameraUp pos:\n"); + // for(int i =0;i<3; i++) { + // printf(" %f", cameraUp[i]); + // } + // printf("\n"); b3RequestCameraImageSetViewMatrix(command, cameraPos, targetPos, cameraUp); - printf("\n"); + // printf("\n"); } + aspect = width/height; left = -aspect * nearVal; right = aspect * nearVal; @@ -1106,7 +1108,7 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) top = nearVal; b3RequestCameraImageSetProjectionMatrix(command, left, right, bottom, top, nearVal, farVal); - printf("\n"); + // printf("\n"); } } From e24ec9e8c0eaa0225a774d08796f9c739c7eedab Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Mon, 27 Jun 2016 13:18:12 -0700 Subject: [PATCH 058/115] nearVal and farVal as params --- examples/pybullet/pybullet.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index aa0115e95..c12085b30 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1074,7 +1074,7 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) if (size==5) // set camera resoluation and view and projection matrix { - if (PyArg_ParseTuple(args, "iiOOOii", &width, &height, &objCameraPos, &objTargetPos, &objCameraUp, &nearVal, %farVal)) + if (PyArg_ParseTuple(args, "iiOOOii", &width, &height, &objCameraPos, &objTargetPos, &objCameraUp, &nearVal, &farVal)) { b3RequestCameraImageSetPixelResolution(command,width,height); if (pybullet_internalSetVector(objCameraPos, cameraPos) && From f6bead7152028c9ae0a0cbb0fbbf6ee2375c1a4c Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Mon, 27 Jun 2016 13:51:28 -0700 Subject: [PATCH 059/115] edit method definitions (docstring) for calling renderImage() --- examples/pybullet/pybullet.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index c12085b30..c8d2bef04 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1225,7 +1225,7 @@ static PyMethodDef SpamMethods[] = { //applyLinkForce {"renderImage", pybullet_renderImage, METH_VARARGS, - "Render an image (given the pixel resolution width & height and camera view & projection matrices), and return the 8-8-8bit RGB pixel data and floating point depth values"}, + "Render an image (given the pixel resolution width, height, view matrix, projection matrix, near and far vlues), and return the 8-8-8bit RGB pixel data and floating point depth values"}, {NULL, NULL, 0, NULL} /* Sentinel */ }; From 178dd54ca547dddf4891e4fba2420927a47b8076 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 27 Jun 2016 16:10:13 -0700 Subject: [PATCH 060/115] remove printf's and fix an issue in btMultiJointMotor in previous commit --- .../Featherstone/btMultiBodyJointMotor.cpp | 12 +++--------- .../Featherstone/btMultiBodyJointMotor.h | 4 ++-- 2 files changed, 5 insertions(+), 11 deletions(-) diff --git a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp index 3d0f45b77..86c7d3a74 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp @@ -25,7 +25,7 @@ btMultiBodyJointMotor::btMultiBodyJointMotor(btMultiBody* body, int link, btScal :btMultiBodyConstraint(body,body,link,body->getLink(link).m_parent,1,true), m_desiredVelocity(desiredVelocity), m_desiredPosition(0), - m_kd(0.1), + m_kd(1.), m_kp(0) { @@ -56,7 +56,7 @@ btMultiBodyJointMotor::btMultiBodyJointMotor(btMultiBody* body, int link, int li :btMultiBodyConstraint(body,body,link,body->getLink(link).m_parent,1,true), m_desiredVelocity(desiredVelocity), m_desiredPosition(0), - m_kd(0.1), + m_kd(1.), m_kp(0) { btAssert(linkDoF < body->getLink(link).m_dofCount); @@ -125,13 +125,7 @@ void btMultiBodyJointMotor::createConstraintRows(btMultiBodyConstraintArray& con btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; btScalar positionStabiliationTerm = (m_desiredPosition-currentPosition)/infoGlobal.m_timeStep; btScalar velocityError = (m_desiredVelocity - currentVelocity); - btScalar rhs = m_kp * positionStabiliationTerm + m_kd * velocityError; - printf("m_kd = %f\n", m_kd); - printf("m_kp = %f\n", m_kp); - printf("m_desiredVelocity = %f\n", m_desiredVelocity); - printf("m_desiredPosition = %f\n", m_desiredPosition); - printf("m_maxAppliedImpulse = %f\n", m_maxAppliedImpulse); - printf("rhs = %f\n", rhs); + btScalar rhs = m_kp * positionStabiliationTerm + currentVelocity+m_kd * velocityError; fillMultiBodyConstraint(constraintRow,data,jacobianA(row),jacobianB(row),dummy,dummy,dummy,posError,infoGlobal,-m_maxAppliedImpulse,m_maxAppliedImpulse,1,false,rhs); diff --git a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h index e433515d4..a8bcf606c 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h +++ b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h @@ -45,13 +45,13 @@ public: btMultiBodyJacobianData& data, const btContactSolverInfo& infoGlobal); - virtual void setVelocityTarget(btScalar velTarget, btScalar kd = 0.1f) + virtual void setVelocityTarget(btScalar velTarget, btScalar kd = 1.f) { m_desiredVelocity = velTarget; m_kd = kd; } - virtual void setPositionTarget(btScalar posTarget, btScalar kp = 0.1f) + virtual void setPositionTarget(btScalar posTarget, btScalar kp = 1.f) { m_desiredPosition = posTarget; m_kp = kp; From 83543ec76b109bb4e454c5d1a4e62b712dc07cf4 Mon Sep 17 00:00:00 2001 From: Jonathan Bohren Date: Thu, 30 Jun 2016 14:02:19 -0400 Subject: [PATCH 061/115] pkg-config: Fixing regression introduced by e46b7b2 --- bullet.pc.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bullet.pc.cmake b/bullet.pc.cmake index 2863ca1f9..8b989faba 100644 --- a/bullet.pc.cmake +++ b/bullet.pc.cmake @@ -3,4 +3,4 @@ Description: Bullet Continuous Collision Detection and Physics Library Requires: Version: @BULLET_VERSION@ Libs: -L@CMAKE_INSTALL_PREFIX@/@LIB_DESTINATION@ -lBulletSoftBody -lBulletDynamics -lBulletCollision -lLinearMath -Cflags: @BULLET_DOUBLE_DEF@ -I@INCLUDE_INSTALL_DIR@ -I@CMAKE_INSTALL_PREFIX@/include +Cflags: @BULLET_DOUBLE_DEF@ -I@CMAKE_INSTALL_PREFIX@/@INCLUDE_INSTALL_DIR@ -I@CMAKE_INSTALL_PREFIX@/include From 58206b7962d905982fa57d236182a3d0c1829796 Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Thu, 30 Jun 2016 16:03:38 -0700 Subject: [PATCH 062/115] Add preliminary support for VR/OpenVR for HTC Vive and Oculus Rift, (Windows-only first, later Linux and OSX) Use premake to build, use --enable_openvr flag --- build3/premake4.lua | 5 + examples/BasicDemo/premake4.lua | 60 + .../OpenGLWindow/GLInstancingRenderer.cpp | 14 +- examples/OpenGLWindow/GLInstancingRenderer.h | 1 + .../StandaloneMain/hellovr_opengl_main.cpp | 1986 ++++++ .../openvr/bin/linux32/libopenvr_api.so | Bin 0 -> 347110 bytes .../openvr/bin/linux64/libopenvr_api.so | Bin 0 -> 383669 bytes .../openvr/bin/osx32/libopenvr_api.dylib | Bin 0 -> 299972 bytes .../openvr/bin/win32/openvr_api.dll | Bin 0 -> 265024 bytes .../openvr/bin/win64/openvr_api.dll | Bin 0 -> 311616 bytes .../ThirdPartyLibs/openvr/headers/openvr.h | 3227 +++++++++ .../openvr/headers/openvr_api.cs | 4187 +++++++++++ .../openvr/headers/openvr_api.json | 3347 +++++++++ .../openvr/headers/openvr_capi.h | 1626 +++++ .../openvr/headers/openvr_driver.h | 1829 +++++ .../openvr/lib/linux32/libopenvr_api.so | Bin 0 -> 2315918 bytes .../openvr/lib/linux64/libopenvr_api.so | Bin 0 -> 3129824 bytes .../openvr/lib/osx32/libopenvr_api.dylib | Bin 0 -> 300188 bytes .../openvr/lib/win32/openvr_api.lib | Bin 0 -> 4864 bytes .../openvr/lib/win64/openvr_api.lib | Bin 0 -> 4806 bytes .../openvr/samples/shared/Matrices.cpp | 581 ++ .../openvr/samples/shared/Matrices.h | 909 +++ .../openvr/samples/shared/Vectors.h | 530 ++ .../openvr/samples/shared/lodepng.cpp | 6104 +++++++++++++++++ .../openvr/samples/shared/lodepng.h | 1702 +++++ .../openvr/samples/shared/pathtools.cpp | 560 ++ .../openvr/samples/shared/pathtools.h | 98 + 27 files changed, 26764 insertions(+), 2 deletions(-) create mode 100644 examples/StandaloneMain/hellovr_opengl_main.cpp create mode 100644 examples/ThirdPartyLibs/openvr/bin/linux32/libopenvr_api.so create mode 100644 examples/ThirdPartyLibs/openvr/bin/linux64/libopenvr_api.so create mode 100644 examples/ThirdPartyLibs/openvr/bin/osx32/libopenvr_api.dylib create mode 100644 examples/ThirdPartyLibs/openvr/bin/win32/openvr_api.dll create mode 100644 examples/ThirdPartyLibs/openvr/bin/win64/openvr_api.dll create mode 100644 examples/ThirdPartyLibs/openvr/headers/openvr.h create mode 100644 examples/ThirdPartyLibs/openvr/headers/openvr_api.cs create mode 100644 examples/ThirdPartyLibs/openvr/headers/openvr_api.json create mode 100644 examples/ThirdPartyLibs/openvr/headers/openvr_capi.h create mode 100644 examples/ThirdPartyLibs/openvr/headers/openvr_driver.h create mode 100644 examples/ThirdPartyLibs/openvr/lib/linux32/libopenvr_api.so create mode 100644 examples/ThirdPartyLibs/openvr/lib/linux64/libopenvr_api.so create mode 100644 examples/ThirdPartyLibs/openvr/lib/osx32/libopenvr_api.dylib create mode 100644 examples/ThirdPartyLibs/openvr/lib/win32/openvr_api.lib create mode 100644 examples/ThirdPartyLibs/openvr/lib/win64/openvr_api.lib create mode 100644 examples/ThirdPartyLibs/openvr/samples/shared/Matrices.cpp create mode 100644 examples/ThirdPartyLibs/openvr/samples/shared/Matrices.h create mode 100644 examples/ThirdPartyLibs/openvr/samples/shared/Vectors.h create mode 100644 examples/ThirdPartyLibs/openvr/samples/shared/lodepng.cpp create mode 100644 examples/ThirdPartyLibs/openvr/samples/shared/lodepng.h create mode 100644 examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp create mode 100644 examples/ThirdPartyLibs/openvr/samples/shared/pathtools.h diff --git a/build3/premake4.lua b/build3/premake4.lua index ae83944d4..4bfb35d28 100644 --- a/build3/premake4.lua +++ b/build3/premake4.lua @@ -29,6 +29,11 @@ description = "Try to link and use the system OpenGL headers version instead of dynamically loading OpenGL (dlopen is default)" } + newoption + { + trigger = "enable_openvr", + description = "Enable experimental Virtual Reality examples, using OpenVR for HTC Vive and Oculus Rift" + } newoption { trigger = "enable_system_x11", diff --git a/examples/BasicDemo/premake4.lua b/examples/BasicDemo/premake4.lua index 6474d9298..dd88389e1 100644 --- a/examples/BasicDemo/premake4.lua +++ b/examples/BasicDemo/premake4.lua @@ -59,6 +59,7 @@ end + project "App_BasicExampleGuiWithSoftwareRenderer" if _OPTIONS["ios"] then @@ -133,3 +134,62 @@ files { "../TinyRenderer/TinyRenderer.cpp", "../Utils/b3ResourcePath.cpp" } + + + + + if _OPTIONS["enable_openvr"] then + +project "App_BasicExampleVR" + +if _OPTIONS["ios"] then + kind "WindowedApp" +else + kind "ConsoleApp" +end +defines {"B3_USE_STANDALONE_EXAMPLE","BT_ENABLE_VR"} + + + +includedirs {"../../src", + "../ThirdPartyLibs/openvr/headers", + "../ThirdPartyLibs/openvr/samples/shared"} + +links { + "BulletDynamics","BulletCollision", "LinearMath", "OpenGL_Window","Bullet3Common", "openvr_api" +} + + initOpenGL() + initGlew() + + +language "C++" + +files { + "BasicExample.cpp", + "*.h", + "../StandaloneMain/hellovr_opengl_main.cpp", + "../ExampleBrowser/OpenGLGuiHelper.cpp", + "../ExampleBrowser/GL_ShapeDrawer.cpp", + "../ExampleBrowser/CollisionShape2TriangleMesh.cpp", + "../ThirdPartyLibs/openvr/samples/shared/lodepng.cpp", + "../ThirdPartyLibs/openvr/samples/shared/lodepng.h", + "../ThirdPartyLibs/openvr/samples/shared/Matrices.cpp", + "../ThirdPartyLibs/openvr/samples/shared/Matrices.h", + "../ThirdPartyLibs/openvr/samples/shared/pathtools.cpp", + "../ThirdPartyLibs/openvr/samples/shared/pathtools.h", + "../ThirdPartyLibs/openvr/samples/shared/Vectors.h", + +} + +if os.is("Windows") then + libdirs {"../ThirdPartyLibs/openvr/lib/win32"} +end + +if os.is("Linux") then initX11() end + +if os.is("MacOSX") then + links{"Cocoa.framework"} +end + +end \ No newline at end of file diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index ebf450afd..24002ad25 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -158,10 +158,13 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData GLRenderToTexture* m_shadowMap; GLuint m_shadowTexture; + GLuint m_renderFrameBuffer; + InternalDataRenderer() : m_shadowMap(0), - m_shadowTexture(0) + m_shadowTexture(0), + m_renderFrameBuffer(0) { //clear to zero to make it obvious if the matrix is used uninitialized for (int i=0;i<16;i++) @@ -1663,7 +1666,7 @@ b3Assert(glGetError() ==GL_NO_ERROR); { glDisable (GL_BLEND); } - + glActiveTexture(GL_TEXTURE0); break; } default: @@ -1688,6 +1691,7 @@ b3Assert(glGetError() ==GL_NO_ERROR); { // writeTextureToPng(shadowMapWidth,shadowMapHeight,"shadowmap.png",4); m_data->m_shadowMap->disable(); + glBindFramebuffer( GL_FRAMEBUFFER, m_data->m_renderFrameBuffer); glViewport(dims[0],dims[1],dims[2],dims[3]); } @@ -1733,4 +1737,10 @@ int GLInstancingRenderer::getInstanceCapacity() const { return m_data->m_maxNumObjectCapacity; } + +void GLInstancingRenderer::setRenderFrameBuffer(unsigned int renderFrameBuffer) +{ + m_data->m_renderFrameBuffer = (GLuint) renderFrameBuffer; +} + #endif //NO_OPENGL3 diff --git a/examples/OpenGLWindow/GLInstancingRenderer.h b/examples/OpenGLWindow/GLInstancingRenderer.h index 34df83637..66664b844 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.h +++ b/examples/OpenGLWindow/GLInstancingRenderer.h @@ -132,6 +132,7 @@ public: } virtual void clearZBuffer(); + virtual void setRenderFrameBuffer(unsigned int renderFrameBuffer); }; #endif //GL_INSTANCING_RENDERER_H diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp new file mode 100644 index 000000000..746f10835 --- /dev/null +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -0,0 +1,1986 @@ +#ifdef BT_ENABLE_VR +//========= Copyright Valve Corporation ============// + +#include "../OpenGLWindow/SimpleOpenGL3App.h" +#include "../OpenGLWindow/OpenGLInclude.h" +#include "Bullet3Common/b3Quaternion.h" +#include "../ExampleBrowser/OpenGLGuiHelper.h" +#include "../CommonInterfaces/CommonExampleInterface.h" +#include "../CommonInterfaces/CommonGUIHelperInterface.h" +#include "BulletCollision/CollisionDispatch/btCollisionObject.h" +#include "BulletCollision/CollisionShapes/btCollisionShape.h" +#include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h" + + +//how can you try typing on a keyboard, without seeing it? +//it is pretty funny, to see the desktop in VR! + + +#include +#include +#include + +#include + +#include "lodepng.h" +#include "Matrices.h" +#include "pathtools.h" + +CommonExampleInterface* sExample; +OpenGLGuiHelper* sGuiPtr = 0; + + +#if defined(POSIX) +#include "unistd.h" +#endif +#ifdef _WIN32 +#include +#endif + +void ThreadSleep( unsigned long nMilliseconds ) +{ +#if defined(_WIN32) + ::Sleep( nMilliseconds ); +#elif defined(POSIX) + usleep( nMilliseconds * 1000 ); +#endif +} + + +class CGLRenderModel +{ +public: + CGLRenderModel( const std::string & sRenderModelName ); + ~CGLRenderModel(); + + bool BInit( const vr::RenderModel_t & vrModel, const vr::RenderModel_TextureMap_t & vrDiffuseTexture ); + void Cleanup(); + void Draw(); + const std::string & GetName() const { return m_sModelName; } + +private: + GLuint m_glVertBuffer; + GLuint m_glIndexBuffer; + GLuint m_glVertArray; + GLuint m_glTexture; + GLsizei m_unVertexCount; + std::string m_sModelName; +}; + +static bool g_bPrintf = true; + +//----------------------------------------------------------------------------- +// Purpose: +//------------------------------------------------------------------------------ +class CMainApplication +{ +public: + CMainApplication( int argc, char *argv[] ); + virtual ~CMainApplication(); + + bool BInit(); + bool BInitGL(); + bool BInitCompositor(); + + void SetupRenderModels(); + + void Shutdown(); + + void RunMainLoop(); + bool HandleInput(); + void ProcessVREvent( const vr::VREvent_t & event ); + void RenderFrame(); + + bool SetupTexturemaps(); + + void SetupScene(); + void AddCubeToScene( Matrix4 mat, std::vector &vertdata ); + void AddCubeVertex( float fl0, float fl1, float fl2, float fl3, float fl4, std::vector &vertdata ); + + void DrawControllers(); + + bool SetupStereoRenderTargets(); + void SetupDistortion(); + void SetupCameras(); + + void RenderStereoTargets(); + void RenderDistortion(); + void RenderScene( vr::Hmd_Eye nEye ); + + Matrix4 GetHMDMatrixProjectionEye( vr::Hmd_Eye nEye ); + Matrix4 GetHMDMatrixPoseEye( vr::Hmd_Eye nEye ); + Matrix4 GetCurrentViewProjectionMatrix( vr::Hmd_Eye nEye ); + void UpdateHMDMatrixPose(); + + Matrix4 ConvertSteamVRMatrixToMatrix4( const vr::HmdMatrix34_t &matPose ); + + GLuint CompileGLShader( const char *pchShaderName, const char *pchVertexShader, const char *pchFragmentShader ); + bool CreateAllShaders(); + + void SetupRenderModelForTrackedDevice( vr::TrackedDeviceIndex_t unTrackedDeviceIndex ); + CGLRenderModel *FindOrLoadRenderModel( const char *pchRenderModelName ); + +private: + bool m_bDebugOpenGL; + bool m_bVerbose; + bool m_bPerf; + bool m_bVblank; + bool m_bGlFinishHack; + + vr::IVRSystem *m_pHMD; + vr::IVRRenderModels *m_pRenderModels; + std::string m_strDriver; + std::string m_strDisplay; + vr::TrackedDevicePose_t m_rTrackedDevicePose[ vr::k_unMaxTrackedDeviceCount ]; + Matrix4 m_rmat4DevicePose[ vr::k_unMaxTrackedDeviceCount ]; + bool m_rbShowTrackedDevice[ vr::k_unMaxTrackedDeviceCount ]; + +private: + SimpleOpenGL3App* m_app; + uint32_t m_nWindowWidth; + uint32_t m_nWindowHeight; + + +private: // OpenGL bookkeeping + int m_iTrackedControllerCount; + int m_iTrackedControllerCount_Last; + int m_iValidPoseCount; + int m_iValidPoseCount_Last; + bool m_bShowCubes; + + std::string m_strPoseClasses; // what classes we saw poses for this frame + char m_rDevClassChar[ vr::k_unMaxTrackedDeviceCount ]; // for each device, a character representing its class + + int m_iSceneVolumeWidth; + int m_iSceneVolumeHeight; + int m_iSceneVolumeDepth; + float m_fScaleSpacing; + float m_fScale; + + int m_iSceneVolumeInit; // if you want something other than the default 20x20x20 + + float m_fNearClip; + float m_fFarClip; + + GLuint m_iTexture; + + unsigned int m_uiVertcount; + + GLuint m_glSceneVertBuffer; + GLuint m_unSceneVAO; + GLuint m_unLensVAO; + GLuint m_glIDVertBuffer; + GLuint m_glIDIndexBuffer; + unsigned int m_uiIndexSize; + + GLuint m_glControllerVertBuffer; + GLuint m_unControllerVAO; + unsigned int m_uiControllerVertcount; + + Matrix4 m_mat4HMDPose; + Matrix4 m_mat4eyePosLeft; + Matrix4 m_mat4eyePosRight; + + Matrix4 m_mat4ProjectionCenter; + Matrix4 m_mat4ProjectionLeft; + Matrix4 m_mat4ProjectionRight; + + struct VertexDataScene + { + Vector3 position; + Vector2 texCoord; + }; + + struct VertexDataLens + { + Vector2 position; + Vector2 texCoordRed; + Vector2 texCoordGreen; + Vector2 texCoordBlue; + }; + + GLuint m_unSceneProgramID; + GLuint m_unLensProgramID; + GLuint m_unControllerTransformProgramID; + GLuint m_unRenderModelProgramID; + + GLint m_nSceneMatrixLocation; + GLint m_nControllerMatrixLocation; + GLint m_nRenderModelMatrixLocation; + + struct FramebufferDesc + { + GLuint m_nDepthBufferId; + GLuint m_nRenderTextureId; + GLuint m_nRenderFramebufferId; + GLuint m_nResolveTextureId; + GLuint m_nResolveFramebufferId; + }; + FramebufferDesc leftEyeDesc; + FramebufferDesc rightEyeDesc; + + bool CreateFrameBuffer( int nWidth, int nHeight, FramebufferDesc &framebufferDesc ); + + uint32_t m_nRenderWidth; + uint32_t m_nRenderHeight; + + std::vector< CGLRenderModel * > m_vecRenderModels; + CGLRenderModel *m_rTrackedDeviceToRenderModel[ vr::k_unMaxTrackedDeviceCount ]; +}; + + +//----------------------------------------------------------------------------- +// Purpose: Constructor +//----------------------------------------------------------------------------- +CMainApplication::CMainApplication( int argc, char *argv[] ) + : m_app(NULL) + , m_nWindowWidth( 1280 ) + , m_nWindowHeight( 720 ) + , m_unSceneProgramID( 0 ) + , m_unLensProgramID( 0 ) + , m_unControllerTransformProgramID( 0 ) + , m_unRenderModelProgramID( 0 ) + , m_pHMD( NULL ) + , m_pRenderModels( NULL ) + , m_bDebugOpenGL( false ) + , m_bVerbose( false ) + , m_bPerf( false ) + , m_bVblank( false ) + , m_bGlFinishHack( true ) + , m_glControllerVertBuffer( 0 ) + , m_unControllerVAO( 0 ) + , m_unLensVAO( 0 ) + , m_unSceneVAO( 0 ) + , m_nSceneMatrixLocation( -1 ) + , m_nControllerMatrixLocation( -1 ) + , m_nRenderModelMatrixLocation( -1 ) + , m_iTrackedControllerCount( 0 ) + , m_iTrackedControllerCount_Last( -1 ) + , m_iValidPoseCount( 0 ) + , m_iValidPoseCount_Last( -1 ) + , m_iSceneVolumeInit( 20 ) + , m_strPoseClasses("") + , m_bShowCubes( false ) +{ + + for( int i = 1; i < argc; i++ ) + { + if( !stricmp( argv[i], "-gldebug" ) ) + { + m_bDebugOpenGL = true; + } + else if( !stricmp( argv[i], "-verbose" ) ) + { + m_bVerbose = true; + } + else if( !stricmp( argv[i], "-novblank" ) ) + { + m_bVblank = false; + } + else if( !stricmp( argv[i], "-noglfinishhack" ) ) + { + m_bGlFinishHack = false; + } + else if( !stricmp( argv[i], "-noprintf" ) ) + { + g_bPrintf = false; + } + else if ( !stricmp( argv[i], "-cubevolume" ) && ( argc > i + 1 ) && ( *argv[ i + 1 ] != '-' ) ) + { + m_iSceneVolumeInit = atoi( argv[ i + 1 ] ); + i++; + } + } + // other initialization tasks are done in BInit + memset(m_rDevClassChar, 0, sizeof(m_rDevClassChar)); +}; + + +//----------------------------------------------------------------------------- +// Purpose: Destructor +//----------------------------------------------------------------------------- +CMainApplication::~CMainApplication() +{ + // work is done in Shutdown + b3Printf( "Shutdown" ); +} + + +//----------------------------------------------------------------------------- +// Purpose: Helper to get a string from a tracked device property and turn it +// into a std::string +//----------------------------------------------------------------------------- +std::string GetTrackedDeviceString( vr::IVRSystem *pHmd, vr::TrackedDeviceIndex_t unDevice, vr::TrackedDeviceProperty prop, vr::TrackedPropertyError *peError = NULL ) +{ + uint32_t unRequiredBufferLen = pHmd->GetStringTrackedDeviceProperty( unDevice, prop, NULL, 0, peError ); + if( unRequiredBufferLen == 0 ) + return ""; + + char *pchBuffer = new char[ unRequiredBufferLen ]; + unRequiredBufferLen = pHmd->GetStringTrackedDeviceProperty( unDevice, prop, pchBuffer, unRequiredBufferLen, peError ); + std::string sResult = pchBuffer; + delete [] pchBuffer; + return sResult; +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +bool CMainApplication::BInit() +{ + + // Loading the SteamVR Runtime + vr::EVRInitError eError = vr::VRInitError_None; + m_pHMD = vr::VR_Init( &eError, vr::VRApplication_Scene ); + + if ( eError != vr::VRInitError_None ) + { + m_pHMD = NULL; + char buf[1024]; + sprintf_s( buf, sizeof( buf ), "Unable to init VR runtime: %s", vr::VR_GetVRInitErrorAsEnglishDescription( eError ) ); + b3Warning( "VR_Init Failed %s", buf); + return false; + } + + + m_pRenderModels = (vr::IVRRenderModels *)vr::VR_GetGenericInterface( vr::IVRRenderModels_Version, &eError ); + if( !m_pRenderModels ) + { + m_pHMD = NULL; + vr::VR_Shutdown(); + + char buf[1024]; + sprintf_s( buf, sizeof( buf ), "Unable to get render model interface: %s", vr::VR_GetVRInitErrorAsEnglishDescription( eError ) ); + b3Warning( "VR_Init Failed %s", buf); + return false; + } + +// int nWindowPosX = 700; +// int nWindowPosY = 100; + m_nWindowWidth = 1280; + m_nWindowHeight = 720; + + /* + + //SDL_GL_SetAttribute( SDL_GL_CONTEXT_PROFILE_MASK, SDL_GL_CONTEXT_PROFILE_COMPATIBILITY ); + SDL_GL_SetAttribute( SDL_GL_CONTEXT_PROFILE_MASK, SDL_GL_CONTEXT_PROFILE_CORE ); + SDL_GL_SetAttribute( SDL_GL_MULTISAMPLEBUFFERS, 0 ); + SDL_GL_SetAttribute( SDL_GL_MULTISAMPLESAMPLES, 0 ); + if( m_bDebugOpenGL ) + SDL_GL_SetAttribute( SDL_GL_CONTEXT_FLAGS, SDL_GL_CONTEXT_DEBUG_FLAG ); + + */ + m_app = new SimpleOpenGL3App("SimpleOpenGL3App",m_nWindowWidth,m_nWindowHeight,true); + + sGuiPtr = new OpenGLGuiHelper(m_app,false); + + + CommonExampleOptions options(sGuiPtr); + + sExample = StandaloneExampleCreateFunc(options); + sExample->initPhysics(); + sExample->resetCamera(); + +#if 0 + int cubeIndex = m_app->registerCubeShape(1,1,1); + + b3Quaternion orn(0,0,0,1); + + { + b3Vector3 color=b3MakeVector3(0.3,0.3,0.6); + b3Vector3 pos = b3MakeVector3(0,0,0); + b3Vector3 scaling=b3MakeVector3 (1,.1,1); + m_app->m_renderer->registerGraphicsInstance(cubeIndex,pos,orn,color,scaling); + } + { + b3Vector3 color=b3MakeVector3(0.3,0.6,0.3); + b3Vector3 pos = b3MakeVector3(0,0.3,0); + b3Vector3 scaling=b3MakeVector3 (.1,.1,.1); + m_app->m_renderer->registerGraphicsInstance(cubeIndex,pos,orn,color,scaling); + } +#endif + + + + m_app->m_renderer->writeTransforms(); + + + +/* if (m_pWindow == NULL) + { + printf( "%s - Window could not be created! SDL Error: %s\n", __FUNCTION__, SDL_GetError() ); + return false; + } + */ + + /*m_pContext = SDL_GL_CreateContext(m_pWindow); + if (m_pContext == NULL) + { + printf( "%s - OpenGL context could not be created! SDL Error: %s\n", __FUNCTION__, SDL_GetError() ); + return false; + } + + + glewExperimental = GL_TRUE; + GLenum nGlewError = glewInit(); + if (nGlewError != GLEW_OK) + { + printf( "%s - Error initializing GLEW! %s\n", __FUNCTION__, glewGetErrorString( nGlewError ) ); + return false; + } + glGetError(); // to clear the error caused deep in GLEW + + if ( SDL_GL_SetSwapInterval( m_bVblank ? 1 : 0 ) < 0 ) + { + printf( "%s - Warning: Unable to set VSync! SDL Error: %s\n", __FUNCTION__, SDL_GetError() ); + return false; + } + + */ + m_strDriver = "No Driver"; + m_strDisplay = "No Display"; + + m_strDriver = GetTrackedDeviceString( m_pHMD, vr::k_unTrackedDeviceIndex_Hmd, vr::Prop_TrackingSystemName_String ); + m_strDisplay = GetTrackedDeviceString( m_pHMD, vr::k_unTrackedDeviceIndex_Hmd, vr::Prop_SerialNumber_String ); + + std::string strWindowTitle = "hellovr_bullet - " + m_strDriver + " " + m_strDisplay; + m_app->m_window->setWindowTitle(strWindowTitle.c_str() ); + + // cube array + m_iSceneVolumeWidth = m_iSceneVolumeInit; + m_iSceneVolumeHeight = m_iSceneVolumeInit; + m_iSceneVolumeDepth = m_iSceneVolumeInit; + + m_fScale = 0.3f; + m_fScaleSpacing = 4.0f; + + m_fNearClip = 0.1f; + m_fFarClip = 30.0f; + + m_iTexture = 0; + m_uiVertcount = 0; + +// m_MillisecondsTimer.start(1, this); +// m_SecondsTimer.start(1000, this); + + if (!BInitGL()) + { + printf("%s - Unable to initialize OpenGL!\n", __FUNCTION__); + return false; + } + + if (!BInitCompositor()) + { + printf("%s - Failed to initialize VR Compositor!\n", __FUNCTION__); + return false; + } + + return true; +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +/*void APIENTRY DebugCallback(GLenum source, GLenum type, GLuint id, GLenum severity, GLsizei length, const char* message, const void* userParam) +{ + b3Printf( "GL Error: %s\n", message ); +} +*/ + +static void APIENTRY DebugCallback (GLenum source, GLenum type, GLuint id, GLenum severity, GLsizei length, const GLchar* message, GLvoid* userParam) +{ + b3Printf( "GL Error: %s\n", message ); +} + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +bool CMainApplication::BInitGL() +{ + if( m_bDebugOpenGL ) + { + const GLvoid *userParam=0; + glDebugMessageCallback(DebugCallback, userParam); + glDebugMessageControl( GL_DONT_CARE, GL_DONT_CARE, GL_DONT_CARE, 0, nullptr, GL_TRUE ); + glEnable(GL_DEBUG_OUTPUT_SYNCHRONOUS); + } + + if( !CreateAllShaders() ) + return false; + + SetupTexturemaps(); + SetupScene(); + SetupCameras(); + SetupStereoRenderTargets(); + SetupDistortion(); + + SetupRenderModels(); + + return true; +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +bool CMainApplication::BInitCompositor() +{ + vr::EVRInitError peError = vr::VRInitError_None; + + if ( !vr::VRCompositor() ) + { + printf( "Compositor initialization failed. See log file for details\n" ); + return false; + } + + return true; +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +void CMainApplication::Shutdown() +{ + if( m_pHMD ) + { + vr::VR_Shutdown(); + m_pHMD = NULL; + } + + for( std::vector< CGLRenderModel * >::iterator i = m_vecRenderModels.begin(); i != m_vecRenderModels.end(); i++ ) + { + delete (*i); + } + m_vecRenderModels.clear(); + + if( 1)//m_pContext ) + { + glDebugMessageControl( GL_DONT_CARE, GL_DONT_CARE, GL_DONT_CARE, 0, nullptr, GL_FALSE ); + glDebugMessageCallback(nullptr, nullptr); + glDeleteBuffers(1, &m_glSceneVertBuffer); + glDeleteBuffers(1, &m_glIDVertBuffer); + glDeleteBuffers(1, &m_glIDIndexBuffer); + + if ( m_unSceneProgramID ) + { + glDeleteProgram( m_unSceneProgramID ); + } + if ( m_unControllerTransformProgramID ) + { + glDeleteProgram( m_unControllerTransformProgramID ); + } + if ( m_unRenderModelProgramID ) + { + glDeleteProgram( m_unRenderModelProgramID ); + } + if ( m_unLensProgramID ) + { + glDeleteProgram( m_unLensProgramID ); + } + + glDeleteRenderbuffers( 1, &leftEyeDesc.m_nDepthBufferId ); + glDeleteTextures( 1, &leftEyeDesc.m_nRenderTextureId ); + glDeleteFramebuffers( 1, &leftEyeDesc.m_nRenderFramebufferId ); + glDeleteTextures( 1, &leftEyeDesc.m_nResolveTextureId ); + glDeleteFramebuffers( 1, &leftEyeDesc.m_nResolveFramebufferId ); + + glDeleteRenderbuffers( 1, &rightEyeDesc.m_nDepthBufferId ); + glDeleteTextures( 1, &rightEyeDesc.m_nRenderTextureId ); + glDeleteFramebuffers( 1, &rightEyeDesc.m_nRenderFramebufferId ); + glDeleteTextures( 1, &rightEyeDesc.m_nResolveTextureId ); + glDeleteFramebuffers( 1, &rightEyeDesc.m_nResolveFramebufferId ); + + if( m_unLensVAO != 0 ) + { + glDeleteVertexArrays( 1, &m_unLensVAO ); + } + if( m_unSceneVAO != 0 ) + { + glDeleteVertexArrays( 1, &m_unSceneVAO ); + } + if( m_unControllerVAO != 0 ) + { + glDeleteVertexArrays( 1, &m_unControllerVAO ); + } + } + + delete m_app; + m_app=0; + +} + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +bool CMainApplication::HandleInput() +{ + bool bRet = false; + + // Process SteamVR events + vr::VREvent_t event; + while( m_pHMD->PollNextEvent( &event, sizeof( event ) ) ) + { + ProcessVREvent( event ); + } + + // Process SteamVR controller state + for( vr::TrackedDeviceIndex_t unDevice = 0; unDevice < vr::k_unMaxTrackedDeviceCount; unDevice++ ) + { + vr::VRControllerState_t state; + if( m_pHMD->GetControllerState( unDevice, &state ) ) + { + if (state.ulButtonPressed) + { + b3Printf("state.ulButtonPressed=%d\n",state.ulButtonPressed); + sExample->exitPhysics(); + m_app->m_instancingRenderer->removeAllInstances(); + sExample->initPhysics(); + + } + m_rbShowTrackedDevice[ unDevice ] = state.ulButtonPressed == 0; + } + } + + return bRet; +} + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +void CMainApplication::RunMainLoop() +{ + bool bQuit = false; + + //SDL_StartTextInput(); + //SDL_ShowCursor( SDL_DISABLE ); + + while ( !bQuit && !m_app->m_window->requestedExit()) + { + bQuit = HandleInput(); + + RenderFrame(); + } + + //SDL_StopTextInput(); +} + + +//----------------------------------------------------------------------------- +// Purpose: Processes a single VR event +//----------------------------------------------------------------------------- +void CMainApplication::ProcessVREvent( const vr::VREvent_t & event ) +{ + switch( event.eventType ) + { + case vr::VREvent_TrackedDeviceActivated: + { + SetupRenderModelForTrackedDevice( event.trackedDeviceIndex ); + b3Printf( "Device %u attached. Setting up render model.\n", event.trackedDeviceIndex ); + } + break; + case vr::VREvent_TrackedDeviceDeactivated: + { + b3Printf( "Device %u detached.\n", event.trackedDeviceIndex ); + } + break; + case vr::VREvent_TrackedDeviceUpdated: + { + b3Printf( "Device %u updated.\n", event.trackedDeviceIndex ); + } + break; + } +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +void CMainApplication::RenderFrame() +{ + // for now as fast as possible + if ( m_pHMD ) + { + DrawControllers(); + RenderStereoTargets(); + RenderDistortion(); + + vr::Texture_t leftEyeTexture = {(void*)leftEyeDesc.m_nResolveTextureId, vr::API_OpenGL, vr::ColorSpace_Gamma }; + vr::VRCompositor()->Submit(vr::Eye_Left, &leftEyeTexture ); + vr::Texture_t rightEyeTexture = {(void*)rightEyeDesc.m_nResolveTextureId, vr::API_OpenGL, vr::ColorSpace_Gamma }; + vr::VRCompositor()->Submit(vr::Eye_Right, &rightEyeTexture ); + } + + if ( m_bVblank && m_bGlFinishHack ) + { + //$ HACKHACK. From gpuview profiling, it looks like there is a bug where two renders and a present + // happen right before and after the vsync causing all kinds of jittering issues. This glFinish() + // appears to clear that up. Temporary fix while I try to get nvidia to investigate this problem. + // 1/29/2014 mikesart + glFinish(); + } + + // SwapWindow + { + m_app->swapBuffer(); + //SDL_GL_SwapWindow( m_pWindow ); + + } + + // Clear + { + // We want to make sure the glFinish waits for the entire present to complete, not just the submission + // of the command. So, we do a clear here right here so the glFinish will wait fully for the swap. + glClearColor( 0, 0, 0, 1 ); + glClear( GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT ); + } + + // Flush and wait for swap. + if ( m_bVblank ) + { + glFlush(); + glFinish(); + } + + // Spew out the controller and pose count whenever they change. + if ( m_iTrackedControllerCount != m_iTrackedControllerCount_Last || m_iValidPoseCount != m_iValidPoseCount_Last ) + { + m_iValidPoseCount_Last = m_iValidPoseCount; + m_iTrackedControllerCount_Last = m_iTrackedControllerCount; + + b3Printf( "PoseCount:%d(%s) Controllers:%d\n", m_iValidPoseCount, m_strPoseClasses.c_str(), m_iTrackedControllerCount ); + } + + UpdateHMDMatrixPose(); +} + + +//----------------------------------------------------------------------------- +// Purpose: Compiles a GL shader program and returns the handle. Returns 0 if +// the shader couldn't be compiled for some reason. +//----------------------------------------------------------------------------- +GLuint CMainApplication::CompileGLShader( const char *pchShaderName, const char *pchVertexShader, const char *pchFragmentShader ) +{ + GLuint unProgramID = glCreateProgram(); + + GLuint nSceneVertexShader = glCreateShader(GL_VERTEX_SHADER); + glShaderSource( nSceneVertexShader, 1, &pchVertexShader, NULL); + glCompileShader( nSceneVertexShader ); + + GLint vShaderCompiled = GL_FALSE; + glGetShaderiv( nSceneVertexShader, GL_COMPILE_STATUS, &vShaderCompiled); + if ( vShaderCompiled != GL_TRUE) + { + b3Printf("%s - Unable to compile vertex shader %d!\n", pchShaderName, nSceneVertexShader); + glDeleteProgram( unProgramID ); + glDeleteShader( nSceneVertexShader ); + return 0; + } + glAttachShader( unProgramID, nSceneVertexShader); + glDeleteShader( nSceneVertexShader ); // the program hangs onto this once it's attached + + GLuint nSceneFragmentShader = glCreateShader(GL_FRAGMENT_SHADER); + glShaderSource( nSceneFragmentShader, 1, &pchFragmentShader, NULL); + glCompileShader( nSceneFragmentShader ); + + GLint fShaderCompiled = GL_FALSE; + glGetShaderiv( nSceneFragmentShader, GL_COMPILE_STATUS, &fShaderCompiled); + if (fShaderCompiled != GL_TRUE) + { + b3Printf("%s - Unable to compile fragment shader %d!\n", pchShaderName, nSceneFragmentShader ); + glDeleteProgram( unProgramID ); + glDeleteShader( nSceneFragmentShader ); + return 0; + } + + glAttachShader( unProgramID, nSceneFragmentShader ); + glDeleteShader( nSceneFragmentShader ); // the program hangs onto this once it's attached + + glLinkProgram( unProgramID ); + + GLint programSuccess = GL_TRUE; + glGetProgramiv( unProgramID, GL_LINK_STATUS, &programSuccess); + if ( programSuccess != GL_TRUE ) + { + b3Printf("%s - Error linking program %d!\n", pchShaderName, unProgramID); + glDeleteProgram( unProgramID ); + return 0; + } + + glUseProgram( unProgramID ); + glUseProgram( 0 ); + + return unProgramID; +} + + +//----------------------------------------------------------------------------- +// Purpose: Creates all the shaders used by HelloVR SDL +//----------------------------------------------------------------------------- +bool CMainApplication::CreateAllShaders() +{ + m_unSceneProgramID = CompileGLShader( + "Scene", + + // Vertex Shader + "#version 410\n" + "uniform mat4 matrix;\n" + "layout(location = 0) in vec4 position;\n" + "layout(location = 1) in vec2 v2UVcoordsIn;\n" + "layout(location = 2) in vec3 v3NormalIn;\n" + "out vec2 v2UVcoords;\n" + "void main()\n" + "{\n" + " v2UVcoords = v2UVcoordsIn;\n" + " gl_Position = matrix * position;\n" + "}\n", + + // Fragment Shader + "#version 410 core\n" + "uniform sampler2D mytexture;\n" + "in vec2 v2UVcoords;\n" + "out vec4 outputColor;\n" + "void main()\n" + "{\n" + " outputColor = texture(mytexture, v2UVcoords);\n" + "}\n" + ); + m_nSceneMatrixLocation = glGetUniformLocation( m_unSceneProgramID, "matrix" ); + if( m_nSceneMatrixLocation == -1 ) + { + b3Printf( "Unable to find matrix uniform in scene shader\n" ); + return false; + } + + m_unControllerTransformProgramID = CompileGLShader( + "Controller", + + // vertex shader + "#version 410\n" + "uniform mat4 matrix;\n" + "layout(location = 0) in vec4 position;\n" + "layout(location = 1) in vec3 v3ColorIn;\n" + "out vec4 v4Color;\n" + "void main()\n" + "{\n" + " v4Color.xyz = v3ColorIn; v4Color.a = 1.0;\n" + " gl_Position = matrix * position;\n" + "}\n", + + // fragment shader + "#version 410\n" + "in vec4 v4Color;\n" + "out vec4 outputColor;\n" + "void main()\n" + "{\n" + " outputColor = v4Color;\n" + "}\n" + ); + m_nControllerMatrixLocation = glGetUniformLocation( m_unControllerTransformProgramID, "matrix" ); + if( m_nControllerMatrixLocation == -1 ) + { + b3Printf( "Unable to find matrix uniform in controller shader\n" ); + return false; + } + + m_unRenderModelProgramID = CompileGLShader( + "render model", + + // vertex shader + "#version 410\n" + "uniform mat4 matrix;\n" + "layout(location = 0) in vec4 position;\n" + "layout(location = 1) in vec3 v3NormalIn;\n" + "layout(location = 2) in vec2 v2TexCoordsIn;\n" + "out vec2 v2TexCoord;\n" + "void main()\n" + "{\n" + " v2TexCoord = v2TexCoordsIn;\n" + " gl_Position = matrix * vec4(position.xyz, 1);\n" + "}\n", + + //fragment shader + "#version 410 core\n" + "uniform sampler2D diffuse;\n" + "in vec2 v2TexCoord;\n" + "out vec4 outputColor;\n" + "void main()\n" + "{\n" + " outputColor = texture( diffuse, v2TexCoord);\n" + "}\n" + + ); + m_nRenderModelMatrixLocation = glGetUniformLocation( m_unRenderModelProgramID, "matrix" ); + if( m_nRenderModelMatrixLocation == -1 ) + { + b3Printf( "Unable to find matrix uniform in render model shader\n" ); + return false; + } + + m_unLensProgramID = CompileGLShader( + "Distortion", + + // vertex shader + "#version 410 core\n" + "layout(location = 0) in vec4 position;\n" + "layout(location = 1) in vec2 v2UVredIn;\n" + "layout(location = 2) in vec2 v2UVGreenIn;\n" + "layout(location = 3) in vec2 v2UVblueIn;\n" + "noperspective out vec2 v2UVred;\n" + "noperspective out vec2 v2UVgreen;\n" + "noperspective out vec2 v2UVblue;\n" + "void main()\n" + "{\n" + " v2UVred = v2UVredIn;\n" + " v2UVgreen = v2UVGreenIn;\n" + " v2UVblue = v2UVblueIn;\n" + " gl_Position = position;\n" + "}\n", + + // fragment shader + "#version 410 core\n" + "uniform sampler2D mytexture;\n" + + "noperspective in vec2 v2UVred;\n" + "noperspective in vec2 v2UVgreen;\n" + "noperspective in vec2 v2UVblue;\n" + + "out vec4 outputColor;\n" + + "void main()\n" + "{\n" + " float fBoundsCheck = ( (dot( vec2( lessThan( v2UVgreen.xy, vec2(0.05, 0.05)) ), vec2(1.0, 1.0))+dot( vec2( greaterThan( v2UVgreen.xy, vec2( 0.95, 0.95)) ), vec2(1.0, 1.0))) );\n" + " if( fBoundsCheck > 1.0 )\n" + " { outputColor = vec4( 0, 0, 0, 1.0 ); }\n" + " else\n" + " {\n" + " float red = texture(mytexture, v2UVred).x;\n" + " float green = texture(mytexture, v2UVgreen).y;\n" + " float blue = texture(mytexture, v2UVblue).z;\n" + " outputColor = vec4( red, green, blue, 1.0 ); }\n" + "}\n" + ); + + + return m_unSceneProgramID != 0 + && m_unControllerTransformProgramID != 0 + && m_unRenderModelProgramID != 0 + && m_unLensProgramID != 0; +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +bool CMainApplication::SetupTexturemaps() +{ + std::string sExecutableDirectory = Path_StripFilename( Path_GetExecutablePath() ); + std::string strFullPath = Path_MakeAbsolute( "../cube_texture.png", sExecutableDirectory ); + + std::vector imageRGBA; + unsigned nImageWidth, nImageHeight; + unsigned nError = lodepng::decode( imageRGBA, nImageWidth, nImageHeight, strFullPath.c_str() ); + + if ( nError != 0 ) + return false; + + glGenTextures(1, &m_iTexture ); + glBindTexture( GL_TEXTURE_2D, m_iTexture ); + + glTexImage2D( GL_TEXTURE_2D, 0, GL_RGBA, nImageWidth, nImageHeight, + 0, GL_RGBA, GL_UNSIGNED_BYTE, &imageRGBA[0] ); + + glGenerateMipmap(GL_TEXTURE_2D); + + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR ); + + GLfloat fLargest; + glGetFloatv(GL_MAX_TEXTURE_MAX_ANISOTROPY_EXT, &fLargest); + glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAX_ANISOTROPY_EXT, fLargest); + + glBindTexture( GL_TEXTURE_2D, 0 ); + + return ( m_iTexture != 0 ); +} + + +//----------------------------------------------------------------------------- +// Purpose: create a sea of cubes +//----------------------------------------------------------------------------- +void CMainApplication::SetupScene() +{ + if ( !m_pHMD ) + return; + + std::vector vertdataarray; + + Matrix4 matScale; + matScale.scale( m_fScale, m_fScale, m_fScale ); + Matrix4 matTransform; + matTransform.translate( + -( (float)m_iSceneVolumeWidth * m_fScaleSpacing ) / 2.f, + -( (float)m_iSceneVolumeHeight * m_fScaleSpacing ) / 2.f, + -( (float)m_iSceneVolumeDepth * m_fScaleSpacing ) / 2.f); + + Matrix4 mat = matScale * matTransform; + + for( int z = 0; z< m_iSceneVolumeDepth; z++ ) + { + for( int y = 0; y< m_iSceneVolumeHeight; y++ ) + { + for( int x = 0; x< m_iSceneVolumeWidth; x++ ) + { + AddCubeToScene( mat, vertdataarray ); + mat = mat * Matrix4().translate( m_fScaleSpacing, 0, 0 ); + } + mat = mat * Matrix4().translate( -((float)m_iSceneVolumeWidth) * m_fScaleSpacing, m_fScaleSpacing, 0 ); + } + mat = mat * Matrix4().translate( 0, -((float)m_iSceneVolumeHeight) * m_fScaleSpacing, m_fScaleSpacing ); + } + m_uiVertcount = vertdataarray.size()/5; + + glGenVertexArrays( 1, &m_unSceneVAO ); + glBindVertexArray( m_unSceneVAO ); + + glGenBuffers( 1, &m_glSceneVertBuffer ); + glBindBuffer( GL_ARRAY_BUFFER, m_glSceneVertBuffer ); + glBufferData( GL_ARRAY_BUFFER, sizeof(float) * vertdataarray.size(), &vertdataarray[0], GL_STATIC_DRAW); + + glBindBuffer( GL_ARRAY_BUFFER, m_glSceneVertBuffer ); + + GLsizei stride = sizeof(VertexDataScene); + uintptr_t offset = 0; + + glEnableVertexAttribArray( 0 ); + glVertexAttribPointer( 0, 3, GL_FLOAT, GL_FALSE, stride , (const void *)offset); + + offset += sizeof(Vector3); + glEnableVertexAttribArray( 1 ); + glVertexAttribPointer( 1, 2, GL_FLOAT, GL_FALSE, stride, (const void *)offset); + + glBindVertexArray( 0 ); + glDisableVertexAttribArray(0); + glDisableVertexAttribArray(1); + +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +void CMainApplication::AddCubeVertex( float fl0, float fl1, float fl2, float fl3, float fl4, std::vector &vertdata ) +{ + vertdata.push_back( fl0 ); + vertdata.push_back( fl1 ); + vertdata.push_back( fl2 ); + vertdata.push_back( fl3 ); + vertdata.push_back( fl4 ); +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +void CMainApplication::AddCubeToScene( Matrix4 mat, std::vector &vertdata ) +{ + // Matrix4 mat( outermat.data() ); + + Vector4 A = mat * Vector4( 0, 0, 0, 1 ); + Vector4 B = mat * Vector4( 1, 0, 0, 1 ); + Vector4 C = mat * Vector4( 1, 1, 0, 1 ); + Vector4 D = mat * Vector4( 0, 1, 0, 1 ); + Vector4 E = mat * Vector4( 0, 0, 1, 1 ); + Vector4 F = mat * Vector4( 1, 0, 1, 1 ); + Vector4 G = mat * Vector4( 1, 1, 1, 1 ); + Vector4 H = mat * Vector4( 0, 1, 1, 1 ); + + // triangles instead of quads + AddCubeVertex( E.x, E.y, E.z, 0, 1, vertdata ); //Front + AddCubeVertex( F.x, F.y, F.z, 1, 1, vertdata ); + AddCubeVertex( G.x, G.y, G.z, 1, 0, vertdata ); + AddCubeVertex( G.x, G.y, G.z, 1, 0, vertdata ); + AddCubeVertex( H.x, H.y, H.z, 0, 0, vertdata ); + AddCubeVertex( E.x, E.y, E.z, 0, 1, vertdata ); + + AddCubeVertex( B.x, B.y, B.z, 0, 1, vertdata ); //Back + AddCubeVertex( A.x, A.y, A.z, 1, 1, vertdata ); + AddCubeVertex( D.x, D.y, D.z, 1, 0, vertdata ); + AddCubeVertex( D.x, D.y, D.z, 1, 0, vertdata ); + AddCubeVertex( C.x, C.y, C.z, 0, 0, vertdata ); + AddCubeVertex( B.x, B.y, B.z, 0, 1, vertdata ); + + AddCubeVertex( H.x, H.y, H.z, 0, 1, vertdata ); //Top + AddCubeVertex( G.x, G.y, G.z, 1, 1, vertdata ); + AddCubeVertex( C.x, C.y, C.z, 1, 0, vertdata ); + AddCubeVertex( C.x, C.y, C.z, 1, 0, vertdata ); + AddCubeVertex( D.x, D.y, D.z, 0, 0, vertdata ); + AddCubeVertex( H.x, H.y, H.z, 0, 1, vertdata ); + + AddCubeVertex( A.x, A.y, A.z, 0, 1, vertdata ); //Bottom + AddCubeVertex( B.x, B.y, B.z, 1, 1, vertdata ); + AddCubeVertex( F.x, F.y, F.z, 1, 0, vertdata ); + AddCubeVertex( F.x, F.y, F.z, 1, 0, vertdata ); + AddCubeVertex( E.x, E.y, E.z, 0, 0, vertdata ); + AddCubeVertex( A.x, A.y, A.z, 0, 1, vertdata ); + + AddCubeVertex( A.x, A.y, A.z, 0, 1, vertdata ); //Left + AddCubeVertex( E.x, E.y, E.z, 1, 1, vertdata ); + AddCubeVertex( H.x, H.y, H.z, 1, 0, vertdata ); + AddCubeVertex( H.x, H.y, H.z, 1, 0, vertdata ); + AddCubeVertex( D.x, D.y, D.z, 0, 0, vertdata ); + AddCubeVertex( A.x, A.y, A.z, 0, 1, vertdata ); + + AddCubeVertex( F.x, F.y, F.z, 0, 1, vertdata ); //Right + AddCubeVertex( B.x, B.y, B.z, 1, 1, vertdata ); + AddCubeVertex( C.x, C.y, C.z, 1, 0, vertdata ); + AddCubeVertex( C.x, C.y, C.z, 1, 0, vertdata ); + AddCubeVertex( G.x, G.y, G.z, 0, 0, vertdata ); + AddCubeVertex( F.x, F.y, F.z, 0, 1, vertdata ); +} + + +//----------------------------------------------------------------------------- +// Purpose: Draw all of the controllers as X/Y/Z lines +//----------------------------------------------------------------------------- +void CMainApplication::DrawControllers() +{ + // don't draw controllers if somebody else has input focus + if( m_pHMD->IsInputFocusCapturedByAnotherProcess() ) + return; + + std::vector vertdataarray; + + m_uiControllerVertcount = 0; + m_iTrackedControllerCount = 0; + + for ( vr::TrackedDeviceIndex_t unTrackedDevice = vr::k_unTrackedDeviceIndex_Hmd + 1; unTrackedDevice < vr::k_unMaxTrackedDeviceCount; ++unTrackedDevice ) + { + if ( !m_pHMD->IsTrackedDeviceConnected( unTrackedDevice ) ) + continue; + + if( m_pHMD->GetTrackedDeviceClass( unTrackedDevice ) != vr::TrackedDeviceClass_Controller ) + continue; + + m_iTrackedControllerCount += 1; + + if( !m_rTrackedDevicePose[ unTrackedDevice ].bPoseIsValid ) + continue; + + const Matrix4 & mat = m_rmat4DevicePose[unTrackedDevice]; + + Vector4 center = mat * Vector4( 0, 0, 0, 1 ); + + for ( int i = 0; i < 3; ++i ) + { + Vector3 color( 0, 0, 0 ); + Vector4 point( 0, 0, 0, 1 ); + point[i] += 0.05f; // offset in X, Y, Z + color[i] = 1.0; // R, G, B + point = mat * point; + vertdataarray.push_back( center.x ); + vertdataarray.push_back( center.y ); + vertdataarray.push_back( center.z ); + + vertdataarray.push_back( color.x ); + vertdataarray.push_back( color.y ); + vertdataarray.push_back( color.z ); + + vertdataarray.push_back( point.x ); + vertdataarray.push_back( point.y ); + vertdataarray.push_back( point.z ); + + vertdataarray.push_back( color.x ); + vertdataarray.push_back( color.y ); + vertdataarray.push_back( color.z ); + + m_uiControllerVertcount += 2; + } + + Vector4 start = mat * Vector4( 0, 0, -0.02f, 1 ); + Vector4 end = mat * Vector4( 0, 0, -39.f, 1 ); + Vector3 color( .92f, .92f, .71f ); + + vertdataarray.push_back( start.x );vertdataarray.push_back( start.y );vertdataarray.push_back( start.z ); + vertdataarray.push_back( color.x );vertdataarray.push_back( color.y );vertdataarray.push_back( color.z ); + + vertdataarray.push_back( end.x );vertdataarray.push_back( end.y );vertdataarray.push_back( end.z ); + vertdataarray.push_back( color.x );vertdataarray.push_back( color.y );vertdataarray.push_back( color.z ); + m_uiControllerVertcount += 2; + } + + // Setup the VAO the first time through. + if ( m_unControllerVAO == 0 ) + { + glGenVertexArrays( 1, &m_unControllerVAO ); + glBindVertexArray( m_unControllerVAO ); + + glGenBuffers( 1, &m_glControllerVertBuffer ); + glBindBuffer( GL_ARRAY_BUFFER, m_glControllerVertBuffer ); + + GLuint stride = 2 * 3 * sizeof( float ); + GLuint offset = 0; + + glEnableVertexAttribArray( 0 ); + glVertexAttribPointer( 0, 3, GL_FLOAT, GL_FALSE, stride, (const void *)offset); + + offset += sizeof( Vector3 ); + glEnableVertexAttribArray( 1 ); + glVertexAttribPointer( 1, 3, GL_FLOAT, GL_FALSE, stride, (const void *)offset); + + glBindVertexArray( 0 ); + } + + glBindBuffer( GL_ARRAY_BUFFER, m_glControllerVertBuffer ); + + // set vertex data if we have some + if( vertdataarray.size() > 0 ) + { + //$ TODO: Use glBufferSubData for this... + glBufferData( GL_ARRAY_BUFFER, sizeof(float) * vertdataarray.size(), &vertdataarray[0], GL_STREAM_DRAW ); + } +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +void CMainApplication::SetupCameras() +{ + m_mat4ProjectionLeft = GetHMDMatrixProjectionEye( vr::Eye_Left ); + m_mat4ProjectionRight = GetHMDMatrixProjectionEye( vr::Eye_Right ); + m_mat4eyePosLeft = GetHMDMatrixPoseEye( vr::Eye_Left ); + m_mat4eyePosRight = GetHMDMatrixPoseEye( vr::Eye_Right ); +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +bool CMainApplication::CreateFrameBuffer( int nWidth, int nHeight, FramebufferDesc &framebufferDesc ) +{ + glGenFramebuffers(1, &framebufferDesc.m_nRenderFramebufferId ); + glBindFramebuffer(GL_FRAMEBUFFER, framebufferDesc.m_nRenderFramebufferId); + + glGenRenderbuffers(1, &framebufferDesc.m_nDepthBufferId); + glBindRenderbuffer(GL_RENDERBUFFER, framebufferDesc.m_nDepthBufferId); + glRenderbufferStorageMultisample(GL_RENDERBUFFER, 4, GL_DEPTH_COMPONENT, nWidth, nHeight ); + glFramebufferRenderbuffer(GL_FRAMEBUFFER, GL_DEPTH_ATTACHMENT, GL_RENDERBUFFER, framebufferDesc.m_nDepthBufferId ); + + glGenTextures(1, &framebufferDesc.m_nRenderTextureId ); + glBindTexture(GL_TEXTURE_2D_MULTISAMPLE, framebufferDesc.m_nRenderTextureId ); + glTexImage2DMultisample(GL_TEXTURE_2D_MULTISAMPLE, 4, GL_RGBA8, nWidth, nHeight, true); + glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D_MULTISAMPLE, framebufferDesc.m_nRenderTextureId, 0); + + glGenFramebuffers(1, &framebufferDesc.m_nResolveFramebufferId ); + glBindFramebuffer(GL_FRAMEBUFFER, framebufferDesc.m_nResolveFramebufferId); + + glGenTextures(1, &framebufferDesc.m_nResolveTextureId ); + glBindTexture(GL_TEXTURE_2D, framebufferDesc.m_nResolveTextureId ); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); + glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAX_LEVEL, 0); + glTexImage2D(GL_TEXTURE_2D, 0, GL_RGBA8, nWidth, nHeight, 0, GL_RGBA, GL_UNSIGNED_BYTE, nullptr); + glFramebufferTexture2D(GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D, framebufferDesc.m_nResolveTextureId, 0); + + // check FBO status + GLenum status = glCheckFramebufferStatus(GL_FRAMEBUFFER); + if (status != GL_FRAMEBUFFER_COMPLETE) + { + return false; + } + + glBindFramebuffer( GL_FRAMEBUFFER, 0 ); + + return true; +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +bool CMainApplication::SetupStereoRenderTargets() +{ + if ( !m_pHMD ) + return false; + + m_pHMD->GetRecommendedRenderTargetSize( &m_nRenderWidth, &m_nRenderHeight ); + + CreateFrameBuffer( m_nRenderWidth, m_nRenderHeight, leftEyeDesc ); + CreateFrameBuffer( m_nRenderWidth, m_nRenderHeight, rightEyeDesc ); + + return true; +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +void CMainApplication::SetupDistortion() +{ + if ( !m_pHMD ) + return; + + GLushort m_iLensGridSegmentCountH = 43; + GLushort m_iLensGridSegmentCountV = 43; + + float w = (float)( 1.0/float(m_iLensGridSegmentCountH-1)); + float h = (float)( 1.0/float(m_iLensGridSegmentCountV-1)); + + float u, v = 0; + + std::vector vVerts(0); + VertexDataLens vert; + + //left eye distortion verts + float Xoffset = -1; + for( int y=0; yComputeDistortion(vr::Eye_Left, u, v); + + vert.texCoordRed = Vector2(dc0.rfRed[0], 1 - dc0.rfRed[1]); + vert.texCoordGreen = Vector2(dc0.rfGreen[0], 1 - dc0.rfGreen[1]); + vert.texCoordBlue = Vector2(dc0.rfBlue[0], 1 - dc0.rfBlue[1]); + + vVerts.push_back( vert ); + } + } + + //right eye distortion verts + Xoffset = 0; + for( int y=0; yComputeDistortion( vr::Eye_Right, u, v ); + + vert.texCoordRed = Vector2(dc0.rfRed[0], 1 - dc0.rfRed[1]); + vert.texCoordGreen = Vector2(dc0.rfGreen[0], 1 - dc0.rfGreen[1]); + vert.texCoordBlue = Vector2(dc0.rfBlue[0], 1 - dc0.rfBlue[1]); + + vVerts.push_back( vert ); + } + } + + std::vector vIndices; + GLushort a,b,c,d; + + GLushort offset = 0; + for( GLushort y=0; ym_instancingRenderer->init(); + + + + // Left Eye + { + Matrix4 viewMatLeft = m_mat4eyePosLeft * m_mat4HMDPose; + m_app->m_instancingRenderer->getActiveCamera()->setVRCamera(viewMatLeft.get(),m_mat4ProjectionLeft.get()); + m_app->m_instancingRenderer->updateCamera(); + } + + glBindFramebuffer( GL_FRAMEBUFFER, leftEyeDesc.m_nRenderFramebufferId ); + glViewport(0, 0, m_nRenderWidth, m_nRenderHeight ); + + + + m_app->m_window->startRendering(); + RenderScene( vr::Eye_Left ); + + m_app->drawGrid(); + sExample->stepSimulation(1./60.); + sExample->renderScene(); + + + + m_app->m_instancingRenderer->setRenderFrameBuffer((unsigned int)leftEyeDesc.m_nRenderFramebufferId); + + m_app->m_instancingRenderer->renderScene(); + + glBindFramebuffer( GL_FRAMEBUFFER, 0 ); + + glDisable( GL_MULTISAMPLE ); + + glBindFramebuffer(GL_READ_FRAMEBUFFER, leftEyeDesc.m_nRenderFramebufferId); + glBindFramebuffer(GL_DRAW_FRAMEBUFFER, leftEyeDesc.m_nResolveFramebufferId ); + + glBlitFramebuffer( 0, 0, m_nRenderWidth, m_nRenderHeight, 0, 0, m_nRenderWidth, m_nRenderHeight, + GL_COLOR_BUFFER_BIT, + GL_LINEAR ); + + glBindFramebuffer(GL_READ_FRAMEBUFFER, 0); + glBindFramebuffer(GL_DRAW_FRAMEBUFFER, 0 ); + + glEnable( GL_MULTISAMPLE ); + + // Right Eye + + { + Matrix4 viewMatRight = m_mat4eyePosRight * m_mat4HMDPose; + m_app->m_instancingRenderer->getActiveCamera()->setVRCamera(viewMatRight.get(),m_mat4ProjectionRight.get()); + m_app->m_instancingRenderer->updateCamera(); + } + + glBindFramebuffer( GL_FRAMEBUFFER, rightEyeDesc.m_nRenderFramebufferId ); + glViewport(0, 0, m_nRenderWidth, m_nRenderHeight ); + + m_app->m_window->startRendering(); + RenderScene( vr::Eye_Right ); + + m_app->drawGrid(); + m_app->m_instancingRenderer->setRenderFrameBuffer((unsigned int)rightEyeDesc.m_nRenderFramebufferId); + + m_app->m_renderer->renderScene(); + + glBindFramebuffer( GL_FRAMEBUFFER, 0 ); + + glDisable( GL_MULTISAMPLE ); + + glBindFramebuffer(GL_READ_FRAMEBUFFER, rightEyeDesc.m_nRenderFramebufferId ); + glBindFramebuffer(GL_DRAW_FRAMEBUFFER, rightEyeDesc.m_nResolveFramebufferId ); + + glBlitFramebuffer( 0, 0, m_nRenderWidth, m_nRenderHeight, 0, 0, m_nRenderWidth, m_nRenderHeight, + GL_COLOR_BUFFER_BIT, + GL_LINEAR ); + + glBindFramebuffer(GL_READ_FRAMEBUFFER, 0); + glBindFramebuffer(GL_DRAW_FRAMEBUFFER, 0 ); +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +void CMainApplication::RenderScene( vr::Hmd_Eye nEye ) +{ + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + glEnable(GL_DEPTH_TEST); + + if( m_bShowCubes ) + { + glUseProgram( m_unSceneProgramID ); + glUniformMatrix4fv( m_nSceneMatrixLocation, 1, GL_FALSE, GetCurrentViewProjectionMatrix( nEye ).get() ); + glBindVertexArray( m_unSceneVAO ); + glBindTexture( GL_TEXTURE_2D, m_iTexture ); + glDrawArrays( GL_TRIANGLES, 0, m_uiVertcount ); + glBindVertexArray( 0 ); + } + + bool bIsInputCapturedByAnotherProcess = m_pHMD->IsInputFocusCapturedByAnotherProcess(); + + if( !bIsInputCapturedByAnotherProcess ) + { + // draw the controller axis lines + glUseProgram( m_unControllerTransformProgramID ); + glUniformMatrix4fv( m_nControllerMatrixLocation, 1, GL_FALSE, GetCurrentViewProjectionMatrix( nEye ).get() ); + glBindVertexArray( m_unControllerVAO ); + glDrawArrays( GL_LINES, 0, m_uiControllerVertcount ); + glBindVertexArray( 0 ); + } + + // ----- Render Model rendering ----- + glUseProgram( m_unRenderModelProgramID ); + + for( uint32_t unTrackedDevice = 0; unTrackedDevice < vr::k_unMaxTrackedDeviceCount; unTrackedDevice++ ) + { + if( !m_rTrackedDeviceToRenderModel[ unTrackedDevice ] || !m_rbShowTrackedDevice[ unTrackedDevice ] ) + continue; + + const vr::TrackedDevicePose_t & pose = m_rTrackedDevicePose[ unTrackedDevice ]; + if( !pose.bPoseIsValid ) + continue; + + if( bIsInputCapturedByAnotherProcess && m_pHMD->GetTrackedDeviceClass( unTrackedDevice ) == vr::TrackedDeviceClass_Controller ) + continue; + + const Matrix4 & matDeviceToTracking = m_rmat4DevicePose[ unTrackedDevice ]; + Matrix4 matMVP = GetCurrentViewProjectionMatrix( nEye ) * matDeviceToTracking; + glUniformMatrix4fv( m_nRenderModelMatrixLocation, 1, GL_FALSE, matMVP.get() ); + + m_rTrackedDeviceToRenderModel[ unTrackedDevice ]->Draw(); + } + + glUseProgram( 0 ); +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +void CMainApplication::RenderDistortion() +{ + glDisable(GL_DEPTH_TEST); + glViewport( 0, 0, m_nWindowWidth, m_nWindowHeight ); + + glBindVertexArray( m_unLensVAO ); + glUseProgram( m_unLensProgramID ); + + //render left lens (first half of index array ) + glBindTexture(GL_TEXTURE_2D, leftEyeDesc.m_nResolveTextureId ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR ); + glDrawElements( GL_TRIANGLES, m_uiIndexSize/2, GL_UNSIGNED_SHORT, 0 ); + + //render right lens (second half of index array ) + glBindTexture(GL_TEXTURE_2D, rightEyeDesc.m_nResolveTextureId ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR ); + glDrawElements( GL_TRIANGLES, m_uiIndexSize/2, GL_UNSIGNED_SHORT, (const void *)(m_uiIndexSize) ); + + glBindVertexArray( 0 ); + glUseProgram( 0 ); +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +Matrix4 CMainApplication::GetHMDMatrixProjectionEye( vr::Hmd_Eye nEye ) +{ + if ( !m_pHMD ) + return Matrix4(); + + vr::HmdMatrix44_t mat = m_pHMD->GetProjectionMatrix( nEye, m_fNearClip, m_fFarClip, vr::API_OpenGL); + + return Matrix4( + mat.m[0][0], mat.m[1][0], mat.m[2][0], mat.m[3][0], + mat.m[0][1], mat.m[1][1], mat.m[2][1], mat.m[3][1], + mat.m[0][2], mat.m[1][2], mat.m[2][2], mat.m[3][2], + mat.m[0][3], mat.m[1][3], mat.m[2][3], mat.m[3][3] + ); +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +Matrix4 CMainApplication::GetHMDMatrixPoseEye( vr::Hmd_Eye nEye ) +{ + if ( !m_pHMD ) + return Matrix4(); + + vr::HmdMatrix34_t matEyeRight = m_pHMD->GetEyeToHeadTransform( nEye ); + Matrix4 matrixObj( + matEyeRight.m[0][0], matEyeRight.m[1][0], matEyeRight.m[2][0], 0.0, + matEyeRight.m[0][1], matEyeRight.m[1][1], matEyeRight.m[2][1], 0.0, + matEyeRight.m[0][2], matEyeRight.m[1][2], matEyeRight.m[2][2], 0.0, + matEyeRight.m[0][3], matEyeRight.m[1][3], matEyeRight.m[2][3], 1.0f + ); + + return matrixObj.invert(); +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +Matrix4 CMainApplication::GetCurrentViewProjectionMatrix( vr::Hmd_Eye nEye ) +{ + Matrix4 matMVP; + if( nEye == vr::Eye_Left ) + { + matMVP = m_mat4ProjectionLeft * m_mat4eyePosLeft * m_mat4HMDPose; + } + else if( nEye == vr::Eye_Right ) + { + matMVP = m_mat4ProjectionRight * m_mat4eyePosRight * m_mat4HMDPose; + } + + return matMVP; +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +void CMainApplication::UpdateHMDMatrixPose() +{ + if ( !m_pHMD ) + return; + + vr::VRCompositor()->WaitGetPoses(m_rTrackedDevicePose, vr::k_unMaxTrackedDeviceCount, NULL, 0 ); + + m_iValidPoseCount = 0; + m_strPoseClasses = ""; + for ( int nDevice = 0; nDevice < vr::k_unMaxTrackedDeviceCount; ++nDevice ) + { + if ( m_rTrackedDevicePose[nDevice].bPoseIsValid ) + { + m_iValidPoseCount++; + m_rmat4DevicePose[nDevice] = ConvertSteamVRMatrixToMatrix4( m_rTrackedDevicePose[nDevice].mDeviceToAbsoluteTracking ); + if (m_rDevClassChar[nDevice]==0) + { + switch (m_pHMD->GetTrackedDeviceClass(nDevice)) + { + case vr::TrackedDeviceClass_Controller: m_rDevClassChar[nDevice] = 'C'; break; + case vr::TrackedDeviceClass_HMD: m_rDevClassChar[nDevice] = 'H'; break; + case vr::TrackedDeviceClass_Invalid: m_rDevClassChar[nDevice] = 'I'; break; + case vr::TrackedDeviceClass_Other: m_rDevClassChar[nDevice] = 'O'; break; + case vr::TrackedDeviceClass_TrackingReference: m_rDevClassChar[nDevice] = 'T'; break; + default: m_rDevClassChar[nDevice] = '?'; break; + } + } + m_strPoseClasses += m_rDevClassChar[nDevice]; + } + } + + if ( m_rTrackedDevicePose[vr::k_unTrackedDeviceIndex_Hmd].bPoseIsValid ) + { + m_mat4HMDPose = m_rmat4DevicePose[vr::k_unTrackedDeviceIndex_Hmd].invert(); + } +} + + +//----------------------------------------------------------------------------- +// Purpose: Finds a render model we've already loaded or loads a new one +//----------------------------------------------------------------------------- +CGLRenderModel *CMainApplication::FindOrLoadRenderModel( const char *pchRenderModelName ) +{ + CGLRenderModel *pRenderModel = NULL; + for( std::vector< CGLRenderModel * >::iterator i = m_vecRenderModels.begin(); i != m_vecRenderModels.end(); i++ ) + { + if( !stricmp( (*i)->GetName().c_str(), pchRenderModelName ) ) + { + pRenderModel = *i; + break; + } + } + + // load the model if we didn't find one + if( !pRenderModel ) + { + vr::RenderModel_t *pModel; + vr::EVRRenderModelError error; + while ( 1 ) + { + error = vr::VRRenderModels()->LoadRenderModel_Async( pchRenderModelName, &pModel ); + if ( error != vr::VRRenderModelError_Loading ) + break; + + ThreadSleep( 1 ); + } + + if ( error != vr::VRRenderModelError_None ) + { + b3Printf( "Unable to load render model %s - %s\n", pchRenderModelName, vr::VRRenderModels()->GetRenderModelErrorNameFromEnum( error ) ); + return NULL; // move on to the next tracked device + } + + vr::RenderModel_TextureMap_t *pTexture; + while ( 1 ) + { + error = vr::VRRenderModels()->LoadTexture_Async( pModel->diffuseTextureId, &pTexture ); + if ( error != vr::VRRenderModelError_Loading ) + break; + + ThreadSleep( 1 ); + } + + if ( error != vr::VRRenderModelError_None ) + { + b3Printf( "Unable to load render texture id:%d for render model %s\n", pModel->diffuseTextureId, pchRenderModelName ); + vr::VRRenderModels()->FreeRenderModel( pModel ); + return NULL; // move on to the next tracked device + } + + pRenderModel = new CGLRenderModel( pchRenderModelName ); + if ( !pRenderModel->BInit( *pModel, *pTexture ) ) + { + b3Printf( "Unable to create GL model from render model %s\n", pchRenderModelName ); + delete pRenderModel; + pRenderModel = NULL; + } + else + { + m_vecRenderModels.push_back( pRenderModel ); + } + vr::VRRenderModels()->FreeRenderModel( pModel ); + vr::VRRenderModels()->FreeTexture( pTexture ); + } + return pRenderModel; +} + + +//----------------------------------------------------------------------------- +// Purpose: Create/destroy GL a Render Model for a single tracked device +//----------------------------------------------------------------------------- +void CMainApplication::SetupRenderModelForTrackedDevice( vr::TrackedDeviceIndex_t unTrackedDeviceIndex ) +{ + if( unTrackedDeviceIndex >= vr::k_unMaxTrackedDeviceCount ) + return; + + // try to find a model we've already set up + std::string sRenderModelName = GetTrackedDeviceString( m_pHMD, unTrackedDeviceIndex, vr::Prop_RenderModelName_String ); + CGLRenderModel *pRenderModel = FindOrLoadRenderModel( sRenderModelName.c_str() ); + if( !pRenderModel ) + { + std::string sTrackingSystemName = GetTrackedDeviceString( m_pHMD, unTrackedDeviceIndex, vr::Prop_TrackingSystemName_String ); + b3Printf( "Unable to load render model for tracked device %d (%s.%s)", unTrackedDeviceIndex, sTrackingSystemName.c_str(), sRenderModelName.c_str() ); + } + else + { + m_rTrackedDeviceToRenderModel[ unTrackedDeviceIndex ] = pRenderModel; + m_rbShowTrackedDevice[ unTrackedDeviceIndex ] = true; + } +} + + +//----------------------------------------------------------------------------- +// Purpose: Create/destroy GL Render Models +//----------------------------------------------------------------------------- +void CMainApplication::SetupRenderModels() +{ + memset( m_rTrackedDeviceToRenderModel, 0, sizeof( m_rTrackedDeviceToRenderModel ) ); + + if( !m_pHMD ) + return; + + for( uint32_t unTrackedDevice = vr::k_unTrackedDeviceIndex_Hmd + 1; unTrackedDevice < vr::k_unMaxTrackedDeviceCount; unTrackedDevice++ ) + { + if( !m_pHMD->IsTrackedDeviceConnected( unTrackedDevice ) ) + continue; + + SetupRenderModelForTrackedDevice( unTrackedDevice ); + } + +} + + +//----------------------------------------------------------------------------- +// Purpose: Converts a SteamVR matrix to our local matrix class +//----------------------------------------------------------------------------- +Matrix4 CMainApplication::ConvertSteamVRMatrixToMatrix4( const vr::HmdMatrix34_t &matPose ) +{ + Matrix4 matrixObj( + matPose.m[0][0], matPose.m[1][0], matPose.m[2][0], 0.0, + matPose.m[0][1], matPose.m[1][1], matPose.m[2][1], 0.0, + matPose.m[0][2], matPose.m[1][2], matPose.m[2][2], 0.0, + matPose.m[0][3], matPose.m[1][3], matPose.m[2][3], 1.0f + ); + return matrixObj; +} + + +//----------------------------------------------------------------------------- +// Purpose: Create/destroy GL Render Models +//----------------------------------------------------------------------------- +CGLRenderModel::CGLRenderModel( const std::string & sRenderModelName ) + : m_sModelName( sRenderModelName ) +{ + m_glIndexBuffer = 0; + m_glVertArray = 0; + m_glVertBuffer = 0; + m_glTexture = 0; +} + + +CGLRenderModel::~CGLRenderModel() +{ + Cleanup(); +} + + +//----------------------------------------------------------------------------- +// Purpose: Allocates and populates the GL resources for a render model +//----------------------------------------------------------------------------- +bool CGLRenderModel::BInit( const vr::RenderModel_t & vrModel, const vr::RenderModel_TextureMap_t & vrDiffuseTexture ) +{ + // create and bind a VAO to hold state for this model + glGenVertexArrays( 1, &m_glVertArray ); + glBindVertexArray( m_glVertArray ); + + // Populate a vertex buffer + glGenBuffers( 1, &m_glVertBuffer ); + glBindBuffer( GL_ARRAY_BUFFER, m_glVertBuffer ); + glBufferData( GL_ARRAY_BUFFER, sizeof( vr::RenderModel_Vertex_t ) * vrModel.unVertexCount, vrModel.rVertexData, GL_STATIC_DRAW ); + + // Identify the components in the vertex buffer + glEnableVertexAttribArray( 0 ); + glVertexAttribPointer( 0, 3, GL_FLOAT, GL_FALSE, sizeof( vr::RenderModel_Vertex_t ), (void *)offsetof( vr::RenderModel_Vertex_t, vPosition ) ); + glEnableVertexAttribArray( 1 ); + glVertexAttribPointer( 1, 3, GL_FLOAT, GL_FALSE, sizeof( vr::RenderModel_Vertex_t ), (void *)offsetof( vr::RenderModel_Vertex_t, vNormal ) ); + glEnableVertexAttribArray( 2 ); + glVertexAttribPointer( 2, 2, GL_FLOAT, GL_FALSE, sizeof( vr::RenderModel_Vertex_t ), (void *)offsetof( vr::RenderModel_Vertex_t, rfTextureCoord ) ); + + // Create and populate the index buffer + glGenBuffers( 1, &m_glIndexBuffer ); + glBindBuffer( GL_ELEMENT_ARRAY_BUFFER, m_glIndexBuffer ); + glBufferData( GL_ELEMENT_ARRAY_BUFFER, sizeof( uint16_t ) * vrModel.unTriangleCount * 3, vrModel.rIndexData, GL_STATIC_DRAW ); + + glBindVertexArray( 0 ); + + // create and populate the texture + glGenTextures(1, &m_glTexture ); + glBindTexture( GL_TEXTURE_2D, m_glTexture ); + + glTexImage2D( GL_TEXTURE_2D, 0, GL_RGBA, vrDiffuseTexture.unWidth, vrDiffuseTexture.unHeight, + 0, GL_RGBA, GL_UNSIGNED_BYTE, vrDiffuseTexture.rubTextureMapData ); + + // If this renders black ask McJohn what's wrong. + glGenerateMipmap(GL_TEXTURE_2D); + + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR ); + glTexParameteri( GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR_MIPMAP_LINEAR ); + + GLfloat fLargest; + glGetFloatv( GL_MAX_TEXTURE_MAX_ANISOTROPY_EXT, &fLargest ); + glTexParameterf( GL_TEXTURE_2D, GL_TEXTURE_MAX_ANISOTROPY_EXT, fLargest ); + + glBindTexture( GL_TEXTURE_2D, 0 ); + + m_unVertexCount = vrModel.unTriangleCount * 3; + + return true; +} + + +//----------------------------------------------------------------------------- +// Purpose: Frees the GL resources for a render model +//----------------------------------------------------------------------------- +void CGLRenderModel::Cleanup() +{ + if( m_glVertBuffer ) + { + glDeleteBuffers(1, &m_glIndexBuffer); + glDeleteVertexArrays( 1, &m_glVertArray ); + glDeleteBuffers(1, &m_glVertBuffer); + m_glIndexBuffer = 0; + m_glVertArray = 0; + m_glVertBuffer = 0; + } +} + + +//----------------------------------------------------------------------------- +// Purpose: Draws the render model +//----------------------------------------------------------------------------- +void CGLRenderModel::Draw() +{ + glBindVertexArray( m_glVertArray ); + + glActiveTexture( GL_TEXTURE0 ); + glBindTexture( GL_TEXTURE_2D, m_glTexture ); + + glDrawElements( GL_TRIANGLES, m_unVertexCount, GL_UNSIGNED_SHORT, 0 ); + + glBindVertexArray( 0 ); +} + + +//----------------------------------------------------------------------------- +// Purpose: +//----------------------------------------------------------------------------- +int main(int argc, char *argv[]) +{ + CMainApplication *pMainApplication = new CMainApplication( argc, argv ); + + if (!pMainApplication->BInit()) + { + pMainApplication->Shutdown(); + return 1; + } + + pMainApplication->RunMainLoop(); + + pMainApplication->Shutdown(); + + return 0; +} +#endif //BT_ENABLE_VR \ No newline at end of file diff --git a/examples/ThirdPartyLibs/openvr/bin/linux32/libopenvr_api.so b/examples/ThirdPartyLibs/openvr/bin/linux32/libopenvr_api.so new file mode 100644 index 0000000000000000000000000000000000000000..a2505450834286ecae2bbe96c4742eca32584da7 GIT binary patch literal 347110 zcmce<4|r6?^*(+VBSegD#As1bV~rO7VL(7o^cx^SqM$K<6cw6;WFdi&tjS#n3X-^q zvMvh|P^n^#iWQY=RHUe=kx)QuHCn5*wKlb=8$)fhs7TTL-uK+Od+*-eK=}APzs)l_ zb7sz*IdkUBnRDmfy}Kl9$|RS|rJ0{2v?DZPUZ19o1nmBIf>e#vQnmitQ0;VWh}4_( zgj+sMkaQ%GWKHU&>>HFL?e4E>%ThJ8H|qNVq=gf-w0%bE2F}EK_Qtf=meP=CGV5|a z)k~8T6ErieJ5|$|%=&9l5Av9goqq~yk3hQO>H_V!s#AVHspgi?z8_ro*Z=%!WzxCX z-<1x461E^+ij)JohX8|s&j9`oupi*nfaWI;_+vnxM7k6CUm+cbl!R1<^gE=DNc`+X zIs^GCr2C{q)0P09r|KUAyjzu1FTVy(dH6Yibe75!pN;$@NG~Dih5YZd$r;C)CNP(PJ~_?!rQ5z^I2n}DB# z^b+!?Bb|%%JW@SU77{hCB#)(4&Vbw50L<$>Bv8abRE(kjUw$T1*ZTGN6J7d zLj5n0<{-hmv<-mU0WSiaiu57!T}UI5zZYpd(jMS<0N#YO4rx8o!$^fl`KaUP9Rp}y zls${|U*L6sLsfY$^0y(4Lb?!X4N?i}?glhJ!;!xP$Zu4^MS$ffyIs+|2mDo}$AM=m znw7{uibRq>Bb|-RT}U?~jYIl>NKd1@25<;cC-Rd3p9OpoDFu0cE(WYdT7|q1a5K`A zNcPXo3akNgaz*N}Gsu0lE$>1iac-v^QS zc^NoA^8hy?U4}FPX*JT%kme&bAmxIl0Pq{3*0f(D&(CteDM@=Zv`km&!1&wx0692cjoFGc4%h>o)1$J+9Tn@v1KgLG9-pZkCLoUR(3 z2RI%n!Nw#H`58!;+RDr<{d;d8kFDYgTi%|X4{NLb-?RX{+9}xU?4KZCUOvX8tQ(HbfltrAP#LU%94=MkdBU1&!US}`8>c|kTxRS ziL@Na{#j{9;^bdO*&|4^kjAR|kqQS-b0{$h^Uy$BKT8H#LlKEMU%pZ{6MDij19O)~hYmxZ*Ez)G9 ze<0n2G#6Hhekek5PP{NB&2o zc11H$!IuF0AXOJ_7kaA>V;C4QVv+Wya{19z+_3bO!K`k-kRyIq-i0K7%wJX$pWk;w;j?=IH+>Onwm--e_rmwDz+z!5>D)zDXZ&!{)J|PgeLwEWV6~4VzmB2J-yz=%7b<2#4;ymmYng+7I|QwR zL(5S78ULj=Sp8Qy=4<6ixYl{Z*y||Iz9FE8v5r;klN|H+&ta%gACB+X({LS!@m!5O z+rN8`S&M5SWIG)4Z?W~y`p^+*A256e+s|;c|1*f{?la;<*8d&jX=${^b8!mBdcW2F z2^)XP_bBv{0ezU`DZz%F@sKrtFM+6OjWvJ2L4P^u&z#Q-VNW^FS@S;v6**5^`f7v| zYY?E^C*(Sk2n_@^`X3%Lm$o12loxqUyQuF!&%J>CC7_~pt);&nhx{oHemfoO;d4j5Ck^_3*5d#82va)thoy%8T5RJz zCmH&<*VcbOj1T(7G>Ck!QBmr{_OD>RyiHd9gO2*$4*B{!aNV|EU`pbnmp*|>#b*#A zvw!r5{e%oZOZ~iIn*fpjOvvA2`J;&r{(p7o<2R1_jp(Nt8~Cfz-_hFdVV|kcf2P7u z!^EWi%JOeFI{4k=nC}(G!u~Ly=6d+ybet`0F!n^sf1gACMM>yrl{G)S4r{&LvX4s# zVh@IXxlGu89Q+Lf40C6!_^(#@uhFXgZyfsnr$gR76vVck@4@JRZQ_|@6Q_c7K}2G)}~-uGZ1Jj^lYV=mTHa+8JMhxtv%{F>`ebIAJ%CtiJy z1H1~1>YldrrK2#_=AX+Q@?CQz^cS@3XB5WUgz=j4{mr4T0}i}D_4{i}zZvMS+h$*@ zFrEzCcru2W(i-|X2kYC5c*C5ZjkNy;Yrk5Yg7MhqW6aU0zuVHse1|?Vv3_%~zt9bF zzPjK_GVU_`Ht{2dNB94L13wA+ONRa~Q|<2u-VWU4cbZM#oZlkYUsH=E4_sB`!}>)I zdwCS=xA}47+>i3`93}(neG+Ji-=2W+L0)q`--`M=zon0I$kPmY%=*6!K>c#dU%Z%# z@&DG6w=yD)q3_!q<9!SB&5I$hmHxkS_=^HeC5#hmyYpGbMXJ4gMP&MmO#|c ze#~dxO3S~_cJ%*^ga7p-qT9DYKgo@je%76cdYe5ybQ=7}lh*tkjrErLl!Y%v`*xdt zFL%g)heIB>1OKr<Dg4H$&goDShO_zPzw6liy>JPw4;ghU=)iVr+ z*@5{s*XNs#{(ixQ4E?cN+QS-${qSB(2kh}mRbPhnU1VF|?>gvH5kItGzOPpF^Du}U z_y=?RgKX=8`hNiaq4gPSKF`H^YF%#0^U?tH2i#m=SEYhK=8IuA<-OP8PYTdqD*EHJ zvwjlVcf;Oj)`C06f4c*p0r@i?xB4%#*$?L<4FA+|zcrp$Y~x}5*_hv!m6kn?$9&ac zzF5cpzkq*kYO?A(FtEB`TmJ8Vu=n(3mOpz8`u8?i`akAq%okv5d6Wc z^P>B6LGX^>TK4h*#-Cy9Zvzai?h&hgiNimnV?WJ!%BueW>oxsZYd%iHcw0i2J+)#y z$=E+l`%H82dk;%DIcSalUMSgXTR%5D#{a9^5zg9Agc0Gx^O~Lmxv=!2Ca8t&jIy z=&#Z8Zxu&FC-6t3Re#TpKt_EiZwl<&{1E>RN^C}aYRX%M{jBIQYrPEvy?sCY)FJ;& zhkb8{{#u|vcFXaAb>t)cIqWkR^Hpb?uOC3&U2k14-v<3R+w`9@Ji-qAjptI*{nq&3 zguXkVZ`u|6$I{f&7aRA7h@VTr)Q9aqL~2=rXC(kxe=O#s`%dUs;iDYuvzGngnI_=r&sp|&KjQhihphQ)cg%km{fDjpFC6@e z9r$ke@46M%elf^lzY8E_vrYd2$9%p3d+2`5(r1q=TK+n040TUh>*;*R&xedI1E4aE{5eJ+gS4ZxAJM<}HWLM_H8q|Zt?~7 z7F05Sg-5@_Q|YNLFUhWifU}BAJVIJCd0uHwwWr2YDNV9#a($J0`8-c{B?enj;VD&( zugfLZtm^8j>hU#s3+K(Os)$#URXMw&yrwMEQ&Uo1?$yhy%+B-l>hj9jld7uGpKw9z zyoJ!!JY*)86=M`tl@uwG&-3U$FAJ*Xd8=y5p)erV%=c7R6fZgW>s-@>D1y% zXp)t=p2|{B_0+0TPeqM1tc2n!a*8WGly$tn zhMhL2x@wN6gfdJmhDK@+LXca$Ai9={@aY~%1znh`jpClQ(34*^8KPoDl{K@fs;S&) z0rD}odF2?#l;Rrwx|)TRB{3wK7iEqeUs~*inPfu^u`*^(yCVA%hXGs|hV(G<{Vre}V635GI$W=&NEhAb0=$;zp!ai}yG zmaFG^igi!vjj*6t0&t72&acYTiz`dP?a+vXg$J2pN0**jEW3$SvKT5n)wxv_4kcok(bb@jk|n+w zM3KZ9QFcu7s;DZ~`$h^kchQKxkrtF!>Z3>Y zjn-JU7xj_a@OpjY%t4E1yc&LJQgzk5tV*9_{pM6vR9x+;)wAZC?mFUIqN=Vh*UREA z1!Uj%_t33tY z(inA)FPU3ewE)}jY|pj6a=kFCww$|GG#@8XL5&E6U?ZAN^~YT-AHrl+7SF8ksG%H` z67dV1*`#u8tfoi8HeET}oO{QH$xZS4@=Amr6RLcbrKVQmP+`L|Hj?YgJqy@}5+e?2 z+)c;6rx%VdEw$kY3(99%D!0|tARe1nHQ!?^Iv86VHhdz+ZjQ%R z>?FI&vv9&fyMsLxtunQ2iOifLOeywNmXz68D23WeY6=aaNC0KUR9p;El-ckDdikt{ zw!(M}qX&La0i#K4dUJTT4xI|4pXBCX_|`s&BlO&5`c7@^3GwI=!Pul5@6)Rcea54W z9_=A%;V%)`Au_Q-)n2$_OQ}Rmj5yNngKh0<3e{@2l_Acr5c`-|<|&!m3uhZW_iuYI zaU8Lox-h$jKFabw%IQUR{77iel`;`mEHkSm9Jdc4iY5oqH@6{MC>^&R5xBY1ta`Zf zs^U^xglbh`3iC>EH8ioRLar)k_f{>0GyGQkY6xUhO8^^*rL6Xdo=Of*g8qHpLd5g) z%Ju83s^?=!?QL2zYWh= z2#hFkI)XH7CSvE-J@M;sHpD~C_?57d$>p=luJy^GW_%jhXkY+ksTm6jB7Dy^3Gbr#z+Uai%3e1*5H zcj@ERT5Yc{FV)MkE2nyJ6zH6HOZ0{ zPbLu~AQYeP6eUgveQ9>6-ozzVT4z{sX2l$NRCm3#qeoOc92%l0j9-&oqspV5pG}mA zP7%9dQ>%P6o;*ZB z&Uv%g^h!cq;%Gf05tq1eXTqsMgc3L=iku(YTNKN!jPW(ni=$n3&EzWV^2W^&)yP4D zkz4`q>n$#oeKS50#?mJu)%t1=wvL&Rutb#>POX~nv9rmq>V?o!om$BbnI%3^T;o$% z9IRV7rWjTo7z?CvQb^1Z9l)5q zVzv&0nrkvb?&uesa;nSc6<05eP#8Bz9CYM?ty^yM9i+-ypAI7QV>ahhIcn(}%xXs! z6l2yzyg=`s)g(pyEk`mj@)+TqabvP@3Qi?#1*&ITNloD-#G1B(cqHT!ZGN@}28V-G zLoqgTTLfe)m2)>6Za>eo6$@F!G53k+ApJ!c8HfK@A<=nG@}VUw*X4}~Ll zk0%$`LkIR2H*0O}ZReU6 zDUYxs$DNU4^d`5(l(3O2Sne3Q!TmaT1Kb+MHOoA#-+9HRx9CNfzLA@^ zSU5OvHP~Ah)X}_Qnbo?DuTr9usLFdNn(P`Ig|QLDIZE?=ppP@7d1bh@Xl@l(Oo=<{sBVlU zz@^idrck`GGF(Mrln%d1&_6&|m`6Ii8LC=@b0N`(id)RR}kN8tG>*zVjyD4~>3 zO!0Xvkj#mG*h)2;qj-!i_Ij}y*cgp2uf#o7J!_8iE?h3gV_X$DCCr**D;$M&UgOES zdMqBzs`TOcu-f4l7Zz61pHvi7I%TNLpDuN1H{BAYWRXGhdrkQo-k6W-X`&Cu1n`l-O82S%%XoT$Df-^C_`; zo_Qs>qc96Gz9<7a8C4ynsgX4cioIF6&=u5N0PNVm%Tk$a+=|n2$1KFu2b2%>v`$h0-+y zJp8UXtav=*jt*)WO|!v;tUNh+qoXxOYe*E++BVdxikjXA64Oj6M|EmEt{F8sna1Qm zutUs^MR=Gxl1^)MJQ9gjq-Di@O z@U`W+`EdHe`S3)v45)7=FGf>Czc))%eleUkc2-aCi#Zpgy-0Zpwea%`^V18n@-D`_ z&&zc#O`l%jKecxp>L@+`4h3Q?AaXIT$!d4^vWD}zfdj4)Gf*1jQe zudx%@C#tG%wgmS=MHXhm2Va9t9m6n;zM>`@6;8)%(>gm4cbg9tk1CXHl-uIr7~w_W zAwIts6_Hz&30mAz{ee?O~Bnuw^S^JM`FOPc@Dzp;=bVFvF^z~GBsQ(~R3bJ;thxYkr#1@d9akCG~EK%9$6b17lG4^L2o9Y+^{k#bHX%w#bhE=Li+u240r)c&A8 z`LVc^dX8pl_FY~h@nNKLu4kc&qN9rN$Rk3=ND+1I^_1`^C{jjEJIgGspq6$Qp`KG! z&MTVy?D9xatoEdYe0AKi=8ni2k#CQnkaJKnw@{5-t1PapGAu;`91fdGnk5-NW2FzP zsTww1Lv|i>qnRtMV0Hwvh!9H7J1I?>v}uJG4I4RZY!o(p zxHfUxwDA+N3y0&2WzyE5vszm$FS4;8F>Ito!tbQ9f5Dfk}ox5Xoux2A*EgFWRw|ohOCB^mQ3u&px}R#<~ZcdF>@r$ z9}($^82JnWGNo)(f=`#{#V}3H*nxR52}6jN#%GW!I9dd3OD3C!Y1F5 zTAHdOfBj_AAFn;5$_)O=5&nZ@yosVuj<@D?()ZV1j^f`h!oL;2Er0=N+Z5cX;9Cl| zE2w>I&?PFEq+p7IgB2X2V5)*c6&$JH7zM{EI7Pu61@jdwRj^FK3I)9i)+)G2!3G7F zDY#a_W(C(NxL(1H3T{?#i-N5R?o{wC1>aY2mx3QD*r8xp!95D@Rq%j<3EwIGDVVI_ zUFcs9=(U$qEiuaEOAbCj8!LcfNw-6wFjG zN5L`$Gw@Cp_On{S1k8(Ts7uooT&mzU1$Qf`K~B=8D443?`3k0yu2s|O6zo=TpMpuG zL;XhzX0ZG_yzf!L$t(xHUcpucQ!q}JH<1o6El$BW`s3Xeg9-5+?IDEtZg?6YzAQbI z@N#??oG=f+r$Bfo-VZ|9tZ5m9Z{Xb&gg!*gAn@LO_+iA%MgyoZ%`0s;k)aElknbU z!Yl9|al*;?4H3dCHN2n>5HEX3AjAfeNO&#Y8Bdst{f6*5yf=Yx8s?Ai2FxGfjo1ST ze~Eb{EW|t#&cyq22+J^^gyon|!nv4F!b-fGoUjV>O6bM+*9ogJzl1vGm#`M^(jdGA z--#!@6?R8>8{Ugei1!v05!T`TafEl^_eluv(zFV~5WYK4i0|L)ge&o`Y{L66|AhBr z{t5B@`3AyYWBv)7G5>@QWBv&r#rzXKhWRIa0`pJ!B<7zGFIiYe_%!C95bqP%K-hx$ zCwvz3Pxu_>pKv4QpYR3DKj9|KKj9Y4KjABwf5KNW|AbpH|AgBx|Aad*|AcR1{t5qp z`6v7%=AZB#%s=6~n18}QWBv(0!2A>b1@lk%SIqza06)U~6MlmECk$i$3A-@=gnKam zgkNI*3BSht6aE+TPq-KJPxvk7pYVT}f5IOz|Aal5f5Lt)Z44n^hChyQpi9djJQnMd z5HFmcOo$i3Pa(vQ)8r812SV}*Q?bqo@q+Z}glA!$6XHemrG)7&t&DKEORFHf$fbD+ zN5M}LUXJxoh#xswM2MHn*Ae1H>mbBS(UMoJ_JVyzc>JXGJ)_>mzGGl&ZQ+0KJLuePq z4p%GVzs?rH@lq76ER}e(;LMf{CEg@B9IjTDPP|TVR+Wt*?iKue;u*w?1Se_PWa2r3 zk0hQ$JVS6cEt^I>UGQ&nMnQyj5^^UABgJi{R6VHxq9byomUE;!T2=5^o`1Cpbkb+f3Xmcm?rR;zfc} z)Uut#a|G9kw-e70oT8WQBAzbzBH|syQw6Uh9wweFcmwfn;+o(~iSHxc{R79pjJO87 z>Ff}^iFhLMcEMK@PbS_f_!{DaiMI&8mN>iz#xHm?aYRKJzu@bLrxULed_D0o#Jz%V zAf7?INbnZolZodDzL9ti@eIK?6Q4#rUGOc$i-@NR-b%cTc(UNzhX6+wZyv* zaQtr(uOr?eI8|M?lz6+~?-Oq#-YPg%U$%yLi{Kv-ZzkR>cn9(I#G3@)O}vG8o#33B zvdzT3g6|>TO1wyLPF2}X;yHrvCEiXvLvT)A*)HPgf*&B>K|ED(4cW3V@npdhh<6j$ z1WzQsk9hb0IQ}H!T0h_&f+rJCB;GD~3h`v(t%46GKA3om;QS@4vQ*;Df~OK6O1w$% zG~(&R>jWQ4d<=1~;O7(1AYLSRI`PTGa|9nrJcoFO;A4nSBc3k!IO0XbQw7f;UPe4w z@J!-f;+o)-iPsYE-Y@H)cpdQ$!E=Z&CEhN0KJg~vt%6S@zJ_><;Mkxr|HPXGFCxC4 zc$46z#9N5h30_8gGjXrr6~tSK7YXhqzLR*4;5zYk;u(V165mBUUGPQ3JBX(WUPnAk zJX!Dt;@!kG!Iu)>N4)!cS^vZ}gz23ff;SOQB;GFgYU0VnTLoW3d@%7A!PgQ`CEhG} zGx4Fsn*?7+Je_!*;OmKxA?_6%8y@DLc#+^O#3vKa5qu-@9O4;*ZzevCc)H+Qh!+u0 z6}**r8S!Mnw-NUe*96~5yq0+PK3V_7>xg#<-cEce@pi%AC*DN7Rq$QJ*AQli<6Fw-B!rJWPBuaj)Qeh_@0i61S7d(Y{GVxZy2NNGm zyhZRK#8Zhk3!X}RDDfu2(}<@NuM>PI@iD}`f}c-3gLskP>BJ`!&k=ki@f_kAf{!6S zjd;4?xhSmCkx&{yqmZt_)_Bghz_DI88Lprn}{b8Zx?(u@nqty zg0CSyn0SleYl){4Zx+0n_)y|ag0CZz_X@s&cn0wz!CQz=CY~esM&dcd zGX&pEd>Zj|!M6}EBAyC7{O4r+VCC!I`4hB)z^5~I)Td#jnJ@f(-H!U9$gLgt(xM&p z=OcIAtNU{umxL=-&l32K2N9QU(2Q5lcu5KL=_2+fr}(<%|e(^bsB<@?Edw3)Lqc z3G({1Q*gXopMw8(V$egL>#xfT{|Ae_zU>T=W=MFz8~wD<%XMtyZ{YuNY2m!x{j}io zBFdt)gpfbY_hV1!^J&Vy^GJvh8wWWKh3&k(2( zm-DHbzG!&sogcd&x$|ROqPKY*vS8Z?e%YKbr|m_sB{Gy zJ5Z)y5V|J}IJ`CR;ftu#{`-{s=|+|WrT&-<6n@*7fCx9koz)$9fsEWw-$PKpje^_& zp+m(7s9u@lFyq$xwzumOw7Qo^!X0Y9Yy2-`fIXUioPSSJ&-3r2Rrmm6CjYkNke|U? zXjKLNpVR*OzJ4KZPuH;%0;|TLWzT9U4+=8&>+0}!KN-40o_(Bsbe9(%CcPD*w;cb= zI=E>1NkRV>bO)8V(O+m4OLKeL(OYoFfj8QML((8D8rSb($QqcjH*`-e=)?cQzxuWl zz$)O|7g&5C^hy~@c4Vf(vNR1ai7=3lIUAQ2e0~oqLz9vMjid@Rl0_hEX(($c%{9Cw zfb*HwmnzZ1H!+Cv$$Q6ssL`KPg$6k~OAzX)aRG`lcp)`YS)i*CT_Lg{6v z)yu6M6zWlTJPynnTLX=y7_z(JNOt2dRYM3$DXC61sJ6Nr{tad&fxs)2z%T!` zC8?pTe+BO0g)(~xB&CIEvOy_nqW*(fYYdGwT!^(0;kcqVj_wr$Ko`o|9nIAf;oA8* zmQZNE7TWR)4(z2__}4iZ0$56zd^5_+Sk5bQs%11w%2{$6g*V5=OEv%79GCY%_^&yj&b6qIG^X2#s}%Q&65;b%G@nN-J`*iIdUh{7jujrCM)UZk#p6q? z&Y<@|=(e6f?SanAses7j{Kti|u8o21v@Hz(^RF?kf;F(i@JGyIt)cW?W@QPpq74|m z@ymoG)53S1fb$wdQThb`n^aQHfxtbs$#<_P78yUmv~%{ut!Uagm1PAx1KY{85+z-Y zf$d%O!ARpTT!EYeT`!xwvwGqE5XKkE`lrdel)Qr|i z+D-fGy4|6c&hZe?SvCPS=Pa8Gx>@vh{yk&h?7|1Ix7N1}TO@8S=u3pB3xA0+tfd`# zMo?A{e5Y(%+u^@<$O?mnX~SC^zuh7A#PoiF%i*XjH)X67V?9ny3MON20@%!Y29dMx zmqDosy?hrIFDi|#uO~OLvDK&vChJ$CNl$KqA%oQ~CwUwsarA%tj{dR~7C>)JMw`wn zn5VwroDwNzq@N`EioNi5`bk(K4HH1PqdzHvQrbD3+FvEkWMBZxHYKg++JxXL`VyNY zu!ZO5!GV1n%-U_K!rky+D1Jx(3b5-8BP;sO3*U_kqx!bCTNvx47^8${2Z?GhPK$3u z>w`Gf9Q0r@-y!l*(jETYkl)B{i{v&&a;qb`hDdH*B$pq_>5*J%B$ugj{%t8Y&1h5d zzYD)v-*$wOzaS|xgfoJP+*N`Fv=Vy#o@Dq%6(a%Qbp3wC~=Owb#;I z*VC4NEs*Gli=dW^;5%$#^=;=s5@WA7W*$QSEXt&<_G-Uh%w1370g3b$Z;ot&T;;{6alU5Tj^#&o?7juq$*Wq5$8_Aa+#d+>Id&HCV7&Fuft-lRu^2 z#GzMAF7G;5=5vDlu5e2MLIQ`W}LDXf|=@xkDmxPiOxY3*7a;eOuvd+E~5&Z^g<3R;D|fX1Mc6Bln5|k>N92!!>5ZOHf6Bwu{y~0i}oz zn7tTT`r-=-;fsHCAE5;emT>L29O!y1SS_CamIIw9fQP-V^IG;7*&oGz#^XY(zO80~ zv7QQWQNZ@sd&0r*5#dML7=F(pnyGL5m(Lile_LFB zuQ~YT3O~}u@GBO6t4w|y(R8kgTl2fu3JN7@*E^}_G@8l}Jdxco95{C+O{NE^d%xbQ16`DMoC zcY}l9dz~CFX$^kCBy~NQ7yjp09PjbMFD;mrcv-_+{gU*|P}8j!{qSG^e%JhCFT0Z^ z11?)iaI~>uNxTuhH7u8$d&1Sos2y!^*WbdkG$+&=&%UI8>$GGe2y z2P5qZ;126wUr;Un0US^uUr)5Zo6)%dG#3A;^Bpwu?-`772d5^Bb`e@4pJYUs zZ!o^NjzL9MQgG@JM75ydh1`_1l;G6CJXV^LmK>a#0sw+!fJ6jff$pI10IpKs*qWd@ z#xMO1mHvj9{RyiWKBf@4iEl)YCnC>ayF4O=$YTkTWEaFxn=zggjt7I0F>^f95TYkX zwLrXkQ2pelyy2W*i=J_MPwrp{Z{MG+dV46JJH#Zj>W%iPW`)|{BK7V~Q4G@FXp{9K z^@e^2oBDN3P(-mq(I&!Ah7%@3qU4Pl z{y0-?Ydlkp_}6Bck%4DWSw=ilugB6TBamfbv)8`*gEHvO9>1FY%RWC9ar7JO-*Ub2*KZ%~QHL6Ov7cI7 z|F-oI<8Ky4Y2;A;W@Q~>QIm7%HAbd3{T*t(uWT?{8-{PKS3`g9-}Sy=RxUMKM$2c@ z_sV4k!F;>FwAVMq){B2zx!SC7%47JWm1_=B&r|Ujd+6Kzt!y^h#@7d&h3P*NdRDG8 zyRqimkbk{d(Tn^WdaIB2-z!^$PMs$i`?0n~N{G>CZ}9=Q z=6L%%=`p_81qYFOqmR;eE@iO%LySHoCUDdn`(={ZFlIh_H}Bl!D1T=9livL+w*5ow zACYa}vKPBO#oO=Ws4F+MulmCFe^7m4tGCq~>!Yvsz>pxGzwKQ=>2dYbJN?Kw^l|Mc z7a@S!xMSznwqA1M#RIYCn457B{TlWZ2?P$_-~S;VF!)CTff)W$j|J1~c;k!*%cgJZ z3k%m~53;@vvVIJEvGl7V{YczDm{$P^o-vJw;hz{i+xAbR|H#5|>Lc1;asgTKZj67h z)Ml+egMY-aIQhrB{yCU`i}qI$w`27eZ#_dpz0Xga`Gkggr?=+Ac9~)8-(C-OIp;f` zd6?7f{wHR>tjmsG5T(c#xR-IP$`M^e%54dbp9pqCc2FiKlOP zm)`l?#&?+Z+_(6L)_qv(6-Ito^bvnx^DnSyW1?c#-yzn2-1P~w?p1#VKUj2Zf7B2B zNvav(4aV69T-YJbAzbZL_6;-o{VE(*jf)Ef5h;6(O1Oqd#UG!DS=Wi^|0`R z*2AI?S`Q08X#M0v)K57?ea<23^AAx!?GW|Td##VNUa<^q{;BtPCV`uiVFnR;bwA9P z6kMzfflpv9;(1x3?OtzR=y7yqKEe{Se`3wW&Ij!s{nN@99|+n+P&Th5;V!QB^q$-l zs}sdA`g-$l`Qfn66uNhQsWI}&(zN7rEYY4^oJpE&4-yYBkT!Z1{VIK62@j6xP&8n5 znADS-W_6*~e?*^sX+G3yjxgHZ|6$F?`8GDjg8pgqk$w<<^w&}LYF;}<>1CviL+tgz zq1%u7iS5Vz#P%7zwm+=-&5U9bJ->aikIAv^`=Yh$(q!zK*sN2qdGm%sM0Pn-wRry@ z_6IpzwK$0V#po-Z|CKXWtKmW8jkxW3Ci_#`^XT@cwCB-o{Pu^lepm7Y*kW@S`fHAA zcu@UC*`FK+TRq0HC(fTbzwY&XxOe+r$ur}F^0(QmVXWraq8KWl0feFQo@|188a}B< z4wx;bfp2@;FOtzRa<*YSOK;o^Udc0Pi^DUS66(b>!GgDRd_oATI6YdXYNlS^1VhbBOpVT3_w) z1hea_Z~o=|cx(=1eet33m}!f&kJuO=WnKA^IZUhG7=MRZVab0zZm6Y0!*T`hOA9U@ zYARY?EDXT{NIm5B{L0;6?cbIzUk}(npI>DCq{Lhf;bDrw zw$Z_q)kz5zJh*4&K5(=q*|vV-jVJp0*>=7a_kK^T{6FnHw)g9G9#q-aujRjaMjd-S zE%m0)rTtoud5Hb?ZT-s`wq@^e&Kr8W|IBUV>9` zjf#yY;`h>mQ-{KKl8ohojfJt3T0?U50aR9xwQ70>sTCPJA5r?o35)G|K4w1RotGY@ zy;Gm?EcPdw;Hn@gW*G;jap$);dK{R>rH|Y=kq4$C>}iIFLl4_LEPC8qIV^gduG;Aj z^SG2pF1GWIL+^*V5qs_1eD=Pco#$`P`Rzsjm|kPNM*ngA4<t_h*q~xXAj3 zjl^L{_tMM$A7!tYx`Ww!-22JB>jzVFi1mf3i0Lnm`0yCL=_CGl;XwK{-t;*A+x0s# zs@|C2$TgeekkAo!$vtHIes4Y>ahUealk=$OU3%AdMqGXOPM;Z%UiSOk$>zYVcu3iw zQ9q^EdNYQ#p47w?DaV$BR*v)Pxc)!C_xX;B=W-**?h*TsuE(*v@jR?iADFQZ-+2kY z_?#CXz=(fs`zv=fs_SEm6nt<;b<+zu>C$)RGvn-!w z|ojTEF0=x@g$zE#n+3atbk=HA%DJL*8%g*GVDAE34F%4LXBw4KYizmvT*$vpveo+Irn&on z05!kd6MB9m`jw|>@zsqjzr$10-CcF&dJOsB0A2n5^TE*FFbfYSyO-w(^T9Iu3#I&O zmapKODMJ4CZKS_I%186N9sa#iG7KfYrJZN82z7nfBpZutIz(nuk_(qtJcL*3QRJCif*m z{!fK3UPlJL%Y`%p^0}AYF8NZCm9N2YH@2gslV2~Cd8?LoyjFBKTqm@5pv1l6O37~% z4d3c+e1MHcvrO6V3!=l>?uIjja1Ev@v}z0fQ?6rBrsPTx`77NG-}4)l{$!DVq>}$r zlqtGe(E?s42RYsr(rGAhFWV~lwNlF~Pj@5VW7PQ+i)nXjWWI7`UhWlIFG@nIw&6cT zxm^(&&$Ea8DMEjP(9aV3jaaSjWj9KGx2)WDyoJ%-xE>{)6IraEZGPW3%Ab_KPJi;i z1m#aSgCYOWH%))C?GIczv>3~u<%=9N41TBx}Pg=pR ze!pSouVR(CS4Q#wem_?tzx|->Gg(-dx*O`HG2Z8g?vufk zZe^adJwrrxxf{v9^9E__U;h^Sy;kgPk~B5^NrIG%_h>Nui7qALdE)pJujtKKABI0k z6%o=!|AwD2{K*udd|TE^tUq}|gsd_B$ub$Q?rt1NnQi_gUuH!-hVmy(Qo{Yw-LOa& z{T%6Ad`{z=T$LVc-G3wc<{s;AxLT>`L1(!e zZvonQ0{$ue@0E&q?gp38r9f`%i?V3*WJne6#z}1RPn1Q@AK@QF8{#<{whMWyl*kU) zn8Fs%u-NpsAIU7({Yi?fzC4b*aW_aim)PmY2)*5(OvZXP{mCL(+kNyWC%r;{a@FPH zPyG95hx~)zfiszS+qEHo1#;M4_0b`J2C|EWh5T!!XpVj+1_`CA%^z=mF&FD=&v3Dd z{$k^gc1Y&m@6kWShK}r#zlZ$w;DYbc{wd^NFO{Xf$GWzgiZT2r{2wBz`u(&E{mLb& z{{0o3VTPJMXwk^}FKBcA{rwi4!n{=eiSqXgU#2`yjZ^;K2+Dr;JBU+PG!t%+rCyH^YqKQTti=w3bj*`wExG2*c z{e>8}#G9RTs>_2i@O7dL!^uNy@DP8HPOF6&d&d^C@COA&*m)}1u18s9y#9AY3wV7q zbQ_`**ewPQb`Rt4dKw=RXQ%%CFZ+@B2lb(}dK6lF+LA@Smgu6+<(A zdmD_5Yd3cTUqTY{Z$^oG*(Z|!L~13vZshwhJO999%5(mEY-kHzeFyv)*TGH;g) z?R3nfd)WxdFOpeJ#R_mYHnH6)X1h+|I8EC17up1HaH9M%k0uJ-Hp@O?q4Xz zT1*W2>oADULbkv*O>nh;aL125uD|wtqV%!|&AN73>*sMu*|pQcHxu7%;qMV&Z{hzWZuuMk zH^i4(^#j1a(}#7c`Wr%=uRKtAI&pr>R^j7_XIc0Z;-f5lI`OkCyn^@%CLZPQ120ft zFOOFHk1OQg0%CpiZR11!50S%Gr=Jt@e=XS~^wUEA4bZ*Xhj9sE`o@dbQ=2wb(k>oD zD{Qu%U2mu>D(iVGo)2=qj*|W_RsHWfB{E;&9rB<2vNd0Se!Tbj+7LZo8k*VXE9oWR zw)sjWZkw;miQDF@9YeIwS2uCne5L#e`t+Il4Eb+Dd;5I(h!w{?W(L2nUv=9JI6MMN9_L){UcO%Z>~0ho*Bkn|?&S&a3?YBw2P}I7_4$(-fxK;|v^!M?0FJu?J74px+oH96kJ>+ke+By0r z^Ey2Ty(p7Rv`li{V>Fm9>^DP1@OgS8oC?~ymo0=YvE4{9F5Bk_S|Mna@0rdUiNkdt*82y@nd@D$vfhtDJfW0(l%?D&9G%EM@VLksf4!^mo+SNWW%lpE z#|* zEi(S$GXBtnwU@2LzBGSi$iD=~I%=2$tzi~Pk48T>?Tg(88~j85iG5;MPe;f<3(dQ5 zeX;i+fPW78rxO1oq9MZHV->Odm5~2b;xB~!M-u)P-jwB!h5Y|+1$;2%|A6ow>{Kid zA!H;DyDbCWc?%86{|JgYt0cReS-vkU>`$a3%3#S_hV_7WT&&VL$Y7IhAeC!1S46Bi%?`! zm_-e;d;X5>M#=t>v`;BUwVCHoe$b&_4j ztWUB!vvVXnh1o*MrZSr^*#mz?)`&~rV)k+=UB~Q2lC5QSsATh*Jyo)4%np+5fxjR- zK(f1-<$Ezh{^=aWSCU=F($6GY%k1AIo5^guWCt_*d&!1(A^VbKTbY&f2>&u>jkvUk z*=>gMit)C3_pQcSzR5?5&c$hFQKx9dS3a9%Q55k0Sma z@6+3dS3HKFc#8h+Z+QK!L~6bRcxMNeBt*osQQ=}lZFuvov2!Hi#c>iD|1a9j;teFq z(c1PelYh4GztzECSNvUZ`9E+-{`Gst;9!7nL+gB!@}ENfeC_FH7%Uzu!yx!pnjT)P z%WG}R{sZrg0Tp4-_wVb`FWTO4Bx&(}&d)F=<0YfGSCp!{-Wz$~hNIgk?}fu_DYrLD zBeqa){Wacf5)MCtw=8Zq)Byd~@8O$;DPOk8ck6lFPbe0j{_*3rPd)zDq(J{rV;Dln zi*ra10Z(U8f+u%(ghzoTg%|N4+6!t&jS?-e19KC;s~MztS=kM3{WN(#C@=gju3qr| zBlIh;7D)^W_t(L*vDLl0HR^ptc!MtAP=kPu0%8+fEseLIi{BABF_^m-@3A}D+T5D# z@B6s~;TR=Y`fEtARgS^@`+I!v22XTv8dSG`y1t`s|AlCaF4et1k&o{$zECq^R>U^h)gJo`Cm&{0NTo`e1UfAX)q$EF1ps7YUmC zRlGIJw=d+|MIW;`5gjpJ4Hi(xc)jEMz!JjO{6I^2A8(El`x!^wBn7il020F^q;eNu zew?%S(p7X*zT*P>?C+Jt+A!aUo=TPAAnPhI{$b z{WKvN$xdWx8TaAPGcxgAZLo@uBUaJ1JhH#Y``@uu;r;Jt8LlQP8OloK_@mS$?;gGh zdyGv@qNB~!k?Qpz5rERU7)x1FBRo zS+b(7%aG+%B;i!q()|mVia#O!HB!`hP1GWt3oL4WuEAbg-&TJn=VvOT<(Sr@C;pdMBqDc15Yrle#ZY}Klh!Jd3>{qKXov?2Njlo9{XKQN@I_n6Zra^ z{kV6u;2H=t_PgpmxT01YO+R_R>`s`8+A-u^@{!$yKQ9qw8-^ZV<2Km!aFZ#pF`Qq+ z(PI2{W=&R$~;IP@Pm-lP<*;R1N{dV zZ|TIHRK6=4p@}&|e=rE^7Nz$Lb2nUuVS|)9zhjw=)?oUOq8$TD`L+j!KZ{gR!(V9Y zI)6-$ufgBr(mjD6{a^N@Yuo1EaRh8C8AC$UvGbhoWG}!M#SAM<3TNLZq7TRG&G&W= z;Rq2QMGJkRy^Hi7{R#hxtH5a?SaOghz8z(S2R_X zgNFys=3=B4@5n~Lj2Xd3yVh6{6m>c{H<_#rg;m;E=coVZZfuUx)>Q_{ z_RRDi#yFj~ks^qN*wgrie#?u1R!|`q&(>a-a}PWUZ?XjCJ?&Tq1<~{;qR!@lQc2I- zDhLw{>w9~(;cg!M9e#qtd=c@BC^S63v0*kwyiV7X#{J=G*etQNhdUpX{r_~i{&8=@ zSCWj&47ihhW+%S0JfcmWjI^`_kK;KSXhheY9rSE6)d*jQvux@v zY&4AjAQrcj7hkY%Dcg))=#Q#$tx-u4I$eRu2jsMv>rSpG*HcH(P*!62TbOHo+t5=b zL^8rXEC=J70Ly|M{pxFsvOqTFTlO~M$13EDLK6-&w$>ia`WxuH3U;|SWnR)VZo0dX zuiC~NtUxB(H*TE27VJXRGv<_yv))R+>qrzaYCi%$Hxzl-Uy=|` z#`5&9&l~MFQP?-VE?0GpqJxG*aIuYd+Q_TMe_X4_1D2F z^1@T3zuVBCf6q8WsYz7BE!be#gRw6Ci+8!?I{cW+B|Z%XQ4_x(WM=XHzv_Z;Kv*q(V}&p=QF-UY#ue>S%rV{ zFXyF^f7>|oQXlunol8&#{^`GzH1Ncc>O=8hs&2A#C~8O zyq1udNxm&P7k~eadCvCp8#JC zZ6E92bgfihglgYsT!!ir%J^+CtcLLKAw$#=)9dCwRbU)Jq6H6oxQ}&0H+EX*^|D<5 zVX5Hy&mr&CIQxM>XF@(xrVA-D4&yG=j}d7hpZG_r3u1;Vg3*FOdhS592L=KV3lySLNHT&FE_S%wo`(0_ufFNddfm`bLilLIyXm8Y zKf~EoD6^jn_D1Pk@4`=ueL^we_xU(MoG?M6av12kyI@xz<9snzo;Ji&^=;pr&^LK* zT_)a^@`R>-PFe7U4p+Nu6+pl<9p*=6!4q&VrYgeQzhE(c{wkQUx3SfCZ7Ay#=?QdPmT)U2 zZ22_n_$5joCpRNug0O^ z^+|z(HC?|k;;yXqhz_uqon}y@$F4tdT`XRO?$+x&g0+Y}^j7==Qe-eRDoA<*FDVK( z^C}mcBs>0)J|}Cl!3mO%-4Ax|Mn2Qa>ZSX7dX{Fb!XXi&RB%fY)hL(6IavVpkR9xK zI%tibDN%vM)rfrMdmhq!SG?w9&>TO{L=HUONJ$G%5`lQZs+{0Lj7feU+6?vG4Vh5v zYqV&bIr6tbmIfCuZR}angp=H*S<7T-2rbTsFT(ZzGI=7zysmIJoQ=lO*9ymj6MxJr z#hCHEOA$x*KvR)W^;3-6+V0&e=17CcaY-8*P{^z7ZKy$eoBu{%kgQ-Qd}z*$C&t@} z|189jlf9WFejQ~-fOI@i^_y0S$Wr$oK50L{+7j5&^>JW_`U$MvcVa#4;G)l37XA=O z5IWk?^+MMk`SFyce)(aQ&drdXVT*D0c>;zQ31T{N_uf{=fE@NF{u_s`d7-Im!hgY@ zT;F!|Al$X_VX?>(Lwu(;p{&)imM+1J#93k`pR?FnVpsFWuVi^iGquWoz)&O0LoC(Z zc&RKYuCTHD-HpGDSzw00g&ntk1Cgh04(y0p5ipY9;TSEj5B7)ESE<}R7I;kWOW1pX zxlShR9lH--=z$(0Hd2nxjVZiRPQm3Yz2H-#44JIT`$K6oImh$^~hI3NuIRNQ#*3IR^3quTafOxT;w)JdWWgsq! z8akZ87Wf?Fs*;An_9)zeP02VfGOrRJh7{zySY5aNowg7w`j0fM0wsE57Ubpa3|COD zDMI6M>AAiWU!<|$Ux0HHcNcJlu8{h5sE;U=>(pEmfvL;hoz>G`#ZO`n7xOBy=CKb>A&Af>Yd7Z!Skryt8z1O#`I)?i?e#$|v z7qAlLfa++>vvI>!_D!_U3lA6i5|f_yXv{lYL;NPW;Rl4?CG;1W^s?VyRBsZRq6q{& zz#G|H1mEei{m>ZNg^o(>v%*<-Q*80;T3_q z;drdUPywB20yYDvOB1zB-oKp-r~}<6!sUnj_pw_2PUB{&V6M=n~V2ptQa`3)h9_xx+Pcp=yOuqGMR~%`$qcq6W`H9{2 zy$jZ+hY3tw=U==|Te9AEnweV%M{r-n=TQ;|xqF4&7qM>XoQ@`Pe>c*qDPF7dqCI6N zW>g+Mi?njyyDf&?w$qQzY%mpNMx;^>l;-*WvG*qMQ5H%6coIg47@g>{$||dw&D-BFq4~1`=lm^X$W;C`57B0~HllR#6U7h$bXvqOuwhIXuIm z&M>H`$YmD(-*0t4$Akd7>U;eDub+=(o<6FptE;Q4tE;QKJ}&Z(eNj@1(pSWmozNEv zsW;P-sAV~_?-)Ybo|?@Bc{A=1BydHC#B7G2sa24RUsGdI`pZ?QY)=H&zmxWXMS~L^ zA)ZRAt~k(_QL^bFkO2!HJTMYRQI-a&9gBYLkA5JGJkt?#tzd8Ip9yE$M-|6gg)@!K z310&+nf5f3TH!^%)<{ikhHciG_MDxD)25k;kC5H zl7(f(6@|$trvl@T{h+EMty`H&xsfUK?t-^WwtA-+I-{q+c&SqANf}JttEkvqa0hAy zwuL&IaQ9K-pcaMY9HY6X{Bz{K8ed>rIHBsqw&MLzh>4opK_%yD)=|qqrTm#B*s1qW z_$~6lAP2*C$PViBO?meiy%aJ;e4CZ?(Y%Xr>LVYU3#4YBI=%DOkthwNVBzyEA2^4732_~7FGZQT& z23s6tnaW*}LoR6X2v22FNxQcfdy%6i<~gnIL*(d)iHb(-CSa2I225niPqjR*B~vMr zIOa?0#EI zw0@Fl62m}f&wUHJG}-a!tl(Bv%43>KoU}*zskYd{dMoier2X5Z{bzkn`vt871#Lnd z_CR1IDd=AK00K6=Cfk2{&*FCZwDxykkwX7H?dJpva+_#>=$-&=vNqZOJ&QZ-(?5=f z+5LUyVS#r;Esa`v?>&;pgdPa{j+5WUytsAa0^a;w^WvN)@=0G3@z_gib#_gB_MrT)4qI&gX*zQ*~4I4%5AF zW4HexbV~UDXEkcSUu(0VjR%3_JqUDc5&@`dO|}2pZD{}9y|@26Y5&4K+Rrfya`)2y zoN-MNU@z^TFYW8@JM(MUP@`sW;$i3}B~|ZaQllIIw>3IZwQ5KGH!+I3aA5^D=ZD%N z-kDE!nJB_+zK4%-_F3@al4)qzqWq~@QaD_k0;|_D0tV!?&Jdewj>}`y2 zwOO>xsKNc*7Fb)Taz2Bik+?5Vv?81`k)6NH1o(lnKVFqDinh%4XOF=H)4Nk=+Up67 z`Pl8#j(l$z@+Z$1sqh(j*j~8SEF7^5@JvDk!leKgi2EbQKx#3GMld8Fi+=D37!n1@ zQ$}_w1|a}(ldoG|b|?pi$f-DFdqmb%lwd*d98~Q@@K{JUlWKBg1Q#$3^0|JZNAvig z$_y?Oyaa^8YWHV@eJk;X$gJfOW-NjIf#1=$KdZs z0hJRsJOFK0>>AK=!_`K9Em#K&Vt#G-RLwVEk#7oxZ@`2Y(MKY^BEwVI3_-D^Qp`pW zs{&I8TC1ZJqjSfd4<=Y}GT@LrLvBNXLKYydSlJ0H+ull@*j%P)bS1%f73uAX)DJ+! zQKb8dBE3q|Y(=`SDAH9(^L8%N?%Y&S4prycqI0G!`JTiNaSU#jQAIFgR9V1h{I`5K zQ7_Bo@3L$8JJyQ7V^{IF)tdj7x8c8KKKvV5>I1LFawLJ1WZY1hhn7s3t!5^S9?mR^ z!m|)dFz9Of&hem9jO0j7tCC&3xEo#{k=f=m%LpS-#wN!_qCqBG| zTZQpot2#`111V;Vj06a0o8<%W%UsaifpC=2(XRh@r@pWr>KjPWO64vX4pPwGv@X9$ zPmHH8K);%r7~&YCXcT?F0nN@6F}T$qje+jzQf2}2J=^iB(U266F-`2vbeq+toCmK! zYih4XEzw41soFj!jwCXT_GD_5P62o5nVW0})z%dD3zU<{{^$dg9U`XF#{NMd3c26( zxDQ39XPlCQ0VBOvw}@Kp==@*)8NIrcYIS)7+f)C7hpGB2EWcJTH4lHBJcp&>OEr^Y zSyaN6L0loP1}LrI55rFii4*Um3>6Z;5jry+kx`uU?mp>SA~J+?-r3!cCqnjD>MiK* zGx7hu4#1)501uS$T1$n2I{I%2@OuK(V;t&|UcOoosJF|n2UjKMdJ#xHHd%E<)+2&nH*u_Y*H=Uu2z2!Ck z`0rW2lPG;^cc&Gry@NCw;9?oTDp7eefXGkVX#LKiSffr)BlACDVOi(d()sVnkiM?7 zw{?pFCCQzm7YqMAcMCP0oopFP-Hx>VQ6zkmE2q{Z2NTNeImSw-nuuFlBxO2;3=ehL zd`72@hT?*qsgD<;d=f{&168#vdU2Du~YT-I%)CXS7% z{q}{4n67Id18XzJYF4?(S25T65>K*nVK!=tY6-n)+O254jAbkwjBWPEzC{#^cx(fz z0tR9z=K!S`!+xlBFq{ix&q!IiWt^yI)0BDQD0Y^EWR`Q#j4}bb6U&v7$PUoI!d*euD|=rNYz&w6ZMbh=Pq<_a zvz#oncen>Nh8yP+?8TS$ZMfqA7fK!(!%_0)t9x~^t{gH;TGJbs?61+jq+0wfRU)!BkSCPF7W;9`&=`d7ld-4(Ax8G2$g1Q832zCdT_t za1qCQI-%va;&`j}TXDSahIv?xH_vcnybt1BeuS%-tixtZZa){zrktbPPjvvG!dwsM zt|5m6XG1-bqXy8?zp#v?Qa9>^0kUuxu2d3}&l9$D9%4@pFocLwHc=`~}Rd=e(rbxWo}?5d`SeI$%d(ZqQH}q*fM>iVoll$fIoU6`tSkj$+59kp?U&j7fDM3ZU$p2newcwNNEy)q{9qN8 zY97)!_Ys^O8UW`p7#O&mf}e+>CXc&;8M10F%Co&Exumb4;y6 zyfYG5J<2qfAHwizY-(bR1*;~<5`H+R=@NrjVgr`s^fphD_1-yIzKm`DW)H348Ntjk zMW4k|Wk^eh)j>)*J}Z8fI)XUK9+cPJiopuXT>9d5=$BFlKqucJ80479I(%(C7+-1_ zAo>&d;%ppN>QU!Tw_EP784yF9L7O%&-CBhoV8xPS4in8JS0F7_>KtgN{^clT9c(b_ zTA^Gfhiir&fPt($5X4AwF1YI03fssNI^AU}ql}_J2?WUddw6qz8j)tPEW+xDG!R1- zrE_&b1CVj3Lv1W6z7JY!^+)OAk#WunkA)d<6TT4z^c& zvE`Ctii{v6V#dQmjqMOZYE5iy_4OPV3zGQ}8R}1LO0{G8zp9~DtBUU3!wxE`+GG}+ zgd>6ULZ8xgB4uqQ{T8>`jU3Wa| z7EzrcE^J2O0_C0wtg9227&XaZpn_5#lm$jAAYd#8#$6CMBsXqvve-Ww6}u6|obi~n z_wo1^<*eX`_IOlZ4U|7=s)_Ju7mGx4K6;h>JJ?7um6(0}_Y9%T4Szvk&|VVb39KjS zPF9reDpo8`s}+=5j=`uGYjshz9E(!K3X7Ucux(iY+a8>WI`T^F`@_Xi6bI#E1^*3B zjp6^XshL>8`{tO#a%*^0jMTH%?<#jda}&^I@9I9Fm-MmG3x zFosDN*B!;t7M6D2nt+*-E9GezXcKNfa7Ks2bEArb;E|yA&9q!h+XTeJ2d7<2un&g3 zmtjBgY#KZL5n|J)nYRkA=QUW~{ov^pV9z1>v*A&1fbl>o78U}YI`*w5|sx#+0f>94L(oh~m)>$JyX zNA_!j6URUeDybTTtpqL$@VLo2_|7tWw{rN;AA1|(f)2U8ay^L#6LDo@Lbf>?Hm*=R zwF`jxYB)|w9p>$*&bsAp<`|!S*8Ra{AO*bSU~QiC&rEopi+6vOD=cGgz%J}sLM}z0 zQVWct73u(1UDvsRpu;$-NImYz+wooy{(I021eT*A{03l>eUauYAZd03|2>CGc}G`R ze>uu$vAk!GY|up7yG66nx^P2n}H_j zeT|pi=QK(08!mO|?Vp456r3|*M>hniO_F}GhxDJ00O|j+SJFSQH`3D@>LL9MfRQu* zy^&sw@vhs>D3;%bMQ?AU@5=)FCB4@_trL`;lBz#`PWlfZzxN*H@TosGg*$38d4VVK zXeNT_xS4_S$nDw3oYd32c!2qb&f3GRsFu_$TxR6gnLWFkle!wgB{=>HEH#QM5CdV{ zg*aa;T+wB#nU!W7&j)1tyjR=DMcVsgBcU|HkmK0LgDZRh5GY(W{v|ViNg#h2qA{Zg z9OVMRy3o0L^Bu0!cJLq+c-IadtkXtt4Sc-<9tc;2*P6I&U04fywQS#M4fq@3hO1%t z7JCKksc_g+MsHpJOuK$9>w|wkLEBkV*6{{+;w|2 zcaSvaNVS96+%~Gw9;t@rM5$tPn})Nwy>;w7p3|t{l{ZoJZm1^#_d%Lbw8+d~Wcs?$9;#>p z4;_0NZAi{%IH8fk{)*H$V#i-K4|o8{0SdS6Kcv<-(6NV2N1|)f@$SJG zSWG?u#JMwMaV9Ry`KB6u;eSw@S!?vQL-(Ys7xO(-{-F>Ad%}vm2x}et@!=qV6p3dP zRl^U#A^yQa{Oa&m$=g6YFa1CF(0>lWy}t+jpT9!Z|4&K(j<`8$_J&~3<(X<-sIyVi zer4sZtk~9xC%`d1)tvTIW4kqh+X=DPp9Eb75f8!}`RGnBAO5wlQ5uB9=>})P3LnPB z3OC|%ahESW>`BObZFh~Q@4LZdRTsf`09m)MuUlWZHk4tIx-7?_ zwgLeV%}EFqS(*d80rY08w-2PZa64(2vAsh$M|G;bu?^=`2P(N7N%$gPNymaqWbbz& z6_Kyu8nPt39_Z`M5*4go99&%I!&Z(O%W>3W(!5Fz#&Tz~s(FOCNr91K!(}DQk-M!z zSj%S#=OO?W2KdsUWK?)5EVIs>3r6yjXxN{z$+s^?8%W5Zvq*j&+^2#@t@e7rVox5+ ziB#rbULe9}bF;H?x{(d0<~VK#Uy~EDu|cU?q_(d#YAX|2R-Ze`_~u3M%c-T~72sBe z2HH^JF##>24p2pI>;X4UxBv>!C|6CmON~0h9Z=%Ku)q-m)6P7nTevRN-CfQ_Z+F;u zRr-A5y&+CFElyH^>&m8cp}nE|W_|@QgHyM!)EI_g%}(CSRSL$uoD89ApmyBxiy&AL z8>WKNB>5=v)!y@ZkdZ@nb~r1eWCt_HzYiNtY%EHkGzTLdT*g01de)>1d00Ln!^J@RfL-I}6e^=^$5OvGVAn*#udIG_peq?11iqrTcNv zkrKEFhl4Bdk9Uqg;F;sK5D}@#?zDNxs7ahju7XYQ0vtl|@3k!RvNNBa2lGPzhbso> ze;DJ*cX``?i;>*vtK6OiyGY@NNu!dSUuykmVZnz63mvYI&~mVWoLN{;K`Fa0WQ)I; z&VJp_4&4Hy5CW~aHUHsc4UW|0MsD7a89D`9QE)urPC+jHsvtZJKEmn>4}G2x%x%9J z2u8MNh0cv^Zx(9H8}mWVRCV5fdI;*~sprD(EU-hfFh*|TQ7ZACw8Z8Li)TcscZH|B z{{HzA((kbk)cWPhqsKun(u5Nn!=*z2<&pyUf-Hh3W5P!Uj&~@^sob3v+dZ+P5ncuX z6^Ec5mqB^-wJndR04;_9hpbidD7=gvEn3ZKjfHMCZ#ZPh4j#MLdr?veB%Y((PwiL* zrQ`LHE)_cd%p2wwlDdFYxZ~m)|O9Nj`S(XW{cyoBH`}z3dAfN zq~}^4_AwL!0#lur>`gvlPKF_$Dm-#8G+E?R81iX_*`ga%qcfGEQT2xL3F)5*1&4Y@ zE@E-;)a_1?1wc?7eu&V0xLXk0+v69K+!zoDrDnluEtCw%4@jgyt$*@l@_>+*Qb}Y~ zawf8Esi0yQrAvnXtnL~KzRHJWI2&oN0fM?{ixZ!FaApD%{ukKYah0Iu;&l`RizLCf z`uJchQaJH@kG5r=|1O+bQDRosH^YWet?`h8Ie;Gz)^hx9DR?lFjBtgCXXzP}B=8Lu z2{@T6G9=Yr*w$Z@eF#XNKG$r{0rL1R2DXQWdt&jt48rsN3C&#k&~YRcYD@=5-M-pv-l1qkE41q6mc#UAawRnTBEvKsr1Odzv0LcHG0Eh$u+|AUYdeX3HgIV;E zf8pqZ)Ovt;oeQ%N+~_*vnC@lL+p&s+(Oprq>F6&$KIqMvf7(chff29%5~pLkN2t$KYb zZi^JtHx~g~iQPxQ4i@;pTo#(N! zFErr3g#mGb_b=YV%)~^auBfhE^pu!WT&}T#C)3j6}k)iyt%g}PPLLwoBu(=vwY*vgc{7N-{*Tw1s9em zpnDV93W3Z*op&cX&&Fhg>vVkVZT6ZJJ|cMwz`ODhszMW5f$UzdO^NC%TN_%Lmv~USgzZHuTVyrAFJ=`u7{t$Yibc-GoMveX`&EtHr>GBHZ zsuIxjYoPiA`COX6gjn;2FCgEA3V5t`iM(Fr7<>A?s%wsE;QfSfH5{n!iJ&2?@bgl4 z>FqC-vG$Ha7OqJsA-@HOgB-r9Q4sP10F=b)n0iTVNmei)WAy~`jh*Knj_@=>>F~D_ zNEbap$F2O&)Vc?wu0!bCAq_O4KYfvbK`KCLr66JR9eC3yTom>fBaoZ1y|j7gndDTW z1?!saVZQ?8&~(Y#w6=@Kc$u5 zdJh7J4oLF2NqLkFO;+MC%w2k2;C5$oC5^-Uwks9iuy(Qp?*nZfynv;|9!F_}$adu>c+OQ{*|e3A9QS}*~$7@YV6 z^q!Kczr5`bu#i{dgZo7m8m= z)lJKkJ_la#wPOZ$+KEDNB?fbLrV+0xW_L5<#ZEiLb~|y=4x~k>N4<0WG43B(jDkM1&tR)BAYWyduQ4jn8@pztjwC;nQj`CEc9dKtH)<) zw4#3kRowZZ@cAkWC<)1hJ~;oye8>6kTO`d**rGruh;7vo68uqWHng*YBUKP2hzQ}H zTQE9w?*UI(VO}y27sTOAEu0OGf$IZkqUQ#OGygGkMBOfT?_m352Z7?+3k{~IEAge{ z1kf+hb(h#priLo4S+Feyo>%~Bz}k+cv>PM7a8Zj96V%EK`ze$*O{#crAGsZ&Hsp`u zfy5Buv+UWV-jCz~Fu*J1pYR!q)ZuQ%yE6J)mu966{W?rk?m#g7$x--AdoG&6P`!9O zBGn0>s&U!KaY-%GTN}6^qfg#TzpK$>&$-k^=VRhjBh9JsN}~!XsoBZKYBe8 zUU7_O$=`!8?iVBi^oi6`3a{X-#EGbF24^Y9yx(b1iK{R_Y7oH5*$H<;t<=Gd?M3$M z5(o~rJ#jWx?~w?)!fvNs0eMUg+gnG{Y5sQ- zx^|UX7pq%c0i9X+CXbW7l_WE*ra871h;wD1j}%Id8zctvTjCjRhr~$)pemJA-3V7{ z{oDq+_2Ic}G<1?xxRq0y1m^|H=_GR6#zOI_`yh*s-+?-b>-Q+^;zRwt5;{&v)ps>o ze}}a*8%?%@fKc%_*)D`bXUsvYz4ikk(qE>p4y31h2UyFmE2V{d(E@H7z>nRC)j?z$ zWy>fyBO8uH3i{gVe15IK7nk_6Maf{$>S2_vV5_R_EK|Nf+8k5i1c{D*FCy6X+ez|7KlD$brP}c& zww~>z0PWe}YcsM%&<;%`D2h}EZ*a@!;7wJ60L{pJ-Qnj14r`Luv`RR&0L6-Y!|tGk zr=0o@x-ufSIQ3boE$~SEy*Y^EQ1o&n*<#i<$aHcHGSc-(Imv;rRcm)qv^b`j`@nd1 zJaR=cZHBQQXt4LwC7VWJq!^j$HfXYV|F4?-yB)@=;>FeIT1MzNa~=n^O9gLzyoeO9 zxk=3%YaWY&zKNaa6S!{~0_9lKzE=bgRq$OgV)2qEi3OXD5DR~Vccx*GP#ug@7Fh;R zi5G#tTC;SJu;@6fg_&M}`3aPsP+tzY`uwL?pZWgsZT9H{*w zuD@|lI#0M4I(e^ekhK&>1Q<$>BD8Wk>0>Fj7I0li{P6)auaFm{wYBVnIVc)igc8WK zm(H`0XvSC#iOT-U%?s?-ZJ@81>ZXKB=!hE#Pz!Nh6D@-g3nyMy@NM)#%yE{wrUC4( z0XeM5f#2+sD-jql(J#4|c!tcCYshsGdDul^V@U#u!8y+L0XAQYi?UJ1e^pV%%8dFF zn-6SBnD#6hlOhVk83z*O?a0=BxKtA8!f$tq3FQI+RB^8IB)$SKSdrgpq|rME=`G!n z6MTpLgvMc&btPVU>?UCBEQ={%6j5>X{URzlL={M0JA+8F3<#{TI0-DFE_UjKe+jKy z6Ev!nWM<*AG5+ zyd>Gy;u`co_LnHQ@|@kfix+cR!9Zn*g!acu@P#S8JoG!AB}-fAAak0C!sY(53RCU~ z>yv`Bh*KFET_r@f{s8LB9g7Tq^g!ggLAd?*tU)HMsKEJ8%gL^@<2U1>coyJFJS_R~e2xRB#Bb!X05%P)B5VcUv+`%N1nuR(An`DnOGeVczHpJ6dMs&QVaJd~%82M}c0g{l#Q1(S zRD1pP0>2bXpz!BFttkdMI>TlhU9F8&lNmwrg{q4&B!(=0<}?cVWb)s54?P1F{gYq7 z&*W-|ZENv-WLYx!hMMQ3CuYksj72gNMWo8OC!A-J82C2v_8F+_#96A~SAHoOVF7*` zn_DgFu%{pWvlL9RVG|0&0?ldhVs( zXBa2X-HjQn_b$=|0ck-YaDU^3avSpXHZcv6S5AL7bMW2!B|QlFBc$2&dhVs((^Aj5 z+}xb?rXdZZp<9p;ZK?YkCpZ}Ow;}Vg$y?ir#!7p5U+MyIFCh&qVu*lAT#F=A$r>4i zA^0W(9X|v!z+r)T7~{2S_f&Nn3V?yLP(Y>h!rWxaW`r4I6&2%c<~FytJ#3sBQE4@0 zo$Dvpn&|O*x8k-pI^**<9F9hve~tVviv*_16D(DZQn+!l5Pxh6r#(i|R@nSgn-0&j zP7cz%>~|>>XDM21&abwC4YE5xqCT{PSUWd(u4cVbq}hc%w;ufWTp@*>+c#&iaDSw^ zw4LMreA{_ZA^D95;4P7N)ETc5Ar6y0P1vwGr!5ulb#j-A$taL~2L!cIJImXTBZWCW zvWfCHR7^HU8Uqi@yj8J>Q}?(C*4lv50wPynsCnf^FF}I{Xb#gv7r|gca5ZSQ*@C~x z0YJ$Gin~Io4Qj|&GWRs$faFOYyeE3`erqe6`@n8)9qYV=G#j_HNNtuBc5W~&VBy<5 zh0`LnT_lB9+mK6HxEsk-Wn5a7$w2W(-kv zD;#|}^(i?@s>VuvT>ea}e>kcIA_Q>dNg1mE~z>VK$P(S&qHGp z<3*i3S*NGX^)Kqqo~250yekEi;8z1 z9QrKvrHc>kXTz`$22|X{8)1$g-hO4baPA$g8MFCqgxU_ZK`cBzOVTwbE3~;w1!H@; z_U>kdxym9oYy>kD|KWY$EvTMo5A~>|>azJT2I3?`z4fR9-@zicJu#KbTv03d$3<#J z$yNodxfoJc8J+c&yc5%m4N#kvO$+L)nRhMu{*40>glCy8H9f1=q}OQ<(b7BumQT%B z19lF6a~d=s;92SMq>PdWLwOFEH^Lk^9Ni4mhVXuEF3(i*MilQnCHz%!*G}Oil7Fkx zY)hdYhby{N(30r*-(Wn4*#IXFPh}Z(@b>w=e_^&&kZBAZfu~+Ve$15c7lBow=EV~- zTZRt4LO_zrz$a3Xg@#olLSGp#7(Ck&%ZVepO&lI-<6n40Y2h|&SY~n2wo?EVJG!E6 zo&3>9!5ES1wlXjpKX$t{I2Z0FQQmzjo;X^a4Te^lc~@B%(RA~dK;^g&!cZ+k!@w}% zBT@yne}N<)9O?-c3w0xlRgT}pRs};7P3K|iiu;7#%Oo~(l&jl1UC`%LLr1`_`X0|w z`8xRS{1~PNt z0u(iRkLa>IP&4j`l%M$IXXA_WXl(OFH8vFQ42JO5@O7a>WlqRBLzm@9h2yvlXY-g- zWnGMH?2P$2ex;i+c9Vjqa>jj57}7s$LT2&KQ^Q9Q)osRYBgP(t_h~Z02&q>_PBpf7 zS)O{acxQ)DJt7r9Bljg__V(q}#bY+dDEev+8wL&=5jwJX$8n((z|FTkK^$dL!| zKK#Ne$TEhFFzQmDj-2W+pDSDscgk7-Z1YVwDwo?FI;X$r#)+_%RQy&9B;uK+3v|W$6FACE%>MmqT(!k|###=OdIqkxhJm8^?~t zlWxigwV_N$1;w zA#su-1CPWMZW-IQTfy+qQT~N3t=^fClc7FZj!|$9#^gVyLlKr5Tx-iTx<;C3Myh=> z7ae}Wd<*m*9$I58bzp?6if_+sDQEqar~+j#wa}RlI^jvX+oDfRV5E20$1mx~DPaB+ zQ-J1uL^%P+ah{{nB~*hk{oihdC%fg8o^r;;J@rT+Km7jHoELj0>|_o82P{=NzQ z;Vp5%FDBmc|B8N*yc6@eDg9z-aZ!#qj}0AR zLLF-bRW7&q+&}oEuVa#Fc?D@Ubc8=rgcJxOI0Re0>bf5|E&*@V@Xc7By1XGJsARag z8;f@YLqm#pTqi4L_^d7!QfN$ncRh}L2A1GuD)+vw_Cjy&x024IHg z*ySrw9(%Cvr-n}q>@Wt780+^hga^#hEPH)3-h`U=H-LoR3DxYy?j1rajW<)J9{H$t z55J!N@uT3M^t1JwJ5Ho9dG6^w^_v7OY-#$OI(A#4i)_4o*5ycb7XN00wBp*u&wIAw2 zT!2{mPGHT_G%$Mg4C-NW!At86wm!i)jHyz(Qz0K4H(URp{^iwgh>cgj*}MLg0Sp8Z z*mYle*J_&g4nm7kZtr^6T$Wo8G^L#AU8d+eSQoY4^%wh_l)<}j_>8xp24zJGHI3LG zn?|&1$~`-0{a5u)lX}$Lnx^fEtjBlmpr0Z}3G_R=-FOQsFB~=ekx}~qT4-{;Xi|bF z^ONtn-!}aZLsIepfg?K!$KO3oe;eIMf9sA~kski0^|xcBmH8(UmH*S@rj#K=t zCw^i5ZPd|w=x+;-{Ppy=!HIXFYm`(qLqEh{Uwb_AW-QgtKOk^~ev!(K7b-E92PYns zdT%{WFCJRYuqp6zYW+s?`*5nI+5&ePK-n%0FQ$Z_RS52c@03i}*9FpMmed{Tsr&62 zZryQqUHY9RYTK*2WJ^k_QBwC-Pu+!{y64(;hqLaKMs+(%-Mc+?Z}-&Qgsj#yPsIZ~6%D)M%)}=rr&DR7w7A4m zaoOoEl?v>NixN*Zsu+}twVsO8JQa_yE7m1$(iLsm=19ero{E=xDt>}ocIa%>Dyb$* zh(o734?7l#V1z_{SNnv_uT$Q3QvQ9CDzn5%N$He-I4Ns%$_ytZu2UvEDGPK;$VquZ zr(Er%+^bUxkmA}exxcj*&^cvr;$=+4lB(3B|fn8kcFGsHM zN-lY&9UAklz13edo*RdG>fUeH#ZGQ_B7x@@yz{D5>U!tK%Fb@Pm)dn@Zp>*^cYxIO z&W*o$>K<*^mANsxQQcgr>zx}{cAIL3Kb)XCYtM}v z>l@FFWGA@CG~T13F=NV6oGhC+KhbzV6Wl)%{y$|a76H%f3rs@{%Q z4gYs(Y!DhN*)#_u4zmo;8|0d`x?$a`t2wB*TU9F%a$omcPSdL;f#==32+AkT3ZDx=8pdJ{#7v^Om8cPPPU zNZEx*0|gNjMfFH@;_>HESRRJJJD%tW&{lZZ@y~v%@R+S|h1)mk0v!^6GI4Z54F8LG zI6hA2^Q&(zJ#wD~<=M8JLoTvUMt=7t$+ugRPu_yVyNjx%LpvOOKjv2m)N0Q`AB?mL z|61ZIo^rtDNR8)emtL!FdVRt?b)x{zRws}=`bk57Y?WZmr$gw7W#B6kZ`G~*Dh!D~ z_B}LNGe({u+e~194?{k|9M%I{P}nF_B_;L*_y*&ot|!2(W#9huNAc!eS~OM4P33q8 z`rLCqRuP)|^pQ~kI-I0Wj$8kLM)k=-W{m%`ewozYVAs!O{gSl$blZ9vrRfJjZ;Yq)68ThGZ&&l{nxwWm6nCsN2=;*Y3JsT&}X=&`Hq!D{vPGWqq zoG0xXk^?X9isMLC4v-0>LStw}O+b65iM02T#*UP7!iNFPb*#IdUl!#aT~sb%OVIRD zI`tv`{|p{QhsmeDE7Fz43ullDr?Tw#0y(vb?^CJh!;Lz^=M3EQAbs0{MsB!YK?o&| zz(ya|>TmD4|5N$DW;4n6Bjo>qq@97g+FS^&$lm0?#!=NKZ-tynv(C%FHO>5Ti|Qz_LuVrAyal*$5K zr_DirO>jnrIj%0yr_Ch-F(3ZrcU+ts)i11l zIt}7ee$ly2U3BSMEEWCYZ_Q{%{a;5LcU7Shin^+e>f{RRf9*x@kT2S1St32?p zyNgjXs5{c_2Ad!Ch8rHJuuXaIJ%N0vK6LvRN|IJRxEzWGuJ2gI4xvt7xXA3i#VEre z1rS4jH}OXnD(o&m$ir5+m&eU7nqq(~{K+w;Y%_UTh8U=C{PLkjsXXg|h-BSSA3GL# z9Z-7YkDbRp$PlHIp43#NcL;7O0@~58{V~|FP?v+`lyL{89TzKg`%?xKv^5mVDCU$Z z9w!~T5zBja^4Q{0=&KvK*qTBMB0iH;Cdyn_ra|2u(!e#@U<7^_eEQGLfsz63YAosWiCKfb*BnhpG0|8n0YTlb}PlO z%y~7{G3WJ=xnp!H`b|+i02jldNGt#L(QVoIXdH^b2gY?*k!8gs+Led_tDd)`AiINEq!uWY}`Ztl=dde7rGd0_^+zSKZ; z5P;pa8(V&0oF{#Bq=uY3GV2(OjjQ5p;u{a+91BwM* z&C#6^%Ns$$5Q{I>3-P;G!^l$jkx}5Y3hVhYJTDrdohNqf!YY7`e~v_(_1+7fNye;c z#fY2*XecncXK0j1WY!}MUPX`w?a|0;tTX)k5x~>(r1$zh5DwrGbT!l+!Zj8GNpbRx z_$bQ|bD!o0hA_>s?x(E*Edb&0-(jCZRAJ>RjBOA7ne1n3DTYC?%i)5V9LV9BwjKZC zvR&vE{IvtBtw3lt8V-6O$#Zpg75bWlZwprGdc=yOq>i%t!+hpBfp0@cT6qYVQyZxf zFQXfnQ&=1L7LSNI0gpfX0g0#y!X0}o28dzUR_Ob`W@CTvp@S2XF!xHTUMT(L#_KyQ zlE3134WT6Y<;Uwhi1MF4UMImxu+ey}VE3CGuUDAUc)ZTq>5SK{$Lx2!tfEDO6Uz?Z zknNhxAsZ17E|U2ah7PraznrkI5Cr_HRezSLKXvNQ3iW5T`tyM9Lpa!*k1bJW^16BA2z#PP3G={b^3+EaG zTjN<}1jsgrwlxN}F=2Bdw06e8wr2iE#=v%F{v5{jE?QzhvLJLO0OqeY4>6iUC>Rrc zi0hcY2+<}(oz0@T3@*HL+|fpOuCWsS!YvRnpVMd>6tciBydxW)i`eJ1vy>nuo_8`k zXyu(8&+8~%&FifGoT>hFRe!pxKRwl-KI%_D^=E+mu}OrchLc3{Zg@Ozh$=H&{TZSD zT*W_-gz>y<`OC;FF!DxG%4O8#jmGCqk?IlZutMEWcmQQU`XgZdR7ZO&nSv2M04Z9r zcl`r!o<{z<2@XGQL$6p1reg*#e0ebHLM*ccuYh(U87Ae09e{Cm;elma6=yk0XJNH;J}X8vW%AkcN7{UL3sb;n4oPmF~ z2*XtR^08lm#byAgX0cB({Y=QFfl7YCIyP6N*c?hRMD(WQa-`TCEyc9_S|+kgUhzW?zZ_>b>ohvz^DY7zGc5`PsIT!3}MXurKrapSSAZEmb*3b@ga6ubXgU!4Rc3i{6^G9%)JXCqp+_7u=2 z?kJW_E(4qD1*#E`2W7of{xb0(lEG=g4gAC1T4J!Su()0-ltST*hzkHS&(@ib*qI+& z5jo>$=I?Z7iJke06_G=HW;P(?E%CV4&iqt+urTveo!QsUtk+&D%v`E7`+uN%5Zquz z7AQ*&nCs59R~CIY^dW@KcP2G=L9h48|5 zEYg58W1~4jHRj=*laB8`DzE6kcW{g2Jv$ZL(}-J<4XP*v$VogI#XyZb+#RU2^+|S# zgRKQ!p(7`%piq@meP2W?)Cg$jM)@*qy-?q_6(zoSl@m6{vQ{G_F3$}EP1u6!@vVN* z#KB*&3cHp+h_?`M_KJ8cGWFJQmQm`}~%t`^Hw%y?wdQNFDZ($d{XYYP1U?lvAOY{!}%o>HwY(4ul zm?**Q(XY23B{n(;h@rNdZ(5Nm=6`0T0NsR zn62RAJv-G?z%YQ5hm&3b7}yjn>ts+L^F>bP8Q=wgeTk0`XJ8U$p_WCLDVsf}DA`>JPO&5f`;|c%nHfpW5$IMdf9va@s0;}(oF0>2E#Oe4zY~OL zcAj|2cnQR{z#?+4ylJuxrU$8MzY{c)-B&MTtBK!A9TeY!eTQXX-y{ds6&P|DT-mT4 zJ14E0foc?@{Sc&9ZD+3k66?jTRJ9Y@c(`k1VNm4PaX#&NlX?P*CtpBX zs=_hLbV;vKFEu`<{3jddvBol_!H|NdPw|j(>S_1q+v;4$ekk{{bWrOA)F(EmAHZ(O zw~?kEV71LcjoRNSm7KSOYgp-Xq`8gGa(})pCpb>$8@1mcpq!Vk|3Xl_(U25o-b?$3 zV0C8P7rXzgM4a44)7lSX$oAHLO98dc2K572Be|9B_hhBLwBJT5Ij<4duu?YC_R_w% z2knLatp$`5ROc@Q`jKth7&V+=VCI z3=vf7u^#m-+fcS9A~BpuP1!Slh$lbU6)k&P@ZWO`adDsPI3KMf4?-G;;dYSCn9wlk zVUOYRXreL2oBJrMYc9%Q?%jLX8zP&A>kE{yOBd!OzQY<;QguQ|IVMgV-eKYpT0oaW z3gRkud~7S&uZ=nrcP@)0;)mR0fqGYpEf-|tD=3FB>J@?b7~HmoX-R5NM=HKDx8sHu zL&XE&y-X6bdpuZ6@3qW0-$v;TOH(yp=)k>Bn3*Vdl_7O4CV`pPFCG+onK`j%B+)7m z4_z1A9lC^vXoV{n7-N~3r|a;56CM4u@%r;GP!)FjzPV;z&qzfpBd;f{v(73SJ_}uv zAp7VQy5{K@Y|!tBT{#GQ@5!>>K=jr84R@fOP)R`*cWrb-Y^wnA-}3=QD5AiFB3z*$ z{G(tnQYHBsvgk%6w&Bx|N>TdnmasXFZm@>#=7Z#m()~q;!9IK?6au{eFoyf1?w|}! z`odw>pd3EhMz;_XhkHG-4_?OivE=N+rrgt*KDeZ7j_*nPd*6N}Tuo>MRtwncg>cPD zIPO^MjJ#}`!cuqtgS<8 zqqq63%^vL$Y`U5M?)$-AaVR?YS3N{z_g zvEu+Ds1x55=!^W+P5RU!_?g*5wYVC)Lr;r$vPHP}vPB((ns3rzMo*9ySG!L{MCq|$ zkLG!HYix=eHAWo_RtN`y@y*Z3_`!-~B^f`?0qu$;DnKm|THlFOm8wXsbv}~4fwFx+ zJ+f&6hEwi;f5lNY|13v%CeGC4JsVKzTC1A^nc z-O!o*cRk6J7C1|9zcjM*0RP>mf;n`^h9eNM0rBxsfPv-;=R3rT;*0?3%kUJ+ypXs0 zOjU$U@=O}d_M?O@bm<}qMWmB;F%G4lT5kZuOVd{fl1~o}SXZ~!k&8GUi0H2$ zF7-!`0YsaZ&b4WyITt4I-N_Ff#@W42G0xj?19o|3KJrtaINx@}anJod_&;LpfdAvo zv{6jq*kfUWl<1w^0Z%yMDTzdu4C^6DnFD68Y;zDEQscuxMsRwdaJo@A!yo++71e!R zBY#HsV&%!;htxwy(O)jzqD>}{vo1ZyiYvDV!HMbAT7Q-U+%*|O+v6i?Tm zevf>Q{)YfaCM-UbkWzra&`c$3CQl6 zk$e$Jyf3j2cylQ}~fx>u=`7*7#?q)nCB+P%`#if3Bzgh_w1))_-86HTs=fju*f{HbK?mLeV0T8=ogaC# zxU?V(0u+%~U~V|XES$>qy1z{GT4Q@RXC|yL%v~!y>sOgno=%}dQHXhr zIc$rc((fsLW_x6G38l8)-}$26YFPOm({-Z+_AQU4Lu$!=|g3Vv4TcVlhBhE5F7APmwn((BXH{6s*VUj2sIb#DUoA zN2Rx*s?Sr^-H~hN896m3Q&|M3-rkXu@$IihPLccuw^UBr_-aN`&GoUHtK4{4y_YM~{^ALB^Y+5^<&{ z3L&-B5wyZsBlTC7t}tscf$dUo+LpBDbMYE5wEtMqIY~_u;ZKbRJsoLckKPJ z;LgWJ8L_oaZRzEl~3e%vZ z>TlOlZ5e=B_pSfX;7r7k;%tQ<75?yv4bnkhE%|sn=%516V*ox~2?jRjV5Y{!($9{Y zi>vWn6T1ojX4J%P=AU?MH2>hgxHw+%m(>f7r?eE}pf4_$>X>Q{%Z|tH(1i^NqpyuG z@b4_6>DWHLf$Lx`KCLqT8;>o+zXCw&XjkD*VD5Nqg`H(?2H?0@&!wpNmNtD{1l|;I zRxddAN;|#UYR_Q{s-AeH!s-#@5l=jp(4`ZHV5-=z!q_n?5Ef2ulnX0M^BPAX-FV@% zrtHgr1HCM9CnTCF-l^zf4iSutBO}F)Ep=ohq){VA^B(!}T=dT@cv~O_Q`E^fIs>$2Ay_5YFPP;JVUNcI$ws7A9(;;C6Pj5&Ktx% zU*rq}Fc`IpKp}x?Bv5{iV!G!$=D0_ar)p;(rfQ4$ejg(PJd~9lnkcLc*ga55g}%Sq zCV=RyXkggaN*sx|t$_B&9sx2C&s5fQN`a(^_pwgNV#+j*x@peFzv6=|quJXYO>&_O zi%{MJ?OCatU@aMOEIQ)w%EF1Kh(2CJ7E?EPR`CdZkU=-an92>=WlX6|eoq{TX{s*s z*q9%Jwo0lw0qwUC9sTiJe=f!_T#9*($%#=+?0kY9&$Vgu1FjWu(hp7`S)4vz1su5D zSEH>Yj=k;8k3Wj*Z;penA!i*CF(@K3IVLig#qsq$8{f&L-ntCaXPZ?T)h(5}&aKFu z@1t(WTlZ5Sw3oW)N?qqh&0 z^?r{un#yK#8Z|=->9`zm__50AKB_3@FRQh(9y5&(GS#yDd-%{-O=_9WVD}bzi`vOZ z%!t%es@5x?V>EW9)lql{~=`G;)0lr67q_$MdO9%DT-jG6x~2$u{6wbUA+ zaj?PKPyNW6g{dK{&x|#hs4ivW!D7^gM7kCgjWT*($AeKOQU587`d@t`lI$E16vlV* zMIw}v2vsR26M3YEGrD?fTHB62%q%Jn zl#eE`yJ)&nz3|`J9lyut=$t!G!DM3R11i1Rq`EsqR=-%D=+%s!3_&u;3t zP}$|Nuar3E&_X=th4)Xy`PUL#2io(z@D*@$`g!3HY?$P{@KI*rXj68QyMP#{{J*}! z;;^st!cNeZaQ|m0nfVTgO0(C14!ycpZqKs%6#rngDmHud?9i(ZzW-Dq@oJZvy}EYj z)!9wJ4V{N9UvXu97A&!;-@Ec8Slca_3Zga$-yM zHn*>HKWhWQhx~V4gogbQwH{>S%r^fabKIGD6d^p_Em`R=eGocJWJhcN-RBbFH~e>( zBEhJA<(OD%(6)_6ZRPf3Dt9((ztr-) zdcM1iAZ|X)j8yspc;q{O#<)wBnT77g^5&}%o@EqO>tjmzA$QqoW?2((L^X>9`x2IX zuB*OtxS1)e_Q!4@iZ!iDcCnT4=aFCqY;qNW!X@LEq8&5>YByv1a|1s#xKdDzwf9z>$u!=>%G~))Cle(LK=xKzPFcCad zGz)h{$WK6G9C&D!IjFNasjCsTc}Ou3oUGe#_Hcr+eNPr5?~dslslG#>V1tL+R~p+R z6(`%Tn0<8zR-glcQ8QTa3g;w!n2cyxvD>6G@xEoz3{NBeQUf4`-QYPZ>^1>^_r-3r z9Cn+f*=>f+ZZkaWHp^zWnd2_ogWYC>-E8}jm)~ZS-<|~Pr1M)_;1K$di8+M)0O0JwZz~k=bbgasta2A}e;mKn0R!RNbbgyjew*p#x4&Q? z&3i%Qr&(PpY<45B37=_(E1alYG8lScz!Ln z`wKji>l?_s54DG7R?hRtNmx#1-;TaGT&7v+WGXRQ4%Ka2SGlp-w&lrjP%3P6aMLy& zox35Qyy!GWWi9e;k|kxQ+Zg<0^f3K^EQ$tUX~dRO6tGWT$6jE;wOu)HTl)yGc-P*CA*@#=|GR>!j>;Per_JFA<&kbUmoA4 z3ad!oQ^h7S(HjL)&!@vc;2^*dYXe~%Ll|&r*xe*DR|_(8!=ELu*(>f4c{c8Y9Nh2N zgKS5VAo*gBVY^R*2b0YS)PwuIR+0Fx5%UlwymG521h=pim*zAl<} z=c9eSCVY_`M$XzFwL3T%UrOV@2bcL)kvQP7wVhRH?FnygtyLtRe$4%dxi6(txsCKz zj6m$|%P5k}-h(Ee>>y3nk(F3#8cV&2G^1!X?#sCSI@{YXKMJHbc9DRQ7+3@|fMB{I z&5LlkRV4nDM7RSHp3^jKJfqp!p-m3}Ymz?{`N$vdLCSgCtFns3f0FGjhS@FkqBj@h z6Gu(vKFr*g(*3vaJ~!=w@}jS-Y^|KVKJE7~qi7RK?gzvyhwf)s>rj5v<;jlN*J{t5 z*QlUiztUJgzW_>MNmY12BmMk1Y|eg+e%=!09R1u;#y30;VUzB!x0Xq^GM)=u_T#VD z1+(!#^w&EZ=JI_h;6K%0Z{&oZ>aVu~80_hR5Q*SiPnQ%P0j zA4s47C;avL2*)aCp8pzuz2zXcGQj%_SZ8oyuXgW-bITQ;~f2ohjEhgp`h*0 zU+>RQiAt&-3+~5X?+P3(VGjJ)`0M=Ki*%jfbD7jv|qwsFT(@xKk?VApwQ9y{3rf;#h&{AiN9V?PyPSI zUoXQ`|3C59tDs=f{r^w=^@=_9f4aZkm_@>U(9}Ktdc5>UwTtt z!$LNoAMLNV?j?m!n!nzuHkkeR>wPAbe?@=24GUx``w{+nN9um0(e*k=`ZT(FDW*K& zdaEKo!e4LE!nBc7)tfbLVNZX(dYIAo@2~fYTWTNvded2ojIvLEy<4!BQRO`k!L!wg z)Ci_PSL%QiM^{Ss*9+)M*(~zQ`RjGZY$>U_r3Y2&5!h$yGds0o^F}oD?ag1W9*4f3 z#z6c$+9VIbb`N!zh3Edx0vTts}D^~`k+6IBHCZ?TwH^dgUkOOf4vkO zw;TEE&8}9bic^ur(Y^BhAK|YzII$QUT2l38cj_$5Ks!3?mBLxiL8)xX_m?s> zd}Mc9MA$sxrjZ%y-ieh@|1O^uV3c$l!--2HPr*erO3u3oMZ|Lq>`H?Ks)+L#e&awQBO}oT=d3t5 zR#qoO9UkU*iwU|xag-LPF@T#zd~geGwG`XCtJp`IVOo)^4S^m0SP+e3#-a=SDwZ$a z4dK^fe3ev_kYc5^uYF0Mg|}g7D(gd%0pUa+j8#qaJQ9R7GwmFka&)Sh2^mN7#MVLs zrQ=qqdYA@dtbMn7;GE9myLCP$1R3Cgr8X+=3A>FCjHetQ9D+nHfiD1vDfpa8-hsCq zCZc2Qfq{t7*1%g1_b%LViy}C;?I7ikvfu7CnDzA6{T}$1#-y*9jC6N6Yc9D~l9H>C ztB)4_(LzscV?j>>F6Y1SA)AJBaMn%-wCQ;l&=@bEwtELOTmXHZ4(JIFpmV%{c3=eU z{;)GNeAD@u*A46w(fr6ebSA&O!4PB}lsnP#Sh&GR>w5q#nX2o4HDvH< z`}H??x7ZcCt~Yg>f7MqwL$F;EJd)Y#U-co1IQ|BYz~=bN`5P1f8Yh4shdcIpl^y>F z;sf!2&Y|pt6G)nW)n7n4e+*A~;`D=_Bes9lwhtojW*CK2x2-Yqr^6Q>^Gx|u6;5}i zoc4BlY90m<&Pu^zqi~9HqslM!Prd;#T_38oY}W?oP&mbZ=Y^;^{vdqgee64X;DhjEX9>8dA%U;s%Ap)h1{U0e47y3RVo8g1@!yq= zf3=$w5x+5iI^3iXZG>er#Z77|-K3@$mvgu?{4sdkV7$|ulctXwhVg+r5{L>uqMQ{+ zqpq;-dK`@m2ywF6+9j0Qq^K*krjbQ{F>Lqw@gmui1T`=znK6B~M1eO}vpjiQq(O-~LM_cc9X~{g)nrGn-vx zFY?4h5l5a3T>MMQlMF!PK)?1@nmlQIK5{&k;*zSuGa8+bWC5`sb3U@s@SKk*|D{!K zlE;7P1*C!)UjL=%nDi5lOm;nsrOokQx(c=bBmbpsPXWv?>A!U1l|R*gY5LRDD-iGC zQLKWF|56X6a>NdP6Y_Xp{!4#`egpeo7c%pIvH#Ky#{c;*{r}j1sl(&{5BV=my!`+C zmz2xQ|5*Q}#SoDH!~K`KUdC11_LBRb?7wvMV>mF_um95anJD#3`!78~p!@P)x)TNV z2^a-ReV(5FWXpg@a~V*`?}s3!rK< zD!^(du$e#hCdzO>50bO?zy3*4ev^G+4hJ0C_bdbyWSf?H-|VHY%JEVn?53r`nTg*% zh#keyc2@rehQGeJ!5G@c`YZ3rmn>~SUl8aYJ%bs2X7cx_pd z&G?Z#3I#{fXrtmZfNmLEh<|bro5i(HLAVVNCQUyq&&)_AZO`@4Ij^9Qdc}hQCXdDk zZ=K?HFW@DP_&X*Yo_iso)WwO{{{|v%PR&++dkCACs#UvaZGYPR1evkR3A8`a5>7w8 zyqmh^O}HaK$5*lNB0^Vpj)k`HUi^^!PHen_tmuhK6WhwbH+Te~A`?#m(A)@|*oV23 zcJD5pct=Jk-^6nP{kFv32wecCvL=qQLnKT_O`5SVXx^KX*TaF>igf1NJ7TL>`RwVx zLCQ$cqJ#aD;l&3umZ%wFPlqc2kFD$J@HOC=!HV=Uf7NC1sFE(Wn$6*|v2+w1c$MbB z#Fe0{x?8U95&~13g?($t!fwnff2-`w#G!zi)tHX4TCq?Z|jGMu-x3$^}-Hen?XAx}%3J+hVV$AKVp5*~wcpRai0 zm<)fESAHY6jL5W#W)gK_Cjh$gnl#kcq@#ZC4a^bKJUO;xLRem!5c#+uor!*uwq$80-BpTCiTeCF!olFcGvvE~=nO4N$H4?=hN1lRs z@woWvG(5(#zB`UlV%Zpv^V8dyNkd;_JPt}PGX-Vj4MvRzj-4WWo5m_14ty}W`sAtl znlx+{K(uF*b~s<>9Ksn!+YOz09t0z~&h+hjX8c_3CxBNWyZI>@5;l22D zYE=G*^#0c3)9q|=+SfpS*?^D4hkedi=sk$Ml4F8cm15Sf5z6v2R2vDPZpR$IjxP&7cCL^(a4f)~`b+M;5MikDVIRMdnZiI!?a z6jaoxs51_aQcEFFl=u7F`<$6GNkD9$KJVrK_w$j=IcHziUVE*z*JbauV>GJ&R`VveSL6Y3YrlVSuLW!o--CRa=+`Fa_~=w0*6W(a zb9#le8c9IT2^KKc+|Ce_-X}E#XHjTjo6NG}r!xmP-ZMIp?=NycxlkO}QTr~ViWtf- zY_m5_o0!%R7D3-{j^l(b`jx zuT~dgC`J*ot*BpNH3Mt8b*6qB33U3P-6Y$(*=&c?rd-M5*q^4nS$WISEX}txi{sB_ zWS*Wp(}uss0&G$0j1MfBKc`8*44X5E20hP2HNw>Dn~;s>+IogxjFh3|9Rkmc z9|}8#%eZ9(+!5;dG)<+y4%!6u40Z9{Kx1ZJXGKkrB3k!ZgpwDn5A1`9!hPLz)62W` zz&;1G;5CBB*Md(KJO)((JSrAwh0p%Y0u$1XYbS%;+=cQ30qsfNNSD{nxaf=@2>H33 z*Qd-tR95Jn)q6UjpM_+0NH<$~lQiqW)+Noi2tKw#)JS=gaPD@tS~!bs zf@abinEMx$sj7>TPLEt)_M&45E?W1Y&~0vR2(afF(sv9ALP_=_5vDcHz8R*~HkG~7 zqV~HQGir+cIXji_=fbk8ZFFlaCNzx<8Uu;oijFD*F97L`$0@JTi z#^yuIX}WBJ2xIAj`+3CH#4HtBfN|sq-tc!WBp4{-?@%dc_dY3%+Q_v}^ILvlY5qn- zWABJ~$lBv27lvp)^()c*#f&S9CA8lV%?J6X7UpQac27o-OAUG-Q=gBSziYk0$ni0= z=0-5{uHIQbu`zY5)%aeBop_0{&CdY@|GSY>h&A5F_myC(`xfhrMcy4W6U6^TM@pRU znHasq3BokhjZxbkGS7Okx9zCsddZ2RHJ{TzXRbUhnu6YLU?Z3^Qsw4d2`_W=o&v48 z(OKeh&9cTZ))_j#tj%ElNH@ETR0%Kh^WA+*lwxI`0^k0WUe;o#XEZ|q`4I^mO>q^r z6Q=sZyawLs=DO$9y6HRQBrt{3|D_QGYxGpW$t~tjvM^^qUCl$d=eLl;u9ep&CBi@N zL~A<~IKnSq|D~i-3DYH~$0~|wX{hI|fS>UYF?6$@vDN3JfJov4^5xJ!HVbXpOjeCl zPQS-HaiLi*Xn6`PXKu?b%$cTavo&^ou2h%nGAUj6ZNMF5UVyrBq9raeG_!ZT2dsTQH`m+!t!ePr4hwGDmlE#N1`t&E8w_E0uS6 z7YO|Lx%uU{8YF)pa?4@$EYIr;R9ADR&XOI;Ks&ydWBj^>jv@=}bOrdik}^h;x1IqWpYl zy`ZTaT?Y}i_+oY%LF$mAQ91;1YAQm5?CgFvf>Hh4laFypMNq}PUJ@0I zQVs)m>QJZZR`Y3&TY0NfJ=-01D(CviA;F4JHFx6K{$5M&m8+f~$f2r7gZvTMQ}lmD z%m?EO@<_~&))6evKiB^#c_bb!tC~CMDGuP4DM$4&@UI)Yvn)0*UT&vQN8L%ZbUh1E z=xq7??D~**$ed1!C}@t--l;qgv&*XI#0LjyMx(Wp0fEFB;gsro%HDD+dhKLfmtziOgRZHQSjLQ@c(DV+$Um5)YISPz zNsOtwsA<@xA_U|JJ8DzUXP`DFSq@yo*DLVbQhVCfiGuhp_Hx3y-4V+anl>4iUvIbk zV)75x)yMZC+pDNZqEtPhJwjKhxj6iJV9)a! z%LS^4--dIXb?5zXT%%h(hukC4+EHSCSL%l7<^?tyi=c8T66WXUgJ7P|rGTLq<~hBm zWJ+5}wDu!@NcB^k7 z7t3ye7|gZmK3zUZ13BIE8N{cSN`DD{S%vSHNPWzxSR3NUwQpV+33;CHQjHUMXE%_Z z#-lL2-ybpG5Ki{$BFS+3GcEO>E6=N^yOq;}Bl7bTKM5a^KZgGEpZT?2u|2+kyDi&fAP%O`9+H^W#_N-fVHX@4a6mel>O)bek8y+KD&Y zi(j3Hg2eqdJIm9vNNWM{t7K$f?mPLIg?7rIZ3VHs8Y`d<87g`Vndxz(pD2~Na zVw&@#S*b&q@o7^o-%cp&1NzM>OF6&#o$Ms+Jd|}5gh424=jipbHGuZs?#F0P%Nd4& z7WLlet4uqG?z?`OTqtW-igg;wx)p?OBb4RbCTb3cvJ_1UCAKvFVH3x?(2rw<{9C!W zjMC9}h-V!x5HSI(A02}8rn}MSiy5=wZgNUMO)T1-#Px0%mIvic`A|N2n!a|7>z$hq#PW0ViUqrikOkx~-&-&X>8*x!GmU^iwX0~tlT;rPhS@Jh((H|82G+`J3LN0w4Q z+}@t;p640-<-7=2+2;Vh7>{}IZEOc$qkRs_&lKXr<2j&R`Hby9D8G=$T<4@W2|eKn z&N(zL;30@doD_~n{6;uXJVJ87c#+ZcPn~Sy5qg!rngUoGaMgyZ5!-k&p1(63eRwKo z4bP<$Tl6g#Qlsc^C~Dul;J=xkee;C>W+HDgciB?+`tL5_U4A|z-M98Ks!>g2VMOcA zY8ciYb2E{JTv!1gblm`r1$n(j3rtSx)WGK6Eb~#ph3Y%}$il9tQmhlb=se1cVN}vC z00;ko76>bZy@`BH{biK((z{TYA54(vP`Zh^>sAgq-Fa(*3A-WK+65D;?@&KN^4-^> zGnnR+iX@N-+eQ);KbSV<7f|uH`Q@2J##x!cP&b{Vv5nNgkLm5hCr>WTrXDiMF{8D2 zs$)~rtD0*%WEtpp9WTvo!vP5UOKk}|{_5stD+;S$I_gTAx>jg;7MHPmMn3yv1e$MQ z*#LsDhj5|R9Z-+01=xNJVIj2*h@zEYkBfS+Vsn;Oo#ONc-@%MtN8buFfS))@o>a5{e(R zr-sK$YB7HHW9_&d2Ojg^gmJ z&kP)N(b_-LWzK4qNj!k>A=h_00fu_(9qSA;>IVaK9lZ5t7x69YZz9IEdFOafImP!h z3ja{3PlU1P+giDEe(_>`$1nbaY&*K}RqUtx@j^)W=IMZ2H9fP;_mRu}3@HntC){lD z)03KFF;+w)%=W%tqfY;V*XU2v>y812)D;tUNXIvY)4vdo0@*zQ!J3oZxAGM3?Eblc zYx&u@dYtQ71lKbLHmO+=R!V$^mqy=-Tglw_b|ka!n1~O~;oq6n4_Mtg{VPXoKj9*l zy=ZqF)ziIrXDwFwfky~ZIek^d_sBk%NlI=Qa6Y*b`mov5;qA3`0Cy23k%eIB5_Oin zAnj?;mv1mvn(nhs?ssS_U1o-sdC;x{F0Y(*wl$?&%&jpqD3@*nI&Ic7r20csHoZm= z2V)O;OhkK&w8-TGQkSX2xq4S6S2&2=*S5h<=o}6*&!?}+>snij{QY}@fA@H#bxq?h zzUX4Mlge3W{kxau`FAhho_}{X{WI}7|L*T6LQ!hUWShGcJw`wG@2mxQJaRf?gMN|A51jSy%4Ey(TP{!VJy3tnF_g;_ zyioq#g=Lji!H*x>!&hZq*SI#%Np|2Ey?O{^2;s?{IVn?&d|5<5zUid zmJG1-@$Y6KL=SnIN&TSG_EC&pIeD?BeZzDlg=r#q8bL9b(*e35gRW~u;61C0PIU#Rhy~DN9cniru3qf0N;Syc<4RG`D79OE)J58ZV@gV7| z%>g=};=@!tNe{Bw>bN#ixwmX9GhDMZ2b~}+G>E|^f^x4Wg0?#k} zXZE6J6Tg0t-dk%y*soi!)c7{hF8t=h9j#OR+@FW{(k_+q=iv(8gc8ZgmY-5T=XZ|n@bq`pbCwUbOu?*ziqZV=2g+n7olvpSE&k%zMl^vxpn}T z`=a%yu14P0G(Nboi_I5^blnnNP;G)SUd2eHMa{=s8E0xG+sfezmv`6pE`h&_bypWU z6)HmEVyQ=|HJgBlRvJ|6x z0qk{mNUSF>mPuwm(<9jz4Sy=<319nCH%M@j*fkG?!0P*c&gz@`j=4RqC6E#0E;Vhp zWR}_h!md1v)>r>3Z0I%3%>I|E!fjU5Flj>+q#32IdYqEA;YIv!HYwUC>l5#B<$YOIb9_K27sPS#@)?_D5ofc8Iwf(5?QaakazC1EF!H52kj$ zD1#%62I(&;eWA~^EFN7g!OZ|Rf3_F5Qztk`TLH07X`&H^_-sPA2kty|2u=FKWs#5PJ7dx*z)ho1CtuT{n)+z&W!p6dy z6Yr`IYs$sacUZb$z7-ZoyA=v4mvRqbw9{?rBacS!!cir+I|{xtAr$K}s0;rd4Y)Y$rg z{An+DjOqI?%N;G_`Ao+O7M44YT?lEP&$}IwJ12=?&Ath3n&>EZ?#!1vW7YQb4sz#o z13^~q^j9fKw0t;`hrpSYJG-bNdm^T!ti{ZfuR5SuBKRYw|p;(A8@SoyA;96fbje#Sr_K z!DvtWrT!_ds%o_x!V_0Wy&90G#ag(d3%X4&FV3v;jl`>pGp`vvg<+PmV|^29D`Pl; zLnZz?4=4c~O_AOLCv_mOG{x5FH^4ZH(?5slfT*e5x?s92C7_U=%**WXh2P}b!+d+; z|+4O5*;!j7DxORUD(1>#C$@~u__5|bpS!0XSKK#N@0{9?4BkuJ zGmk4tra7A*vZZyC-VGC~J;h{}`1OWMqo!tE#H@5~WWOC1Mv;E%72#y+PM;x7|T(19S@kXh=i=H7A>j z1e1SU(HM4XrUCRVuRApO`aZep1;p@@!Y zi2KnJ%gsP=8n(DJvA7sihP%G@1};gDFidxEOu?!Z@l$hauy#+lDB;{IW^^s@bPUL5 zr*c_fuWhEYzEvyS(!G_av$8pH5ipiDB|dVgvYW$rs#k#SUDOD&VEx%*(-zR`Vsnnc zOkCo0)1*YMb1I60Ne5Fp0ui3tpEZDx`t%W6z=*#*%LHpbqPbe$!#Us(v-2H@gEe`v zg=vmUp-mV!^2+35WB9VykL$fR!vY58-QCJ&uY7$Ow7)1?H=7;-eqi6MsHAMl%Kj{`uF8QQ)~%c7o?BplRILIH-rLC`IhJm`G(x8MREbckBSP! z)R&1oE=@hj!l>X-b2SldI!xoeG!Z_n6288FB)rG{hadhwA&+`$s&+sg6^I76EstIS zZ~tL=^r>jz>&T-@EcgE}%cE>)u2Xr0L#sI?kD5dBXjw;jRJj7-8OWmxQThMV^61gA zBB)N}5n=~7bx+`Ps<2wQ--lyj$+b_JHqUxTm* zYjC*j^K)%$YxN3NO56OmY2K}Dft-HlCR#EtgzUSi?}h?1k1#WtmvYLv+!?rjT zyL6kt(1;RPe zP2-|>0{k%kjqfiM{rwOtm;?L>k`jqIJ+?K83d~?x;w6G=0-~oqRfx z-s{mYQWsJ%ho2aCzjDTj4KGsD4t2AT;~h}fI?_koB+vsg3MeGhT`Zv=pzdi3<)iLoTY9-> zn9}bheAIQo-v~rTP2;t1e+~Rq8nL(o`0Gu<|3Um!G1w0Hn~lTAklwN22>jJ+PQl1w z;*|h@*H9=Qe?4sJoBh&v$Mf+g{j;MJ;Y*aLn#O*st-F|TgWP>3)kxAo7>m}WtFAT+N&j~x>HT|V^ynrMu|IOz0ry}eP6lSt!yo; zTpg{bTy2_t5-&RzbKk1f?0kr|G<eTfyV)02UbHmUTFB5VFeWFLu%Nk<)@wHyhDBLoS#;P-K%)NL%2kT? zA1x>-RJEed-+*IiLtXt z$3t%?0#ft_vkxNH${hRaR58M-{|n5jP#SCP)5a)XNi}@z1NO2vsD|OVrtU?_MGCD;I<&~^1DFFv@WV<}uAB%z$2Litrxbs|vZb|&)h8?} z8dY%*Ap_J8Hk5lI+vZYR`3Jc|G+>6hj<#lnN*UOepxFT8K^I3DR zJU)UVmhis2Ic(8c!}%EqbmJRcPm7c_Pt@hF*1ajK9;n`wi@ACYzJ$Y`6E=OnFkF6l z?*Ny#!O2eK*<@2;S@oJLKM0f-FS&lRKJ-rQHQfH)m7ylL7EavH?A(;&xxBXy}?*=DzQhMmQF^R~+b`+|&8I z&x=_suq&|)_Uj4w>T*;sMy(%{h0dxq*>dd7sA`Q)SGnZop3xaIG~CEE1Rqy*zl2s% z)*L@A>k`a#7hg8S2cd`V-z3x&G!3!q%@DiZ4AHUI0_P0;L8WDXOT6ly9zg_pe-e9_ zH6)s-k4{C~ExHz5os3()la#aKSuxA_zAxn zHg|1kJD|^EFEY#Y7h8cB8TK!Lrj2-^;bu~M6ykYom6}A!n;~F)Kk4s?HSy~>4J>|r zUXcs{BrOmVBwIle-o+6;-3bS#8(<;zZ#xd|1kX5Dkoy1n^K&{HdQD>u+xq@5m#2#m zeE$vdbT6~!=j7={6$pc`El*#T>_J5CkUYJ|FKp!L_vpV&292Jl5}Uwe0h4?P=lBQC@sVsaY=i5`g;~b^q-dhU!MM-DNnb;zvO>? z`G12vHU0{m6=D6{D8I0gryugr zsXQHn?5Sy-{@0v5JrMPh12$zX@q_y>ud8>X@tqvqMUz~tY|D9SqV$0d@^|8?Xe%gM z!g=buNI0W6)88wZ&nf{4HYTrQWJhVIg-Eh3R zKQYh}~Ep=O`e&AIS7{s_(W{gT8=nedC)iTUKwhk{Pl<9W!u3A5^dIia3 zmKG08G$%gI%-8VFP>^lpmZ@nC-nSz^K9Rw%3g(OXv)&zi426tl{-GL3F8_rIx)!;6 zSQiBQg4>PP%s*KJdN$ho?viUEY=bedcpHXFO=I&5T?(w{bQw!16PU%FneR~f@uvJ8 z+45__bi4Ax?}?_^6%^Bc8+k~Ir(G2(h!^$WFl}1~!6&8%w`bFa{h}W9N zE~fDVgT@P0kW<6i9aZZvXuah8aQkNk?axtRi%sQA^0E1kabUB(yrIAIO@B8(ufg=& z9(j7PjZmnUSZ9Zm`hs43q~9}$-yr`uMvdXFpN|};p4SK$*Qn>XS#RiX9b%!T@mr?9 z?D!4>&b;wq^Dw^7@wY^U?f81+#E$lW!_m&+J$RS_i5e-J3|#~`hu3%U$C zGFo>pFKf0krm4^BpJ>HKufn*En!y|nyr%eh6h^ZUB+@rhFAINFMN1>c7C6V{Ew|c$ zDuPljvb9?b;tg5t2Rk|IQe#90=I+D80ZG*L&vU@P+3!K6Rxf$hm$^zQy3urLCw`_` zCy1*=xsUheU+G!$0-5h1+DrBd)toYbH`S{>lQuP2?aEj}MmlY&S8%-PU0o^dr0%7t zYkpe5_7u4Q*aZOQG-cN2^Z`vsRk2+n*~r#my|>>L}Jl1XjnCka~J#bSG1ub(v=Nb-OSFnXssMjIL#ZN!egk^B8)Epm7IK_~n!M=XA^?4~n|X)SSXx=zdc@WR|@BQ$Fo-FmGjZ3@@mQqs^baIcEES40{<>(cOP7pJZ4 zOQJiP3HAX(2O83SM}4_f#|+3|QE+Ydr}$A2FJ%@9xrI*1fv>WSyp7(xIC$-}K;NQ| zGjfw&HZnp9XRW?LzhlQZuP4_Yh_u7M#m0vHyowUD$UvLNgE`K(e$zppm{?S|A@Ko{ z9(*|^$t4Gx%z_h(Gk?j)XKuWgz|b{~zkSYU1~v+|x&7$jICo^Ee?8t_6d_ol?8U@4 zkVi$td(1i(NiFCviG`k)N2q2TWAn#xYrWCf^YpiN_6yU6lICmmjMqF5j*4(8BoW>jnP$m|P3HiGLygZFHOns_Ek1eh%CbqVo3rchX)vK#St>;Q;U^(L3{hNJw6Xcec=Az zr+q0>(m6`|RtG4pQBvZmU~-tj4GC+^5FGh zO#XwSVN6~GkkVG>lUOUe47bDN-2f;|mZ>F!$wz2KwWd(ZVA5Y7IbUKVZdXfa+H^(Qc7@^?IK|#)v{ZpPN$mX#UNUrIy)Z>UK=$Z>zXnv-dSf<&Vs6KB?UI-A+j5 ze6dQ~s8pM7U65jHnC?Z2hDqf(kpZ}IMsAx_CWD!lvoN z(V^VQ5ht+@-K%;%YLIi3i}5!(;#RMB`k5d&(m%T3svgk=BYGr1EsFCjllh^skcOW0}X zjwyAAl{#Zf%^o}UgjhcydK35oeB)1nr+oF~cA82q;cQE%`d$t{?5_&rGgwT~H_~U) zL=K3|drw&5Y)HIG>U??25zv#F#isF0aN%~+tpSHRCq>rKt zmb+UFGySZ1CmQ5&4JmjIvUR`W*Ksn@n znNZB0w)pKHXo9Du7P2z!Lvk!Gp0DtR^|Wt$>g`a*!`ptMy6J}-S|idpgA&!Xb8iC*_3$hYs8z;M-^$jn z)cbwmGxobIbt_kA?g{WIKCEg@J@0>PFvr>Gx=C$JrVY1S=JWRYuhAdDnA99_Bl-72 za$TWMpH_ZJiAGtdKs3}eUNzr{XemUKiz12rjLECzDg%|Z< zu)CKWiR~XyXsnOq%Noxl%hDKRL=In^4@?eslM zpNIM2-+;)fX?&8iO@`T|;cEo(l6;7X+Z=`7|A|IKDs_{S;8=FA6)v^3c2s_G_)c^* z@;ktLY-XjU6ff|{k527wdOe9=e2+nT6aV^iFy9vRXx*Jqd~Ln^bScSU6MJxuE3}hR z?rBzZf8I^%F-mhUjW`FuM;3VqP9jF0)y-goLlFFSg(_PaALx~r_=MriI*>Z4@vJbe z`H6AY%bVO&=>E|<$RfXE_R|=MGVjW3b1qdo65or^iWZw+zq03n<1ZS6SkV|LKYevPiv$ zeP!)MYgK9W!mZQ;8VuX7qBkozqBzVraQ8y=b_Fbg^)!#3y21K2jRPJv_^>VoLsH$N zb=sZPUqX4Zf{&G}y~OHi7qxC-H(`T<_;|7K265D*)shfCj2sDZb%JLmX!U0SA-U#7 z*(>pbJCM^iOd*v|F4q0HLpO__cIO_>cJw4F(z$-GgI!V!y1isc0ag4(_PX9a6@~4R zgbpqv`E5i6v8 zeVzH%3L8X+{eE}XvO$Ge^&RL#@E4m-PsoFR|IXn5H3;u$_~-mthTgUT^Em3h(9T~5 zc;mwI&41p>$h%aXthI(eK4jx#zHIIiKYdWw_`$gLy7#X)Rx$rE1X$+?tYylI~B{J8Yb--C7xA0&winzdun!!?QsOr7)xqyMFL zGW~zMeg9GV-#6SpVLvOuZF@n#3SduoOZ~=!e*Zcyy`eSeH+3J*P~v~{+Kta|e_SvQ zm-aVuob>=-4-VSDR_*Vm_G|t2Clw1Nfxa;={Y&+gl?SQsnf}JM?{8QqZ{v-u(S3>f01B)_32M4o>_1G=kCF?&i7ko>kXtwP2(;P`ogkQ zItwSn+0|FBSjy3;D8<|{e(kYacaGk=xXdmO;AWqhMU@J#i|v zXIg?iwcEiQ<|rU*OXnvm*iddZr*MLzHFI;|54Z8c)F1=g&mRcOqtgyTu#wXMk!0nA zgo)W^ttBYO)H!+qzdk=#m0;-msnz@i(icQ236`9F2EN>p5TShV@`FdNGeU={w)T(l z=VFSqrGAZEt!ezr{XU3A?qH$qa3FLeGx_x`uWEzDoO|d+4V;L8bRIs3?Gt2m$VZ{hwr&7Ahs;KLnT_bo(aysZGl|M z97nI`YneH}i69*LBJ)p(C+)>5;78OG{R_=s$w(!=hpWCXBzW;C4{~zf;RV4$k zVbULh{Uq*9N(_)67f^l;-~W<2#FQV_p}bc7PI=S z7QgIzNBi;@A(Tx_?%08oB8i@vvaEkVd8-GqBdTmtgmffhijtcP6B**0yn?5ZI+2uv z?ZfB9dy)sqB_;90ieCRZ1w0$vj`a2( zmjF*K-kY@{IS*o48k=6w6su+a3zo(le%`2`2(G5sO#QMEayQv5!iwFhS52`y^ha^W z!9~t9YS5`$!@usZ_3kYFkbgl%oLhI&SGUgmJ9s^+G3fiACbmv|Z<tM3%tX!`Nrx&e9+_9drEz%|X?NqI4~*US%^U-VoesC-wLf60KyBookxK_BdG0 z=H19siC%!|vd?OYX6Ze;fP=fW$z_4B4sS)+e4Qz&ITwe&EGK1xcZuwUv!d$zbn`v2 z#u7%@F?0kR?Irj9!bo2O=;7axRmF}9p<8yip#K=;$f}z97NA-3L__VS4V^|0-~03E z;Y1Zn+&~wPCdUY0h7iO3JquZQ$pNAM7D1&Zx)knjlHXr6*B^el{DB2-C${%UZP6B5 z(5*SOmmr+9006jY7L3F6viAN&=eqMCch$hJ7^A;EHd=c+vl(n2bv%)H@)`YG5S=le zKcV&Y4q#4?;+^nQ*UFDnOw49}T0h0(-vp)f87bqWfaHv4DK9twf2TxxS2f%LOLrJr z+`1(EUn6)l{5CSvyy%z49U|J4MWn`hh#EBBnR)TcBOXmOP!fl>KE-wz1!1{ z>Iju$&kV@53F4d5-I;I8e`Jf#a$NR`)7S*Y*}_11LauNtzL|D~)9jSXUbGOF?}v$TQDO1- zj)5cb|NTx&j0u2WCHel6WXm(gtprh}N&v~1>~|oljl^CW`!zr1CbW`$wtm?VQ6Smp z=v7l}uKs8j3zGeDNiW9;X14;#E(sly?E2~%3FjJN-4(Y5I2jAI=Onf3OZNyUH$503 zZGTA=+g~OAFJG?PMsLwNV1aBh%a_U;@`3n~_C56(3i-as$4GZbxT&reuO;9qX(h8` z77)p2<16&cqY+*6sOcrA`EvarDj6AJMx&OOLDC`VzR)!!E9uVGC8WE^Nz#43ty$!n z1V_ku*im9$EF}@S;!nVvSZMaeK&CM@8`_s2tvj6N*cmtIb;=3l_HSeyRZ#sR`-dO>743Ey2UKY=D;0*Ea-;X9L zY2@L7st?A%o<4j)f%IFN^~A!=)0rm&<~=^#=hOP0%Y7MDpMT_?UEmp4YLR%uEM7K^ zR(8XGedbMBDpzmSog0JbJ9C@0J&uDy1i;xq#*G>$^T{VQqrZfxQ4ot}&Qc$SbVDBl zQr!jKuxw?yNo@7F6d^>K*eT<-j~~>m4f8*84*vhmcKN@U{{Oe~{~rI-{Le)Hi~LVb zFFD8O|ARa7za(}}y9@EZa`Wc+f5}(z|3j9V{fmuaYBrDmV?O^cr(BNzx3uT~H$Khs zzuAfS?qMCC2S*T3)BgfMd7tch_;&uwnbQUoyzy!L!M9hvk;>dBwQ@W1pd^0`HG66d zp*tgM#Wq=aa0&wo^X37349SBl(QVSZh+|A3q&JUYd2lN{WZ3>lD-TvBZ^i#;j#K;k zQakz3NQJccKM)LuhC9E94lqvtu4oyw`XSl zjttQ6uaE&}s)cRIfbQ_e_GEwrmBu3kynlpIXx3)oOg{qLVSj4}`wxLt(|FNs9qd1& zAIScboJlP%0>Xb+O8EAl8gz^}H1?mwSvxJk>IdXt_3gjiwkIL1CfKwidV+~q8l5qu z5g6qGNu1LeQl-$BowA&I5VHSFW!Zm*sR*HYh0rhGZ^EniM(f*xR^I+qYV zjr|vB2p7N)dG;S!MRWGw{i09unA`P^`9E0A=1GWMeEaVuinh1^N>Q$~Yt-0#cYK^@ z@3DD1P#JP@r@%fl@r03YJhOo*V^3n;D)YC*RdnHP^Q72G^ocqZm|r~J>Vj`Pw4TRz zjotsoL;B=e`+nA1eqTAml33WXTf>C2#UNzay$}5v%TBltRF1nqvnBPmg5d^0%9mfi1Cp%#Ixx@P6GGH zVcg9%wAT#nL2pKz{6lx)4l6v2yC2blwtsEDlvMj`vjx)%?tsoTXV(I0XiYoIi5i~}KSDKfrk(v5XhUBJ=4Uiucb1TA zO*=h%c4Hkz)02V)MqAa#ns!c8`e@n?70Fh}H@2%-V4LiSL`b`YD!0}-3!^0mrEq7e6&3XFV>aWn}B6FDOoIRINvw6~*lU}mtE^VeGp5ag(OqxhS7+v>}i zPto@(RoRl`wrsu&)y%f^y>GxjU#0K8>LcRw-tG0hKLY>u^u3dik2Q^n8$0NG#y6Jr z_b>nQi>ws+ANTjiB9b6x`4k=h=l%V?nfXB9lauM|`ulICJ`rYLjvN%y_ny)^kdq)G zfB$f!?`iRpM@aG{Pu~ms`=9^4=rru_KU&R(xvWlC+oB46X9-2y>w7~bN2Kp{=IZcG9SC2x)19wtitX4JmekmbMY(NK2d12xxX44fIK~Uu5X` z=wY|aG5bZvzQ7j}ZXNdK_~_zS*qU=DKhFKj_~?Ys4;UZ)=!Nmo&t4oKozhGxH`p-~ zO&-RKb@Y4BhKRi6eIe+62TgZ~4xH^n_qWCHP5Zb&XZoSJ6#3}i(Pdsd;BLChj|co5 z9AxF*cH#jQlnaT#=|Gug%c<25O+4UxV#ZKB;J!j61p49n1GD;}9HOCk&j(J&K_Fb-l2J= ze%P+m%YLc-RqAWS1NKr&Ii*p==g0QYD4Q9`SH%NrH4N63dk?Tm<9|my;1~HC<)5}N zt>@@nI392gZ+AEza73=~*NF!Vhp}_<-jiTj@$M)_081%kv4e~!=@Ann~nI-#Qv-fYMzL$*q@;~qkilUx^s6+BUq(P#@hdhEE zj4EzG;Hpn-iX@1-My953J;|Z`{0q@T=KF#?&eW65} zT`#`2UEjefzFD$A`D{q)&4j``coa@yA|>@cSY*){@^9w(2adjj?|J@#yCtK;D{^g~ z{67zD2dbyz2{*}S^e_H__VORNa`JyQWm4Z0GuG*+Rg3TYCrLOY|M&6be}MVj>sl!E zw)uAlupaWlq&Kiw%=D~BE9YnUEj^|0GwVouKf_={^JhZyP?hmBoUl` zO;7vlh#Aq3DH%d{eyJ_rWMh}rusic1bW^q5a>}9NGLn`dUrn#nX&GLA!9-0%StOuSy-whKQg4oI(D(i^0F+QaA<%*!F_3 zL#|)r<+V1~4upvJ6bb!HE(M30Uh)NI~@uu%=HOMP=8d>7n@;KzyMS`Y9mD4yfp@`e?PUh*A&M2EKM25xO~q4U&l z|G{WDx5k#U+&&<-LI!eqWW;X2vzuljsZ)j`=GI0sFIjpc^FsdjeJkwuhwXRP5bfS$ zxlq*m*5u)iR9*J@u%Wat@@nX z^eb+DdA$UyU%>j?!uoytc=pJf^AOx18Js8If1l&?Xzf`*7Vx@U3)k^6q|`qK2c@+j zSOI<^k72*Y3eYSN59WU0PUG2oNH5H6d}9+}u5S!(C_;98tZ|SA%l; zk#N51Wup(($%C)`af5b>)(+)&|K)=s?Azeipl;FHPnh39-J`Yd^OxOmbw}}jA-@Z1 zm&b?L8@vaaOSa-iXKlV8QYLhH_de$G?iGf&kmIwN5Yj8I@Z%Ptn8ifk;0}_2<7#zW zg_D0A5^&b`XbGR+>Z}|m5&UxFO?+q7GUj-(4{KtUs!ZG5HCm^TZ=mOC-(B>&#r92T z-|y%3(7>Enyz9Vb{aiPrYy zBj=BoiRA)$tZhF!Z2>#~sEvV|LkddBsckI0EQUsW9O-znE}RyLJ|)6SU&NC;VT(6q zt222^`nPJ=q%r9JsTC%#mqt?a@DGX4$%UPdi`9PtC3x?=k61y2$TS-F}F1{T2)#Tsz7%B~#r76;67}J(d#( z^WBPUZnragvlfB7EuVa`HS^otd~O)V30;>=JT!Ga?uzua5J~?2?BG16+0S-8VvzX9 zB*Wk+D_YNVCUz`bI9jJ-Cw4qBdIy5eOD+oOskg0_p4#rX@)?Xo@vtpR{!Qg@%4M)*#sd+2XFsx<{v?B*+dCaJbqrT5oTL zpBe^u;Um&ddozNnQ|WStQm4Fh(td{ZUTvLwWVH4+RW%kYIr0m+_GqR%rI?!$Cin-W`fp8TAS&u_ z|CE%&PQTANl;s{X0J=RKLiGx_bmOP3~??i6B4I8amVcCuJ;yk3k-Xn05H zG3UC;VbbK9_wh@dBBc(}y(6}uR7ncIB1$rEnChiNqmhDX!+R7u158LY3vX$F`o$`4 z+IAY!adl{9+tVLe*|vEX6r~`6T)WIQA5&GrX6i#o)W_u<4u{7bq+@<|lp9hK2d()j ziOL}ynXPZmqieJ0=uwJ^4X4tzVOE8#Q@`PD_%QI!nn_BXtx|Ggb|!zHL)Jk56C{5* z&sI#HDEFv=6C#PyOv1#ml5PIElL?Xdj}azZq>{)?n_AQ@p0F97gA?cvVl#qI|B4SO z=4SpV+CA}_pya@y__z_@JBI-Wnj^*JW_(hITIldzTb?F@9BgNIXc75F5<$PQ%GT7! z&(c<9E6tTPM3W+M|J$i_H2FEx5jN@Zd_X>NyoRKd=7=XOWRD&Lz2T#~8mN1W$(t85 z={-_!{S(`HNvU$3Fc_0R)YLD*IL$lftc!=t@wu}@ZI~VVsoV40up`Xob1>(V)~5!s zveq>I{0d)HERpmidkbVUT=NXhf>YTB(!bZ6QKAwIH5s-ess8kmf8HE`jXdtDL2_Q{ z4dgcGpG+4fp)rfPKkzd_A${5D$Ts;7+?IcQhxW8y&oC`DTrPR3oxeJ+lt84gYIE|w z%BrNbEDtD-u~sLsnuUODjLGIMeLkPgox+LLTnOjJT5Uo`j^KA!7Kh*n{u&e$ohRb_^eYf_wv^>J8r{5WGEtrRHY%EqI`|7Q^+C<+Wi7jk`S52ZX&(2{r`lb zes4ywto+!Dj6=KoA_Md^Y0xKtLQ&-R^%t44lPMrf17!_J&%Bpej*xjP9Pi!U`TB>@ z5!;`y_s;_#j=ZaBJn!e?haf+}2_NQjg5kGIq;+;UsF$x_zKam7Y22O0zKUKoyp`Ys zn)MS#aP<{=ag_2@*Z*vfQXdh8eHEp?Ng+|{&D*BbKR!S^?J0E>1oxGcI!?M>J4*dE z$D?wTdJPB4HO4FXo1@gMewm}!H@8i%E6q5=^ji10MsD6f3E!s2ub|gkAu)`LE(RDw z@;ATN3B6WobwvmM@IFIuKD|Cc(J;M!TVw$_PQ)8ymbidke+42n*z5I|0#&AfPp_|# zh_W+!)fsTEM&kJXb5K^G2;|e#4A`xvvEgSSdNRVVTeOb-uCm8#H*0=5UY%Io6w_`T zn%pk&OkhI3l6dZ-kch|IHu3xv*6u(&d;Mbvi08nAIug&hpNEO(1h#n^{?~TToS4&k zoRxF$TDnOXIoD0&W&-XL)k#!K5y58DyF!{yzv)Z07dw?|KWAdSRFBfGStl8Yq_0qA@y6jMi<0zQ>IxOYG$W?Y%qJJFy1 zz4N;FLuFriUUxn#arV6KaEvQRE7b#OUeh@65=5j`7Px;S(ZWy+Lml*YgN@V+@TRb$ zb>(>aLX@-eFd3IrXEvUbtIiCKuKgY-Tnw%g%>3zF$y>+(%$(kUkhbS7hO!q@F z2;fT#>>Nv9lfLpUas>Ggm^EvQVbGAi0?Ym#DkaUw&s6ib^T|@P!7(RqqqXwWl|7D^ z4rkQe{GK=*Ml;Yywf^#_aLia9a{dZ|d@<>Vg65N-7OJjh_YCyG;5CO9x&4MFu9YBV z%1`0gnxqtNHnfQn{tasr8zhU9snDFPf6JefQo-U=(<21^jcy% zU&8s~MKiLU@ay^`Ytl^}`Tl~leDbwaeKbtZ{{QiYq`3bA%OTz~-`}4*&pz#OzuYYO~LMS zz)oJkqR~^PJ*iX~$t))1sV@o&Y(9t}AHLzQLlJE?jb~j1G6EJ4@>|tes=drhEOTaQ zS~P>aGXnP*4HB)N-g^l5rT~B!cjYBEZO-yZT`m34m(9ofL%L`!@A4#qEIG+}Yp?kP z@GJzGSt&ZY($JASs$n{MSkgM#v#S}RLE*eNd^$2FyWh-D-m$#B^)3pEW;B}AD-;c9 zv>yVmi?U{JVTc&AmfoJum^!J+ytVkV_MNrQz^omry>>_&P7@oP2;maW@fVb>FW-#PbZqj zuAnhrKFOHE^N%rg7Cw8Z@lY&coBSg`HwLeLCO6|DB}!FuQ>ERetDr;$OVNnd8m+M|zDUw1K%z zLYQLiR^|pzU!H~G9yAA8cwNqE7t5Wc2bXo6| z8yIVe@5LQhRjU%WaSNE~DRY;xo7khI*RxG^Ws@LLg+bGQ(CnKK0A zy2Tm7i_jEd*qM8f%9T)U#>-NB2!Z)&6!u?<$61HKtZ(V%*P-}zZuK%dI5*KucAfq< zy^S3@fxX(j1^wP;1{}{URdt+tD6q+PxXQITNVZe5LJVcFgIG9ulU)I3Lzmv;f&9=u zQ;8!Z?~@}#ocsA};#{0kV)9_#9)jTQ3UJbISewr9KbdnKsS?0NG)#jk#K13; zFI)_q{uagE@-5zQC8!>;B|5`I)6CTy5qsdu$S;~nPX{SXQ9u;w9|>_BZwP3D@Kp^v zBC<4L&ObQjc&@v*YbMVtUth*~2w^BO)M96i$&&gcZ*(=)h%JhfE>TYgk3`4p!D|V1 z9nzl)3haQ=k|gekE#44aM^(OM>LczfHEcbAhD1kEICF>3-#=CaLB)tqSE9FU*x1HXspsd~1DtDA_jA~UcLvc=rM{MZEbW)EaD zn-?+&+{&a~8(3aMxC#OgW#1**s9NYgEuMwGD;Ier|E*d`CVRKC-XZ@m^g1MhSC%WX zxxlzQ;+?U+Y;&|O2^5On4_{xlDOz_DPtL}H)pMe?zofkZ7%xsX<3X zYmvSMeD`iyquBkI(b@`iSUuZW8GTksvkjMj_R1H^09a>|7c4C-OUy~UXAiSv^?~Su zv4!5G!fBgn`%~H^)ofx;e5YxfkDN+a#*891uPOE@-4=LffX5=IYAz!fID}ENRi~go zDFfr*a7y&LYMx>QRgWr0K$0)U%qY3ieFTg-H=8;tTGx+y0}~AHA+ z5%;mMn8U+4`6Lm9mt8|wx#M%?Dnb2t^4&Fuzwg)a`>OEwFZP5YM^cmMO%A-VfM>#L zsmo>nH@E*-uutT@dY$q)x?k2l9XqD~hS912Vu7w{Jb>L2HEZXAbhv|!WZmMsp)L7W zg&$x%iVYf}KdTr)mf3$X}vy92AJC}aQGlU>e za@HU|j|9Uri70A{tr9gF#T|v{LTnHNb8NQO%tO>w6$4pC>iSvdYZ$M%qY!?YsSX3% zcn78P1{UAP3`#4G8PxYEAvOONx@5|;R8ChfGF~7W*Iyit0aKT8#`9zDazDtX?3d4Q;HpvTf@Zl+afQP`d zfQ1~|W~=kr(i878A6E&a>!>pDaf8+C7DyN&E~{IcVy!}>J4+u(!q2VeV*~_BL*`VIWI!t|Lu+$I>dB168p;~$P9fJ!E_g?)(r{(Q*Re6{; z?G*9xb+%?_{=!DmCjNhk|6dE-oW{Nxpktpz>2kO|6(!S-T(b{z&o(!>h{-NlC!U5gL z_nb*vezy7W~>IVzLCEzh9^j5Yj&uNlb~D_`bV)+0~KgbrMYzd$Va~ zZ@+y0_Z$21Iyys1`3LSDy-xaV`V$^<@{&6R2xGfLip7e`uOs0pm5y0ir{(xlTU-Q1 z-u=pDNIqNzu{G(QG&Y{|QY?J4>eEds2E5F#${pgDTbeEqV8ore;i@=RD`upWl(3=Y#1@{}9`*P=*`tOX+)i;22Q@um|`p+84b+b_R2jlD8T<2hB4?~2I43N&uqtk@Y%*55!vO7drw*uBKsku!3= zJF-nG_{c3%!MTwX{WjJtL!$x&G$&KV&f>mR#SNRgT(bPZ2OfB!ZaE9^l(Vo|aqh&H zc&DW@#l9R!kP&KG^0VUPr^Pt&9Bkr5eLz)DNDtVIanrYIN#8`XTfHQC*@{AU=+1cc zPAGBD+_}^_^MumG(xO#Aa44vUc4vA&!kviHX*UJ5h%J-}q%Xr(T$!Wt!VqpJ{7a8mg zy$+{PF;dNmaTzmL$gC)9ijNOE!!xtYO{}1+V7=IGe@oRLozW%L>eb(3hos=4{;s_N zH%&y-31BC1-*f!fKKe|t2QUnmd!Y9JX;!6 zYzZSGiE-tU#CU%=pQaC|S~iLC<@rrskF*PInqIqvCMQS&LR2q9RJuv?g?N=l-I6+? zRt#-4i9Hv8u{HHD|HvGguoX_be9Kf%E)Mit7R%HbMgDY%y5uw5@ z`+RH^m()Otac5cZpD!P#!Ywt8e>zR_;c$qNZDjqJpwwNGUW{^ee5liu=e|rfaXp0H zRAw&;lHBtZxIel^C|WVOTHbdCH)<82b<_P?Y#b?RDz|mZi|MAoDd)a>?Gx?g-@hg4 z>TllofrdmacGFEMl4tW?Du}aVYci3UT=Nsa`Zs0=SeM4jEuh{=Ahf&R@&V;KAeLlb zGydl?cp!-+SVRzp$WKWWR)tA%FnNTEpG#gs?4%PsF?bkkGUCK07Al8i+%!HAa z9B!?9hX3~_rVgn2IlP{!{D6OCB$)uiA3&JXrf%wopBsV3Ix8urv~erx-EDD^Y7mDyC|yYc7~fSG@8&lI0uj+{Ym ztdrh>&v8Elm^a0UG||`R^gxhpe|Mr*L+;Tma;w(ir(t=}b}`+ii3eNWbD2w}DfHIUUh5mE@6nO2_|AjynA{OcD*<$pN^m7to9LQ~C-G6wGbHPn z-;bYxc&>Yvhk(FhjtDICCPc6q0iZ%XJ`fQE{Ew7?|3`@b2Wg#RU7eu&QcE&t*?D8q zmdAS`#B)ynRvJY)T*H-Q>;PR;TTc)*@qHB#1pv=;w!ldY(CMdK=KRP7J9M8>RjVJ5 z1%q@uu)LVO=`bhcW8hz!dDPb*D2X|6ZEq=8n6E~9NCBso5q~6u13_yb1o^X}g`%b9 zk-}VWIeO>5W37y`hzwOEF)V5tA3xcr3UC}zI7RzEyfFd!J5{Sw>omPpt6_qxg`#p6 z#;;?#06Q1bv8rJCZ!mK{JkTE~ry!|ZQ-1LD0R~`Z(@sRY^HCaU zzx4j`Q5DS6&Qy9z~JcA7MQoD@d$br3j$4~Hv<87*_lPD(VKm= zu7Ntr*s;A7B6GR%uWD7iyezgF`(&8#vee8!0>B6yZsVrUZy4dRVj!j7<(|Mkc$LtG zFIpe=7fy-{OstOYiZ9{MzH5qvr0o6n71}kQ1OB99e;>IssietnCC@w_LS}%^;fA?{ zPvmv#U^B3)3ZK7<+4?*1w4!*WoVkTOc*HL%_;*X6Hq>xPZeQuxRjc|mXu=Ev@O3{1 zNh>ss0Bppl=J$I|wG4+EE!lq_7vZISgCdZpSXfZ$wX^*o#a ztJJ(WdNvZC_5nRDg~Q0{P>u60@EsEA<7;tV&&Hg8s0eDi zcHa)!nLP#CX{eK{Lk8#(-|ZN85XJR%OyGc^2Pa@N-XzfPPeW^H*gnYRvrh9V^fwj zN3XZctjUqQ2u)7m)Q%-5v-HT9xufNQTwpN~4ZZB6=SN!x8{(%Ja*cJ=A#)O>yVL{@Yyr?>wZ zefp@!cvzZx`bqol#g%3q_vPV%17+v(3!g9=|me^yL+2lVIOG`(&8`Fdo8B!5_c z{`}ei`hQ1%o<}R#O#d(G&*uCu3l{W0Nc4X=HW&tX8Op0RNk(h`iC`KSD~%s5tqUzF z(Tej(UT{q}>~+UAW-jVxQ_f#=Q?=$@oOo2=MDguFk!UL}C2s0um6jeP4Tm+e%ZCQD z=LId4n-&t!2E80*TRcsAAIjOi@U$`D*XU`Md6G^@>^45attu_6S`)214Y6!|YFT{@ zXiPlGs?Nk|=p4&U4k}=nvPLk(?@Y(2Xzk|z#oD{TM^R+$!$}AbFwj9GqM)MUg%y=3 zDiPKVEE5n7f)HdCyvw5N-5J13V8)(-v~44Z__C|3uB*Gax?TZ61OmxUz(wRHprS^M z*yBVEh!C<${?Bu&yQgOey6^XX{(h3_x|}+7>eQ)oPMxX>)fa~fx#QE1N!b6OwYh5O zfYkm7qPn<0qVz$#t>mBX%kPJonackX(mt}Py)U1)#CZ9TN2Bf6A)_MIUtGk|z)`t8 zYpyE8p8orv3>DxD!-Aibk4X79edSe~EdOLH^U11HOBj{-GP{72nsBdG&wt>0{(I(#>w?;c!%v*Vdf%QS+D9_nRA$u_RK|qUu$eI zwsvR={S(_CR1Y{g0FnkXI)4+yBUd-IXF+#>(&J2hA+RQ5IFCIQj|}! zU=K2?8L`s95U?{S9ccU*F}#2Om5uF&tP> z{{jO0KP5Uq0GRCmEO~^Q2mc)&5m3UR*5UCO_cM5`1_LQc;TvzUub+Yz6RBQ*p$xeY zEClVk1`4(4jXzJJ8v83W>W$-J2(qj!(UkF^0zP1NoPr;=6E0{kKzb1AAqgSr2{xCT zcI5Hl>tFw=CA+b>aq>yVo@8gIJ$-d{@#>%!zNk-VZ#?I0`3&tQe`Ct93F^8tMP}Tl zPF=c=Pw)O}^sg6)0nRPxA`Jpbcao`le%Rkr4%=V#exUsn)^v>j`8iqPihM@~p`yB^ zNZnZ^R~7B2JSS#$BcupO=*kfwHgUFnGqzwNt7ZZWNJ-f`rvZZ!#|{JB1@iV`yre@` zyriQ%W;imJa#lQD9zUWIiu2`m%oha&RWiOiI^XsWtJvN#zV>p#;*JXKHkt04t}W>{ zoC0Wder-t)M2ckL?NMW7VZ5Yg7O_!+BXu4Q@5_4r8hbLdM)<$_L8`(hR$2fLs5x~n z_U3MYtq@x~wF{Ox_&)5tuY!+xlR~|=__F>j;R8K`mxm8@3=S}d?X~X99x%0ON;`e( zk6F{YsR|S*_Bj+{QVFHvxp^JgfcFAu4?Qjs?qCdi5yAWXpVhS`j2y`_rlMZ|tmGEA z8=#-FzPy7a9PxkW`PKvI7_X?mF1Q5<+ zNz^XIW>2(l4(*}W7P`Q+zk@-@$Kc^M1nk>m4s}Yy-@QQToYa+0(?9iDf%TYP$@i2A zI3K?W^7sEngRX^^T%TI6H)5tms@niVwZ0QOQpX%wXkM}R%#l6xszL}GGP0d~F>}3_ z^-mzI!kt5OHe$aIv=IpE#QNXFyBs>w^AV=(r@2Sxf&I`R)PFQ7f6^)A={8#oJ^g)NVQ$H`=3vb#{i72699<(Xh%lO=Qa58Sptqg27agoHx zz1HyT0mGW$UzpNf*l!vlUEuFp$DyRY^(mTDCAGz6n=A7X3{a4IKQA^Dz{3}J#IS^( zK?Asb=E?B1>~li%h++;k-r=e1obSV%{^d<>}`CdagaG z-Qq6bj)d!%#wNPU!Xv@L1zF7xYj@9|8UN?Od?zE0E6NE-y-t2 z6U@a?<1n!1_cKI^j?!I-I|JR$xa_$X*_Qqjf`vhRWHRoX0m^9suPZTZc;HKgY2z-+ zQFx7&0ibAxx(5zffhNZZO?=m}#}H})2c_@f!q@_&5V;&S0_4UDa-k#Bri7w<1+-H? zOBv-0$xpBlI7shdHvxRa-UuvCHt^AD>`j1tB%FYPQM_H3Hd4wb3t)JV&EZy=4-Wuh z8XDf^TGc={H9NIO2T-L+U2irR#PL7dr$wL5sK65@44a08MBnW$tWb|MckUPapR`A?>cmCS*zqz|BRvgq+MF$mB7KIH__S5|f{^ta?T4LW(}` zi~H#Ad$HuFM=*D={-5pRr9l~L&d!IdEzS1DwkJy+Xy1(1Ce-OKb8d9&-2C%9JdA{%)~l0e6K5M za2JgI22hwxa9w|fl-pYg=r!{C&Z zV46O|NBYa3g;3&-uq(kXb_*J1HF`x2t{N^uu1`oF&l(JW@`TdApHV~dr`0kftf=mw zUFk`>1x}GEs)!@K7g<;hsV zqOx~RmRZ^Z&xv7ArXRNi%lA`wah`abK>p`~I<_!_3z{&$Qv#+HeY~6Ukg&a7;G;-& zH?+5}w67z-CV?`C$}eHNKLd1lV&7koUvmU#^%*JoB^sl{y2YOOQRi_-+t*9^xn6m8 z5nLns<}g-GmtRvco*DA%M1e3$AoPLIg34(Q?FkJ~^HfY_mT)c*H2J*eG#SlL_6_X| zi3aaaYZ9$H3i%~kLGotNC)4GbH!A7!?2f;3J|0G%75b+UA^|X-7pwAV@~m%4o@vpu zF*NREDRn0c_GlhG8X3Ns^}|z`C)r4&9Gg!$b`n2aIrapyNr9WO$CO(8-%{hDH%v;| zYjJQ`q`K)eSBjaXq-vKm4Ttm~U0u1hMtsm(^bw(GN>y~^$XaA8RS_pZ4yP>^A|B#N z5HCYpgmCjyO}X~+o+Fk0QjhCYy2khfQi!7nG|;4%gX4K53n&q6UFIE+Vy(zL8LT;2 z4ANA>=&qD9rbRcSMgIt`MW%0rMx%F$Mg9t}`6?J?3-yYHkblEuT)iV~$Fmkay)F~@ zB&Jg%S88}#V)9R@!G~#RE{PiVN2IXJla@OYbD>{it|1>zMiHLp!zld0DSZ)2BX}d> zv5V-c_#&zzam7a``Vr#Gq5pxGvHtaP7N*Fe+~wUR3C*pqHnqJ_XyM?F@CoQRUVt@y0{bVkLCrDCJ6;v>F_ z1#ZP9_RSd;+e*c@MBeG>XkW!`$OXsY?iss}Q<0uFGT~D<5!J4~ipTjXKCLR+`(A8m ziPXG|Ix5~(j*EYeM2fd(-v%g2dEZHy<)tilQXceDUUE`y^-})mq>S@YW;!XQNO2uO zDgB)O9PszcP(>oupPuAMMjX3qvZmx(y6if%_pdW+ZjkQVRrCn>olef~!!hKtkCvhr zh>!tI^3XiCN^v8cr=R~u8oL{fVgC!UojqaRR0ck?bYAvbTdGFBor+a(B8#1{;@Z*z zkPUC5=hv2s+s-I0v`Tw$s|;Q%NJO;6_WwGM(yYKJ?P--VBt^xMB3BgOnB;b|rk&xA z@4b@JgAlCJK7?>RQnbb8pW)09L!4r@& z>eR{27xU>O*%jhxaC;q2U$LdYcKd5-XuB6``jLDK&hO)A@(o-SP!E`DS|{rdncuW; zTAt=$72(EgXQqboaKhixWpX*LyX?C$OzcjelGr`;j5~K-Hvop_6HHaBd_Id&I9?-V zIMIA%mZA&+oCJMY_|np4Mxl=VXD6>M@+xE4F+{Ir)({}zS2+1!hM5l;=S~hMe}a?$ z!DE0O2&Y7i6`0R9Es(S}hDED|3mufl(=GiuTo~cQ`Btw8`2xXIvH4iIt-xpK6dmuD z-qR<8E<cHA*-MC`DDZ^HKhOoGB=GAZ`I_&PAa)Qftmq|$dpMHR~x3_Iq3u*@FMrkv$PKM5U&6i_CVGkj;W)W0xgz5QNGUyla` zSq?4IVJ2+Qj^+N0ayTFTDH1U*3oQLQ-?%J%TrJ|4UCD0xFDu}Ys}u_)7V#|@| z*GaxZCLd35JW4AcL$e?ID=f&Uuum#@UZq*AzyLq5gZxd8njHbG5EB~D=7pnVGibQH|*dgKZTC;mDDf}+UFoA zxgJL-Ajx7uFo%6SQcU>?sr8Xr9#!cC^Vlpmi*rMjL2`1oo19#d{L;fP!LFyi7ybmcWMS9R?22F54Q;ss^AkSC>c)@4Z zanu*-y-T}Cq4kxmP`06XTCl)b%$ze3TR}^BI1c)(U_{#EU{ zg?sTu1jtcK$+8CHVhAeqS%$zu%popCt_^@iFgpWsw%Aynhq~&*8NBJEE{O5;hR547 z*P6$FO?fFC?l9v25m=};R)A!}GUvXAU#W+{YvuYKX(iUfDN`$NBr(mx2?2p+4esf_ zEW@tW$}{7tM4qAE6^WgJ4EA^_IZ$4fsg3nP8ubbE&pCLf3KMQ$XK?k`%VGv&3QcFjE5&@CfL5b_`-!C z-;{o`C2l1E-%HLCj^wL#j>qAxxxfH&-`xt-Vs{Z@d+<59SdlQDGz-v{8aeb-5yVs- z9JzOZV5!9zcI10HBwsr25-pca;t(q?pcjH;*)-IUD&`TeidOuWc;8Jr2l65{WHsu! z*bttLe&Ln@j--W)v2iFtbyPg~*I_hJf#SmH=z2&?nxtMwqjX<-!ucuyb|s=A_YvvK zX)eOfR4ajZCCegkxvT`1^qP&LC1N=MSSI*{g$I>UvVNh=H+p@B?yUs1B~>9f^e`yg zCiT3#uFhq>aY%#Am03XMpWsa1m+`_IPYtV1e4TBK{4u#01r_4~&6+WodNRS(yut)? z=&vR>yHbL#P(WP^V32bTJ0$0LyJmNqDA0&3)%EM}nS>FYd?%UYLLl6Bsgy~6l-!60V;#;rE))p5;H{qR&c=murtQLA7Zf#t} zWR1kjBqvPnL?vznimH7v#L&q;oHgXgHo{Y*aL{JHVO61~0Sy=QsRMm1{ai^AfZvQoG&U%Oc#+Ip+S4YQ$twVNKD*3c-MomeOmOM zb{O?(Juu|QfL&n){@R?!0+oY<@xh^NQ%b8=;w8bpAU`;$HrkdC0D>Q~v=uTe#Lu1= zC0gV~3!TI5Nb)Qr*Md(`)SR~+IedippI|*yfQTfqt#ZBt=7>m{oxjFaVtn;5v_M28 zCi_bkAgi@N;A^p4fh`#uBqmG$NeYNY?GzY=j+rJ$UkwIP5;|Ce+)?Br!J#nKI6(e7 zb-x5~-^+e!BW-^sY(>7cEaBn7xwwQ!!RCSi{q*s+B)D(QU^%<=Va!a4`oYy<1D1=B zh!%qu+Tsh1-QffITGS*(XWb617BV9^E_`6T%=_Tk;RBttn7BLj5+8Gr?2c}`gmUh0 zPE?WJ&sWGQQ>HJb#9S7N%(nC*e}2j|z8Cq4YuGgvoupsXdO6C^#09=`7y8QikUE9s zI{V7~+E>np*MC5o1Rb$%yTA39OX0VfsvBlt`GG1viGQ7NO|DnnfVx@0t1P7!;*%X+Oxotf8U>y~$v_i;_|jk%(^`nu zaqE|wSq#5W4(#H0wOAtryfS&+J`^y;Yy!=B<_%i_8OKo?!D6)N9ePACXA`n747rbG zkJ}QwhDPpCbk_%(UCM%o;wEzzSJF9l*lfhu;nF5fRxU5-=|Q566mLF7N7GF6u9oW$ zoZbe0%E&WB+$cE%QSs>MDC@gs?sFaZ9mO=@2Z0r9Le~->;~$KNA|)n(M>*_PfOz&x zm1>md3F)Ae@^7SuOSbYwHeu;4j;Sfw2YFbAt>Kt-CulSN2e9!LTJ%x;<*mkOm%VBV z17tg{H$6c?q_m9eretv9T{4A|At@@X!T2Yx0&BX?0C{waG*Z}b4Sk-(zZR5G*6N~% zz%mCNfsfgGDnK~1`%laQ7Pq{B(R~w`;X3Q!RsQX9?a{qrAoG|sTe1I+Dv3Izft8Hd z%jl#%21%y;R1FRxR5036gz6chTT#dRO1=P_ce6Wq!AlQ6aCeXj>O>-&KZDI*#WX~s z)N(!E8bNDKi2@*RzdH?>P!;4_qbpT#A$TaU2jB1us$0OGS2aFmT0HRu{$$ii)Ubcz zMy`Zespc+j-7kv#au&1dFJ3KxfcqEcY z^XO2NUVg5W_q5mr^jp<={Fxr(ByUSmYTE7S`01(J&o8JkLi|jOpR| zD_ozOD?e}>k9DPc0UN~hJ=p{9YDz`#S=W&eY#vaFDZ9LO))M_Q~Li^))Bh!U#J`Xe-r*=Cts`U9n!5NC}8bZ3KugI>G{+ZT}bcc5r& z-?UAtHMMp)@u|H`b-x=0vD^ws9b*Q#hGiu|;nxS>vVIV`V5PfiNE~ZcB7{Vxx0gXD zn}jb?oAT-77r+}1QHTs2(OkYV>B20RE_qJtLYD_xr^{@rS&P`vfJM~0LlY7<7-V*_ zqy;bc_tX%oyMu6ox)e`cfhU3-9Tt7g9g4KBYO%G@TX5+cCKv9|3#_p}#8GfnnLiC`%P4gs(fO5KB-{AGp5RTGmt~MCkFDS6!!E&^` zn|=p+5H{F!JJtm32B?l|v18F)r+Ys~#no6&R565GR&WTo`g8QO*lKoZIq9Zoh-;a< ztN94Yi>B&gu zeg}%jEiA!x7xQ(|R5Z+s??AWllLf4F6_l{Yzb7o>&d`67Dq<#ilT?dVk{)suD|Gp- zSYlHXReSUgYzT|Evot*NAR51tX$wySPPhaVFPh*|OPPS@%t&wi{q<>$_hsYaWOrOD z(a!#sFUe?mx2%Akv-(K3{0Y+3yx>bJ^Vu%O`tNGn@RRYFAKf>kwfPR@siUbWH%|0V z0O9p^64=P!+X`v3-tFzv51`FkkmkuJ>F*M^zrUCMYKyB#Z@Uh6IB;Lck%oh$X>gWK$93c4#E>S4)NsXjO4S?kK~*ba4Ocx zNb37_%q?~Auh)JrB&7=6j@4E|WitSu$?mz7a6%rE0G@gN!g;Ul5pXx+AKK8LorQ z;48A<0zR!cibQiF${5F+05@?1#G)f72Et8r9i-U6j#`w`Y#up;6%Flq1M> z#BTu*Y2p8WcTiuBh2w~CKr=t<3YxbUB`k4DxYFxc)TcjClv%DK5U{);v@*7mWyMz{ zg6l1aR^|UvL_&wnQTh7LMf$sW2Kk&<&AeNjLf3+i zlv9XnBA!eBwJ8NEM+M`9;1m)nD>(7Na0-dnBi$)P8=cPN5kXq?A)= zKKg|UDW?$a2Kt2@9sG==(Oc*eDGTcf2-kF{(7(xmDW_0O3Wz4F4E)#tDvtjvr;z6y zh`mpAg+C5;|Jmn5(=@LSS=iNQ zyPF~sh_a*etN|*Ab^JVls*db%j+BX-ot3x&8NBcOXZ#;Wk}uQzA3!qQ|1pV6mFNF> z4s+^l(8TqB5O0Mp*XV)NB2(Awe~#&sID=`_6UEnxPEig}cXm6sOcs;*yx|#-5@0vV z^>lDa!TnEIi~HXNtTOx;#%d)n6326`Z%TG`!RI$uTm23;$NTNt0z$tzn61@XnSfEDo`ErdgB;r-%Mr|cBXZw7fw56IKA>f z&6E=KVVV*|kCqJ*`2nF5{T~0-Ec&om%tMoO8#nFJo3rs`v z1=La;XMYW9lj=)xqp4D&wln3RC2JAa|6y1jlN&u($5LiDB{w4}K0CP-VlG+hvP`h_ z@a)n_kd%9%FwN~Z04Blbls&J@bplwf!WQQVxy^C7EcM(USEqDFiAxrso}M^?K(mqN zk~nxldifXGVCqoRSu8&fX^HbWF0RIwd_MJat-aaGZT^g^i7p3F=rp!0bYj!uP zB@n8vJWVNLC9YD6q;rYtzYf(OQ}Ow5P1wJM5WxK>2ePq{_RI<$&zmi%Re>kIrDEir zQIdH*HgCY#{NNe#hJ+^Npnb(}N4XJly+1DrbC0KDKEoLGPrdh!J=nsVG`;gMj{j&S zrXJpZZpw!K_#>nR@KRUE*;fw+6EwA-G8w+31+MQ1)x}$sr(Uym!owWx_5jK0*hHN; zsuF47*`L8ao;9{Q-AQzm75KyzQ-yb6fvaBT!S<|^kG`OyEg8kN(cuWohp=G+?OEFxHS zULftfsg;j(cYT4sgrDX-dNbVtyBVTSRe^H>{u2MG)7Pmz$P;L8PcMw4e#*B|IShbQ z0rCkrcOtQA$JbvR73fR6{fMQ;jao#Jqogb1Y8UB>4GOA2m&;ZHmKpe2BreeM(4;>M z(k~sAb>MgKRPmx7=#3UbWMoDG^It#??af7du4gfX0K(xu5^n>$x*YPrYCuqqA1ChO zZT5dT;VS~expIPMk7JbRUs?1A*T2FcpnqjE5aX0N^A^m?IA^L__vtU`k1}8^`<$Dl zj0^&uCFi^&T;ZZ}9p`O~g*|4~qEHM|?t^Tg=64@l!*&qC=O_->0;|Murg`&={)0sr zFY=?^0`tUSGj5XD&n!=Czm9S<#=^e#8Mo$5n7c7h{`NmbCU=*d_CLE7?Z3;kRQvFo zNHjYak~^=G_Qh}V#fr4HZ<4mhrMErZ-}aYSO8sr$AZ>fn@J6;hf@vPzad{*sn0icw z^j}#*zp@tniV_AlpNp>%C$e4N^2$$vpCdUoV^J{06Y3+zx4_aP#*hqzHX_rva&ICd zEJvE>SA`aWLAbSCh~PSLx~J1&Jey7PS>5k%vns=hLm!1N!15Zlc?r@yezgK03K7I- z=XeAhIk^!Ob9?(Gbf-i7bXoqEFUV;53n1$A)73+9OuWxD<)^a(A4$8R`Idf(Z|aTr zHF_5tRlAywuPo*t@XWqWk^%R8W%sbfF-TMN6`ALHR2;w11?YgMnUuc`=5iHT3K>&^ z+^EP-7AkssBHal22Bx`BPQ`zZ)xZ_&cDDlMGn$E`hoYzunxm-vLoMm^P=QkDCKhqE ziUil_msheDp`aYW9ucW>W^fvi)>iYn2OwLMu_Xj~8_6%O=pDSlc z2R$w6LSUCT7HJAudm@lU=xO3uQpLqK8BaF2z|M3-s<`7+fmVEK|JSIUxCLp+*D>vr zOH#W>o02bi(By)`VzwK(H31NcOz=+s5axAZSR5$JE zDx+3zfN=N!u%g2M_Z`O%m+|ByzLt%zA0QiEf!9JqDJv+AD{uf{1O2UnuBU=|}mXe{*vR`Wy%V#|h(T zAYHJW0a{Uuy@+`@28$@(@&(1Ed7&YRn*kR7YIU81S-yZQc{Ze%I>{f;?brvu@ap9N z2iW~$>b*?tXx_A0&eqiZ$Dl+IlweliWyw8%8Rk$Sj=Z6Jwb^ZOho{r2hNal`t9VU| z{sGOarmR8P0|tZR7djVds+T) U2a^TqXRj1@%+IAj&U=`xx$0P2MbnNmnJYwlP{ zd|Bvd-bR|68R&Dn-W3_VvKs7`u-5I;bIB$w%U^mbZz(uTW_ zWzRF`2rNOwyX<-FxW#jG`tXh%cY_weQ0!J z3-iiU1H(ry(ON0c;@=S%4F(DbuVVA>DpHW6JMYF6Ulj{#sk7-?bT~NEQxobr#%sCo zsF0Pjkm(Cwed&72;#7s;J^sR3QrO$Np2orrSOq+J2AatA`S@Eqn8d(a6eN3A0+y|} z1>>xTI@TK%JO9IVz#ko~(Q&4r!IRQSGx?b-^LzPa{#LX}v)NJa_n~@XHPR^T?{C3N zhsh5;Ao4bqyPppE;GAdM0mi`jcU(8z%6n(DJx4-fC-D#gwIf}B;fmS>Z4u|n*V(+HBRh0zYxi>eiw*hhVsmWnfU$X*cJwqNFd~<4bKz!Ue|d17=fA4#2qXG+ zrRO^GcRHpm-akkjYCm_!31ruPUIX@(*o&XFpO=z1f*1v?5kGG~zi@c_c?){-3-kHid!n{*^{F_nFG@UKCZ^a7hH!Z3mZ(9+@T;P){|?nvvH zB=cUqrW&ggK*7o!NVc#?C-<3efTSxvU!`yrhnY=c} z;jtUp_AI7}K4_&GzhqbRe`V1x*uMxUaQWdVL1+>%Pp#h3v;7FcS(i2#T?8R7Tyql{ z;U_?G^)`CpL4;dNg$SPgn@)$Pn#qPd80p4rybTZ@5!Ph1`DbMM?O(QOAkAAJf6o2| z#oXSW%4Rd;R7(6UGdju7dZ$RsUYtt(@6fWwv|q4)eT}|$fPIyyUdR5m{Pg`-Mqlp| z`ljq(wm2SXioVXCP4HaI_rsXEidfzvUPJ&SR;CU6UTP`Fj*(*|R*wUbsx z{2X?m+zy`WACxi~6wl7R92g{u*+bW;P4M9muqIH%-=$Z$AmbgKk`(xm1+Otg>|uiH*zg;{nN_+eGN&<)D>BbS(%HWL1WtD zK|S;}*_DHOpt3cl179PV#fw*r1Ih$0t8?T!;uceO@YZv{CXPYZ5xUsV*}?ztmA#mD zaQjR%_^+NB9KOECL7I58IQd|aHmPf?LAU?X4*oS86FYb`Hh5e+_)7dv*}=WfI@AvS z0K+5mD#H%e>kfi8v=_=?2Nx^Bwc&> z(L?Ov=foaXk9D|ml`ATBVg??OSnl~nv9>ep;ZMeT7Z;am#~axK9S6I1l@i9$1(S3$eHy1|%-Jf|FH@ zNAM31WAcqWE<;NorQMo+-b6#?3%Nj{0CR_fM(k3ps7~(y5ghgDu^=b(2vY3_UsK<;DT_CQBBaC(tk#-sdSFb7y#EA@^gD!BfJ?mP^q-tpKHKy!$n@E!+Gt2Hi)o%d zb*M4zknal!NcR~TSD+5@!wv{+&y;=h3cxO6n&>NFtVAJ(RGFt^k;y)u8UhcwvOBp{ zT@IkirLW3f3oV!5=~L#nh(dO2 zoX(*JIUhq%f&%GCn9I1ZcW7?yA54A^SlARBrY4#=Fz#A~O zAk!ZG_Hq;(A#X*G$WJS;$Me9Ao=N({e=sXvN!=&&9VP(eA8<(R=PH+=*$d-_{oHBT z&$UzbDC3Hk_a_4s_Oja#$6vLaVCLo7?f-&0uoE0L-+`(wWu z35lTOv}<_M`Q*sYyIZwK84rI3@p9tf{|%p;Igcq~k3v{E@%gTiRk6U?&vn+rTSuj) z``?Y*#qDUs|wK0 z0_^^TeT*9bzr@}yTcbJu`JT<9YEu?~rbVqDz8T_zH1P09d>jTJkT@XbXeP;2|Kr;c##QI_C- zYl!S_a$@p5v3R5EOl_<+KCMvHhy-96sunZ_Mk71pV`D!@}&5 zGtIqzjS`X!1ZhxWq7<0(BpacK_Lg*1KcEtvX1(=n}!mvoG(t3>ck{ zG^Gb&pShxv`a?%Z5zxf7FPEhgV%;J3M=IR?Rj1J(K^3>rxThM9Ju*9xGzn} z!F_!u}hbsaS4Oh+1)w~G?51?P=I~lN`}v;X)l)HQkU)M zN!r%w-^17UJt!B6MdzR`pRuUs%YSJvb|OMzFP?&v{jR-uI)10@#RDfCYA@29Kdimj z*R>a&ebZ|(&5Kf;kKt=9-5-w?7eKmcfcyvK+w+HnT~!T+t0KWkfmJsN^h%% zIOUbg@)*hS>VDc*iamv5%4mfxTfT5MMx+&kRfvB#io#$G_JXmx{SaeSii|*!t7~DOJA3NP5=dXJ+t4=j{;un+_8be+R@o_$z5r7 z{tZ|W$N|dEfBbJ^B=vRe{2?!>@06X-w;x);_z#rNR1RrDF2j6K3q|1&wNQL9(Pu#> zenP%0snd+c16UD!`*taobofwLrL<6!HBAXCWy7g3DE5B|hF9 z)nblwAso27jYRq~I;x>KvJ{4AsjC;| zE?oyqF~KM;h+r660Wi9NS&$AUEMPuU*dVY*?g4ec>=_I&%5)_duAl%jP{432($^^- zouaNUor1?uZVYw6yhJdEbm|A(=Y@qN9n5P2MsDE5vqR3UyAGI}2+RN#ZJ2v!oi(I}+8XPHemmvPACTX#6$Sh=a)* z_q>G`oegGq8*o*aD1#jfWMS~G^85)^5VNFWmBTS^h)X9qz>(iQ9mf_mzAy^|LAgk8%p|)#-pw7DT+O_bwvf z&PbC}Y##O**M#(wN}es(mX&0G+{H$@Q}1cvjUnq3FJU@(9V<(3zpsGuZYX&hteoh9 zH0}&?^vO&Asz+jf0CD&-PKLT}1nB&6s+(`%r9oLg<$ml(;84c-=eW;VYv~PC0NOE< z&)q-{9c}4bRI2}KY$;)|$#%d|6$m|;BuY3iKf|}ks@Ih%Ecu+A^?ZI0CR_;&AwsQImr z`?Toc_;#yspm)*6+pM|TSF?4#jY=(#Z=4r0SCtR1?!@cWL-6v=r_pv7LG8Cd4TshBh9DJZXsozo z9;&Mt{q~k~e`=9s&{(wuq{0n%p?3QMFNQ;%^_rkOUakC6xUHHA22|J+C#d&4@%}Zm zBfNi&=S-}?v#rAq0zTEODh1B-&k6me;^ie^X5S)ko&+4{K_=koA_-TUeGY&WZNhsy zovFdnm^G0?`g7V(!o5gXOkvVXP5^pk>O+(G~<(&X8brIp|STIU_f0-!FftyeH> zLEd+**!KYA=DMaa@f#2RM6>g%A~nRri*Er6=zSL2#~*v~IWWngMP{*0+(~Wei+~H+ zjUaG7wi$#}ujr)rkNkPP zl%K20t89)1h$(M2;ZGKD0C`&M9Wox%>l7%wk5W`c2qy}JQBI4v+jw{$9{ua)j-)wQ z+-)uBfRE>Ce>wd28PpEEe<=0)n4tpRkAqE0s)x=!^ttlty4`^G;Y2s4<{Ee989a!M z!QL_$adSXeJ(?$O74l9NmP@l8_-it-zX_mLJ`G2({UOLI$@l8tWji@`4H9)+v$hMK z@uDhWGx1j=KOZ&ipx3VR7V|H(9i=e9V|_J!1ePa%VlC7DoZRK(heP>kw7n5Z3*P@- z#__}Z9A|Olav>B^4fKNill(6rk(4~aJ0r*3Qe{K9vfBqhWoM*uzMKyyCE&_(_EUu3 zMjZEF3yfz3MjxZR&RRAGGn|w166tCk=1N?jiZlsLvVVKFGj`!+Dls0q0K_4W*l;=E z4*vSDfIzaF!#_?Im0tb!`s`qVQ!n_X3l&XWL#iWgt<1bQv^HN1GL$oA6y&{tTrsNm8@NPIfyirnKSLN;Bohd8_UM45V@&y>3 zDQdtA0^5_qEpUann?+yQzNoFmJxGZ3lzqwU>T`y$n+ zIORK_ydmWsE?3?6+QWTbA}^clrBW~XmaNxc`aV|3M*s785ff-C!5k(=3r{s>*$;t@ zWu3v4*u^1C9T!Qbuk*h6cmY030fz`ua>srEBcnHEJy;qnG}_VM>s{U;P#o&DMFVb>O6wQ9$_xqPm*89pPv9iphdy9I{h9Vh2`C+)*#7U*+E?=a94T?Vl)(9; zyx68tCr9QeJqAk@Ig=B{?hg_gtA!V1o9^3gPer(y-oFiSaH^z_2jm}k5&d_dLvaKo zP4T#$1ZVsBROH29r2OVZ#25T5p=j(ndBPc>UJ#_34pMsrl*d(OdFhTLY8vD`H zq@$s?^_m{i{nWaG6la-n0~S1fhx)Yvyc?;`0XmU}F!nRRjzHujUj0PP2_p+0gS5@E z^D#K^bxwuuToSw|ysVM}J9wX6gOMiNUK_d=HTn9Bk}CECN?cXqHXC@6ark0B_Kany z(2mlNa49wY;aFHVI9il_GgS{T(D7)F{M@#;!_P%f%!uLDR81)+^qYRG_MreDH`Eil zCI8mOdNkp96;m-Rz@P6+**^kMTqoAqiJ@FZoVoKn8uIA}E1^JQ|MyK2WFTNz`c|R_ zOp*Y=J7akVkQT*LG4O3~z;8BhnLAiY?xb=3+)|JgcM9dSD7XywqK!NP+wa3S;Q53p zz4WRhJpQoq7i%jv;R+=yIDCU#EzL5MZJZ}wXez+Vw^M*|4*?q^^l;~$O0!+`O=qj* z0&ocA)k89J=)FXYBTudnvd3XQm~y8ZI#Sq6iw*`#_C4qrZi_406c2oyWepS5j-724 zKBldxLL96$W+d=wuQDdvd_rp{x;(IFP)mHszN>kNk|>4LeFM+XVpYh{77xv~F3%p= zJJczu&DK{TA0I&k7KHW;?5)L~LYeS=**&!wZzQ$`yl-7|EHkSHzRc;A|`fw$pzm~yFc05|+@quNsldajkiqkw;&HEKh+ z8T4cWr!r{V;^0+urq8_CxEn|P^02X`%aCR#E=HajUJ6*#8_TYsuPJ3BHDnK&XLetV zaH@22gYWky-}(k_uSHM6I3*&l;w5=m@sct49LLmn$$0!fAxrT$;pH;m(cCiH!3W|8VMUl)C!yPFk1S{3z10E7tS$4kdhdQ=9s*{5TU((VlM zomZNg?gQ(%zpOOB5)bPH*2%^(*mxOdBv>g>WA`N=mDS)4z%?+ZYw(VsD}u@IZ$KD9 zakv24+pN-YGYiC^HA~0EODBLS0vmupc4g^!wCDFzxbp@r0*Hks2w%>&JM$Ck4@iR4 z{QriGR8Rb9@wv0LFs__-Ku_oX&UKJrk?Mo5`iV7-mkZeoC>u)03H~z+R1dQCcrOa5 zmrqvYh}${rFV?!f&_Yra6!_vFzfIsj?ZVH;U=)c7+L^3?Ny@<|$YM-qeCNpu6sY%S zoq()12)zi@PwmShM`Tnz*o!ouS~wt35IVJJ6GDRYJ=sM_(uOqS(u7v%j6vV#wE%)s zK1xTiOIBrH+|yY(S0~?8@*Mr)`t=N!w@CHISGWQ`h@mLN1I(4>&zt4l;yH9s*w3>Q z0nTl;frEBVD_V>FyKUzdc7_mG^&LiVlll1Eg?X@on~PV4zBD%M-(Uouvh=ShM9UxH z_lIHyY@da- z3}Ca_b4=f?V>jtL-;JzZ++HOc<T>)g&l?J`UC}A*;}2}U{urzUzCLk6lUr8*`oo|2+TIK z^rjxcWA&ykc*cOpqG~sEN)fu`Yj}kT_;Odc36y8}Z;c zKb=vK!*w6_w&1qv2e!<_#(od{)j9$<0;Um1-?Z2fE()Yd>}v=R;d7wX8Zy6fkg3(8 z@5oRTthfn(!Kvj|U;!}@^9lNnM-vS85Fmn?dzTqlhmyDG-)74!4Bg|%DLyN)1T;m< zM#X%vTjCK?81Fy*4AAc|ecj1SuTC@Yu!keDXcHO;zLZ=!+fD7~rOsnhSAf>Zxr*)w z&`@n)K2ll|kZ~G5EHDv?~dT|P&1J)4EGjz_lyhMVV(t9>U0h39UN zeme5=S}ZA%>NzixIs^H5eMKHwEjkY)WR>r{WuG`#DmED9TassTo<$Ds1yW1+k9JvH zg+zuiWx+G;i}!1nAMAY)4-yPB%eN2<;yQM_wzsoQzW4&Of> z6BF+nU{VQfwOAMY6y#$EDLbK*G~J=axL4*7$@hK}z!bHt2tP4Di-5G)F{mrSGY%Js zK1KZxxGU;lK)!+$f==h?hwy(vIfzuB_cwA!FEH31u80Nru}^hhrU#w}wE}z8w3Zd} zb8xC->8HG6sy*!A*e^r3!u}Vc^urYeY6B-9j^hmfjQ!*>piEF1%|Mg<(uC8P80;;r zEkKunkSQ4Q{x|(A@**l*y+B%>#8#(`$qJrFM{@8YU=4wah+WKe1Xlns`(a;BnzMj3 z`#IQ@N`4AF?V-|MMCr?}RB5H#zXEF|x4Hc1$fuRiJz)PnPy6>WkPF5G1voXmw0BzL zrLbMlMs2CGT}olQK)tUNOQ~`mqvEl`v;_n^hf;evQ(z~{kv+Lmm}|K;ckvQ<)Umy@ z>^taw+K`Pj#~y@*OXcOVUIlhJBq?HySX)~>kG3}~2figf1TRISkW2&4jCO|Px)dn` z>8YwAgfsd)^Knc@H3sM|HgZaY{3N(6{{qn2D5AP(=z!GrR*=%M{#5)d32ztR+yR|% z!|~cJaKL5fL^uyu$*9NShy*7K*KHEYl-t?ElgDQRA7ae*s0{*ZjL9Hy4sD`H4Jj^~ zql$~Nx!7Vg`uhO!KjXdH(9Y3z4`@-5>Jfic3oHUUMGk?{D5hj>QfehE}*> zFlZq?Tg!cwwTXvz^L}v5H!No(u@*(DANmXXf@2y5m~OGP|II`TX?jgx`oi4y-P!gy zgqeW@N6NU*KUt6Wi^X}8adQy zQ`U1&+}r~l;t-Ubl6;C8ia*~!G1U{yANNPIpsyp(-Gw{PN3bHOSCr}tPXmg+{Q%mZ zCqf=z{ePAO8%S>k&IN;L&@S;&7)wW_GO+6~a!RS_+KTp^f7wTJ{6n|9Bpd~9G$^CI zdCF2xa{Mz0hc3K3n zuoZf$nx4OqP1Xiz^JO_L2lAbeokZg|7<-AV|AFX_RR8s9ju!WS(2BQqKLEDD ziq+ZD50F(s;ibE%UP*L-%#YD_k<`D@tBhwWuc`SUW$?>=n#jhGDZ z|GVYgcm>tWag-W@j>E6w|BxCR|1A6m#xpMtPlr-aQLn`|VJN^tb@*f7Q2-Viidd9- zYgrgRXSJT>+A}B@bxA=-#sM*F-WTxqM0RF@Rg95+aov6iLxx*$-UQTX6X()q7NFZL zcrbLeO3kT+Gb*>ToG-E2I_4IZ=M6^uGlx9xH^U*!vaWz&k zt^oMihzV?8N)puCTR_F+`_6b?59uGNp8J&I2mL`(2IWU~AuCKnG?SZhF;a9pn?lI) z5-$P1YEL)2)%_fZhb(E}Txp;n1@1fGV%?SPfTEIyR-3W9>IbtOh|?hN3uJS_nI`8G zmlS_dIB;a^>p+Oy6A0jsfEufs{$)nR^mq=;58ODI14nemeycwR%!n}N+{ys1~dSKp@Yu9^91qgJcU{515r8EP~u_8N^?@r`D)Lc*Lp`6lbb z;o!kb2zV`W7ta3%9_$CYU-=e2UER3Swh@p7S0G~qY~oYikR9)`?GV_=Ye>gcO^_5l z*?)DI2u)xuui(6cPAHAc{0!ahJo7X3InZdLQP0<|z^MMB8bA<5aSfOO?0I%`dk8=z z73wNl9ojzl;b-a}>YwI)8}>R(T=>7|D@{&D&zjPW%XS`AMEs@9pthjCIeReeUk3B1 z`ITM4@6ux_t<<7T%56MJ+V~UN5S=ZL=a3Y;n(c~fgI5?Ez{3{@hkrjCfxw}pH6oAU z_ht3=sSpI9Vp%;(9SLZvT;BJySr4=<&Be@uR?RT=`#Mu#D-~|Gm*b@zGC!_F034ME zea2q&F56o12>v8bQ)Dfw0!Ceff$wKii6b>|okNQ`qXA_gm`eyB0;&{u>E!a8M55d# zZAN|v`S;`}_*e}zSBKv8ka6pWs`OW+QOFLuC??LH+0H%5V7c)oE`Ih%4^%Ku;T5_o z10+KJh!+9~pJ?Q-O}I|j*hbn2#?}n>jY6y6Ui2az_kKLC8$3#n_whP`?wVNc9qhRN zrRZ=n#BkC8zH1x?bn$iK3GKgN16%dnLl-A@oPkml0O_y=DX4|cH)oL)*hw0Yj#wyX zW;+OaZun02wf`LCc5;bT+K1hVp*uhXYKhmwdziEc^Xba5E69VR?XSVdk?J1sD1-Zq z(00!JiXF<24UW5gdvI7OZB>1kzc`yU^Hpls`6vtkE)W@u}t*&e*p-fYjdKKO6i zdM)`FYlrfag+BN)JBI_l0-F@D?Ep3&`b=S6v{vEm%92p6dW$Kg&yij*LTUr#AKLx6 z{}k$mQMMPmHo$T$=G=(fmC8R^uac9;dGcCvRjPzxVS+Gx$cD5lg1c?6N3E?e4aoBD z{LjqC?uq2D6hc?EVM0g7f6=Uhsv!^3o#G4i<-|>WCjFvqvd@# zE-b>jf$m@x<8sz8A;Km1>S zy>geHvVQh=)?eVW59?E;`V8Vz@nd*eL6$YGAk>!(J)~D5W;$(Sin|j54Kf?41(tpc z_9XEu&;B%@E}3(9;kLd7Bp)m_`pb|LjBa-X84Q2KcnqY0z?N8+Q*(< zSb|Md$HMXG=kS}-FTvkkrRp$L6`eaDuReik7{}q$EXhB-#!ij%7xqj{VXO%sArbC4 zri1Bejk=@5C3Pn(QOE@Lz~0v$>epPDJS|3lax{BF7NK|ZA9*mU4vXL9PNdI*Sqi^t zIGD%jjDzLvf`7n;YVazBf@q}>09O{VDRVPePBOqh;L5R1u6>U`1Ci9BoyhHPF9W#Z zcu*`_;3rXI`?2He(B30^20iS#8^kHUJ-Iy7zexW(Jn!#d?nkP>wSc)AZA{%0oCdaL zQR_{Q%=GlN35maN@^(dKeD4-ee+4Lv?=68mSv*1FmEe9gz%Inw$>SZr zOp~|9myw2XvZA>66&xkd14I;}l*_Fa`vIi1mX8Oz@xWK9VTDq<3|g5rS7NW_El%!` z*FqwNm)!>jKyU!u$9P+lPopra57^iWyhDa4!p{iypjtF+QNFVzD+>+}M2`)HEd^m< zzmW}w&y@`&doeiId0ACK>Wct+9_ksaykadQyE#pOnFyZJ5eMFdrSk2!fDhx5wCFcL z1_G*59^te<+a>P*D&Xd0a2|W{^beQMc|D9471svD>;~UtP~x*T#^Y*$USjDrH)8Wa zqPZ+D!YlaGk1dv@dHfC>(Lah0dolVd2*$1j6vQ9`g2K^-!>F>1niMSdgQ$re40eIz z)RQBmlk(Y#nMj*$2I??kV#+vP>#w2bg44Tl#~Z?1#&_OowPl8Brw`#`h2eQpE% zfa;u2;rErPZ+jk1yj5>Ktj?pDks9>PoU;c1$~q?V;d+D*!2g3X5})3W!w=Gm`e9;D zKgP~$pjmi2Jp}C1Q*~Gus;ddj!a;C+x5rW!jAdCw;nq2YCQyr5kMm4ZK%jk z$A(9A&wP_T>%NRV0}^pe1^js*YL|;l-DkJgeKKJ?QNce770fSUv;7mi>xW}!-uy!U zo%Wx?nh>d8U-@(GUxW79CL4_5m+Cy*n|d1XK%+q8=h~g^^xq#pIodu+njVd&^@e_| zp67P^C=LP!u*NY zrugvoy`NRsAKt#tgcqp1p^c2;~e$N!Rt-ohdJ#?it3p^i_aAvK68EeY?^xh z{{|n$^;mA5_SJd6F4F#QrTtu&6p9~rU@0_({qd4C2;lH`YQ27YbJ-0AH2SQHy3w){ zM5+(q*b-GnT=cbO|ISrkx5L%aw`}67)qCSDYZ={Ol!ehB?WLEcBIb!nC7WjH_WoR%MDadeJiI&>HQ z8|LWS$4b3RQO}zKR>eACq1F=nPFy3TlzPOLufxhkrJgzt)eZY|EaF^~C})vQIXD9N z!nx;Dp7;u`2!fP;8EF{C^%sGj2tl>yVX2E$*T!V^wJLTfOxOr}QK@#LvF?7~EV$So zgKEweHd@Vxv;H<~`3}qzRtckurGG$7#TLo42U63(%82c1wVu1hoPOB@4(&zdkFE7W zt$VnW2GCs~3Z(QNC~g475$EX?^v(yU_hLAe3hcjA2dMrq>Z3UQn|cEz9z$zN3q)$z zAHenh$qCNP?oyh^H%!sOEWBRmr+4RrKl)d4$QjwL`bv$Py|_mfUb#9HAB=yK-9u0r zA*jHD%tK?P_y?2OzLKp^*uduT&-ivS*O3JZ zpId?bPFSQQ+h(FqXia1C3t=d z4LFfQdoeXGG|L-{w@yC7XxhIIPk2>>0dO(R5n?hFZ9-byENg_ra}9p3atb|*LIVPg z+Dry$YRlK?yHA9VG}P4$?JZhc9BR0?ZE>J+@)Yp}CMQ2!R==Vr3L2}=4AsN2jSbk% zJB{6&ze7d`JSWw-xz5;4pLd{fvyC(eK{L=GMQkJ9VJkcuM&thd@Hb;{0*(7`wg;5& zozle&HK6e3UB!))yC8vn>c-2H?TXeGwIp+j*5aW7cwKr*+?7Xz3U2<%_I5rj0Bli} zHE?HmPw4dG-BY^3Zt?oP8=XbB_wNR_`*#}~iZ&(qK34Jm$?c6ji8rL*wR+=;Kqz#4 zaoOH`bBhm7&Nude1ijZE+YH*GV&Y+xd$_F8*i#$W+Y`UpudhJQ-er3qF5AoAHg>>6 zUg&zm<~pPpfd*K+o4-c-=3QP1c-!muhwRO};J7ii?!URAcn`4KHl@RWK>g&-#d|^> zvAwbC%(8~=6@XOVd(E*2rBT8MsoBT|W6$QVU2?$2UrVk)j9o*XQQoL6?q6aw>pQ1! z-l?x@-(joK9NjeaYYdEW?p41d0abZp+gOBc!pliuUdISxZ?Y) zsrCAS6R~bh$=7$41l#NDTQ=|Nu*WzCE=z&Lc1J7Udu91HL}1$=VA4mb+eaAIgsqhF z4Z#um&b##Hp23r+V>2^&rrunj#bTgdvZvl$66~rskK{jnL&0QQbLyC6zBzSVvb{NV zJcb=%ncGGpCL!KN-}R%})hf+R-cE1U2E9(xoARd&!X?v%(97h}BPex^a;7}l(URYV z5F*g*l0CJzx+dFbD^Wiud6WW^&p&y|w)T^|v7~GYb~Vd3=%3%EA3&JS!R%(Vn{{7~ zc_ib8y12`WtSvu4#6+r34`*kM!g>~7wgHP^E{3ejzLFbDLhX|s>`MSKUUFBKF|1%5 z7I=Fz?Wt8iOjjCgJhF~8;*s_0&wJ|6`|8go^=GsCvr+w#CgPE8_{xt*wyQrMsy`p8 zKOd_K@CPky;UBE%tDI39NT1UAg8%P<4WbBZ12q_ktlIEw{=t8Vld;S^oLw2H z))t4V@iLvUKk`)-GW3>`&~c!KzUw#ItFOO?l>(8^wH(19bEn)l&b+yX3qXh1= zv40Qs1owC*?#y9smE=P0Rk^i8_MjcqeI0ef71ifxGoQmRbK#rAIGUff>_Ssx$7+k` zz%0zN%IZdq#7ws>fmw&`1NfYbC#3Z|S&!ksgR-?(X9!}eRThr^Bt|*8Z?%%!CUKt1 zHCxGSo9K#6L`~XHL*qfW>?f%CU>_5AlcKp-=e!Ke%(5+sC$V_5++^mLZ$XjTAsbci zHly#%y4uMKA#1D3TH<7tq}6Iin*7GJKhGoD2njV~L#k_K6{HY@&)K*(a0~ z7BJ>WpKS+~y9AZ(_9Pb~sOF-QJcZ0KLQ3qgCwq|4a*CgbFImJWTrVVHmF_I+u@>V6 zjNFYJgdAkF32aZ^4iIk_ARQ|~{#HCMM>b)v2kXrzPHte-_i&cqgt#4H;5=jOq~wK! zy%I^xdW%`;7^ooq(q83&Z`uEmN5ETYir$9T35`_)%HFy6c&Z?9x6gha?U<$4t+G#S zQ+iqPYVDzSFbwX^ZRJb*65TJa#ByV7j84EHkJ78gK+tX(X%1ow){vZ*k@oRmXb1sp^##^wvG(YwS+T_&dfCKC z|8Yw~UG=FsQ$ht3BU9VG7Y2euhv5O(?_3yp0_XfNGp@5Oy0kfa_Gf@5M z!#~D|GipnR$gk3p+8GOxM8|1-#xneyo#^EtU$({^Jf1HM&X9qDy;_pndlim7V}V=M z0rC1q**ddg9hA{Muk7F0rffs_{th==gF1w|h41e;DRiVcsDr-x2!whYGkD&_8q^6( zWB9(jHj}%C`{&{eCNRK}Nsx{wPxY!CPK*2Yld*OfPrSw|5L!Gpi?tWw`G!ox@btWF zO6h_U;|XG(?80h;-D*riTzOGTe8y7zYzbdst%_vFs3pbApox&rp!?H(?gawBsWXmY~5^0ia zi1EY%*2@n!j}9H@P!a6_{KKPo66V=hOX#R%j)5C--ln+Gq8nKr30Gc;ewoLNZ3%6$ z#vGGt{}CZ=56@t;06VY+k5$yQ*PC*JXHI7{W9Q^?dQ%%HPl)U+NVZ=>21*{igkzWN zYU=V}nEoQ@`Pc0jyAMA1CLa zDVUsPd3tk~>AfC~9!14v-=G^yDg*n?+&RJa;Rn0imKD;%75j5Txn>rWsS&oavE|+% zr5V~aKM>Tu$#|}0@Qo!nEDC89>=eHLuB>2tV}o8*ki?ZRm~)uUp<^)9p^{>-%u&Ne z8f$C=9V52twkVJOGZ4*+S(-QnhrS`;p+tSP?=H@DNGL1a&98*Xls zEDAT{97T>6rQaT>kG0sv0Gb#rU!An*gRFE+xcLYzI!4m+wO9|9P~|&YQ#)wUNs^;! zu^i@HC0|G5BqP{x%4y-|Bef`(U+tmsl5><6ZHv!vbD+&f9J<&JZ+}E(^Ki2eHkr!@0oj5{Ac~I(}tj)L=KN6NyIa`}~ zoD}M<>EoGvtbEPZqBh7irE|FXPHn~q_?b8$y$^U4)w%dTAq#{*n$@Nj6?LsaK@kI@^3R$;5&|Y+ z2??M^Nyu(UAS7$D%O4FIOhDEpnpSM7MVs2#(w1wZMny%98UZb>(WZ)(YU)jU7em`< zsiFtQ!!GYW0ub%-+T`&N9^yI=^P(o1FL{soU+1v6bS;bZNz}q3Q$k*_c>_8m8-MIE^uH_znioaTh=Bm@*@G>Q8lq(b7 z@@;LDM=GeJdLA8K&t=X;Cf@r19|%kPiGwQ$OS@Rd#m2>|Z>!cq8Z%FL8)du5w^iRg z(J$-!JH5{O6Z~jow$h?o+!Pgbzfej|FC=A zm)qQy8aHc*d)(TQCz!ZM*uAY>X%+VcEM!r+5}xtT6LlbT1lzr_(U zCV+9;b=HTvk!WSmFCRWWr!n^gZQR$Um9|j~dR`^o{T?d%Gu8>GbCdRa^`i^-_KyAj z=O=m{6Z(3KwACfOdEA)z%f8+rBldcq5=(lokK5aOlog`x-kJRM_g=-{W4%{Q-rM`Z z^ge!KulGXmP_Hmko`j$A>Ed}vt1OgeD`Tl z?BhfV|9sj#QT?$v_b4V8MuoXjSJ4AoyjXogrl@xRWM(9~M8f`#OiklDy_@WW**irS z__P}>nXB#LTt9QQg>kPeT&d_U=w0X^&;0;?bw9c_lRxu4AR+i(kc6|WV9(;XMi%p$ z#Ji=6u^3Y*HRGV#?bD))AKtst$24K+0mXezUY?O;ySFhN|NchiBZnW+{Aur;?){c; zxGdc0(n~@{sZU9)UhM_ZjSolxn#p{XBGsp2N%glLsBwddo?v-e9TtFO>iCQ#)VBJIg%Rgk9M?&^m9?z`b$Md#l zCT==HrP8yv?m3y3EAB)+?>1%?@vW}+G`*lVE|+B7sekd!&gSOCbFpzx;yJI>mpZic z+QgymVWrn{3v*gn5K(I<)BDdi9yvl3UhVDXjoL3oahH|J{o2M?*YVEueVJlGsxQOh z&E#2A|8m9)W~W2_-~WI~oAL8DW0x#xtRGf)LbW&6cQf6y`+p@;xz}=^UiZ9YsqAo$ zm%`B^(q?NtcEbCB%=Gr@5wosD@53{zdl+(oOpO))E*Xn5c*mm^3xdgzd&7O)8~WwP zaedltO?~ZN%P`M~eRH$LUvDB+XNmt7dGrpibMbmCu=pr#b#!t3Ni>`-+>>k)Ad6Uk-it9DMASz4yfQmlvwqYvaAz4-70>tgf-B zSKC*{soD<=u*&Mw1o)hVPdBS*@__9Fj}Kb9i;-70xDQYM4O+xYwZ?R_LBx5&3R>*d22On77F5-YFe zqz8Waqahe`J(E=In7DAE_pQbCuMb(GuC=Jwc(sCGXjr8GU>J6}zbRIYVWD%V|7Yys z1>@Kty=kL%^I<9xN{J&Zt_fYTDyL!)*`vRZkE|0~V!mYuT#7gnWqY#9uN06<3BsA6?X3OopH;%TT zD->vtUfYdtnmzWA&qDc#Wn&vNj>t65e~V^a)5+ioHu6-E?DWz0yWjb^( z{%_ESQz9$swI6mH;=aYV^)(q@>b{8El0B@@J+$tNA++LcuSpo*{LR*0b`3XcojP|R zXL>q)o3tL4--6M4sZwv|Qs1TuDh;1*lXemn!Kyz@tN4kVzNgn<0@S1MpG&juZ6e=v zlQa{!&-J|^ks9YNeHpDUe|*7&PJ;H%w(9Y)7D>5w;hXyF$*= z%1wBy|CprW3rSY?X&k}4mNzRLVZ$T1@#f2Lt!N@*Z15s(V%40HEEUD8n$G?KSmi9Kv6i=Ax|0#`nL)${{ z-i1rV^lQcRPXeabUKQPR!&Lv;KT9M0*$Pg&Xm5_CPFqrk!o6ONTU;c}%lv5v$c++1@V4%UnO4`~{ zeW`(kIreJj(TzmkYzy0`vlDuU`#b13C$}5n$l|*!y^|gOtF#bT zNQidc)y8WtO`EG#JpRk0b>{6=mocN4nR%aoJuNq|z50;08#l=I>MZOy)$LW5r1hIE z7N{t^$?cy$R(D52{O4~qCY|1R+X&X5Yfm3x*)69mJ?r>9Qt{l{c-yGS?R9sIxXn}A z$PV{0KmCBpTV(xgL#z0X^Ten2CLr>^s0ny#aHRi9`MBZ8J!i?1@ld(ho*;|GXE)k; z)>>g=msj6?Cx`D|rkzsAy~AXs*^-*s`)eiw#^ke+C-MJuncZ@;xAU+(iZ4Ah+026+ zRLy-ET^Py4w_Ary>-ct1a9Bjz12u^aukx{Rt!2XAnVy60)#R@XWY#60V=w+OZ|213GfTCYVYuU8Hb>p zVhLoI6s)|9fJdZQfZ|c&ZeOa^u#61zbL^bAw`lp~Wo7JPNx3}Bq_3o~w*A>`tHph> zky(e_W3lsBT6T2food_T{}rX`^>AG5VEu+3#WSq_&IF~Ghxs|BQgBcf{Epg% zV}ALG9Pi6^?;BXrM>jH>^ELeJf}Q$$Ga~kNm)=NGaOXm41hS?6m4rO+8~$0Mz;me` z*69U(T0iW|IePZn({uU~GhYdhT%HZ}9^+orf3ub~ykn)0bUq>Tzk)u-GVd!(`2I29 znYZ|-nUxy3xJ--?3$&k3J%z}%J2)xdRIB$(Q?Xuye^ar_5{mXXTw;T4$9^`K zGQF%Zm;I@kIfvXAdiV2_E&ikU@qQU7)qlwBi%pH3V8L3YV_wYY(#Hm1!O`9&Qu+%i ze+|9;C??x)ATY3`?`m#&rB2fu+T z&;MwlK7TW}T)d7VFTppW{@4YH-^;k)ThQvw*_pUm?gHxXOi~gXGG$gm)yqtpS)U?H z&bgejkP4uB5}f)_{GamQh)}HRmBQE-Pu%>*9e&nECzdHs(JMdJ7T`-z)Jm zi+$3H30^H7Ud?jqYV_?X<+rA9Ay9(;eN$^Eo-1>^S+F)`_huUnLP9(rReo(f76Vw zm_^}vDJvH@@Xef0^5yLCrg*a~vfKWNR!BQFd*bIO)J=~|-1KLz)o*B1j3=<%7gAaH zDUoq|5r!9RDM1>Jb$R*5Sq!OdGj z5TjEuaA!O#?|AcFxfcYAa8ELICR6weLQZePwG zo>AyP?!{AM_T34o%jA*_I*aJEmu}SAUIHHp9fb zr1zt^4iFKU!z^if&Vg$0VObBN-IV@}yMpWaWm48bd7RwS*?Sc^+h{rCEx)gJbAoRz zx!dJiJ6aE5x`%+tiMUUv7ZCKHNDa3`oOXG6`Ww~z4)4*^DN{S|r<(l-s22Vu+Cp5X z(Q8RG86Ca1U=QY#oVede(pwYkc1piPX5YMzmip;mfxjDx?S}e~61@fcrH`l2^| z_wMt2lXFnMGw65T=M?$ZQPesg)zj{uYwRZMlaBA0cKn3~%C6c_2A#tf@<(5C6F)38 zsc%ciH#wh~m}fNi17-ERBeq1AL$r+(qxag!Pc+f3Ev60d&ahx##tH&Ifkn4e-=l4* z>^z|LO1}DjzM}V}kU=|4DgF&j$+RfX!qiGdRv%bLa69j`2?oaXNmf*GHIof$YZUrvT{4T_Aup?$6l6Nyog7h?c znRRC*>?M;*H|ElZX$cH7xs%o;O=rM#UH1CG=~`||7waE%(HmcVmLJw+L4f4kOcW$X zGT;?mktP1XO0JaEh6Mj2&Ce$M$ZuQ9eTLkbHasF9jBPG+X`EwNt(8KfW_$0b>358F zU)RVyYE2Tm!=Lz`ROp2p>*a6nR4PiGdn{FH`V7y7zQr;~c&!Ws{`>Z6Y3n@;@1EgE zyjB)V0-@}W7W-J~9$9qyjD=b2tK184V-XmMsev~izK~?fQV@+J!N0Ckvg79q$qwqD zzL=_@AkT`NsYheIAonkuu3eZ6UV4*aQi z7Pl61N1$a81Neu?efMkG;*-DVj^^biL#jtM&QJ2?CDG{myyU=SPSK6_X_-qRpPL-q zYBZO@S-S0volChrl%>NV+~mn%LN`X2BV#9>4hP1L`R`(zLMA((%51Fll zj^2;bVGfrKN^Pzqfw3ZXGiftMuiz9*TaIDum9>EbY5udJ}JKw+&h#F!oTufPI*54 zs5C$(RS9yGNx5m`tM4!1SG_*}wN!+Jn_iWRvHvYEuT<7lmsFHHE8UZ7s+7ffbF|NM zs;Zrt#U<{l>h;Pz^TlN;DO2RiqV+Xy=jvrClP7EPvSOFBx~kHN_{y*gi=1wci>p^@ zSF2XLs%pv!HQ;f<8fSGy@p`_dh(daCP1*9Q;%Y}uab@ueCu%8L_<7DshqF4T%Hgc2 z30N?vs?uFuRbel#bXElP(p;{J@{(eAc~zz8X{KO-yS#FReAmLtuP!cG<#fy`UhS+d z4qVJw=awiO>E$&p%^q}ft85w7)m7ED@hKCOd6hNp;))6_Xj^WT+m>17sdU)JPfm#x zl6BP{ms>=WCn%Za70z(|Dc(T0+(=2?T$o1iz@PxLQoK&k06*Ws0Pra+MaFQ!kNm4hcrQYelpym%0~r!O#!8 zChE(iKrmh_zLTZob8KO56?Lw(e1*N(U3Rk9+^X!V7$U7G!hGntxJ*xaG)Xl34NurO zfE4rf%#Ic+UguR(8Ny`b^)eDx=`3+au}7rA%X5Ma*p%&oqA3XqZKhH(np?VaO?ioP zPDOD|%`&5sD^WyLqiC0nwqD_^jwW5;E<+G7gCMkMY~%GxlCg%qEl@%9FJTcExE#f9 zr-Llfh4WmFIc3F_D@>O%q`fY37gsu#ua{0JsGIF9UgL}=m`!7%GWYP6(;U(ym0 zytJr55iSp=cifc@wMJ3Kkr{*iWs>U7k z5xP9LxV$o|eq?zVqsF2#bE1ulS>+CgGn5s<5hbm}UA`u)po5}xCnH@fVV?6=kCU-3 zl*Bw|jnf_U988BkM&(x(o6*jh+O?G=~^ac?$Ewj9O^;$Y*{W2=mk{N;4 zmSNP{{PixU-r`m*%h0RjGJTGqgf5td=NxCH$0V6sUG6e{O{c~!%XXH!Bd<}NL&0fU zdF3n0PEylaLr5{rB0L4gmaxFms;i47xJ9d(KShRTw65R)6Xw&fG2gjP`j|+sxmCGN z%6@rOsOzUPnga-o0H$gemR(Va)ba zWf|+pcCC(z)LymLS-qgNG;DA;e9FAV<90H;=iWn#%D6t)Daqv4#l8OID-k9eO)rZP zue`+WsR(A4F$RW4J|ie&06ghBk?J$Kd6lJd$0f#xU5kiVWcqDMgon_@2p>ik7`HeD zmCPF)lZ}|7$)-e=WmFa~*ZKxAFf{WsrizA_&~=K`D6f-5v#Tkl{Hjdu5T#{>hc~w> zziKwOWG4xXF)Lg0p% z%MdQ^Lv1Bho(hMplH2j+PFqD4iyv~IJ$W+s()^>ba>HsHP?NiNgrl0Ct-EHRJVRRXIo z1nMqd?X(eCmB($XDz(WytSqmP!Lk$+$kXyl8=b#xIl+Z;JrJzuv$Ue$noC$>O9`t< z%d7QTG)0!40`fVAKx(g+2%}z3k$Nd{I-G8@p4wL>d0en)_C(uqjLWH_3XtIvc&WZ< zHYG*M&KO7}&7l<`eR^XXf2Axc@c?XSIf&T=NsL%AB1_FWq0uN(k=!$dmBVCUU8IWC z%}^aL(N{#ox&(>*YhkJ)@!Nfq5uJDXfw*XUQrtWwKUJu4WC~aEXzfrnF2~?_5q^_&Fidw(ACe)s&$HkgDmFg?$ zOO5&};j_H?RrHPiG$K!8+do;WzNenv$x`a(`d3;`ce2RsEM85|Ll+iUdzMvLy>B%&HH3qWNkLj7?VO#4XP)1UD|9nTAU1OGG~)`jk~Xt!xLd(fqnLRmRMza zDi=-pZVY?`r%&x`n`e2>De7`gnk^nkZ!y7$i-`nd3Er<1>P0SRiLAOU(}x1N*U*;6^Q-h>z{tu7TO<6Eerd zqr_+2>dvcKP`QM)i4}oX8qGFCmyD??sI2k0Tr4CxY30?cxyy_aw%&6YzBGFRek5IC zi&Xlqn0ARFA! z2;B_XC^v;0nbDEEHNmx&{4&q#<%`%BlDh=SGuT!v!jduuE|X-lg0kABm9K6qY10onNJo%WToakr zpuC_`w$5vu1L@>DSG!__6Taz^SzcLQQ)af)RIe#2WBoZ$h^F*L)l1V8h+41=qUz;3 z*K$1=YM{I#`g9g}MV{e7&S|iBE88Kag_H2b`ek-!_3H8( z>6z1=mE|NhLT*%(?DEx2s@9b_ol*-UbhK8yxV)x(xpogNkx3d2uX<;s>1dh8GQetG zB~mBQ$>@s;Mz;_Vj-g{OuBPHr*CNBvYI`L&_A>s=c7`fjL^y#VMz#s%aDs$GC&?)k z-QK{qV4A*664+xgm6)!_1yl_!md0z`+I;aOz1%9(CA|)qE(AJk?dERE-rz!Lw789YH^mh_ZhekzOxUBO!4!aDn^u8!LKZL66DkR0W~B9xCc8~~dKaQ+o%COUIO!Ln zdY}ko9ZPmn$uo0r9ab^T0#>)9>zb7odYm3-riTs4=(GLJ4|lcpmbbJTpn6hlYmI$>K`!HA4q5B)?&XxAx1e$uW~gq*@N z9gmZBbYt2~2Ufx^z04K@ww#J?FnGiMll@5lna*k^qnK=DoTA>q;nE5gv#rCO5Npe; z1GBW~VMo&qg&y4x`EttPN7EfFe0}dNq@|Z_c;0Eo`-YpAV2W6dq=T&Vb?Bi#;_?lc}-t zGg2=YXt0fj+ko7&IwIg``E-(=Dd1@O)GO15cJ#6g(-}NG1_#+b(VBRyb{Nt*DZJ2q z7?VCZPZ-qD?KjCe8&;huEngqrLU|q1q3n$Qn2qDr+SJI@2kPgD!*+Iqu?6xX6js@* zE;xbGZH_4q2BquiEqFY|9xc$}83D3)U% z`qGn8)`RJV0@l-jjpl)0+vASZnGj3E%SiKh-2$ zGS0#G!xvA)-*u9Z zpWyzCdmq<{dkyy-?w7b0-1l+!;_7kha9O|kxBH*UgVp5ka@-PJHZBb(aa|2B!`X0O zH?I9p+3@dhL-l(kd9A)h`@tQ?{X1{||CI+HP^Q1d?Z>@viKS<;ooKQf1*r|bFc9!?!Ry!;@-u*iQ9*J3HJ={m$;weeu(=X z?mpbzxGP*NT3k`%tSG(0xz4FnFIU#`U&&gKlcC7r&NbC?oVsR`PGypQO{vz8hbkr7 zc^##qYK5|fC9taM88fQ&EmC$90*8EE#q15+#?{Qgjbx=`*@DFxd3p2FGvxD}1-Y5? z<}S0R;=YW)(k=+lxS-h5r?oH!DHhRY?!`&W}AbyVmxP@jbqy!Z`CcZ$;mk$ z8aJ+2@|Y`5)@l0+J3bn2Xp6@ z@|J<>Vx`(CYpm%W*{%(ElS604725hw4K;|}@)CE@q)Tmz&Bk$fCuGe`4q6l3q>+lg zS63?eCt2&Pmg=O;CX?B#;h=)8Mvk&`l!POs93a-7Z@45_q_#?qV>qiPnF>g+mhP%m z9AT#XR`8trD(8CrlkHpA+NRucWr~93+NQ44hHQrI5~*jS7xt^W7X0tKqxMs?p$EMK zhHjhjS-ubES`0t`n`zx<*wAnawiFJcGc|_X663n0`>0XQJuv@_#SCTeuO;9_};ON_C!9W^E&BwpZjXg z@-O)Ls&V{x>vy~mJ&g?!*V7}uN7`YDkaz6S!*#=!=lj)fzu&Lc{(*XmOXsz>!ZvsS z*Mm#uXJ~fert+&h9k~2%U8nFfK7Y}#R^XC8*E#hVZJ*CAxNJUm;Y7Z?xQ1im`mj1< z#E#W2(wDsicA= zYP;Ei1B1+h0&_A^lv$Iuxi@~oB!x#<-Nozlch}62lJhtx8qX6-*xLNpoS(tCXIx?{ zE+r!a%B!6+ud>PXSIRD^XV|zwvr&IgG0aG_E=t5{D1`^8%_6B?m6xwA<2lS4m%Ksv1-ZKA)S5KC_Sv+H4vy7I-q}`rYP3g1ojk#ak%5W5mcq(Fgj(V!DY;YU*Hl$b zzJ^n+)p^l+&+w-FoWA3{pLn5e3}4Rt3APbh2(prUq@hmzeu}dFxtnA!27r` zNaB?Tjg5N>y~gpdryNuqAiT6n2YdXbHtsJ1Paw)I4!3XU>1Q!x+7~N4{miH2 z+<=BghRbPg-7v{Ac`lQi=^7)6S|&uvD>-&4#dOonrkYct zcP5${(%NN=3fiP!4Lkx|RY?WYA9R-L$EyLQo(!b3oYN1YG?0$oG$zGptijeWU>MkP z^;9AnD4tSz@P7~;X_#W~$(@QwPR$lwbCRMRX^)l*ObsAf{;c4gG@2)Q$x+St2@{QeEihu5y{||+uC^Jj3m(Ba zaPEMc&$W5F>*4b@+)M+JUXaUHh@_gMLHwU%q?w;osXaSmJq?v|?K>Mr^0K^NDC8@=YZ`fv^Y z;jCI@wwY``^aCM;Y!ZX)0F#r=%$ zKR>P}S zTo$~V!aFa@ON?vb;dQ^PDD6c5VVa_J!@oiK*KNE_wR?{Ky${wc(?6U4b_ev+#*Lda z&apyCXM^v>Z zRD+9!jFcrj@IpAY88$^ab>*9d38P1zHbN=o@O*_4SaD&DM2#C)@X!D-?pn66K)JM(}7t|G;afRm~#~tN*(l<`1?n_RnqsN_4 zx4|TSP;d_}d%_8|fom-|V^%ta!J4z(+WWGqPnvv&NrPoR-Rvh~E_<~eQcyP~lNVG) zTq9IU&k?w)7}MY>S4voV(K^ggWGMP(!Z^nj%({5Dp7!7$kCl}>X2=5fxEfs{pytuk zl!8SWdCC<|7Q$HucPTu!EjLl_GPzyR-tod69Fq>-EqLKbC11NdK4slF*A;<3>n12y zxL3Qbn8Yi#idSD=<6M2Y+>H>u9)>JO^D+qrcUcA3AEviWX03i8`4r^2ldsku{M7Y$ zD5aw2nmPKHz+~Rs5VX(VO&Pv+V)5yJeQx21@1NbVdiZ@uSGulxwB+!QA8)!I-+uyq^`{@xc)INU4@XL4q*SF7msmWn|=DbgBtt+!`efIAkq`la% zq3ieO^!EH=^}?sRj_%v^+xo@ZE56pgbCu(^FP0xa^1Ab$1%+`*?^O&dDY-WB%YU4f z(74}LIrA24d3H})(eJ8nUGd0UJ@K>Vc3G}JzUj2LS3NcI(JyyCbydaoCuYC%`t$Fn zez9lQe^wlv;wk(vc zc<#-_M_<_e@a`ew6SfRp_QZRm_a+}6_4wVjRacymUAFWW=M}$v?d7FUH>Dj~Gwjy) zT4o_c!NqdhPE@XD^;{zqOPzHaIlO5(jcM|^k8_S66P{Anxi zy!_hL3E!)5d^@hNZKZ?*jM=sUk%dANK||9h2FGqrl;^qe}j>VWwl-w^pt`ZRd?EZyWXI={*mrBksTCF=gcA4-emvet%-$ z+dodYyX@1r^H01oto-IB%Rm3s3TNG|S67_414Oj z>#u$y>-U$Pb};+gk-z+Ge*D!%w^`C&{aew81s|^1`L}y3C$E38Jag-l#lJeIzI0FX z+g0PP{-`YPfwiL##Lpe|{Ih2b`Q{ZD4=s3c=5w!&AN9f$-?_2vGRw**3xBG<`^w}u zJD>7B{NBX#9{b>?)>j-qxcJkOBRhV)(lhe@)kA(ZY{ZW1u0FkY(~9BMUt6LKy=(qU z4e3Tz*n# zU|bk?!{y^vU(P<#4>p`oXKg&8mgDZmJ&Jn;_c6|P*9mnfZYIuw z`yuW%TtDuD`V;CD+^PzR8t2E! z=YCxLL*ec{uKmR%k2^PhX7hQ9@?<Sw1CL*{}Bd6eR_^ z9#fRp;nA1)?&?>S^A*MBVO1v4_$DKjhP+Hg4Wu8bsa2%J7Ft42$c=}YQlxY3#Y+mSO)vxb~xh> z(gRcBA=nKqq|bgQ>&nmt(hrvhlgMv?1#1n{9lY7Ooh#`2)4sI*aw@TZBxJ64pU(_bU_O<$!3@gyJ0%C zZl=6p3T%LO*aBU!12(}P*a|J<2_Ggy>)rT=DbNA!umQSY3v7ZNupRb5Wefg!zBC0U z!y=dt>!3V$+6)_DJ8Xe{umjq>_=l;`aw+~`GHinBuoXIBCv1S$d+-laVFz@<9@q>m zmk~ZphJ7#{T7CG3DX;E=$WmJ_=hPl9Tq_cY=RB26}G@m*a4M$@efm=g~by)OolF)4x6CtRg*Z`Yg3v7iQuoL#cK4_VOfA;N?VXExk zK^Lrm&2SrRhi%Zx9^WBY1T9w*9-Ig}VK%g~7wCp|xC1uB4%i2ez!df%lco|roCRB< z1NOnKFy(v1BXW317{zT+(?A6F&I_!fLF!e#w z16^{m>4#!6vu| zcEcWMdzg5plYek3Y=(uf4>rJ*9}*9A!2_@f9)X=OX$JY*Ouj)oP^KFD>LG!r}FRM-vkVag-qAGE_A&;|FvW_Sp;!+zKY$Ic?&9}_Q3frYRL*1{&Z z1Gd9Gun!)Bwif)uI+%Pd;lgy-4jr%?HbCp6*bP%*2Xw(6*bFV-BHb_>EwB!Dz-HJ3+o2^5dtfrO{T%-=6*^!MY=Etg^{cH=d6ImS?=WFD`O?OC z4V$3@7CqaqHo>On$Y+s1&$uh{J(TYpzQ4%01?!+2Dlai!$#-}Fx;pyRW3Ut2(n;rQ z%o|`QTnFuYsdumrcEUbr$-tg{*a6$&Qke1v$$8` z5^nog)~#U5dH9ER*bSRtf}M206sVk!e`td)mOb0=C0#up73)x*W-3|Gk+U}63T+#XtJ%x3 z^A7SKcHc?7@||_~V^C=z-6fQlk9q)Gw~`L|e*baR4^y|%UL1t8o&19--zWcI--Cqf zBwa1kGuR2omr^f&f<3V5r{te}{~7rQTYo{lSwZ|yP|mQZ4SQhIZsf4}S@O3G`5xr3 z?*-(r^(FGV96MeopI{TTt;C)KlJ=m|9+ z77b&)ner)Oje3`q7i-qZlvADcgt`N|&N!hSfK6wfP?aM5eT}sSX#M&LHI;I*vVQG? zb*y3grQBHC9z*$9S=;tYzMp$S9V_`f_JrC2UFWmr4T~;dU7UQXvz<^A$RFD`PpGZ1 z{h||Ux8zsy3DruvU95d?C%tuWH*AN8VCu!JkFVxB?0_k(n;(UCSwFADADjy7U_NYx zwXhquz*N@PJE036gH3Qu72(5aun!hND{Js|Fa`zU=M7D78m|tGVFs{(0b_! zwG6u8cGwErMGpPYei`Yz6@PFlOqqB>T?(6FEo_B5U^i@s_DQ4)DM^nk3l;e<3!zlA=mgSK_(!7SJg%b=2aLft9X;UU-u`=K=r``451 z+5B!HY=-M#H{1cObJ&Z4MX(1pLCbCE!DQG9(_u{>(~Q>P3x&&u=TbRYDGQq-cGp* z?;xEGloxB8cGv{nup4fNsdeP1T!-zOu93Sz*lt$7Gi{MV!1oy*k*azELOWf&2{s4Bvl<$#`_Ym)c zv@0LsvVQ1>MQ|IegKe-GcELV4n*Pkn+T%p&-=G`1;11Xdi^!jphp`*h!D-}A^CQG7 zY+-+qe5iYr_CWfZe?ohMO+O{Q^8II&1L?B;oN|JFa4L3o?jjyxEBS@J-H+3bVCNI0 zSH8E=PeAL_)a$Lp4`)F;EQBst3!7mx?1UXqd4~20?Ql#Zc0lD`?0c5_3R9lLKP-ZE zunD%n)aS_$SO<^6PH4N2`1dgWKpQNADXzlMZNyov;=v9fS*0VFzq_4SVGKKFa4ils7DcDf=l;*aX|(u}IiT@4q3pO1ferWwQ?E|L51JDKggm2Q{Z6m*7A+)_kxxtioh#$7YW6=IC{r&^g zhxe(c(DrBQJ8b$3{=dujzf#Vy^K;4>79GRCke|Fw_#W~hs=5@W@+-wVpmn&a9)Qiz zvK_rdRn3AaXQ=9S*qx-RhhX#9Rdw|Dxqg~^JK5428J)h7J8U^{GuJCLpvP%2=>D)ST|c$*TLpY(gEA&Qr=LRM}GYnUQhW!8(arna0l#$ zovemKvj3bX6T2V(E2E}6CP9+5+1bYsp@{%1p8nswEl$jz^Tx- zh-ynynAt*`=i!mY3m?t;o<>OZu?BQOPy-br|HA}oU0untzh zX1Eph!8Vw>g!UoVq2*_!8%~6_r7Gux2nW`}R=88X-$1>FebD-I{M|_Tz?7R*)d7nN zsW-5W-zq-{n{FZ8Ul1-#fwpC;YKKj*R<6UH&{{-(iyZdBKA5tL^cABIZO{c%VG}HZ zt*{Pu!cKS$D*TrC*#E#Tm<@|ch)2G|7T5|qU^nzb#X-G%482nHVI5pb{x`vOuo>>) zdOO?$tt%)W=z^ACq7RdyQigx|4r}FmIpqVJU>CHmq#i*#w6$U{EQHD`>OZW5tiG^gHc(&T^H6z8QPyoz)gt({&7=pO4-Y^$JPPlGNlz=v z18^$*G0caLK{tFBZiBtB1AYd3VBFp0-!qEx3Y-Y{!ED&Sg?0*m>ZM$E)9mh{{9&Sx z_~B*n5ZndFKC38)U^={bEBOPjhuh#g@DQBeNclXcC=bFc_z|ptzI!QGIPE^l2hM{> z;ff~e-Sd3^HvJjg3wOae-=SW@+4qyqJ&JME#0MXQ2jE_4c}Y=r{E&3RM_~ng2X2Q+Q~~)HcUztkSDO%b?r4i;OC0ThYh!VH z(pk3~$%oSuGEW~pKXH`XvQD|~oSBzSN&cqDf?v(el?Bcyf%@`eq1{`_6VKo zk-E;jQMs?Cy@ob&v3U$}ccZ^1Lf>KN&mBcygv^58v>W=>r=exdkBs=|o;DPFZ<6#~ zAF}p({D>`XbUSYBS2H8RUS))xH7Yx3i|DtY-*bxkHuSs1mYe$3iz33mSx>4~uE)@^ zqH~t$WE*9o<(6*am?64+enc3B!Sok}*_efX3gMlq{yOySUqOE-`mV2_e-Qnqub`h0 zPapUd^rxZU`4#lb(C_;S`rFaB7M^;3?ngi6E9f6X-+qevR_efb8pcZWrG3ahX(O}v zQpmOKav{*JX?Gr@j$~5brH^o+*M(lO=mqN9kZft1n!Evd^3DC~*=BjVCRS`*Ycb>( ziQE*AxjyelCxtMg)n~E6Z^%c4g`vkG@`R!EdH4sWI70IA2%6@z$071S8jSWL{SOX=hIen#$v~O|S zbYj^t3;8bOvGSqNkdHUp;RvOp7Wtk5{O=ezWHLq1S@bD-lOjAZnKZL%m-4;qlWkxwzpwT?mW7g~^SLmn1KS;&6}@)qRhnf>1o zlJ^WEw=lmG|61P}=)3Yl{*wohrw<}`81h)@Ye3#Hfc-6oJeGYOgUEXf`T6GjxiOSJ z3**#4@h2PdNoM~mL;ll|cVU0Dep~9O1Nl+pvFcz0a?7&V@)qPt$Ya&yV zFE^CFbVDA?eh2clfzoftW2LXfkjLtyJCJt}ek^$p@~#2$&yuLiW6ejB4Y@Wy4fK!N zWJ2$s(+znn`yGZnR{k^~?-?L}S`2wC{~gGW;y;$W2f3vvcK=~vf4V4}gUA~Ok+%#Y?-)ehGl<;6BH)1O zA4Hx$h}>bwZRYYd?u})B)L_V?%`arm+=Bcl+L{q;wk8LpqG9MdPmSJL~pQsN%{u;=_%;VLT~FS#Opw>~GZMXv?D z!TOW24A{F)K`$M>HuR>L+nZMJZwagS73dv6FW0Q6^($+`^tPdQ6us1w^vc8Z_MkV~ z(XUQ7>uK>i!}NO4OFjj?(R4hsPC;)fdikfISBPE(dV{5-0lkJ(2yYj9JJ1^_pQRt| zLaz-yn!Bn0*5?z_KOQyY1BD}cW4R$XKsa;F;b{3=6PCZ}=p8);`zz2J?Hs(kwxO4d z-eC6aL2nj%gVm=V^c;i4EBQ8>KedtZn%1EvBHw{LR=#E%^1Z>@}wCP1~of@{2ta(HmRJa|$QxEePm| zJ^AQ4&=Wtw`GaY_&yC!TJeob?f14qX=3lP0A#cF{K;?J&)|`VBeF zAtX1g{0Q<`{>NUxd}aXoEaanCM9&{7r$XdokuNo;FITHq>E`;zPyUs-I_SK^N)Pe$%W9xI>Hkv9w=cOc(3fV=^D%K-8g z0zXN&K0RDTB_aKjze-QBc2a!GTKASYeIx8Srm#h~1Kp|BJkMz1OGNry5xRZo?qAcdUKSUwyJ&NKxk*)#aL0~gd|J!% zpnNumOZx5z>ZXsGx2+ju7PWE*Y{ zs%DHTeRc0?mbBMSw}{_n$B zsFQx$(0QBV=g^#jc`$oaZJ<2F&v^Xw;OA*RTPjSp%&8x$%?7q}U?wmjz!vG#w&TZj zSHH^ErC~c~%8c_Ssa&c>F7NVi4k64-17V_Lgc%@ z^;JGwMhC*+Y~H;3p#_^QnaqC+LisvJ%h#j$8NZ1TDoBRaQ|D4HG!?r^F$h$h0QP(U_pX?|8>hSbQdYbUFhxcF{k$8S!@V4wJXY!M+oj1hWkhepAt{)|JaVi~o7w@xphR?x%f%A;^%@*`m zhSbya^NbGk9lX!tuvwq;f!fmDkewlY4hUk7vJL%Y-e*x2p-){W3HD%37hBrVEkpNe z><`*P*jl~%z?82X#*(o6&|k+pFG?fA)@{iO3wtaLVb%|L9^0&&%^^%JJ8uZtJ$sZg z4V`TCw-WY`&H8~dmcxyqI$o-O(ffPxyG0t^cly=M(fsCz`Q_lD1f=_wJdpRP0pOs)KmqTd!w~Ee6P=^zG@x@)gihc*owTJx=rp0Th0m71Gdcvu)j)YxnCv&|c{YVH`o(^=+*}s} z`sO?`^lQ=2eu;4^n*M{~;Y**m3;nIwlxenm$ZVNIX#H6e@;%5Omp(B+ip{r~!pzaz zrgAywf7)4VF^_46&G84!eN39({}IQShnVY1zjUrC4x`P*zialBq4{wTN79c@9%C17 zjxVLI>C>d_Q6=UvV>^E29VEmM%6sNN_*oJ3bA7m<1NhnX75qq^DwCM+;fJLFBOb=H zC0dqhsPOglAl8YX%oBVjWYKzu}{ogZ&AKtDTEW3HJ{iNgPAb$RVotBv=`B_OkZgV`6hi&+2BRxM4=Amic zcaFLL$r`o6$PUTUEHY8%07vnk{OgE&ia`DuBeS${=^tz?=9ZzG#OGjojI-G?e@`{! zSDEDtwfnmCQN|jq=#`;YM>uI_J^C~59c~D8ff8R6dOOhzTN^dv6M5?(^3FlzeTJN^ z&y&(4;ajiNU(90CE@dbur{NqHIDg`5l%|jNi8#V|*$) z>(JST&i7=TJEuC7j=+3mzNrn&9Tk6iph_6+UHYYCgwgk=dERKMLrTDd)PmXC7&d+? zp5EeqggArsAj{}q;@6rzFau)Vh%3a;p||Omg7uWXf3D$Y$N`g)nWL^Z)l;UETDvX6 z|DNCWt8Ym<3vLa?8>p+lHw8hTBz3zJKV|Pkjvw0n*(%zRKGqt~8TCu}=&rz@o+iqA z?&kOnBll`0o;fOqPm*b~M@ij~_owxvPj_eNlV?WVkbWi``4Qw%#_Z7A!o1L!E#**$ zpJ}|yX;CoD|Bt(WkB_RjAOG>$%gJp61VyDt>srxji!mr7R@w$gLbw_sBBC~gWFf(j z#3UfJw2gv*ii(Pgf{F@?ii(Pe_jp6B*itWOl~$}bs#viqrAm_T^EKzpIkTI9^!@w% z_1ni|cF*g)F7uk#yyi8pnR8ieM1Kd*P@IwUoXuM3tDu)>eEfbe`N~ChH@GoL-tE?t zcSDWL#)c=?2R!)7M12cI5M9jk8a>!(>;F;b&tr&<`+N9uTj!#=(Ngv=h8P=z6Przf zb{4Ya*ne)qdbXq4!;8Q8?VLHoq3MKeH2COn{&#(@o`x4Jp9ju-^|VEYvMdGgDtr{IX85Elw=@z zXF$f9=##-BY|EC1%#Tij)Vp`LG=!y)tX#P`APnu`@(p zsZQ)L37!q`JnZX8yCmsy_lm4%IY;VwW-;`|pQg-zx=oXP)dt5#nC9uR@d7-R@Q~UE zwjQf*L=y*!?JDTXE57AnzhPP@fi_{_s@(4?N;8Rq!l^=UO{|+Rr#x3cdRBe;Wsz;pq*} z_l<+Eq3Z+P;Z))Kh&2v+FwqMBK*m8nv`e8q&~Z=?{T}G0c|lxs$6%aOi^2E&_uh84 zG6FpF>r`*9m-sbH^n>Ot$qOe}1$2HsdbGXp)N66!TMOUjuX*NA){ZTm@s)Sr)A1j^ z7yh%ioyf1Exz#~^?&6VsWl1glrJ&A3C;W=FF7M1650BqYlehACw+Ue48}c62mC)|C zY2AI+Gj&Y%g}c{;W8OL?7DlvIEZoi^t6Iv+br2 zjm44OJD-@?n(~Y!`SAn^sTx zXs?Xw$osbL#d;oD4o`DB?+B#6XtTu=j5+H%#o!p^Y71X$&}$L%MYO`=F*Z8E&TEQe zkxvaQ266N49)t03>Xm2qqvJZt2=B7iEX>DJZ!tVCtnunSp(9V^0P0r|t0p~%2J6P~-5q)Q3}HUv z9g%W3E^xv)YxSqwws7C$B5-u#~#aH$3Qwe`%jAO|D9K@`jQ><+Qfn zCblTCc#MDj&iIpS4Cy0z2k|C!`<7$h-fnE*@`nBLj3T|iwgvj7yo+-hb#&;{KU@7X zG!~xjf#SWg!6vqUL-=`T?sJ*w*fJ%Mp=0YXZ2z)jNzt|!J>^}QQfeerMIgJdHV|Z7YKq=8n&LcsBQHZNE^aeve&n^Uki_KFGK&eMbF?I1<4xdm!I6)ehFhUl|FK!-6w-%k*|#H z+_@=it^v59UN`MU-ZtLTEJM+kr|)mBk&Ht>S0j4%DW*+~)dL;dJ)v*nJ;1x*jmq7! zW}jp~V|x@lE6_!c?az{V4s>iUM#f&=H?7C^6P65P(@w^=yc2x~@1)ja`}$6JIvLx0 z;90_ZtM%Bv$m01Q#`d7$#LEJ2Y@cJvFuESV*ltF~oRQwxF12L%zMed`^XZRu@N62@ z+J1bLzB$$KFt)vVBj*^ukziIF3twUlGAyJHg1X=I3z7vEFwC?d4tB z{bj5lWbv4K{Y`4AmtBi`tKPy`_;m|3`@_x1oKx!Q@l{3OXMX#W_0a8yX9Dl&)?AOzGdeunsZ^qDpj`gKNKmPySSl@xXwPoKw)^i9nRgB#O z8S5;wd4D?BuXxw@s~mS6=hnK23#1c+xXBK@8#fE2KJ>aw=E=E}0~scdYPS8+%>!n^ z^Fn!R`zsmn{Kn!jzEo!O;KOq)=OOlr4?l?vdFOgYCNf$q8D>rK3p;-+h~>kx3!c7> zt?fh7;Q4{+clMA>z3XhA!Le|2*7HLphxTHw)Z2eF>sRdcCdbjQlj|kvspfj$h#)U; z*A!LoL}z<8dd=e5kByeYGwHXj?FrHKWsAq?I?c8b18jk1Ba#QvbvrT^@m~4MM8*f5 z$cWqR9j0y6V+`?hL2LU{4m>?OvC*YA4>r0Z*+zY-cL_2ouV`(r<~Z;vy|x`jUO3cW z4ucjw7ec=h`i&e%H&}Xd4^XMMt?Bd7|GlBx1J4%xT>Q|l!@4fflZ~nt@Z#e>-nuR! zdJckS8#J?R8kwx-N6%gmkvlnqJprk+M(BAT`4K|j$+d??`@#2tWexb9)F*kmuakSd zz`q6{bZgLnrO*Q-VC|y_aLZUeAyI;JJ-NZCMORJ4>PO zkB=W@(~l7f7vJRJ54Q2A2lyo(zKf0b`bP9#2fh#T^K86(4`!L&zHQL;{T{kwkr6$^ z)t8?R?F$bJmcdfD{C7tcGLNxoPuF|RV`7Ce(A_ppfUX|8Lv6aTK^tdz_@e}Ge8Fm? z{3l2={Gy+4^NHU5(!+v!TA*79-M(zS-NScg>$u1s>+&bHhdrK&?j-UoxjPA8xoK*U85A<7* z$JTd1>)u~=t|1jV`EQjS2SAq%oqC-A*5)UAx>Y~d-G<1PfXJfshi)KrL@5-jVH!c zczdlfzCMJeCp2YQrT8LS^}3+gP=*XB3Dlh1#Q1bf=#quzaN;vYLa{4Z^tXzLW>m(G0Zsh#P8Q%C2no4Nq?T4lSnuX9T zhGqrFeqWJ`=xg+0dE&t{aZ#+qO{0c#w|`-*R4+y4*uA%B3vza(>aFhso9SQrkT}gH zO|=)=?5A6k-*GBym<16sXzQA$sYV_!fKU2(;CSo6M2j8s|{t2Ah06qu&4jVs8-{%pQ8+hHpUJz@-Snd|k$k>_w@d#~1_xv#4 z{OXY)OLXsX7Wo9SPqby%2L9V0{0rc7ZTvJBFTPU>{tfVhZG1v*w$PUa{r6SOfo|{j z(1|`Pq3gr{=5$t{jF*Mr`-2}U<7MQ;z~1gY;RVUp5Zs*dNq9pJuXOq;EZSlDEG@_e4H{sVK z?Og&-pXXas-gg(+e;xS#;C~9OulJO|{%?RU06*QvyU+7ZFk9NvPkW(T1l=f`PS$}7 zBC|v#>8LokK3p7J2i=i29dqQF)*LDSN!0?4#2R0x%0TBT@LRxV+j!64g=eA1FY8j5 zpLK=kqF<9NPg8j&^6nMi0DZ}et=4_J#5?cVUFoak9{wSYqmR*0zkj{=E}s*KH1R;X zXB#q`;0bgvao*CQAU4fj%Jql57~c5C)^;-fpe~t9y!cuiJ1^^beJy@iY`7O`r4O3n zn*d*uZ=a=~2jljuz<#Ttn*?2F@n8^g7J)AT|10sc_izpKYhObDfRP41Do;{mdli#!K<~aUyRdMLvhAz&3Yo*S2=AJ1TXM3R;1Wi)j z@bkcT)_1}`&*Se5FTS-B zd?oz96Zs}r9@FEm9e;&7=C1|)U8*>)He9mz(?11%nJ$ z-&fwW82lb|?hG$FH-X;){$`08g(T<354^pg@EU7D&UFK^=ZEl=^8b3jJE7YP9ox4_blihpY3QWB9_9GqtF4{B3tZOY{lWJDUu()6h!`Oi7SYW4+IRhFH8=J zjj=KEH=f*o!(6kqwf(Rt$2W8)J6TohI_HoW&)XQildgcW!7p~0gzV+-w6bT88O0;!fo4e6O`V6WP8^y*Msy*#dqW_*0}UN%a{! z9cWw113lPFmA3RHF>3jswf#$J%hXQWk}N#APul{4gJU9Z4)W^%$$zP)A@7z><)zr> z)<8rjw#ld@U-+VP+sGWZllpSNzaX|rs!#8Cj;1eqT74mxW7WBoKFD4D6}hwc-ddxl zLd z!Uc(2U--U;r(kz$`znroKQQ#;toX^j3PLac*I7v&V)v;0iLV)t?wmBs(~yQ>PwRFIh6o{{0W^{rkbOf$(jH zXV8CIli$a{_1wA6g!xhHNp7x)S?u|0vuzvqZcfJGiCGrC-8kHfzf{yp&jiesOj z`@Czd{TBIu+8*Dr9!{ZY@Mt84?|~*Cnn^Z|yLZp>Z;l^a`+)B=m3bFhS{T&n#_&2b zZ{&d*1>G9{zxD4noxXoqo+xo|kLI?UOU)%A;VFP;LcFd0M`HJ7r`z&nABI(Hc#$3A zq@UNpQ*dNk^7G`zhIN(=sjSMis7{K+mv_Ot2VRFh^X(U``L7M?8m{l7`w;p~*!w5a z$46QE89zMA_QL`lXG^P?ulIJo9uRvrfqw)1V2*tqQq~n>n@P~^g-+M~*D(RDsr!d^ z-6M3}Tj1H#*4p0PmOb3f6-4Gb4M%$A27>F7A73~|{J->|ei7n8`81dWb{l|j%?6Kfm zz!%$i*Js%ec5}>pa6O>g0o`_)@A_K$8Ji8U>|7X&EHmyVW+Gpg7`X%)>lmYNV<%r1 zcQ1&L5FQn@52HUA7|Go8wG{r+quScP6&>EACsX<@(!*3L9p~+Tz>|}~f2ayiOD8<% zC11CdoIus!AF;Ofm!&@+uz1Y<7ZJy<$iG)=AbjhN@%&(c#pjL@>BIR!8%OK8Z8bcL zfAW8ec^|@CaO{D_ynLGVHuO!|{BNw-BHhwY@1t|i+@$0_yvCTub#>i`6Q(nMj>G5d zJ~TdH^OLn+YKt z@2$Nw`9E;M|Io%;@BNei3Evl9#)ABRxZsD_{O-OfdrV}nLbvz*@7(u-nSBv2 z-xj?5@Ayt^bhyYdckj z4SQ_n|FEP@(F>R(pjl3qmKByFYoFe~AU)i@U`MtZy)UQ-zK9MmZ|5@J*%@~gT zexQGO|CK*q$QWpbZZ&i#37r`O)^&pw;5UKK7QFG3Vu{=Cyww7J!+!AFJ^B0MR}J_J z{AbwphuwFoh;8EF-v+l9)(NUfjr7?bqh+QJa2p z`HL4s$^-U-SfkGjpZNSdct3=90>^&4xSs{Hg$s<)JleI;_B_$+FH?_u?@Kt}qK!kp z4cbxA9?!8a7kim!sf0!~;j7Rj?F~X>t`kUK?LbZwG=*Z*MTLPZ&!)i(2E;GjoVGV| z7oX(y!}%7E*o1VC{=FeEO0k~f7r~Q#^8d|-o8T>hce1o8#V%)9b`g7j4eb(Wwa=%} zrrI!0g1rga{n@Ypnm3@?pAGv$vkRKhV#8SlfsURH%PhZ?_jHKeC&80_3jgOWetDL~ z0Z--Nw)RV@GpQb5x8ztQakDoU6 z2CE)77V0G4jfR8uJINM8zxJlK_RHY)+u_EKbCco+?GX7JpwC&>)_zT=^wtu{Yxf#Y zAN@YPlP!J7DfRP8zq8w25R<;#4$scQw)SaRw7bOOG50h@UQAE6u)Fzth44%|tJC&N{M9eg*Z&a=t@QmI=v$z_Ba=EV>R3l)aGF&~ zk#5gUcm|cXwO<0iZ(}#k2CqRajPay|cRvWpcs`^%;9COUzok9TbgV0Ui&fR|q=m2E z2OWisDiXMo>bCY4eATbp#LtvH6n5G5Qe2i3EDzWfv+p8y=d3x%Yneu#7e%K|{Mdir zqquQVEOLhFUJ>f;YwktH^4d22{zqRY*XP9MH~3RKDvLk#Wm98NT}mIh_LHl4t~(cW zwBNDtErIVzvERV|oBdWJBj>`l_D!AH@27T1DU_=e-)p}ok+*nOTl-xRbn4%UPUTjg zV!x|x`*~w<&~M2{e%sdmIJWWa=dRJ%LkwS+YCn1P=b|}n?N=nx>v?{k_A7z53ce5F zs}cLH9TL=K;@q8&%{q85VJ#;sdg0_8j(hFKKK4 zSnPRqM;#+AwoJVGC99J>doDso?@Qa-pR(-}>`gAU?WyBG^lPC1T^e-`v+86oNXN9f z(Imr2oY@7>tn1tKeVTrsk?(|uKq}209vk+2k(kQO_2a)IKZpJlTPNr*uyW17?JoH(BN)pXiO8`0vRlmbO{<@dfWZ5_~@RjQ!vzf!{-Y zOt(QBtUZ8c@H@aCDtNR0@$izXt?=+?3Es@_j4^%hKttdWanPHg?Ts!+*|fCZyw_4_ zc0qG2G`~!tG5N00^!Nk&MbHfLX}Dg6oF>nXa(*B*lc3q{(^%J>uD0yRa$%?kngJ+w zn+1RT#?I{;2fq}24)`D1^3mZet1q8~CL5Zcr_fCGT)7}t;8Eij(Cmc1H}uPG`T`j# z@*L>mU`_@fr}S0@YQF0yHAEq%5?vjZAdaY;1ce3vNB>93pVV{$F=FI$cod(uBWFTw`U?8|Ql zg3kd@`eDhC0OHzi0(b@fm?Zq%2rsYIL~+i~fhHT8efg`{eFZcRznJ(3O$NulT<^X`(JvqT zQt*Rqyj!n-k60XB6?858sZ0EG5j0Oi6SUPGcV~P4TpXL`-=i%upM-uV^fDLty5XNt z`8M7T%^qm>6~70<8l8(jkV``v$T4#(TdjUFQ4}k(2Z{JkKD<@%W``_ZeJ_7_o#qrx zh^5lL8fZr?XPqCmXiW~-&m+t?wh!V|?|G~T!Ef{N#5g~{vDO$|XXLV@*%FcEtJd#a`1is;%;pad z)sw5(ZVvdq>?KaJ@oxS}{`7l4xQp#pLpurDKX#-oB-gSosJrhOeH(hUqOJYlD8FXj zFt$#~7sKZL>!O+0S3NIb{c{I<({{i5>z-~Q+Ydy)V(7Q5WFIey-dpe7?fH;&9T#cD zwzEY3D))MOs(w6jTxc%EF?}Sbv+(w&Y=D2oUEbcgY2R7ev?>n%Z4W4$lCPUzmluo#|Acc<)M_m+O1%3S#;JP;v_B z`a`z?y1g7n4|>M?QcdCMo+le7#wLhj4*Ez5Y2_8q$rd28B|?{%&;_rkh zcY)S#uXpc+@b?AZ7x_u^jU|5+_}<_TviYs&K5IPuAvXSuU_M*q;rCVl8t~csk-yo) zcP3wac&CRSX4lX42HyS1eLU`UOQGv=IpdUizK?DYbmu}h&X&iYV0iZr`Oo=OLbn9E zq&%HHT&k|H>s~iv@K~#>o*s+qpnCzjq`XJd@#vyQcPuitLAM#YqdQRl(C4f2in@N_Uj(r#lMHH)`|{8VxxoL;9kEdfVUFfB|b0y?A{OCY~A>z zuXWTz`!=*IJJSB%r}bjaa%j(8+os=h=KCY--|!hwiraYmST8{L0(8eP1}!>oU6Zf| zU|}pDlCOpSLH5pUdiVLDbA26(xeeCbsKsOI?v1??=LYM0f(EjQv*Mw)_B2}t`2mjz zhNt*K3N&pcwDTTrv+f@&Ht)b3xgetZR`-L9vBl7?hF1E-Uk_KiV?_FNE%;5~6M{D} z-Mt>btwMj0{@1c}|3jO-&b=lb(CX_icV{lvjdfNl$V9%Iun zcbN5GU(U~gW*aou+cf*Qwj=awpda-}Tl>SE(uXf5{qlOhP+yDPCi0>0Z_~SLGyfg~ zv1xQMV*OYjH?ncDOxRTZrab&DPM)ro3oR@gOpKs~`B0j$bnhno<*M1|%zRw%~ zyDErW((b*`?tQc^`Q6l3yL%H11%J9NOLAxuPpL4@`Fv=OMW=~Ajk{(Ik9BFJo=Rvc zp~?1X@R?!mm=>R!2fh^iEE_NNNa%9Mie5jifo=_S7ut0GdMSLS-~HglU$#NNH&t#x zKRWQ2A=+QExtKKSv6Of#di>VYgO#1=+aJ1h&^2@H+gRx2-c!++xEu#{E_B(Cr{s*# z)w@(WXK#k)SZLUm^kgv}{k+?L3E@zAZqP(zE&oY)Yv4W3=f$qb|Mm0k!%$*_?a<7E zhD+FiuKpS}JSx>@IoA?jq5p?XKia=$ePv)X_xaW+^b4PG_g$j5QKRwwk?^?h0xk}C z+-rRU;rS4r`=}#2+v0J@rv5WCH;TLWRIG%)^2wAvTlc-h|27LC@%_!vcjK`4i zmSf4#|HDwi`y6i!S#6?`;VX0_2IpoEL6XJ|)q=s5YY-IerJi#wEMP=MtQNAqqPj^; zZarRYYrnvEO#-k1Kc z9eaaP4Udu#Xy|QH8mx+LvF9%ogP5Y-vk=w$ha^oBCA2NTC1lSGS5`Mh;i7 zd`a$}Qub1%%8=Dr?j^CHFZdDQ$J=cw*8j0kEW#x8%h)Z2Zq`2J2)+q?1^A>~!Fo5& z67Xk(?`qd$<#_AB58IFYH^85`54_9?UxWW4_!DjUjPtn>26l<=#8HyzKM!8??L#tg z#6IK+z5smIKJa3U{ zfWNr+=k2qu>3E}FB1qa9J5!HJH#mrBUvdHRs*raB^6ui;mseo)E^SVCgXnk$yX&)^ z$e94^TIB3TPGC#M)0n^lrFt}-?rU{$Bv-}U_%$t8)upuFS5fCn*~^qV=QS@MH1qfv z!!jf{htcP4<>@`cLC_C_zS(Y5ac;KsET%t02P%diO(AYE0R%%=&%txxUkHDm&)@kR zyb`*_(Cu#y7C+kz-9yj?ds@UfohSHzPp|hNzlQDs=-3_z`eK}DeTMEr*IcLPs?&3$ zLv$F%Sx|qfaaP!*PX{em>fgv|vgPP}gYf0fn}i+0`#Bo)XOUt{P8{BO$obLh_WIb( zi>nT*cdb+{d?cJm`Njx$PTm)-y)JC(+Nn7qk@oXz=n(m#-^&RH4P( z+-RZBDDVgzBs|=g?A~Lu7~T`!Ovyjpy%cwvb8`=2)i(u6t@%{53BJF=_dAaLIyK+f zx=&#nA#*l!jm$V>bhFM1Di;~qwe<%i}n05#vGLC)=~+kr*^U=3BkS#6ainZ(<#YBaGzpP331By^2%XHi))muTW~rdu`VLs4@;sPK^%8CBGSO z4!DwJtmCdXN5Q`i{$9xP`=n6E5P$63@pBIJw?KcgOT*vPS@?+%t}}2 z4l^BppM?Kf_%F5jjlOQs-LJlT;oo+E`bxa$dz(@lp_f?Ww~rV^XWPo+(NwG7b@RNA zla=s24&PRr&(pKYSo8O~i(srYXZYiUH`Y%kS{DN(15&OxZk8V>BIzxYFB|diDPA z+-C*~xH3L5#|h6+L%T(0G^ORFg=fslNe|DM6J8AJSq%IG;;(n0FZ;A75Sk*hb!|IBV^L$u+>>&>kDd&m8SBCCN zdptuulHqd2PhujwD&*W9QENiZ%Mt$H;&5(g2+QGP5jJ5(g%hD2TglVa?Vh+3uybXax+CIn{7A%Ek)}R#+`3Ne$8WLo$23)Y4ySj9 zmWBS4rj|sU9ck*Bh{N$45$8{7>RFTW07N@JbL(VN3YGcT`DMP&x zI^z9w^>D=D{L>L3*%K+`%)Qc|s(sn+~$;|)%sCOuKqI_>m(vP7f%v(%#@ zXMLu6GgN$a7xh$HZ_YfI?r{8my7PXv+Lj45oiXk=7wkGn?Fl(6d#D$~+oJ#vr8|#z zRdX{Oj<3sb{?k>xu8%*;aQ@Lvy`Fh0=Won%Ug)BBWu3_J12N~R?rLfFPdNUriz_y# zp5L27&K-{WXJ|8f5Yq2MICrM=ZAh&M)#)?ceo?5YJ_xB@UO#kpYS6E=PrV&dA9++q z9E+$t=i;ckJTz9R4?@m+5%opnEMi4e4yi5v3rNN}&p4`9`Veni=BOt^&YMxSAiTlV z=&8^&=aPfe7b5k)A?K^^>ay_BNYnOv)N`o%Pt@6RsJhm1HXo`Ub)1!ls!yH1cORneO>_Qska{W2x#nQ?Wt!7^kXo7k z!;J^4kJ25mH)J~Zc2N&!I(KzZZ)G}nbWvYqI&WsHd$I)kW|s3_7xk|!=kl&GEH~3a!jI*7=nhf%+WBPIxeMe^|naYwn-%n}5o!A!++Q z&RiW5qF;1>B&yCjM5)=`Uv$*9A&wpib${4Vf0n~9L)~w42n!tE7w&$Qqh651kHg(t zqpDR7Z;f>SEUMN=ID9+O{jX6vg2St$-Cv5TRpQvs$=4h5^|5^Ik*~{S5HFXn`{k=e zzFw0r8giSb)t5%AYtwwKE=u#Y`XbQkZ;pCNRQYGP`zwxWmiljxbbrht=5Y9Kr2Act z`nMb|iFUuvQTIkUd^OsAuA|-;W!mIxvDALMe65qOjq>%je0?fkd*$m&8JjEQ3oWxx zaz?Auob%KK7tSpD$?tJT7bvQ5=EVq(PIF8>8*=t$slSDsKQT1Ja{groaZG&_b}o;h zr=0m?#90$lUq&4M1L2CO)10O5^#!+CW&%RIf&y zzh|npNTe;3XT>A`$W%{9<@g5DPk@V1O>CUbUb#(?OzLhUG(7CZLHsOiTpTg?u z2;_ zMLiUe<4qCgk6l!|KE5vMT-Q~-OazOm_oB`pyNd5~e5d1F*G;{pk3V;uKXy~Mq{;bp zY0h;y>LY#pU7GX99Cd%Xoc}8Guky7#iJ{bG*`ngIABGMYh6xsj zoQ4I}K&5obY^F)sDDhfY1dfw3HNZtKb{`x~WRi8$|cp~K!J z_`jTSPiR#ab$u434`(@#cTu;+K9e(#bosevKBRx|9bw*V{z_QJFNf5u5od{`>$suMjOz_~4`Y9XNe=NZlvRp6k^(_}=hG^#4tcb5A+}s-C!+=J3pk&S+jv zbC#y7of4Dinm?thRg!8vDqk*?eP&Z>0vK-hUPU1B7Qs)+Mey81A}V&EbA zI9*+pK7eib{hPSo!f*@S_gd7sJx#q6WfO9(%@J&(YD}af9nh2vb>O?~Ce zgl1m4^J;hXR=V?T7xmAKk(_xw(|NC(`a09OubWyGb2#&I%z3(-dL!oishj#!_76F; zy^BL#ySfPWj;^jUhoAc(2X~}7dot96($vlA4iD;G;?0F!i+;pL9dnJuWv%`HVDgC) zSBjj!WUHBCac1dVF?Ca9xoh!fvem6*dg?#U==-wO-^Jp4(?-9Zt=>uJo`c&nN(e-) zV%yacd>@yu&GNNf$Kv)-;uPoZnELh0p#?GZboj@g#8^T&m&Vi;k;6Fie8gFlgdDQugP~}`KY;-fT%vI^ml5F)_#z4;eJJUhX#aRx=cX=@^=iIxg zc3GP9dAj=68yHzbj=DRf){9M~OEXSzeyL6ekmH{@qm)b&{xQo%j&y@-{Mhn;7_YP%Odb66f2B9>cP-jNT;!Ly-W(EUB+ zumG7CM$+oAbDw5+iC9P})(pKK3(K^GepKWW%p! zs13|LS?Z5z&TTlA^flAjO}njjdT?4W10a z8XshcHQ>8T_#Sh5J(Q)kI?huWBICbVG6(-HOVS~Bs?(jvveXB1_)U7Ruh`wmaBjdz zQp?}v>r*dGh|cVspz~u|=ZCb;E40oF(xu(sI>c9*?H_WS)#>U68SX7&+~64?~nDra2q3)Te3AvoZB| zQGE}K|15Q_RI@6h*Nbc#WH>Kns2y_RN@>74`FgX#oCjm-U8&>qj9x60F3WVTVl5(7ZI!R5z50sS z)VMEG{ewNN40UnDVdsgJ(}oQ7*NC$ugC(9!%4?&42`O2EZ`V1}gPH19Y1xK!=c9DB zTEx-mIbTK36>oN~N|SU-pUak^{0paCUEsnQac6)U<{tMP%I}%It`4gP=d+M{PR8CM z8D=`iXRWd_bQ;zR$tKoYa(;K%xjQ|Cx3bbqciPg`LTMg~xu5oBqeDY}#FpKSQC5LQY$V zx28H*h1HGH3R`~eLSNtcU-X(UjtrHTF>%;8iw}*SZq%CnntErhOVTEFNJ%3rZ+c6j-alnPLcklXWP6s(QNrp&uPm-y*E1QKcOD$ z($tq>XKk9A&vrzbdN$(RlqN&@6Gx&T=dX-9(A?@c?>Z6&U4DBHN^dV0I~aADH#>DZ z`aDKJC~;*(-69%MVf@%W;%`?+6$=ggGf-*Su5phy?n9KW&t5zJLL=AQg@1aSFz84AIT2GQY;W=73_Q$ zlCIYD1wZY^Sla2GU{&6keric<$K}Cwd8K$ z$ewiB_q>x`?TE9Q9ixaoFImC8j`QaX^^_xEN5@GekPrVo18#?yg9se{yQ>CT_obI!Od0`0w$r#_$Uw02j!vt{3P zSy$(y9_qfX&KC!%wcQ*@=H?uNgokrvCGwUm8!qjBj#7U)$l)xNmd4NI&NJuHuIjtc zr})sd(Ul?gQD1VLyStDyjOX|t>D(D}ONMiOSG6~TK3taR%f6|Bt|QKJX)>_cF9SoX$W>EdiTNVRow?!gY-WVvx$H%`ASUmtXL zAbaH?4jH$>wSqlt1xZg`!7|(lT_WR-^nm?YdcaI6SYS~oeu`4RcAo939uIMe<7&2o zx~ZGlG3llr4X+F>@1}O(H(k`t(R_}-jyiwqrkYucc2zqa%)u)3K@QX8FkN;{cBW&Q z1sTrO9A+HNy^ER7MP1dGnHY&2?n{g$)AIb7^A~ooW6l@d)ORuG^KR;iF7BA@^Fw|| zIS;0*-yA19JrzJ z8D1kqOX#_mD9*LS$X>P|Fmr7`&iyImT%V~vWm7Jbz$(Y=aW2e~l!{{}zsuO9j>s{W z(5{a$>gAaI$X8;rJHYX)d}oW_aQuAwVXtK4_lIpq&x}JjzF6|BXXQ)RnRWJW2>i>u zK$vyb*pEX@G+@yuYuf2+!|Evsp}@|h+C~|W+v@UcoYnY{Ser?!c>yuXL4?Ksi z3iV-gbyb+o_%d=Phi`gY78&O`b&P*ka*=ash}l3x?d|n5kVMIu$psP0Un%lw=i?sj z|GTLzqB0=)JDE!#_GRT0PHU(q+LXH_UtIg1TPde4NQMpCadl_ZE1C zUOpenuiz~FIu9?jP0FqJ8t->Czq{ZO+>741H~7u|k9%&1b*w^Bwa2SR@bRZvj8p7S z56-VRF{1KMj;IxE0Gm&o^Eo-#wR=dFbPd|tSLB>Tf&l%bp9SZoo_u7lO_49UPU2j1 z%6Tr?agR3kr{w+BwaYH_{l3pO_|{H~sQUA%dyrdy4!=3Sh^RQf;-il#Uo!DhPWg}%P=l%5F+p4g8d2C<7=(l<|})l$n(IlLm5CRqKv0Zq0FSrr(93Dld_(&k+PNYF=aO; zjY|lJQjVbvpcGNYQ>IX6Qsz^xr`$O8JnV3q)>Af8wo*Q(?53nOz)v}bGJsM<8Bdu)nMs*Xxt?+-Wj$phWh>=l%5F+pBm9(O zC<7=(l<|})l$n(IlW(+LYYaKPr06QCuKcl zBV{Y)W6Ewy8gt2^lw&9ZC`FXS?)x|-w142$>6?RQFU-f{8%xdU=fQZ?0+>*^D=GaJgv>#K7c>vAh6 zPZd$KANj>!RBq$!=}qO6`E6=&f2+(oRh4iW2$2;PWr4DO+|wvNAo666kRo$~`3S9i3MjZo zozO{)mof`R;gye^mvRP0<^?&Hxk1Wegh+kTKKYf;BuXYl=$-_SB6Ew8Cv-B$R8tI{ z%tcaUjuN^oilJjD>vqW;Cv%__v6cAB2DX1CZpp{ZVBOf{ z!fwqHgIw6HL1K*yOYLq3KIsxUfVLHx{_C>wz-nU07P-j%^oq2e^!3 z7naEA=EyGWDkfvng}dlq8GA0=RsYHubK!3KSH_YHi{;#L=oem@`>oo*&PQi ze6T*R{axdGXxQYd5p{@$#ed}!QHSbZ@lzL;%v>px3q({;4U6B&C!#FJ)36%qqXw_K-mY?k__3H~-N(RldVfODWf(t}?G zHXqUFJ%Q(Qn>0Vd|0VE>yUE==INKUDLjS`QI4=brmI9Zhz>UDoE78%DFaJ3bpBL2s zKnnfKz$LfyT#QHmfzYp3icKZ0Z+F)cn-=MT-3jQA8wU-3#c^o*ONliwE;I{*tkJKl@KYwM= zo}&c5HR!*Iz>Aj#{r4N-66!PkdAGn11^xfJ!1o9C;sUQ)yDX?b#|<%B1*ty|c*Rw2 zP9ge@2hP8P0#4xBDfAnJ9(x?_;okw?g+8W#*bw(WB0uJaFnvzo9|7kt3FvJB9i64@iNB0q>$e&3I@8&RfGf zSUh<*rO>Yz_}ZX|Ile>Vl*DX=x3 zvvSa%@pBxfrT)Rd<|Fb;Q{c)JcrI|W)xOoh`HUyi-j{`bP0$}-1LrIb;NA?1Jo?wP zZ!oa=Nd03iSPrk_tNH%GUJnDut@!+rMKAnWeAQnb_)mY}#SaGhRSJ>!k;CQ`cm;6F zErESE0`Ic?>s#P_t37?B;oe6?RRha=xJ>_C2i!6*n6Fj>H(UL|0~xC2>cAe~0-KM> z%kDwEV17A)W9hHsfb%a?>SzzH05%_?pP2$*37mudOulj#@D^Yr?~N4tkAWAj4fM%& zQ%YTh$UiCtJ_&dQTT|d2DRBB>x@!F;_4i7F z3xVamJ3j^|_P8Jge{l+YdkXvvaLy%xef}hP%O7_Fue~SepBO28{N4c01KwiU_vgUo zBl?!5z!#*z*8(?RL0$%}=>M>Vm!b9%aEaxw-6W8CACZ3o@b-nl{5BSN(jVXfC-SO= z{%)lzJ@`uC6{~pG--90zy!R1#n}M5G2mbK2g%^F&B#?L?p+7tYJ|4K)8b4>G;I9IX z<6n93ihg&d;5PubtPJL-T`BkwiCW8T!T35=VA^NwR|&iV{}(oqe-*I#h`wu5;8%s8 zcxuMyx59r@5Wjj`i+SPCO@YS%Zz2Ae`LH?#f2rW{A2Z$_5csNKJiG(E0(*}~w&?o} za6SHI68y6f6NpP$Rb>U~6?bAVfJ2=t!~ym(2F&n^evzLdMApcVO#0k60|u+KNZ zB@YDS=f^)X(uH2BlLcN8=z9)ui)EjSQ|OnZz;^<#z(0SE7^(lo6#Q1;JmwG6U;h=D z@nGO1j)2kfham!cAJOj*De%oH@cqE~*jvJi)W0n(Y! zQurSO-eT4NA@HOJ1AV$;sC?p$vHwY8IPW9%7h15ymx>g42Jm9?8{-elExhnQkOGGY z1luirj~DpHVEl{*Zf3m8v@iCU4y^7C;3dFYt_ke*wBWsu)c2PZ_s*V5l(I2L_p1D6mVj6H6*=%qj20&XEb82^%&K(>%Coapf% z@e}H^@`qmnucg0a+7S8EfXzqhzZ^JDea64;0N#ba^#v#N&!^CTkOCivBKda(^^Xz7 zypPCV3cUTMpgm8g;6DIfdrja^-HyW_=r7@w`cDF0yg0z0C-_@}_%|0gk9hxckN!d6 z`gwuYd>(MlWkJ4q6L3B9j6XdK97kU>9=-uK zACcGXX9jZHlnY#f{~P`@fLB=KVRj1r9l&w=)A;MA6#O>eE!KG4C9tJWj&!8=5q(Zb zfs26SmOYw)ClQ|s``SLYq|iSIyq$c(_{+<{`Br`D$J0Nz2lyj_%}44#894vm0Dm@c z-h)AZTnW7Piol=N1LrV*n)==VHXo69XfF861N-xGC{=HbpITt^5&Gs7cqwr4p^hez z@qcp){vW{kmcNN2yVjsH9O6HR0XJLY`!rG1`$&Bw1-~Nj*9$DXjOTlScV7tQG6?k#?fPjrvvyE`S{f(2g#ymnF0 z-fJwp(7$QHLcbe$mu0UXokTpmBbYyj04wljyj=ji3;P&*t`Zo39Rr!z>rLP-mVbUL z{N6|E>(bvquDyN+Jn7n?KPCV-6A#V&Iy;5_2H>29*cmZW--ZrX#Wp@w`1>9z50g< z{&zeA7;^PF9oT%t9!_>elze2 z%l^Ak@EJeH9{7Wt7W?!AHXo^PByjUR!FZY`c=R{<)@{Hmt_=MDb>OvDJorrLy^qMt zIL*E1Ku#URRn)G)^>+sTlm{HYIgmdZc+0Y2zpxtEd_>*?;FhIIQ;+Szw{Z5`--dJ5x#w|J3wNoe0 zm@>SAll>~H${Wg>8p^Ai8i!XDjw|P@@RYLAWsS3ID+)_0rcLt%O_)%2Qf`0Mn3z5_ zkyLSG_0+`l`li{9$*1d^su~jIm1T9c6^UeB#x%2_T9FzH2Ngh64jU@Q9gZmX<2DrS>d=-%EpeHJbYaLvT-MumG4rHB_ zd!kB}2J5s$h4kjw@(VqzCwnL@ZzwMtmuMP1qp7ZNR()OLjE00qGqkFlD(h+!pl8&J z>CUQaIGdK(yc~n|Bt0_@iiOH%P>!~BE?Mfh zs=5n3ktrCu%$Mp>jH^i0iZfLtxaVwoVtU2&dRt%d{(b|?#!hB1CldHqMMFaFN-G(e zbiTH(GEs*6n=$EGCPlAAlQB0=Q7sNwRM%iMEt^<69+?LoPLex8D>}dgfXRf2it@&$ znW;ol$En^pts^v1V@j+lOlChD39X~kaeC=`LO>_t-B8$B z9pVgPmbwNRAZGZCt1qvRfsix^yl%BP=-E-UR}Y1;;`6v3su7?ER@XJ^t{Hk_VTw6A zbdT2;qw8igCdO5ib01?e3AK165*~)mXqcH`XfgUL5@XA2rzVEij!uXVcdDP(t+aYN z<}vsV0c8}UzNBh46H0l_kh&SQm5sw|r__1mNhT;evz9sO{Bg`PiON!L)g(?08|6`A zzb5GgG2}SiAs)ihUSd~q_0*~}W|Y@dH_i54P!F)FGl&Oe9X(n2DEp)ME zWmBiu)shvIH#C)%sj?9>%f=?A;wy=Up*7`=qJ<|v@cNu)Ms4SaZov29(`_}wExZ?cUx(jO(l~WUE%&2ZEDoSVtvH^=)(e_X8bRZ5pz_fP?md^W-8i&g;k1ge zBXzLvEY>G?FC)uMyd;>CfMWu0vTsP}gf=M(F;vN11D9d&HZ{~%)LU7fo^tv9r7~ z>GXcnN^5ot4u{p1)(v5q#N;4rl1{9Wq8hBztCLi7yP#w2)E?Ght)i>0l}X*@OCH%J zhB9gDWd7*v~g4P}MXJCoH9|6Rj;D z>1e&)D`kJ@2DWmMruvX2&|Sfn({OIwv)D z%vonN)+7>EY&QeZ*t)>oNAf^ViNHPB-ZAUnQZ`}S-Jije8|!M=&Ctyvx6&Iwn58l$ z3=;_?@YPMJEKf~YWM9rK-3ULfnK})uVBHa+<5B_gnElBdB^PR{vla@bWyu4Ih5U@^ zNr74WVnM%@^prYR$Q=cr6)vQC-Chv-Gk}&EC^VC%U<7 ze`05SzdW*bZ#S{9(?pguu%gK_^Z~3~^dRYUBB`w5am^qgrP>)=dY1K8`rcBTRbjc_ z$h29fOsSdCSY@9vAy7}cvIq%~GT+Lhrzt)v-cYS=z?{prYt!(`!osoRs>hZlZ{Fsf z>h(?1@WZecEL$b+)WHM5iNyIq<#~QOFr9HTt89ke(&!AYgLks#611&aOs5*xL5c>+kUQpozjqC zGqxg8IBlOHKZrD5EM#-uP3vX1Z44d5PR*?H$<;Ia^*e=Q*-8zo8_s;8GX%=TO9&f~;K(xRlaxVF5uuETU7 zJHZ`Rly)0B-#|;w>Z@!254**FRN_F=5Q*qq&#@gV*;2(!KQ)QKQ9K)H>$}lmaHHPQ z(%_2f-y5e>8Zb#o{yF=`)(i&?60;CP|{6J=m`s#rmkm9UTK2 z5|W&;ec&mYa*@G}6rGH=q{)Q-cl*1v&S;`5Hq)|89Lz9faxEk&s~{Hfw0U5xJkR}3 zsURk>j4a%Ll4G_#gZ)m~6M?7Gxx`f`DLByr3%0f@I!WCbi0=N=`0B)k^=zP|c91pT zJd`C{r%Qg{4w=!^R98E?yzzXG($BS-7HjItEA<|iiGPjc)3OVRManywzbpfv#WGJu zrQU$`%x_ZGGNM35r~8kV0NIx*t#fx*Q}}UQ_j;UcpC@0Q*w^lz=Z4<(zQS60X@Qqe z)e&kXo0V-+S)6vbs+JVX{4kX~Gk0*X;f=O?nO#=Kc1oD3tm%A^dLu{-!dz)>luc<$ zB=1kTRqtcO>CNX3gHn5GhbzCXAT!G8JnzuDJR*65ea&h=TlfVXF288z0eb&7!Qe1k z!`^_es7lF6lG>HJuYD$KD7KxrVxE#yBqt4wVttLHo~tEgGpie#xB$}09G5gYM&b0< ziIlMwm__H8T>q)6s}vd#_z_Noa~Dsq)LF2^axTjyQZ6zk8@iJ)Y+{(wmt-4L?@^do zdtu7Tk<6pw{IaR;N+SqjCP(eqr^BaniM2r9@!=|CHP}s*tP?s=|F1jA9hVkK{fV`T zh%WABzYf>UXo^3#)5l$gj-#5xI=F@)}2Y-@9(&~l%{P+9mbYR zeR-u`GI^)flnWcGlQ(h6NZB1Y)qVR5OVH$LTd>?N(BUGYz1wXrci89fvD)$!r`GYp zT))`I#q0hu-V66}U6H#_lC|r!F9Ij&War+Rkb*r4d0UTrq0^J&)A=(-QBC<&dX!s~PW5l4aJRk6NM6et5|hho9}B5 z+~58lm&Z*+$t%y4y8gdP&aJ17B#6TKNxQI%l*bJa#nNVj7%Q(M-yjIvW6fX!|9-!! z>brX;&PznhV0Ty7<8raAU}3iwM=kIxkb zNhRaPOj~yFF;zs(QFNeISzi$_G{+@$Jo*Zy39wnw?uo{0csi%!%TIkaBwV(_?t)gn z>B&F+jeO0Lqcfd>Jn(>Srf5!*C~Q(?2d8|SHx-9-CSEi{3_tWdlaC%NRo<^{UKb+3y=?v+oi{jj%gh8R9%X;TyGL9*br0boR2p-0 z+#R%5i;6+zP~zeYwA|NkX#zgUwn^G3$SC%_t$j;RGJz2Ahj^vf0b<@t|wL7>Ro!ngi*f1FMp$IjB+r*6J z*r_Y1B(x^Nc@`rzTT|kdoN0AXl{^xE{3K9#-Z4p5{SSHmqZg}fyGI1Hurg+AD%WmCP>oZc@pt~(Iep=@4ksa!x58eQ$;~2pEeiXeY2CsObVlicN+`3GC z>kdmw-<*kqZ$mZHiWpHuAn}BJO^KUwptF{P~+rL@PM zPUBD$g=8pUN)x6cuRtsaBkOnip-3IYpD|z}qot{53_z>KO+=hV4M;&4{?>GR`yVbQ zUmgfoDm3XH6~JQKf?vsKT|c{9HN)*~b5R8rwRPNg+YQ~E+m{hc=>Rr*dkfTufkZC3 ze-VDJdw39m?&@bgE!7-ys&HxHiC-r!8h{eN zR|$iVKN4~v+h?f6egf^p4^qG5;hnGx?5WVWPVfa)q#o*^`rNVav9GG-v`KO4-i5=7 z`4)7h#C^<}QZ|@kBS81N z+=M7IvbkC`eOWW>vU>LkGf8qOTfN_t)DiXADubKzgZ9fG2GPi5Vhv3mI{yP_H?3a4 zpgTFx-gG?#Nzp#W$3OD46;!4=6BKVWhTx4;oa_R`H@QSKRg-^pxQ_1>Gx(aAS{G$p z^VCXCq9ct9y-<)JE>?57qu{ydR`d7b$>~UoM#v6KGbte%^S>V`5|6HJ3J&L&3>V+7aH@EySsyj*b0$<~onNjuGz-l1_i|AJhvaZv3>za_XPdo8t^`Oas9 z+jTsL$G5i@a5i+Ps~JSKuYVM2Q26cNyW2qQ@i&+4jC%*)I3grc9>itWLW-ynrFas9 zVl2#)Nhq54-I9TzZEDoRlV2zp^MF6js!L8Bt%V=O;0#C4Re1;Iwcx?-wd~f6tOwRD zbQbZ01_%M_e)IwxIS%mQ4jj47#FUU=MB9i_Ix3#kGUo;cziQI4om*?j7lB33z2Y-6 zBKN54sTnZi4VglWOGa#_)UONH{PO~(2%^2`ma7=+IsnU$`rpxe8;QmJ;*D5VY@28v z{~CTS4hS-;Et-FqiV56847xJUvukErGOiYuPfi=Z^%f0N63U?usWvf)XTU3;=^`Yc zbh3+gaXE&xMO<)2NoW`f8d?PrzSS-Xv9oZU&^_(16JDV%YcAXT3R;k%Y*vouWe(d|KYyS>xiXQG>CrKZ*Vzu&dbnb~t>e)r!0|37|k&id}P*Is+= zwby=}eakZe2Q#qRc%E88`~brAkP(RG6GCPh*Xyg2@T zmCycmxl)CRW%R&b z73m^3|2A7yb$%-;E|>jHUVaL{@l56QJ>Mq^?ff2ktiUe&+s=0x@=?$K_G9Zg&MGgS zT^cP$``fCH)a@t~MlCPAq{vkeGaZD# zMptV7F@?T0Z}^Tq>B#|&Nlbekf1B{P8Grx4-&^?OrvrcQ;%_Vd{)xZ$@%I7#`1ufj zAIX)=HTl!^Z=ZWxM!(MYb{zgv@TbFvzLbCQQF{)l|LEFDCluat%QG*3b=wVv>+j9k zy6eQda(?fA@tC~#e|Rvh_?ihT%!F^gn$!3G{U4sV_NwlkFL#{d&Z=5;?>m1xv$AT< zyRUrpa>h4S5nX;Ix(;?t&yP(S4?pS^3kkIwhUyA$L<4q(A9HZm_$C;#EB>eAlzUl9 z*Zj*5>l*KjgFhHY|5p#~TFxjqBir8jSrDgQQ{fz4@$UhDSNP#^>bouuei`I0W^$FaleIQ8|%k@IvMIm6@V!?Ccdes^#j`vl|Q&2jwa`#Ajf#ff_b z(5FBCoS(bn*!d~M!>;1?vN+{F633qJ#%cE(;*>ihjz15NV~3@2+UtrqapV0s<+jJ^ z7jMOB_W^P2&>xfAuG)Pi4Br+0M;v{+#gX4Hj-K8){CCIUFNsrbN*w;3aqPc8PWuMq z*lkoC|NK49_?sC={#$Y642?5S7#>HCCypKNjN^yT#IeIKapd0&ysLin7VO*=etaCi zZI4s0VhHKVuU5s;XLX!$sv=IizZWMCRL9{r;^=>89Di6HryYyq_`|Pp`g?PnasSac z<$e^$J}cw!UmQpN^KtN!IQ1%w(@&?zvD+7M?0i-nf4C`*{ww47?Kt>Pf9Ie8x-(83 zyE2X(BaR(b#KA9%(~hsikzWwUK3n3nnm>heyRJ_mMdA%j4NO&U~pOj{kJVv70ZBKG(&m*Aa2* z^=lmYcgJbp_u}xM7e}98HD4kMOuF|?r zDK48^N&%%+mDhpsqS?jcED2+(O6%*(>s=Ga6<=8H$*->TOsJVzUQK%Z^ajt=nmN_^ z)hG#BUBy>kGQR#SWUU>ZRy@AAd{(VzUU6M{Ep)7@E1g!Jr#Qx>=M`RDHtyo_rTJwR zB$?9Fim7|Or>5EYp6WRo1I48sAxnlrTc~D)#Y`S zWr9|emX!-zeT19{8I?8F6Cq`)N^;MdT3AT>GG&zm)+ri!IIQ}U{(RaMqc&n>SntE;T_Kyiy}yr-_RdfEjwbC~xpE;3bBR?lRr2cno(Tv1wC<(gLRDVsCZg+{G{*GSdR zhDTLStELmoa+OV=T3JW@Vz>@GaB3bvVS}5%3F;M*J{-OQ^UW-tj(X5^G$L4L#X6Fe zX_h79?9$rWa>$GdI=iyEzP!$pH%m$vDd)gNtKblMvotURhJc@4l8J6s-GEk{n|@Al zadl1ItkSCDN;rHed^*3dYdVV#x+*;7RqPejrL$ZW zG!d?+mKM%-Rg_i1iCqL5u~MS4IcdW|wObg_HDtnyi9wewsRwGAH27@=pr=p!bXU{G#qq)b|BWBRz>6vf`#1}SO@f12-X~W$7i>O{+Uf%57 z+Dj*(NyMqnDXW=PTUu96cazF=A?-{^Q+}c3C@KG`?V(M2ab8}eu&(rUO13rppJdYm z(5!5UE|l-u6b?g-uZNez@n^%!A!x$H@t*XIDW&z5W$3Vs7*iT5^2-3Gm!X3dd+JIn zJ@p9B5~K4D%u!xCD^3nFQ%|&ZX;rxu=IX1pm?55%Sv+nEiYYIT7#>YtS3ae*s-Ry=MzTQ(+nYB@U1EX3(Jxm+;dteV;EX~>5jZTW1?G*n-6 zS*SgtvZh{28Z%si3=Ng3?1YrAEF{L6K)Dv1vM2tBjk?MZF)50(^TZK-7KU_B9%~hC ztBB>{dv?3nV*Zz+tp-BCj0RH%6g%ulD{AHbCm%TneW-q3by;3vnH7C2Wk4^V3uh|x z4=Jpj2FcfHFb#O7$M>e0UR};ZrOCsHK7u^u4Mvi{OKxKbY(CrPMi&sjX$%P zv%3i}b<}wPsIFGY@@l8l&2)Kc8ZZm3bIqD5Q(cZY)iuQ&A7$PSwrWoB@Gbh4R@F`~ zt*@!`xEObs1#zdo+~aD%%vC0K;PhZwpsy`Tr!a#(U7yu}B?U|1ggg?GByd$!R5jF3 zcW^dT3vbzU7#YRLOunvs4rb%73Ix-7&M0fKESiH^0l(|#K{ZTmW6QIaZV{A=hN)Qd zpoiIv6jobaR#{P57Qs-dF0iT!oq**=Sd`Z@4v;iw`&GgSc%Y{`8MmDa!IDKYI zagxt(nL+cyE=yXZ)Z?j>=pPGr0STwmo@F(dB60ADWEX^MDFncJOcFiv1x4vhGO;0C zBP#+fU27_)md=aKO?WEXH5RtZuB;b#j3h?u0qZezM^X-~oFFtZSA-m(X)xIo02s+P zqo$JU!U_46v>ImeP@hV!_np(xn z;k?8^R5oNtB*kh8(rK=$si(uq8|I!qcf{GJpM93fW4Bce9002zYn4}CTss{rTnH>v zvWm;6mU>Fz22(J4p>F7R#b|xkg$4Pe#}p4AHhfq{B=%%n*V|W7{MQZV@RH=)MrP~>|MlOW*u3TbZ7Tj6`c&dhiQ&4{y17DG2g_ck zo_=^t`jH2u9~zUMbwK*TT6&`EbSpg@<==Meo!FW0>AKg#>W-s6Nv;(Zt@P`zL2cGhw zYR5?qJk7#OoVZ2Lb>M{-f1?9Wv*;BLywIZC9C!m?)q4@%X9~xYT=3wJy4R!e@N1K++`$(iK93%4k|#EIXg@Wl?i-ICwpz}u{c0G2!O)K66Z zZFS%sJfMTmW(U6AlHcLLJ1jjvbl|CPDmmL7c*|cDp8RC2oo)N4IPiAc&JNslm6GFj z;DxrG9e9T&XOaU?wd5>z;I+0r9eB3IzubX0T6n7iPpwmWu5#doU#tGL*@3rNbcX|P zOjZ0JI`B3N-|oOu_Na1qI`C8r-|N6@_bPsu{rrw{4_BJSpZ!d1dv#dj^&|)Wp@p|N z@XZ$9=D>fq@a+z~(ej(=)_rz+9JlGY4t(<`%0Bk^%&0sTf1FS9V~@8^-1ZkIZu_GX zx8s2mx7*E$+v6wkx%jj7vBzyEZpU>eUTDR8Cte#5xBS=1-x>#RkArWIgO^zI2giH4u5;nOvIgof8@_<0&WSHp8Oyivn*HGHv#U##KFH9T@=0_m+9 zeyzs8Lcyh@6hlEHT**je_X?Bt^Q6wc~-++Z7MEt?QKOc zNln&p6&X~f6bCqg0VkiH2io82L=saQ%E)}q%PO+-Wq?ah99rtD>VEB4R6!%z8bzt!~1D?yM~{r;hQx)Rl_?p{3H$k zP{aFc_;w9HS;I{YS01bqcWU@RjeoC(+h?RC`Pr!d57PLPHGHs!r)c2`G z@JbEeso^s;e6NPj)Nt3|qyAr|;mI0at>Gye&NIdKr?-aJ*&x1CHN0NK2WhxR!_zdp zLBmIA_-qZ&*6=wR?$+>m8eXX3*J=194ZmK)OEmlj4WF*z^EJFy!xw1yTn*=0Y5UWt z;f*$k@5LH^qlUL=xL3oMYq(FtTQ$5%!&hkdO&Z>&;WumeDh*$(;q4mk*YM36ev5{8 zXm~)wKh*Fg8oph_gBosX_)-nuso~8UzE{IrG~D%k)cJfQ zc&diqso{e({4Nbo)9~dQK0?F)qT$&Zez%6ZHTFVygL z8a_$GU(@gs4PUR}ZtoAt=8=bDq3zv}tR;jqW>gGtg$GvQf8)e#T#=TMJG4EF&%i09 z6Cf(oA@r4`yOC}edK~FQ(rrRtM7lfaR-s3eP9ohR^hnY@NH+>SoHUy=R4eppq?1XP z2;HCb!K4d??nAmK>1?5Ukv@cUn$SH-qoS@*s?gm?A4WPw=zZm&4=3#sdKYPf^v*v4 z4E&yS3hC`ae@U8K384<5KPKIabi2@7NgqkNP3SjBA4R%V=+{UeO}a(s)ufLh-6-^P zq>m+CEA-=}xg`)P5&8kr$B`}+`fk#FNM{Ru8|mXorwM%v=@Uq&3VkE#zNAxxzK%4v z1VS#M>qwtSdgmXk{|wTpq_+z_h4e|JJA}THbbr$ALXRVTGU+yRn)KPE8-;$3^f{z!g?^m$2+}1&KR`N@bfM69lO9PrTj<+Jk0PBW z^ev>%C7mktjij?krwDx=>GMdtgsvlfKIxtNrTs}~lin`$6w*1QJA}TH^k~xULXRUo zhIE_I7m>~--755G(s`s?gdR!y0@95_4<~&g=~|&rBkd+#B6NS!`J@Yl?nC+_(%C}y zB7HIGG@*NvE+CyMbT`stNv8mhX zairUY-b#8r={BL?AU%O}tI)5JE+X9`^lH)*NjD1p9O=tR*9!eO=}DwZgnoeZ6{HJ= zzMJ%wq_c&-jr3Kd(}cc-^wp$Og}#yWWYQ@@Uq|{H(k`LvNEegd`J1#q=@Qc0g`PsX zlyryCSCXDWx?SjTq{~RR34Iaisia$l9! z{Yh7nE)=>C=^3Q6h3-XqCh0Vxdy=jqoho!U(z8gX2)%C#=xWj~p?8t4A-!|2v_I)u z(%XgplJvEtJB0q2bRFq-p|_H*C*3CW8>Bs?TZMj&bOY%Yp;wchO}bI&=Sa^XT`TnC zr00?@5&8kr^GFv8eK+arNM{Ru8|mvwrwM%v=^IF=3VkE#`J_{XzK-+)(k`LvNG~M4 zbC0w?=|2{&Vk@k{q6Z#_3KGLm1k0#wjx<%-bq;DeKDD-gB zH03#62>mhX+eo(yy_NLsq}zmkgY+GwTZMj&^fJ;dLa!!$ zC+S9^pCf%2=~|&5C%v3>iO>&_{tM|sq3qy^Edgrgw{-j$;Zx?zB>A#Wg5c*2e50GvbdK~EoNw*1o5$T6Ww+cO) z^uwfEgdR!y5z>u94=4R7=~|&rBfWxjiO~H?KSsJx=su($C!H;HFVattP7}H(=_g62 zf-Z6g4s!dyaVO3-19MWnZzq`hFzQWSe<1#)g$I+8y@@X7@h7dV9N?Oa??>>xzJ;G6 zcQ7mYx&cf#+ZT63YVhdR641enpXTu^>q?-Zhv8a^|JBt{CB2>ej5lDIhwT2OoAJMS z$*bLv<>+E1poDUfj(0?vQy~D?S>zg|xH1*jX^N|iT<0mS7g4hLK)ceWmtuQRX;bh3 zv^mz+rlrMr`sx9{FDe-Ddv+s^n?5~Z!0+o@xHfPHl3uz3#W%Hkx`jJrks$iJgGpww zsP!?virjPo`(Jaf`~G})LWld^ zy$zE2=!KGbt7jK%yfOSG^EYPskqhDd|$6{6Mow%z(rc^UneRo07)ZX`7Nh zyhgE22K=dYjmu}POK;LXTqUfpu=Ov>OW%?w?vitP`j(uD?%*;mi*itdm0S5gu!h00)KmnlqS*;p@Pi#D*tT)%l$&eb`SbFRrLR(66mX8Q;!X601RJ?>y$TS0Js zD_h;)G>EzcGurwjx(fVZb2;LUJJ^&Bv>@2fqIgmj&mF?E$Mk@wAULZLwkYubR^Z=N z;QzM3zr(y|7?sUyiD++%rg^Oq;PONlO4(r!7i|pR$I!PRSPn6}pu-4}|DAahbqK7X zX6aiB{9hLMe>Arb5!vk#QKyUS`E6#8i;>dQp6`EM$%CN%$1zB3GWTODiX_ALmbAo5 zRgbKlNZuq>1nfeOYHCLu={FgxY~Ksi$bb4tAo9}xjoP$XC3?<*`>vY^k8uYtPceKu z5?n6t=I~BqUALz8g?(TG^Y@>_;m(w(zvrys)Cw{hZLNJLU|9z_^P+NUP>+Zlqj^8p zJ?>ybyZH=+h5ijnmnT!RX>1!9@pRNKXN}CpCRk7(fn-9K!#49~8FopYIa(?2+NI>P zl=Y;%Szi}LD)+r!Iiq>0&EALXjf#Dx&F(o(lYFVox?>kub3g?O_XaNt``vr}9i3jC z=y3ZHrQnPHZ}a`1(nRLtJD~~eRp9?q=(~lsy2QQbvr7KYC8bfNsGg*tSqduDxUK|5 z?;rgeV!1b~TSVntP30G$BnmXMsPSVU^8Fj21e{VSaWsU4Dj-!;K9r1x)acF^ApXG# zmH|Bln)v+~yQD=w`w4RX4T>JG>fVC7OLd;zAr)`cY;hl;P}ot-(^lTjtxz)b1ycFF zMS0c9k@B;&@|W1yK$}yPripb* zQ+tkogC_^k_Ir#9<}xf8-A$h$l5XN4!7i{V=}qg>lbGv28ADj_^md6-lh;T68v_0U zwp{;@jN~az?G2|xj;F^aL=BfKkW__4Z+n72sSFpCVM(y#GxAp=#h>@7c|=5qF+li% z4sPqx@LkW=%=^@z7^4YBrQ^V&#*=nWZ+9Tsjlksp6GPx8cObua_zUC2Tvl#3lyfX-pc8sG zd(tfVkuCmYrw>NhUubhqjc^*xS2Au`+`|=j=mKKitT!SVvb7AowG0VXhVFE%i}nVu z4g2f%`rio6i={j7)Dk;a%k(Jf57NKTwY)!MH)d5caC>e*D`cQ_wtzMJKntaBk(OY~ zpfxam8V+W2G91!}!H(+*VEu?~!DbmT)dWdBfyK1dGqG*eFcVFaElopz31)>5F-_0+ zY>2*3T{^(U!L(NDjrmM4>kTBk{Yif(*V2EJE9-o4VcI;1DZz}tFy$;XRA?k}S@XK| z_Rt*4@Mc{LX0Tm~@sz7f&A1*Zq~RS@aFzL>YWY>6YgD$8b~caRfM@AhYV9oj1fBej z!@07hPIPDGOlhF$Ouc{Z=F-|o_PsT_^G+=ux&uiegj_pbq__hq?DCr?y949W!e6#b z4$Vk%xuWe0{+HtM4-$SZoud2{JUMhzC*}Yu?gWxDk)P{;?u-MRIiHP}yru63quCEN z=6dKDupl*;eJ<&@@ecle5&j<`m;C<%ON9R=Cx5pH|5}UxPV%eu)1t8Sb^kYTitaAg zf{I1q+Yws~-))H46)i?H>$50)x?uglVJziuE4YJ6SM^FnLOKY~V52z^>;PXmg&-f! z@f-!R2_!t}ZGIV-zE;s<#|v-xTEoYevl`7@dwRo_hOdp}($kdmo>1Bwp5=MlXf_p+ za59mZo>w5ZJta|=h8_5(U{u}*G1PQCb@cf}G?(Gv-gYXLx>OQ4Y#7Zl^9&|cNWxf2 zm?BP=5E8OU@gYd8OpzoM{6@)3^SUu(LGV0FVHC7 z@C?rhxPA)PHynwJqYfunWi)l7n;`z$@n})lWT*BW%7U7?f?O0HCQa0n$kHXMl)mB{ zY&*~EMl;uakl8qx22LZ`1~MPy4UgjDBb22Aq|tPPM30IVZ+M>JyGxHB-=i!rcN1oM zo#Er^&}a^+BA=6rU2pg^D`13J@}SYnR!?{~yv86xT~ zRin9*AaO}8)`LlDu#?ejC~0YuE^)2tYh;HH==D2Jnp2GypP|bdOOI7@+ay5+fDNiI zmjhxg-@>=l5_%mWY$`6@tJqF~A&n(1invS+&bZW2srQQvSZY!D4XIDLVm$~D#gDL! z$oNt!>hp(G3}2Sw>j%hK!uzvGzgE)KAl?^{^c!c8d7-BjWRAyFz&zWOoCdC`QLeOT zk3(p5#NiKBK={ZSyAA~|b+zJ#Do+ifPbtsHZ#QStUK)&R^sWPm|#FAnLiG6xEq>8r84#jK%dSxV|A5 z7xM+2;TeJJzsdDX&roL@ebduwqdizXn74f^ZPbZtEp8!yI{Xd&(euNC{-7=vs@#Jq zandxou4s6K>iM9MwCfy*Z3;KsN|5bR39hLAD(p!W+E|5ZaO{AFR)D)4( z#FJ$Pcs|HMLP~HM}0iG3;QGTtA%r~8-^{~!70xwL?2kM+nj#Pl8vJ1 z$Ty^@IJyAe?8u&EZW1tk6@)>0WWNCO_oT<507S5i;}-SVTEoli2{h2*i z?4J+wdBfd3|3>l>B&(sv^SRSxex!-X_KtK@VsnbIRsMD)o zNu8GC+V)S|50twZz5>yXErqE+<}a+!(hH%uTDP=7f2m`4v=S8iIGOh3DC${hEIkNG z06!9t6FyHX$n8Q(oNdapVg)iyfCUWS47%Bl(Nqp7-Ufx_luBVjmO`^ z7RC~5Jg${=+$lnOI%K0brY{O(&Vy;_zc2vVe#XHH^%Lo8zM(?;_o#`{+#Mp2`90Bf zxUh1k5YV%Lj3xh6#AZoXbIElI>JUh#pG_57d6Pt`dqny*5C~Bhina$!f)}jD(toRJ zULXk^nIq%zn4zr3A%vPZj#~b_D7;&gqy5=GjAm>7@r9`IS4lioWIv{4tAt-9;cz5C zkFSLHS3*sH$B3o%FV!Cn-}AJe$e#igkmny_)`^6Do7BM9A}z665#4%HU!SBus-W%y z6;RWr0#yv=W0i87gz446&0HF{}p@v1A>q=yaiH7)`%oETUy7 z!9R!^P@Lf#sQC7yqQ;WminvwM`JA`mOH$AtF~lo`njRNXkaL6#rd&`OzR%QH*Y6<8 z=}^RJAQpv}N%|TEr3-YY7<7urvHKU~Jtp$HNx4DAUk%7u(x`}MB|TBnXDP@Oz37uh zQ!l5yc~XzF#L`(vG?vam!6<04B#e`U0ZP!l0*xosv}M1tRUCc_4pNO zfcC?##u8Hzhe)OP;&j9JzJiVvXrI*cIuVCV=O$5(+OT*Ept1BtRlq1oP_z0wlz{UD z;&z46lqmwD^M;Q^*Q41%edQwOW+lgzgkvP3K*>oO%rcK9)b!K7*m|7-CFv85$jy3Q zi}`}gpLt%2^#+ao6Gc3pD3h9|Cq;;?r?2cz*=m`+%#uwxM~E6nNtyFCe4W@4lN{($ zuHk=^aEeI3`Ti6Jp}o5I{(yI+T+MS z67|#hUv}hws9S70>!I_Hb?_%R(vuwNPW`!$5Rr%Z+W-!xH-DuX>y?p-F8@Av*-Glw4RE>Wq|hPVu0@V zsd(rdT(icxJT4GSss)cXoWS``p9P%nu!fib$%Mx**NF{BFhe%|^fVy2d%we3RQ@Se zQOn1msK0+AMJ>T~%>2e1K3>{m4Ezwn+A|Mmk37iN+he?gJ{aZb>Bl+fnD$2zX^#9O z9kjE&|0Iv~)XTrZK_BLj-^W3p>Y#HR`7d+OM?3hB_`lk_8h^eIG+X-@L(t2;;cA=<2_}W1(G7iZae;s}IM#u6kX+X` zj1{?d{K0a`@SQ3GB|a{^2CR<`lnCkh*jW0t>V_?-1NJyQo00mgq*i!dp?^7@>KBwE z^%;|m`dsso)aM*rTlJwLA`64}Ts1*^4DyU6GZnExgwHU1S1I~yp=UPS70rJfim>+& zGr+ZA2!sw5P%Ylo5d~|1g1hV3JO&>n(1o9cb<`ZyXv)&?I}iu4o^2XzVPX&PJN@M& zM|`V2tpkIitLX_|A(NM{y$FutN+Wj-v5WHau4YL*8!KNTAs!J|AFfNxQ^-nP-8O; zh5<7gZ@v?tT;k0kQo{-@-kcw&JkFz}ycOr7yfLc0dvG079(Ece-kfa3n~VeE%}*#@ zxA(!2tJ5brXzo+#=~p=DN(b$C(2qIjEe`q%2mPCaJ`VE)z5GlEeT9R*)IL@0E4G(Vg&G z_)9eSVaY5J7rTdB7hfJ^U97V&{%$ATWh1lgi&{IWz($7J7a4X^qK)iNw=;uibjGW#OczW5HadSQOSzL;-c6xbI>+819+H-SEn*%x!| zi}US^!|jXrPqidJWM9`{JpA7IKe`TyGpOz`j^%U)*V5ER+jpB>Dm#Ba!H(3`C*{?@AM`FCPYSnSyR|&~G{De>vz+9dxlycRd)Ng5HP0c;Q*l z{O%6XydKw+*W-M&{~I~D#e*Z>AFzL%6~cVMJnJ2B1$fM-266b=Eiay)0^-O=0Jwn-f*+0@Yu6JF6Dr+d$bcBW?| zrbtaZ4JHSqqw^!!%xWPy^?j_{d!6ZONaoouG(=1K*0m#H2Xg~7gl@7M?e^{qH+=36 z9BI7Jt8w4ep7$E}odLmCme}*xa=xf2XU!Q9k~1OS|GOMA^KH#F^1e4~HbeKoQ3C>_ z_cpc9HFy^0Q}~4ix&7~T9@_ZZ)t(_pcYD_-fag&1tg?9A{tkEIXdD1r@9Ay4a7g2C zXEb!=E*`?{op0LnOVp#lzuh{uSJ6_mikhIx*7z>^U7j;Brzqe5z9{%A8Q`)%!(Au& zwitQ8xdX?z11JaP^PRw{{|ghk;Xq|}nDuT_=ZPEIvW>MLShI?;_Z9f}6!`NNn|)Ek zfro zhw!D~STv4?;)r73drljGv^{P=kG746JEfQ(DV}`)Q3EUpQjsdhxf`wr(P|M!(#ZVUlelb%HzE|Ioe#MqYcU4?3-^k4M!)!)rjLL%}`f)u>?TN=a;lDCqVh zn`jx_t@BZwwn~J)2n{^F%o~{68PTc8gtKq=o0;(1&_q(+tbY!Uus<8i&NKQjig^gR zFH+o(*xa5;n&1;G&M%-t$RH<5QD) ztDO(986c?hHTzJRz;cXB48l5IIfICS5hGXc7PF+SJ-g*t-k zR_?vrT#H>&pauSY;;%bQxt|&+S}x#^tjk}ykqUn-2n^hQD$nQ5H48GoYdF#NLK0`A zZtiH^_zVGRw;AlJb_=4l!-Bfu8M6m#w+1{9MR=m8s~0}Y!~0*M5#fQs$ zV#Imx)vt*{Z8rTlXu9le|A@883s&CFt(v9eaHalyiL%#N|0c~|trACYT%NIRlG{Ia zv9We?N`ZfDqyHl_fOw6bzu5ngbd^0O_kn3-0=5||6chNZ{!}CYdUc@h-KQuk;#rM` zp|%xCRD)<0mjN;Iz)lTwH6X8;)bPEocdvynvX7Y0z&$#j1mD;w-%~MskI}S?$#y^3 zPO;fMS4CRLXl{`H_oG<~w$OCxf0OTbG(yI@*hUzr=vKQ?jt0#}`2(-l)y$7lgCeW* zHTxo_3l4X5LB@$L#v_UM9IzST5tZlTw%nK4Pxil;YpneqJ+v*?|2>O8PoB`qdj_OC zI3F&wPDOZz_R*Ff;gOA;wV0z|#LY$g3(PggX8u_}EHHO(Q&^2x$y-!qM~^sR5bn=m z1R+ce`bcf^xahHg0W4z4POA7($NO*!Z4m--1IW&+<+UhwkTOw zMoUeDw4cc@>TXP+s;ezxF=*&&G?dscPzw{xPiWe$lz9u$-ZH_6VV?eDgL4wc`u_;siTiNsK5o8uV?wB( zv99x zP^3B`&z^LQiE1)vnCDQMWUT+k(1Tzf8(h$>VANdGbDY-bN80=&P8iYfu2gG5*sj)Y z3{6rkCO)6<{WHPv@m%Iu|DJsBj&7cjP+vU3YLkso{z0C;W1IeM_}+v5K3saY{nf@yWV?4R`C!f?h(i$-^?oLmQj=Kw) zc90Tv6&u0rPs|VI4p5y~4bDbW6Uszi9T7VwtNSCEc*i6C#yKVpRxva9Y;67^KUl0=Nygo z8YJ=os^8fHa0MBSR1u1qea;{$J)ENm*-zLke^!&NkiN9~1Df zB2!M54x&+N0DKgNt)8)!?Wn5LgU32jexO3(b*w>pyYsDCvltFK+Dh!8pxY|ze`l!kuMAqYQrOWgEd-y1CMiKT+ z@N}EZMDWP<`Q{n~AgnWC1;fX845aUt0L%wVUwcuRV&4mVJ}Z59zJDVv^910rWmt6W zFk8q$XW8JvJ>id5v;C!CZZh-W1$at3!E**ecwYL~<_7dIW*^F)sjZQn>%XzM6Z%1( z|D4XPc6|Q2^BrwJO6I>RkfA<{v7egb|EH|+S)Cu1MyQVGcxZ^|WKW^YBVSbtJOM@W z&~IRHZaHvu6SM!ru4m2HuzP?IIUYS2ygv*w+x~ppO!3AFe{Xo|7^a|fWhgJM_R>{rGMi8+fe=pEg^2qZm*tQ6e2j%A|# zVCX-_Ao!M`b9AoC*>ph)Dv!CturV8RhxK-K{v~evbYfc>tsiNhOW;e&g3>;C>fQ{f z9=E4sop~Z2v6T41mdTB7q8zaPvD)ANr|j%PbcaBP5tetLD?SMfT@er7jf_0N zwGhwqHoW7{d&T??#Rl?T>HG%)73{6`@AJy(9>HAjlKw$!edc*CN1LuK&z9%PP|g^hJk9!(Y$3P%JgnXi;ktbf72?= z%(9qys1mxKD?&bqZa?R~VGpEmj_sX`?YYY^s^8X|6Y$93jd&$1YtQX4PY`JmsSF?A zJfe-8buc-s(qXQLTA`_+RKMo71l((_a<5MYqoESu)M|!o&Sv-sq@dIjq|_txgA+Jq zNP$XXS+3#_rhXx={-D7jwg#S4BBd|H0=(f>Gan^)zNbx+LS@LK(VhRq;?8<96Rw0@ z7zq;LHevva{`om-_nrC4%b4&f_RekC-xEt(9lD?Sg+lty4c{|;kFeSjS zlL&ht!iPPl=LZm6Q2fU3oc5h{kh$t$c0fLNoN8AOjqaoRFbVg?&2J=k7wKw$gM(FG zJ6}36wvn3~=n=t;dAJ1u%eP>p<&LG>FC(qnzic{Pz>kgx&6_3(5#$ufdgT**T6QAZsxxE=ux!)KV_}NifCHPVzrn{wYi`n>;E%u0U z_F$t~3Ij1D43^}gHa^OXex~+p5jK778i9LhHDn7|X5VHG7Q?Qg#ld0T%_#*Vhl&qI zQw8P))LGtl2%YkwQ|K3trQWOwxJILLyY@-2A!~H)B(vsVWa* zu?JHh;m2dpM)MU+R{Yk~=u+fTQ=<^)e=0J!T0GLr`#!@wXz$>|3&BBGVdw9m;6|I? z{WNoLGe3V3)57SZ&zMDevu-`os)A=&jQXE*{bs4Zu?_0K1;8o?nsnZ;N1(SM$Q==M zT8to{CTKnd)f4cq4~>Dwx{$39k{A(kc8rkg#XWvB&!vEB8ei5g?Hn0d3ePOLNSSYp=V=%yo% zv{;?_VKzut@x_iG`Tjrcy=3g9HCiF$>`{>rA~z!Z5(6-KGJUX1Bvick4Wz>>RH&GM z*z*UDIm#kTElLUHdO%~5Pt@qK8)Pl3ffRp9c;xB4}|{%oP~8#en7fJ!BUG@eR9)*p5vn|4aDK$)EY1 z&8rysQWSZUs%1ZKRtw}=G3-ib3}e`#zOTbHp)+U*Z&pc^f25ON*-A`f-pV|KRGy*H zJjXcm@Nr(2QA+**2w5+Cv-Tct2d3JXP;j}$pHBXZK&ZWP?CGdbaPZ@7p1f9f@ZN0p|{!mydTjC0>e7^N#1-9OH$Y@VUc0 z1?OJvIpf?jJVWw>mxVhGyIsFezztr{G49NL`Tlo3hZ`?k6mI-&n5Q4^5I5ky)Hd@Z z+6jv)HN~?1#+nG_BH%tta--cteE-26S`_x#G+C@C__J06E*Wlr*78! z$2j?u9RiumCc88Dc&>5}#!BlKE)Fi z(<=_e5-JPzPImh@+iPsuw~_T`UhmG2ZF}K;4`3$iRTP>T4t8Ju+AKa zb>=frv1ly<8+tlk8u1fG5V7av(AfxTs@-Vc$)Sm88m&HZxBU;8L2id4g#C*v(lqnZ z#spV>U^1e?#{5x}lRc;5c>+#{zB8LHO+e7b8^89LtFPxJ?wqbqHiwlUL+0e-}xR6wu1}s7B0-Fq$>XOU-tmtaWE%(Dlo1pxGDY$)FPGJ6abimGN$v zUf_7K8)}%>j7dL)b8)xu?c*Z$(U(HpBv>ojKMK@Mc{V&Cv|&M`~#_KMMwGa~rv3*q2Et+*!@d zXFLc2oOlIRDtEvTF_9P?;=CuZI0rkO#_|^4a?m)3s@#x;RX)~q~kz%GrA z>OJOnA4LTGt^!cIHEowe42X}BZLJo0i4z=jbyB3eoDy|umV;Lz-T`&YpU{+@w}7=d z%Gw$0%lpwVWZlSC{}BYZOQYPM#d2ROo+Dmu-oYHQOW@5q!_Ek^7NGzv=NOBRkjpgX)}xxe0zzP=xoe_nUe zL!p9Bzl-YXbRVR1{)6{$V%Odp=2#9~&%aAXJ2*xoPF>E2emto(-TV=CLwy?6uu_2G zuId<`S~VNSbmQI#7{lh4y)*v>Hto zp)km_M-vSGVRP(<5!tUjD!Onqxw#A3t&#EYV7QAcCFy!qA5ee{EQ^!?aXlGH4+kT) z(ngd_TO+@oW;J@hQNSt7X^xFGw!D0lZ*Zd>;I_eW*dM!9##Iy@iurtC+_ zZN1=ew9W0gSQ`}H7tTM;`Q+S8oh9<3{gq=E-K(mOTVo5uxMY;hAqM9j{79^GKSQ6! zEmrHroJzn^Np#of*GyY zkpJ)c!{?}e#E%=;AFe)9oS{5B+8ss3;+3Ul^{toI|b zpL<^DYU-XA5=SzPWFZ=GhxRKd*pR$(p zhwsBDv-faX6{kO(geJH9!z)qlIQ`*gxPjdtmPWbb^oQ5UZS}R1D0iIxa2L6){xIC; z?y^73B4-!QMCS$P7M9wxCj4>{?J_si1deF{t~Z0e9V;pANzw^|G@EDd0^!a zL}9gR!*u3nZ2fOW2r(yisNFgV`uX3XUO@~J*r`^&8{}%8Prs)Cy)yFxYWe z<_MH&rlUY?lk?gglpTLYE8eFFrU6UeV(xgC9Im^Dp>jBV#Un>@9z{1T z4not`vbic{a&tA$7jDRgL8U>188h%q4SV?;;;FGl+#@5aSSiGzBYHm_wW4V`>ii__ z6O++*8<;V`t=S(57K5+}tqnxik|7{(**14BN9QX6Am@*kT_SRMw|x9zSd$MIz1C1$ zYg)V8{PP{=7R>A=j#tzkd4=rV;$Z5&i&XlU?zkW9-z2X#7;I&(8`#~9EYef!oNkT-4Z?$kCc%9X!?#`fq3i-gj8h0%p-oKiug`e}zT)b9Pt1tmr5sC)HTb|H zAJa3TVyr|&>~FVWfa5yv(LLf`ui{*dDvP2MVrc?{bn~3OkQHX&{FXcjqR6gC&a=>{Y z?3ZF>XI!_puCes8=L&sx(8|l0D$knXeSL5Z+=%6ns`j)mKPLer+R=9$#1Z9NI_&Eq za0jnXlbxNTi;!SGr=Z>nx{lEO3c}+l*#9|tCZQ#OaKj!8lO1Ns!xXzF8|BEJ;E(1t zco!KE_EXt!G=ra0IRVVedUtbSH1r)OgV#!xZIAi*$Lfw2Uvh z9=xzdhRbEl5y9>g_M?CQ1$^GuQt$v5cFc-aMbdd{4FKjhmJr<9CIHu;yxg7nvEloK z(*$qUvycFDt>K;`ZUcf#oyR=H9h|3%=Nm`4J&s%rc%}OM4<{-zU;ZGnITWH%yM>mpM4bP!byYuaqUk&60DVV9^_3Yzq(~@Ps43}!l7OUJ zS$h9_3BvOf^4OU+giZn(xOQ)D@B%zrXZaA7i@AwCxSA@0l$ zPl|hR$7DBtzR7DQ;LLS4Iy)avkKrEy{>#&>3`T5*uJ}{QkBx9C;6L#fd0*p;oU9X> z__>T8?!YCwZggXTDK?434~Ym`B4e^p-$Sz{YzpmW9Kbnl%{Xhfff zcFIR{1TGn&6@d2yp@8QDF)||gt#T%_oOb$av>fq=1N6TDb+{z;0QnRCZ~1>53;88o z$VYn>$~{;2kPF>xD97(%75VuvL)3g1xKVszwD`JyRt^5j68?0UF&lP794r4%hQ5556*{Oc@txV8MrV3qiO@5Gq=w3+P@j)Lm1)Wcn3yrvwt1k!EhIY(pvEA`%XPP|MvfJG3 zM|A^Z@JxI=?w{k^z6Cid>o6ACbS&iNcsJltj2-6n5SNp=!SEiBfRU?yr0Q6_42&}% zl=0*u#@_3b-J`Bg@$|yL+;A_Rp?ElYKhlpa37p65k0^VWtYfpjz`G@26Kts&LoscS zwHvFzV!KCbF%kh9cDdyT*u`iX%E%Y36InmP>`FA8hXKgaumQVjmWDkw4GrHPv^w8f z{BLQT-R8@S;~K+-A{(xzA*i})PkRXF(_cpO2PhG7*t`H14ZQ(kE!5)(T`Pk<*Y120 z-j7+2f9wkLL@_+4Kx0>gc%V{EMVq$bmz@^gML~Z+o6evc$BM04y{srcxQTMMnXfi; z3o@@AcfwcX2M&cJaE26a7-c&Fo}yAt@cP-d6YTGUN8_j(rZHSM$sW-*bHYi0Q$WXz zEDJFZHmsn&X1&;@sI~LK1Lwmyzky!0%Ib9^-2R4D?!X*A@WC^>=4KA-nPZYYhggS& z&tVe=8dmX8HYTq)&+#44#MO#9&g32uDz|G0nIaE~d%uVA9jD}P0tN$Ip5jT1EN>Tn zD(9bWhTW_^_YV7@QEQVj+v24$%hS#`TD17c{*Ch+tdDhfGB`60JsSaEYBjeB*Oi8fQDK3ia0 zcc2~%6RFQdr;#htPM?@v)#p>7UDxOMuIjVftLpRlk}m7RSEZD1=R*s@qR&|uPVI(^ zTGwN7^d+<_lqx+fx>>)YG%D+S>UKQZtdOrNyWY)!^~7;dOj%!^${(&Y#iF}kWKy^A zP4vKR=w+MDD*8|$Z*%8M+T^M8(|G4;aE|<5>Gg|#Sj>11zuvc<5}E{+qv5$&EF89< z>k9MmQxOUSr{DG6$$X5(=92Kf!)QuMgajP$gdqEA6?<^u`m$D{iyW(Y$7y9vn)9UmyrF-C;p0QhSaE)} zmysHq;5*D;_F~2zoDa+6&hF6ROw!1(~Qn=7j*%9+h`}p^98s+^d}G%!9vav69n>gcfzV z7?;cC(wc5JNs;O#D$-V{v=T%=P;H8uuBcU@%xQEZ7^%4*6<8xS!*gQ@1+w#wL+TPq zgSE-|nV-)-LFS!-QF4Oo&_%FQ=I3*ESozHTjf}Zrb3D#scBW#Dyt0G^2D3)u_w?Wb zhYS=KxZ@k!1!^UkBm54-7gDQ_AX23}8NT~49f$-!qj|GheXxRN`;8cdUIf5#-m)`~ zUF|XdWwIj6#0~zS7H>|FqEIs#4Cl2X4YT&ifWC=;ed8)JWbPhv(Ag; zvmQZ~e0=@1mak6BSB@k+oX?+RtKIA0+{xDwL#Wztjq!R69i(!DE;g%S|(o!7|!a4utN)-?9Nw< zuI3IlwM$cE3`ACS_l*(9Tz@!)tmHL&Sa(j*0v4}zi|+#n!ts_ zl*=<6O398zFyq^wp;W!dQ=1rpzD-{^l$wbL>Zp|bZVn1+p;BmV-^IA`B5JKS+ZIp< zk+1Gmn*God@pc8zVflFM3%zTHc{R@E=6L^1EC`gZ%2@*|;|Wc%R6(Gj9nb0GWgp)f zKE6yGesT=7;3!f;?+f(ZxgCoG-xK&nfav_mUXREPrDo`2Pes4QM%^lI)FqjFuZN8= zuSA)xBK|WP7W+Str-{E+#Q%wkB7Vily~825Rmp8ta&a`Qe6h&IY>0A;W94Rw+-Y6N z?dy=cSjlyZTsbFI5O|ngDbmkT(i38(f3l56c@}r^WIY_CH}61c_ED42->HU=i=;U5ats${Kn5GNiAF2&7oU@1_Z+@Rg}?Zv*3Gb!i`EZjR6>rj z6}2(<_mqCDLQL2^SBX=+mbhNFxbvfWK~O&SQjfK!lP}Cch_H-z%)| zMAkjHCIwn>N8r65KnAS)+FI-GM`6;seBnH_PF4Jx#($BVD{YN$!I%d@$Om@ zACXWSy7Wn5UQaOy!Gwh1VSj#)4mh~~ri6eGHHjLA}4soKU52F|B?7VMl zx3>ApY^wa7c~&wz)Hd^;g_wtEgY#`r;!>pqmd)qcN}!V)%^#tLwhQoO+@Z};Ko*=< zm%%ir2*q^9ya;A31n>UXYC2CzjNo^oa?BwV%=fB+f1~1uHL`4evBoeO%YI+RG8tZf z!98PGgV!Mg$(l7f@6jvxY9u4=!dOTLGatekb~$UV1>}Zlb};@vbj@#=aawz6h#3uK z(WLQk8z_5RMA>U%l%2g-S5}(tLZz%U-Q`GD%BpRhC3L7$z|eW44!00C2;ZdF<~|hM z`jPE3X)y(V8)GFY_-!CZL5D|J97VriU6~5o^RCiBL2&n({eZS}be4o!FnXaxr zb?VfqQ>RXya|(DpxZ0&o?=-wF+_?{4)d1)6P#3)RxAy|uV`{hLWIs;RL6pQRDfU$~ zQW_w*>f)gwklfi4EBs-V%lySIA~LI5r4X@CBNzVgy$>^zyvUJ)_TGE&`dqZ;8=B;- zbbZ;ePr>H-fuvUw8=CQrGC|XextrZt=$~#0d6s65RL+U+Kvs*t$W@otkVDe!Pu!nL zW(G-hxkjkgtB>BJS6^tUhzCMmCEP^KDL-Gawy-ga&DSXfq;*+-DkMt}^E=cUW@RwR+HkN9u0ukAp*OP9kpHdgq! zf&zI_?Ad0t3Fip;oNJBW$B3YQO`@Y$3KA>pl>OA*cnP66?mh^`)Y%toIejGcj^1D_ z7avO%%f)}ieundY*_fzAHaO78Y6naZ6R_>y=zgp=hgomU-ksTNi3Z>ab-=u!gIDkX z3PR?cIRUdjYy_W$ab0)eVtfpBcjPkVAnxcTW^?DG$Qd*spmHP`Fh^x8J&`ISHH@1O zNro{~x3w!H5VZN^nzzwwE^o{ZH+n94dKP#pIUUVi&E~{dIw*}l)m9RN@Cdo@Dv~W$ zc&bUo=hk^HI-F>R+Jy6hKpScRAkW zckzXF_&sP2?-Mj{)@9doF;zXBe-lwMFI0Sc1-Cr!;l-dzpRm^A*PzH1*qZ|8NL?{; z!yVW`nUVaEc~dum=^S;v1voCu#{?$tGE?J}26rQe+dbz3+-?ePm4e#=aN7&qH&73_ zUgv|`Q{XZVx(T?6MsV9JxVnOy4Y(PA8y?91`(WB1vj4oaDy{#KQ7(>KfFtx{?tOo{ zy$J@|C7KC031?vZ@HaV@|16z}r#=z7^Q1Nb zBQ39A=IeoYNPnH>yndLk8}PM{;E`OfBZ;#bz3P;D^&VdNXZE|qrYGPfYyHI^u(%V8 z7wo5v5BA?iDpE~J4{2jH#;1uk>R7zMWo+lKF5(QGJwCM-ns?MN-GFgrb|7SP@D?9bN27QieFK9v68p(KfO)fyaMV%*a(`YS)MgZ#kW^ADkn z8dl?-o`ACYgIrsojP!;>*y?aM*mwiEp9boFYL0Y;qfT(+zODNkXaoaE?7>)V0I6MXG)s3ua9?WgP*>H{G!McF) zzBcY6h#BcC#*(jvJxgn}aew3J$41sh;`@ z^w^gTLG$ixz4=i%R0$bBY30WXFxXW$^4wBRzZ%GN zl{)fMmP;ruqF@N3VWA-4KWi=sVB(kxzfCEWs zjtG0^l@)7>L}Mbn{yiX@pg)4@MT>cf>+p~+^v~vNq)>VSh$l|L!=TFa3ip9lavE4x zZQmnPxvW~9J$Ptp@yWt?3f0XLj%;7Rq4YQ=Qs8mR7RgG40DDBG)Z6P&EmW`>a~5@t z&sj@mAf|x*E%Z{Pu#^2EB*c)0(KCta)|*jWZI^-$^c(<`pz)*qH~<9;z6@Ukt%#@n zBpi4B|0Ix2J|NnJ%Y0pW3c#?JsZJE45KLx|qTIm-VbGnBU0>j17T)3%<`G+n(QF!& z&csW5u2ZA8Q{!}e<`-6J^S{`=9RkOO5LI1T%G8b5YULfkYeDPGj9|eIZEQIiufDzk z7zO6wAO3edeGhE5A26@z2$pKo5uQW59wK+K9$ViK%(OuWt$Yhd0)7?tP9PRAA7E8v z9)!zo`5L}rwmsX?d$Er@TsK?k2Bc5hKP{nNU5DkTmF(c?2vo2;vPP%4Fpue|=YFHt zZD}5|9{4x5FhD^Zc0)upR+xd0(QMl<7L%QsE+%M|E_3CsVidh#8FCAy_!$}8L>>AM zG?9y}lJAk-@zjnXgBTkn9UHGgu>Y$=lMAh$vaBYO!nyFIStXA8NU5Ejd{xMW#fi=~ zqyLIjCv>ub^GY?Ys;IHw;9yahV8C%@MNIPhX5gaGyX{_3W0(} z!^XNpVk}DBC2h~QFXciCW+}M68N_1=h=Q$bpbPx5D3eVkH{{-ulL0UJq7JGk=`LG5 zk_1YHGsPuq1G_`lVr0`Uu`U+xPB;Rs<&e5vv6DBZx{<6^>kH%7loEr%Jdczug2>Y$ zdO8QK0g!>8@=!Vo7Qi^EbLsF6;E;k(hi@0z0zs*=rX;RKxtz~>Mf1}*+Fj3_6&U%Q z1Gzub1rD4A4JZriTQ>U-g2F#z^u-Aajmr7WnH_`H{W5n(U?jkPSCBbThDCO-eWNM^ z-ckl9g1vShRdyv)pz*0I`ATBo32XHdB?A`^%n}vd9cc8`K270>&yj6>*FV zW;fKi{)-ss!Q@&0D2Wwo{M;B5n%n4X!n3XKKIXi$n)?6LY5`$4KS8fE58nFo3W$#p)o5%BDp=!K9w1bNR^KO+gj39#{^I5N?PpFW9Y>e+j&T z#t(jYdHaF4Dzb*BlT?+0xx46(sn>0%?Ax0iG*1c@e5aKwm+-=a0D+Dyo99#VT`H0< zRO_7kG07YiaX7AI;ElUa!Z~OU&d_$G4Yg-G(O=OA!+@b_9?Yx_8o=D>m6I4sQDe1% zk#6y@VI**%zE)NSMd8GgcpoyBsdNn3F+NYk6IW8OHF6nz7L8C?J$y5cw_=4sV5}6` zzlh!gsVTejb#hMHPbybZoB zewz${&B9@L@Eangx{AexuuS2?d%O-B*b0_T0u8FLgP3L?f+oQylR$?m>>{SAh-7%W zQuguEBZr=mKe)8ql6Z~Hh$YY2ML-{-4qPi~SduKYremcGmj1`~G=@3hslHPs~=dcOvE%8y>ge)P) z8N0-zE0DV?P`4LrPS2(24<;69{S^cjvQS-O_1r_1rZq63#GM19ly1TU6N}6zb9d-U=oj^B@AZ2`prlg|Keaq@wVE(r@3 zYh&MLd#TNWQq?$-6VLMlV^tE6HYCKn7c2a7t~=2R(k9xe0vr?VkEob9PQI+SKfvk> zUzPAFU>Eztzd#ka7RdSM5p#dptFC85@c$i1&Eq`G^;*$0=Hd&v6lpGMxol*=h*H*m z1hsvLbC<*DBbmE&xWZO{8X1Hv^(CI?;3fC^%6FLw4wdgRW^Aa+9(XODaT5|$s;UHC zYoOj>rj}N@MjcRG%~Vo*OTt1G(Q8!HN>Rh;FELjk0m~-YM>?>Q%hmkEQYmK}soB{< z#|{CemO$8?)F!s3Bbv?AK=&N^8R5_N{ORZ&qGfHx zO)caCtWv>((Kh_f&B$WRSNqZaRE2oA1ar}KPE!xy58_t4T~(W;TfHC__Fu0=>S=MV zC#Xw}-w)H1Z!X-!o%(8R>(xHN5205ImpfKEDt7HevAa?fyIy>mxR@^V|6fhJ?7{^%A5o3gvuLw z(K%S~QDi;aQM>hq;co^^9l=#~TKT`h5g~I(PRQ&)1Ncplx2@1BT6mx%RP`@`#g{WF zcP}R_pq0YMZO<_up}p(GZ)$#Lnr7AqsoLEj5i1b+X=_~SRro73_#_&jfWJ=~qQ{Bb zx{f zWp3^YGPC2d?%xiVS;q1VcNpn4bY{Ibako0 z#GK!5OpL?_u9n90Lv6yJfV?vQ)YwBY^MG58(lyPl-_|JVgpBWK&VhtVr%U8dShT@Y z8vywvK=x~CCT4YweF7jRqdw!zXe9nZN|mx2`yi*WI?(#4@Abd<+DHnFfGtc79 zE?j5M75ew+R}=X%an3$V*94TPrK=jGud%0A=bG85BLr>s(`++&x=qmLN$C8rY$VwMKno@y5ZeZQ#v4X>Jf)l|~41g z`x(y;&MLN%exJv29mj7Uz%2ys^>EAca7$c=w=gLr zpjhqIW!m8fHl^o&DW^y8TOc7yX|2t>+a0>2KXbK6V4;BWu}y|PBUN_ftQQ2C&TUJeNdM6m8>8E>L}b+xj+6raLk9=RzoU&azP;~&FXarA+XnK(c!>DWxy zN>;1mjy`tKx*;>zW5AB#EunbFcaAztyg0Yp6#(MaS=1t@mHf8g?cSr^v1luDHI5#` zg965|%;a-zFCg#TdOv#Th& zCv#X!6j5Eg;Mgu*{6pEwMMjEL|qAL1?m z1Yu^|VqD4;J|keg(@|Cl9FV*$tBJSm3BHa2%>|W}c1@sBv>|H*6_=TcT%X%#WFj7E z5yVCwzQCx#JJfgS?i|_F+=cN?zS(#?69}pS$}3CX&Ma2=D*|Bz9FiwnDm`=_rY`)> zt@9D@E@X|4*n3K3bM(H<(~)?I=2IuE~j=Zj{ba#x_uVEPDguS@Vr{#Z)6gvv@e3x!sRBmHY4^a zAmC?MHy^FVPYQbM##e;z*9%q-J5`&}idf$XtRqJxZ+6B_O529}@)Zt~ku0EKWn>E* z1r%Zy?k7ecFo;q5sXd#zN9m_T!a>26|0od>c*U;&fI!JxlAJB;kx_GNVUX^|pT4;MBRcr{zHCZ?)&&vH!OgNJR1ZCDrG zT^c?nC9g3C(yzP~>Rn`;AHwi%u`S)AyAK||+Fv?sivw4^9QLIEQS@?fi|+0kISB?* z-FS5s7krhuoTySs!}qYud^oczhUDNGACmN`H+21j;))C5-v zFKRQgc}e^c(H~9>=kd(1U{Pef5)a&uVC!-i8*-?Xto7PUPKO+E*gQQx)irzC+je8> znlYlxb2k`0Ul^}emJMO7XKQvNRMp+OYHs$Ig4VoEp$UjElD~Z{0`m^+-BPN z*YSOHM6=s9iOq_R$i%P7EX$9Cg9*BR`TEbh)|$c(aBfj>Zo)2Heq~0qc$vVtM~esX z1E@83QR6O!^pPb((K$hv0m@gFqZzlI#PLqK=rd}mGQN$@UClb-6I1igv2#Z-bg>?7 z!aQ`7^^SiN*P)cs!KYtA3-3mlNTH(ZJ$mPd|3E(-exl|d>=h0D^sEdrDqg_qDf37^ z=`l`Z^x@=ScOB7YWXQVeuCGCJ+%%xb`t{^PT(__zWXv0SNl<+qIW}1${iVRY5OZ%> zcfCNtJr!pl5cx0|7ePOQlwMnmfoT=8^kxCAq%MXFh6)x1jCsR9!1xApSN1~$l97jE zAdrDSc$NI8qSxiHnY;pv5bO-q(E0}8>WCY4vqh)QKnNPKO`QVqrDfA>thEs6uLP~E zGmtT~1ji(ApMgrUjL+dO9Q+wAIwFwxP_-;`|8AANU>~MqaACVM``I_@XB;D-aiv{s z!2lTo`;HazEbqIf^szs37*b~FcV76F`q(qO zpvq7mdm3NtM;}{P(v&{-Hk^PdhM&IZ|JTQUlRjpHo&UeCkChei!aq+JQL{3PeG06= z%$FU_4`}5~Bkk&uDedbMPX68X$(E;G_bBi=gWl7*X$rIj)O$m=%eBf(D|(M;p3=u zJ_dWFx1*JxiZZt4Q+lzZODUI`O1XrFaj_QPOPmdo+gW?^!e}cX{?9VNS|Ma(*Iwd|CRduz}F9~&!3MlQ3ya+pYPR^ zkNel>KPvp+(dWhM4*Gmz>LHo5&r;BS&`;*m7+OXL!MP)hc ztGCbDpeD%qUuUFd%lGT0`Ut1`5vl5}o$807x)SP3RNbqbx?6HQ(CgSJ){MiePF73U#I#2R?o~( z)elq9x4xzba%QS}u2VhFUwtDE_CUWSPW7x*_1y%7_M3T#*QmNLJ9R(NJc4}S)Lpq9 z-?&N70+JNTo`*6H&8_F*?)YRfq2x{Si{!fGXQ};r^26k^jCOv{QQ`Lw6QxW8(RQ2{w^$w`6hJ2->_0>+@UC>M&ZrVyHpvHIG+`2ER zy7^As_fmChow|#?x}#LxT&M0+sk)Cjb^qbjy-d~pgHv~Cs_tN??hw@V*yAvWP7L7J zud42qq^cJ<)r&pQyFQb;%bmLIQ+3-qb=!G$-&1v~ow{4wdZhS*2!a%e|G1=hO4a?V zQ@1u%ce+z|HtIHJj2BTx#<;XlF-CH;&pwk}lU$u#nc|1!yUE4LMX6_=kG22nNiuG7 z(Pz-QIot7q#wlA%0@e|nz`xa8?s&>pd@XO})U9^MJ;I|moUI;af7BDcZj$2JZZ8Pg z$)0v6YP<&MI75_62Fc_gBFt&o~@e~jDRc6kf1qefUfR6#_4D! zevS|&uCxj_rNCDiVpUQ~C7#Dzm1qYZMdK(jiew|KY9A?TuKb4DD%7>wUH1xNM!KGb z&rO)CyU)XoC~&F7VS2R~XM#pI`>8y6OSexG7#d}@Ed8MeOG|6LGyDh8E()r>0wfV< zL8Vu~Nh5c;vjwaB=9kg*`7ff9)%`-W>okb_P?~J8qH%*rkDlJ(X->~O;5b4ne*|50 zx=(w)-Tnt6EZK|RrY?y&X|)?f98T-*cK=#Dy4`P!I_zjwx2C$k`eiGW0Tu9t3)}WjR+2SKD4msv@Aw|D4pfdGggSh{AqW8_SjlZFv zG9Apivi?+6e{rh*jg9NmoXYw?{~7fURrM#O>R-{g{<*B;;IxF_bXDKnnEEEz_?wq7 z-Pp#HtUp=iUg4Rk`ph?!*6)WLoNi%#It!uCEmHN{G_KEaAp8Q>@2Tp4{Fq0h;f?EO zvx>Sp)6U{IyNHuGvcg45-4*@W>8w*)9vMQ_)XTkfF>b+2p9)N`fV zwQo*CLmkkNNFQDy=l=KvU=j!6O=FOA@d>Eofqac1K2!ZjBBv+L9}{yLq4pr28|(X! zr=ADyPYhY@tJib$g}}7l+$8dEj{Fso+J8XM95n=XY6vL036)L?T0+aChxmW@HlAq^-{)FEWSQEsrhe3tzV;}+uiEj6bd==)&bH*Z1WW@VcyYnu=a`Og)ziu+N;eC~ z5pK}BEhk{C3tx|@Cxj1!mRV>EZel$O``~?~8@xG@4Pj4Yo$IERWe*2LtU#6asP5@= z1QBg%E`X!yK{Lr74n9gEt3~4mwpXHo9It`oWcWw9*_c$!CVjjo*=O_n)yf}(yMzBl z{@RMJ?w7w#2mZgnUu{t3H}O|%EV;jdzutfDzvr*f6MhAMy$M1z&0oeT`{A#X3HJc} zwPXB#`0GeO6#hC6nu}ki?uWmQ1a3|7*9123EBI?wmwot4w(<2E@yu62>$#|W-~IHdqWOD(9WeHN=)5>)?X@R7j|NSZ z&sa@i%OZz<4+{+dRSKYqcL-=06uV#aG<2?W@IACKA^0J8|g6SgR#*URaaotJSpr~TqWf% z97yiwOtUQN%6fggFJ7uiWp%?(r59K%Mcg8`J1rJtCIVZXFU#NL^fTcBDU&N`-VcYy z0oh4}F_cJ_)OhWP^Wc3RGKb|bW~wK$WOd*T%kU02??T?%p99(j|F+kH9pbf-6(NKv zkAXtDcl79Y@dL1wCR@ zD#Q`B*E6vp7y876YMDS#C|n?q;bR>7C*A=F)+;d<$7}EXFfmHTMj+eEKL%^5o8scN zLGx8AliFkRLj~KQI>icgL&Uozv<y%OIC7`O{G6j> z6ll9UVc{CaZducZ1HS0cD&H}+qxYae`7ycw86mA;vYj>;5c7#sF$rRYSD`_0BRm`L zOw+->;&$Fr8@h+t+Q+J3gx6XXf3dZGXe|jvuduZT>-02OpZQ=F5!U-C@GXJK@&1RU zXjYC;B=us{ZDrSq_)t=<;r^F#F48J?&)tP?Pr!%&QG40JUPI}4ALMIj zGR8CUy&~lU9=P=`xH}1MiUN0(2QD4&AAJLHF~My?fgja<@Rq%^jQ9?>p)5AkT{To4 zcL|h^_ex(wUy+~-Rlz6^Z+Bs^XJD!)HsK@(^uFE$myY*)K5&l{+{|CXd$iY(yJpxS zHZ)Q-)KKo=t(BV)g=xId-H5b8 z+_%W1F(`?YsMznX{PIXE=b^Cu^znfEHGV-TDOo$;{tq0`l7I7!29u|yB~BatPwehH zpl9|Y7=vV$ufZHP2=$W}Dxtxo#T1JZd~=H-tm@k`e*16N9;u>N;mlQ;w=nVQJoMo`V)%VJlw>WXB z@0Ft}_G<6^?cn_F?ELNK{LOd%7CC=){Y3bwOaY#P=dILDnxSU@ZJ~Qya-EU zuN=lwAX2t7tgU?44W?E+56#CrxJhHzjkI8>TZHEhc*cGo8JNt=bv$>*b1lBB#czau zmoCP)i}5=jzp-NvEywR7{9cW3RwEn)k2>QgxTRMYOHRTz8UG_B9Gmo2unM5heTe(q zBK(7g0r}1QQknjb{i&w;q)0#^rH3UCrC;Fx4fy{{{J#AX2a zz1jPyAX-tn(H`x*Ik`0sX{_!$)EoGB+BZ3GKHDvw+u(llm3@)(X1;o}(tWeZ&U4

gKBo9#9rDa?ZFxt?2D{YRXXQBpAwlLqM@?$5z}u;kVSpyz6gb3bHNllxGt ztnY`DrJCFQj#lG$(@Dr=MZHqa|Npn-*;5cT|0DA30s{WON1nCB)OIJ02=>05HWwOX+%i zx87MwZG2d_yRk~*_6VCnJdH5h` z&LR}HJsf5D8_2BJP0kJfgZ^-)_^s-y_^bT zsB7>^wLMD2`SzgsCPCZBv#rcU07~5GgFnkO1;GIc!4OqhgYb1_j zO3A*+_k<{8D0NIYX+ME;3Ov-}0h*ma!4|%A(2$>a0}H5RLXZ53bP#u2--(IXH6YAr z`uKDz6!fLg_h(|Mf{05GJFLS}_LSX#=5Qr5esWcFpxY}B0}>d!na8Brn3Ibe=@aTc zN2H0VR$fT~q;x=fOb8Nam|agrv&@ACa$!axii)R2=V#+DCgAy4C~<>S{!ujPyFv5) zmIus#bR^|SHN9Yd_%>u;6RK4QtYPgTrU4DQDm7l{tD@=l%CT=iIuSfzuJ-DXf`H@; zh69aiu#jzgq%+7?E4HMb3v`w?73)?JA7ts zA>jnR{p6vFaAW@1h;ZI|FZ{lf?i9@Im%75ReKT_T?A6?-8f#$C%fP+~gaC&OL$L3t zY`Jvt$tlF={sAyR+9MBPr?bu)b`n&vDvDdkSpr#?w{ubH(<~rof|Rv6_|4gbm+IOq zGwXDGhSC}-bv8pmb1-OHloK>w9U%Kr_+7`>10yK5kZ})ZNvU%wTYY@6i(zwEH7+?q zuqh%~3)er^$7$kG(8cQR{H#coR;GSVa(~LAr*3^Sv%ZZGN4YLfzK+!vr8=;PFWEJC zl;CUoT$wmo$FtbFzi+*m$N3qig0G%##kqkEm{*}k?4OPP*_UG1t(((p@CF~}_5K0&Ahu&o=kRcfwB%HQSBiO=y|W~zLzY(l9Ib8`G?<+C2<@D) z`|KZ}KQ1N0hZ06At{rV3q6Qmhp&fKUS=}oPoM)Jwl4114nAia?9oYk*VsD;#C@_Os zjZf)uYd`%5!6I)7I>8QMo31!%qIA}}f@uyguHV?bv8%#8fUt4$jU!96cqR8-usi$9 zE>va2&8yc!%CfE|W@%&9Tb1|*XyVYc0RnVIUgsW%as_EGYms4mL;2B>)RYwulG(|9 zrbR|fF=5uZ{LsgQ>ib$CYxlz3guq7nlFeG&CZ)zK;QT5{OGH@-`z>kpjg}*mjcKlo z8RQq7SZ%iVU}~U9B}cV07URk6bTt}H{6vDp3U9=3pw2tJE(361vW&H?pn%&?fV1RI zV0`iC)EC{-zo5f}`^8QCqFl9+k^15f>0eyJ3fAo&2od2;v#!WTXsQlki&$u zc8*iU!bHB}AuPu9nI=MPI+>UwX7@!osb7TfSifoMF4zLlU~)2BRdc}M{p8bvNY-h0 z3nLA17)co69E#)g+JD8=;HcvxyUQXDph8(qBuSmVPZNpDXo-Ma;75OYkbI$-Q!!3ZRaSF_avJZi;=1w_K1+V?@Bec^+5cSM=$V(77Mr~rtUj3C zS2ZNsVw}|eQVwT7!jha12fgfQLDypKu?1TEJT?8Yhj5bCWd=>8rkbCb3QY_m8IyTu zj=pOH6QBeNmTF^1;*%0>&cQ*eIJ4L)M#Q)_ZWU*j)dCrTKhZO5c^AB~IB$va2P=*x zx-n9H98H$mgRkJz(4(P|)EfrKxarP>^QZ>e?Z@?wOjYh#N!;Kmv|&_HRqFdd2;-vG3ZB3fqq z1VcUWxZ+NQB~diH*=t|-FsuHTU}o3MhiXyn^hDn!i7Ee;s%D^C;v6(?FH04MSqSsj zUIh8CW2`kbWWAt2D;kVCPf_=Wx! zf~Qjby=&($^mh*i;K2QD^Nao6JzMp6Ufu81-+KuN{XO9jufIx_boWizrk)baP3W;7 znvWV?T#xyIcqQ>9r3P;4*xR+z=42O}86{wLWSJ$u7aJMFPqa$1m*WQ}ZD!;n*;at- zyE$76i6gh}eyS+CCu_KdsxP8y@*_3Rt-I$+`Dm0cVfidoF6kq!GECTAu*eOmKmk**ykc2fLZ#E zWaM?)Lux1M4uE2l+tK71Y;u@1$xMOByGq)XqRFJGH%c724o-i3Td!d@ZBUtxaCe6B zZgQ+U--W-f3K+|{WrYeaDTPAD0!%8AuQubd5ac?v7>Ty6$1`yHGG_PQ<{25ouh*G7 zf453ykfn{sRD#sxV6=|rUmL!X32R|bmZsprx97-&4=*Z)G2IN+j@dv= z$9%zm>o&Bq9y=rhcF$tt@Q%r6T>m`567~!a%cI8u%XWe#)9pD}La(;he+^|pmd#jU z4`7MzHo98uLN%6iVIZ;ZY00simN?5PQ(G$Z5(>lxS!!TTg94O3FmE@Ce^TS)3{KGM z`p$#RGQ8Dq1Z+1^?xkSQsnCs8fi4hbv2D%ll`WtQm=|M@bpf0Uug5wcs)7!Iv9U%7 zI-zQ~E#PU0dV0$7WY@}{0o~Ppn+ZkAs!OyP`Nh$_Cu-#eXI*sfwUIL=jqaB%AO@@v z&0t!n)@BrC#_SV&UapOMAEef1)CLBY#4~Ws0CRmr@gbHw>~NW4>K>$+8p0G)BO2m+ zM;(fRBZqbZ!cLWvik{ec!2T?GpxzlwZg?q+5MWIxz$$+|afYw=vo&9Yyk7CHlb#RJe58cexKftv0 zvS*E8_N@Gj#M>xrJRT|dLjZrL2mjGD_^nd#PZ9WZ2un`k`sR$Q1E(eOGa|#6i)APc zN}Cjvjf03KJznJMa&)?!Y?9)W6kdIS*IEzakD2~{w@pF(t3X_dQBE`m8TZpqC$*W2 z->YfRpa-~oS0d0V2yHr$+%JA9K9*7Gmj>_J6uj?lVt?}q@1_I6!#EeAzqMX}Tc<%h zJq2;9K;)slBv0Q@e*sSiywr%y!l6HbU^0SlPE5hOOyE6Ec=Lg#3(tZSx5^+OD8X0V z3)%Ps$cyDIO35o>DWBVmwn`Cd%8J*LpyGeR=8p5!XUWT3F$Yr!(`J|bD8wV6)SA2+ zYD60r?Z{R|B}PMR{duv)(Tek%NfqXRS5=m#s?^yBxwYW!RLVQU;wx0G7o=8cZE@Z9 zHpQ`J>q{!~6PKc6&?kWbG=9P05W%3d)}fI4^mgY{esUZ>kyXs=|KnrWf8lBNA2Nn= z7yVCyYCmFJ0Uo^;@NaPOMF&fu@nJv}__ith(~+k%R8_V(XaV_yfP8J@Zg4Z;Lfi=4 zzj$!}!ik|in(k23M>-5K8@~*d9I{lVD*1>fBrbt+04`C$2K(!^NyF3OPF1fch3TQd zbO&j+1_+!;c-(=8)Wj6&!pRsJQg*PcD1n{;UjV^ORyd4q^atf!r3qQ7+MIs~yq z6J~)G`KbYeb_cL7;&c)(pvZujcNgV8PHo zqKCR?%`U#qZ_lQjn5636gU$Ri{FY^5l;JOKC~JXI+J)`AS!8yw7SeHUyFrOtT=(j?P=0|hwn zP_ZaD@j%ux`&rTlQi)F;94HckW+;H(na8fkDeUgP%8aufI_Dl6p?)QoV8rHK=Z=^! z-QsM{06XJnjMy8_WI*F`s$#D}!V!+tyyj`vC!BkTp6BIlaz{!-)Y{Q(5f2QwR2^NG@tTwE3r?<2r>=;n0Q$B6@2pfY2{ ziHD9;x7eQ6!v^t&$nk%n`aARGm*l@wkT*u(wT1uIHJqn^C_6C3GxD-J2(74YqF*$k zOCwpz703x$ZE=}ix4xMU9IO^NAZx*D(loz^FEi5i47)98X7%p}A!y9Q_N@X2;(R>0 z`dKJmi`_Wls-PW*EQ`>CMiTdFwTH+lAxV*OJdw&c4rBFHG+@$WI;`8>2zRxx}A zHh~p-k5E)A=T;u15Q-N}Cq7!aifNSxF#XbN!Sul7pZE*@!=(EjN#+k?nMBnhp`@d) z1dT0v?z_5q_+ivV#901k)Z=ku2#LSfhj6c6mwZIqBxJ3@&6ZLv0bEZGel%2({5 zc0_4Z%6X!S*i$ZVX1p(l+?$EIIb=l8oWyo@vw{GEW>oPj(@8^y4;i8x-{NNlehz?D zQ_ocwJ6aDQ-I}pDm|N?mRI_^4FzrJwxkV*j%WUwtbQ5OF@XUYCmEj|~8DFQY@ze+#7APA9~PD7(`AmB zMVK)VHo4$WFeWCMiXKjNpvoeM-R|{VKKcPek;<%dnudLMvy8E>MGL>-QRH*cy0{gSTEyYwBQd@FJ~z z8E1wuS;U^%uOes&Gly`Jk83a0z8P^wa{q!8r57wf^xdI8ET{_^KRNRt zoEHM@kb(K#?=|65`M%bR@{VuylcFD}z=qOo~1r;c$WC58wLGwPNCCAUilV5x_i1;GMroT?50>U^`6J;yL1S`zc{j0x{INRYkG+b6X{zd`s&1<4rmAkL z>MC?6aUQAABZO6!26Z1(pM{>0sgJ~8kEzRnHn>jjQaUM}?ar0{D7O1NQ4UaUU$_O- zCOj>&K;~)CnCNs#=a4px2Pys=wLUsQE7F4av{-Bi_0RoxU@SE45x z;Tq9JM$ISpBLh8JCt9Mz>A1Z^_j5&Ov`>=4Vx~wsnIy#>2NiboTk3r3t*PFc>aAH; zk+>Hi{K@9Q=`wEM1`!vPHJ(@8Y(!9^29J!PWvfe|mi>yx!YDjfhUElN%#myu!7)#Mzl3mz;`$m{Y zicBdIzLXm))E$(8hS60{=Y9oK+5rVH15LqZmo0yq;KoD%Z+ryQCg3~Ypr~Q!S7HBv z_&yXGYn60>d0vb!!g_mNvQf@FZB`s$- zxmQ>ZgzP1MWj(+7V+a;m+ATmKsqq974lp9JDH{mxy>x2ZRZrtH%h?RYZFUxp3mkFl z)owEWaUKl^;g}?aH&qRSzAjfF-t>$z%-}+l%do7-?m2k`^vrVX0gGe>l6r-xXHF!r z*zPvr4Sahd-o|z})5>3Df01|xHqE>h+%I;+41)6qD>uOBsR;TUb2i3z;74?p_=Vz1 zLOkS&GfmwiTuE=KvO#D*M_y z0T7UGL<2bg?xy#+JYOq+o~mkW3sk+!yAkQz0KjoKXzet42a0gDl(9UveituFI~WAi z;#Z+m5&Iam-{aSVRbSc6(x*Z1vMLh$D-v09ge(1Pwy?&-&kzr#dME;{xtIhvhGZMF zfIJ8rrq5*T=tu51u@N?Em!ical3G8PBZPF68-|u&dpj(&S0R52mJ$*@Z;8{dlU8Dh zL$`$*2W_Vd1iWQsopDCuQX*1*IU&XhufYSjgU2>K@Kp^;9rKtrfgGa4CTUMd?%A6- z5l<<5m(LD&tB~azhd<8PC_@=P4y7I*qqYeiiO*Tpl7L&?n#gUJI_#Zs8+v1G-6P#_ zIqm9y`yljG5YQ7&9H%GaLhOkFFzCr6cyN010!I(kyq*kV6>B=FXwTb%&Xl1*?HlMm zZ}|wj_Ew;>2OTCww>U)o;A0;uum8s(YAL=H-rgG|9@Nr-$H6H)=y08e$LG{5t?6WN z`yAr26a|hwVVx2G7!d69Zv#Wh&xG1Fdxp(1qN{k1Rn(H*kv;}UVPavh?L(f1!XH*G z3E$Ai)gznz#%3~&;?hl3Aeqah(`6fs9@!IE1zbLSMiSP6%57N15!*HKc`Y3emH!*t>x3IvPF03Wg;s|kY?ea}P*&isGoa2lC zagt{swVIiAA9lQjo1153jOryWLRQ%X3<##`!MA{;UIES&d@agJ@zQFCa~57mp)dho z;hRb`t2==3A{cqZLAK&QBkNd{+ci%iaqBE`*biTzn-aFBQ&7-Uiy#N<<>j3Bj`xpN z-X37NTv6(8vu{OI3xCnMV#ZLQlnW-0jjU`nyn|VWZE4n%H^Rj2UR@ELC1CcZz;{x`_KXYtV0;UWni~FVb}vN3H>w&p_?I20IrmyX5QQ zWtK&4T z$e&O#@hQ+kf4z0&dewjLxl5zxhd>U0{i;UK#f_dxK7ajp8@2aHqvu|Yp4&Eh{uuc9 z&^?2qIfXq>qkWI>@G(|cUMgdUW7bli3)(v(<|7k~_yYi9*KD93%%6#=&Kp^&AVZ=7%UX|puCeCM(O%CU?5`XjE z92hHQhXM^9q9$rzIJPl=FmnjUo9gc|m__^Fdc5jRflk<=kYkD0QGX?+B#Jt3XEeW` zR=yNXdU|KCZY9>8@Gx+EM;{Q*nvP^MO0+@CuC#aFpt`uHfuNL@9lo9#c6lvz>_|@X zwv@h%>F3V7$&X`o4pqi}puYS=iz02}qSz0uw2AYI%2!5)_RNgjh0^dvCC0YIJ?Y~c z;Ug~Xir>y5>jVT$`H2IsXT(>4T{{j+C$tF!Nyw^jI$E0r5}@^6b~DO~*w(0*b4C0i zu@*(4_l*KjwGz#`9xKs7;0XUpwDMi3SXg3YT;KkZjbQP{hobgn_kzRYKfrBA;D<Wsks9q4lF^42<;z?etu(N8X z)4})~v~GbN={>Fd0vvI`yObX|`aEtF-kpA~l0{{O_Q--yBJ1RUE(9}F&{#`5I&UCu zbPjW|gCMS*WR^lX*p&mitL1mASG?vcts!39`RKIizw?CgMX0lfd0M-n(L9)YTqNy@$qIzkdu+gtm~?5fWi z%?%{}v$uRlzJ*zA7Zf79%|tLzbdFM14-J@OMKx8sTIf6Qu$;r)5jMeJYVqgrgPD== z$D5^ehmgZLcwteZzj2<7Zl_1_SBuZbBsnngF7*>nvU{ri9;Vg$ew3XTbR%U{>OXTj z`E@2noCsleME3-t;b8mKxjr8G z3Gl%q`{j>`9?ENAd2CH+7PMevB8MO`5X++5{v437ycR1<{64(Gpo*mhg1!o|f^A7n zt89weeYEb^ECT~hJ0ni4N^9&BAtqonAWShDP|$2!NZ6%Sj$k_-SVM6p0+?Oc8lY4$%tm>6$br;YpOq=jmS;d`G534ZVjrbY&x6Jgjubo`-E7h3HFPWM-rr zJ9(vp?iplNvy+Pe+@7+AG!n;*peaR(p{UF=26zGB)P|J<)@)@_p3QIe5ipUkbN0Zu zywF`fN<0cpV-8A4LvH=Q z*I6;0+aGcGl^H$xxWD3Ssfzxge@4}pA~p2Mcsko$-9*0?x8CgkR&nI1sO($16N~Un zxh?i=_x@VM62mXgnp?%0i(8iM&%yT4{^glhTYQ20^cM2ew)vGdltU*IeB#IkXxh$t zuU2~%->_2710=`+{$>(ARC_sfBMBrsw$C|SM|)x6LJ)T^7@cr$DK4sq1#c5{A^Upa zn6g^geq&g8RcpS_QVE&R2@n7R>UF-SUXNa_TMD+t*%cz|H4*3LnlV0Ln_h07|c>iW6pTMp8jyU&U zW32KCOha?~<`a1EBQEob|9$caJUYn9 zCy<98falW_G0X*vzh>WsCX@T*69}wOgv(poh;ZKg7k=NP91-E?@R0hq+hIshBC-2u89 z_Bxc}Ko_bobD-iT%nG2*z+Ifq6rM$`>P09hv4%`6^Z?XzVxNsl3WJrO@Sz(GFJbWZv&%SI2-=5< zl3J!A{t9j#hH*|6y+^q*xE@Lu3w{F5^I96A%7~j+Hbu%pi*d7O8@bt2i{s7^SJ(8( zw94Q>8$O?Jp8%={5kw@W|7G@!4}l#>cK)K0u2milg?JZXS~zqj$>K|){4g3_)@4Z1 zABR)6pii6aA@}j;c6$WGf*dMIq_UFRINRY+fzU);scgdopyd64&!bL+d_gMjvi~lt zjzlTJ~|zNn^6IjaK7x7`toA+ad;o38s&+l!ItTSm(Z$XOXW;{Xi_CuQe}*dV61Gv3 zZ2%$pI0}=`;vaI)Iq)MS5*t>g!vvqezN^m1p+_*9v0GZS_#q&wZf1Rx$MbGRi{}J( ztqII>@3DoqZ(!G#0epz*}ago*H?_kT!+Cc6+dq6AL|MhA@NJ}v?UtSTCFdboWREVd1^Rw0AUWP&#eE0Fo^Kbv*Zz z1Ox^x{y6g&$o4FmMOCux3aw;OsG$D%r4eqp0kLP9rlix3%+aI4SvikBx1U0{rBOV$l?Klj&)rerQKkNk z@!UPqAo}9DSDeiL+Stzgrg-k;Jb#aU@!Sszyh((&-+1npxFpfem6@6r&wT;><9s6g zY=Vj-*D6K$e&V_3b8SkG=k6dv7eUDTkLUjRUG){J_(GB!$8)ceTE7&}T`U+his$}^ z^J&xZ+>3g#|1$H^;<+z?S6$Xr0J2|b(kysl;I9nf@vA;@G8oD z`@ZD9QC6dUvmC1eLw~wB!MylDOM&{D}#BYmV11xYupnJd%6ZTVU zcpuk>YE0}aI?A|7iZGNT%(dD8? zE1!+yb}9Tx{!#RQ6?jpwS}Sjc}4al|BbAr4}|9{F$%HVGopYQ zFzNt{Rze(D4+xlZD%cRCUmI`$DE&mpYtSlTOe`(K3?B_>ug$yIY7q?@2l&QcM`SEm6);-{U_NUUvdx~kk&l7gT3DE(0jmY8 zu}!!R(4fS4;1I4zMg}OjqD~~up@EXXl6%V(n>3DV7DFCZ!5Sy%O44E{?t*!Xl||3M zsaL3o!f&i_2janl1?z`(G$zwJ8Z=-FTLAyH9yoB!wr`w?9ZA8b!?&CAmPhRbJt&~v zxlD~|;~;2OVV4S457KV0^PDWScuT)N<_vQx7&>GQ@&?=+;*fdg5QN2s%uxeK`$l7| zdt+>a7o5RK8{=UZR@nd!22M3xUgVr=TPIqEp9Zmpa zumX|rH~}1B!DHD$oq^(Tq9YrGkOVqAXxvfjFoB?M+(e$JPK|zzeaX40(YN|y^nVlM*P}%sLmWKGwYmVT!q59 z(9ahSg(Y^c{WcGO($tB~vbmLbD5)`S013Fic&NorZM*Vz0P^CYpcZ2Ki>!n+R~A*t z|BQI3^>|0G7B3#^xe>}zhokT|lD_Tr&zl+Y*-9c?7)x$#h%iidg^ZzUe;QtJ0s z_cu!1c&H9=8ui6PUC)Y)hnj>R(OK)r7C2SGgL0sL{aQBTI;+QQVx*P-(1O&N&ECLt zZNGzrmEZyOxXW&fB@Y}(sp@RD-#eOnjUJ#0jgtND@~RX4Iq=#bP#8^|c&I;U@dDy) zs=*mE0?qC{PaF3v1}{2m191%hDSdR<57%9^5Q-WA#v@YZR|%&GROM8>VydzW z007uT;hO4tduruJ5ri+MN(TVPSl?364j=8rQ~exkXseY^1!_Wfn#M4~9fSrGGw=t; z8W@PT&&KBDVazwb=jAJ3_<~#Z?!po;VNB{{u~s~E6bbk!$S!stbGESH;dc^O|CN+C zNWF78JYyD+*PD#HQk-=BAoo0j)Mr*Sr)OPpk-y(y|mf!24L!l3O&bUL`_k}vOKMRCEOd6g@MiqB34*2QoeZ+qd zR$)ba1wasLD+rBK2pyS1=(NTN-6)MBXy+ng#H;Q=k`i)^8!)y4ImO7DKSS(!;Y@8+ zqlr%Z9NR&aS~hVxdgOc$si6Dgwoby8&GrQ|6c<7Dkkg|<>wGZZhP_rgQi?C77rl=p zS!Kf(E4&mB4q4ZNrPIhd1?@UVgZ6{}LPsniE&Aa@u99+_p2{+a_jjkKGJhsk;)N5# zhi+r+7j}^=Z|xU4vqgEF3C0vj@F>_sa?-bb@dyZHqYTJi3RfMRwbYfYZvwnI8Gi@!)iJ9$HT8?Cb1@3Wl;LzKPB%KRIs@ zT5)fj8k1Z+dgE4xW+Bhevi;DlSnqC1!IA^cQuGD~s;9j!+%7Zr2GsLr>~tPTOO@8F zf?jkSlW-ud7tafp(@_oinBPDzCbFQ(7_TZ+q7Ytv z3o*uQ@;PiJ-$cWSYf*@{PV?Ftme$rY^xy-I_8@79PqD&Gukw{?l`oUZDi-l9)-O&K zs7|^<&Ta|B5;&X(A?7D=bdrYHSU;A}`yLXEnNE=`hq#mIZ@&g;W7DA|jw5Hs3a>ca zrQ#`R$o^e1J~6Tlj7Wl(#ip=Xk!sMDTei*y+X*tMQ+0;}PUX8F0L+j0d!U5>`4l|+ z{o8Qy2DE`n@s?xE-MH15G(E;`#J>-mi#LcEbA#?4%Y!&L8|3A{P6(34R9FWbC;A-5 zmE%?}y$rgOdvj8;cJgQ+6K1TP4agb4D%OtINOQ4Ov37fINX6P+NZaFV%p=6wwbjNk z!brv2J$D*b05{%_*u#A!>)Jmn(eO?g;rSP8UaG8?^G)_~SMm3LqO|_$>RFu!O06mn zPU;L;E1&MxIuy02U%5eJE8y_t_WXchaz{y*Q(M7h!Jsb*TZXF=tcpl$YjkA-Ib367k=7!1weUngyEp&IHeriR%SR znXghwegIub9K-&3@q{;AL7e@ZdYp?Nh#Qu-`ynoMYO=IFY5;%iCw%lux7J|P5)~jV zp72D`mi+A>;cNf9%LQ`N;j5o>31$0xt~)^c^oo;OHfkk4!iwg!&-wZf5S${W&1J0Q z$6}!K8CmSk17Y!o3xC9cuo&sqx`9}P1d9@pU?Mk;aquYLhZ@j}1byPMNwD0{XsG=K zsIjB}0jTlkOotk4P%E(z5?bb)Pa*go3oUl%sd&m&s03Eq(e@;KDkq9aJ>EE;GJ>y& z;z=)KVHk`DrRVwKY?8*xIghXdX&g^^H0&4YBk-n!D#30Qx-=Og>BUoq-L7qyoop#PEl5qq{Kdw!0SGgB@I1fsH`%e0|l3XCw(0S=^YtkR-pzp)#we&|GQu^MGOn*F= zkIKKQ2PQxD!7pEP{Hx@~jMLoxO>(vGd?nEnbV?#Q9GzX~yDPt4^Sn|is{jJ;Cg5G# zc|c+aF!$>l2aL~rNt6ozjQ7W9J^*gqzbV9v&x~KAlo0mp;2TJa-xim2E6C1$gn9pKNXvpE>woCq8o+eu(5bKz!!QV2jHgd; zO*S2$S@0~jEREwc1IAwG(gXLBmoZz#Dy=fZMdwNcUBGy28iZcJi_aW^b=Zy1q>}2z zXTDVm;c}IPI*wyETsu78 z^#z`^(2ip-X)Y|v2=wTUc*hy+r^Gw?UbnX{?6>ht$v>HAINM5Pjj^=W3V3|Xomg9%Y*3n)!Wj`eGhA{eY zFzxrQq?^**&se|2NJh?rwTg_877&@TH=%L6eJ2vDH{uwt%1IQmRoa~uxQC(C;yROy z0V+9N$|vinK}``BhjVc)H5vDa=bZT@ft!2nvp%2*^3HKjK8PEo$-p9St;`J<`ndw# zm=BE&0BHqZ6f`BLDX3k9b`XY`gU`^E*|8ah0)dBgVt*b}z|l;RT57MoXlYt|Z)H(4 zbpk%?@SrB`@ESn$Ok5keCNOdL58#BvN4_C*T9g-{%gG((8HTr(KC?E0gDgCyDPm9hoQ`l*@p3I;p( zBFrtSqzEOof^=5CD#3Wk?Uxu3nhD8^0_juPn`TW#Eg1RGR$sU zMIeWJ(P!40Od%si$su3R<%jvEoz)DQ}CTBl9u07ed8Gv|(v4ZO(FB@Isj| z@9#tg=1u1k&d5<_oC9Ob%Uu)OojIx$SKGllQ?PpEVL**w6SOrU)jp`-!BF)%NgqI0mX^fW;@>Gcw)=E##O72NUh4;gvm9CMzPE zy5Dok|HIvzz*kkA|NjXg5EQ-9f~M9bA}Xj=P_aaaB$AL5y-{2cx45B5weI%{R*_&5 z<@WR{?pn2CTU(c^w2ETg!Xg2ein!qlBFJ1X72E(<{_oGsId=)c`nCPPzQ5nk*GqEG zIkPs$s#hzA>n>T-F2cmmx2;{p`LPmI)$@D|oYNQ;X;x#Qkx|hW8 zjd}_T**LJd+BF3=i?V6XP8H{;a!Q&vEyp@e2x;dv%`|6GZ2JK{ed*o_lnjlHvaXJs zxv*{z_pUUz+!?%c(~*kvJ}du(uzSEQ_a_!Sy%|05V#CM*slKWmfStS)dbC7hDk-YT zj$3Rx!jWa}XfPb+V6S;~nb}GNfpYrtkA(#|fuX-wIekMPQJ{9Du3(z-Nxvp?OC)Ovu)Iv17gES#Zt0s;AR5LA|PMz1EKPY*5yLZ7xtfw&aBMO0xCN z=~!<{PJb1uH$Gc$;dgz)@ht$MdE=XqQ?F3<&g6xp9E!}0jMzz+RQMi=kiFazDf`s7 zeI#5?3504Jt(gVL&(tr~k!Gg258!l^KWp#8guOxE0}1SI-b_DWt2i+hPClBo?pBIF zlA}i5ftlvY6?E@(`;mFWEVllwC3>?RWRUt?-ePm*j7<6blyJUvCSCcD;F;8~d6Cm! z`o7$U7dai3`p9-+g@cVHImj*1=RlskMKriL{hIq+o<+Yk8P4T%dcON+`6{RCk^1($ z`)2tt=i34HTk0~X)n-6uJwhbw3XfDLFrz6|saf`Nyd3aTy(pRcEH6Cwd9M!7zvY>| zQ;vU}y^`x~C?Sls^Zgx$eba~8(1Gyo9$S#2{@7Ds++)R4{)h?uloIfgwN3n#oz2hb z{G8x^PUGh(?&nl~$|g_YeV`$0WS<_*mW<>%NLVZnmsg{lyXAu4fxJc74lYI5b_?WQ za?ow$8l#Nug6rA5jtDwafAwa3W|1OIx_ zyU4z1%9NM}pbkb0pMW>z)_bYuNa5zrV zCkGu8p~<^@X5NQg-L)IWtYq|lpKR$HqFEfL z%f9SGuU2P7nfjT$&o~kvs26{RaA6*}3E{CwFPba8Y@NlxoL2|C5j=iuCaOIDt9)6u z{Q8dNOM>zZD*v@>->lETbW6wb`>M$Rrk|?L&aRI~vUQH`Sf`R^1yc&PNDXj(v}DV( z%_V;fE|HAQ#A0Ts&XKOp$ZQ>s_vF`^Pdre4w5t3Q3Jx|`mS@YuyZPn2xN%r^Izn}{ zF@ZX(*7XVJLpNOK;Z{bU`q)|J?c_99KAA25Tc{zg{6j(cPvDi5JtZ!^RXd$FtQcKz zooKaoTKN1p&us6~qs)x^^cgeby4!LVm>px8t6kMhQFm8~` zc~0%7ue3mDMi@{9Vcue4jtZ<`I&$Id-{IMwjLs$)OLe@l`czPzTYpA}=LevO-0y`Q zzUzkT-0xe^|HkKIgLT~!bNH7cmboQp;1iUs4LuV2+x7&l(yk`&IA1h2d6jnV;9?Kf zQ}WVdv8Sy@Cc6!9Os}aJp8n5^zvxpiul61UQ1R@~_48ipEWweU232A3^J}_(HTY+g zWZY{xUhTDQ?)^l$YxC7fd+mI^iYD$B1l;}5*F+Of7F%%G5~?Ca%+yy_gcqMccfeJJ zAKb(z)#Rt_z~CnUhCdO(;m>K|PnV(GHD0`>8f$O8C;PD~gvu|zKp&m6IDrBtWo32o zbDs%-i%Qz9dFG-rpeb7roE+q;qGGL&Y7PSSdcT`cgkx3jKhjNcEYtlO5npj>w)99k zLKF*HueB}G;sV<NMV6VP!Ff~Kye;NkC{vJ zBG>G0C5w%EnTsKa)HZt2T)9=Y#xL?~)TznjjKkDNjcOd=`dIQw&`0c&oc1qqr9~TN z8haTC=@{ zR&u0LdNL%Gem+2*dUQmh2$9V4OMVM57ciPDgVuog?ZlWW=1Vh6!9~t3Fu^ zEptfdaeO0A8T98AGlpsJBe>B}`C}v#4-=OB!Q_PLzn1a z-azY`qA#w`pQ1;m2LFws#<2!?5-adp8t3S_q{H)I_uNQ<)a}3dZbMjCe^q|*N?YH4 zzigxLi4}o9B3xhG`Y}Z<3*#Zxc>$+)U)`r5z9XO4>T~i^;uollM3MQYbba&OGPD;M zS;tq0k!`XVSpXVVn?WLjr*kGfz1%@5eV5aJai{%X#am{^FTS`#|A(o6Y@0tPa^X0y zGdMIetIY$CDB6gpM}TW z;(ioBAkc?#2Un~Lx$4#Xjs2oY9D<5>F5W(rbHRCz8>S$8b)KW%pD6kbQ>k6Xdl&Z! zU(E@-vVXH1@4BaZwOJ&}dxvU3W&Su2ZDGm(+pI+^;0zd+l!Ed8gaL9(1Y zUGOyNH&LME4mG!a*>DeiV%2jA>Jv&@HhDZr z9=Vd}r1g{D6peHorFqk0Hh+Za2meFq{}uk(PpJNp{Ie3E|2_ZgEXDNS z6J@XroFY3|{lAI3jhqK(BrYsqEyef;y` z75_i-&#f&Rk1&^ikijdeN2BOUs!@#cNt;*oV=F{k)SrZeMQXEufcrNiEmN%+$DOL3 zAN9{S>7B+-^(ql#O_z0TZM&qFHT+U%iM6)H4z5qMH~43kd;Y}v4gRm>TYlJ3L8LQX z9~nXJ<+sevNUqkl__OvdHRDwxf+k)55RH`K$MWInsunVnkT>q@Nb3%^=lFcdFfE($ zd4O{M^#8=0jFU}8l*(M7UOaG7j-&;?$yzpQx~zL*J|Mn5)sABTt?3fZiZiBjyNGSN zcBXbY0qtPVKZymy^N{r<$o?H$m(f%-VQL5d%j>_`0UWvdSzbQVkAKYh zQe&-c1TSL0Korkx=cUwTRY~wy@>0)b_ODNZm*MnSJY@xpY3&S@o5cDuwlUP;9z10E zy0*=QRGX{%>GBQ@GG~ZUf8unzFQS(DI;E_k;+sgzE?`9463&~fnLnl6g;QqQX|NvU zN18rOBQwHuyq=mSsqCh5bB2ctoajd*PD`bB;3qpL7m+GRbGXS*yF@r<}|jv=>=Zt$9O<7dd!+ePUvXbhtSm zGQkhVo2xD0IzI2^kD|%_7d9mOzSmIk;YB}-CO#WG^%?D(HzO#CRjHG?GU7gJNW}Y9 zH?JI4k8PB^LPhEmqquXnw!A)B)0ZA(4B8)~Fjr~^d&wy(bV#x*-x{iTH2|DB8_=cV zk>)=Itz2L6-bGv0`v;+bOU%ia+ZPwEHY@lARhV-`VPI;IiegEcp(@f|D*`Rxucch` zSWtRcPxKhPEwMm_=Ih*IdqhJV@+-y!|W$n?l}> zAkWg#Gm4CxZWQi_KgD^HQ}r2ifV)xP?r7m|6u668B$g6|_mbDTG7W?IRFwliunWk{ zx!rb7a6iN2tWBV|5Nzb3w}4%rya2sd@=NI5645L4zRq8Z-ghtS1ii-wrI$*tP@G6Xd3^ukqS1gS6lN|H6iFLPTI`4JaxN9(%Gm)?UXh1j|YkZhT0>;E^q(BUB zx9+by(F-q*I+{OHI7kpJVs|ls#(&XTC4$ zcX;wwd#{IZqKUIThF9i}=kcpt`vLenIP<0|H3%tW{gH{$r?CN2k_STAqZGGHNNY{PuBHv$V4Fkha9o*(?R zdyXcQEqC*jwt-bY!vau2`g)B^&HJ_?|Zm&+!w9wAPxTcr44>LqBM2}%H}M3rH9M=XUCWA z@3`FlI`rZBTQ~Rvq7|RUuAqyX)J3FaM+QMh7x2`OyqxiU#wisINuer@XAS;nw*C3) zmhpHMZ-Kx3F+9!OhdyNF8e*o9hescJ^Z8_v`(h5ifa(o4r2-v)2Kek(LL8dUp1iCd`eQGUxg)gZsC2sf}01$AvSo zJcSg@+~Vr3Z(R_%M(aT~yn>(m3h`8Y+?lDZ^wR(NQSUhHG$cMJcu3m!rTKV?@8;HI zm&KQ-cA;grt-f_Z;==WleEFGXGA*W?d~bd7f(^VsfBhsjR$!UZ+1Q}7^b_G?EThl> zEFEi;Y5x!LZx3+(?dteJ7XL#UXU0EBDaY8;d1$|eHxi3l{}-xDTW;%l$L==$+R7{AR5^ zW!^un2mcB8dCVyY!}Fs_a&i0DH`y=EQ}`40eeDj`&TDM@sNX!zKE>O#Fz6pT0SFhu zU(=%g^;7Ma+QpD7WUHMU4fq42rWuc|Fmepmuwz-9v+m(=9bwVJS2PT)j=5EVF=?Zi z1A!eN$$x%G5XBVmSiIK^5oNJ(JC4mv_L>M-vM5u!e~~+X`C}~?Z6GVMrIF<)zy*Tl|b}xZ2djcMTS{oR=O=% z$146Cji`weRJ!^^TB>f;DsU5k6v$_Kz)M#C>9fKD^9CGP-Conz`iBjPz4{(JuWSDT zyS-|Y_Sz)WvP>c3tZQrv8_Xcgi;_c=(On^zu05g^Z5JQm^`BoqYk3iwu3t7Si|Qk_ zFGQ1lXGM#4iB^0VxiVs9cRS|DI&ann%p=hBfPhQ(vUUuUZY_qJHBn+y-LFJ!cV2yD z_~+4NY(Sn7G%s?Mp$taQ7yKzmjGC*i#iiz$z>e{GmuOc^Rj~J;55Bk#;N_GBZ7!f; z`3(0O3cta+%{7vGI{Rg%*#bx~j?9f0$iNzc4QFkjXktu10N;Cu-PY=8qYmXwyI$ zp!LakS-ni0`b5{hT4}XK_<<7$wV2glfv0jkF~*JT=wP&iLp$11qx@xno)=FJTAty{`;{;^_4J_MQgs(#N={p@g)(Idab z7aqWi!S+SuA>??^-|()Sccqzkh0l49+btAh$9D7jzwA|fa^a;pPFeH3&6Nyn9Y%wO zk7`pN81Nq#)h7=t3{i{izlDyhTh7)dpN7`8c6WDdS7$d--Ju#HTWscOeC)@zc*R40 zKdT^;m6Jb#C6}Kg473LqkZxnke_eR-HfrY(f9O(-i$W7Q5ByiW6aUEE$S)yo2hk^p zE1nP_ZWN3zU8>95kBax8ABlh}^j=++hlqMSL?@0E5v?|@nlMUoQjv^m7H4`2;kb*p zkrmW`p22d5{Er$C^&w%3WhR5@@8GCzjP3tbh*|Q;_wt&*+HXl;tMlRpsJmyS|bb$r?)=rgIzjRqJKNtoV~&;?MzJ0ss;x zR7LUPfXZwD4K)UrbtONG&PIM-%|8+Y+gzx> zOU!o{{l6(cuhjT9B|od#5o!K3P8bN~=j$+l*SwMZeCd~={2Xg6ER?Jol# zUA)q~V+9VkSm7+-rbhZV zPK)$sy{rE@ZIS-*g^~Ufm*!l{W$!rT_*inpj+m{4drIq@m#%5I*$m5RKiVI&-(6Ul zJhAV#?X7*$uLJntCEdMQ%^$4slF4#uYPp0qy=?UcP8%+<8z+-D?xas+)_8^Q84!lt zw3#@$&}yi?&`OpVF`Rf0FL{PG1vbtxpCA*^-`0{|5#E!d_{99Vay+x!iWHf^+;$W; z-g#g(Bmm=E0(qlX(LHiQ8wP7ZPqa0v;I>!K7V96 zQ`P%Z7QQ)j8mXN<$K^lvw^j3mc{$h77Ay6S>^JM9E?yxg=eJS&0~e*g$i<&6{6E5P zw^5NtkHPr@$B{qH#`#z}*o*vip}Y_rq3%;g3*sDjx1o#mws>M&)l`A(_y7I=+21$I z(!0DYJO-#eIjO{aHs-qxmQU<%t0iVXxJm-oKO4=N4}XS!9}@ktztFaqp|L!A)p#@I zExjj;%l=Jyw}tZ=MK8={@RAMLl2>7lImmT*bDIW$SYUOn_gSZj4+rhSJ9C(1u6Bzp zG0nE(O7lG1mp6hx*|-$7(+}dabDJDgjF{YbdYL+6g@kZfwpwBeEvqas$5|labgx4N zOC={voT#?SG}7BfU&rQ-=UhpyWO4W0@f>oh9nVG2FrLd9L@=I*ZN-)5>tCve z47~}z(nr-=d*k35zRKk9*w8v@{BTyylb08pvjm#mMG$GZ0hHDx%4=Mf*5rh))y;Fe znp@C_M2L0)r;ByGh&G@E>(wXkXadBiH5D4(gH|^Uig53`9*3RAV3K#Ek{QKCC~)+1 z0A^QwF#UATPe3NopH4i2p3|=usuj%Zk!J4dSug!cVakYloK>Az*^CFolvJMG)AHEaxW zskWvIe3);->4hBP4c2F6pRmhD=0O5Xck_=CWhO?KBt}4&%#ZAo^`5__D-yvj@eeEU z`F?mw;uvS`WX(xh+Nm^!h@{yo-h;nQjonL5*RAH5=zY3SYCG6&CV|JEWW(fw`1FT z$xF*o%I0ve+R_&PS$*PN&p)A*Z){?2o{J(dfdXOtCzPe1%hr$j-ARNW8w>&lwgCjj z+N@NUisxe8g7a)q<+DD3p_?P%fkxKRFc`D-A@Yj468p~4cWBOM=+{SCW8MePd=?%X zXPGWGPP(?Pq{zNd6CLd3swv}3n$GO;UGsO{z4p3*9O?p6th0nPen68PESkXJ%^2o6{==BH zf{`)FJqY1!^&IcX#%*3JX7KT%|h2f*KF-n^V5a|FC?~ zCd+>s*{b`TP=1LCf}KT8hxaH1Fa*V>;96(W$657~m}lPCarH!zWr`g9^~c}Mn568) z>nJ{OhC9d~bF*tHnB0x@RcPM|G=aED@ce`P@y66|)LIVz3!mRRMCbom-%oMs9Q+q= z5}#F5GV>)Jka1|RZ>NkvvTTDF>7*Cta1V;~XkJ#BnAN=WyB-Uh-!Gg}$GZ_d^f-UY zh#ry{8T$SY+T*xJY1pR6R$nhM8dY-)ls|&MI)pKrZ9>Pu1ta)d$KTQVU7pu}IDR?H zD2~qQ!lsPK(o;BJW|-3`ICnZvYyC-Zqm{Ot_yF|B{=;zdQa^oBjj_em{DMtEQIWg;_ovIUWKuP^NrrUS= zBwBIKd~QdixP!NL;D+?ec0X=6oagGu?d|E=u6_4>U3>cPdM4*;x3Q6ZC~vsvbG{j7+$aS}1o!lL^I zucCH-q=hZ?oSZp>U7sgO*=h7A+XhJD9%(rp;HsYi3k9itD9B_5_JG{d_3@FyH?EeOU|anwl&?prF>a>d1}lsplwx zt+>V+1%YjAPU5ZI&CI~J41hd@cM#_ZiG|YklqVR$Za|I$&NF-St+9CxQKb+bwP&^s zU)%UlP#zI8FQv-|^5q@t>u^M{t-nm}^MRvFVx>^DTL2I2vZk-Pk58j3-+5Pz(Q9g; zDRH7iwCc!#m>Of5KG6g`+QZb0oRgAm{@Mwxb8wI z(++uFLIe{Bn6ts3UQXwwBFO2Zt#!;~nx*`t1+2ID6XAHR8I(GVN)F%fO?UXF8xW-i z^Vac8Y?9-Z*m&^?o6790E;d&mWoLCUvnqax*NQeT;bmg>z_yx-k0Py~Gi|{{TszwG z3Jou@1keP8#J#!=*6>r$^KM{UYA%1O*<_$OPd^dxV)_r>kR4U%&wSn3J~ONyyJ;Ld zmH1lMIJZ7_mjkn{g|_EsIrb89!LCH*=8Ot_cv+Nqms4p$gL0m&dHq<~BZJPf_qcPP zJG_K{=Uj5<*LP(w8th)HshFHGiTVmmxcDFSf}$Ik6r z5&dZi00}Qa7294zi0$kXO`6lyOYF!BcHta5XyNOrV%W~d ziyhO?=fry?u7`Gul@0A4?+KRts(#MS1SJ9e4TJugC-p0c^%|wk8sdk?4#V=KDCyO} zrT)v;ca$NAWUpq^ZD=9;1lp`|=lI|F5K&;YTKycvKO31&*_*&4<*H%J+}ucIqY%+z zg4oaGPFx<+|Z&}UmQVv!RWF9iLTd-RK` z*uViqXpS-s#+Fy_A;0JMmjf3ZvyS`U%rH0pKn@i5(m1!&IJXYQIld=2%EXSfH?S!u?{rf`?dk&>h!V`i5Ste-!K1n3~QPTg}==j=nYijQw;C z1roDuk(NdAZJRD7%+ixqjj{pIak2drP^Y5@alhIK>5*r6~YM{ov-4+Z8{m!li)%7C0?^ZT{J7mP>iX>T-bmVvRHlZ1ms^$ zf|NM3Z5TE63(yhzr-_%Hd)tU$ zSQ6vQLjN^*F3&z&OFhS4ww8L%b7(&kjt;IV0Xq(9=uPuip`DnPH9yhN7K!7$AuA$%;Bf>8&5Nd+8KSJ zj!!?yc`wgpdNT8L!Xqd(>@FV3X-`yL3J-#4%M<3|GJ)BH0#JW02^Mt?}+>r z@8|O9QS&VsYIWWCp9Y4;Rs$ihs_6p{8a=%Z!)8nDd;wE(Ug%Hd%_)Ubllvi_Z{@-_qEqN8-4sgY!7n% z>0kTUCC+v{Q2uLduOoS#$VizUh-2jGZ_20ccjXChtE_y8Oxf)Et@snO$oNcK`*7QG z`|zG!Y+;)~!^u<4kCn$kd4!8Oc2iY?co)2zv1e4@txs7^*)?|Vg}b=9-afF%da<__ z9$aFMr~^>`{&ED%A0*O4)+~b6bl*X8``KwSO4LxmzjVD=YBO`N7Zz(y!)|ZImm{5j zy&k6|H9D$8@lA}y`k}GEv9w~grhNJ@E?UzOJ}qr&fyBbtEp`aHWyH|#vC{%eHnTpp zrNmfr(2^J2I>nuJ8`-f#=~~w5>C2@estOqE*vRTOGI7_HVa)wByAtE<%*;n&BS3^V zf^jCvUJ%BNb<#^mZ`+5v@Lgs#M=Lp<*~%ko9q(PvObMFZaKxRh?B>JH=;T#8AMJ)5 zkK^Hy=eKz1OoZa(x%y&J#pXLKb(!;t8MlbJ+gtS@)FM>Px17B6{LQVzo$V#7IFmGs z$#@x^S^UXkG)3Y{iksKCBLEqu-?^=W=c|I|Esh22eP9qA-~W7}jT8)l8iM7jdJbjD zs4#CZEdAZEjOH8y5IVWeLT!y3_(bHcO77aA8Jm+%hvRqi-MV(dRwm_u3Kq!h;+Te* zne?AJfKCG-HFY1j?cluB1!z7m3r`2{g9f0{F46b?PHL4|b6 zBZE1a#ioY0Oq7)hWJf~?`Z5{!kOvCx~#4c|; z3r7UFy@V?xnFY79s##DW=}z;^!5ZyqvkpEH>h3%=n1zn~=i&`S5k51%IAQe3PYZKVuSf)U-62LG3Eh^HwMKopt#}_Yce88JT~OylK6J%!J)my z4Vkh1P^6{x6({yBiIw|D^(6Uq-1rwU#&&%$3y4wJukmGLr&^{^yi6yr+Ra2M<+cv? zjM+VaLS|J5{ov>?XS}yr%1{u>j#rTyjhCtluOP4U#`mHkDeklLcRWtzR~!uBAtA}x z#pEojsTkffww1Mwt&#Yd^FzoKz_#>nqC?IrjqNwEjSS$SQl6UlB>RUlBt3y66SG(b41lMW`1n5Ta%7_4uvRR~AJltK*SrV6G`IlQFl zOEy3eb4?I~^+%NRw|sn^Gv!}ddJoIoGQjR>3;vd3kJ~s^q-7td*2WQAcIB5p03z#Z zj$cBAqbb_Ahua>7StiI?nv{7QVIcO=AEvu{f>$3PiEfTbxF1!F@qI1B^I#XhSz z?!7(#+mCwv>J!`d4U%v-Nl0rEIkggclt6+7dx8)NpkAKV7^_@q#vrsZ#%oGM;n6P{?%O~c0H@%(*5*>J6G zAQz^?X&^f$YhPIU9bKPzBS@tnB4+1{0!SPT^86jWAty#E#DjkRdhV z9Zt@~S5(XQjGt74C{c2YMgM|ME9PC)z(b7^bs<{LT_1=RP8lh&2#NX0H-WrK?-#aD zBi-Xar4C$YwgjzA%FWYB5l)RMTK`p&k=3S!O7g(+9SgS~FI-;`I}UuCv3P2fliZxW zwKEbXu7KW}&bZ|pt8U^nJq$flpLh{3XDYCfw8?FVsJ+D$A0*PUi5-y-oU)!5+g~~H zxanbl$m|ONDk;9&94L*GSn>oMTVVdhU9i$h#4(yD`aXvlb=^xb9DeNpuq-8+@yC(?6#O!kIi#@7HH;dS0; z@n>;nwa(V&uMFPJiXs6a{n`BIE~rm5WAdtdAO>y66na1CD)hz=sCO&e^?{qiUneam z&sFJ7=A&-6=7vOFl!Yeinu493uv0lL7G`yorKBRHndL0d+{jgr(5cp{TK`Jh@GF7OORdYDqgB%PEPv0SKiU5Abm^VFFhsLWvkzX z8VE{JW)5ZSiA{faZWpEtYHs{SokUu;Bb+6}qvacX#Jo{nLQ6kvly|Bsqx=hG=0+Kx z9LTxAY^>MbXgj)k?KN`Ye}0yxK1Ws~pL9f19P>yOl7lvWmJL&cidCCpqQ;1HO3 zz)pkT`|aEN6p)S`{91g}vr&dr02b+$n)~K?BvV)u2fZ{tN)!V4kfYIPx=oMg6-qcPt-y zzO$w)-iZ;(sXPQY0egl>jOpoX!JZ5Wc&t@mOapP8xRXu56Hn8O9W%QFQ7$XZARv`E zs;q)xT_d)OOg3M$pGvsSgPzkZkHab9Vf;ydL?)BO*$#Xgz-5m0J5BO|3;-8o07(6s zs!s>?FCb(Ux#n+_Mh?;j#HXkU8SZVe=DDX6)ht!*Zy0N_; z$nSo#Vf_j0bKel_=bztCAzU4X&_1`q@63_2G^yH!jiKqnyttW!3@*79{db3e8~ zyV?BV;fn4!GAEF$V{b1pY6@vGNgCWxbOt)Pb}B2Wk(L)l@X6X|c+te)r}#UKzfW^m zr;XpYOw}bu1w&6DXBf;obk|7B{nQw`H)+};Ed^ror}qO#_u@^MyEN5^#vTwYr&8aE ze?TODnzKqYF4NSe=^b?oN?T{dvA!?23=e>bwe2q3czf*&2(1DW!{8w%+(ssk#4U{1 z#)?S>a|U0zg3sj^`C0-c@oq!Kib(5G5T)#Qg1v#CP<=9%Gp8aMHv#7%)g`eb@za_w z?b#(>&nvJpp(HwF0@v)+(2jhw4Y8dqxEsuj{R7{OeW~)z>R4>#54H# zl8?>L7N#z>eK!F&mp(mRTUeiLEEKM;;suC^wCHlfq_=S3qNXo~)d|M8|DrWTnGV208!WYqa8n zNXuF{E1EpJF!eq^0=<-jhqt3X>BJ`XER18TWf2h@>5#As+$=+JIz(UX*W#hpvGKKb zlW0i$0~gsPcmXN1`LX@jMzM^p^@7ICpY?)kKjEP`w5GkUZGzftv9IHvFAjtqx&P)S zgtB7lk(PTIOJ3kxTT!sSn@kF@QoZ%mT-o9()KTI0R0tJ9X=0&5@k_0uSPMMVctv6( z+4zi&6wy5a1wr5sL^ncEf_oCb#lvShXm$^wiRItMbD0%DKytF$J(s7P;JrPKob#-s zX|~h!t<`?r`s7IV;f!9NYP2L1_)nu7I0<=7gLBH(E0^|^jhId>CrI0jp`I|I~~ zC>uKtU3^3jj?z?;^-p)7Ywh0AFrPncKg}#2Z0Q7_!a8HhYW*y)++#E`ahiEF=P^Fb z{KZvZt8b>l4fYi`Dr<3PwYgD}mCS-}wPp7K%p%TB4&&*g5+%b^#il#o8~lkSn1clk zoI2XJ-tXF1*yqIG{WtU}h;Pq!iPH3Po2%H?c#TasvhCj;Z0X_-3R${{_0D8jnZ(^g z@0oX)vh=K6e6QGOy(9F;?3oI@=A5u!w@B++@Frz3TiErBY7%#kv)psH74hv>(hIdp zyXcdiIC*}F`7^4)>U+eqys>9vq#2%A4!%s9Png$dVp_;z;1$V(kNJc6c%9jsdt7y! z72cgWm~1JE_9~C@$EIee7@IH2aRbaRj4G}(kwyBu(sbu<5Jc?gZz6vNq~FfU6AUqR z`?NNVYob<3iP@lv*?F;AO&Izm_)kFSHc!D*!fdZq}Kb4q!r)gH}H(=VqPJ z{02%AhtnEBa}kgNZPg33A6QW~B%D!<`|j%S7MnEd21=}nQEiU;h&6+h*{OSTGgfh~IR#31eyTr!t+doWOB1=S=T zn4sc5ZU*sg1e`ZyIEgr3MX$w+eM-oR!#Uy53;p$|Z`-8BoQYTy5iM0Gqr5)BR z<%r+ahco7nghHU9G`kZu%OCt)k9UYXL_0(O0;fxW3R#4;YiF8P z$EK!|Wh|5<3&1uhRpXo>jJPZB)z6Fj>GWG(JU+t@E^?MH-|+Xh0Wac(WmY1rG{3`7 z;vNZ2M8MNcR^oj#YiSq%M#(--#q^ksC`{O=T)Fq)OPiE?pYaK~cV3>{I|<)VlYanG zB9wcFq%_1(?nQr*Blm`Vpi!%l2V^CPAC7CT0~f3ot1wg!Q`Mj{~pLcX1k;OvkD6N*G~JL66wDEh39qV zEaaeQVC#K5%0C;@LjHjqEB_=)DVQ3Vm4Ce2SpKm@(U>X%>|p&j)NjGAdPL$a%(+|E zinR94ng7V6c1e&Nd-)VV+>v8W&GWlVvESXop$$GV`))~5UTLWQ{=&R$LjA4c6J#(h zj|@iN=Ez_l_$efV;Yj~18PswoX-54GW`RqXD}CM}ri8zcfd-XN2G0H-kbbN4`47Bn z&G`yTQTV7!%yw4YtTv0Zw%~m36fPuCM_OL(gcg3oOhXH=On0>KGfk^=7(-n+QxXJn zUHU97c1jDou|lO0odoX*hHe8o&_XT1sK5?jNKN&YeG3KBn9`-H;rd&!zQw)>yMSk7DIMg=n*VV9F2Q+-jo0t|{j9ii%Z4L> zDE)Y5Jp_GTpZKnN6zS8PN}mt+Dw-c7N!MIG)C4Dx-2NT;c^vyp+KdK?8RO7LggNC> zzDgYO6dtL9aBtOKb+ceMXp222YzNUs$d*>o5oQwKFy;n`JRY^;6{m;uxc}4)tTqq7 z=Vruz4S{G1E9N9x_oqgrS#8tx;i{gn2@rT1$rESnrtzkXpIT0E{&V**w205##*8$4(j=;&V%#b{erCT5A*Uvkrbs#NXv<9F&Ou%0sl?7Lq2PPupXQvd8Pn`3syfYZ!;IS&NC z!JG6aVZ1v$&*6+gD5p4bm6j2-d(%r6*F6Ngg`3u$T{ku|x((XuU}TM*`l%P$qkDP< zh1~qHK}xUM2y9%!xrEuxOAE=>>-Ctex3fQu9NU(jDLU4E)AWPv-yTMweso*xkGv>; z2$_+-)%oASJ#JiuWybYE8u*nvUlrWd7T}KI4qR(*Yzv&Z`Xq;F+5?9!xRj0iYN?iS z?}Dfar!P2xaXx;9wf@OjWTISzZtdBetJ)4n40(R>^eYum`SDk^C2f+gDkxySCe1Hi zq6QN;+V1jhZNtvD!DUmso9%fw+cQR%zw5&eh+}iEYqL=m7mOyWxx)8tv~O-zUCzn~!^njWo-Xba+ zzK0;TALOap8_OT2Wqn)sj09>EPjuvNdV7S}?)NqKIcg*Qkc~aq8`%_ErCHN+XS!iP zH4I4NXH|ccdQPmRF~G&BL@?c4Jlz@Xr~V55#|BI(Auir)+u=`hoLG z>F1;;a`3a-YT>`hcW0`>@8!D}nN=9{!7J3W<+~vc zh#$arI}2*=??p!bV`q^%WSXSC`u~XU{71i^QJxpKci_A0=v`be>B)`wZs@;h?lPL| zjPGvPfo>Sk3zEg~U2L~b`K}Tio{*7DD?}XnXR|%;B&y8k^ zvpi?@Rj29^e)`Pn$K|>D5!I--ZI@txWc8z7&HhaK@v%@pj*T4OmcG~NU-YEZ&cg9Zp5#@{Wr~tA3NjM zw_Lj@;x%9ux-*2eF@8$1Gs0aSu z(e`Zh@%;{nAHd(&s%~=79(U#N_qWW$rudsM(hsnMzkcxh`Fn_!NcsHj(X#aM>PI%> z@4x<==2k%^o$+_qZ5SMcHB>SmzF5vB7nV-F$X;zJopbI;k)KL~CkK6fr=!Sb5mR_g zt-`qLOgYo6zaC&>E6binE#|7^f%ny*lvY=%b8>i^Ub9%(K$B1cg_ z_?sWZ{B`0U2DxDeU~jH`=8{n8Legb z9p}Id`Oh+AdS>2vp2pObM5CSl{a*R=m#q9bdRhnh^9o+M8g)Ev2DH!4X6 zUCfh}L09zB8_m65k9MzTU3jmjC2sxK^l9Y8S+;;TaG^CGoWCx+zqy0mzkX}b?N|P7 z{Ew0|f2Z1ylru}9Nw~dAE&Mm_i1XCo_sW^q#7=(kqZg}ZD`$o~Abx_4WL+FajX^u2CU0|+*WjnsJa%Mh>I(> zqwfyta+Cw>&+LO!(GNv|`NGM{E5N${p-l;=Pf8I^H>F8GQiHh7j|beXz5_ewJs3Yn zE*%!gB{6=QZO@gb#5)r&_hhAsxf$?MH)mgT5HI5Z#O`s=6EEpS6zk~zpMyXZPIhHQ z)!rcdebZIyn} z)bwH}_sqlg{ZtN-c9_cFICj|X1~-*IWA-~t{EyfWU}M{B9U<;7TFRGLFH49avA#rfc5Y4$qtkQ(b1G|3 zrC)RW)j@u($Z}DtOCYcstiVctp8mA+z~=j#BZhiYC`Z_J<1rL511EPXVmgYb=fq-Q z8oof&X%R$jdTJdrE9A)#b& zz0Q-f!#;;Jt(lcN5mY<*b0ohylRr~?(3M|Vf9{WxKZj85N6Me^5Gzt(@j3rx`O{q> zeXsmE2eP2&!)(vi&U)Jc@dM<~EY(d8`V`ThiLd^gcbk$w z`&}6(=~M=t2?2DJLA8Ml`q^JPwX<5_8h~v{I;!fu*+x|LcS#Jy!&`rbPBQD$p}lp( zwC@M$RoNKhAS`EljD*v|C6ZKkx<-`k3~t1@3rc~ZgY;SvvEbeJTL<37qQrdZ^^*X+ zA%NGp^qNdRvbWMpu^&3ft3m2Ju(w_ZHlVc7rq`yq=*q4l>D9p!N6nQVpB;*mT!-%W zIpSnj08AybFWjgzYdCAW@%alr=L(u9(uq*ijkxRwiMl07OkwQiNFeIQPEB9E@qYAh z|46u*jwJD{pDwe)icIOr;)kviTEEVNT019^`rN^tHyc|N#t zyHm}9#Z23jP#!fM1a0*G`Zpqx;??>Ssi8su>^##`h}U{|xPIpd3B(?27Ip<)er4j9 zKT3Z6hH5`jemw?INRcwN@ZYqb>eS%(%C84XY|mGZQ_og@{mcRJ1LRkspiT}t9z~Op zU+2(X{U+9jUbaH2vvt|ia%9)pw|~E&xL<}%hxMU9(6ZuDC;uTcuVD_h)Jt~rODG*p z&wtZ=R3^-wjvaG_(CI~Vix9e<0g4i9dOCZmgPhm`oP=`XET}9i8`4@YdhN{41Vgo? zMiA-g2{os3)@3^ghIhO0`QNS=?LOfLiHA10Nn@F?d3L>sT)B~}Cc$pHNaLleZDL$y z6ba6(lp_PeEV)f!y}&#%L-t9$F7oK`lA*=1Vc04+uSjNCBWejyzZ^(`lx$3Vx=bWEaXuo+vzXIU55lGSG`ghdJKE)*h zrR5*0@Tpo++@NU)ul~Z*KvuJT7{Ifr4r^*0P2YGqq>jo)}>#(^9vG%)IlZ zXmijxG%Zqj3O3+~&t|r6s!hEB>p#>|>IR-T-?7B*;&DhdKQC}>)4Kd4@j1sQQggo zTcw!86lvo(d>d9$`Ldk$o}^$-bF7~xi`O^W{&L&9F|WPdbK7(G`MC{kmTx|bZ;`GH z^^@)i_AeqK=Go;kme`hv${E9{f=dUODwfM6#>x<5n%9NjeXGlp;?D=$z+oq?=PKWE zaC)CZA}5m^fdmxnBW5F*+2T)BtOch~R{gt;5Bvk(R}xP#utX zKg6Hcx*%50K{hYJZKlQNp2p1Bqi|jPgG&Q_o)oKmmiD^l(Ihk~Mc zIqoUggn>Pn=kQEDxd?G(_=E{Ef6cL8sAVEmwAfA8i~Y&zM)y9v{U? z$x^B*&)5)muw`#Zl^amIMiaX<6t2=O>}$!u2DRb5j?YNC`%&s?UWmlU(RJVhd zrXPD+*b38--4WFmdJdYA0GBI_XPR#z0VEVB&v?PUa4VKFr>-NMJh}M(5cQllyvlJB z8`a`7b08m>fjnh(4JYqT$JT+irp68zTaW$b+YROu{^7dX)Xo6pU%0*|>5g|EvVKyV zXYYb`aG77`z?8mQJM-!S<+x8VTuw?8q`*two(QU?YdoLBwyVobUm8!}9?}=oP<_lZ z$AV~=w&YdlOj-BJOcc1FFpw~x;{-91A&o0L3qDwJjM^?r;Ua6lNbC$2V_IhtA$Q#JUf_bs(Y>3<2l(8heoE%&Zkw%M91 z5u}{Jns1U{F|lP|L#2tik~dEQh9m)HPE#4A%vmb(1^?(}gRK~!uQMwH3BsCp_>f-6 zXeF2?3B`%U>Dx8wM;5C7Vz#02P-`ESn4cFx0Xz>1o_F9mSDa?{qePSAOEN;tri(qf zRPiaBGd7wW0}}0a+$Vo8;l+tEPMvDu^oe1Tx||=)%Ived>GWHJC2tNQm50s%7m&|6cBz*D&qJ)h?Ej@L5PaoY``%2=g4mXx z%b9YwWQ9LOXUCl+>t#6;Z9*hOP7_he2 z4qThQ&3l}e`fn$$bnY4y@+#&>BO{ij_T+sAv+jo!lW^<}sVj}`A;$E#iEU@oL7=fX zoQIX53uVIjW&cA;bk>;q`*&(Av)*aXeuyGDf2sU49aUcI9#VPCAfna$8NJ0}MGiF9 zqAEP{HF1*Xt7w1hx@Bv~8LumI<1^Xi`r-*FDBTsZS$#69Ev;K}M@Hh1692HCi9^Wu z6f{vm2J-9ejLnWFzI1%BfWyfCzO<208;OA;N*dVLzpx~6L5Y81&%_0JitfdF_Ro@9 zqW~~~i@{6NMYk=lC#P`BBF%Ag<%nJHdeVV)0W&2D2C7`Q3dO8?-iVaeJN}FD!;CNXZ zvzdf#xD_Tbvcx~8XJRBL!!4ziI!ep#OHDgE``x#>L>tnZJ@3F>^N!fiM<g{;1 z^hwTN;1*{kp^EK9W+o>NSL+PH1K6E-TkrGP=AwFEhTY2g#FF^lI^uLSp9d~#K|3wR z*qhCL?#iU=+ZDtmFo4)mzP0_xCjMfy~w#RtCQ{vp#uINwU{yFi4yE7E7#YVJA!6f)eJYC+b-`B z{n6z#beCixT3TIRV9UlTz2-~H3S#HxDUyZh>jS*o)ZyesJ(&@`j zk9t|0`kdZ^@@uj@U3Cy?nFvhI zu6ackfU|233T&EWRXIe3DP!CSs@4R5*SnD*^J?dt<8P2IgK*Q&EzV`XYR!6J_3%#O6g#mC7D>2kH1cN6vzye*SVb_`n5bh$BO zy8Pu!wYbDQ^a-ZRfuCZbkek{0Gv)~?PQLx|s{&ab4j=W2mvqEPN%Ed52Y8#@%8uJ% z=XEvc20z#hUb;E7IDx36Jy-Al!kl`&0KRm$&lmh z%@RV!H{!BQAj8Ui8nkHLPa70K#pa+_ap6RF z-9M2m_KwJZp3vdBpDXYDb9&1^U&j5CuDt!eYW2q7`{jIpp_A`H|JL+LPO|nCN`Ad5 zU_A@)Qnq`%51T}Pqx}V${x_=Mc8{%pudTntRfp4V)Hz(;?rm4K`CUK4E(N-n1!|9&i)n0DPgd5$OQGCErV0Op= z@+y(wXNm-dm-u8J(!_h_#TVRv_*RRhuQ^xN{BfbTZlyQtqoQcC>vau33#8({;i1Mv8gcu;tpC_K80iR0Y^ z9GX*s0e%@nR;O@^OAO)UAn+9AXH(Lr>}Rcci%@CR(ntZR=odbXA_V(eT*kft3d==~ zCeNAn55?zfS`dzxGn{dV2d+z~osv7G#RJ>SdZ>=@WbKs4%c)@rwjp7j)&taFBdq3g zQD)*TZ_IqJ@J+Ac&GC`+j#mCO&nCg?bFrAWs`WANxjoTQMW?zDc-O4ANQ z$cx0201x|HdWvt(IK~B@iW!A`vGXzNA6wDwz`Q}1Bk@xbSW;ig=BPNV6m)XxK{y)^_<0i3L@nKF9%_FrP7fNkaFt2WFNM3oo zbuY2TD}Lm2VHi(#&s%kP-a7M4`wOz|e|)%;gh5i4jc)%?U+r}R4zZZmjaPO3+Uxdb zB_Buz7m(M}=_fnE=amO?0b{VPJnElfrdjDSy!_zEqequ-X!@#L z7gB5%JHYct8gAGrj1DS+#P8%t;@rIl12vX(5;+Cw z(XyMh)cLee{;$>rlb%Sw5ZWh_qBhCnoc1cK_oInZ3|DEEvr-qrA7&mfduwK~nN9!* zojl%=7CX#uu+=6=QcjYarCze(J;<4*h4K4KS}jPUn+T2}Mal0X(UlF+Pdp6JNiY?x z58%;U!5gTBBRDxX!;{)4zQnZAQ2LdQA?e?xMETrT`zaeLMy^jDvVq)ViG}I;0X;Og z_tX7F=({m>J-OB4LPK)={_|3QmnIAB33uMqW_d__265}|VVaEm-dg8B0lt2L>+1r5 zRRxOnl{?*$9Q5Z)6iwe?u32dfRD;sRY-hNL+&1&2qAb3WM_g(O;yb032`S^hdPP-6 zS)vH?Mp~}ni*g2+*F+xO&r!iyP{Fu0W-gDRe6T?28E~enM6@$15=fHh^K6S z86q4fBJ5X?@@%L1S*0EWubPiLF<5h__z%JSg}w|7_n8y6&8x7wmYBncz7TD?kOh!7 zH(B;1y&22<$2BD8I@$Y@Q`}-mm1Qwf_QV(BPA@|&xFkRbyHN{CPbzo4)NCiE5#04^ zceGly9wflBFRrEGr@QcvKzRN(OGDd2LjwXD%G1xuLF2}=T-W@pqb49-DA`cMjml0s z|3fXAM`$LH1h-031^}?ibs%uYFK3?0X@{zIoTjVl=XMEe?M_KMKO{z=&77T4+G8qj z?D%!s4-toQBVEMcYhQ71cUDgwTd%8V-m;mltUf%uDjglYI?W)E;50|OQgk? zm_1l=f=0+EkiCQ_OP`LMC{|>P#otshs@eI)mRyB@oM#UQWadnQWS%`)W_FaUA`@w7 zPj0DaXHVwlLki{Z+PcAA;>89t7H;3aFRL$Q)(m|EWHyZ%{4MkZE$P3Ey@x$NegOAm z(Z!0!)VcrKNM74-P9AcVO(+ldJl~}5LcC`5*G96i$OZyje4u)5P2a&?A}w!-#*-7t zgD26x6(x{!3$2`sora0imfpfELPc4D@=ASNES_53bb8;x-v-iXAFodVp*r^e@xw`? zQ*tEHq^%*Em&_$lN>=`cqCH$cOT3kef^Uh)0Z6LU_Ks#*g2~eC?j++D=|ooL)9mem zJhJl_P>$|cE>~-_@hPFRCv(`kcD;vw_~Lfx=Vv$ zdUX=;lR>_vLN$JdZ9Kk}r~-o04b~b^Re``9CsD6nB}ot>=1kiw?S}+)Wqt=MM}Wsi zz~dMEaCrPxhN&mr1{Rl?{g%UTQz`Rurc5s5pXSiE#B5Hv)X~9{L!uprS@ym|;&UJ6 zBXL&xwH&VPY=2We|DHu`;Ro>Va9eC6{@sh$x%`8zHdr*y%!oO`%ai$0ORqi=y- zSGKn9lrEUb)NrMD(Om;}g%nqDKd7u}%qf};=Pm~Ea$Sgb6-{AmoAf_vFFBs-*eK%H zr;!I8`8jL9bl}%d;DvmC#cZkZ>#Ay5(T~utvspqqkX-{Y3?Y^Px|WKEPl1O&$m8J# z8)*o5*nPBo+&lD_bNP8p2YxOQKM!HPJLBiwvi#gn{ESr$mbM5=TYh%*`c@z=;&-oFcrT9!wW-+Al*No_gU-Y?a@}Pn?EohZrwU`IJuYne)UOR#LLnml5~_2)tOn# zWM@y*9a@pr*EFpeD}@&~=8B60Y|oLF<1~1GctF2rOO|JZ#KDw-ND0_#{hqlxmG;9X zu{&lTtjX9`Ei_lYz=NHPNXryD%9)V0&iH%DbRm0Z%J5|UNReXG$DC;KseN^}_G9_A z4^i_H+H;u=8-Jzv$*wpHMEf*9Co3~Z52|phEqt>Ie@9n2^Je1}WIc5mJ4dazc|2bt zW+s$LeI5C3Fg%&<7#j!ktXbOQLyfFaMbk?<63Gs##88SUl-pSqpg8|STo+1=67$rx zcFOI&BGz%YQ3B%789U=PTOy7Jm1k$P@Y?ye$>LiootH}dE=(VatatPk-jUguS~kPU ztK^`~&vJ1G)Y3PKH?#pUT4{h8)*^%rTFp*mjkJjxa#{#3#;?@RC1#@JL2^)~ZDEPo z(p7jqsBn0;LQPO1N(Coqy0qG=_XlNn$(Ah(%9dx!zV6z+IVijCkqjWK)Cz!nPT177 zd!H-Y6qJ2FTedAIJD;*oD@>t^XJ28#I4vlCd$#zsLGfED4z^{TXY%v4@=hrE`Equ! zrqij6y^ww{{Z4LvGR04)4DI70A}+FXW=S9luoJthk-?K)W7_1ZX|-;E?n&ysB{ikw z6F)I?5X7wJs(gv<+$cw;lkaY|IXMZ#ZWS4X>f~|2-NnO(QN6v+E>7@wseRpEXT$sL zb?a@I!bL~cn1|oCHsf~yptTouALn}Ixh{?Xy&w6OBjx)VWhAUL`vOqV|7fnnR=k}{ zMu_9Qd0-zF3!kk%x*@prBsmEIvZ|k7n}scL`23E5C2F4p)JoXrf{snSGG7e8Bae=HlC5f|a968McDKIA!YRW~VUa2^{B(wx>#pNc z!Mv=KD^b4|tc)2;B5ztNHBX%=<}Mz=kdVAyqR0$c#_%&W=-buUUp4&Uz~!F%y63^+ zb1$CLw+9u|uZ2I}0bzq~AM5xpNCOZ}LLp#SsZN3=E>mW z{_f+D@S|2?&7Hx=buZX9=bWK&EU9Mkrj@DDWd_<@NpF8*$Eld@Twb@go=9CwiijEt zwURXpl*XqiKA9Y}j8?RDc3kxH8>-btMyxU^$mN-F!t^uf1xTK(i5gx_ z;#Yl3{2K*red5gq?l2@1ED!F&h(y=EX2UmtWOt%-IMqIUgkP5JJy+3^?ge2cXF&JM==FR zCuGH-vuVxzUR2LKuf513h7xw8?PIV{q*Z%zrCqY1r`R&coK`-_cRnc%_&N&ZSO<@) zfImZ%YTkbX5bkz0F3Z+fkzeEaoEi_QhW5wO$06Aof6T8D%c(I@HO9CaW!V}WlFNna zsGJ&ys>Z>t#)lP|ar_A!=Zs^6ji$MA{8TkQ){ExKN3u2koUI`&DWCZwHH+!7@^xxF ztB2$rT2`@Q*)c?5jLdk|86$VRD@4ZIYzfT}!t7SQL8VPWWodA|zJk~3nYl*EQ9;v? zP{<~J?X&>>w$5Ry^KfpRBV3*I?_G~<9beFTkkk_$(H$s*J% zhzrSX7+I>V*7~6nFt6>e;GVpYMD28Q^KUg-a|c8-St(JEqWaS!UkkDRZnX$|pa%p*NHx>*@mEOZ_ zW~Y-IE7|O%4T7#xxZWtO6*P0fIp1aCS&A~0G))>@5Z}g2PAU&doCi}!+&ZOp6Vp#w zwx2&RGiWqgv;73E=JZn%w9-TUgz)B%Z*XROHZT=b7z{aw<+Y4TzoprJ_i+8vy6rdU zCDX4ndx@-F_bZ)0Qh(LlC$_Ho7%$l>vwEOb{bkA`nlQBHphgK$OAyMwGS81ElV&SI zd_9Xxa|Ut`h2*RDYfQI)6RnbRsE%n~@>meu&X@V_OXEzt?@RWv%|2*0AeYzx!p+7v zKB7tqJ|*waE_npvypycX%QPG`V}7mqbNdOeA+CyMa}}(lOb(Ky+>w<(8d_)@x^aeW zdI?RArAc$3o&Tq%*|+bRLtPuLtZk#-w$bPR3KYgV3q$p&p4}QGFt#a= z(=a+(7`Cj!C{P&3TNs-yj2F{*I0ECjY#2*$Z9cz#lESF z-$eZHw&38J_>^K1ocQ&ou9WDoFKV1K-{buOv9v;~>iYhxW*U=9+tjHm_yO$jVt!H+Z0t*8y^cWu9;o0z#dXyPJ?(T>SEv3_5HYJ+II@`LVhUB zn`+&2r||_7g|OIevpO#9dQd2KZO;o5lCnTXk`$Q08B>{dFh2)Rl%L#xIbGOOj(4^} z_(O2NWpJr}1_{X0>uHlOlPTq@V#~OZ_07~Y7p(bYvT${_bX5bd#yll`$|0G$(yxLy zF|l5J5>qkvHjg7Ycy(s~o1iiJOXcDSiiEDmv%&*aUxhvgu*!wLM^Vi~ploh1ovC1% z?kZLKf|ZHM@^so#Q7ZVN?c<2z_QPmRE%L!%R3h?!CpMbb#`@GB2n1Kh*RUN8tENU+ z9hiOJU~<2S)IegkdctI4N{=J6<{#OZ#A_)Tx0tlKE7Zr>&4K1CXb|FXjb4Yfp7F0u z7BiLSDM&JZdY#s;u?bDuVbYp6;>@+Qrn|O3O~cB53nk=(HB4ZQA;C9ur|$B9@D|GK zh3QtjF=;x|O7dtSIa2mqKM(1lSx67_HMD`=NDh$%;mraasy)vo;O-NF9baH2Z;9E& z(m(Z)AA#8*@KPFqmGVn$pW9yr;G^;tDJw}Ma6=XX3&luqxi(f1c-kh2L@FK)p1w4v z3b+d`xb-J`^kg&c1s}MB1l(Up@S_^{e+c8$a8+Sw_V9jv1r=S>@#b_x_I!xvOpLid+S-O z0S_*f_1<3cipWdK_Nd)&{=SnF<((9Ep1Gxd=O2>KPk}nSBO#RjV{K1kh$1XGZP5%5tCI5}A{J;A1zkh{%2|4iUGYjxl z8(Tp5B=4V49g!P*Z1xdx*4NorcO$NQxw`ubs$u^%!%O+AW+Z_=*!tz{%s(=YhICh= zL8L%D5GD}2Z;xBNV`vv}_~IB@l1weE7&;fVvW&{iO#&Ybd#D(;B(T1VlEmZ;Xx zl^>GO&l`mhd4>tJMhn7J&L_v5zEq{(N768|06$ay$OhMMI!JTgA@?C9%hPv((#_88 zN6;|5lD@z!GPl)B&DpA3+=oiJ51&k2KIRp*H`2E*1_mvVHl2pMEO;pb%os5IE8@_0zwYnrg7v@91Km1$ID%$$ODPL}S%2jViwjJf1Txbv7yQ2(T&-sdJ= zYx1>c7RYZK=os(VHmqMDuA-C_ezC8}#OFTU!Lp&8G}%>647isaMYB~#HiqaV6o4+r zHZT;;my3kHA_`qgA@44Qc=vCQhTxbgVS6HkBFbY`l)4GlpbFzj7XS|`&|VMRdCMjIg`(4Z?CVHye0;9(_nGg-F@&X;Q5@Cpw7^$+Ar*Ns;($ZE*#hNM22X zofll0N=z7L#xbWPn{+O-_hBRk%oqmgJ4ELVw5^<+X=N$$n$^l>s9h`xkv20%T49+e zn6(|1#w@QrX6I^ivrm^g{iM$6Bp^ksq?eefr%D$*Vr6qiA!XVry@G%BR+$^=svi}W zPOZ`>?sTd&s|~kUI86useFbcalwIv16+ADCh|k1qw8PFkyaa^amV`*zY3cIWc3Peg z;FiB$%5R~(-!%KX|3mCFq176MqvRJ|YmQPWa4-J14uJzmk^s50WkNb$7>Q|@eu7MT zGO51Oxbnpfdke%gm@_BYb%#K9UoQ}gT{=aZdZ`(U{ZUWMImPSv%o*YPd|*=n8{NQ4^At?Yl|6CV|b zhZ<#XkMj;QWmNawVt)Rul#?UbpPLzKPPseqgUU|nb!1NPIC{N`AMT(UjbWMIp`Gdg z{cbabPIB$c$kK^^!zR67mEgEDI!tqt4RsLq%*woN)nfQ zF&EA}-cz(Em9gw>Gu?$I3StX@oH{Af@q})r9wzE_K0txzv2d9KtiC@FnR&z{bFRbmTVbN0# zfTI!tF=s&*iIZUJ@FUwXwF*jW9d!9zC;GX{SM^M<@9ZA;DB4Y(Ep~lv>E*M6 z6&bQ`B(8Rx#MMfCw6v>_gq)t;ZZ>PbL>EdJ9=j6K`RwP)l>O2ckpr!rqsAmSpdxBZ znV_aqBRr`nm+9uqvowk$kSI8*j)~{sRZKG-$dmhwHk%7x5_+}QM5eCL9%KKC`)SZl zJf_LRwout{3hicSuo2=SmLn08HEHfmd^wAIll>jna5Vd5ux)N2UO!9Uvi(5Jm`K^a zM=)}TM49PC>p(j_9@sSZ$jK$0g#F~mTs6&nJ78BFXU3o5H|s~k7SG^piil%(T?$F)dWb7@$-t=Zi!Y2WZpmF z!yV@@fK_^&J9qcgrg`-AUivcGU7M?-tgpQ*xt7sw@4?qBqQdnG+DqM)mS5W&g5Q<* z%dRsu^z4J_`+BBMSD6AYq*pTh%G6u;2Prt9v|RnS(PrsOm8tb`T5{TM!s$+ZJb0`P7hrQHG2n$W z8A(SYF4nDOZrvecZvULnfn*-WFmqS-8%&26rI4!A7a^S^9LDZta=Iq7U+VL(h+9P? zSD3SJ@zaaA>Jo`r@j}mq5J0Mkyy=O>^x#iWl25vgNJ9?KGGU zU=tr7NJs8HmLWvWujzbJD)Y&8;O0_zGK~vFc^{8umS_U$MR2{iO7)ldGwcUFDYWfv zZI)bLv$wUMSw;#Tk+NBb(5ZH2iBZJc=TnuC#`#JuYv-0v(sK)UJn~-HY;+6P$k=%! zF@Bg}aNl|iY7Rn>7)Bm|k0k)(zMm-+>0I*57Wt|8j-|9u-a3L2`)AY!y>5b@4Nmw2 z=%r=Oxw}ycFl5b8hEno28KY{GN;|zCNw;%RYr37?AJf;rllje=Gk%ndQ&oKYnDXYY zI#k5IH9sSauOjjpPXcbJihWfT+hW#aYBy8cJ$w#AV)v>NGgppLoA{c&*u-UDq}#rY z+CCb49xODzhQ@-%vgiNuG>jW#;p6+^Ak3Ggtl&u0m@lLW_6kp4p+8+11 zp;-js4}7`v+WWTVuuRRN?dP>`g*-RDWSUg}lmr_zYA3KefFV=N7|EREw&d5}gPyng zyXVVjmi2Cqh?OY!!`#e$$aIxEU7(}UbdbFG0@XbioI*ZK`{*V9M#>&K$fY$n(AO0& z$-E=tw)zEddCL8=ErzwZXP#pod_rcBM}4zLiu*7_VN#Prr7I$3L(<^S@`3*)l%qAw zEdu>~<%@p^hK}`S<_*bP$@Mj$SF8BGQ?u-couQWr`+5U3)nsu+ZtZcM9MDaE*KUqH zhVL}1tXv2u-)1x>Uu#!34`U#CI7B5S{=xv`*6o&uafc2x>kxTYLCjv+*0!zEhVy&j&{g5HM|E)X-(i|{f9@-B zck%Hf)7rHL(c!`;W*+9Hl4d=VlRl3lz5c)=hRSok`JH$M?#p7SEVnv*>)uaezDDQP z5#wLMZ71;ydnEG9D+UeiSK&Okw5D`ra0necwmWiDD`rsFDt_XcLEdW^4Z!5`=w zOb^vJq2ru6)pM&$KE-vwioCR<^rI>LC9Z+@5`PT~WYSz}KI9%nauEW~%Rm6@T4%;m zs?Zp%M4Lmc)zMFR_mx{^#BbuCxkXR1byQR{dYkEAwY!ZwCWelxOq_p8hsd(r@Z?!J z6?Y6B6%3Wge69`0M$9#nY}@89bb}^Fn-y-AQ@zeyN~UN{RuVn8%bYp1C_aLvPCovo zCApj|f{3XvRD`b>wHvIQhOx+2Md^k8oQIkPL7!EDlt}BTkDDkW_O2Y;b?$x&Ipj%I zZf2Otp}@zvdxlwuyL5UZzTD6-lkE!byCIQ#b&_EUV+dd-RD;9Gfy5Nu6x`42lT`8w zN>s(q*-@SNId9o7uZmr;V=8ySgy#AiFw16T15Y(&`uhj$H|{$!f4STdJi#g^5N{MqENJSNqr9=TtDm*LRzmJ|L=q4c8jF1py+m6%lrHHH? zI7kfGHppws2y?T$CoQk=7qwIUI29IBLDp1>YQp1Q(LLMhnI;AETob2U7MJcpO%5>R z?#~cvNJ)#BZcw7u+aQ#Jpc^Qy>=Ejllq1r1y{bqJPa`!Pq+GZ=SVUG?yX~J>$jDfW z0E*pqnKoEiR25_5SgQ<3^j~S_zAC#gpNF1s>(7-%C>>Hn@!I(0nb7jxY0x6FgsIV2 zDbOyPLQNk9L%InCo237;*(1=7Tp;#})nQ_EOY^4dH!K%8l|=JFLM@c0skCKn(Wx0; z^~%uHDT}5!D5$1zGH^V9-DMMCPxATZL%q1Foelk9p!Z6_2QX;aDpCGHK%&NiGFHqRd_GrjM9&eR@R~Ya=tcx%N2Z48acY5kEgb%>g49;H-bz*K;#ju-RI z{FPgJojHg0imq{@KV|EJXd4mUn#7qSVPvuJGtE}37qeq!SSEY=KD>)?nG1mt-bJ*` z3HpOznF4+!D%%Dh=1iA8VAeqbwKk^iadYY;^kKZL&%Ul+j2C>?Nq+uKj#0H%&qOpt z^J&0tP5iP#e$Ul385Ul=g&kgE;*qpWvtw2f#}+|Fp->U8G=bP}R6TO4gYMTcninAT z4b#nP=NoC7J7)iPlw@y!{h*S(Lo$6MI|n&OJ$zg!2;77=`LE(G&ZBmP)0E%Ki>0BP zpX7dYH}c|n6%RM^;_F&A5BG??*zAkE2;}|3gkSnt*cd7e#3Sv)E*jN^PmzKD)rmel zY9;?@6lEs=ZGZl8lHV~a{|SG77s=lMcA5GO{``#(li!+^|0{p~KO|o!Bd@+ktN4L$ z!D%>gb0)y=C+si_^E&?7$CP2_jzj56%OYQFU-aidO}i8(ic4i6S4wJA<(^!d!KFVU z)Kg_*JPOk^v;IS7asZ+I=lHW@I>gx!)T`NWh6(Zi@_c#JCBxKBV;l{Iv3GMUpzEMiny^J5&9@O zTzHoqM|0CK(}(FOxk2~ayf~V=<7NLJnv=!0nN(i7nSB{ESwRnPO9TZ-FG;18r%2iJkfz-etjOZoM7H)^gp83fcZE$*ykv(f69F?1 zDw6|f-v>VR60k2!!ycFgyHY^8(Nn(>*e6Lsd&-gzfuSGdQoVf@xNW%}&L?HTE%m|e zFL3*i;Dez42;X;Vg?D}_J3fX*BHA<%o6UY%n>l8v>tmBc8HC7OeQY})TbOjw4^lcE zCv$$SZr()C*XeSPSef4Jj=B4lA1oJc;5XIzt*kS|1^Ytf!5)=P^!2PznJxkG2Mni2 znO|frLG!+agg1T^dlALocVcJ!y|lix=^FPTzPEtTc*-wb9Mt!=0@ER&0UF`}AE{(j zhfyY5IasUvic(ShX6AUSblTqsFC<<-kq(4d>b)aBg~D=+hp8 z>*g_N%6RX74;CD%5jw3Cugz@RDh1Y>*PoGY(&m=vc(=ZTv{!79a%#XceV8HnNpsuH zF~65Vt!`A9<8$Wqr2#kN^XCMg;eBLBD=@mUfBM!t^RiA=GlaRWd+%0&%X(t5C=+lx zO>x2tx!s&-ahhpG$Mr7WCuI8rNNz?SB2UYAA3=r&kQ7lQEf01-+Vf35sD<16`F;l> z=2-|!{)S(&-gNy>^Vo0%Iq@%3v#-zO+oAO4CmC=c2A6Wfg*lU6mdW9=s8<3A8;e4?)BC?UN1}e;#j);h$rNy zmcN?v$;*K0%`<8E#i6V?l8-ZWPLVptQl~KuAGbR0SM#Tdg7biHef!(6!{x~;I>5)1L)9|)+>F7mmUQ@V`_1Kl^-(VW zUH>19bIFX*T=K6>ntQkakD-nUW=dY9h^Twp|* zp^|wfA3o)t#7Uw!$;9G1IAwzFe7~rT1*-NgI|OtK6FP+0l^6YQ&^nYBGD`sN`9jx=z)G!Q8}bC=7&U|%2e&b4HU{xOpQlRRA# z+)$Jkd@ZNm^nD~(WJ)pA8l}(73AC3yObCyZy}#3I>~vpa4Khc{7&|~(n&5s}oWly^ ziy36dJ?A7Q?BIqHVjuT%vR~r=xU44|@AW z>^Haf7cQz2f1y0K)LIk2ph*3NXJ+{ePx+26vi`yY`RPRO&lMH@L;k|k$n|_v_zUrA z;4eJ0=->Ja4HgWJzCHYfYdwEq>$%d~>Mwj!%UXY74g~!7{zA;^(c4XapWSWhB5XNx zU@ktxAsvDfO4f{RO#2Ck(wY+ zpKX6eHnPnZdccIwa2A#H^3*4jT9=4Y)o!&(N!GG(+8yyzo)sLuIiSxK;hQd6Gfp zYr0OGZj`2DYjN3`TOSkD2uv=mEDBwmoP`Lx^KLu)&W-dvkk}%;YP-$wdj#;_%)9R9 zTcK}`j1_BV-7go>$0t94lh5oro8M^<-vYP!Y!4sYooTiZAp|#2Ws@K0y*lxAe$H`u zgv5nfp-}f`q#cCrq#8PRz~;kXSbW4Crl<5RjQyhpi=hD6yJTYe6|#}`r`2*>vu^6( zoTd6xRL6%XoZ501Gsw@xPb;Bgl=$oQ1*D5v+AFGkPF{3+`UZX0h%BCYno|K zZc*Q<6V=-a-2O}N%!KugnLTU)IVG`2;w|(9)7bu?qee&YO5Zfr6Y*slTWD$#lVo@I z%T7)V6lR~ELLsLZ$KW!|U?j2qd5YYn!d10dk9rv#Gxqd`El1dURKMki zGRKJ?m9<7Jf}*fFu~F8DVQ`Uk;*Z5;zVgFynTK#Kjkc|8!!rffM0NNF;xga-DRX8I z80pH-Ybrn0VHScXfvfb4eVUc7TY_5gBIUnE_zNtSBS zW)^1W>9>t{z5y-iifIe$4&V5izDfA7Tny|;**$!?e0U0``}iQ|DPW{oCJg^0AIz`r zy6mYQDgx}+jsr8Zk2a-4`C^(%_LG|JLo@HCj`$tURzDb31shSIxeKMr)a+*B3&&8<&}kQ~!Mu{7bJe@L-<# zhh&cD!>=d9(yl7wOaS3;V>08|aLWx{z?Y$O{k?*B_LAw>QjWagjDbhzc21A`MK+_F3qZ`ql)-E~wL4(}0i znL={i{BoAMHSvA+Tt+=t5gt3xMqG|T&RItF`GJVbGY7VhxO^VD+1ob6_Hw{~CGcBe?YSr5^B?b_C}+IOc3y9|>jjg{_^JPp(O83;nYzVbj z&NH+e8eq+nf6BYAQ+QmoEm&Z##cqN(H^G}40wbj_{1=#QO0CA4RWnTAg<2pxAy*+f zspo02qqL~9SDR(5$p$&>d&3N&Wb!2Wij;lusaN>8tis}`)x!Hr;iLKTce8tP#9l$Q z5-`6_gUN1FZUa#;uhO@A!4HMUrVD4cIoT`xkQBb2uODeM!$9t-68jDYdY8x+q#HOT zi>Twh2Fj#?!_y5|8;~bxcblH%q@MP-+v3Ud<7-u(e^{O-eBzTQ*)hwKra}1$jCO3Yg>(Dbra}_LQrY zS#mX7IMNMSOg%x%&!8FhCRYPJQQ0sRt{!9M>b7*@>^?r;D?DEcAI_Jb*L%p-pfs3l zxq8Rz$?*b40)aqqzjWd3HbY+FGo|nq>29~;+pf*M%GGnWfu|UcmIK*x)!S>}Gq{>O zDBXZhu3jZ)FLIU9S801Tt*C0_R}f5iILGvZHBi@28W%-U8$Z4)zk@%|*sF3i+cDlU z2R(ASRU=2;x|dGgkXoPB$;+gZj}!EoTHu#X zbH2%G8YBh!oBJtHRcbaNL+HUZ`&5ZCD>;b~=B?K< zuc#we#M|-$?q%`D<6suI+=(S8YlbK^!Q^I5Fome~qS6PX#?*fX z;&Y{lS)}Qc?Zv|~OVuZzzS(y_i}y}K)_W^~$kaj&qONylG%peV{e?v%Z1=`K3!ipE za3A~LjWg%0-01RPQTV$PLSKe&>5voJp!AnC>x)_G^Lb*=>!Ek|QOW?fv6>fM@#mgG zd5f~$`#?ofhucuXg;1fnzW29;KVE*1f0JMQWBKuL5!s8(evx&#zV}>5a7{F=b6v9K z_kaD})W%o^0`x|FL~|f&4>Xz(8 zYogyGDZM|jvg)*+p)KInlE=W_DZ4fAGdcv>H@UOIhwPR$7?#7M%~f~w3@%FhQ)HO% z%#q+q;Uvx3=VW}~Vpm|7>{pO5pwUoOD<3fzUvtb1cUrFoXT#Q88A@sG!<|7x~U zG+zDJ)LqbU7fnOMxkbT>`3yVpB6gG8HCpWSun@}35-tC@p2fv5f?U~^fz#|H-G39! z!pNyp*^)VHN8*OI*o`}4D^f2(e30>_tO#vMo($~N;w)zT1KtZWmcEq5jL$xR8C@(h z7V04o3%6l8kf(C_izVU&mxy=M{1VxBuaTIxaTa|srro2+qwnv7T&s08=zdWMPC}oN zi%%D&z^3IoAv)fF<$SS{1Cf>k%t(f#+4?kyCgPIFo(XfoJo%{t%u@}uiGp7gnjGM3$+GHl(SGD7v|=-&#~ zfp|oa48#YoGR(im_U)=Tr(&6t2c~!Ur zW47r;@D<7FF4TDEr|1NU0!|H*{bu5gVjo%NjYG`1ihBQe!$`7w=Ws@#ET=ptCwNR6 z&TArxD3l(7($y^-C1{=}EsTwIPR+6Oh8L`)E_-JwZTW-vzFdTqpP1IRd-v|`ZyvF% zcbNZz$=ISr$)dl7!-z-KqCn!T4n#Y>nbRDIe2^FD%L`#UbGh392sMe|Pjcty6hTFz zY%>c#b1b79Z%~)jtbh`;wYwymx%+R~oHDzELczovYZ41odgLF-t7vVI-je?+Vhtjc z=2IOPo6K>nwYiwOx+cCrV8t3FVB72yV({wEn$`wM*Q!1!tqMg_-FtCW;E@J-VA++1 zz8Pt-6EBBAa>qgpr1Tb2Mu9`JpY-&*bdTkq9ba52DU;U1fr4rhic7Z5m*23QeZrQo z(3R5~_K0c?3r+H0pjD@5{TZt)GIciyx5o2+?BHHT{Vop#B0CVe%EI8G=sJ;&-|t{+ zesk^}mAO8-ZOO}Rsmyg#eDj~;=e@_OXht>;lhaMDyxGiuPW11BMuI2iV(-daLJN3} zo;H=RlpjwqR7D^4*U!nbN|tl(Pxh?yo)Ao{n^}Gb-t{e)7AUw8&ycq=y`DZ@`cmQ*(1dJw?i_9V;({rR{!US&whkKfn$4<2hKuOMgS5044hg zgAh?FENRY^Pus%St-8KqK6YDU18ckKf-eoOZ4xETJ>25aHp_$_mh{%#b?HqEsQF%G zd#(9fc6K{@^yK1a!Gm-rHV+~Z^@z!R*yd_)o1Zd}-4ww`*AH|f*5R~O*ciF8Q+OA@ zRQ`j9rDbyJ=b}oaYp{0O%u;%NdDhO|hwgnJi2*ZrG3nz?@(d5Il+b#uLz$rf9546@ z4KRdv=%?OY+|jHD)z-=$vV?4@Je2?cOql7ujTYyX759BKIY@fSwPGc0Fo)g5WR}&R zfyfYz(bMIKte3pCi0t;HBRHmQlmm)VmUo7yEtL;f!+7tBhs!E9!vr*@-2D}MtuEH; zL?2^F!=6(m$BF(DR0WBv*mK4neUXPBoEiFxLPhvrxxubsecu3syAT=1B1Zeky;gx( zgU%tp`it~D3N-eWFiS%02O>w5Fw>hf3uhD?+mg|T43oQrRMoi0zq``YxSO1YNyKtw zlqL!HcIIH2+jul3vG)>XA>&@X(~3rm`IU^@#DLf7ER_|}@|RvMO(4|z&I9gS!4%ap zt0pl5aV#=ViSpJ0f-5=AZcZS<6%C4OvEX{Smb2zCyAa&$!J&jKB#*WUGwmEfiB~Nd zjb4K6Hwd?Lp;d*EC+k2}Ffsj+2-jN?CYcIl)7Wh=*FcfjQPrXm;WiX6 z+evn;)!ZOHZP zhQMVXX78y-Kzh8z{NWlfYazkH#?G!$s>pey<1EF+_z7Y>xJ`JJe|^bj!}`%6t7E`eCV z-vFB&PiKmMu4IjFasJ~qX`dCG6I}zcHj;rg+|-9Wfysk;w6+_syVL^_(%X-@a(U`?1j z)4U=pBn?K@!DD(W+0|)bh#n?rMauFsWWJqE=D#eNf`mDhzE5rxGMUe<>dscj@6tud zhj%K-XIG>-cYn6l>Z=OT>eElJphgc#h?Gsu)Q}BVAFn@`m=y_xnJvXv%U8S(-Nm6r zXc22hNjW?t`O*hgt!XQTZY!Iw6{cI=2-G*nSg7xloO;}Ep&kKK6^{FMBJ?7&{Uuo-ik`O6dnl9~+-@4M4Ru#WXSS07M{YX9O|9CAUQdYggjoH6aVV2HL zr~R3<uJu*J1nrby!*N$|CoJRa?F02P2PHgE zCkv=2Bq37vdb+ef@OiRiN|RFqX)l(1J zv_`$M5Wayt|GY2%@Y-V8fHY!bd}MTFW#^G`jdb<49VF;D&H`R;frs6)I>L@~8}z63 zAWfgI@{{yC!GZaENlM(@Prl;u(=SCcrCqmcK9SzMTM{B=Q_`jVQuIq-X_1HIFcSPt zwv(br*(qr_eu4No>j$sZYXwd@2|hT;=I*vAU;Igi(SkWGQGDlH=!TxYS%YkmR%*@aLRR;x@Hh%dFH&} zTybCX-_~q@OzDIkQmo#2uo<67c}{8B85B$>?RoxX+QtA@y?--w8B6kb*<1L4rPYGc z@jWK@MWruer!HUjZCNYig6XuSQnTH_zq7xl$;y+B@52EZCF;i<~9m zp81B>nsT75w(m#hCI%nof~kwWSr;?zN)3bLK_&2?m&v$1S?tOE5uHGMkU5K~I1oR( zu_u6QLMkdJGSYjf7g2hhX>af$duF>f`Vy4r#ewNes@@A*+wJV*z zp>iX^_S>$1hU$jvKaRZVhQ9TuSRV189_NH!b^ANAO4ADv^d`2SUYq{G??4_x~6pVEWvxg<{{ z>W*e+Ka+0u@#}vq_ATyVb zpZ_=Vw-*evdV237_$o$)ZhE`%1=;xgzvX#NZE-HDUTt>E zI#Vu}wG;5vm)HSke`;wT8!>x3-*!IoMa-@fG|bYGES=u*&onl26?xgMHiYe`M%8il zP|zZ(uou_bj0$UOSQYBDtvVJCIMvlNv-|gl>QAHoa(6G^Pp`y-D9QF78{2w9CBxKF zr(_jQ;sfIP{*TJw_Ldx`caELfyJTW3)m>rbYuf9QCyVVf&exsO`xd*!E|x$P)yHP~ z1!*6Gj1OPq<{GkSu7_Jm`3?AtJ!uh3`>>y+A1S|5T9g&7{OzMK@L6~*`|3-3=G05u zwV!xUqZFoX>;dvE`cQ0^NomxiY{myICgqK$MSAa0-S$uu|?Vd2IFr(RjxC&&u71ix&E5$Y3L_V;8L`bOB5l$$+; z4pRx@*a2yOhv#q79)M|lOF7|Rc05s{VBo>hlm;%iYcs_Dwk?UN)U1(}B-;*{%ExB*wLw@qD%v)bg2|O;2q1d@;Bnh?oo9 z+L4WY{HqHQ1!U|#*ws?KHpg_9jt7qejhXSO9F6+SR6vyHd-IQ1jJ*n1KPJj*@tvCse?fepp8RboxP^oq zQ$SrgN_5}SaM_iT5;|d_!LWR31OJ#-gei5P+J~BI=8!;C5#e=Zr%CCcX(=d?A6O1w z;AA$B(89&sA0gJ_9`@gGcvKiKJAw-4Ps4=EKjCK}F)~+1#J)cV_O9HPf^`7Oox*MD zet+n~I}QM$Q)oY4CI!sJ0BC5Qx;!xbZ^y{LuLd?&{&T^!>VAYl?_cKOr||E zTUGz$m2fY{QJL;DbQ@(+ZH()cW21`9<#bI2Z+-E$`n3zkP~)YCZqLmzO$-hzHx=MrkIjFn=K{va2ohIsNU0MTH%E+R1fAkubE zw!KuJ97~Q1&sRR@2g(muCKsA8EtD*eeGqF|D6TTbeL;diVOx&6nw#CBR+sL-qt5N!S@MyzX+4vf{WGgmM=gh|Q^(e~N+o1ut@I}-NL zKR$Z;0eTPmOPaNW@TW-fOA8)+3+;zP+w$92e>3#f#|kEspNYqG`QNcV`7y?P;~ww< zY!_dF*jrX2O+e?LiB-YOi7nRtX;?LJ-}9^5u0)3+sIucE5iP zAlyzg&=EMq`?0H#Hbx$%uLwt*w5_3rXn^9^6a>R))XpG(qjJ%0!nrL>%T;C4zyK zPE!Y)ca!1%qL-^CtJH=_cHuD@HO+aG2k(t(9^7KamMI4-9LK&2+u8jSIczgxpj z&9k+#L{NPfod5=^51pnNf@jI{mg*%ri8EFX?!-N;6N=OPNpy+HeXNPvv%sb(apTJJ z@a|4GC96umb{dWWNO)&)&`B2a%cYaT+}SG0--LJeaTbDf6YNfqohK^lY=4;SkRlS{TWCi=r(=n3Aa^xOhHZO}ux(4|#_ zo|2B9%q=ku(y4)n{wa(V#>TNJ#S0a$Rc1a;!`ILs9$y_%5qn4O54*hCwL|(yGl)z( zQ8(|Y9t!rX6p4nhO)p;yl}KRZj8rJPweivyhFMH$a$NieWv zn^{E`3y8z2ojKd8rjNfSUU^MRcYMWD4Ot0MBYPn_rVuk-K!_2_@S~n&%Ul zltZ}-RB28;L=MID=7_Xskk|!+m1m8k^Ad>23BFgd4Ys}n8)J*b=DztKW;bwTp17}B zfh;~^W$H!U0L{pQU`yy%U93fxEwV8YdzC5S0T2nq76jmy+~dZIn9bl}e3=jEHxc+~ z1?HMWzvix+F9M4KTuWrU7grH`^Q521;0!EE7CLiQAtUbvN^y9v2z?q`wtb~{k80T_ zT;}E|@KhDGG}tM;i(xDCiMFYsa3!mHLCnJ8kby|uJ(wBk}5=7xP2 z<}Ni|Ng}~!Ex-b!6C(j^NiKO4tb-@kB>Ly;MVDp&gc`MT0gR7G=@OA`YlZQY!P&JbPEvX4wg;+!3`8{aBBx@( z7#QS4e?{8ZMrpb>_OTw*M^K+a7?|==*^?Xb&BztS3kkEzF;!$#M83=oy`CZBBlFSs zO2q9#f=d6j6x)-C)@mxZ?33$uTn}3I=I3}qgiyzdEJHxy7-=bdIv5^D>x3+w#Gmwh zVs=Rj1Ks`ENZX;o9>R*KTw!OPp+8mGCU?VKJr`CRe@a-M>gLL^Tt83|`Mxc9bjd0` z55LJAY>D{H_5*eqM{dktMb37OnexV-)O=UviC_bV4>Mh&7g)FIeZo+ZliUQ{_WZ2_ zEMqMOLtMtD=p|+BJIVinhI9ufPXKMJ?=0+I|Vpg;S3mBWB z`ijWE+JZxcO`EJF=UBoyXc+7#GA!ElLv|Dq<6;WAa(p!e$t6IHXdQZD>zC)S7*9X{ zD&LI5;6pM7F9vAM=-1kfzrp)x{ATxhFiVd=r6V)`po6VI=pbAbI+EN-E%unb$JUcC zYahES9#-O!-Kd|nbk9{E$?}xzlvXPIiukR)3afcNPuW;8U+h^m{bBCds#x_({;6BV zKO^2YBN0K=#F&X^P205<{!cvyvF%BZ#6Do`bX0hK-(uzb_Y&TFTH3=sjir98h2K!Y zY=dZu-Z@{sQg1P@nx3#No)g*8Ir#U;j{M*wDcFX-l0%&1ax``@_`Gg)f{-FMHa2;c zVr`a5&$VmE5>}q$(zWI#=@1`5^()85>Q|YB%46{NH+%PIn?FKFWMF=l(?r6{eU>oc!2)(Sqka#Dl@Uj$ru^7mDjMpb$oad1`d`$#R7=W3GG+X z%*<>*C?SP6P&oB>r5}sJi4u~B^ZJII)@m^Z(MzB6FNfD6JFau0AMl&2xd&FUvb?If z{0v7rl}Wq$0UVY@q*kk4gq^`yG#-0^=PBD-|hOiKG{oQvObS( zS8I#FSawCm#zt&$g)8(8+asID#_BekD-j8IBfgQx8uF1$-RJW5Nn(?Y$%i_4Y+@h9 z7MoULZCKDSi|Ab(u6@%(rn-wo)z>Gh&v5q_Wqi8UDch@#IPkg0^};Uk35BK+8u9SU z7IuNDWXNDLGL5<0ah4xk+%(W^7);|hQp`CFB3~iwvvyk4u!QcjaKr=(H+Qx z#CQNvL9VcBB3OlFhP6N7cos!8` z1{1a@==GwYKQ%8SSm@?HH@|M>-MormTD^Lp=+zgIA9k=o%+5>lsjCA`ap&9ftwf^Y ziY`VFDXX__iyYUw`s_aFR>dWn3_4^*(GPxRc5mGACieLG!&!u_(_O_PrGnTHcbHYL zhl?5Wfy>tg z_p3?p+g!DQo{e9=&fTdrH4Ft}f7iv!7B(HhI;pBxk$I#PD$1VW+Z@7AHm26Hhzd+w zpR*ZRiw(mcmDgH+Am~sPemFUTjn#%JKlhUF(lWNNM0DG^wx&8$FhP50BV zTEKytw@_0A`L;9U_{>ssCjyuH+~Y6%;l#^`2(TRek5;syE-nJff7K?e;>;%lXI8RiDglfyPpYCZ)l!;mUwWmCSjx4{e%)AD@ z(~gaeYqf6*%edE)S>sn8IT5ns71`sLMK1%NwWgk(!Zn0IZ!T#b8w+i*6H4_r<{)I) zolrdfh;<=P5qnOP|77j&M4zT5r|Gnc*y|<_DPz0gGOK=PpDIU1Ktz?BaIGTpZLYaX zh>Pd3Xnb8*#NT(aIkW)rv+6Z?yvrebHrDG;y;S40nnYEv4ye_2DU1v4r!@cmDAK++ z{#iH|3m#nS?#%htHII`uUvZ_NUp1N?mbLxLtv^Y$ppMg%U}s5l$tq!~FjI#rbM`lO zsK=_en3rkZWv%wBNdcWG4-bEVBSSs74?9a;>X*2qJ)Q6FpT7g6;AW?^9;j!T(6d#X zD#>{tpbA9<40L3pu0HU9IOx*rl@Y2Ry?nE0 zK3UUG4UBFP%&IJZ0Oh4%&tSs={Ml0j4=~p^X1>vW)}OnX0)gort^NmJtq`DwmiK*Y z4c%Vx3}$3x zr>Z;FhY!rD7=e{58h7NXB ze0h!~XDo9{>SbvUGq(I<#b5hR;+d8H>3OLZ4#Woe9tSd1c1C;~!YdHi`H z5KnStHY%YG)8)22IqaM14~x&cY)`l#g3W@Gc^gVn3-J$I0?ktSeunWi-;*afZ>pQl zX>UJ!q+I#*2P{wt?zHnMlJ!MyumntSns15c!I6$A~&uZ!7TH&fJnr&Zr8+WW@ z7Z#rboUU6NP2ZDc4Yw&bc&>%A(GO*98p=EEplGSy+E(x|nCjtUBMQc#pDeg9Q#^QL zF|j*^sWt8GAKj1n7h(~=Fh71S=Ilz{7+hBzShT*lVYw6Ch74?Ntccg=D|>2UAF`)Z zv*=R_d{V6aSrM-;lx3dWyeB2A^Q&W@#@4W(fn)|2eN4%9#WkJ&5$Lo8hJ{vEGztA< zrKGQ(`PoVEB2#&>R$lK`ew)e_k*{(?D{QS`$<{`tHnxVw%nki*T^vYS&7v=LXrrdn z+YABgo4xwlue4m}Wg!97&Y|9j-P@xr>k zxPtS_5^GWvp4uZPbPCr%)x^G=S4?SEeA5?t%fiD+z#wL=J(NfjoQL`1o;`(mqNVaw zSzNPQV=Z8d?}+(QLpn(#wgZXFXove?87?@5D_W|0otmSrVbN&G>(+SsNYPY1W0^e%JL&Krux!c*Yp9qRAJg(cKk2ta%*ArhLM0~kKM$503hHKvn(+-fNi*}__-sn7Ne^uM#d7!kol3A{bB&f7R|$q z2-&Bc_OBeSbm0=WBIJF0z^UA9f+hcIv#~Tgh4fetJ<*J|8C4jtPfW_~8rYU?!}`_6 zl8AtAU@izV5SZP}eJ6@R*2}Ea)QErvm4_q>rxh4cN$9I0SjnhQ(EvnePw=) z^(7CRyk`NYnr%Npg*4ULP-xjw&SpRny&=y)vRN*9W*p>|tOBovdj9(!1RnKUFI!Ak zQA_m_`_EFgX%rDO!hB^sz9Pa^zfMWZ><@%~0skTkG{WY|l~CX=6k01ak|=qo0<-!R zG!A}WTprSF7h%1N%mLbZ=(d)EJ7$U3{wi9<4hb(9$B&%gegv;J@V@YjSCX%hK!aOe z)&>XdrNPr^(40gM31>O-WSRTtFR6#DCOJKwwpXj-=N5_1sU~=;vs}jJ+VAzr{Xugq z>V^B<$gi*F0xWKLOUD`s4^;DL<&2ZGTds2NfvknK9@&s#34O97Z*nw&}Kuu^*4Y9}I=k9q1B;r}Kp> z60H+*RMBMcBht_W-V+pqpT*10c^XRR^1V${( zhh)=_F&c;usJV-DydK4}>^~GS&9a|CM%QB!^q6pC$Tl2@-q#p1-7lAb$ok}SDo-Pt zG}2Z|v%m5c%&T|iG-uXhBbszjxcRT|C7*jEvbaT2^DeUPjXGUWxkFD)p6vM~URLvz zvb#Px>uC5X%uId`%`QJ}n4YGNf(-Jv>)_Xv-E8Hw?>}G1$yQ8{Sml9Uv)r#D@MS%i ze=HlkzVC17OZ`?K28EP~tYOU;aG2f0&1~N5&Us$-jzFy7g(r`YyK5SWX)kDABon5_ z6}A+tAcO0W3ZCJwlqcT3;C_Awy9Q!qQ}|)mb@izkuDrwxt|V2+(S7SZ+P_-crzfvk z?6sdApRTBe%YH5mhK>fIt|x*}OF=maf=O@5u$Xl1%5T#{q!`k)DYLJ_uiFfbI4IuK zHjXWL`w4K$T{+R&5^#=bCOW@h6)DS?h{dulH}GaM&}ormE!yIY)a>UqTlwn^oN(C! z5?!4B*ep0bNrK>Xk7T$w-OO(j6(xG?&+7RtV3$aXqxf*U4q>qRTKX>oUy8f%2Pyno z5(IvUWVrAT=C=`lf&#`Wn7F?{??AE(9lg%oK9NtL%LF>Dc1gB$t@*pJnALA;#gu(a zMoy>%es^Dp`6A~kcC-|{N~$0*OL8p&-5=n$`qL>3kK+aRlOT;OW8ZLMcaT}e*Kvyi zc?I?4EEhQt8%_B9MWEASDY^naFGr^d{kHvIN(;9AA({5iCRN(+C%JC>J@{>UvSjkw zKZt~M`(35|<%$6E%ynXWX*iAIl5kn_Z$J(@kg<|q-uyHI*aa_Ql7L@J!7Jnl7Jrwr z7K?&=`E4G==S{v73VMdVxQrJw77mRj;++ju5Ir7 z-c@VGe-?<@fZFQzpH;)ZC*S%WNn%@g8 z#SACcx{P(M;r`00)ho?q40=`(uObG;nK>F)GHP@i?vJNnWx_}J;SL?)KzGrf1 zuixFRNX*b?q`G9Aj0b6A+D2JO`|*%_40qD=V#_T?<5fq$3~@v0Bf~@kaM&RXM&M{L zU8Klbim=r!*TA{xy>=8S1gm6S%r^?-Pg+uzNjFweJ@J%yZ+t)}D$q^lPJnU{cNw`H zm~|VUCoQ{Mv5JK>KaB23-U@1FAEDanN9V$35vh(j^;?~8L-XaILf?F!r4P6*tUDLd znGHKd*7sjF*7?P9Dx57_KC+GA#;2wA2M&~;KsGN@eydY-cHvm(K9Wuoy6P8_h7=Ox?yknxTarPM<|`UM02zFMr8$Pv2=A z;hc#uc4uV$)WBQoBa1rLbXv(h#uGn{d^cpm{*evkOf9X8VOty7dCjU8+=lM4fzpYvS!~&%Ax+kFwLjrlXX=qmIA}4Z}cej0xo{M}w1o^6Qo_V3yC|V8VzFrf1p_d>~Te^At;WhEu%~B)&8%+x=`f5l` z-fWA}*Eil7NL()CBoje}Zs1AF)g{{^8-@rI(eTZ3!*c-HTUHTSH?`)ib#Sn@Q%iMp z`NZ|w?nr5uAe{+`z@iQLwYeKu(~<-3@8QI-!!tsGcpR<5ojrrMM4bkNJ z6aknMeTgWritu;bfb%TB%z20F&`I`}d}mIym#mj6!dSxuwk)cMd_0cA#ZGhpU~X#S zcexY&8Nc~8%!yuSf%OZ$SQno$3v8%KvLU&ODfnY2{9Ts`e`MLwnVyh%uhCuZ4&;8< z_OUZ(9QU*}ckr?F>zbHlUs5hibzam0d3!A&VM=k$FW76o-0|K{KIQ)3@yO?9xEoOJ z)^utvk8YdD?#AlslI7A3<=PL9%JJ^V=alx!3XGhr3zfT5vB=t7g%<{L0p+7}*tA6ESXPJ84Fw{^D+BR+ zHC7XKE-`#~k(EVL73ii^uU@q3^)Hex0LJdYE} zGs|2^kP~^!s_48bLhNeeT)@XQys3KvqwVCGn(oe`ItO@DZt^-Y(!@NGa5gneM$*M= zBO90zH!vdxI`InJnu(tz#dpEb=j{6@J2=w7c6jIHIiz6>i2pA66$tbDarwPo$ep%v z6g&&y_jdx3b(@p>F-ApCw-j9Trz3I-TMCBTKXvxcQ2VFC{uyNd46uJrw14{AKRxZA zpV>bL*+1RvpU(DAf&J6=M{Vdk`NN{X>c5H$=Z8g`O8kWE&|{xrvVW^aX!$nI(lngK zoLauEwS&_z(*DZlc2a)D-YjWel+4?`g~(#Aq)u3~QK0L=5CV`8`vA!5i7$z7||+;`jAxmdwNpy@Y{8M-B-jZY^pv zYX@mDLX4g0(WqhpDeSIGT!+oq5Rl5F&&;ps`$|oszLV_Tmi1s0Gd#J|H7kUP$k+OxsC;PA$<@6Y-qks0pElQu<&XSp9*Kru)P4p?wWliby^y3;NLc0XTS;@e2Wt;r*UJy_TqZaPDeJ%C9H5@MHm^4-bOhNBShAZ;}Db+{UeP! zx6AcV;hk8-f8{g06U%oz{Sn^T&uKW1Ea@0AiUZ;*0?e>FIpGx@N@2omBkP>OU7YEC zDac-C&FK6{ZSLx}b!x}gH4t{hlVJ`Lh940n!^T6hCJ`*iH!JaGJ98QY@tVX1g@Zw^ z0*H}y9S3)CqHjTob9*!Y4$gC;hmkQje{7@EuoygEDiUOJ-@;W9ULY4(9g9zaVN7hSs=Y+S@E3WpJv4q+T!*6tE{+Nf53{X^+&(Z*>x@(gac0WVv;@T zC!EOnype<-!GOT%{Aq#QMJx^Adlb7+?(h!pEOP!o_TB|P%IeztpM(Lz&51QuRIH;8 z8Wc5PRDw_mOkf5kfFyucEQHJiB1tA@X1FM7G!u0iVzI{7o>FVu^whQ<>m@2ys;CjP z$5zyMM?p<>rr@QXR8fI>ziaR3nOg?LzW=^GpZ~{v*!!q}Jjv$^3C zy9E#4$1(b|to@IB$YXS9y<1wP3FMULJZ5`fn*NYdD`v53e`fzccPc5y7OH?L(!mW~ zZfo7lu*C^Vx>pWoZmBSlH_g<}r zl<dO3xF!2I&oY{G}?W9w}Cf|HFAa#@^!>7p?6CN_Ep37`q+WOKlIThBiRY zzHE;gPhrUy7b|!oFMA>$N1=yH#q5zv$0!f~XVj~nR*lre#MCpJi>ewJ7q+He}FIsoSry7?EaK^HWC zCwwr|Z-*bdnWb%m%3I&37v;d=F8WiJSm{p(S)YE*2n6cc@}B{qdePh@M&`q*t0bohB*3#5Z=eHU-6-`G#U zOmpmW`Zno+rPO1WLm&@QHDdKVG@qYmYvt0Ac=Odcyb!{x-7wgi8~Yo^TIzak=|bjz zrghXezd{yq>6K-Dj^Zz}wald&VO%))c;V>}!`{<=b|;5&JneN3yF2o-zO_3t$zk;4 z3@DJV&M9r5yN|Z^RP*N_*slLIQpr1!)s?p}O8qVVc5=KIJGnISD(cteS}Kc*mzTC* z#OI}+o*4-~Q{*Yx+4LK>lYQ*ax~gBN#%(W>1z@C1DOS_oYl+Qm`RwqkCzO72{Z>+? zFB|ykP3)jlKkaTSewL5LZE_w*dNe*ZGEDXIp$GfYaqt5jdafV7HzOIu0@juBHK3xCmu!V2ezwEZwGl=Q> z^d&MA`=w%Pp?s#~5CPjl_OsJg0v9Qcr>WSo8h91T(W`+cYd@@??W)%OOvVPd%=NU- z#Wb-I>}22OZCmr_7(VhLB-;ajVqt&!Z>c=h!@uXs`BVID-48x*uHT3~x(d4_xo*c+ zlUlz~pE+R6kNRVXPdAg-^7-Mm?^nS#S*#;+*GsWJPqDsidtmtC!C@5ZQL0!&!&^S1 z_K$BkCs>?_0#tKj&!zX zE4D@*Ef|_sN6(|2T3{VMlONG5hN$}4@N(0aS(G(#x9p=O!Q9je~_xMZA65e&WNVO$a42QRF|5j@LxI z_RF?OHHFJOo;dGldvq>ePITrEh*jXh{T{aPMt(?RwLR*RrQiXs>K9xsYkP_;WPu=8 z&Qq~dKvf@9`q%SB1>axV58Tbtvl!w(u=djaXYKx0Su%$$5!|1=|f*i65ff zBZG#qos&pU#yP!y(SJY3ld~nZmPn#k3Sba#4eMrpw5_#QG2?x177IT=-!<+f*O-@L zbMR#AAvjb-(8iP8>iUl4nGRj-7gt*mKl5U{$w7JB&(!$zgoI1SfxcvB^AAic+jTGS z|0K+!j|FK+O_CzbH?l4E9%hmHxhJ+=et!C|{wS>Shbd@~8a-5=U1RgdQh6Q&u?js)B0ul?^zTIG>rkk_utf`xB<^#$B*ZdY%F&^^m0}=}zr($f&v?-FY*6fGelwiuG_K>pgH1;pQSA)se)Y+0AF+!dp2U>v z*NAC*K#FpG>{t;w@>Hxu{2o-ro5xRG(EGJ@l5!rubm2qal1iw*o>y9_EflJV*d$Zv zpRhdnl1+pctJp92BfBsh z-afE0!ni?E6skl$?Wa$}qrClx93!-pNBY>({KYTj*KOQIyN9Yk-8k22hg@}kvzR7)yrzUv`a z%ik1N>y4X1TX-IcBC#dr=7(Xw8|fUhTvGWDfWPG3cAW(#v0kxR==WT06?oDNx4yTLiQg@l=BmEE6YZ9HC4mJq!{Fq&1(50 znJ$N#9ZQ{&z}CTndY~o@zZ|tXGt_#PouNe1t=f1MOGj@IA`Xdp^_)AG1^d>#TaA zoCvwRzB^;TzO5u#pY&q9aY3Qn56uB28X3m zyV{07L3O6cn>P)3MdS_@P;L2s!NUDg7R}EwHz0~T^4DEuiT;a8wy2NQ{GdJZfjh#L#c#FzCD+X&fI80@-`28caBvBe z%Fxu-_t%GNwbr9YP%!!@r`>DRE5N$?wcV_`e9pRf#ysvWq5H$uc=EBo=90oqbg3f3 zMtW|u2#o&D2#}&P$|kyG-`=>o+e#nA)~eNc@U*SsW#p?lmEWu5tMgSKM&EcB(|OOp z$P=NOmM;d{!dJqsJo1^FgHo(Yx6QYx=MjGiH zNp;xOM*ARBKa_qz<;cig$~1m`dg8|*PDld=AWA5nWn?w8s&5x*B zA9Rg--6+@QO`}vD;Y+I9>1*GxgzU|mj#FO2@35p73{tV~y5F(;cK7we3yT zqn0ZtSVH$SPreBfMyXaQw9p%$w5q1&iddzowHi&$H(}THW<6u~?-*f!B)75ft>^Y5 zXTpGLdrY)yAP02V)Nr+Y!CgfcQ$M&~g|1t144vU_S?k~un2A)+e9@3T=cXb==%pmi zDa6_JC)NI#{5o`&wWFFmScy?&93{Huq^^ zwR-Lvpms46T;w=nvb}P6E01$XSKE{8D{F*#^(W+sshaguX5TczqoU7$zL)t_^QLpP zj{hdjjQa}PRC`P8&$-&J7fmLg`}05A- zv7WnOKS|SH+x2&+#c#V_=0pkk_+Gp_vPapxvQ%nxL#t{3E>2js-|6@WYBnTYd&{Puv7f#?9<#*`O^*n_dOa2^H@Oto(3iSNU#ZpM6&+T)HzSc>GAy1 z1-#R<1hYcDcfxx}@`kMXFm?s^ZqCJYnKzdnd^w9)RQ07G*3~ki=jBS^^;^A@y zPg{M|(-!*3({|+^IZf@P2S*Ict~aUwx8&0o(t+$mLS4?ri!BMc)P}J7BC=}?M~llw zMr%lsVI{Uv2xTBs32(MXymbr1W|!bDZ)>onxeV1h-v% zLflaGo8>ZzLD`Iba>jO%&IzAc%_7j#s=QZ&umgwtzuPrL4 zR(7!$L8r7MdXZF@Y?-nDlbOj@UShY1DXr?fDw~$8^DRLanN!t+79g26%1BD0sSmBD zloitIViK9}H}X^%9Y%f_x1-z%M_Kf*L`MBKinpGOXU%J|ME|N4Q`X;k4^!Hv&HRpn zv5)>g=KbobzPclEb;MX#Su#170u_a{|8$8c`I_CTdl4m&xz(I;*yS+oAQlgHl*V7C zBRGwV?*;}Z8+C9g#cuq3@D0_XBlbfg>-@W_pK!O2?Uu!3tUZ_9@>bqH=^1z1xys&K<9D~Q zsnP+}-qrI(4tdZAQ&hd$4q&TkckKNA{QU;=rZ( zMxMwI0|=^ML!S9%9xu*Bo{0RJRp8afDL#=`OT~uea+tiTR1v z*WK-PPg<@zOQ$P&lwrG+T|tg$NGw;&`+08J_9W+d@QVISa|u1q*gi5v%9Q?7>>~!v zcyK|>dxO>BI(g->;DF$0{Z$#vPvUUcVd3%|Z*KzSR}0jq;F?aBsS@3B295ps9^S<8dr z*sp%G$26BA;W_5toOgeVb7kd2o+@K!{_R~qa@ro$@!NHLr%K}1aYVDVo-I!- zo!DAWk zA6|1q?R0n^56-aHJQf{51==aE2QNlU zISJ*8yv3thSbs7)ln&kY;1za0G|rGFOM2Wu`Phd8q3c0aMyjUHp zbW8{y%|;h8bIPXVIoq|{rPvJp@=9*|q5)R9oI~Hs>8e)Oq`X)9$#lClcm`L{a2~L` zyyU&$iHz#yXzgej@zgS^tVP-$*b{j&D)VpN$Zvh$7QS360m<3XG6hhP=ai!!ACyIU zqQ94o8G;Jcx5w#2#(ff%{W2+wlR$E3yy%0y!^vKwo7Wdwz3{e6E~cP$7P(p1ByH3V{!$mJrX(De?eB$#cW~S)V)qVwWxbK)eQp7q+ zuQkzWwaeS$k`DDve&ollByhd1g`2q$COELPx!i7LHtcY>FJyfB1c~3r)&y1xP*_{g zHtJ3-EOieO@4vXX_(U>N=!(4NYTXi~_d$Rh_jzTOfK_b;L|!Xx8(iMLcCfXyjl1ZB zL3i~GxuJ*Cii@qKwg+~*#ysIFdCeAHBZ<(J-i~f2OP?c#(sxxCtya%bDKh;4<#Mu> zgGXid$m2EFyuD{|%{8Cz8Ek8n^AYgtsTn77_zOVG*V`dorpK>MSA;|?g=Ti zMU4x1x%AaiDIv_ZU&yF0ynBX%rMLNqv}%e$jQ~^@+I6CdvyEhQJREnPL6aaus)dh? zzDBN`?6k->j@gj8iX(JxOs3-c*FgB0~xsQHQ1)wD0|_2 zb)|xW=ZZ&Oty#ow9`$5+G=}Xin|l~mTcdS6B$};k^wF=SR)@5<+e$;VwHBfGRH<8M z;$ikj(mqoZzFx04iWMS@~lU(so(VLEE&E z<31@zSDuoW0xoxZ!FXOZcDH%9VI{8NRwQ@6yJT8Y*u-wHLg{8Z@_xHBTOoo&5e)pKLxLwi_-<+=eoqF7kvp2e6k zZKS8;ZvN1;^jDXxh0Jw`px-*v2O0G=GdvR%JZ%B?++Q(m&)*75^kB29Bv`>1cb zp4;VWt9ym6w~VgzO4XHis8(oIN1}*Hqi(v%VZh;qne!_(CHah%olad{vV^jIMcaufFJ84c}92VYy(P z&p?UYP7U}ldZ8we)LdNFYJ_|;%}(L|TrD?Aonkg6X2AebO=wp3LyNJdsaw>fCG>~} zUFbd0Cfb(*K{&g7jt?KY0GWTBH3IN*?V=i)bJCV|chrcx7P%&*hO%cb&=n*c188b=q*U`qmzI zyK@8;p1WF&PiYayr{Zk2g{{PKx2bWmg~DrB4EB{gB7f6Q0)r<^2|a?54(m5<4ClhC;LIjK*yMDe6l zd~VfiR{59u&pj}6Z#EjqP!2b##{Upf{#|#ecHBPsf?D)Q)?+tN-{iyrquIA)PA!#S zDjb%;h)ds1gVs#~uOIHuRb?T2wyHx!lTsK(!@j*DDfriiA)Xq$V*Uxg#NZ zHLAh@jEWL^He0K_ks^!9)W`K7iL6v=kBTXZ~F1cT*~f0Va}NV32|^0V54 zpXN&ixSDll#by%Kr_Pa=H?!S&YA%h*9htN>bfZY9hqIbP=Lw-jLXJyDo4=v4e3w`ZC>7>)N-`ivouM=I>G$ED!4x~e{88R-XdmgPD~F&b4_Nx{Y1C_x=d;(V-v>m2sj7}AJ7 z^p=|J8|~|#n18K?f!RL4^88D#A=JjGvX?J(wpA3e$VS;5#g$G$zTqLS$&Z#=(X#(& z+jS?>SIAIdb`rJ+=U|V;sD+;~n6yKO@rqVC_{BSc@9Phy?>fztuk@NdbN?Fj+QK(e z6G}N%!z*y?AxQkq6NE=_vXif&aqcG6W2;^(kNn9qU~XY~$+mLa z)VFal+>X?^q3-qNa?nrC{D|DEN?p?7?I9^{pwDlfh#B^xEi8N8dc7>Y_fU3Z;t?6xPE=R>h%ErCFy}90>(A&{wwB692%T@~D+(iS)bbdoogWLm zLkzD(+&b{NniC{cN?_}>LPcm61c{srQEUZuEjj;|4l-^2WTeLk+{C(Eb)Khv1!sy_ zy8fHYfUZVSw5dXM6q10q5DmCrQTC?3G!ioW7!4Izp<& z6jLm_{NTpBDZH#E_Jmwa&CFTNeT$+$klsaxplNpAgOee(eYMq94e^+*QQrrWW^(35 zGo~E}>@xEj$;?YF0&IyMCMWt;`=?#U3Sr_oZ{Qd&T5Xk1)6;gOgNJe%cU|Pn(>AO; z@)9+3*I{P)mPh`_9r=s9?XdE;=@_3+uNqQb@|5j*Su=AFc`7)>-8Q?BOZG!diCH&@ z9R?S7+jR26qK_*gKL$QlEk%3w9{@K#vA3X6N1fa$Az8-O8o*7R&5*hou~5 z?wpvX<-L@m42T!ZY|sY>ql%7J-$4PhYxEIX0~Osc4uly+CifB;wGuCTiz zD@Mk?D{8`mzb(3fYXws0`?7Vux@|D?r6x}144g`HD1BJ$?F!e{>2}GIEZ1xuL=&c8 zmZhTERJyB1VupX$9z2c1JO4pBMF*;JVc;YDc14bRP@sKsvwE6Vcya89I{0VG0u+kBCwDdE*w2W=XArY>)v%>i?{nvY)4D`VNfp-QOZ1_-oIeufa55Hi25gLf&9 zvwHzU=Ct*ae)1!|miY&0I#p&lRLA|Pm1tZ|k!@k=phWey@D_e~+D2bLMH*Lca5#cY z6A|xvM~S#hWT1!~u9D>=Lr2Es-EqFuD0XORP?V0&%+Wt ziQl`9Pq8-{w@Xe9E@N6kW4l=51dqV%%?b6o;3bAK16Cy8l;hzlTVq$K3Y}QrO1^5NmLXbp7jXsfndggM-&cCwwS@dEcw6*( z++c(dogEdEWobPR)+(`u)r~ploz{fqri{0M?q2D%ZQ&n5ZSwnx@OuD$%JSVuh;-ua z2(6L+*)3L_nwzt_DU%CKX#Gm5TIyt-63ZH^^+gWC87r~WZ#=^4=)BAoup&L&+1=7z zWKO)%-`O6LmGPBST@fj;Z`oRFrH!^7S3-~!)! zcLWnwj8@q$q7$cgR~tt$*>~dotv7-7*vh-HbiI*IqcTC^Hc0nnI012^u%XGQGCWmrj3{Fe90os_Kl8vn6C@ zRb8#uo}_@yIb$rYdT%Z)-v#sRfi;1kuihS59ts9)8~{y;5lHyN7rODQh1NUIYO%*v-rcb>1o>uW0a zdwq4uSgNTSE!yc@SzGO!R#z1WEH;{zB}))hGn+RVldhu9*OV=EPH;H^riidm$=D0E zXk{zuu*^!QAJP(@-{`Fh`n)Jp2f7=*)0S5?EKBh!lLl82tZMKsT_br+(0Y7TD}C7l zrqX=<4Rf1(fk1*-`^|4?%;H<=4^>M&)gqXb!8G4;e<pW;8i zG2uJiUmXgltfYIXOeDN2szuR>M zsG{1};8U?Y{y;DhBk4V(s@isk-QSp(+KYt~h*k?^Df z4NtgveM#TMKvr5EtX-K_X%azBA4B1R0_XWI3;F2Zlj@r13;2SG$O)ZjNh|$TDSC3( zGk7LC1*5KtU!q-WKgr1~-x@XICK!rd`gzjH)YjBit5I}ux&qRIGSqNEs5V)8bDR9t zRPr=Gc_^)xF@T{cwH@iMFQJ9BNVKA0D4-i-LhR|aP4%l7WVAOVO{vPGs``8lf#v>S zWmD}kEQ>V7Dpe;*5Np^~AUhT5w{m4{`V5?l9ujV`+KWymTYE;G1HIYYO7ad2{Ou( z@-kXsazM%SGfK#y%M3M!85iAlo%ES$>}U*?eyo6oWtkzfu{{qEL?mmAT60buo*6OHD!}6T4H!+{aYjnn!p3I}D{H7) zs(K9(FliDS7Pb*3=}(aw<<&1}Y7@m&>7U+&4cjkphQHE3l__t(0Ap-SPklNQvq~m5 zb#w@34K@vU31f&6(;_{R4D6{EMtZ0i1_usxhUy!Y-C@>3U3O02($KQ>wviT));1`? zl&&PD6idC{lz^0ONhI{BHjol-JNQIQ0jLUd5i$lic$h6O{lcN zXR)5arTeLQ0en+RY;m%UrTR((TGk{hKpEuogSBS!C@ zHFiCkQAZ>zid`&K(9WTqFS8ik8(oQ@6DZc7`|m(ltn!(7wr9;;rWroX2#^(3 zl@X)9jyLP8r0ewsDFSMxU)CDuS4GwQ&%06<8LN08cpF>j`_1XlfhE)MrXl`hyx{W@`_rBvg$KoQR*)o4Kt6jBT7L*d0Qyr=c1?=;TN+t{Dx_4n; zf$~*_r@2>GHK_8$Ky0AgW%W+=MTzptpbsUIGa4D~M|D`zfl1af=o|dBUbYUrsdOTH z2A!d6%`8OCl?qzD+*iFq#2IJiwqHCW^&q{-Qo2o%LYH_3{}j4_Oy3kG%_dWhWd2nD z_Z=A~gsC(k^_Ri7vB^)XuMZ^q6H2~HMbQJmq0{S@bm;W#74Ub+^v3vd==8b@96G(O z*va~+8cjveS5;5lr3*JVa%9uOtc@0ia_Io{3{HNrY@DQ}^VhoqUqWYW|A;>N@iX_T zoE}dKyZ&^>z@JK!m7g*mWk^Y{6OiFhl)^R zBXd-rcOiptvLjS6`lT-dn!9LI*NEAboz5^!NLd^CVy^Pnk00rmnxl24->@Bt6;N#Z z)0>7&hN4pW>M?z>(cR7o1?SW_8QS{EY0x2oISjLuY5Zm3XA;pB8kGs!EOcxX8I$J& z)ep9XbRlJAB7>i7AL;Q_4b5r9sp$$`ve?qd(&Q65H7KW$r1DAfSnNE@Ic}WG7+ht} z$v~=fa{zjC$=Dz@SCrHBlfvJaQltoyMehsP-tsq9H2SJ#!JI_}X+Sa)SNm<1em$%j z#r);*DHqjyEvEVg=P}l1ZkS$idWrqG<}I=kq}EX_{*6)e#Rp zT}`ihg$mXYgKMVANURtfirhLr9mmvK)dnTvSBj@sSPwZpQ%_R5GGZTcdX$S=i8QRV z1-_;LjqNL^TS2{%j)_KJWfadL<=2#(`E_RWe>VPXmY5G+enV!KXfRs?^JF_zMdrUl zDKArKHF_HnQ{$<@f3f=i0HeC3lWe7?6;Pd+rX@?HKb_N0cjsbfR&6#Wsf)x!e95m zMl22YR%T1<%xa{$k$Y< z$RVb``pZIZFrU zlTT)Ng|FJrEV*foE-uuRDy@{G&R=5Hx^j7_erW}#4P<2^8Ey>hGuX~+WKT&>D;Nh1 zw16g`EOcq-6O8b*#%JaswcHZ&%m}fjo^mQ9Lm%1b*z--~i@qkgD?b(c9vhEEC0%gv zGUZOAGZvdu^DjFHrEDFdl*Lk42J3&|Jt8dKUl}c9{^42mV&Fo+M7t~w)lV1{Ns=J}Y4%gUkD zd!2k5N0UzVRuwC1O`<@Cj3!-K!^&FJR?n%Ttcja+rXi}&E=;d&s0}PnEuWOJgeGt7 zuclOWlTTJUqhQnYn;e^x{AT-B5kG}%vi_v-^|0ov#Y|~G6``f|wG4ZSGZy|t%~d64 z%9mkdvT-5j1-*>!n4_nSHoJ|~^8}cI#&Iq=K9JlLF!&lRPLEAi#ULVWGM~%n}Y6G=P)t-PPs>m|=DLSPvIZ{ z!?Ya~O-s>3Zcwt390)SU%|bWZpHfM*wzAS0c~tgBHa^A>na(UrdMN~ka7?LWiTwci zFw$ieLZ4_*B4*)h(50}?t{1&NU@UrM;giC^kWW=|EnpUUb5oJ7cbVAH2a<12UFuG# zblhrdUy*0iXR>{#^#dv5>2jVLs=>g(DoU9)W#fl@>KK5Sx$IvaFkPb@P4WZM^{ewj zY1&C?deR3-^pOtDE?vH4P8Vw>iE@}#sc|eNzbSOO%hRft{?<&FlQUT(P=vC-A}5>F z--3CmBdb=Vk)hN8_LUDzpGtT^$QSZW4{(D|uPz3;|M8J{a9}>C9Yg@A;Y%6S1uHYWAVI8p~+e?ON@wVG zhR2vQsM82p(l_YRjLgKrwJh|yI4k`u5Tx>!EM}D>jj<`QR!CO**_>CQh!g9f2jXkU z&5ST42GIf2H|SE-T)|rsN`Pej?w`-p3Z6Lekal(ob3>oqBHwZ%qBME#RJw{Z%h$}W zq7%zFYk#1rM2|uzYXND8rxFPo;rak{@|;sfc)xQ{8R2PpmXlC=`tM{57?Uu0w&hFd z4$7B`x`0UutA0{#%@u}JeWdfxMxRK)P>{}ldOYO+O6g>yKa_Oz>8y0hZ1Sk#IYlB7 z{ZQyqIcKN$H)gOs0N*saRJK{^-GLOYYVI#~p47v1J!hdy@Xkh0dCI}UvemrpVRnUw zK$qZoAid443I%*AA|EPUD&uT&5Ke!R&iIh%QW$5Wr@o~egA{4A*M~H^6rKm6$0#x; znTqQH`6lTOfiLAI9gv(%QL`5H^2tH?XQR(ZCTo2nzbrCvkSkDIogAn8*Sj>j48~gD z$+c4^dGaz+f~sFQuZJ|H3Nix%_)#!|t7_H+D}5;}6O+F$ z2~V)nbb5Y}!Y3n~(oYFA&Y31?L?fC{I-OBSZf^>urehgH))P{AQciVMa?sn@LOV3N zBx6mlH^5Wa>Wn4H3^}!TMrBH&GV`P9WGRogYg6@{#wSa7f>%N>sgodeW;Q{hDwH8V z21(`t+H7>_**G1GiBVM-@+D8m>gt&+4^2nKlM}H?vV>fTaI|sO_$0vr`KY6>hd`%K zyk-)b_HD-eGx0J}{+7M*xlitmFTpk9nsMuKx8v@{*$Mwwy3M4q4Yw2b5zaz-bzAqw z*B*lNK)Xojacgnwa2s%U;x^%)!EMLw#_h!ohvz8VSllF>2e(M@zrnBF{~8^5{zQ4; z>Tqju>u?)zcj7kTp22O$?Z)lJ4X5lz;l|=7;YR#rZ`_Le;?H~IALC-Uow%2Af5AP8 z+l0Fh_gmc0ao>dgYxl3w!L8```?%|HSK@*=(e(;&DefZNT*L3{GWge&L8@M7pzCkr z&c==XTJQhAYxgHnrpKg|>*4&)!^NN38~+6NKCTz{I_`Pg)40vJ2XS}deudkBGwaOF z{Qh3b^ELcljq~GbQv5IBcO`BXZfc6Z$)^OrqAdPq_$h>a>mcDK-M<=-M26wG0l3c@ zPt5fG&hIF02ks@@pK;x|hjI7feuKLm_aoemxK`X+oWu`+m*T2$7aD#h->)&L<7~Q^ zgTAJJt+PZu%%-FNmwuBei(=eqxD#(_f8dI6Q*d)}OK@j4vLbqBz*kpurf;>+(zMjFihq_f zg7uA-<-uU%#52!S7?2+|oR|^3&^crAv^levho^b*(1Ekrz=E7}R)$9f2Mg+a7liyl zs!t%uQ4Muw%~Heh1b0o@>R?k9^-K1UoFO@$Wk!>iPO9qE8f3syEtjBG%chVP=~TPL zZs(P1A1H;5YG6l|I3=M*djrQ~eNAUrrlJL3pqf*k_JF)M!ntGKzvC@T^#XrVUAnFY z{alV@N1MxN1S@=N^e_9jC)>w=_pBldGOCmCK09F(?Wb7Oc@uk$C{^_BYm%xi^&xux zzWDHO|NGsZ$%iI`3t5*K@-`d4<@w9ptwx-GXI}3%WO(WjWZC&8G!qU`Zp{bqmwazC z!ixBPgL_~6vg!YR7v-MqOgZLek;{U-BMq4^A^g@ubQ`nq%1rM-&)c%ZoiL-nya$SJ z`mZzW4<%?28xUoZ_C> z7zQ`sx^M+O`{EtAf*0|_d7slXGVU#{;xNTxJ-SYuxVU051{P1D>L4RB_Y5>}8;5%T zOo;iD;W^Y$TP;@50f*^{azz8feC@JYZbI>`#yH^pjx)YO{N=vYjLy}y+;yPYq;s)Y zs=Qux)f?e~+SOdOz{zzIX-Xz17fEO%!IYOnMI3R~#$hd{hWu&aFnSVqlPn4mQ>+T& zFO?Tt)SW5;^}Y}HXVlfmZ6{R;C8RU8l=1e;ngeUb;uV_)MVBvb@U2?R>p;pvT3i)e zEcd~1-MG9(fHbFEd5RrNN#7=8ulI>@WEY!JNu5GB@f3Si4H-WGX@cKa#ZTChBZDm( zu0wC~&WXX+V!oV!!DZTh5<|Ql<7b zoW5!~_XY(T<>qXyD8)LBn9R>Eo*D2rj4R@GpQd@rGCbF~QK3w!rhmBhH}z(OpPP(7 zHB>8xwn1iupEW1clq5;8*mJe!^O1>hZXo9UK>MW#W!z$9x%do=*B_EgdWYHC+ksF{QcE*vw_m^+YyzJW!iCyk1ZR){2DnV&xMEE0=gayynWchQZ6n~3CX zhkkqm>I|K91|pO>bJ7)`rbty#H$I)IwQ~@;GO~Aw;`Eb;H|;bh5l8OIQ8xoIGN2Zv zJ4296{Zz|&xwJUd91X1FVk6b!`lTbUbVw0jd`Y3YpH#h_Ge!+UDe0A!69`V!Ph2Y1Afp*oroqQ3!0Uop%2#fEDP*!Z*3OHvWA#--sT$CIjS@wA z9~mPLDp!*_3C0nB`tLNgq%aayX6kVnw{NOQa?xv`aLibv`j|aoM)ZF1v+MQ1D$Puv z#UYNqr%9Yv2$}RL=_U1l5Y1=Cmo=-pmE4MLylb46a%N_;=&N6RvkVVVc%pOp(G7j6me4%|o| z{BTb#Ck}28Zb~h@aE-Vne9>z??snYWxXrjdxNVmajw@;+ZSYnDSA%!+oKWPK{NPI~ zsegvOVd48^X@8mi^4y%tTH7-vVlJxNO%tY!L1frFm zy#(P?1x%Q^ry#mE*X1iDr$`>x-%tI*6+S?H#cjTadIHY9m%4Bt_2Xgc9d0fkQeTbR zh+Fayez-ljTVJM*yh8oKEy3Ngwf;~*g|SO;x?SCL>cLp8;}bPOu?t6ghg$Tu&}i?O*mitSKz%QS z%MWV36Ollcq!ocl7E)xE`4wgJENA)aW9U8a<>0Itc+3saF&wib-LCC9T*aj@`l z=H^Gb%CkQGuxPM)=U{BrVIK&=A1)a3W5J`l>jw*dzwc6Y_1f9Ls*cI?FK_YQCOH0v z*AEly+_-&>;J0Eg?i9S?)#v3aU6#{44-66fR;t*tM#2rjs_?g+uncdSsa)L#DC zQuzj$W%tv*?+MOXlv5!1YTck}!RpDj&jtT6B2T{EYI(}uaGv0I^J_hVy`@WD6l}U| z*)Ig2>m4vja7K@Hmf*hD5zh;*xPR!c1V6vy{<8(^ZoPM^;7d)+%yz!19KNK8!>tSyRK0M;ms|8P=T%RZSqdMKF9a{Fy0={LFBjZDQ7~xP z^h?3FiyrO~EdAAvnSw9h^2%hv`tIjC1;6Nf=>@?{W3_6G+xu!mu{=+|VcCBPZrixz zHNn8?R;S=!j~j57;9}3v-wHmxcElTklP()LSMax`xoSMg&mZ=PJYQ!Y{+zv}s)3Lbg# z>sG;*Z*C6=eq&hmJA&c!yd8qyzO;UX;2qz&^m4&r&mPt*_|y21n*~p~%Q95(p4$dr zDd@b}_L1Q8zs$Q{aQVkM-xA#a_@G+BOBOEuRPeu-`I-eUJE!hw!S@EOXb@a^Y|nnd zou|DJ5&X{OujLCqGxLpQg8m&3eJ1$XhmYJSIPH-Kj}mA@^8{~M zHT)UD0W*d@Ecnnjb59gJ^W=f^1s^%@4^Ijf4*TQ1f}w?#I195j^?h>fM4HetBs~aOlnTxq`nLG-QL|`R5$AOR#m> z;3mN%7Fq@hUOV&ATLcR(-}tuRU8mi1h2Vr^9~dt9lN+D^f#8ToUi_=zgCA~RD|o_= z*M|xAJpaOVf>Yn_`Mcnr``%bC*wFIY@q&N;<|Ee#UVQRHp9sFS>TbW_su>TC6nytP zc{d0)UTTXA{^`6yHG+$V;zs>i3!P>i)?h$+;zM@L7?Af|+3a);8=k|C= zjl-W1Ja)&x?+CVkn0vZl=HKjb=cr>M+OFX8kGjCQ)AU1`W%Na-kFGzR6Aq)R?4y@r zFxf|6WFPICIJ$h|=!!E&k1jeVloDk4Lqj6BymWGO*cpd^d-n8rd;#t;+}pSTGve`+ zaJS>4xI$MvegSSPZV%4xj>p?^f5zp^G4(Cfo!M-x$WZ;rFj_BJ<7V z@pu6)5BCe)Ex3sB94X^>iYv!|D(-3{d^n$;-9Dc$P2-l~HeMuW<6b?SgdIgntR{$3}R^!g$|ycZUDo$I$R~ri7Unlt)gFqJhZ$=!`U$7GA{5QK^^ziR=L3I4@bXKE`!xtsX zTI$ePoLQH?#(%9Ytmu9yZXIpmYFq#(&&w;*T_OI*;A)KU`IKEXE`YlR_YQH2i6ib~ zep~R9-^0OUaD}*Y3_mA$6Ydwd`*7X37jZji`}Xg~<2x^j$BS@J@q8<|v4Q>=SLmm| z#mRFsnCdR%If}o_2+uioz0x1Z z{|q|N*~uAxu$lL0|L-V=Q{WF4gPs3H zIe-OskzX(f?gsn7QH8|27k*&zeeeUF52A0d2kZrd8+n%a46I@egwXt7Yu?uobkOA?0o{hU?1-fkHRu`JPRFY?Lj|aB`6kiC%7H#1Fcxd zju%N6tOP5;Ft`@%1v^3KOO!v@2|BQ(xzh;W8z7=edHVdou80CSo!JRc#q&0=!x{Y z_MuPEv7h{am2u*My}A41V@WqWi1Q_agZIT9q#GWxFTPH2#J>15VBcZ;;&r6om%lIW z8ISyj^9%;TbztW=IHz(J`2>r>9AqZm41~KKF|vWk3|m9I*PM1pcm{Bf3Oei1`C*ZIgTS9 z*bCNy&To+p*a>!lRy%Tml_%_rk2;rlpc5=U5qhxTWavRJ*bR1oyTNX-U;_M3fj`&- zdcoqteetmPgPrnxDsq99V>ugCLjFN7XdTb!By5|wE6uH2#ll+4P)6xGV z(&a4NTCiXi<;P5;$Af&Jbv9>(z+ffm2rl4U>iO_ph+JUhh0uZB7eOcf7efbjEk*t* z=*J6xu-iwzz;FOPFjMUUonXP`qzhJZj;u@kuZ2#Yzel~9iXK4^=xsw@(9w?nG{SGB zK7gG+pqxNw2l@kxZ=rlZ#}A=%lCK{@2NwSrIxu)U^$+a*Ir=F>o?oILu;UKo2D`z% z;(rhIXFB!aA@m7WZX$nR!RCGOMKhp#igE+J&%zH3gS!QLNY@2F&R0Dn?F`%vc7emG z*FE4^un+8(`u-B(p!H?aque^c4N`uu5FhM$4LwtS&ezd1Sn%e)_;z{TiGC?R$6M$R ztbChi%CGC4eepX%YcKIZ$GhZ5@Ne*$jC{M`1NQDF9kAH36r2o~=_Z=xsADth^he1Kh_qbKyx4Q>F7zaYP0CFpg- z9}I(GuoLW%aIg#P1$#j2Oyu5+zCb5f33|aG7zR7QF0c#i0eiq+un#QQhdySJE?5j! zf|Z~b41yhC2iOI6fqh^v=-5xX9_T>_*adn(M;yI@VXy=2wCs;}OE}mI_JG67iI=-S z?gYJ{7wiDTV0gg(co*0S_JBR$Ua-KrKkk@Kc@5kjuLK=n5Ud0{z#gy%EFQE!Zk+=k z&;fRUPOua7f?Z%3>;^l*;9%lOIM@gFfCY0&CvShe7%T=WK`$5tyTA<+K4gD<6Icmu z2gBfA2?s}AK={!8@kwA9Tm*K3Yr!6H1K1000)r#=$9IFBV8J}(0*k>OuoCP8gJ94` zJTMGy0*mv}C)f!NuYe953px%b9#{+p!64WHc7R=AC)fjafqh`{H%PY;`+lUeJ0xa(o9m&o=ZN!4zL4s&W9fCy9j#F`d#R&kz)yZl70@f(r@*F z4zQpKKA;oaOL=vI>nIoNQsfc6diTfg6s#dX=&y1a`4&BaPV~~Xob*si2Pf2X@z!zUZw1KIFHc5x&Uf0G|Pi!QG$}9PTAPI2H_p9ClnXcs zEM7_apcm`_t*b~6bb!5J?`rDba^hcsykHRI6(36%*a7x|n43%HUNCqi^3|f3 ztB?;Yz8bxOmEfIVC)fjagMDBxSa2zFT!a3>a0}^xJ>Ukg58MP=!=wXxThYS`;)8Xd z^E&9j@b&Nod)5(NhaBzj1AD(H23FpWzQK-%s0U#93Cag7{%`c_hd<~6t$!ikVApf#73_Eg{eT6pQcoM< z^E&zgoo^DKa_<5QDCgoGqyvWEB7b1-J3N!G&R+5<^zR}+*aKQGBOG*qj`v6xtOV=8 zAh-_f0Ph65z-Pc7a5vZs4sRl#;8@TaB|caH)`3oN9T@x@@`Js*hzIt(Pd)?qe*it` z_&fOoJHR`^KClP0eoXm-UT{>9aL@_%f?m-3Khz^I2zG&$7S`v$FlY@SFX#Y!K_}P; zdO>Rr>zrVC0Be$9ftB@4FbM7iJHSyZ(c{2)d=l6VE&{!S;_(?Fi^n^`Ua(vI z!CtT+AO2UM2XHLt1U;Y^tOGm1bzm2GC)fu*16mJ9KCl2BzLxmlSg;cGfI+Yh>;OAJ z>o-UjEC72!2WY(#de8xSK_}P=2ElHy1MCI6z{(?t2YNy4Rq!o9A7H^zlsD)E!(b)Y z33|b9FbMX7#Uok6zM5yS80-cY$@9_V4|E;t`^^;GzS1z;yw40eN+U@zzetzq&9I>0dK1Uo=4*a?QgF0d2q0lUFo zuotwRM*LRzgAULEI>BPl3s!<*umikP!pBk%!ESK)b%dWzy8?SbFW7SidIKFrv_r69 z9Q?0`ALszRpcCu{>p<&x=)sO+^Z|B(eG(29+yMWxp$B`xAXsn?^q>>mB;nw8um`k8 z&>QFgt>+RCbbwya35LNi*a>!k-C!r!3wD9l@4*LjfPG-4w6h7M3l@N0{GDJJ41;%q z9pE!yH@F+DEJ5xz_<@ta;)%qQXKhvm3oZhKU=Zv8*MXg2C)fpU0=vN;un+75tu@q_o8SXF zK*uupfW=@C>{w2^V6YZ?(0M8O`2ln*kPCEzYr$UdPO!L+@&hZu?VzI`zBf~TU>)de zAfI56HR$6@)?4;wktHf&X1v*r9_&O7xi$B7bCXq>p_O4b9#qx7)+>vG*A z29?5yM+x`h8VO$pT3ix7ZN#9flHuZ=bNO74l3?&pj=axqIo6b;m@tv$cH;lTiauJJ zlWAP|{Q);x+Xt>2G_PfF?$tx#ST+n=`IC6tamz14eo)Irx>MT+OkZbh8JO!9`dPzP z3Al${t;JDk6_Ee@@9d4AEAdQu=Lp^GVY3Z7$=4+43ZXk$=;lbiJR=4jtz~bNxe~nEH&0Fk_ga zFNW@;i@9%0=zkBr(m8pXq3Ev>Nrkuki5$JqHC|%KY366PP|X--6qBMGp3Av}FQJos z7em(!om7iN+9~B-Nw}nUnuM#opqJ@dFA_g!#6M7Y2jS}v5PuW#y9mFX@CfxGQQvZx z=?vvM1uKW;E*2~urk_2-g7WAY)*vu%SZ=xCH1qL7d77(foWmOB$u;a^f%0LwmuOO# z_BEcW<*97g676Y(9TcEPT#-LG0R2?$jX#uCexFXxOg49>JTEXM)!A_x8JJ~eD?{X^ z5@-4_BU^^7N7(%n(%H68v$*mJa(JKVYk~q&`v_NoX zqI%?38uT*+sdoz9Nt`17F5{VS^VvY7?igw?n5Dx7!ePd+bkBpBBD9uvWlnmi1hD>ZfdBF8ygY ze3vwGSCJ&-m9b;ih(Q-8$Dv-rZzud&o!YwFjf2NqOA$%kQP( zA5^mb2r7Z&*Nm=@tAmQ5x|7jweb~;Vju4>SAVY|w>KMFcm zaBuv_{IuzIyGDSLVyZ;^AL}rHjg&m5lcQZos$Th+u5w`EXB= zwnJYg_*Y`y>O0n>FGsImvdjGav4CkLGX^RpdcM>VddL2&A-oDYe62ikedjsZbA35w zGOyIH=MjBaOwF?fL#_^TG{^Dnygt$fedjyb^L#mTWlott4>^vF)F9be2DzkxN+k9p+IGwZX`IOk@Igv_!;+1UWO#kb&lo|NAlk6aeX zWzUtUm|SG{5J~dNt{d#^nS%8h&P6RExgsOy`bE7rBWj=Rz?b0slxi{6KGg2e2_E@{ zuNCIA;FF)Z?Pse6Umrce?h~MVy8*WoxYu1A`NVwZV!a53rFT%)stHN&aNuX-oYs&i z{9Gqr`OwYE0Ma`XxDarsp*%W&=*=^AcLDU)x-~$0*8*RQb6*!Vt9Poam-3IFsps3i z!pRZcSOde4v*5>S)F$U4JIa7x4g5<~ueo0QJSTsyuS{ma-Bh&f%vOiVM2d6q@W<2wY{kH$DKDJ=amob~P2s4H(xY zd^PYT(EBe}FZzAoGN(Tl&uTR|ATY#OLVjKhd@b-BFlX>hy)IHO1*Xo)$ybn7uD?<~ z-CE&q*X`S2SxiPQb482XCvH#^3A{aw{bK5gcpM((B> zQ8A75F9*JIBhJ^gh`-;(Q+YQ7AA&u{<6hTaF8l`?@l&-w_+;;y)GohIirCBXc#yK; z=cx84z1`X(KHkOqC@PK&Q2u)v zlTE&|TuGdwdq z%BLII^JYW%XX+=bCPZYsWwiHb>qsXqk{boN%y)SH^_)k}9b+*Wax$X)wm0OKLT)SC z+oAlHdE_`hbd#*oxDk|J|A2F{Tep-im2Y@^><_=!5FSYcKeV!LFhj`%WAND@V1zUn@d`HS#*QA!pwH)%5IKO>$l$}&(v=rH{g$ay{{9rKf znXs#qM7=G$HewsMCuaX>&QT<1!nBerqw+ijIoR!c*vKIk>UD#jkmFH{v)6X>B>S=s z$9&~;d;>emKAKDA&6PUvbWxoHLkZ#cA|FwO{V3pl3rs#V{!qL2FH_4Jwe6i9=m_X? z=nvt1E~Zml78)C2J$@3u8vM$G@VA3s0e-4i-aG#};^6$w#Q&lpd`gsjsWS>DQ2trq zhrsU@!@nAQY7ff44*c#^-si4~vk=KvSx_qY;7i1wyF>fmc;Hq8*OLF0fxi>{|Hl8QjjACR{JtTa?fNb1O>ffR`P5A9 zfK+B&)E@MnSH=&A_QQ_psL#KF%K|P0+((!{MCwZWYZ>QGc8(`~yZ^qwE(Lxu@Q3o( zYTzn>JCwif0&X>MB?6au4&IEvrXB{6+w0D8b7{bj({+>dXd6aGYlH{&wT=hRd2J^_lCRjfZ-0w3?i)7XEW zUdubFYO;Wkr7p^+_*l$`kk8+l7gIiT(j?=7#_*d|?jKQ4W{uI`?AKsUGF}xv>ih>j zy(RYlj^|V)_o1m@lqWK;rHTLHN|FsE`%*h$y9DnC{ayR2kxwn~%D$WbzI_dlTmJ{! zH}db_ydT!{nS&3wwm8+ zJmo|0eNM%De*Z?m^?iWaFmZ68w|#GskzDlrb2H>Bkk1JgA0I)DxGJ|%#-l+-s$4_#_$}<=Tw8o*stc`&Xu0-pys#q zerm6kjp3n$Zx8(WW>0|1gX!)0%C3#Eb}ffo2=6UUCO?WZ`9#@urq`~`zz37?4RpfS zn|edP)^?p|uqc8W_huf4n^leBY$BLC#(n{vNuqMnd$Jkew|3hbdAn;@EX~v$s-Nm% zy@B5heEK7e|DV?zsa-Jst-*K1QBT?))M>7}=GqinKUu&BpJ)tU+B|-9EWQ}{%qQ`8 z7ogrPubF45{avhqa!4vqts9q^~aRoxmYzdZM;)`(R;%McyI4(-23KS70CmB zq|bgm=9)zHMei5ap}n3Vzqr|hH~X}D0X$h-pY!Eax0j~w<|`qM%>8!PF1DYJg6zUlqx^fbmFb!dDw@O8kCCA)+N zpQC+-9vi5~@K|k9IrftN!yEN^w>={~?W3Mg>2)UUIPmJ5%0cbatt;Zg5sl%#ameQ* zkDO^Iz1D22Y9S}!+^;Gy63@m%e(|x5dfoYMtUUHv^}_f?stL0&rhJz}uC`NScnOv7 zkytsHtK^h>3=G)ckvLWc`Xc|J_sc8czbBIXe;{whFSXuUqjnsA zBI*zA_;=%067XA1+#2c4r}?Eh2EyS%gr2it0TaS3~-uvqVGIZ4CA;pJ668sxHTMdTZePp8W}5h=(x2M z^1a}{DsG(tc@tYqe~gJ+`Q3qs|Nh;$H4XT!mp6t}BpTb*&2uqbC*4itqPVpN`1MyE zI&KXHE(F~32xY!iS48|KDsDMSwTWA3B2fmpylWf7<4A6+N6xI5oJUj>(GD>AbrtZl z@%;i7uiAL)m-|l(@ru5WQF#OUEzNW3^O-94(7I2>6Ey)qIC0vkh^0@2kbU$$jiIRD zr*QB4$!njdzn-UK5aG80zZ3YsGtZ*>O~OKZ_S3rmXq#|87vs)A>^ptHp^eJD7J4hE zHilPGJ^jmT2esWmiUT;d;k@h(xFoj=a$Tn*4$!zz;gQqjjt{+Zw~z zzKpab=EwBlko0CTe?P^g6&}5+f0?+HsM=dUJ=N_u4RS-v8pH7vm!9^>X?v6)b?5n! zu&(Co^xc#K)Kj8sPh?$B_6`O=^O%M(9xt%H7{3ej$V&BG41PM~uXg#EU!y#p$6YEP z`Yy{@;Er~2nD=tIDW59v*SE)enl7L8=zNI3jrkak*$$l#9kd{R1Nb!uk?+_;^IMYd z4LO3a+ywOPcPXnLEJDRq*e2@K0DSz;fBEA`)QGR28)j{}F z&)b;a&nvIS9QD$N8fysWI~Ds8CLgmes%BaP0%l*7?Ck~|l^2h}o3%He`N~gCc|GMB z&wR?$Ew6e~)K5LYnb0seQsj?SpKp8XusUW@_4MteE6luz9e*}gXQ0i z`7Pz24?fjTOZn6HcSwJ8`BS_y`JaY+-xW>t_0XPdxg^u~Z(9e+*~; z-UfbJ3w&yWY2bGS|6?s(!c}xI*BtlE?EK4-URadaA*%Gikw8eazDS)O|6rTmioZ7C{Z>oeRxO!>HfQNC5+*MNUG?sfUmp2}|r zy6^QMOF`c;3ITUL<$Jm(U;V5d8+!vWlB-7s?);1L?|3@u_gU|Ax9I*&-#gmBwo$+T zC13Wz*bo&SUCzW>%^CR&Hw!C{AA+i^EnBX*Lcq>URjB+W$V|yasqu`%hk8a-ZhZl z5BVV^Z_4GaSJYa{OuJQmZUesSbB*Bvgdaiq!5+_hSPkG01wX;n7hRr?c%Yeg5Pom) zdx4)s^3BA%;owvLD!!Yz%I&G@AN(}%SGoD?@y%9yKm!Bn2u^Nb3N;$l{~F*I15dKL z{20&9(@jeJP2jHvAIlBqqr4veF7Vfbul&c@;~9^V&V>IRgx?MPt>9xh7t~4jp4|+MD3Bt>G&R2R6Tg|9}Ip5_|47N zRQZ|T-292kw2<|eV;{h+NAGzFHD>B97OMAZ;7eY>emL11UGJm4^}Y+Z*}%1Taqy4+ z8bNj?ou&CHE+78L=f{cP4g9H)Z|m|S{adv^^Cu(DYCABe=d&$p^g=LEeV-4;N2IBZ&DmNK($Dd#fXjQaF+7?G>OD*7!TY7-`2A9P7()5c z_ua~Y>r1!^qzmoMae(sk^+tZ+D}OTmLOt&t;J#R=$`4!(aLx5+;?wuz)`O2}B@AP~ z^z^Us;BN(=ux>lSujz0u(aM3XRBj1AjgE*G1{q@~Zv8PkXuXfcGBMBeT4K@-)H~1D64u@ zPxuL!1zZX8L0E~{={~c$3SjMr^c}&)z(x8`1D=Le$p!`A>G|0>UCCtMK8dw_a(Ngc+_4n+2}NiF3w3Kbtb zz#iVyRR=nA+;$+pNd>+f`3Q_7zK))J)Lc;=7{cDUI!A8YM&*+axuLJ&?<_-yuj%|4 z`v!a6OwWITUl05~!f*HB-Sxua2@ecjIo16KiDx{E{o zv!juoV&&Gxm|i5*k2jIElz$#`PU%- zH6-_>S8kq@Yu?xSMpr1+*Dm1mHa3Q_EQ^#;*ZVc5z6h6!!WA9@r}77GDscHx`qaB= zSX1Vf`e~pd9xl>59{9z;M~@S#-6t9(>0Jn1C2;SOpy~gp3v*VIUR`^J1qfdad=b7k z`JET9+79nBsC{Jpxd+-(Bs=y3pAo?K!n}C%{JF1IOnR3Bw;y)AjCNR~$@B5#wd>xzfq<1;+8Ocq0-D~Dc z>fC0&tCw(_fE)V`&UfJ6)r)cE1~MTha0xYl$-e@)H4f^7R>!7Yy=#m{66&j-*HixK z?>DM*dA{E~c)d@opI76B8CyL$)*Y1cq3;84O=^l>->Py#MEfNNb6qcGzz;<^A9m{- z^9}W^h0k88(~|n2618h@(x1{4P9{IO)?-)n{Nf&65~>s(Z;ByTiSoQja>G1wUca{A zAu)ZZgyq&iF7Ly}aDd|E1s*xhPao^~isZ~=6;z{aexG%bN1Rm86_oFS?^!P_ z2fyGT{A%zs55nILeg^oFen!v1U@Oca`+S%>9gN@k5d19Wt9=h+zh^x&3VgC3+mDg* zgKyR|Gr{jFn}1$N_AO`m$h?Wx%~k3l_$=Uq_}(sk_sebHD142JCp+l7<{^y# zk?+S~-35E?a)Rj)O}M4N?MJ=+2lx7X0M-eFyV_N!+OHb80>rW`K- z#6QyIV_yz>h)?$Wu*4$%+b;h?l$Xv(55O~-<&n(5Cw)DEuLu5E7q9Evuk>;>;slM!`Pl;@YBIRk@)642hYC5Lhv)dPjuy@_bt}4d`tYz;0F&PzZZP65AG1j zpZ7sk`xof^U-ag$>H}xSZH`cCIOwD1y;;DApf6G%?mGG+6q&T>_>X*RfLns!z85el zRc%G*g4G&8DQ0(7^}G~%d*OTVk#XiR`a;=z}Ezu z!Y9K|eOG$$p7SiLvXfF9=6dp6x6hnPu5d?(D(a`+8w+;2sa$K)xfFtGxPR5 z$~yXa-Av#rfFrl`)~`BI$tNkPe%An316&&y7hNx#nBP*pjAy=j4qDkSl9#F%yi2Jz z>2*P=Ug+-;q~UzT5#%p-dGPL8XtnrL7E*chFT(iW!Mm>1aYpU`=0yCY7`P1J(%f=T zeAOO6%WEcf7>@wulhOah28+#6Bzot3>B~^lk9)RgV*y_ z3^MxQqW7%tV#sMnNu=-lV>h;ahLy zC`OsR3i?2Wni!h!qvv1PVD5TMQ+N_|c>PkHWj;@Tf+UaM;HG-W2YxK@SI6Mh_l5Eg z#7_f$HSiN-@X`8pU{>V^ekbsk#i9Jid&@E3xlr#D(YdQ@eVz(e<%eAGgr@N67%+Up zJ#wCTv6HT<&0X(Nd6q&h?bN350Lt(7=H=|?DYF6U+<5*F#B2PWh0)&fppLN@g#|1f zGB>-;dL7yT{ZoN|+YkNIJ^JAXk@wY~q72OILux-@E%FKW(e3HBi}ro}emtfSRPJrS z%?2*V#t#)osm)opUVr~g%5k1rt&yqmdjq-Z z$k*n;zkQIu$Rn@%kbAy=g{pC0DU%%i{g15!n!>viAUDh-=lVCk7UOJD&1)Kp+9?Zi z<%65TE2y33dgMIqYgg-PB>Z0BgTtG`b8sK27u6SXbvs?JgAv$d7yW&aBH+)pJ$O|X z^M1E}bs6=zfO0YQxDEMC#oxzxg6eTb3wB*e5?KM~cTdpbd^;lFogybBY zs9x7m4jAPhn;};|wkcc!J(2RMIfi`$myF8QK>C5})pEJiW(LZo-i|QkS_`@QYnsA8 zLC$wYOLnQK57Bv4K=)h*#x$@u~s*_283DdcO{HF?D_j-&N&$qVcHn zW$2LY*2FjCyl1{be@EtE{F#T~FK7N?E$FXizM4TP`)J(N z1t9yjgHQIi#P|+`vF?e%1e%1D}q+ud<5lf8pGSjM$)qo)pO7u|_mI|u|4|b3 zl^T60qbH85I>8jRBk)zgkDcRPcOh?&-){qdD)`4!ex80i0@XqC4dBlPU-fHqT*7lc zjQ$?eV(?)OI(c;bAo5e&PI>{$tN~<>~KL)q#Ikl>9uGUrh4lP2mTl_)A^>LdqZf+oJe0 zT>e^;zq2X&yEFCz#ix2#`Ga4KdtZI;NZoTESFX+z7S;ctFJnQIIyd8^Lo^;=(I3$3 zqxMU?6~aG%`O9;@4s&mQ9!vF-5B^x_IRp1v2gbE)lv&#U!JiF&Bu;|QPuR(hGVm9J zKMD6*Uhm_mC+htJSCA&kXDx7bzy)0#+RyV`cr*C5;9u?KBMzv(Gaz!FumQNVyIR)M zaRlNC`1E`ws!s0Ev5wS}Jz2oj1J_(!B0l}SvATosXM$e~KBhUId?NL>9Q+X3;qp=M zo_<~pekJ%vyL{BgWm=xdHMXD+RTT@&LjlttQUF6>mC@MEqaqwFmWz^L6U^iD%xP1zZVmTggCEFYdWq z{gPu}{UI249!TYw2Dz?xx9m4d!A}Ffx%QxTtpYzD{G;4_(O=X#vh&^Z(3H=1-~@1O zTwHX&^^MZ}=JFx=&fwRhd@admG5=&&Kk5nXMu$R3eiZ9J+{>rUQv4?VOy-~FS zL~)t^e%gN2<9JsO>Pg3BwUIO+puY)AY$_N1-MwD0tEG0S0-yY+rFrc(@X3EVx%pAt zh@7`r$3(X;A@I{DnwjmZ$9v3Pdg&0et@})XM7lc z5I*Hs#{8(b&1052<{vp8sq(7=eryZ%L;ALXKNS3vEn^SWxBCsB_b7^+4oUbVWIPmq zhwoEK7=A@*-aKm}x}K8jghtt6>JyHH8 zz}<>^@_o}IqSM_E#TOf#3ssZwG*Q{z?HbGv9%>5T;jQv9| zUaeo%3m*Lg?x{gtFJ-{z0l)YFy#5*pzG#!HYf;CWD&W@xe;nb>`MZI-;!OTE;CH2R z20Z1|`_k$g3g$x%R4G<_iBF7h$_9V$xt1k|26xwdM5=r3B?6#ZU_ zI+{7qU9YP42W~NN?WsOY`>O+$eWGxCfhz~@c*3bN!hZ))#*ybT=|#ifj<=bBlBk1@6q1? zejfOd=PalP_Apic35bW_w{rD^?~(5fepm35Tt0lo^BiY5_-Rr4!S~oV4g7fU)xMeW zHGU3D`7dRDWZn}!o>qasAAS{?cSO%ywlP0azUcfLz~2e^mhA615&a$fmgIYbUju$~ z_LDyjXFhsfqax)O}R#4rd1jnQpJ}^mlGEQEy9KygRPb z2T@DNlX+NB`0c<~0$=9EYyIj$R(3#bN~wbfWOphSputs5>hC|e;{oEWc`uFBP`v03 z+*IHwUT7TbjvCi&9-<;&22t@Bav7_e!Ua*|6u-ld$eW-dZ~p*4j&#p0u7OY-y1{1@`rzKpb=t~d4V zXChPkWdTdQcC#oz5H%(HyYfTCnjmdJB>=S;2xvST^) zht?eYIWm=Z6L9N+3*z35e?0I}zPrF*4gMVB8#^O;>izb9dIz2GOM#DnT;qLRJa+P! zr_R^#i9)h7|2o7o;EyH!s=hJ5QWLNN?mB?%EC#L!xD3LXdWV0}kU{)~;Fo}(;PTOL zxg3x*9N7i-l3zYL3F6T7xw?e;aFQq>+A0_*if=~7*dhO$SAbu6=Z%KX|_^Tn` z#+8pgFVMhz(&hRf>@)A9b-W(&^~=A)x4V4w4||k~MI_T3e9|B3KPaDOt8sfc_*8#q zk-VDcp&ixqGds#3=G^Idtgv;Mnvee|xG z#_a;G*Aq>izoQ2n#kELyRr*rlSVh21^Xenq1r%Ac0u;O{-`>F00QVm+&Q_;l-1#-( z=hEQuy{^{tInuKR{MFzuAinBf7>`x|y+nOO z%j`F7ru-_s;~H?D{<9bSAoxfk?XKgRd$NrBf5#ippMi^tw|f0Z2gCkNwPD@|A^Y=z z@A_1e{=R|oXSBCxJ}{p7CwcQly_$1?W#IRMyz&<%uiJ@P{5m|0d>V#^|T_ zic>+`1^!gX=MtYUDyMG>#z)W_DBzfUBjXsoZt;jPwM<22yH>KWZ zuWZ%~y)qzuo&SaYxe0%-p4P9Ca%H>aLK!0ZZ0Ek_%cUOK_l64kJMIOwO<{@gkMzy8 z^HS2V{g{$I%a@hXwNwsB2|3PEXzAJ~CB2WS7qwN<6C(6?-_t*63g3Zy-CkKKX{AnX zN;>`sXG$7cuulr6@)wv}f>AkkL2fGKLPSvcqRu&Av;pN?>DZ;nHpi1~ZXh>?LTf_O z*Ly138~V1hzWFxvaeHS|d#id;?VXDf+4nbF&w2-j^wHm^pZy`87t*{4_LbQv*DR`+ zQq)U^y){vph4R5ma`2Z%JwNe6oUSX))$jF z;L~q&Q9nz)5$z3n0TCg03*>SHHpke~W-Q}`9H`~W()tWK06do4ac zBBti?zMC-~Y{fYfubk&OWxmREoDTP#DYa8?$gPLm;UvdbH>86>4}pFU(M&n8pM<}? zhJxsWM@6I!u1|Vq0-y0obX+F-QqaeOegx^^D+}pb(2GESk7z0$seY&8k?MDm_?DMa zXg|_ikR?40(6b+UR=9dpoK$*psQ*UvWTh0?|7lJSl{ae|=JTKO^ENmQIwpenrT9M= z-|(RSb5x(BY^a@!fv*6bzB}mY=jgwszMPayoMiEI?7ji}InPgO=e3Y8{|xg&*Uwb^ z%S*`^>4rc2rQc=l51f;rKC=sQW4ATw_y1w%6|gM_e^@yMdwV)6X!}zCjqwn;GRTm9 z^X&d9X>*mjecSE2kU zW}J+SYgs8pPOs*Nwd_C^%tz(Nn6GyZDXx#ghGFfOP2nru`iS@|?DUQk1E@YuwVLxZ zDkOB_-&*LatHb_q9DYRnKQhmV)NgJ|xrGOC&FSkGa6WXJ<&fp%FC8(lUH{#|{e|qw zq6zTMrZD}T>SpbU)T6SezS&%HRBSUC2hMHOlSZ;<4f4s`#rv<9r36cD>@U1VeeDAL z4*)KT8=HZv08XtR6;;io;=>H%Z;!-KTH$~DHLbxMHNhKIB!N;;lh+)L1kq_Fz zC%xUkkN@dFy;-0O(9Jrt)V|o5qyPR5^V>%EcQvl#{HU6yU_{4X>2vSh^L&)=a>&;~ zzr?+{h+b8K@dEVYh&VVU*dMuO;dV3V^`QUB`OTww$y}O;;*W>8{UQsY@vX!IItFie zlm3p=F(3KhFMW;#zs(g6TmKlm(3+bdZnNdg1hLGPHSyw2yVKnX;xAk7j1zY|ciOdn z@q8Ri20F2S>!p_1V)3tYI(%Y_Qb+$vxJceC7Bb7%Q4^230_haF&LOZ>s)v<#5@$Ukgxv8=bn7`faQ zU)Z2QM=FW*mo;(X`ZxVA#fvZ5;trRAK2}b5#Jd)zGrw69ChxJa(j}oI!R#x)x5a9U z{-4D~X-o7|NOPUMA_gMx5!uh;&w}Jj1ym27fp{7AzR+% z7jN70i8wLck)V`0a#5Uk)1hy6LRXg~Ae%X$!Y3ZKG?qMSL#hq7?DHlpiLG&55(L>vcH>>a*njcrj!E+Td|Z*2amKEcr?Ta{1nVEnd82 z>U~MJ)$0yx1>}CU<=uX(h8q7zM}FqFexnxM;+K!ciDwDEAx^#==WL6UU&V=CM1T+t zrF4at9BHKv0PP03%(2!w@?%GQO{#!V{IJz6y#hZzwB&C-QDP%tZnWukn|%$!heNkz z@=PH}jIU@XKDOlQc4D#pz7Ics^~(=} z;)A$i+}Fm--`k1u1d01)3G%^KVspavxPL!UZb%W22hPI%zJQ$5R@5dPf%`A%Q@l{y zs?$aI3n&OZwy36BP{cs@hph#+c!Wbo%Hd#SoPC!i9yLWffHJZ@FkOP^GrIEWxN z88_3d;MWe-vViLZw>adQLVRKcH#<6N&9;LdIAS&B^qd`h%Ml;b?G8Iw8`YbvwY$my4_|4XZqZ1X87D}esjcT z%H|t8_^TsINcVgvh(9*ChHhVQf_ohC1Lv63NuDK6l;?>&uux$M=N>gdl#+V<$SIb; zC5U;J+?62Kz?Bjxem|NZZihc6kVmad6wlbQF@d@SD030162)VVtV1I^@{4$JFEy|7 z`F0efFg)ybtWuwR)F+;$;GmrzSp_Doux2>oCo=25#Y6mFi^hhhEZLMSsx0|rviMou zm)P>NfOys>Ivn85B=Lv3pY6z}QpAf6(Kk7=q?MTNqx*87{JxcVUEOc?$@M{TyCnKz zgpk(a9d*A=%KFw~iJ$0?`sF8W#5Q$*S3-OIVbQe-!I`OIPNKy9!XzpUmFGC?aOz~E zWsPO+K)0}*g|@uc7R#xf+~^Qqa+=j`JSeYQvPOze9l2AA280-CZJ`kJjg)^$YaiV% z_sd88o|qBr@EA5>KDXs=GmKH5)TlSe-z^K{)qS>uajC`@A4caHw%T!)n|$IkM}FxO zpZd~N`?tFq@*zupjKSKGKlsGA#L(@N+N&)Ne#rHf1!w%g!te!bB!&gMj}QnItE@X5 z@gVzJpx=E~sV(lK{LyCFeUWanu1tas$zfOy@JF9pPA=j7D^vCJo5PlP!# zlqhCOS(6|hij$x}9w%o7#AAtC(J81=K@I+kBVM)p2{Ff!KRIF*Ws8CLM@LlA?Hi8V z>d=^~a!)x5X}4>(S>gxw_5&$LJWZ_EEcv1>R*==}Y??l(&V>RTo_?_qGc38oMu$9K zh{tRR7jER@opu`9S1fnr6DeY`FN`VmiUe7iBDN+hwN|8v1p(+=5s+^ti{}I15v48} z6sT==(h-|&F`|E^E#6~Y!4n5Vz4f5=i!E-a0#F+qXC3h{*#~FYWm(_R?IK$)vBgS~ z;-(;lxqaos0Ws=FYe_(CwL5+r5KXpxI!Qe4RM{Zymu+U?fB(6-e>JWR!uN~u68G=K zw|O&B>`9OisOGB9JsGOckSmhJ^`9e$&usZ&0Mn+&aQ~KX(1S_hd2-H=<)CG__0z3? z(8Eb$U0gX3U&aqBOAPE*A^{ur>&?e>ySthClx5777~@#Ahs;(mqGCgc-qc>d6O zrga~dNRP+MKNG~AY)WFU_IFzpmZ&Z;rv6|1V~=Yuz$k9XmGLwkem;%{h&$qG#8u<` zWAUPb?5Xt87`8U<4wML$+hr43fPrhiBObEx#Oy6w&UN&>^m|+WX$!;}g*?!|4y63Q z@wn97ydT7FAd7@x0hOxzikSVzsgFZy!nAuZeH-VzRh5VG!NfPST zv)yBQqGo%`wLvk7jsVTI2R$7W8y)Nhed-&uC@9uRY^1&5m$gB0FHOUqiyMSL$*#tv z=i&z~2+~vnQ7U23+@M%RZuNTNp!q@ZAcgIhlZO4-O3V)C{kP8Aai)b4THK9T?H4b~ zvxT_TFQ1AN3&;XEOv+K%20K^IwrI+xD3|v@T5HLMWU;`J+mdNrF<*^NGn2)ee)$Tl zi<3(eF&C0Awh}wz*`kb-^@v_f(EP+N# z(BJUOEeYZqbw4*AODd|AV^IZtd%SIleN-tF-@;aWnmks}xK8&+%D&=kJuD^tlfW`p z(Bd+Nck~3%rlrlb#XXk9TJ;qRT~dv>Vm1fUZfd@^(vpZ;HN^f2BZoyxI)rOG4Ff3F zr`5JV?^Wu98_A@1E%{+&tY}5++ohKL$P(XhE4Il7X>c0Wi<4xrxRx7`z-4gOk*6(B4Ctq6}O0_yX#y_Ry)+J&!LdW!VzKX zEIhKd@t{b2Y0K?2GV5)H!(Oo`V8hKx!*t_AM|x)4%{OIIJD701EHM7u6&)1|4D>6k z4PVB3+QH5Y^4e~v;SJOzJ*49aNf1O0ZO2+$E{~%SgAJ7?1RY5$ z%nHA#^U0Zh(cqKoq?j*>f+g>#*ia!IyA@#>+i^J}guvt@tu`KELhkjWg5^i?;ywt+ zi6>B$I8pDT{h4wpm&J=UQtpuAW!%S!FD1pi+x$4mu->2ccD(q|FSq)|yf|X2B|qx% z@=dl}6E9}?Byw2flYnjW$>-w8yrwu>Q{1V{6XGSA_HLZ`1cW&8og~O@*iE1{atA!1 z^QU1yr`|7r^NW>n#M~GU!;!(n=~RMp#DF-=4&}43iwL`|v^{aONP8xZ=AT%GVFvwh zyx8rNzs8A5DHq0zT5KM`QYlyZMOaam`Q@Dn2+m!E_}!oOof@z((b*D5@K2i0@wGUy z7u_C_-ACEHq!#&@s3V)@QdY)`5cV6m@^?tGYC49qIB}1kAkX>b0}0}5D&wtjlw(Dl z#H-)P5zK`&G^32!{b_QEabw)~_T|W^@*>o)4M_@+;eudQxxwBHAd@SxxmXm4MOc7dj#EA5)^`E!YuSS8$uo7q|?4s;$_O zDDO=bbJeEPcS%HXh0?cvCc+U_f=XSCyP0Ld0(=4-G348AB~42d>Sv;r-)|~a6s&>1o?Q1_$C4S z`b`OPU5Z$ec(R~F2oXqf&eWG?+=I%>@m1U*nKNe zYQGMeA{C=9Vb^Ni-+T&>CHI#U@|Sl5cg0e zSf|I6>M!HvZ%JZx;sE8#T@T03J*EbLMk7FwZbg8>ZZ}=@j z(^r^+#$gWWtd7UNn1i6d(UEi24)`;1;w?${KS=o=cEi>E>^S-xhN!_YlREs-hGq@- zv=(ow&6}ORC012y@s?k{9~9sD<nZ+?zt%_0YOf)tz#~u9Y1*+79$oa3ms}n3Z@vTGg3r@{eXoZ z_xpk`C5!icm*f5^8N_NIW>5r|i<7a|LAAaTCl|F6pV95laq`YqVh){XS`jbHT8WqG zFxvO=a#M`~_&tHLnUN^JfO95&gPMgg#~pzPk|n?Mi+}aN^E4~%O+RA) zZrEGvwD}g#0DRjtaF(TA0cLF>S9sW_J(efbw%DikFxDe-Gkk`w!E#l7i-e?;&EF}Z!g}pWy4`&pDmv|jE4UWv`9S#8^==q+)9-B1e0r-?ffRReohlY3w|ly+xHW}rTG479>Vyh#+&_k5HKFbWE|3y0 zxqKJGI!(dxd&x0Y`^ve>o_gKGd8+{jMKj&|5sp-thuXBy`=5oycdm2=ijxfFzIgQ%4B|B3;b9SqbC!4 zx^xwB8jEY`x5+1izZza=z)Cv|Kqoh5s9ush5x`_prYwXH=VZtY!K1 z|5Cn)?aySn5>C@6H*ZG)o)CDi$~D@LO42pGlGEVt(emm1yJ)|rXYg;+i<+>?r_20K zXdV5#ZOreZVt$_#^ZV?W-;?-vl2$9m_SZMb{JU(jwjZ0q>MG&5bOis#c7wXGyQ;3$ z%%^j|bj9mL{KlW(s^@}WO{=b6*wCWOuM>gYRCOit?}Rq`CcwYdffwAH+TQu3u4hxL zy|})xBcd)k%1sw%BQnm^zYTq8H~rh#xs@v-L6e2auPLlQAGTi|a;62j{%!Qs^Y6ac z9;E9J{(YtX`TyJhwJnUlTU($X%CMS4$Tb{-AFIFQG2LGAk2fD@7qS1Xox^$EhEWDOCQP zcH#7NPIEXN!s!@Jr*Jxp(?y)F{5kEy>FJ#2a5{w3F`Q1}bQY(JI97a=MPwjht@bbO)#VIQ0+W{5kEy>FJ#2a5{w3F`Q1}bQY(JI9-*KxX$(=D9t;B+6SejIF8 z`E%NZ)6+T4;dBV6V>q3{=`2ncak`Szb)0VGbPK0DINisopVw!HaoUB`(>cxIbO@(o zpN)>cHJ|Ab72}$^a{KlBXL{F*uexDk@eS!cyZ7pT%1J$LP`^&O<&+-XGkTtQeeviK z6DAk;IPv<)#iyL0F=G6$*P(0!) zq{WkUI@a7xoK!rz`_&U~=zi4=>Bx~+j-EPlbW!n@Fcja{Q#!63F?sTc8?_E|f6Yh;k}}E}dX<$UCX5>iC6kaJ z{_C!c&>3EJ{q>^z$Vn3>jGjo$i8ow1YV=h%Ts?l=#A}uN{9pe^^D>%~nE6l*&$mn( z-RgKpKPJcS_`MHv7b9=xYbFgb-ps$uyveA+Lm?5sKO=AEb0(dgs*#j0VT`<)XJvv$ zx{bVN$V(6&lTi*lj0T1DEUH;Hzw_NlqtCuG;&7e%ousI{xE5R0dg8^ z{~auE+OLAwFD7mHSG0ok=$~RijQr9cw7n+nW)>1G7n^@YjC_ry5hm?9odr2D?PsWu z#>h9|MH0G9dbC+sDe8g!w+eJ>V^hm!y;ibH>*>mJCW+0z28>o7d9$8d&GNDM*x#EW zOa5c>ujKV$<=>R2?FO%Wh~+~ppJx`1z|obi{*U~(1GnV+CV#Weh{qd_bfvRn=wFfk zWBhOrFy8#T^7^vtlUgD~N<5b-ze)Fk=ao0>)153|5@WxSGihUtycws*KFjud@}^rO zXUGmRCz>gL1&{NyS-w|{|D+p1PU9g@_GiSfas!k zq%F}wl)u|q{WgBu9WbI-#L)XOy@crySJw?p4>3KR>C-`{a+&87Co=s$rWf))T0f>g z!*s#>Y{QuTj=?kCjE@aWuV8v92^$Kys0<5M5yrfM{E2X#vcU(NRN3wb34<|X1aM^)0XK2LAOL( zVd65A#Zbmq#Q5g~rq{;MOPC(}9B7f!kM`xbW9k8KE+gMI!i*;-U%cd|>^IMy41KG@ zw-#pnGW6eBzgX8Pp^o|I%OOWZN-a0WoJ%)ZJ)9cwzgQs^GNKai1eLB-aFY0_t zINuFS&y1n}Xz*3h_7?jB+X(}N9~-klv$B0eeoFKIh{nl0LcPWm(7L&wLZ{)Q6L491r*UhqWW z9H!UB#IY+_Pvx=NknT#G5H~TtoZ|zEudew_55>fdN10w3gRf?KMGXB5(8>Oc6Lh}0 ztp7)*moQy@iw!*b_#xp-PSto*pB=Dxqxz|1{cTuJchCthdTM+s>X$D1tOe22&(?JH zZ8Xp?WO^uD)73Z5Kp(^O^8T8xzEuYLRM08kTF%$B%N)j64Al5LfTasZXLWh=H9e%L zc)g72^-SN+^pBZdcb>+pZ-Ifgi|L_3nr`Bisn3!jnr`Z|iSe~eH{)q)lD4Ow>F;sA zotPfFMC)0>^d3wv8mj46Gd+*#bxc>^G6HWj(}S03d?FhM3e7+&{e3DS#D>@7l7@}v=;bUAUFue!UGdM1x`>Sgx(<^?}_&!XZ zX!P)N`BbLg#`Kb3b-u++UuyKctM#V4;E@YFKRI{lj&l-rXRufe8lunye6bG zeizd-C+d3O;Yiq+=u*DHu^N9N=X*ZWW81fs>4mg##Z{vI$2VgPKBNhF*Far(bp-8| zDnk4m)AYw=bP&q7oc$2Zs;(oME)LW73}t#Brl;5Gd{1OM%a|T2(S)%~|A6TQS7^d8 z%>U^6i|HA7@02c64@b1q_7oQB`Z508o#{otXuOFJeVCq^tns&Uz7v>Uw?h+9e042k zx;fXO{zf}E8<<{C3n*MB&TM9SZK>ANoBNAAOxv09s-}-rQbL@{^a}OI;)S?Es}rS$ z-cj3$v-9eDgz2&Ne`N3zHE;-*D+&8})Lt1oH32Yn(f%IMO@??4OkFul4^Gng(*6Nm zmoq(mzy5tS>%Wfa=G+;YNnHyJ9`A9{^$+zwzK_QAO5Ui?;Bp<2rtP73%IHFOQ&$et z3p;6h<}>|L&}kpQoIf(7iOS+@~3b;oyntcTefxomkNY zOfR@V*H0enxt!^O+uihwe>2^jS7Nsl4;wxAYX$#eJt3yo@73)xiRqt!PW4~M=ORqG zer0@!^F5aFtuTR9{+6T5)tCFl*-X#mdb^kLgP2};rOx+6re6cPnm@;kBexrTmezkK zSKk{(|6;9R9P9a->2-s3y?xH~2BrsXt-y>UhhsyJ><>0*I)19_pSYoVFy}fUuC7ZN zU+}%gk7W8hrq{DSU&8c9nQqPpnt1gZ(<_eAcB1>J>qn*sr$)C+M|5Pevxw(K=Q6$z z)5}BJo|~9Hh3U2I&!*okFmygwX5##_OwS1Gd~eo?c-PSB1u$Hfvi@C6FNalhnK+q@ zz(RJ`f2Dyx>*9%SOs|}w>Bb)hFuk^owja|ibzKWO)xSBHhV0Z;#&~ls(6svsg-;dc zTqnA-x?X0wId5s`AF-Z-y*l44#_wZ#CHs{rZx9m+8aK_kJX3EyK&SGSFV_mr~$y6+T&*^H`=_@yBpI{H1}XFup6( zD=yaM9m4cUOs_vo+kZLJ=QBOCQ4=uis%r)46dyt{@gcy>&ZmHRov!t>Ift1DrCAjA8h*3bkNCf#Ray) zaWf02GuOi&O`pkn(wQy>Y5I3epAWi!)=oUFR^pcAVCO?yRm!Ob^8|p6QPJ6L`!(x7?RafxeY&G4#Z149=@qQs#D@t?&){}Eo$+&+ zUd#JV>f7evJ;d}nUXRRW{ANSvdgEi&;uHiZYR3$om$udBiVK)tu}2e3J6^~15}r?* z_;VlA>vw6q>8I-RggpHn`G+~*} zUJS#;kL<7fMAOIXVv8wEFZomJNn|~@F}3aKrknHk#vk@Fy@r%8HOtaNh$Mnj(_3t;Co^+D7vxxhnnKvHK^m<3@LA9$Zi|KXT-`PwtiRl$1G~V>D zJDG0Y8!+SeGoaHrXx@u36JX+-pTZ9 zm|hSwub$)Lb-sfbU&-_kE9k_2-U$PNjx(Atk@06Uy&hj%q3b6u*HosLq(=AO9?Ht$s(!}NO?U%yQ2$@FQ)7N*CJ*WWWen5^;dvYud1ZBGU7Cvf-?M>D9st6F!5&*(+gVZb|1j_R}G%`!_nO8`jP477ioLA zImMY6;K<+1drZ9;KaA=4PO74u!}RNzUdj8JZJ2&5)6--2ua+>qh{qArj_a9T@7Mav zS*H&u+SBLnG=^>7*FLAr~z{H8{FFZyQ{>_1G6w_-tZkzi5kHK@h{DM7xW4lIi#mmJ%2cr{z8eo%*AB&(5^h?~E^` z?;qhhS0~~`I1H7m?qaR@9<4^4&GgI*HPF)Lin&Y|eKo<<+j^$Q?w4+2dIhgT%{cXg z!SB}kjsG+mI&TcW&GsCArna-9v&N5S`ahXozFgaLDVJ*$(~Hy}g~lg{+5S73p272Q zOefU!jG>>Zf&XSbZ!kR+vmdpa>2<$opsBYMEa<2{D__&}UaTjN>9ssx?aujL!}N^L zHE?S^r^YX*zdiK18RGH#5GJ>9PCyA2Qv%AAKp;{~o57a66iOWp8fZcQvpz*IO3TYx#Mf z>F%okhvzT5xOUtj~d>>$XFlIjgvcdnQf#^Q! z`jYACJbyEBpbZ8B^3T})r5;SL=%wv1@@qX~nO+{VzdZ|d8kf!c>Bc{oGCuR)TF(NV zh>wi^*1BTMJjy;-$E%W<=ir?{Cp&9n<~ipuJzf2=7Mv5}@?K`>Pv~~U2M*PB2h+>% z)xS4zyHqhf$on37tmkv4SB}z#_uzW?gX#G8yFwcOIXsi>?;wg|&bJ&7I@w>q<28z} zt|F#q#&woYe>r19*9;xvGorvEJ{a8&fapTB7 z+Rh9PsAfGil<9)^AI$ownCY?e{JWW65!1e}GCgyvwr`B3)7?xLJRex1$s(n%wkI>j z&rb)P#x?VOfi%XS&-ilsPCBk-tbZZX3%I;Itr1mB5Ai%7!@asTGd-OS#Nryq9s5_N z7vgiZbfu{O@h(h1ZD;6xTTwbOJ%i~bahkr5>G@1A3~KrUsTmVNr*dV+>`TvMe1T8n z*$u^$Ot0XBLfKs2TBfJ-zWoWD?>9^@j5%K#pT+(;K`X%5X4Q3yp)=n2+bE`2o~H57 zaJ~x+eYTc=i0PG}Q+zPrQ!sJ9hVh}p9VPIC787Bn7v7->*ZFkX4gp;CqeNW~Ygm6b zrq}a4;aJv_!}OvKT0d`tid#S@d(3;!+`QrertjzdWX@KsV?Dt>Izuzh`HJba?4M@- z*2wfsp66pbMP0!hZGUBk)-zcbL-b&J5yyd!jK7xYwbM1h_~&g*4^7eZo4FpUm|k+5 zrgvug$4nPTYr-(j*Ur`U1bIUD2j`p4^nxEX{&1#eGChOm8^<&KGJ}tK-Z!7=we?!h z0LE7`J@$OUYoL?=oA0_9fBS~<6=;3B5?PN#peBC^J+BF$bA$bZ=@qAIyz!rGrq`xu zf4GJ9lrz1M$MMcge}d`tH)_H~Os78zO8I7*a|=u#(_hom&x*G5Hl}BAKRSx>Pcprb z`}N&Sf0gN(9B0ft?Ng@L|ElZLj5`7qOZ67waTDgL>lo0<&h)GF@7uY41~WbOJjM*B z7aSkmAMay&1)twA`_g-vUO!Hk_X5th8z!!lulcTtX~#^aXC`U=Co`Vjizj@>Pr6*D zf6@E#L@#O7KvS-2rq}WM{bkm(i|L^S+Mc)lnsI!-))Rb3|Lzpf={Tlm@;tCF>nUNn z`3}zE%5CH}U^7&}lz&Ht%P$8u6XM^L)&#-{a2Xa`F6OG7B8W^w@p2ET)H0 z8+4g?JBI18^WGAsXLA2dX8jdL4^QNc|5q72*K<3@e*il9mHEzzX~$m~U%>O&K8%k) zUzbbRx_!BtMYf?QY5UFmypZVyrCLE-)-#>ym18skpF~&J8iS9C|F0SS>_1&t&!0@M z9i#I-huiUNI4b#7Img>1#!msA=5K=MZ@rj)2jer?Zw;Q_+gJWsrWG$?{o9qEG-2NB zVm0Dt#+S3hnmBVzfz}h^{V@|C@|m8_0o#n5lbCM4Cu7Q6!SvX5dOg$Y=4neFXFF2{ z>3r+?`H}I%lbK$zUf0_bx;e!trWf(T`YhIS!G&5+@LWycX@|I#>E?Sn1EtRYIfGxQ zfAcg#yw7y}Aw^_Wg>V`KYw}%UYh!=~MlF9P(DF}42dMvhKP~mV zL;fm#m*OWpJ7Q7sGn$7vq4Th!xbLr^b8b|>@9%oE;^yA3$7(&luK1YxL(VAvSEe3M zzEqA&{rkQm1vUM#^lOTr^X%@An(_~qiBWPaJqCUdo`2_+Hib#)Ou&KxM z+x!7=+II)^J~+cS9`}9HA3yJCU2$`7q1o>*R(zkvNuR3y{3XRtC_jIZ;(x68McrRz z#s5`tU!R$Xb$;F`1s|#7Z7S~9|5C*-UM1^m_`^L0KP?M#RO|U?#r-(=6HZ9GCC%Rk z8S|fmieLPK{I{l?lwPQ~?@zu<@e_}i{=7myEB&tGXT0+x_nGnp#cx;K_lv$vasT|qTMVvxj+y880VldD zeM-iw(_H$9miO~a{#x;UW$FK#esJ}Q)MM@geVq1_>_C!(_r6#FRR>G6il6y2!GHNG z`TI7-FWxSIiKqOK;%C)AY3To*23LLC@c)l0enJhGAJ+l@o8tS_{{2qv=M$RJ&lB4Z zV&t}m$`3~suXSa9zC+8$ieGrN;QO@yXB9v9egO>M{t$4QXLH}@wOY?-w7j{$^_LXC zrX~I9pA_JKD1Hby>kk_5{$|BbX!)9_&%aD@Jj2B$uh;T#RD9nL3GiOUKV{0RU)u1E zzgPUkze_=*S3DAon%4LHUa5ah>-k>AFMdhp^E$f5eo3u>eboe@^l9%1@rD__eFj&-*_j{rn@v6N77BlcAq8iu-Y~yA(frRx0=@ zsjl=+Q~rVgW}m)a@tWta`<&u_9{AT3Kd=1R?4xNg7FzfFJw4kh^5 zSHHoe;%`^{g67{EzVvH~pLoO`F8RN7Tz{c>O~+;Q>e9NjyI1p3AEWg@N%4I;UPI?o zil2Xt6olH$e~v3&(s-z$hi%2rG=(0XC4ZIfQQXfT`;6lKCrUxn|1T?k_6MZBmp)kj zepFlf-&a4WW#@cQt>knlk#Ru-xvK>+a_R=f&;N&1P}dLE6z{8^Y3Sq!6~FL% zQt;cg{N1L!GJa$4zpEqdo>zVQS}p&Zitkl<`f(-bPb%)8$N4A4{c|pRH>Ccty3qf} zbRM3jxPN}Z6^h@lex7G*J?~Q7=S!bZ{H*eyZ_)CfQ~biig|6;YJnl+A z?|r09z{jP#r5^=O^2OYns$^a|$2j6U-nqhG*LwW;{udPY{df=QNxQXYNPpg*n>ug0e~nyzmg4=NmkNwOt)ck+kCBaaz1II4gR5Pj z>RstWiu-ZBFDmZap-%yyB6_aVm)7%f z#r?d~zgN7ka>4BPhiz-Sx?akTOW&^ex%;I4o3#Gx6)!zk@W(2?qPQOi+%)xnMkeN& zIzPW{>Q_fQ$e#avLh4l2>ao$&(dX#>QT)SZEQNN<$Kc7oaK%5N_}RY53msnRFHHSgQt|t={%`(4>HppbOZkt=U!@hr?|-lqoYVS$ zTyZ}>^&Z7*`=p;=)cXHO@e?W+zEkV@lEJnA?@;^^XQV&(YupEBJOA0Q_yx`LG;}zp z_yN_gep-r``ih@X`7)vSPblu6J39}Y{at?`6OhuUmiPTRUsb&Jco}F#^}6r)A*EaO zOB?#U)!@30FgN(mhTL}jdEA@Pv{9JmS;x%0tvtND}IMH*>vj^|f@@Gyzi0e1<`av(2{`6lW z9XI~f$1A??`=r5d)p0#nasNC*SMj~7KYWvxKco1Cqf*ZswEsVE%Ika{)bjtR_=(3! zKYwA5{P11qAI;kd?Wd8aM-)GQT*|*q>;D_Y&-|2pf4Aa~e5urP=92>4tL-i-UOOVV z;ghEnFL`>=OBKI(leBB})kpoX)PJwaN5g-f1)S+t&+~qZwtJJ7AA{aUf1arQe38NL z6yVj0-^2BQ>b-o|PaE8`6aQN4xuE_WLvPpqi1hQK>Tkww`VPfQ&y;a#`etcf@iSNj z`eWo&OL70)*(()4uqhqCo4-OHisJi}(54mteZ|ju{`P-U{JdwsJmY23|NEaT{b_1F z^NN=?1h_@=bxpNgAzfWBGFf8Nxi=iJXI{x!u< zXn&v{^Pgw`sM3kbUo)Reiu>o$UZl8hzkE{hn$FuZwEjImCiRze-3@=(r}zo=4?j=K ze~;pRKL4$X*FG!jXzaK*DQ@0TGxpRyz?uJeey5LX`HNqa24AlG`dKg6etuc%f4cT( zRdGLV^(w{vb4>Rs?%#*-t*?;!&%aG7Hu}=6;`gdQa9!J7QvASY1^5NUe_HYWr-V*^ zLh<)0KBn{hNX0*9@UIE*TZ&)vO6kwoxQzFOQeEjOiu->4Dd0?p-oCDBdEfu=QpN98 z{qu?1?rRnAt3TQBpARZt(|vSS%YPa;okuqJWGh_yoR&Y~=>rdXm5l4$wX(3U)ejaG z_w9m_;%C*bIFRWmy+ZMOA1i>0fzta;J)T~ApW-JzFXjJM+x^zNq(2vR9?U*n08aC1 z-qAC7Q_COFahY{|sp2)&(;lMrzftiqmHTEsKVWdBt829UpDJ$N`x;Z6{@Q~ceOSkD z!N4C>(ll5b2EHeK56k{x4_+8B?;*JOLrUhI0~f!#WZo}u@rS1G6S(-p(s#04{Nd^Q zU@rcMl6fD%#UaO+ZAAXPr}W5@xzFGJbr1Za=AM2R|HhKJf8WKg#e6>4hWOuma7nAV zFW>%g4{p!$?-Qoq_Y~YqEO`DtM!}I!t9e26-{#Mr(l?d-eMGnnlskB7Zl zRQ|>Q{z~9Q>vArDzdwL~Hh^FCn&SGe3*g@!z<(fszX|w0dt&t8?+M`V57hIq0R9&N z{9zE#Mf3Kg06rVQlK_540RQO#es=)>+W`L1pDgbGQ-BxIPm9av`RDC{dR`L1UkCg; z*jZ=3EDQB!)zkhVQ2ybtuL|dxarm{KFZCGvr5q@KQvgqZQ-6HD@t#2WKMvq~;czJG z=YJ32HwW{a8BkvscOAUkH?c$j=myYaTfBnJ>uq>TW2# zC{X@20sK7y{6hi!&ja|?Z!GTT(*yXS0REf+-U;A$2JqJf@CyO_V*&gx1NgrN@N3^x zJP%I`;PZ@wu8zw(8au8YC_m8hXLP?mLOv_~nBwQOo;Aha6sYH41NhvVi~D~(fZra# ze=vamQ~-Zh0RL^^MSS2-0{E8$^;~tXcwF@W-Vflf0=^f12LBw~>jUM#7{I>C0{CwP@ZS&MkNCOb{y#l{F9z@x;6>wlb)ft^0_DFHDF2Xm z6!-Hw;6?3D1}T@Yw)?thta!X=?X$8$B zNmV|b77aj@k(#A+p5&4|E8_D+iNBAZ6#i+PsID%!$D*J#3WC^Vl>-tC(Yzkdzi${ zUKhjNMCM|A{o=8MbBl32++2yP@$DFAyhWqg-|Y9Zp--MXy4mSexTY(f%4jUDusnVc zuWOI$qwP-8!lYp4ZyB^l$smeO(cjf>3(rzlwqy;W@$|#R@)&n-xp&hh9_prVF`-Az z++TnEwxd(?$Cnm+YtvP{wT-{&C(QB6MkSgVu3+dJEA4L5!Y^z15*05-lWTEb|NF=$ z9_I#l1=UQi#oVwzr(1(gZ%wCjF`8ap$7n%4z25xXFwyO`ZliNUquc5v1NvfdvN>pu zmp5vMw>By>`1dkDPY(LecQ`UVu5Wjn$5w6!oiCJ4ugg^1jvw{g-KAR=d(D$kbaS_Z zznNAlTa}q^a*DSWswk+zw3@Yr-Ru&)%+82rm6vFkjN;YCa1?JeM(d?GzHxpjUaZ!a z zU>OvC!$zyVjqYz`a0K}H(veeammIsaI$)vTAY_*%o ze5WxSa^Ghw`5&?>%Hwtw$CoNwSp4Pfev*zmMXZm??nehVN26Z1+Tw2_blCveC*$5H z;6I~551V^1ce*_^4VLNS{7+dmN3vroq(_tUw)$kR6DQT9De zxb+MFkkv8aOt@1LlibDPqqh18LYk(c>{aF!$*Ohf==c(t@d)z4>edvx<)GQe{R9j=e2w!q$dgKB+9ddm=6maPPlIL1a_ zERWY3gJF_YaA?rmpemr#t3KcQ?b8PpT#X3j5y&~H>9 z1WuzB4?D?9RGuj%BBr`W~8bdh6L(EG&V$oa(Zk|%Hg2@^s z@oI07*2>ct_xdH2+3dIIXLJtw(I}1xQKoNyKGQ|IDuE*&4kc)4$PowMHGCoX8H%Xkd zSGTo+xCg!~A2nJn`G?jdJt#p_*=Tng*o*sTX3DdrjmF?)f`3orM)Rz@&6OBS+fZX6 zU4kmU#){Y0TZ4Jb`3iQDnYPv-ZZ?|hNsI|>mC*Qb|IF;nWCt3TV7{1%H!m%?WEI^Qe3|nbMs}l-e?RKM7zm+ zn)FSobaoyXZTbOv0lr838rI=tD|x|YQmxq?VjB;p9@MP_iedv>iKe{D_Ftv4wa`Dd zj0w5z=wa@|)Dos1*3vBK5VHYGZgY@`b~Ti?A21_y1~w>21G_h1eP+FsnHq;uC4G{< z3rf~qX7|(v?H=qtD7m-6eqj#E+;h37>~Di=mE|30jbG@qM>9)8Cz?*pU@{|#=wa}y zm3_1x=PdAX%ym}h4A(hNX0cN-zKq=V_@l$oB#cZVvn4hO2HRy4-j&m68dlQ607lth z9ws^s5<|KS1&{iq7VOM?r#DPMLR`r#SqH5yxNoNxMf@MMZ{tyE;g9Y8_DKoo-S9La(1q)+RUKSgBom>R!9GHQa zfGSV>nk)qNx-1<|mzUQj*A6IzcO!@-iWg|>F$-7MjP9ga9%Hq;+RJw0G$@^9oQP{! zg#Ai3Rm6p?p1E#|bZ&xvj`1@4Idm{{s~{X6&arMC`raZ01IXGPn7w=2rd7}_GTtSLd2C%~#;!?R9IAyIoaKsgm}QlO2~Ca6V>Ios5z^Ntx|n)HE6SvW z=VT;aKquvK&f&SQ5I#3^WGvE{^If=OvbzJOFC?^l61jLPbC zVp|mD(7TnD^z)+WZ1(!wM5bfBvOI#|O7X527Zfe`=73ala*~k`l;x&JPf=OsQMipW z4ND^K{rz4nZ;b+wSsf~794&&G0vxrKXqLpEC85c=Q>|i@^s6POcTgzmL8c|xpF_tqsE-y&uTaVrjLbk652 zVnY}ytfc7h@Mvrv?sbtLMlEx=c}io)lqPH?1?J+gKAMfIy@@# z)|OTB%|rUtdTpr4A)yz|a8GU?be4NG8T4P$A>%~g2uIu-#7hYr`Mp!=@|eN0q*R{9 z{k4^-sN5bx323({+QeHn+u+j~D^n($ji+esNee2_kmw^e4UA2*kr0WoZDZ+@*0LFf znU@U4Af49ujw}GLdvF8J_BV&?tmqKKXJQDdKa(&oFbzCSw4>l6KwK1C4VpZ>^VKE^ zR5ySMri>`6D+F9~$MH*KVtWIz1)kzevZo$Nk$(|!h4KUw8Fu$Ay}?NgHQkLo5z_BGHGswQbV4G8SIQz8 zYwM`Sv8)D2R95~YRu;Nse#va2tRfv~G(6Sl*BaZMUZaI5HZvYply8P)TZJ{nKT{@lmTvBO$nc?p; zg}>L}cx%Ihl*<1Y0Ut~OZV@$nN}9tO+nQ&lfk!iNS@C4U1X&U*mv@KFhc0dG8U=Kr zw@ISH{+OoRIIG5C0cE@-TS#}=b=Rj0Woc5`Co(SZbutXf{&=HtIQzV%2vP6lD!r~x z>PBDJ4K?Fz{+UBbgS=Ej41l*5MF9~rM*tGK4F#fVjV|JDC1C~Z`^XfHXforV^-hxX zGpop@YHc&ebj8BjwztESh%%mFl4Dcc87H;^nr4p1hi*PfDB4J| zURK3jg`O&6#gZ77YXPiJXa^Oa>S!YkxA+9v(?HR-kO9 zECGo`fo)w87?BlT!XAq3Z&>?q+GaJn~3 zj*a<#pRFrX15buM>ZsfpT8xf=C*4F%019oWY|Z*q;I~mGs9Gj#;G>qSt@VG6bqp<>5LrE6R;QZ}01 zO@AYX=x+KQ^q7hIsMil!j6ts0vj>MR}>_O003@JV@V#fQ>b`JAW?IOQBMCRVsWQo zDnSTLQBs~~!Wi`{-ybs!VfLD;cI?ohdSy9Yo;$c$v1MB{0X|dhHV4d2vEefDX0}Rd z@jz5kFoX4G}<7ICBQX52h|8Zk8FkWwy1Nsy%@{S4X-kNS5#^~+AEFsi$?9!V$)tm|L$}wq zD)qQ_J8!$oAZuDm>B6k~OYJOFn*S0qF7Bu&8zf06k2C!uV|CF^?t6R2%2-&0;8emB z@zunl8E4;g%<3!2t?t@#Z&{7vxlwPU-Q>cYXydSF=nHDD@cQU%l4WOw%V`wE*2C0E zrXgjQc9b!stCBIU88~O*PS60TnKX1ZT{m^B=<*rMC#ZIivJg!jl+{dabnUCINkR37 zfpUp#4cIwGR2acLGlof~kGR1--i$&z7`U=2WG`WKoILAHaWvURh>{a~+pr6ldqnKB ztTMP^)8I&_?1{@SLP0L=__$2VT({TV-so)(vozb(fRPwNL3NWF*P+;42gR$M)S(m9 zSjJB#wmd8He3^+?Jv^F#7&!u8fokHJPL6ejhX%>57;-olVV6IM`MXd>NWH3tBMm@S8qGz%An(^xbE&7wcQjtG#FWHRLM3p!!M ziX|PV=-*iLldxKuk+2SunkqrJMZvrjI2kX`e`s=W#^y=UJk=OA*CS3K?jS)6sps&~ zbX%I&V&&9u43cAm-eU3!*^B9jE8~B#KXMEy;(q23!7c4h2Q=%DYbZqHrhl-%j0KF= zHH&(Lab>lwfO41SA|#o_ICc>uU3#PhY8*(J0cf$OeC(PT8fN|LN`q0A$CW!aioWmWqYs-cN(sxUI&LE?9Vu>K#dUa z?)gJ=w79avypX50_ln#ahHCN#A1TP-_{K$=pD%pMR9dhx9rbe(GS%qX7I&JZ929U4 z_yt^1!n$ha-PU1UR@|C(yUg*klbois9AQ~VD3ZYZTyum(Clbt@5u2SU$@r))S5)DU zuYONXHPMn&?N!t}drQK@F6_)twPI0X#q3z^N>|m{>g93f*s8xDOkf@*#hhDOhHOnE z*s7n*K+$U>eL|dhG8~JTo!JIeT85lQUrevCgi;n~B&4;}lPk#P=~|pi+M8^4kRmFu zXK9w95{Xx$Iy^%8oh|V5Ii!>Fu^=o>nnaeZiI*Um4@eRtLn1w=b7ux{RLFI>+We*% z!=?bgV?A<%}*kOh_v4J2n#Vu?NhQH19WOm5u#966H)H0XUVWklj zOmBT?heB*_m{l7^YsrYhc(mOta@Xq2&d4)NqsX8j9d6@KeKR=c?Unf`P+TrS97PTT z(*Yw6bpDMIn(uLex~`twh>sp|ehKM?924fCG8jC5;Hbb5Y!Y{pk8hufw zZjE3P*<~ZKuGE*m+8zu?*hpU5ui1lXU@aOO!WqyU(fKv1H`99-;fdNrQbxU>H0fXx za(^4?9?rJqB+g1uUN?sqEyj>J#avE^eQNLTbOi*I43`^`;z3LSo(uf1X;g?z1%Pm- zBO1nEmUgQ^7Mu0X?=rJ3*=$f=ndU3*RHfO+ya1PG($=J8wK@TO%n1z_zZ#vmNQ2Mj z+=P)4`k^?E%{#ru@}o|-JRDAq{yLN!wBDhpkFg%2B2|`Ur7ewN{ir%F%*CR{StMNB zzwuA5dt@hJJuWFchhW=_!=%2sk~(h?d*2)kp{R5?^GSSL!Y!=%85^E#_v?KKXSD$B zrDFLcY65k=T!z|F>29?Ly)LEV9&ZfVnmt9eBfbmT5H3l}m+`1eNqRQ`UiC$MerXIr zPI9nX)Iv{ni^en64Ra#0EINpzrtlk*|B&_}WpO* zA4bYGa(Bp0NGpG(CtmXzp;+NnZMkTLIb=hzGAHxl|in%5|&;RJRqY=`-{G@1F( zawdnzZ#V^wPqe3srIn4vTP5Y`K5Z6-+9*H`Cuaxt4U7gkG?4L6S)7PgjcnDWWEG)5 zO8gd{i+MB$@kPP$-9p*E@F?H$XHn?cq+NS~sYzvy#y_2xKNIAL%lhL~98u6m{L$px zmJONmnn1RI%o?klQPl3TJ;inb@yX2U&W0uqa%G7A+=0U}6y9w+_*_GgEX3Z%|H#*FB!!(|$&{DxR;Es7fi4{C zA!{1$Ksje6LONzbZ;q%F?9jKkh6pJuUDeP34*4q#TeBRAkvb96=56*A!N@TAVHCmR zQCS_C)+E*p_hfK^Sj?*sb2t~d)~&8uF(TP$7-wdXYt1}%7(J=l6qso<)N)zYJ=OMZ z88rGhWmUnw9VBsxlwrG+NNxYN^e+v$av`03O@%bGpP#);<( zw+8NTFxE##^jYSaFyeIAi>YkwdNTpVYQE}AxrhXeb&Z9~G=|5$gC{YsWRgdQxHk?_ z8H-gEv!Y8WX!2|_onS>=SdXyDyf---$3el2qX`en&$ihnQ3QL&oQ)=Tc)WaM-W-nC zB`>m*#ieVUgT}_qw*xI(gd1dd8vIpt-5y#rF~Z3(itguZ!OXf9r6Qv#T{~O8NKgEe zWd+Grsc=T6G@}p)`QDpZ%9ICbGCOdd|E7SB5l?_nAbnN^gSao8wH=4vTe;nEAw4sI zweimk=%(W2`CZ&%l{pm;ti>A17Q=;&#^zRFSmK%uB1E+=970ZM3AsBcV=-dafWEZL_W@Hf%4L|)=7{ZjyPF>L zB(LzO92Hz+7~>L*$q_b0QoWJ16XZr-A6IWg7>16976!%nibWjV){7b?wKB~T;cFD# zoHrw=G=fuLn0Wp=VW5Q`xM&h$0IW1khT;vN%SeWl$>w5yqIRcCNKExCX0&6RL5tuY zF0Rv?K#m~q1x{bvZ5BWMR-zF{q=>-~^6`{e9{ zRupaETOW@Nj@2#h7}RrA__8{z1|19RiAr~KqXKnF{wF~|*Czz2LrM;_f{1(x?e0l+ zKW0QGk_gci6^?nnZsdVVY|+cSc!8=Gq8(XoHlugS4+YZ8q(IeswtvN?x35c~rW5>b zK0FBd>q|<*xpd^DP1FB&m6Mi*YiRdFx2C8d4KY901zJpbVy^juO`IgoYvY*4v zH7%4_N`?TAy*i5Y3}5sLza%SFzQ=mn@*c|JC814QSDb9n2>`+KQh5>@wtI69ks5it z@r5$FEH-2Zh3qyggI^AMl8&hC6Ak$J3s-WtA5A=yqv~LARAE@|Ve9NT^rba{sbgKr zY~RgZHpFh_`_<}v61KplL6;O**+&7pJN2})qECdy+cY=f3rSP5$@8wX^d7CUTo1rW zgJKS3*~i5Dltai~cA~!EG(?N3!#Hmrf$DS{K)J5g{6#Q_FX(Kis4h7QQ}&bj<>WG3 zjsmG)&R$o`lg%9)Gwz?v1u}7J-Q={% zj79lf7LDP?P=xx);lNuUrH`WPy1;3Kf(mwsVHuq4qkOMOS-6DtE}L|Gl5NN=Qooxp zePNHIaF30Sn4M3E#u2>1VSe0Oz&Eb2{9*=`EswE83XTQO<**$^0~$K2gFs zuL*Zy_xyrH9?Z<_hDIwFO8H;D(a7U&WruFL2lkfB<%MP>XLe{o8zvzvmHB*>kHc2R zH8@or(j5=7m!-vQ-Y3?2J^SKIo86gaRm$52rFgNJ?d7C1e13~d{^&EbCR^KLZ?I^ z)7kUZ61U1PN~&L`$%o)abhv?!9o0wuPWbwm`brgt8*!Eu8Gks{50}j0`V^gWGz)0o z(;)Qbsu@mXKPP)#o(>tJ22i%d=_P5@wG>! zx8^CA$U3#lEYA#+yD*@FuN+;5+s?0xS(e%K06L%R;7d@hKZ47^_&(ae#|4g#2{Ht% zv<_$b}s6mUIcgRIEb^&KT3Mifo&5RLAK6ywuZPq5K+?F;Uw>73r8v;94&Y&g8cY*;=j3 zjIie&f?v-g4{3j`4neWNWhX3KjK_d?K{kfegAR3ol;p}Tj>l5kJkf00q7chOm)~z% zi&va5-JC?}91X))`*h*SYl!~J?aRVwY}IRx<4Gbed@Hj!RRUp|;`^0tc5Um0Y3%BX zFAxhwmT0jr8Cj}kk)`T?PGl+f@uL3OGKGLX8Hx`YY}H1Tk#f2Gl}wIpwwB z5(B1vT20IKKq*30z}#`bhfk(xpImA`ks?~3LCK>CDoz}x1g^C4Y$tOnZZS)=*!7fn zkX=EWd62o{T}_8Ee5|^iBtE0{*t-*{Z3P!U*m`Y&)0u{vyLjf3Q`Tg2xKhJIdYC;d z#g2E=pb4*^xeOEEsc36C!rYwUJJVxthBER($j5N&+>u2x1CTSe(x!XzZLP@>NRC2f z*kG7#KTxm!37_PvTja{)7_12K>#rlUt(PHt9x)wakvoj?5U%vzU0Z!9IQf@z65wD2 z9epEjYnG_VmDrDLfXp2^$IL)MJ^J8o`pFoRCjUz}vFkp*bQFirIjiu?^_w*@^@R9W z)vE?(opCi9UC~iKqcdlwjESffIDpA<1r6)cEtbbxgI=E=a^x%6*5Mn)V-Y->)Yf$^ zYfJk#6Xqq#*kWE`Fb2K7jNHWT>5%q9OKv)kDGeJOITMXm z+su5^)zprs(2TDPT5n`oPlkDqk4X|jMtlYN(qK6xy$VxS zF8!QI7DA>IepU$C;j!tZfoA{YDOtj_dVsqi8KFQ>8E<3i0ZJVLmQk9I_&J9bE$2-- zOGEurW0;bWDo6>FS>(Q?}l~@w;frMB&8NM9bu%V=lk0a$ROWVka++-rmjgy}tWR+S%=rrHJqP{m#lGED( z%9H+mS?Q5Wp%_k*EIu!pu9chmXhbA$AnAI%58ISwgaX3*MlKY&8=dHz%t4mAz%K=){dwZo^=DVCzM=>Haa;I{e0t7^7UOt*6 zS0IN$$Qj$%q`-6G+%Zz4Elne&BvDna7BVXJAJGXpJi5%R!fj2dcUmucO8r#al%J;; z(JNn^mq)6l#Z@fLL-Rw`jB#A+>3DRt@UV?QJS82zH!{t@K?i)}+qs&Wl?i_0H1HxQ zjexglkmX(S{tGA~m+=gM{cxA@%LOB#X3^LWEVDqDo5-Bn+p(LS{?SJ>mf(l-9JJXn z(xPZu=*nW%6EuEA+K?4bUcqtkE*47qrd~6?&NrP{*`|*5nad~A6}I2iHjwq)H&tm5 zI%V*a@Hxn%491HCAU?Ff+s{+DcSx8Ir`ecw$V`p0-X@seu-LAhl^SOzanr^oxO7OV zFfF*ikS{zKO_O6QQ1Il^14@}%sq8ZH?#Id|m2JamJ#-BP8+xRCL(_;;fox`;rUy?9 zNAh=md2ESuCW}v?yDTM|ILP`M)vB3|W-Cgo>FPp!b3&YXR>;aH3h~#RnvFWrK&#SF z#*Ho+Ek0hL$(wu;b3@<+B`2VxB3R@mRlSIamnO%M3w(HGD6uI)9UJsG;8=!lXW(&keEgvHK?xiBV<7>ngfhp~+8E{jJL z58rek8ngJC$ezMIPHfnb@IGZvlk?u>LMGjIU1+&yPDCU+%VEg@}8Qh4CTY*~0Ii`n44<$Gsl`#w%9>r`W|3f~jCG{i}8Nj(UFpdC` zP({v7cG>@@`kQi{;04HS3v-YJcL)*Ha}P5u$@N3YuipDix~!g$Bdek)X0oHN+Fo$O zYB+R7A$k~@n?rJL%K{8InxDlq)4YJ(t^SgVdZ`#4zR%z3pI1#mqC1{7F3`Okr-<1L zS;x)PlALm)vDBU7eEi&FQ@gFr%_*<)h_ftRqzI+X0SY!@tV9^LoInaoc9lieYC8Fo z@(TJcC!1<_%>;=hkswlo&|>3;UbEY&Wa^B?HHMhCIw?6rpd1tH-QnDderT42H$bYz z$>38~1TmOh13Tkqw+{Bx0(viDuY_DZO;3N2GubI32 zEy*-;>%ES09FKbO=^-m7IJg46ZaJ=X=Myl6(tSNx_h46rg+GChZIvX9! z7~+IZ45Mtm=rnY89Fk4KDa}i8oQ<#W`2xxoy93{}tB~4y)jV zT=q3hCtj=XbX&MNP<%7#BykN2rd{im(ISDjF-jfj4_* z`7o`;%SY5YnrZijJW~`SaO;fmSWhFyg|2w$sUe4c4;+|(&U5AtR^w>@xKKMdJrO#@ z3-!vcV6~5-j8^03`bqr>J4Lp_(K-(d)=l?^bV++K^< zHhNt=D+?E1j4b~fxA1uH8g@xCVC|G&+=AE4?eXd`Nvxg{5t?aaBB%S`8Wu?kjkh{A zf9kYvl zooljTo=>;P!9BX)|+K4T~OF+kmoi6W>q7vv4)Sfgq`fg{y9Y%-&^;TPr zZTA=Kwq-1@*$P)e*7RBnq$3mJK;B+VqoJo@X|?qmmBzzl1GJmf!@Ghh4IR(*!X@S_;?ZcW-}c69 z2FJUVx1QUfVH0-``GR?sB(hr$&$Z zbl32B&H6$zY~n?GzS$6cgDT~I8PkXh$9sIqiEgI)kI$6x(Da~3&o~qez$}{3xZ5)E zg4}||q&zn~T1#so?TMIfR*_Mi+AJV&O9$SJ7*$)yB!)w4+12Fs&nkZet3>wB9o`(8 zR`8M*NPw=<$(j*40DBD0(8GLk>QdF!Msv*NVHP_mwD#g?s5FaqtgQTy_B+C}D|Bh1TWpY=LX6wRAQPG+uRp7Z2zuNW z-5K?~Vze#jN+Y*I8vbYsDnp}_kW)l|RS_h+g4i3U_3K9NFz2&jRm|O+jUQEQ4C;B*E0n27{hu6N0 z7YbKkGbY5sIj0|r1VrLWqeGGH6*9asO)pjH5S3V}y8@=v9yU4%q`UJ>rnDnB$gweO z?<_jZ&dh8RY)=w1Zrz}PZlSG#7HBV%mKU!!+J-K%ru_P?WzABIz@1x%W@%UK!p6?i zEW2>Bc}wRrUhNIAJ}{616Pue=F>2VHpbPvhN_5GtdCDVaUW{SR+-F9M&>ESjY?2oY zKcn}8`C-+Ul(0ZwWCC}er$u3jAwuYg0dII_wxI)v-)3U1q7n4)p~*P%T6?$A?G*?J z_6xyfsjfA;iZ9?L>pO&@#cqD!7+YWP+#&;Bkw^?Y&(PSc_V+SzTS z542(Hmg6e?HuyiNm8N^f%g77K6XCG17>X%zZc6*#{VI-Qr}$fGwLtY~b@Em)@8f>n zE8zOzcJ1_maPE0}fhyKh6YdI`wPOvyRjrA{TAksxp~zGoIQ%fv;~Y3;lit$tjAMG? z4@9E5JL{w%LZ!}phP>rH=ClbGT`XY4q6TxV(_N*bZLsh@xL|L98#g`a!K;$j%*E$v zF=8z25sXfMtHohE6+F~apTNv`)R-N2h2eVlG+apN zeojdcCaW$?agkcwHI5CTkabjK&6(dxiwr5iy!iZ}V!`sSo}#CG-M*Vj#pZ`N_XZs& zcn7kPdW$k)nWtn^RjB`XbN%$`7!Jf?kBmc*&(@eno|Y!JOQ{Gw7BoH19EcL$uoh;7 zy6~*;lB>oYxTw31JzwA6Sm|}#v4$L$-BV`M8cs*Vr@kFu#GtL}5E^oguGQ&|$kJTR z_lRYhs^@uOj|~N71B8|T&`i9nA$)1MRWv2?1`f*#PA^Z{rz@M;NOYex?v$6Ac=`wK#_S8?fg2}toFYF;c1x62S37ui#{K;N177XyH2?qr literal 0 HcmV?d00001 diff --git a/examples/ThirdPartyLibs/openvr/bin/osx32/libopenvr_api.dylib b/examples/ThirdPartyLibs/openvr/bin/osx32/libopenvr_api.dylib new file mode 100644 index 0000000000000000000000000000000000000000..b296e20b85bb0a23606a1dc7350a56c58b4a2c9c GIT binary patch literal 299972 zcmeFa3w%_?*+0IUEXf)cPQa*9BcS3XLdB?6Q&0oRCfveB4Wbg_4JuVG!memFl6bNq z!|^EIY3qen+uGXprKKR=Fd=C+T#AVoM4%Ft;#rs00KSj_CI9bt=A6wYM6~Vu{@>59 zpX8IXGiTv@2fxqlgeBaJuuJL~hNtJR zhXXwv=;1&Q2YNWr!+{NWSPo*)aFOPTXpQnKK_*|*NUt7JhScq;Mn7bpqba%)#QELcfaoal1V?SvzS zj5uyv5STw}&iC!Gt~izra=Z4N>T=PI|BJ^59CPO^=wNDB9816Fc0GjTbUX1h4q-`2 zaL&S6b8au0HD~5rgm=Y}Hp1<)zz@3ddB>rUyq=24l9IfU*Nu#e$wB5Y9Z??WIx+=O zl7A&7b5NJ6O6LXUcbk4RA(1{lZ`R{Y5`(OZxg8uhmWI(t%d*q$ieq*R$6dD^kB;$3 zdl!m8Hy#JeGbe^)_FOV?R-j~NaL#SVlx59Gw~OVb8;|1zJ3XCa>$5XItC4mv;OL@C zy8SCDx&4;FEgex^>!bx~pF~;ce!WcGHh1>yxlYlJDN9AJ+vPO<__6?P?60Kc)&&b< zZ^zclR^XUqCx|agJP!ItX3b-$8tPr^EXec%~^ zCmoLp=dat9bJyHkZl5u~WZo@-JBHmg>(;sRX3V)~e#tHKW?gvueRv0u>nxY6>>_%A zn{9YB+^J}|%V)Y><3Z@2J5Y9H;Je4|8VUg*?aXJy58bYpP?4#t+^!>r%helUlko8G zRD|t}1?g`>QWManh;d1|v)|JtYO1 zrnt}zbyNcUl$V?FFfD0yxh+sI)IIFl`xXRd%pNv=)~)kznSbA~{Q0-cp0RN5{5uy6 z%by#ZgT^>(?wku}I-$d+%$UCbAq$4(#>E32@lVAQ!!J4Rb{z-*M6kVJe0R7<4pVV9 zUe-elulruS0dH`@eAXSG+lCCeFw3qw(s5}VygOwB%GnuS75TzZPHlHh<8tjfCXczd z{@}I?M>;87u5$rFeqV7P^bo`<(|%|D_x$y6poarJ9O&Ud4+nZU(8GZq4)k!KhXXwv z=;1&Q2YNWr!+{2)nbXJ8f7`Bx?RP!Gv(if+Q14~P{dz*{SflzOcnAwtxL4g`i8`T(R6 zp25}(Y^MzCXW@;1VHr+eR&}U7aErJ+T5R}zhCu+MpU4~R5x&9g{kvircswkp1IsDE zmK5fmG?$^D24p!xI(nUNddW>7eyO6je9yxGQ6z``dk7!)%h#~KMZIA^ECaVHr&&3h zl+&P`Mmnay0rYxJ|5lQ1`YjYUoHv;Jq+D>h&xS7d>A0-lo$qq3<=(!EYOP`ln4#dU zO6*u&d%GQe6~p!O{u^8*#?qI?2x9bdtDZG!JAxlzewK_4t`V0qR^h*}pUb81@gRXU zmw=ZJwuS(;*tvFwjeHASbMX)dd9X?)_x2_7{o4Q=Ao4X5dGRul(Sf`PWg&7P?GNM! z{L9?IUZ(#?(L}?)oRvK36qI5n5QVA(v&=`o$4thfDm{Zmy>%@j#XeCJS|7*?`=#)h z{tB7R;t7NV)Ry)pu~#gfo9-rxQ^liq!k2X*nz8l{U=?YDtuufn+Gp)7zWN4ReTg(< zu=NlKC($5cq4YM;dzbWXrS}%;W!+d);1w<9bq@oF6bj)li+-0s=irCfE(Jt1oiE_y zd3-sUFDUnE5{=A9lU|vRM|x#GZ6C$z^zZN*NQNw*0f08J3>ms0e^Vw&NtU1=BReq_T#w(Iny35x* zJO2_Jgf^?}n2xA}DF?mcKkJDFi`1YidAmYpGgs<>x@Dcua_?E};eFa|!ef_=$AK?|grRwk4@duO~ ztM}0lP(qGEPGaS@^9=<>@5bISdXlNX*Dizj>af7t_a3@9HC9;Xfy&P5q(7%Z49eTW z;MJmZz3sL|IidAhi0#Z=@!;QFu1FiaMbzR{2Y0LOozsU4|&?dUM4z)CRfx==%sk3uAv_uIRTH zNn6Yn=hL;!6(i_2n=7uPyVYEAFWp9S#mjUX%oSm})#i#Q-8JTl?~&9Mz)tsNbHyUM z%gq(Pq`S;qv4QSVbA^{ASD7m=qg!UK_yOEV5L`#W$Hxl3m7ygFMTX?+b<$f)?-=R* zoZhRX_Xxe0NbeaCz{vU1dpW&lNbf{?`%CWvdXuGhF}+8?c5}sZ^zN134fO7o-o5m0 zm)?`Ugtt+8v+4bl^iHGqb?LpE-v5%`CG@@|y?>zhN7DNNy^l!metLE3?N6DyS9(X% zJ6n2xO7E@GyOZAQr8nU#c*jd`7QG{-SI~Qz^!|?CA=3K+y@RB;o!*nAcPIvIkre5@ zf!_9iu<(`iekHvt>5WKlGrb>6?^I%V58jzeS3<1ov6;UK&kj7F)t&&hbs#4{An<#81X-r%$6L+Um9*8A8?;sl9 zadgUh#>eTD?T7H*y-qoRwy$)`vpBd%oie;JUZ>oKB2%Y4NEbTgS-Q>Uir45ur~HL( zqq(AuE_BLiRA1HRiX6JoDU0c@FjxGXE_BL9y35TKEp(w%Qc3DkbA_KSbjp0XW#)?I za2=g8I#%$+R)m(wwtpR&rF6=D^eUb5JiS**fH&z?I^{3)DxKn@RysohoJFtFDOc00 zbV>=mN~eVARXXKGdX-LDORv%?pVO;!N(x(;(kai-t8~g6^eUZl4j5$XlrtHsbjnD2 zl}@>nUZqo-=~X(VHr9-fQw zT#08hcVxpIiDwL+$#`zSa|@nXc<#nS-SIBm zzu>X(?8kEy&k4x?B)B}II}pzWc)p7#2hTV>Q}En^=Po=8@jQfw@Fv`4cwWTwJ3O!9 ziL^~AslGH46|ZyBBn!0!ruyu1rl@k-B&s-e6yazz(V-H3WvzFJqQYiyinAL za+xv=!yum-YDFvuL|<#L@L+)8vi=NgYk0`*Y>CC_JG`(p=&P}Mm)DUd^!L`LjTpkl zkAJ(^gTe*GJ~sTt`CT{M~I}-x7aXMfD$t1rn<2wAH6n zH4b(MlSETf1O|?Y9-}zb2zoJo?prmZ4il>MrZ3C_ck~p_WQch`PP|3_!LnWNF$%oe z>b!(@y>(aszG}U7TF^ZP6GYCDeQKh(6^UZw&Nq=*TkEfrHB#E3hNL{2<+AQ%)M|gj z%kE&ZS-8H*!W759$tY|jtmGXszXm|YXs;-2*{7wt_G$h6Ryaqoo$Pjnb0pif)rmmU zD_0`P^%ysCR_B#-F-*xYRZ3BKU>Xo(y*8?Z?l2L!4}i(rUUWgkKN`q)IT6L+S@`Q{ zL#d1Q#t*?iMl`{<&;|HrxCWvyR$mAV9rFz(KVUXS@=FR+E7q@Mm27mXcL~xhNkTci z<`lOmYKitSrg+T>ZWKP6uyhn6dTXm&o4z#gp1jm}&|^&Sy4$ih1Wwjgr|506M%L?X z(}M3;owg(?y17GC?EV`0EBm0~m$P2mM%SPD`Yl-xr4ey7dXf=rF-s%SKJoLv{HmI= zPu#(DZS~fss5lfoiL<-7`Jqv~$0%xXZ_C~i08HO_dg|(vh9QIKn-%MW$=d41rY|6P zMSILrEA(!lF9Q3?Kr@Iev$jVnP_Kvv5!&kOF2*2Tmh4^q(6nGSfctB!8=4|!ULVUW zikRd3M4~>Uka?SVDedm2%$m$bNRKQaYh@p1DXMfZ=~3eSEv9)dIw+@k{vO5GTiXMD zmpoUB;Ihwhs-sD;@oZ=6gfNA)Hr}Wvo81?{%DR3U@iVo7dD8wR>o>!qT*4ydJ>YT& z6LXMbj@J~oqlx7LOr<`_f}G5X=7 zYd~|mHnEoCwuw}QF%|U5#;fLkvayXIa4RGTq6ZU6Uy&Y7Vfh|GimY~K#FC0uy)L6$ zd&_j#zme1|Y;g+VL$;x6Q4^S|m$tYcy!&nDvxYxnGv!TN?Mu?zQi7+T5|dDgeS&@J z^Db{siKZxiRr#(e$QkZ$d0>m_xk_*U@*cnNZ#DhREXUA4VURM>th|Q+Hb!qi#{M1AYeZ>-QMkh>-DHl>z6i9_7r5%8 zA;p^%|FqQnMxbrh`i*SV`i*JEdyAIZ7q2Z^zZ3MD9KAkAudNP#XcRZ1fJSLU_D+;2 z(9hOKOH!)5qjIv}3m#xeT5WlLu#URRf;~Wtq@MIQL+84~{#~FL9dfgBq=?&f)m%&E zC{0jMj-C2T*o&xXP@#UHwKDM2(M7?&5sRlxCjqr}H$Zf0SLJ#}ape1W@6eyck#QX; z;?rAiIq8_$Ly%0z-i7=PX)}8&9^z&|#L}zyV0?UzijV8>r<;|_G1sLqhCPEZ>}a<( zqTpysz0F6SVGNda8m->IA}YU!qs`{??;eF;t}=MYHLDNe*!0ZGm4pYOZ5X~8YbPAW z8x}rfZ&mpRpk`byu$#|s>4Iau$}s7qjlu*Z5zvVma zl$G0vAGzra;o^%5K`G73$8B7%tz(_2Wu}hmi>)_hplL~YxXD;K3}af3;9AVLEbs^l zCZ?_a3M^DOpTR9F^|=CL!Aqa1{|=T3_`K#@^O&DXQAR2Uf+i!hhj;)fsSCC6O)f)u zBuoU@qJtHt^$w=+JRp=rp??cLR;}-hMF0n7)DSl9}L7&*8v&9kw)kfKw#t*vIxm4S-g3VVvr$m zAk1S()THy?8qCCNV|cAk-)3>r#d9*dClw)2#SvnhfDQv4bQ&DhC#PYh3Ru7aBaz5W zSt25T3@k+$eD}k*#GhJ~n{MQK&}bHtvKT#}S{692Tmd9Fkn6>`*39*?&&^FW#(A8+ z>Ix#x^~l^7zt7?!kFz@hJIdGB4n+Jx6s_$3Q(b|xtx5aa+rj+PjKycOMx`2v(O_*O z4`c-sZ5}a5S;AC;!XW!oYY~7tjhCeUNtZ2$=2x@GCyI`kMMq$~mV;@t?5|V|vW&o@ zI{rks*5jDr=ymC81uK4j!sTjv{V81e3{vwiT=_)I_d?9~lbG*C+h?w2m|6K!MAp8X zf^2(>>3@lEW^77K^_8zMMSbOO;JA%PUVx#&say2eoPB`{6>Hf#Qm2;`*Q$BSYe2=0 zcLpM)7D4%?epTyN(=iyNdU$%DluyhHI3D$2JdXj}9`FZ3FwU%e#U{=yZcqx%n+#g4 zG$Nm-nzR|TCm=q=xUBzH2oGRN8O*HrM_lz-4v!8sEBAx-6bLBp*w|vzn;2U_ji3u` zL5FCs|HP}YZGbQ^Nbz$%;@_$!B>rxe)LGU)0hs#tExOP)rn9Ck>(lxIQpL7N(o$li z_4(Sor^~#n?Y!66c_WaNu2D`k9p*ho0=IN@r5 z&H?EP!0xvZghmU4DgbK{#a$=Q;{|hTQ@=oEV-{75z1Ckb_%bIT^Rr{2R+9|F;Nxd@ zSZTF5WWB-ApZtPB7#pz=Kl(9EYQoF|5zGO+ipBLo92pm^>d0NM9}MwO`OXHm2q$;4 zd8cyf*;jhcRuAy(jx%@Jqv#uptTC5a@4CI+D5J;Jf;#N8IbgQw%jEZb*h4Fl8dC z5t_zulLK&L)gAa1`)a;OG1Hc2)&$NK2g^Tihfvgfo{;#x#8r1OdVftcrF^#x-JOtl z>9Xi4S?yR2?`Qnbqp$PC(U*NN&`%G0#Ni>Ql^^CUK*7I7w}nGQ!qV5YCFpI5^Dl;Q zSMZ&^ILhI4B*ZcNk{k(9+#P(l)^+ zsHEfOV;kun!l%X)cJ@NusX^j$Q9?T?O7D^8(GoWhf%w=9`W&zi_4GNwfom& zYBy6=>f5UvT8>w#|4em$ccxvRw*z&IL*KeS(^-j`NE+>{$`|dYT)TdkE@D;7%^Q#X zkzR`lD&aLGJNPyf$yFlO{SOcqp(c*WvooH`5Fd)oQejUO{#_VlJKAjHQ%Y0qg0whc z2cLvLOkMXkow0$_7-RT%nPo|zAPV_j_uuX9krhmH*tjZsN-RIU`YVyoEpXPyD?w+z zC%ZKmW$$<*Fv)?{rGrIqm$mBzydwC>Lvs2%E2|xnjQvaOKpFnzk{GyE1wKI08HKxy zk)Giry %8j!~v=HcI^=XiWkSTORChB4SF=fOCS9GMD;0wR0@8D)p(zu=g%P(DOw zBbw#>E8IAHUHP8a{B^1beI*%sef3N&)4!EJ4g6VSZ@~MawY|M6v>z~8+x1efORGp` z!6?L@7!H!rvI7ben_TAsqv2mJ3Z%(q8Af`^VgIwJ zGmP|>DQ7tyW_1x@<+L%vRUn)CvUwjPmIE=_GsFhOZ~Pu~3@{dX$+{=WLZ`D)J;+ZG zudObwiYwy7cIVQ7D3tOfRR|2Tu(#;~mZY#CTG%yPdmjD+q`|;|($*Eil>H1uAx7Ik z(srgzTPsQxqs;-ejsO#e1P79^#4t0Q1o%EizT{y(bhzY4jE63uGyG*DpFETpz{aF- z=mBbc{Dozh^!dx^#3-`+8|E?W7l%0+i`og#mb%9x!mch+ydgP%AHD$F#x!ZQ|^9mXX~OIJ1-fRMzh2fltN;qkv@&M;Q`qM6yi7|2~qPHghTUt^a+g3ne^) z3ExQg%@V#&!8gRgHxT|R36EgH*AbpME|HqdyR`}gu0hIShW|~Z9OR6TWPWcl{n6i& zK14D-cV%1CkzS5G99vnfQQA1X^!>m<*39gJ=xn33Zg^=!;BvfcA?OxYL1a6Ak8RbX z!B}JxYt>_rS#+o+#s2n$A8j{pxiF%AER*eTT zQ--p91Aqz)I9-)Nt3ZozNxBb7x({|kx81g02l~jNBN)pnBIb7@!Y0|eM-jo-cp`j~ z2nXm#00I%G*o?bg62J*gLF9yP^t9oZLY_?m?uO0fScYBEg<&nPbkEpU^k?xE&;Ymy zMi&lap9gn37;9s-eg-Hb==)Zh^%sN<<&YkwT!};}*Aeg`E2tQTDIWppGi4YnsFWl< zfk~sy=H8u1vI}5olBCpcMbe3qBo}hBNg@(O61S!(LKvoe1XLtBnSJqVkkks2M7>eE z1BWxtV+(E#q|0X0Osc~Gk%4G7r90Sxp2u8E8x{2XF=*MSe2Mu=;fz0h5DQqHjBI11H?y^-HDOluE5H8rud`b;J&(hs8$4pG z3U6RIcE%nEq?;a$Zc*i)9AuC6Zp%v=3tLRz7&EQP^xb26s>H{cM*}~A^-C1((d)l@ zjj2V;!B0d}O(fAA>3%smaD!g^m1udLF$X`b`66+Y{%P{TZ7?8WylE`(ig`!Swq(@lt9u9ps21O%gk@9VX`Xex7RL`fn%&H@~ITe9}h)$kwOsn;%FYK)sE zMiXD|bvDAO3e|PWnMTJLH%W}9sW5jmfvj-ucojQZIg=Dno*2E0KqCmWBb=L~Vn-+k zgI!{}LX3vJF*Wxh0yTznFIBM@Dd!3WG*pb z6h@O$!f}HKOZ>tuCS#n^g0)6W@G?5t$61vbgRSykVl=-qxEF#g2ce(gU3U&W#qU3G zUw(8-QPD~B`{JaH_|OWY-w=lg46E_5nyX9h=l#L6(VG2++>b;p8W-F&1h>c zA#)TNqHcOB&GFCsAnqjjG-JL;?9Kd0tN0USOhDdhzLJtG8l)_XBFh{_A@@W0MS~Ro zgP+8Nd?^ODqJZ+4gbFM8Dy&Ah9P~oI^Obyuzd~BdcfF5U7Pjc67KC~%g?hVQzdW9w zM*cK~FQ4*Fgi5~im3-$b`Ocpt3Mk+ClmCPNGHdVLo{^Y=bS*Vj(yVG3R&(dxjKs^M zeX|bW*pk;+=z*DS=2DdCbTeO`NchW(pt(LnvlL{6 z_`2*i(V&eAFX&tGZZL(32O_a(t!Yj$N8~Wy{d@;aiSDqtAId$U%71xbiRjtEV`K<|6j0zG~1Rn$;`%thsdNx=YJ+0GxN!gp`0N%DYIW0w< zhl5;q+0v(4v)UsV&XJ8eoTFNLj?xNPM8{t^M`@6pLF!E^l5mdFE;&jQTQy8rYdKe8*Y8h&Gw1om_CTf?~>v)aEqI*9=youG|HEA z9+Q6&<`2CJJeF(5&N!VagGHC86qPQq_iH%k=WY~5*b;bt*CFYKssSuAtHB!LY}59u3GUF^(Ye0%K$ z^m+Nxym=SL=Tp+KqpuKM(afdh*mf}?4O^$eLmu=5l4?HpP85gbKCR3T-8+Xom|EW6 zp6qhnbBd93gsm(EMMOfq`Ur;P#)P!cda)t+IwS{gQ#@JgGaKJViCn>Vw_2Dp@; znjH@IV_^qgiNq7q0Ej?$g9z7rnPQ~9eh%%;BIBWvpac`?aM{y;Ar6Eg&FQEJ7CVqB z{F|`+EY)*|K9TYXuwDHj@1>S6@b_qc0;=Q5M6dxdWe?tracX1WTy3=*m7^A{^RI(x zfEylY;N;9U0a;o`8NrKPfqra8SI&|4))b>~Q}izWe4n8OG8C`DsaT`!gJc{zU;!M{ zJt#2$`)1kjKP&dD#Qu0@?0_x*3fMl)LR@Zc#7-aB3 z1hY6B;l{0}D0wX3^DI#i4-VbkhB^F|7I^x=C1&MVTMpF9JqbCRpjFSQ+PQ<6BTn!@qU3-g<(z zxEkd!Dk_J8Z|;`%=CVc8VdBEv&DB0J&wTD)&KhOCdJu%Ot<@SEY|z&8Rs;zQ*`=HlnL6v12-m++x)%%`w94*WKNo0W5%+Lty=#Sia= z!DFwu^6fxmLQR@;KKhz+7bXaVtX^YI_SmAhpcAV3T$LkQ2raBTK{+x-pPxA44&XCWm0bZ8GXcB=qX z$Nur5(D>-i&Ej3LT{^oMZ*N92CVNE@Hsz+eF>kTeBg%L)Xu%2qI&=0D6EX};g4Shj z$ZD@Sln_Xsb%>+riN=)kjp;)(Kg4|cG}UV(7i;C!NIHEeBW1d*_Uwkh0QY-eGe0<- zkvQTp*tP7%CQRA-C7T64U~+18-7}=6MHHmBW4;FB-a-IxT^OnssU@p^g)p+J2!wZ9 zj~fbklKst1$6I?@bu+cF?BqNcMYycl=x(@2{kV$QUQDdHl?3{XiD^92vM|*gk1g<< zu@r5j{h|C5ju{N!5+lbmq+o@H@Cx_4B0SLK0x2G&@}dG z^o>W8v=I6)^oAwqmUcs&Vy0{;TBHOwN^XdSLJh~|zU4%<2+SPpWHJYuUpWd(0&C<} z6Vm1mj;#;f2al^>Eq+DEc9c&)+Di-FA#;~KV&{CG#~_;@_FT_jc9S(gvTk&KdiSfg_{ARwL&%)XDbP|@M^|u((TML~F z@{cPqollC4xrYtiDDW5)y;<8cYcLl5#5+c8#Ha(Zl=)uvMvO*BU?1znKnvjl;Pt8Q z4dOlQVKF?*%0HFE(My+(6cf`3_akh!LjN`~%^ZnUD8PHO-WByj7IL_}+dDz*<2hbe z=4SVnAq!Kn?ZNAE&DZSV^7bcDjsouyD5;8mvKHh@f?djC05w7k(OZ2B$GqlALo0i+ zW`1h)N@sqnqF1{0)&#BM=g0_S=XV#dm*hqoIMD_7*GKBbzKY;NdiuTFW>WPT0ZATC7FI%H|bN5K9b4g_0bFQT!80XQLm~znns^weoAx% z{SG7MKE{Ge{f}&mkZlJWu0G^8g)PM{^#H6tV{|Bw$D_cM=^udc0U8gxvXB8)E`%6I6GFRA*+9~lWCieBolKmMnMmJ=IbZA z%3Mp*%W4m5tM}_iPg$sGFYa5Ak|PjZ6Wk43(Q35W;^4_E-KKwq(_Fs`#U6PALI7C_ zE|2@kwWs0B>q;2lxC{->m3fMhp2`MQ0ROiHw-8`z`kERsm;B*_BY) zZ5>iTWycx)I(c?1v%%dsq#*T5Ti4}E)4-RHDqUArT7@3(9aMv(A_~y6wEG{X{cEKg zJ7DzI6s@8^L`rYphRPT>FU3 z}x}R!uTNm3G2skbvj%N&+5S!~B zo%@a8UVyK3JCozTAOUp*`_aiTt&zwRB$pX-HA28*XUN%c{uTBwRo-szc5)0TYzM&i z5xNHM`~5izZQFfJwKn?#wZOMw!xRv5T)@t3I5_7U!N~@P30ncq;!e7rGaQ~-C7Iy< zIEcP1zdV?9U6c?XCZ>`;~ zAHESc4IMsn(RV}JwGcnusurpu1@P*JXD=G1AHGR#>DCVyYoX<+fp8KOew@yQ?0p(6M+oJ1Y{hl?WA5&GdDE*h^No}-1@WoiukT$wf41gt&09VEYo z6ijSB{>EziTOf6I{!!Y`iS$VXF=ON%V5-ziP67$cNbc1s4Kb*d1-3N2mkz!}n_;3_*bpxws;aGORig1jystT+b=U zi#`xeLhtWFZ&qwha*ONpwAHBfX~6+2r{UQ8IK4UnP=A=lMX7b!8?f45+!EXpy+mw< z=&U?T-Y;-gaCh{qa1tg>uIP8dNj|ug_zRJ1^u%xy)RHTDQr30~d+S-aoDUZmB!!b; z;z2K+2TQW-Rh$(ga?}}reGNZ%lx-NKt;S*V8DL%T4aw03ndVftwmMZmG$f#rCy@T{ zNXZDEO2OZ_z_(NY!mi2D*WcF*=KCm_Fi_foY9cmAFVPCuzS{R6B4O-D{GnZ28 zX&d;a=MlhQpS6U0+V=DPo1R|)HnzTiRT5)TjxjnfyD2c;yxT42p;}JW4-X4oFN*hI zHCk*G2eUuaDt-ja;$yu&K|&1F52J6@8CD~?-A6Qt!@>7)-hTl@lF;`eWM6QG9!?PV z=HZHfo3hqNI3CqjAJ*G1&_Z=coV`V>s3sC*^$s$N)rVPkj6>AGt(NwbN^BtBF~`S)+-3zt|ak*=g%oB9bVq zt8LPwaHEl!ygB@wW|7bmnB36d|)Jw16rq#C@u&>S*~m3zQ3dgGB=P~s;24UlZAQ@!6B}0dS~*bT5XMFrzbtV*m1Sa4BprgPW>PG7~xn8GYZur1J>CTfHfHEiPAbAF0K!emqa=G-kgW49$K{3 zUcC*KFaapA+&$7<{Nt5KgNlf)1$fUu9#+jm2*yPksx)#U0L94?UHb*JcgA4rb3oY3 zY18D4+g$uZ2UoBeWUv7aB(5NFfk6%~m?3Rk$;5T(;OHNq9aiC>0*uSaQJ%;^Ar>#4}9 z&fbgx1!&jT;#ZvolY$ZA$s*ObJEQnMQAh)!eSQoxw48R~FXP4vZS8=nZB8eeqUjAl zIvi8KC)N!wtkRyS$4xr>^xDRXcLUkk2!31!KO=)H-c>@L9W2vAOPTID3b^+4I$fT0 za|IIq;6}oGv)W&0Sq^?``h@8loA2J*uWfj+V!m!jw#okcJHff?@Kjd4A@3~6dgp|L z!JCYbWMBIaq;kMP9)V>Ml4e z>)nG}Pu)QNnK-RDVlaCS>-^40ZvfKh{0Q`%%XmtX^Y|+yr@z=zb97+#I_@#qt2sQu zc{}?^zFE4If_7SGY`uwXFm6X?tBL&Yj?-!($=ez|$hWiM|4R`{FcWiML|2_k|!vT;`85;Po@MtpRz$=#;6VJC0a z0plqm&_8VsoF|^*p&;}6_Uy)mXS!>$H!eI~tc&abi^V#HD)Om(iBKR_h`zhooX}ho z=_O2FUtvymhvl6V0B{{x=f-Y+Y?;(j$ED7+FN9IigNVSC*`@UsPto>erg`T4>K-yKMeBB#RW0Fk!S3N znA#k@zB>4U!fdQ!)`pFn49MOqHh0_?)4M7qcNCV64!C(X-Ylvx-{SF8Lz;k%%Jx?g zI2!GSwl=+b5Ugk65I5Sh)N(UL+FE^)Z9muVG4qCXHaz%ZFa$*uJ9R-@Xu<;fZj=A{L-+~#?zve2*SlM%XSY&JG z4*`Yi=gf=1Yt*xg%TedU-({Z}h0A3w-lY(EOu4{B`F)rOup54oS3H#yhvSN`!C?;( z%;yMzF++S;Ykl;I8hOkHQX-#07eZAGH*33Uh-PVpIt!v&lA$icfh9Yx)pQ&MJ{u`b zb&8x;BfJ@viL#l=5paj$+{dhtWj+%q4gC3i9K_*jwAhk^kc^E^Q*PwHz!TexA&l*f zme^1OY!@eDSyzID5L}*^mGO9=g%0YUC|o|0cNA_8-VD{llyzIgOoHRX z4PeC0(kuHJw@fA}K*TTcX3syI`NIf{b&th@_l@FoBbdfrb-3RLW5sD07V|1Lno;em zAP=J5a}R1-0F4jFA*wxeBO=1krw)1 zm)K$rz87UlLR4%>DMuD^c>2eku=D-~aFJ^K;56m0;h3Y{B1MjUrv;15(FuIv#3UFj zF#WrLNKuM0g%Ut#d`iOv=nWeFbaZzKHO(pKxQ=M9UYKjRUgK)!*@e4Ks1YgA(URad zV+8XO2ogLInSY}K2u?o)%|0#P6D6)nO45B83{mmU@B&{Rq4^|WNhN`l1jY3ugBY8 z|17zDV~fHY?44gVz?p3u_jplRa^CVz5T!(Y-j7nn>0hV5RC~eqbmV*+TUJiVY}8v5 z7v-4xj+c;<@-FY}WW9|*R@P-eXe3kG(VXIEV(WK6)aRp4BM-6t6u)l-)0G_=CnZF( zwl+b%Rn zbk{U{L{im9Wi>G3;f~Fe1xaRJVq^4t1_2R*l4Q`Yq9-v3m=M%UTf7XI07+D16NLs; zXhhwj8hk9OesQQ4PIl0Eh~}C^g{G+!MG1}3!Bq%~qbT85(S8iFDO#9f<|Tld74B%h zY_g~R+~N6Fs9^GZ6nVaGfx~mVM`B-OPg<|puGIBzz}R0xah4gV#os|N8|(dnZtA~$ zPi(wD9sQzN>3Tusucnl;p;~@mFpHiw^eaOfFZIh5uO!=`|#_4Kro4;3DJcVMw5+1Nu62*c`P8Igtwc zA7*A@f0c4*`NkXPl5m!hYzi*7M1OTBIOoTPkP)!-_3jvdlU0h{Q4a1d>xCK z(rGZL1|m}A`UF3fCfJnVNBX)1(G-0*9JF0C;_5^k4+sOIKl#IcqX|_CNGFx*ucLOwgFeHg03~7$e zvk`Dq=O7sLH3+b0YZ9Vhw(1A7l{p#y=!y1tz>qa&m{So*TG{2B>VP@2S>j~Fah;P5 z2bJB^Y2SJX1cV`-xefwOuN(w9UxNU2G75C!<|Pxmi$Le;UF?VIW)VY9*BpB72F|rr zQythv&h7Hep<}OnBZElQXYwu8e)~Yax$L(v-U=oRmt$=0VN-4_nqy@)VY16-T!sL+Ufb4tElzBwiTvwU;P`ZnIaZCRg? zDV?&uAyabfX_R$a;(G|LO8i^GDg)&Nc&UgF(XEYsY#TUgqbu?Dbm#F?-2Epv(f*C8 ziauAW32BRg*`%dAyT0+@`J%1!X)_}~1J^i(}l_fyX2 zy+PtB9<%5AzcDTYCdqMwaNI+J7z@r%TrgC$G+75f?>PTfe`kG$LXqfsEW2K-sD+-v z0)U<7{t@EiaEKFcC@U9ECw1s|!({MCAss9v9TwZN*NOcLE+2kvPT*qkv3VnOKCbCb z349<22YrHApz6&VlK(`V|6X*hY@o6EYK~kvNi}3{5Okj*S;VGl`rpF1SWQze0Ug$- zv%x8Jx%=o+_rU6)_Jm-?#5%wpDYhj~g~t@=KN!gi)_Km6(_8=Y?o|@&LAE#la<;IQ zPP#Qtx)t4}gOz^;)KGs~`F|hn7tb&MAC1B_l3GrVK>bXh6i)R3^Pk85(4s zQfOeZmMJkP>6py^7&n-**ODS5NsV23)r%=v$|{H2vag}G4AiEP+Vbd$o$L|VE@TvP zyRVwef!@_WAiZUzY&*TN-2RL=MW>m=wGginqU0))9JMeaN%gUD)H+euGd(*sDgsB> z-wc2EG)oN%vinfi-vY3xCi`~|kqn7Lwv2ev56>dKL`mw;kkmW5Ys_6Wk$haOqE);I zSvRijEcvNRJInhv%))kNho!vVujHNUd$=X7J9+04-?8%E2nxTQyzc{vl$Zomt1K4f z-RWy7@`)&)p~ewxFHTfU>XR8y4u8AuSn3zq*IZ9g(^yk zb;oGVc?eVe?=kgr6VP|`L#6V~$$GAQ8-&EHyIV+ztSxy0*O2;dNP;|vtA&y=^Nj4{ z-cx1yz={c$6#oL9(dnLJtghEbUPUN9(LwST8y&c@Og6_O->0O@=D1gSm&(uRNC+wQ z(V&8sjbSrERPb~KLeavF=0q41x|b!CjJZO^ut+fBlZ5^%gj{1GACRyP1Lnv#hXFU^ zjU)M~bRiQSFvRMIpDyDaXa1Ri4Lx$0DaWjw@KBXo=OB4mX^Ts%fI)_L52H8atiO-E zH_Dvg5rtOtL`k z&*uv4+Vx<=l)uK%V5G)P^}X{nt{i#z1<{`)U336e508>%@8QizPMjwXnLmgZD~z9x z3;spDwVDCQ@Ljq{GWKUM!N&R@hhIJm)Z*|Tb{$my;CYY+8^6YBRKWzEIqublkkenbpIMy6$NU2tM% zt!)IgcASiP{vnW}ReptE<35jZcd7_BH~n3md2f-&*hSGU^z!$4MVmR|u>g*wcO8A; znx@QkcdpAwOa>z>9s#By$vm0e`s(cMtKB;v9Hy|f9{j?6NHo@118WW?yVn`PUG6Pr z#_#P@@*Ka2or#{`M<=a)3@9>>zW!PG(Sf*)0QgK!lIIT2KA-B{Cnoj#KGK^p^3w}U3^av&|U84rH^(uR8ruEUou_UiGxcs&<8tTC|F9?~Hry=aUU zxG?>GkCALH^oRu>+!1kuclZrB5K^B2%>G7Pbu(nGL9_%>9&|nrMQv{*?j-L9~YyH<;62@Q52=XWo=K(qs4=Bex?5<65tA zzfWu#vcOYwG(ofuNff+)HGA`d@8EL_yzdi6PO(2@Tl`D#V%f6O{YH2l6|O6vIJE-t*KD&^ld#ThxqWEzV`GLx~@0 zX2LZRwezurf`25umdE*w1wO4`B5upXu1L+CeiJ*FEDA5D-WVKJ5gF;rInqfjC@e$18-S zJT-`sz7RfU(kS*}-4hr6)Z;FUKb8QrO|(FqMWQ~^>#;AzuEpgb;NTmIgIfjeAK$8f zcEt23LB_olMVrXMGN#{#1Nq<~WH)0OAhS0IF2WwkqH1z5)?aqZKQy&VjKb=uS2VHN zf!sua&l0dO4IG2|DpV` z#yZ_Qd^*@a2_-W6;^Rpe34crlTs)5Gh#ClzKcqc!%apCCwNx4$C?NtvDMkV4h=1PXW$A^ zxC`x&SAOAUhZ>8T<3LSv-~#=VDzC{R0o$9zD1MYojKaxJpBRM=PpM*5Do(kGQ8-VRE=Hvr1sP&g209!)JP5lN z8i*F3DB*Ywj6>JNuifktNn(meO!tZj=t=jW)%GSo?kPrLrhBpYkf`TVcGO)OUHFgH zKH$6x-72<}ghsOhCgAQ9Uv|xc@tM5#MQlJBY?b){s-Ydiw-pL5l7M{$8+c`k?=iG0 zxwHYnf9T-Kszygd0)d;>@H%g{bI~{};z|(}*AAxu@a&>*KkTk@}w*&+VH+X~g>)i8zO5~mst@kSf-Q;o4{nXtyeK7O|ND6>XxE`_~g zi?t>Z8MPRr(~Nnk#=RbVco_3@_hzxT^HM!5u~!}QFG{B?UBcU4CYOPr$swU zgD7gu!l|1*+4$;D#?o#ntH1MTM&fV?jaIQ4b%u|&#Svr#x58#S>wu)EUbGGAtte># zB{0B z*X#wChIjVP>^*VHw* zn`r#y)-`ML`X z8d6+mPJ7-Xuzu)o$b=E^5X`nPvPOOh7Kv>To5H%LL-OdpmIw28wQb&R=&*KKyT^dh zg$-^nph3WhRxJ(O)i~ST#7mrA#wntoUgHt_u$+>;4U3{5!k!Ji+Fuma!G-Y!I7@y=yrWhAQZ87y4`nxM zxs5|gnF9Mo>`koDC%AL|-2iTue@bRYlXQdCG8&~WYS2roab2&!5l5am1xA)?Nn@$@ zWDQm|)^aBlPLjhk=EgDTx`Vs>FOXOAF1Q*uc78g!3U>Ey-qDa!~sU>Ki#)a0^`l00cBRkp);(5I`?!3k=UF73~#u*|%L$4o%LvGoJVGrd}5G1k@mw=%%DU3K$9mL|% zo2W@Cl?PE&lsN#MRR?{9M)a3_l61 zl=b30u7^4DF`cAfHNajJ`!2uFdf2U1tbx>ygB5&uzBl+@bU5|s)c{pU@wJCR;$wEG zF?ms6AoKtPT;}&BtqX}6x#4R3IoK+8unCRxU}JWTRsb1qd>cxv9g^jg-=Sx-pY+5Q zsvtgR;k&F*$p$npZkliPkTRE+7anI;xT%v-LBSd{&M`yKaNiO8qOw2VXOwQ5^$t}f zRLt1aP`hZ=DxRdYQwQX@y4R1g<^Nmyu^IGtryn=rn(2Q=Ki21g)c*zjNIJUc$BD@5 zTj~(5k zv_5WObUnU}fSnOdxe%GU@%G)KSaZ_Mf+Lw*4{}A+-HLO+am%nj2Q1BYJK<9L;^fa6 z&#CX;4M=}k)#aa;^ro^Y!QuAF!i>2Ma} zO6Z?OZ}UgXZ#4_tO!he`tPdT~Dy~g{k7wk_Q_%boV(L9tQRj$@%IlcFy3lYHvo|Y0 zxEt_XqVN38=+u#*!>+ML_(j;P>`k5|W7AVdjh%xivvQ-1Ff0FSu*8LPD4#QgHHLb5 z12B;bK$a;#V{5LGJM~oQ%NFtkB+of>bDBI(axXkmf2QFKJ*n_llV4$f9U`#vPI7IH z&U6@0s@q8A9&@Zn3V8v68T-oTx*TxK&S?=+$n(yFnSlhczc)+lu@f+1xz!Fq2)hfA z%EvnvD7|6-4jJIzs+?vz=n2T}j%=^aM(NSJpP1uhZ7<~$n*Bj4CC{X?y(z67g!;P#2m4+=YOBNtPii?GKmSKV{!&TsoEiON0 z+U~{W0Km-3S1BCHX62%oxO~VETU;Jya=Ai(DSZ&2Tj54E?5TVLSw*pe9=!_ypl&75 zQN~MD5`_E|A<>Hgk;=`H&K5@lp+=mfC^0cY9g<+m`e#cjA&D^oS}apakt@4j3Xt5p z)UlcLMhPxu7K!h{8wuJBw|jkE1);}Q<7roRRO2@Isi*ti3%9eL9)>7$@#`|eT>Q`=i3@sq8$(!) zV8Nf5T;Z=zhRrlkiy}8rr)#$kpOBz=!53({xd%`&$rm;;e z!Yh)ZiS- zJWAPfMkz8!NizBAqJ-(iwN81vPoMCu({oEB_7WiX(cbb;WbW$|XNuAIYKzL<`812n z9cK~vjg+qa(GHXi^RjoGK4}EBOZidkb6&LIDl@+qWzk?=)pCF5pWX1`J~?&(JUhxk zDy1F(^?3uZk8x{x9TBSgdy1Bst8SOdib##J&!9RwA3R*<==qC>qelGAND5~cprPSp zqGew)5wEl0)^Z`YJIm`VmUXn)zkH9aTjdc2xK#3&N^oW$J7rj*&@WZa!^(M*HPrcr zl(4^rar_Vm3fPg)tV@*4UKz{JEc2@)B7nM?8LE$BP+qLwmjZ>-Dr{%5TLBha)=8@e zfQ(w5s!A2YEL#{vn4{IXYst~-ucD_gOqSFvzZ~a*ji;oBgH}I%0FrR5RDLbOWgAQz zY>gyx+^Zv@(Aqv@zXZ1*!qrD9S4m`*PdLSRE{EAE#f}9=m*qtgN3l0BITX93uk$$I z3`CigXESdo_UIXKNlj(0Lk)6W$>dV8-$Wlm1YGP*s*f1R3QBvXQtLa=EmC1r#S&~l z2rl!m)w*N}cw6q@DTdmd z2u!((&J!ADid=6vSK`4P>f+i|MD zt580%0DIujRilF*K#ASSvZGMW{QR7+&}>m}IlS2h-SuGXyQR$lQu9X#ly}x3>7o4{ zpk9Cukf8E=bfOFBI{fC`8WiyxwgvLGCOc}VseDH`d{Rk!^=hl3d z(4{`|1{`sA<6epsdhHQ>uO7$^Anh>m$LbgISsb|@%B5rf^z~EZUO4ZPN!}%Qd#mPo zt0sGmRPYfp$j@=O#N8gzPkVI|B>8Ukuk3w3EdRV6P49$*GsV3s{8NUP@0OukW{SIU zJB-h`+b8Dv#AKf_DV66M=B0|ssm7!<ETg6TajJfvB&{V}eJXiQxV=(^$m-J>zWf zq^$}8jO>vv9n7W>`5}=MJDvUFg?HhVGdgNi&gh^_*#wa1IP{=hy7?FWKla`P zKFaD|AActa5HXUVptz3;3WAVHLLg{0fg}(OArLkfoD7)>8A&p6mXN66Xh0apw5fHg zXp61hTCdjBT51EGmi*BEYfMG9 z{V7hF4KZW+Daef8^CrQCAI1Gr3_Xb01CwJ$@t=W#TvE1w=kP}0bU8&5(<6)E{v52s z?Zr%irG5Q_M~kp9XMTs|j1smbc+&;O>&WUO7v`wxVwn1`45xA{l3kEm;Mdw%)XyWH zoOa2tNlqBs_Yf>FV4jL&r}*wnBy%k&)u7l4$P)PptuSn^zf$C}=prKN?_Dja`rYv( z?+iGEO(iBq-e~ElKt_>yWMOp<{Ui@(GzsOHn+M2}zkyFA;Z!ILzeXh#CMm{`p}1d& z_Qb(*^Zaz|8wZA=Q52^4kHfV%pA8M16h5r2HQm5H^7GTM=RcD4kcM0dL*SGC5zC&y zxPa@F3vhd-|C4axC~Vg7dmB!rHy5V2?H(%L5p}VLF!v7;_hEZ<54NNmQOCIc1@geJ z*~Rxhs{JoZuf;9OwV{F9af1+AbSF}#huEdr$dDv!6|tfXr{bV6n!7M?tPZuyNspN3 z4Pa`5cK7s94uZ1NtPTB=vuA9ft2sbO&X#9ose6b+Vow6w>f2|@m5Qi=(e?8WKgFkn z=&i5~h1+sgA_<{K)5vjk#&)r+M$};?mdVFs*B&*L-&s5iTfTRY!UFCzSog8|36dH+ z`C;EEj3D`2{*hAfN$CB|nJ=O#vb#ecBu3%hG025=T`k8JeBraM>sm7sABacF8Q_y7 zyqn?8o;c(^py%wV9Bj9>ZObCv;@$L5o`}%V;r0w5uHJDSYdSlkciF9MOAifP^CT;Z zT1R!X|MC(Byna=k&Uw+nE~RgFupN3G#XDZM>%FNr;jCgCexwav#eSJ61tI!``(>*; z+Sidc1HT!bW#YoYt3fWhT=A{0AlY6LWPU}j9E$IQZ{VCty>E;3@}jP{FYA#TWICvm zPDet}{d|CqRp;ldYMGzyB65fj$0Do?jovO$t7sy>qf*qyPl)M+Cm{Yx=w&-=XM5;y ze%Q>exLwNSP-4TH80yV}d3HOcGoV|(_Q4}X9MapbeTQCExBMCCxj81N5bHZ= z#`9S`AwH6_1A5;SH2PkEM%D*a&Y5c;KqAa#ow;r!Y?$SOGkpI*`o0SN>=L;K+JVt2 zy5bRCE9kevR(*&qb7?g$x{4N2yOj0{!tZl%iWG@+G^Ui{T|rpslf#0bq(}fu@^`D43)GX_fN=Q4{N2`(u7)8Dcw)-B!=QC=NA-t7-*8f)I zf811I0SV<0emNj(&@*@@>^D8ntb;Nx7Q^YB^xAdL;C)Nm$(JCKg_*yi=&!&m%#F7T zF`}dlwR371&Q=YdjS}2{I}+K9SDW|}XpHoZ54ofBpeLdgv2B$DaZ55IMMeDe_=Jl1 z+cuK()j}~_hn$hJt2AvnT?TLAwyQxXDq^7^bV85s6FZoIh`6i0Y&OYxX*8?QhA-MP6bqd^*RK&wjK}{8LIN~e^{`T1{O(B@0rk}%Ei1V+LG5JvQ zuVI<%zH33U9_2XBZ`DgOCTx>$!SLlEUb3N#+0m=Fi>BEaTOO9lgM;UVVBU`zM;lhqJ|m&^Ja- z$$s8{jMy%S&ez2J>;}%yI9#1AV&Ffg9XnBaem0Ktv-d-<1%x1N^Z1&*&wVZ&2V4hPR z39>yHTmm~W9;&%Rq#HW!M7B^d!xQd$&T=hwElk}|8<^=?nkb@BxEeNzv$SWi^b6lC zNUpsAEj>C*n{t?l17>L}V6VHRg=B1+rF{(ljQv>H>sea9pwY9mr&%BNW0od3qaWE# zj@$Z8v$P!8M0+%y;u9Ei)e1!}?P-?w;VF?ULmzs)@Fq+4b5XK!v$TJZT+Y&tU{nw# z7oPfkl9-=G##ihwiRH1as}^fujI3Mn*)K*`h+*G_q1QxoKq0g17MclR@}(jjTVy z2C5oaeOAEre_DXN6jipG9j9D)%t2q%JNr1eCmC5EM8hyu=}xdwBkOnmoAbrQDc--) z2-?@L#3Uy&vaX+pRW8EC6mLE3bv14$GtqBkO%&AFYRaigy!iV@6iK zA1P!SMVi#e+Q_Iyrg*o|&-&v<{>P219umrt_1l1~et*MLjvsP-ZQEs%53&s6Nw8Cf z7+d7cBHXY-H#{HT+^_3u|MpDeJ8D*Rvp83p&djxDVPyh$l$-SPF&_4F^?x7G@e)09P?PYA;9+A0u z;YouKaUZZ;5c++4+6Hmc5qDM5Z`}0YB7Ke6=l&Gct#`fE(|G3TjHCAmIN^*IL?RG%v0jpwN@2I7n% zvcJRfG@r-%^J0_#-zxt{Mf@M1#J?&}zR8%&Q{a^FE#H5j353-f6;!O3V3hZF_io1g z0bd_ra|W`hMwxeJDiHvq{1AfHWgiz`ao->0E#ci1rAUblS|!~5ZIn1V43@}h9L?+H z+p%KP6+d!Q8m(oW111bFBIq>rfmlFIs4f166r_%hx{a5sg;3EK-6_?;o%nJ;}PbtkUeeN>~sTfknNO@ zF5U?I^-c6fI8Zi*^C?xIZGS=sE+2{}Hm$z|cTVf3Z)e(& zQ~q4;!$xxHPdoRNOII>p$fdW?&$DokfjRnqN|ooL^md$UFBw4BQn1C}z-!^hKwu(T zsllH*j7Av*>Xs z*tQoK-L5sq_B{mvI=-F?^c3JTgBzV_py%=sQWcXW;-)MYV+?s~+JQ^PhJRw#Pct6ZIr1$-hIcB<#IlMHz0K(Vir@tmVQ&t-9`NOW^|1a)_!Pl+MtCObU*@_hcBZ(aEDO?RLf!qN z`QppcKSEf+JVd%FQ7_T>==s74>@Op447RYQO}`8l_jQeCi_{x&79Y%`^Y z)qIU!ui}g9g3q{QeKrg^E2v|7$@L?Fi5t9$YOpc(J%)%ydS zzzy8a4-s}2yzM^+eAc~;0Q_e$dm#5^I~p{Oyo-EiKRIe_Z>waUg%7!WM~I9WRsgOk zh%9{U0CR`Qx5?zH9jY5k22uMt}M7VI;OD5AOKjMl6z#4^O?8 zI6jPgi#2Zl$A_E2eQ)E#mbdqmOBXX<$fZZ|R*d7rCwRt<59+=Wj(YgebiXhWZTo(8%n z9_v1CaksC2k3mJ-pBjJ@!pl+N&6a1d#YwQ(@P?D(a}nOhD!h3J?+NVO+}FR#Hu%XO zj{QU@%M>2Z3MS#U6_X8>zCBRfP6`>`pecP%;0v_-LZ7s4|6*Gyu8&12@!h3ppJ1f= zHtte z{(XQDnVwmLd!l%j6kmw^)9JYY`L|7^=LAS+Mbtzxuv}8fXv1E2(qy!NS7iMn`j_%v zRv&Dxj|uMJ~y}D`d{pSj{B(A8!x=>jdxPy0@759fe?`}fX)4w<)tOM7^N zuse%(8SUW`VXAAi=+p2af}Pc{9;JM+l*tUA0{`IonpGH5OTa(bJP z2Rc1`%S^K0N_n7ZkO!Iu36mlYS27OBz@Oq7zV6&;95B)`j_Xt$e}bou154#lx`nl7}^oy{6CY)o^&#;;PXxM$<0^V!*cJ}Wk`KY(%Gb#!Bacd5P zQ~BYK=Eq9L31NO8&+z)m(Kz9AaM}k{oNrZh58$cu#ay4F-y4O4_ms+nV@Yl0*`8s- z50=z<0Af9ETHl6)&59gLWGjnc2jBl8=%Kv!!F4bH8qk0Q&d*XHnz__! z37piv*gCWSco1iW|@Jv1a#G%2+85thxzMcL{8`C<-+ZmwTJ26vEc$Ady3o`3++30qK!GdHI|$p4U;;&%1f zW5Y|vx39{^%FxmsS~AM=isdE5EChL^_Aw#EugU_kpasvi&&A%$3z%<@z`5y~`tHy_y^;$j*tx6BsGeYw)ci)A?W`>qvMv$=qMFw%KkYX_m zYf*epC04}ej2*1Z(@T2x&|Qdb?-pqN_<)<^GwKJbSRlRNgUp*|W@N5C6FC}L|3Ugp zuodUe*NtL67h$&w;*XERcEUM99833~*q;|WzCzv%9M7a}e8G07)#gO;b@? z|9S9&$8`9GMXcvJY2lGzp2YVM5Mz&OIKFj}r=*j#4`wLJqF=7f(+vs3*;AP&A_Omv1&tj`~`?UL(@OF6Me^;hqq4g=rd>Ruyr?M{?r zDDWz;^AmL`JT$x%mmuVhLGyZ~6ON}9=ca|;Z`*ARbq7-0(`Mj1@AkZ7!^Ovz^9qC^ z5M9&1NUZGwJFu?g3}VI*45Qq8eigHfbHSd?4)!O&o^vLB`)#z8qIuUWLnZ=DrDtc_o%8kd=|4E?gMZ%kBXiDORR$YdD4Xp=G3m zi&L`No*tswd+!C{trC7TAj%0W2j^!O><9$b4X&Amj5z^`5$~bo<%+$3Plc#|ND2-N zX)ozR*N^Su5#h3Ian@Ak_uxwfy92YBf`5ZHyc(~nvL?I;cBAlOg5PU%R|&yXW`hpf zXBfCM5JL!{>bJJzHUeVY57>WH#6Vs@2QM6YR=Z7DM8fV)*f9^vkTa3~N6*(G^g_tP znv;!*Lg1v2x1te#c#uWalHR3+=meAI|Yv^q&($P0spgsc+7~9_IX`d(VgPyySmqC~G!oRo)dbGO2 zT;E_`(rbl_5IcQ%Xi*O@F2_tba9J29X1cqDuupK z=u3ruiO{Qs?i6~R(CdZXBy_*fTZDd<(1Su>EA$OQzd`67LcdAqw+a0Yp>GoU-9o=t z==Te~Q|J#1{Sl%6PUu}ie^TgA3;lVacMJVhq3;m-n?mmq`c9$u3VoN*2Za7lq3;&@ zzl3fSF*nkLo-XtZp=Swwl+ecr{RE*~g+5m3|Ki6#+kB|4Revyi?qL?uKch^{5#VYIrZi9W*utM2e& zK)eFAZZ^^1h}IFkN%REK%S1gyPZL=&r1U*TG>hnAqFSQ+i0&lXMD$ytTZmpKx`F6D zqHBq=aO|tEh3HJ8MxvQSP9i(eMMPH;RTAAwR7&&!(K$q0h;oQ_5RE7LJJCr*7A#Zx zMiCuHG@NJ>5kIP_JD2EV9ABxcAlgO5lTv+uCR$0fgXjvP7l=YcPZDh+`VG;qh&qX$ zBKj|)mx*{cMO_ckjYR(-+CVfEXK?%05RE4C6OARhjHrO9n&<+e#Y9e`av~qmOrmRv zrW1XaXfn}VL}Q75M|2#~>qJ>Z9}x{D%EDZv?_W6oQa6$41EM)Zy+kXB-X;nWy-IXD z(X&MN5p@wgPPCcm4Wj#rdWn8S^a&Bq*wh_{&9A<117SwGvD-+kn2)C8gE|V$z<3hs z6ex<6G5!vf2Q`Li8OE^{|TPrH@NW*BlWmy;PasFq8(o+&m-VZ zy59*@2t}p_H_{wX;wRm6fEPi1mv-x+#0C=$gBza+8mUEu*Hhz<0I&az3(4&_P~2yr z{6GVVG_VzK)X=~;>8tP*zrl?YQqLgTCCw7pVBoD72KUFlrCkO$j!r!S)!0CDG58wV zLK4OW_9#YSKL*cz+B0uTL5R(D{# zymU$Y>GOJJbOWOCaE!xeanpX|T#fw?crY%yMdI*Wk6!Hw6pp-z38LK~Lo zB8>e;4HWy!&&ls$C>B;KUEWfLLAr1$Qlwqx!@!(4o@Bp<;aKf500UXCgo~($%znY` zdZdUg<_CBh_dq)xPZ8*IFtBe~MQ#Hyupo!gFdWIFLAaa(L&OgcyfIH(N!FyuM$&M- zG6h)8g$zfyR4c=Lx?G_QBBCA2a3NjpQ-;+vbSs08hIh?= zK87I#OYuYI;5WGO#%oXx-w~!c!U`He8x$AlMk?Gk^C%=4~+#WTsoA?PP*Ku41&RC7^cEf{37k~RBc0W7t~XKlmOG$IXy7lx_e^QV5D#!JR0}QYpduj(T86@u{1VErL*+tkf)ai3 zI0F6#H!e%PnBXY}$sYk5{`ZkAV+RZu(3Zc`V8bEnM!K*E%AqZP9_6x;E+J@4mG}*A z`~<}$#)=>75D1vBzoNxM&`Kq(VeD2ehmp@PXlzvCR|*6DETPLHXzaqouU@%)k1kh2 zi{wyD9r-&05oEZYAI^7vAVnOYd`` zaWoS@*;g_2pF(|)?k_^U1|@!`a0-=`LBOoLgceJnmeCu3ly|{!IDQx}Kr@XSkv^P0 z#E*bE(#&*oRA(--p&LC=bXiNoUEsqGYYlS7_yr8CmK$hz2Zk!`G6VT*h2d7ZFz1tNupbqZa&U|>%y{Ja4J1Dr*de1t)=c{J3)a5A2PjH^wO)zW1b3}o%4 z;b}xJ!tGBmSYdesUCu=I(9dl&+yDdp{D6kLU?_~Hg>%j#ShKOMh7yzg6A1V-l`%(O z@grab{S{(joB;z%;CD1|d}Y}zCFx>l0VGiT4j!NIHAbqe>g+PbkAMTsACUo;|Ayhe zl!L*!6l+e&FlekK%-{|@jc-G1!&CgY-Hm@^C-a95tD6bn?{Bc7%ir;|^h3K&SVNN( zk$y8Wf)g+gmXWXkik+zV4Q~APH9=II&B802lK2tO!yrw6fnw&DF*_%NkS;T6sE2{M zegO>}ZdjlW8a{=g2+sx@Sk)sf%K-xm=f`*&>!FeLDb;oa4EsJr$hZ=UVgHPV*Ps|S2W#VFsI#HA&|rfW$)5@s820saX@thG#l(U( z55ORPgB#xsqMp`$2PTHcY!$Vb;eA5G$xVr@Hh;NV>u0+1~875G!(*6 zgeMmk#x*dUhNt+k2pGq|;b}Yzjd83d8Es7EA@d{z2Zkr6D~|y%JkD3e`j+8+L_+~I z<_VXqh98DVo_rSuhR4=s{2Us?OD7p^OnDORE2h9v{0JC$HBGaiXmHXn59$g6{>=T% zm-qXlAjPD)&j6MI*W!U0Lrxsm$H$XzX%3)22MQ1jOZ{t#gDTtjxRnuEtKw)u)bCMP|eDN zL2v}rUun?>XS?O}lax}QSjm7c#r_oyB@mothfkvlwye&K45wY_In*4OKO^77H zT2<%px}4T>_wrcpITMUhcfBjtG8dLIf!5MMV@+b9d5jU_TI;BZ^E#C-&5nAv(;B5f zT=FLvi+nDxb(W{G*1f`7?Do1u4uVQjgJ#+UV@`uJHY(F67))+iqucKW*DH_)P!`1H zNRz`~XRYxB>Ydg`P%n2`>pe9NzaX|Dhg7J0B|~nNdsbNYN`u^5)aY1_{PKIOtGsT% zOVWE?E8IT6w-s@-A@hownyl`|T936sRsa~>erv4*8O`Y1boQaBtqWYrA97CSkfX82 zMM9>T)X2Ibq^b_N=K$kX4xiOg?{ztxt=4)6il@%qxPo-ZzABgB50h_C0V6jTFR=Pr zeSTMi)mIk~)K;fwRU;W7R~LFjq+6|iSud@g<(HwLd~nV|KC&oK5xoq=+U!MvHX~NG zsHDqLjaPU@rDP;Qj{IC$=dyZTmj_%3&xuUXHOB3Op~lmIymm7)SGiGqNFa)^p~>TO zqiIF2~H-qEPY2aGFlf>!0)bi`&*fF^=?!Nv>%Zelu{)A zB4R8Hmuzpg928Ko*Uhw*szS?QLsNFlg$o)*rsc4a&6!&)Ds99LQ8SU2dmK)ddrme2 zRrW}S-`(J{BL1F$-|DHgI#FFogP_Szm$19h8t}QS%aMX;9ndKuJ*rKytJ#fq2wqHn z4VuYvudMtzY(CpO_4<@kY}ntDyy7jt@1PJaZHefCX!jvdJ#v5 zEH%;14ftIx@vM-eCX#3@kaH%!wX&cQV|S#lv5wD^sfpCeC{?W+6|{J%&1OZ<>Rg51 zmDEU?i6`qmIy%uDQN9>3thH`$gCGtx$r8`YMp8|FBB9H^-WRB;ak)@`WMQyq>K(1I z9ZDW6Rv895{SBl-ayxE6J;RM z_o-Hm1}nOAk|P;$j2k`ZEHGF)&18sb9GS{f$tr-F%Nkl!=c-xBPKo_#oCg)CAAQww zj3o?QwHi}gO+>y144r}uMIOg1nj~ht^&$?CWQcYXN7>}{ps#B1MSCk0phFOI;EK)D zy%3}6>_0KOh#JENFq6iR_KbEYWC5oyeoYgGo?wr#SXY zF#X{uo5%yxpEAsT7+2ZbCX$F*Pog!ZADA<@&XbdlME44h97{?)-kFgJ2ZBpR>8}bj zHF>-k(3W6&5$$0UX&KR3YSuNgm6NbU8Z`q$Smk=ol}Ln4FVd5bg`P!n>H#mlL{d=) zFy}~g(Q~*xWS^Ws*ppv4n^l%B<3D5 z`D>z{C+8S@i1=bxqtoN9YI4=MYuz<=IV>#ns7zhxky8#;U1EZW^NFGqUAi4j&p!`y z4>?cWFE2V&CJ2iQ*`cA#y#D?2j&4NEOQgU3@*+uPiB&n!VYJTT4CPDsMc+2lz2eJx zsN&3Jzr5%iVX1KvvtOQ=^9!($)b(Sr%j-k?+b_R5z$(-ScA4lD9Q$7a+V^ai|DbrT zaJB4T(d*EPoK8&4eG43oD`NYrJ=Id}QOsgua!5>t>_SgEWvQqt3b4A>yBt1OrN>im zpin(Eh8sm?ELvDPy~^*!n$~c79oTd-Dyn8;qJwd@qDnbnX94aU#iGc{5aTi+0&6zQ7?u>C&lgEwA&JUQJls#ySaX#x=R)cCXmk-TeLq3`iCEw&`FP}z@ zm~R+r&1;%Ta>eOwa5uWFSS2zQ*bPw|DYcl4G0MYDu4PgO8dOUB?}gm6_*gtnpaU;HrrlV zv~UiMTo(SPxf$6$LDUrViK`Nj(B~Myy4b_tR{g*cMZ$l7r^e%3T{O-IoybW%tdCH-g&ts z0ADMyNQU3#sHgzgv+}u6zn$0xsIO(ia#)iy6fxFLdyM%EF3i1Fr+bAPn{Ls9WODbz zbDgUNdrdWN3>%V%iA6cv**NSY%<|L+8X5r&tJOHuicLconlLx<&>pc1GI_Y+@S#Wd zTQBorC0;8wM$lVX&xdiw3{e+n%s`idIRh*C_z5$>Q$Xx=u)?DP!?)Pgn_?_%MG5M? zDNiFN7jn}NnW)M#o;A7({P7!gD)D>;c_B^KilYrHH7*`Hw3uNHAn z$e9ScqDE(>*H!CoiQ|h7djPRFk0N;1*xT`{cHtu^cyU@;K)Tqry>PFei+& zu=3=<+G?C-b4@J3&xqJ)3qQNXTG1~KH)dGH`yQ=TRQYr5cI<^Ocla>9<*q)W4;|Yb zWi=I5aAI#_$No54Xjx533G50~MtZ!oDB&xz{rTZ@gsT-@5SYKKg$_;ougGJoE8y7B z#2zi4w{*AVs0p{2otSBqdp1_}?wSNw&NgDw>-nnb)%>Q){FCfZqrObu;mw_R6FL-6 z9+04UIuu`wx{TEMP_(iP!HL{)Mhfx#IfeL`1*ggQ_Oy}~!)Ptd)i{OKn_)33@dEUm zBP>Q?HeUYX*>#R#T!m-Tw{SuU&)|7@wTWkCFxfIXh$@$A5}5YOr|oW{X3>wKK# z!?Opc?RMeWITx>C@s6?@XQbZ5vtuE`#re_dYP`tDGq?hDcy_vRdT6A@uzC=WBk^oP zJn-Cv*N{7pg1=V82j5i(@%Hv!JPWTej92mO#?!zTcpcXo#w0we*MSe7SsM@z4iI&J z+b}laS=oVf;>j~!>Br!C6Y>Jjj_#v4u9`vmYh!LS5RGE%xvGKL0E2JI<^ zVLc6pm&PMN)T_!|ggq7IIUUcljg*daz!UYyiaNvk(NTi5mV`HpM!i`A zyQScB5%Opm%ueudAx@|hO{fnB>cT((d{!Bjt`>yT3ce`+t~D^P1>X&Zr32-ebvy9w zi2LoxmW{}ZjqvkB@Y`gh4Qw(}o9;4FI`2Yy?>15k?=ezXw!xnm7VEu6O7^`*n)Rm$ z?|%5hse&Gy>bE|OGTIE9-y#l=8J5b&jI`imMrs$H#^VU{aU&(G%Si3$f_aN!F}5NN zTfy&X#P@0B)pN-A=Z%zs=i&Au!gvvJc+s%*ylkXpzk;-*ZW#Y-q*cBKKd2v@c0j#h zSkPYQ!v$~MMY|cULaOQ_vN79$;Y1{Hs^EJiQv^YHA#lfNL2N?i|i z6Vwl&?uB{?>UU7vpt_-c5498OA5goYQifZM45*`_tWak{oUKZ3d+YBN+9)U!~pLcI+Y|LcX_2T=cl8j2H0Sy0D8jfI*FH63auR5{dQ zsA{Oop!`s4pf*6=2z3Y4e?fIZ{RZkus28AiK>ZnN7u3g42Kv0=P@|wuf*KE%19c8m zDO4rYMNm$tMyM93YoTs{x&>+z)O}D7Lp=udG}OybZ$fpV&a*$%za1za>r<$|P#sV_ zp<&f!rHM>WG#&9UFylc zmOt|AHt`ddhqOaEa3}{3<-nmFIFtj2a^O%79Lj-1IdCWk4&}htm;-;wu^30@T8!hN zJ_7z6il0#)4mB2P2Gsdb!w`oosFA?@#hZoYA?;8O9Lj-1IdCWk4&}h195|E%hjQRh z4jjsXLpg9L2M*=Hp&a;+%z=@oWHhBODOy-mJ+`=d>db{jP1dTJOD<>{wGeg-W-cg! zX>L<`)yxI6n$qx>KL1qXqM1z@^N+N?{Oz>hMJY|GO*~O>RH5B|kv@EsV?KPezbB81 zZ6(dd{L9lj%$#zg$H4Y@0IZ}q8$N>%ryYP#h8f(Acg5moNydRkvi22r_ksA_TiDU# zTL^lO$G1xIe65W&OhR!?%=gpxR5w_=N)}vzBXs%vV87l~Vgz?3&yD@%8K|xItYVZ- zIFKmi<5(+_TT)r$HiDFeEPk=MyPq-1Z}F|bv3toX>wqHD;%f?!!v%~@#(}UX@YQ)% zK?*^uD5c({37T5t#}QqeT+DGhk^ehBjY;*wGTo~7t1W;*Fs&;^rZ>Uw-s>{_-fccF@rUGcrwl~^x>|ZKlWG6wf$}%q1hK%e1@k-Wo7bfSl z_bivOQr*XaaYz;yr=t=r@DW_{DHFR%7r~$`17|(l<1O+1L89HN1UvhRmKHlsh~ro+ zBpUcz?akRJV~DkuL3NBm|7{naP}pngR@zqt@R6Jmci8c@&!+QZv5a@p$c+e7Nj2__PAw#Fj6&m6Xs8Uv7C;+2vt- zJ1Viqi_s2T7RGY1+36ie*kvu)Z#GL~*r;K-Ab^Na*pI(tK}A)zU5pe6^O6|i>28lt z#5o@WAI5VTuWCu7&Y2(3)NCrg2l2T|8XA~R=U3;KZ$~E&fdm*>1Xw7S5}&E95VIae@~VTt5n?Lv)lo@?AaI-pj+CcUA~JHrLEu=>6!6udLDsA+5#@cuLEt&dhWUEcR6C2N;~?^D zXaL(h!S<$uz*a2g5XIXL0xw5ZG|6|w^4qT|G1e52`_{^wtID-6XU=Up05-)rvOm51 z0Q`D=B@3Jk_}-+RIcV;Ai5VMza=HJ&x#)uFJOCCt2Of^~8=al(b*(x}<=-O*hK%%Q|hrmsd^qf0C8bBA=p zs!M*(jV}sCTz3h3th5|<{iUHjx-J9Lfhd9ap4JWlZ8dca?w?T?3|LY7-BJ5mugew7 z?q5+yG3&QGYQzVlWEf0gpD*Gf-Sp@3a9bO7Q^i3a8=|(Nh-i013Rf448dqVdU|-;m5UfxI;PwobG0)JC`<_lud&N z-!coEyJ_RBuc`OogKkjVE6x1ip2qv7(bp=*k4~CuBeV|-V=aV%iR^tu80mBDqKdMm z5Zoj}_?@uEo`WyOx=UE|J9LKgq%w&(JS_}9mun@Ro);#+3*TYF)GbUxN@5JVS80zK zBE$udY=<&7xdr<-m677{Jhe_oD`|RYDRzixO`DyxX>iokaXu_X9Msp+p;tNx2@5dp z5=K`;O#>EtsBzlZB>4VQ85m_ia9N#dQ);|bV1zTAjNH@ z@HIAJedrgtc89Qtnl}kE1oMq8tC&|@lAlLkcS}oeEej#0NbglHSe20Qeqn6&)%Zn4 z=%lgP9NfdHqYLf$2)f4J;9EfnBJhQu#cm8SQWh^TMq<%ze3W9O+3_)^BUYL!1pLo3 z2~susQq_>{3@kNEUqDl3UX}3ceTc!Qc{hMMfgq;j3VLu-r|G&>{O$3 zk&$ZjTnw%I62nN1a8@E$@NqV(|Bq9^4Bu9B!T@pIDuzm^2zrnQ5W=QqWJIm|QfOV( z2(YTPVL8N#yq;3hxT4=j#>ea6bAVq_KbLlZtNEAG($YFUN;A^Zf}c?Dh8|7LJwpyW zHTU2%(*sP+_lF)}YJNC0Eo}#GXh=)D_d4pkp`)T%J1xN>O_haB1K2YyEG(?7tgP-z z?@I5qbXq!6gO;9@ZcA61)tZ%MwOTi&3|Oq4X_cLp?$qwo&ci!Xx{nMF85q)$g56q6 zb!XbZ@L)>th=CykmQ5)=!@5#CEM1oFA)Q0IjtHi9rUuhG4j(w8Go`6BrNh!;2|{%b z3#Q7yDC$h@P77uRE!lQY?6Ux7j7C_SsAo+r{K?mVEHMyLCr~k-&s%^ z<1<^MHq~PM`1&PFcv^HaG=3ZYSKzSMJ(tQCVdxZcxMRdiT6d%t2-W0^u+t3F9gjt z9e)#jr71odGd>-l;Y~!053%O2X&8TvN#6sScNIOcrst=(#H1%qO_f&Uc z423E0pa9qkTK+CH;eZL>PWnuI-;eK0I~9Htc)P+qz<*SDCvbY2q#poge4NzqLzE-! zF&8vWVGFtHz-*hN-^`4(O-w$Gt*~dF5dR5yt)eHpu~5}e#7wWo$->G<-{=G#e=cB# zwa(lRfd3P)7x@qT32=N^g=x{SG-g?JPs6P&5K2M6#EcK)rfC>A;%3k=4|gL^Iu&jy z-gEx^88l8t7{4QNusuG1vhdOK6|iTx#J2#imE@5)bi&N|Fb*0!X@Q@)EIx!^9oA|1 z2$*3VZ7K`O#8?M=hDCe}aC}%l22ULp@h;Guo+f2!&^}qXUw}r3JNYmf?x-s&BXxi> zIBtMF!zF$jI6mACxan{;X1Va@Dcf-Amv}vJyx$P{gFynDm99`5#43tm#qw5qgc2rRA^i>jW)-qesZJ)YYCDsaKWY z8Gt?WkoX6{YbALkEGx_mH$E**p#M<$B|ZyndVl?PfIbL%hD)r|wWqK;LGz%ZC)V^3 z^Ad?0@q3_QSyMhu3Nn(IGHOOEOgS~@gIPhn0c#lvT|&NUme!nzzoaWKXjGiY9$pG@rWZ6 z!?K#f(s(k$?E(EV(6cOv8K1FG*`{`8 zH)yIe8jJW>Lsk>$Mf`#19h>MEI}(vNYfQhDHJJZ^o_>jSJhK3ZE1+pC!g9iVoC*tA z(;FuK#9x4h^^LNsvW}OS@~Tc%m@=#K6sFv&QiUnI>OzGnzl!{w)bIn_NIR_u4T2ZH zJAhdy&2x$BT3nS0dyyx=BTq=olP>rsYo<|SrqQ|r^C-~MFEMGxLRCW%lU`%e2SM|u zq9@k$x?PiAW71O=*U%Fse_~DFWU8MUlb$lWPE+*6nx24|{52NzO@{FuO%JT;gF~bA z8k2rgGcHe4^u(H8*Aw#BnDmqt_9sP89HE!d5b+sMnDmq>cEm|Cy~LW{3P4Q$8k2t0 zmAJS{(G!z~`QMWorPo;SzZw_lY5u^Pz6*eu{52+h;WfB>OVJap!uk4+0P~{u+~>vfmy)MbZ<$46Ne= zXOUN(0L1jGG5u0rT<)pTFEOoH*75xb?FIc!xa?2U1K$N4A6AE{9cfIzltp*cX)-Kg z9Tw!bMdGG0>4TeaWuu}eeiS%9tZdMcPX#oM>6db)vXKzxAu%2zT}^lrlU`%eTYrQ# zjG`yj^qOZpf6CE&LeUdzdSriuzsBTGnN}x{lkp+m7d>TS`4l~|rVpCm-V=! zC)V^j4vfFXq^FFyqfVFcA=dQWsS=Z3W71dt6!$-dScRy zh0-+f^p*ExywLoC_eJ0R0B-O+L&l$YU-Xo7c&DN#*7Q1!jE}~Qzx5Y}@qwZz*7QLD z;`sP)dKmiy<7Iq^_eF2rj9VWSJ@LNiH~k9p6U`rZU-Z^rW1nY&j1RG<*KMEi*O=+; z{*7V$NYN8(`pOiENv|>KDKGMrGZlYeO&=Tsn?!jzYpt1x9|mMToSnHMTd*_rhUQ-0>v z3R8yWjhf~di*b*_l%@HI!jz}^oWhi)`L@E8r}=@xl&Lv%l8hVWY90q{MZMwAWx|~% z{J9A`&Wh6C56tz#*uAU~9tVw6vN!$#%=y?croEj_PvTPQ$*O(=KLET|(MQS-W@46g zP+?KlPhtKxMU^$Mrq4FfYfSn|&`ePD#G1a)M6WUFJ3v#U=!rGG)kLo`={rHQOwkjE zf#cI+q(#%BvGDs0`WfvPI1&~BaRoH1!ldth7I$_cabhe6J{LGXtWHxrHKt$6$^4n} zOAIT~2Ns&>H70!*XtpYP;(gH@&*R2dMNhmhddhHpSJ4w|`fO95uQB5TnV!b6Hko!} zOP_-tK80lJzp=faJ)y5$m{ZG9+eL z8Z)d;&>XMmi8XzeiC$yUcY$V#q9@k$9VU8>NniO2mh+09SkqUV=rtDc0nG|UPkE`D zzS2|{8k6359ha0Udg2JZiGQWSB0iwmsN-Xzx0>iRCVdlVHY<8!&0o`0z(QlvcYx+) zMNhmh`cBZiqv(l02aYf6E>oM;Sj6p3+}fS1>LIWWtI#wyX-s;`APy>eVoe`3(Q8cl z>^~XC&5E8_)AyL-qcQ0z)A%t(Pps)R&k9&*O!|&qtVa|*v8LDMMS6`%-vgQt6g{z~ z&o-5v#-z{cgG|pn)fRv?eW8h7W71cGW|^WV-WPobXs%TB#G1at#9w3bx4w({sG=v< z^jRi)jY*#knj@#m_!IAoz7RBdik`RUG=EX_#QUPR_G4bB=!rFblZn5^c3+z0)lBd-VtkhJ@+GjjY;469&Q^iko3fw9@9O6Nv|>Ky9Q7O zGbBB+rU#7BYb^M`k6Y2tR{ViAJpnQKYb@wLfOzP06g{w}?>6x#zTjJOZbn(>mnuwo z=a(x?ndfU2rrh&e6{hU-`xK`9^T!mX4D^>3rX2LYDNI@DpD9dv=p)XR;Zi30sR~mr zdcMMxjeb7yP}HRvkUtG_p=PrQb=c2(6F;*7JG9s=9j&Hx+;7islUyWJ5l^@}zdgYgx zG-IKIyuH6}gfL%*Wvi8XzPiC$yDe>e7*X3F?b*0iP%n&>qqJ!Mb(6g{z~*E}m=p)u(x zQ+m6iC)V`YCjJ_ep7N(NXUX^wYx+VHy~ZLwpBcsyMQ;FWdaG&9qcQ0z&-%BDo>ddj;#rC7#?cwh9Ci+#DGC)V^q6Mv1#pYpS}D0*T|UkN~50Zn7lcMPKbmB{!I zlZN$2)5O#FfZ`HGPps*?;fI*?8k0ZoOxUXEi8Xx?fSB|elb&}goK`C1LwqanTF~)F zdd7`_n0_@De$ya_Z?^Iatm$=mk)C(~Xt>_z-40HLdB4Ldg?YzASYh7t@IzoLg5vL8 z6SmEX+FxbD+fDeavM5c92|sSajHm9ShMtf2L$KhvtTPqnnUgYwJAhX!%rhQ8RhZ{4 zo>G|SB3@INXBEa@AbIla!5W2mmf%%|dkV3RD3>%m18|+dLGe!i2g*LH*f4&na5nJ& zD$IA{e^TORAYGlnj|+R$6V!_x3iF+5uflu>npq*^!}puV z1Jf_xT`t!4NMD=6d_TBZVZQHsOVd{wM$J6Qhws{U2^wPB1?xbPah?*nE&bOT?l?D_6sm%@B6aM~j2mwWyfDa`%(?*r2> z_uhY{?75fzxyCmkti{qV_q`Vi92EQ8FDlGE>f@J?CMfozmn+P@<;N7}zVVSuB@Oq4 zFIAZPy$>nOz1)8*%zfGmE|m1#gWaew_gdf8_7C7bnu{b2_eH;}F!wzB6y|>Btcz9L zHluAT%st87+Wyzr!?{F-^&5;03Ui-u^fKCGF8w6lYbeb7BH9(M1inXM?*D92n0q_# zY5WZO(n}>D?#b8`=Dtda!rU{tP+{(eGyt<)xYu!qvgba=`wDZ9Vu)Sx{2 z428KStx=fk&7i_uOWvw5*NG2knm)|O9Fiy3cUFbDcDq?&>$|9{3Ukf%hQL8_H^xT_ zbA6P#oP2^}9W+s4u4_sZ=9=Xn3UfWOyGGLUz8{NAVy+`TQ?haE!iF zVUE8eJ<>iK9BhutuRgDVs3};Ybp5eSv;j4h}R+#6$ex)$aeLbr%&j`JxFwY1L zC|n4fihh$}@hr;G3iF)6c!haRV1~jxCs3|1&k0~ zsIV3IXg~d;ZvnO`Tn&6aaR%=GDMFqoyaO25`5Gr35ft}6J)tn~ff^Bz_PiI$uW%Fa zcNAU=e6Pa1=jRE9dB4w_3iH0GGnyqI-XY~xn0HF;P?+~hoxBP(BQQS(K2PBdz!xig z18`8`4&ZMqd=v1!3f~6&DDa3(d8Yamg?Xm>U4?n3I;BO@>;#^uFwaykR+wjrI~3+w z;;q^q_$`Hbmh4@Hd6vv*l|1>*=qO+`U2*38G=+I~eVW2NTVAO!zayyA^k;&N!Ukw= zRG4S!f2}aj;lHXdzmNE#HqwxCTv+P zcnbURCR}R59VYyi2~S)T_1kR1TTM9g>L|^{CVa06e`vzz2BY+06Mof%$6gbqahvc% zCj5a3pK)!J{t^@Zt_g29;h}9&`k5xY%7pJX;Xj%1@oS@gmz(gNCj18zK6YJ{eyIuH zYQis=@Q~}G^e38dt_jzh@CFmU+k{^=;eHb~)<^k|G~p5xZZ+WtO?Zn5_nYu|tSc<| zoC8(QaGCIrO!$ui2L;VLCj6cWe{9147FhB;CM5W$k^eY}1)u3ATxP;{6ZV^M$b@e* z;d@N@w-Sr6o;Km%oABRFc()0sULTF;2opZWgiki%(@l7?3Fn(|sR=JO;bkUVW5So2 z@Z~0atqEUm!Z(`mCKLW|6Moc$pEBY9G2#C;;kP9o!t&Z>vNyuf{267!6HWL$6Rt90 zw+UZk!grYPf0^)uCj6)gcbo7I6YeqLeiP0{O~`@b_dt12Q=#&qra?`IDu9{+bvD#F zP~U<&7wSByLZ~9BnNYK!ilIuN=0KG}oey;ZR0Y&xs3lMrLR|!PG1Mhc%b+fWvO`rv zT?VxhsvfEVsu8LQ>T)PAln=@e6@Y4nvO#&ETA*5?u7X+(wFc^Hs36oeP}f4WL9K;a z2X!6PdZ-OhA*k!2!caFrwL^Uy>N`*!P~U~R5$YzWo1t!jx)tg+sP9AF4z&^L4yZe! zegO4Ds7+9JLH!8odr&`y!mp5dg>FR?DInaO0)MYh_*P( z<7+ufuyA=N=Vs?jn>N|)-WzM>7xGBz?eHr@o#OM>D5Rr9$H~GlWdQ^rKrGi3Q!J#z zyycfcewpvAMvoU4(NA&bPR}Jvxz{u`3I1dr`3j%1 zVRM?jIe7@U+~aWKGyAGmaBk2PkiRmes7c{+vvTo=3FvAo`uW5nA`OR$-4=pweQus0=!UZUM?(}cS@ zCK0!seBqWfRuQ6dTlNZjBjQd`5hhz1?p%*EKq9rEkB0A??3uur=j5PX zl{7ZHy`IJfw4KEcubU-F`D+K%)MZ#xbf8nrL9)TuHBg+V$LrgB4irq!&-+@kAR4~P zfN3HFgfNbT*1?|0mQ!MCcO?fWSE8{HouK_9TLF97VhAZQ1(qy$l-Wf&Uoy@mxe$QL z(%$c2qz}ZhsovqQ^?3JMShj-vsrg@5VW|i-*dg(z83KNEy|q;$W}>4lb}bJ;G7Ur# zdLX9gpj6su!lU7`pfIA=y6auby?Y&c2}1Y|=lpm-qr`5t#8rIh<2$jxRuAQ7e| zRnzPTsq>4*Q8)9cB9^7@mMTcGu5Kp9-GcQr5n-}k=xXsF494GF&NsSNAq^CK-naq+_Uh~H z5$SyiEz@R8w3=r4>KtB|6O#e|UVHMK{QQEir6Z4qFS-obVr_XR* zp{cf)V~Yld9(>E}u8Es2l=5Awj-O2_uXzS-q;Z>lJyVWaEdx>4{65g8YQG zS1`@6V_h*T;FSeLQ)9$b74T8Y^DIvQQsm&G%u-w>a&sjUS)PMsj4EC%WF;yqHYnOJ z;CJt11fDuAH}`9*nUU~SbDoY?wRl0fXT?Ie$hq|LgEJqCCY80Y*<0^fvDbcVdR{@! z*Ry<(Vao(poFcHq21Io*Ed9fDcle z)ykm4HWkIf(S8A9MhCIBnumrawl!+qE9l5=q&;un?RhIJetjDk2VHgvk;s`UT8BAa zoP^*e4Hu#!`m%(0=g#B~SgF_3K+*$^vA@pkbv9w!p>@h-xQPQXjBIn!JcTk@vGrK@ z&CO?=uFC_iZ!S3W_}DIlQ0G8xtxHT_%X4xo9bTX6q{>lCn91iOH!9WAAz$9>z>(|# zR}mGEkzQ7nZ!f_QbJ#p`p9!4}{v(fOR1 zx!H+=uX&F}fs#w@@#6X;{IE#FKXS6Fzz$~Fc3on~a&y*yEv;NmKI9@(hkHP!Pw8r`aWR2{M@e%@9&1Vo-0`0<(M{a?&r6`0 zo?uguV3RX7!74Y$;6R1x3yNc}^S-H5bFtm@b!@yvBjDBZ4AG;jI)WP`4sbq^WOU}M zJS^4i3{wo*GUeXMdU9b7c`8PBT)4BBT@qWe4%KF^$f85VZ9#T5J}nn5BS|RiZgcE= zr9{X#Sf%q!>2qzY&06Y^4}JV|O0<2~%P<|eCmxe4`dkAWr0 zW>d}EqqkyD0NqN%=rE^2hM zY0iSG#47-G`I%}-3s|l5>`Qz#jwV+X=OG+=&7DDP5-u<^u}xp$@^kBryO~vuZd@ED?o0dT%Em4){BViv zjfq>%RKyK0H5+j2g-dq*bMdCmvBKq39hmGrrh%;9-H5AA*<;yoV#BNFBN&`uXPS0J zMk`y~olXnw3$roj!GeGdK5k`!=?>Nl3vDFG{|0B9vQet{uez_)H~qlzOJDmacAKK} z^r>Rn`lV*9`M9=1T!<#hOBO&={eEYCV&0037g<}$2|Z@@1!4?|zoqmbCfoLvc<~l! zWZ^-LpW>;CSQSfU%(_3e9?Ru}t-x-_ur2O>!@Hd(M-47YjcFUUyx0wlvdX=3&EulP zbf4Tj-qjYZF9*WSmMs=1HLLgGn`#1(Y1H^7Oj zb6eu_+?M$I%9i+&%a*u`wsQAZqFB3Ctim4QmsA>4wlmRMh%)xv|vYSuwvl`S@*;wEz3 zWRUGAdY|`KPCJ&m;xfNt7jBKSuaH|xVry%!TS__8@^inw9VHpQdYvdH^|onvrRG_s z4w#Cq$GvTq?B{Oz*SNHiNr>5+Dky2GK`vuC5}B-uw3+PnY)P&bq7Heh>Krk98*)p^ zW>cFO+=jJf<9#`dT+Hm4UNNiurVXI)e!rt-MC6l0iq2SpNKe~|Mau`jle zyQtsf;tbmYa%pCYF(T9=2B=s&`Q9eh&a~(*&na*Qy9NioV2G^>;-=MjJMIq0+2N{UytIn9wb^{D98Hyu zRvtgXCB%wCwh~p>96p)jil^BvPps=?SZ4caZlB!WOmv#=_NhJ6M7P*oMj5=jg&QT` z)XPhrZ^3#fKAR8;ajLJvoJbL~xLmezt?Q|8b}fj!(2yIWf}`1Y9`1e>*R5mhNpJ*f zcuNwC@BfuOQEW)bp#8ByC*yrXQy z*K&S)pwW%}O}zSLBAXm;Zy9fsmzyDCjRjI>X!J!Uld`AuxkbkC6{zqdUUA0wtg5hs zhA)^|JOA&Cj7!MKi&$Ay=O@n#kr~-CyKvL7I8~XnjFC4vcz-Q2fMqYQG{$>goRz4k zD#9t0xvVVs6*v6{Wdx$kKG%-zZbv=qE6&M?a#j^pWR83v&zj6s?zxzgR*iX zm0?fvKc@zK$%OxB#a@h)vR`7G{IZSpKdBrN`y{03o9L3}{(qoLN|qG|u}3P8>5<|$ zR&o=!WTqx=@8l=$3r$b-Sdh5mW3wf0GTCyI?fE3x-$}C1WXnskH-vql_+;heB+}(z zTP!kfDxbQtB2Zs1w+>CKu>1x`3y!iU*xPa&{vUf^10Pj!wZBUe2ngJuplC&-MoWqU zQDaFF%?bhVwD(BFd>)(KZBnr zRf1HRbx{x%0x0``o|(Iw-6SAizW@H-H~iS#x$|-6%$YN1X3m^BclvD4#CbSQ;|=Pz z(kB)jDgAN)w$sN(0YG&nt8U(uOSsYK#AQ-qQry}~CEVCHD0^wtvIaYMTQx+JTGe2K zYO72%DWQxsoU1=95ct>+!cL?DjV7S7Uo1P>yO)W zwM?2a>3?tsI2lLB@yquXWKznBMExk0G{=3cdYCi86M|_kJELco#|O*ab(~cE5_d9L z*^?#~PMT?cKN*@?!p*TEVhlEKW~0!rP|$JSi2p<*#^G*M z`ah?eo5|aLQza2co*)~^zM9`^z0`W;mea<9Y+&n!R@T5Ph*zsaxZ{$%(Iw6awlTUO zvccHrSto!|%d@-_0M+s=@AyC^oaGS&$HWoN@{X?-*|D)B(c=|_syCn>QO2t$1m;`) z6@e9xVxuN%o|`Do(!J143L#!0%*jq0-6ys=C?;&1lGz5fqf#g$ZObrY1{ zf!esi+GggHa?=!${{t>bw%NY_AD0M;h?*+CtLuK>Q4L3P^RBt-_G@r4v-6|821nXS zZCU(9u$GbSceLPtFX7zUrdInME$l_P;cLI6#f_{wDwj+1gh6#uFZr|_oZsyo9M-1n zIBb^xkG&B?OcVE}yij)BdQ=rmNOSnStt=AqB;hpehhob+!?fq=cm*H%c3jT1U0*+P~EWkJdP}#=NyvW9w3_FT1qu z7qukI_lZz&>oHq{AMf`aQP<%cafB`4hybg!=WJx77!WkNA0C+p&oOXZ!HiF%^1(#1F{I_tu{imQv~j zx1UN1#%?v7_~g(M)NyV06;?5acqb%MT3zWmzB%S(-VW+NXVUGHX@p-`IG&&LfkB_k z59OZv=5`*w&*o?&%Qd*!huc$aq$s|20F3=nPkf;-g~p*|1BCPcSemkxyE z8JSJqbcBPES+nNMHl*Virb(A_!h?Y>Mr}liT^`R zBJ<`?wS8rsNE726@}4+eFhzk~TH?Li;~GOzK(l7Gv~z3Wj{PY8ytmZv9v4z@wb!b3 zEj^CX2)m`*dG{5Z@#o#aM!`Ro@;7Mr*-@2msZ~C@LQ!LaW2))WL{WNFHO(t@-;i*M zVVB}0FZWzWL6mr@do0CUcI;7=Jq$gMjPLQ))PkPPYZegZu$~dzmlxhKyTzn-lqIvL z11vuIK(A=_WU6LPn+uK>jQ>c!0*;6~nB9k#x$`E+U*(TGnK^RlqC!mRxaD!YrEw!( z-Vr&T%5w^*%~>#O;_N$)kM^+OQ@$^cjn*-nHdQQpvUK`4*&SQ-sCc_KTd-klC3G1+ zR1V5x`88z{zEMd30CW#G9c~}+*(bShOTaEx@N%_SiN`#aW`C0`-qA&LF91gsZOUGE zi{|9O>pA2A?Ehn)B66n2-1^!S8|}-9eTiBk((JGKs3cH}{mM}Zffi+sa$wk{fN-o4 zau0Chs4T3HCl?h>oHTuY7T3y!)9tl9yAvxyeD+P|oIh~~8ovdjTIH+Qjj;L&~Y+6gjitT|I;aLUZdGv^cn#VIrA;9IkN7Ty6u71+@Q1vCAHXng@w zGsccG#$7saAV3sA@)gFvW9|h~qz3-dlMNoesWX9Afppvymlq;;>TGloo^z+85T5*0 z@|=Px6JgdM_hfu`z|rXBY4#VdA#G+BFlHvw@titq@+>rp&$%ds=PWpNag3L{+F6CS zjYdZ~;D1tnZG8NUsdtQ@3=Dn95g#`NyWRM>S^N;Wazr@?P@`E@Gzs4_4#=RPiTV8a z3VW+qd`XC|WLiOx@sOk(wvO?Iv*$u~`Owh9SOA`RGK^8z4Rc>{Iih{@3P_tcY9b0- zWF*~DIN1ks&yN9_a>vXmD1q;WPr?Qq-;izp*G_?U3ba$8odWF?Xs19s1==alPJwm` zv{Rs+0__y|-%5ek4t#p3lf&UmLIXSE*8{)2&JIUuF+&c=nfTRra6lxRP6#ntu2CX7m;dk5Q$+qH)HmEJ} z+xfLBR)3m$@;w2bijMt-dQB;A?U z0{QJ`8x|kXWX_2j7Omi=+4xMe%kaG=y!-@sGbbJizaksnW}8@ikB7(h-ktyts!*w! z8(-j`%|q!#`sH1w`XSn0zQ@CZC`tGSKE^>vbBkNTn_$D!?NWR{GM`A5=JZ+k`Z!so zCA<|jyr>-F`;qv>9v4uj;xl*D%wBe=O`0+iyy^wiPQpg-OJZVToh%MnY*zlr- z_#O`rK%z-DyeSiX6Ya|JXbG>;h9~Ss^8Lv4n^f2=MO(vbxI*=BiF(M2x$n5{A5`?9ZmrZE_MzWeMg~h>Z}2t>67M7oOj27;qx#%ESNKIM&W?rb70*zksko< zUl5HQa3juO5K}l{Xk0qL5&k&*V(=x^osJ{Grz_MEp0;4S2Bny?>;Q9;a zvH$p++^=8%EW7)N$Dp|U&Mq&aor(EXllxy2-{URIIUN6PRSzXke^-1dhvOpTBHfFA z4F1CZ%;-D#p#5Jv1==alPJwm`v{Rs+0__xNr$9Re+9}XZfp!YCQ=pv!?G$LIKsyE6 zDbP-Vb_%pppq&Ek6lkYFI|bS)@SjD2vAX$DFy%KroR0h&?c7`k-(5GkZXBKGGWQwg zA@LaSHET+@`1OvhQJUY9Z(Vg5t#W;>Ww^J@y^ zzy8{}B@!En|Ba*d#XB4DuH96nWx5;mI(H*e5nhRKl^rfecsawmwXi|A{3~^9YTwws-07G-xSLvDozE|sW#LtcJkN2mrz$J;7gbc zz+)9)zKK=Hx3`qpoc_+J%|IyJNe`|a$JF5I4u@gZK3f2gB=8he^>b9^G53i@NYl+~ zy>z25tFH87WJf08GGwvDWffy0n{+c}zJ@+1t@54aF|#KjoV6u<_OmqUAru2p!rh*o zZomGBK&`dJN1UaaK-@)l8D3Z}QdD52`1&>G1d+c$z}&1a-hdPb`Z>QwH*3Pz@J|;0 zM4`QmY~gejK>~|s8Sy<8AxZIf2~l>0_@fM?z9lNKQaqpn4I;pRxm656eQod)Sh=)2 z8yxZV06$0aQo-|c5W{~+oM0!WiBY`}QI|3@npT%m59-Klbt$WwgKO+yB;{;m1rsOm zuWs(v&HVtZ*?>{&8J^%Zy>;_d-CUpViZqh=9qSyk06MFxb@?U~e!ZJQIZY30x>*~! zKCQG$d$20pK^BM~FQfC2{V#U*F0zH`Wi{ce#1mgfBB&@C-J69h#mvI?BNeTjg;&|M z;E-Dp6xYM<1JR@G=(5dnl&TS$(7w@nVCT4}oO)o$CCsapJ_s;ss5W9q?j}$S)hdL^ z01PijcqPN&k4B8CDh$=-v7x%}0*+GOWlR*eYYqpn? zyK`R!^|qkUa?3WB!`SSb8kvLBBVs6ae=L)?iWDHLojc4S=L?hUHkqI>Lb{UOg2q6zHb1h>tjiCb1^J!G-!lJYiTV4+ z@?Q(mwUIyRaQV+_m0u60cuC*VDt`tr+t>vHs*1P)u}%-9(;##2fLGPdkr zl zc!!A9%?}_4!d=mpQ}(hg6ua|ZWZG^iE)(fDI?vp{cz+!ja?zQA{gW4sDBY-)b^_US zt4{~u66%HU;{E;bchP8T@gRuOKvSxAACi!z+Y6Y}^vTJKb!R;UkJV??4ixziX_o5` zfu`Qteb1?U)h+Tpy&d`1AZ_vfUl4RZYw??h2s%Z(&s0TjXi=o6K#}`oksU}{lwmEN zD~lv8_z5sMtwr`nkv)9#;{C66V$&Ay_ax(a{^I=t`TUtcbu{L!@Q)VnZ$JirZ$$h# zjEGEY@lywhNLTINwGxp&Z>4fLW&Z=oU=?$#`J(s|^i(4ul_SCGbNk0A`zZoN4E!5` z00R&peSXEj>j*r~z(xe#WS|OxPZ)RxffSG}{ND(SWZ+>0rZDga1ny?w*9a_Q;C=+2 zVPG)=I}r%^(IW_VCv~Q)@D&W_%W$`Pc4b@#l`+kw@_Eovp==etnc++oE@Zfm3g5+W z4;B6;!zn8KCx-Wf{;2yghCfx|8iu#2@JkH8rNVD9yitYsGQ3uWdu&JeNfpjy_+b@x zG5lXDJdR;Yg(ot+ScPXZ>{sFY8J@1f4>6pt!cQ@Ly$aVd>{j6r!#OHEgnWL93eREq zJQco|^zEg>k22g@g}-9>n{S%w{<#WglC~eI@Cb(ARpDt2zoNn>!__MMcZOG~@JkFo zs=_-NUZ%q1Sl2HR*3NafQ2i{B{|@|0@%try%kX;?zg75E`GrsFpczdP~Mk%!HQhetAyEF=@j zMlzDDBs0m*ZeX{to7ipaMs_Q^ncYq{*ofa-_-(@vORU88KwI+ZcWPi>LONa4wtV_Z z36Zr)iR}L)4B`;YW~1^6a}@@6uhlBwJ-V|&%CUVU`%6f(<)d?h}y!P7}iG;ScjM)USLIbA)*a|_19!6unt1HL2K!No%0~A;>N7xD|5zi53Fu8nikpuPq5^97&wQ%F=P*ppL;R%-lM@m4Fig%w_*RB(fi;U^ zTVUPKur072Vwjwb{O6M~$>|9Hh+%R*!b=(ENIP_;o?~=OJ4Nc^!Ur_%+~1Y&?h`i|4KQ-G<*>{O-W-9{hs%J&0c(@_dYEJiOBZ z^L+feA-+GJKf-S~emCHED}J}*Hy^)y@cTJ_zr*iu_%Z)K@mz=Bi}<~b--q}`^&iw8 ztl-EE_UU$j4{Ry(cSDB&wsq9G|IOWaom=otOk0nws(YtiSDFW?WhhlwT7(eNAal4^ zSuzfl0Hxva?TOEWIFe(6CZ1BZ3RYX1e_qd3qn{|<1H|%F%E4G4SI+D0#%tls747p@P z5w0+c?4%4-%|&TUAA~)RuA6UQVOp}$^~?ZYlB?`Bt)gSu`r;3r{#0rWHig2;dT>-K z)d$^5UiY7=ZxXt7qchxFEm=hxV240Zpfx;I58jxjRSZkRGHie^Rja59G~MD)(j$;X z3oEl;H_YAQ6Ydn_{^(#efR|ooj%HHiJ|>{7c` zpi=B$03Gvdl*alXs^2mXmb~t&klpY$lb=Sm`;%5kvW#@<=8NIpdT=z_Fwz+m({$%PJ?DV0w^ng!;LreH=UlB~Z{W}^{^y64 zU3z~~xH8H%#7B-7b}Ke^WO;Ddg+#~QsPM_(1~L*K|8CvN-_`=3+Oq26ZBGB`T1At- zX_s!k7d|Z>-{3-l{@txR59m2>6QAyZ{gPoe2KL|Lud3}h0QH0`OE&t!L=EgfFyUCC zm%i>xL*!{H5?keMVJ&M*sFZjz9mr@EV=j#Z4oGOP2M*lgzY+z2M?F|sw|w0&c-`A{ zYfQIoVRSspxX}P#T10oQ*E9F%nYC=L*oXa(YHLTlZ)5!nk#AKVM4;@KKvTrm{r+WR z@m{<=w<_EbIvA=Q8buduKgy`+S^>0T`|U=t2O!z2e?)p>|3t^5YpiR`=sd&RySJ0m zpQ1@JYyqxgl#WH;)lv%IHSD zx-s258Pco{xJC@k_(p7%sMM_C_ybBF^D~dRUwDyU4>URbU8qCU+~!5$E=2fYuUr+L%0%_(P`jHB1Oc_nX-5l5hI3TCVuMttc;!`$l64E+nKUhA%mG$XKMH(UM`py;N%$_TvX^q31* zdd#Vn$Vwr&?;XSHdZowtxgOXb@tB`u7q69YFPyd4Yc?8z#zqzCyKSW9xjd4!SI?2 za|8whND%a*Ro6ibc2b(Em}Xs4cObHRAP)i?`rh2!{ROiB#WExcAO5KMWnD*5AV2gL zBgo(Rp#}sCV)~{0(9<$+bUqRTKw&DU>cr#V7dALyKcNS&79C?*?q`-(=^q240&zRi zW9pX}e?li}Wj~9JBE|xi1`#m?1*moH4At825Fcp}cO%M7`5os~YseRPWbGAYh(oUK zh$%;|tSa$4?jfuplK})EUzWLhjm17ryu4bbRI8GsnoHiON={HE4ONo$c&zO2p`^#$ zBYq(Z_mS{0@GeJbk2Pc=GOgoS=U}{uaTs2h!;%mL5?t|kOfbzALfWdU87}Tt*qV zu2|uNHG+5yS%OwQib9FsfQL-v4(2_v5NXifTfNF<+2&*xoX0w>Wh}y~rsGwuDlmk^ zozLKH@YK!z(>T8_-axd;b@G5n{IpUsQwgw8`brL#{Ls%)Nbw`jyOcayymJs%243?8 z-F(SqzKO+-Cpe_@Znpbs4CMxB6Sw2yJ#>j$$!|%UocVpV2P}ldBdEm)T;Mr@WuM19-O790E;nSg~J+-#90qI>_wZkuVxYnYeW0<+! z1JWSY+j*DkIW7vlnL9zPN<^tu&^QobZzW5@J^t{LXSbQIN z=}Qgg3pNPxn+gysIOH;HEYT{L`LAoOKU~84*0C;6CRPPo_23es50FG(bYk0rSFp?Y zdMzkt1g{cT;OQ%xb_ZD1Db|)cbc4~jNskrMsR+rNS09M zr-CilYy$zm1YS&F_X-)lJ5{`afUEfKOB}v)#l$Zo5zy>(sAuo~42=p7j3TrexzIKG zUVym}U_FBuHuz5kBd|B)#E&RI#zgrTUB7Gw=?(J$;Ad)?rDR(z)8e6$mbqlEeB>8v znN!QP%vsB|O#ezPb0H{f@l?xWmgeH2n-(>vx+%}(baPc-z6JZdhz*s!h0v|ibeYB7 zh#3S+RQKjO_nQMzHBLH!Du?K3Xf-^RyI~y$znqpf3Ausb9-#}GL`1na`2DKbdJwXz zF6D>RhTtE98O^~S&A~%o#xjJXL2JmD2tq7v*b36!@H7xf*^3y~jo3N_Yg2aOFCHJ` z;bdoFCk7__^>cXe7&bqY3{>O-cF5n5M`SHFjykr`8EL`#o{sJ_ukW0f9 zY!J9?abvYs(Q#CHPYb-~NOA~91KZY(B`~E30+^w5K z(*Us%`GMWYRNYK!aUvwiSr1sdA5o?qJl}YsEKS^C+6a* z_&=_HMnbq8wtxD3AVIEJb1M5MSyd3^s2Y#De{NFwkG6mMGJD(o(@mk=D3WEKtzxBo)``t~RsS^L8J&+g z8`IT*8b%FbnChkm?66|PXfub=Ss+IxxU@n15+qr)F69_5fAo{QawZlxoE{4UJgOL5E|=wEIud9j@kd#% z*J*%{4CNe+{R!8)6N0+eS6fuHI7`L#M%)BDtLP}>vd74G9MRwVD~SCHC!t~t14MRC zH0cy1k$FciR<-_(>46#@;CjW?{B$z-jPvYXcY_mif#u&6PLtuj*n@5gUxW={qaw(E z0W%O}&wdbODArCSNG^)&!Td%vzLHB0YZX@>;)CHdtze9td6%q4h%@gJwW1laK!W0e z>#u-j7Zw>$Q0W8OujNc4df^q}fed$6VF$y%?7=#hr6TMJu1(`3=b-P}#Q91O4i>{% zC{UAX zTNkt%>`2Y)v}BI5K>5$=H~Cw7E(6tNC2Vp-X zN3gB?p}x&#h-8^jF+|fpSX%azDAo{e#Sm8#<)JJRhw^c;z#-Q4pT+_(GaDqP#9{Vb zaDW?|OSK=6{r^}ZF^{AFyND+NB%CCB6-rduVsCYDzauXhy!Ej)V$?kHsuYNxio@YE;yk2P8nk9)Fj#gXse) zf7Uw`YAAv=T6%OZ6zcvJ)GNVrq4bNjKTszOb5W{T^ml*>F2aD_>i>km?zt1Y+gd6# z`gT#M&qWMon0zRBtf}>Ce~z4xcE7oYId)Kk^F6ejaE!r=(tJIL^O=Mk7?IjL+^wM8 z-j#eMLGBQpkrt_8b*BM%PR+b0;_s=4RT5|g2U4=EgE&hxo3dZf%JQ1 z1u6;3or_@($I?-4N`i8W0@XDXH63NsRXols0G`Fs5{b>-03cOvc8fzf6rNW0qi@JO z+|6L&n}%GjvVVoo_XekAK;^VUe8AROYne`V!*+b`ij|2SOVk9)Rk9fa=-4RR9{2lf9LFxCDN|)R-H665ecAT_*5(Tw`ytVbyQ%jT}o^(1-4)Th7(%491+nxUF?=#fR27#l`Ur3y*Ng6 z?R7h_az#_!0501qhcnyyo*d=7#PWxcGQ$YERa@P$w(b(YMH1Rt4seEvy>_sakg?P$ zlQCY52e&dhR0(x5D{5i`Boea}goMWGfwj3P@8DQ=SL%aH`R411#bhN;2&(j;Ocrkg z5!A?{fu1X<(Wg4U(WUS*{Xb5w0!yD%9o2psyuVZ@?|XlFGRXizl;u0 zVDTd~k)u=s!g-XcUs>2*DM3V&{r`>@1E60cX;@h!mOvEHaVi^fVPc9nsQIBPtdK zkrJwuEf$6&3;2_868N(L5q3^-JMxfr=SI=gN`4P4Bw95#TF)!A?s-)WzizBqP)EWe zL^ORJsbZ}qVs_0h|5?_|n1q_=s+t)ub|VjK{$7k2SISzc{vk2mRJC@MwSwD`Jv3e( zG-o%xA}d@8Fd)!)q(}m7Q_*=UT4w=>O7NUQ^9+S1OW9~%h%8dvP;OG(KyJ1nRQe+u zc)bb*ZJ{Dz1g%OL(|kfuD&y;9PE<^yFh-;hl?rS}qo_PUs#|OGno;@PLqvu0pmS6n z0GT#M{X@tIWG2X}<*1iXg4Q@06F=%@LY>TNW5XD+01!gG(0^Q{*@L#9ZV%eCV#760 zR@7p+J}x8GaAg@eT%%=Hh_h9h#36czDkFy|%g7-bEmJPUayCfDHV;d;ETbk(@W}AE zF?p$69<`JYYJC1d!fJDTet{&;vX>AtcGqKJ!@;N5e!A`F5c`>JKQFtn zlV4)(>J9$T2ws=w$^2aI+$taYyZWbVPt<#IwrK&(aac2she&?koB5Sd{Y{cbdqVIw z$-jL)uC;Y0c(jS38ii*)cJr`H&n={b+f=eRTw!R_-iDhMB@xK8IDLJ+&=N`!=?-J z8oIPU0cDig#iPp8K{|Dy5-U z`Th7VIV*1eqWYt1*^&F>R3O@-KQO?(rJwpzJ?1X)1&T}lN4B>4dCX{bRB%BmSUFvP zzIt&|r|xGDnyZ`j`o0}dn51~D%ilI~7NlW{jK%3Q)*IkXJ#)Q2{Fpi0# zLrLX(2HvB)$AtS~vGaQv*I)p0i)xr}8<`&%)rXSwHBr9BINsw8exDNuPVqdM+oS~0 zo_Nv7c~!fYcfK&jjkQts_g%}aqbFyFFWue`Q{c+|=~hg*r!PITUaxLS(pN_@gb=FMSC5H}n|e=hYQusI-C2d= z+Ha~oIpEe8yxKLN6>2aKk)!X^-vMtEg6gBB>nz_a$vJCL2P7tOHO#9G=OM4T0ODi2 zR>ECYGrwZDoXV_$n%-;<+Sgl_$@!OmyPVZ!tl8wrgf#{b)tSL`X}dltcz<_ zI>Q~Yu@BB_Fmm4a<(ux84GRY-nVWIIP=z5%?v0bjluW4d5nwE<4Ak~UIX`V#s^W;S z4;}MKGU~Vi!+V3oEa-k2r(wC617%HDM)&)l2_3+UzzYfZdve15?cp=ZWBoONnN(+D z;%Z?AkT_r9{K`DIt`cMtPoY#@fI+Z^qc-py{;F}y>xuF5bIfR$`5IZy{MxW?$(TT) zT>W2ICcvsEV?w+^7li7VjA=&jmW;W&^F6m#Q72UuAHb9%%G#k6RFeo_>Jwn|1}O;^ z$7wxmio3yXB~*Tr}nmR?mRG1bkd%JA;79$SuwUKd!32mc{hu0oi& zvTxczVY5qoh-7NV#c$=}XLMg0Elt;hL(`h+qg&TvA|45$QLFbWOyy$J;p?JTf80@z z;4;`gdDg0DzO6eCAw6A(6>5^hG5<_GSkxr?fF1;gf#0OglK`l6BP5dl5gxqpglS|d zCWFj+!fXW0dR7!1oesrE&fET;q^dDkLg~xAOp*%axAp4JI_tr%pX-Z1r2f}qW^AI# zjXAV$T}sVn)mWCs{T3(;YHh;#&iCM0Esj5t1qKP?!k#qssp{(6#ak`7-i4Aq5Lf)H zv2MvuDd@kH;s8_+RVuwyL$iZw2zb2>Qxx5y`NSV=thiu{g@z$T~ z0#62k?^})vV>C8`_eE(u+_3({G>GxOm|`%2+?1|cu-$}uMV=J|yKd4il*a(UE30`B z3yYIGh-~(ZYK8mWB|zC-8L1C6b=L0N3Sh7U-=2&|^x_IoS%YYYR)QkXb^U@vNw=0! z>jD-99nx+-S`>)DHIt7vw-J0s))jfx=(nIqgo=)_pe$8`Qo6O4*oJ<9t~@$gVG&g& zi~EkcQWU9|MXr}MX73<{tz}dot?5safl{|W$hfhUSsU&Ce;616J7y9~keF2!`k(`& z{E`(a&=GRr$v6EJIb@Hn1vc>{M$a$6-YGi{Zhx#%n&GB*mvBR;$sGCRN_GL=9r;I1 zFLdnmiAS9~O5M|e*wHm7M%^#wlROK{L-|eymQ9PXVa_pO`|N~cs9N#DG*o?z*y8KU z>|Y`o!r2KC&W$0w`KF_W2l93~c7&h7G4U}X{2+<|VInC~$Ad2_oH1E67@~&*(lGDi zta&t$ldF+=DKba8T?;*;yJRn?=*1fZqMD7Z?GXS4y@?Bb5Ty725?Fu%ulN<8yjafh zD;C_UqR)*+<3wk&9jDHpnU%yA9y|I=35n6NN!fPv`-m?89kdA-VTxa2KlkA2fUc$| ze(Uiogx-Pa(fbF|9!;MA zWF=l#aQ6Bqs0XXH%|_6dF~|rG%gCjfe&**{5w600o%9*|4L$N2mq&R<(33Gv&wNME zdCh;00dv-YVjJdt8Et2X0)g#v&TijDx^t7hCSe=&A-6$t%Y!ZHjCTj=NoT)}*|pL( zWmy4J7T_jLS-7L|n0v)Hzd%cZ?#;+D(1;An7)QLnL?qT9fepFQ^%-YXro6}O=&yUx zGPNF!&ZklPJ)U5|DjGynhaIg|^a9jg$323m8p8$-%fOuG$-tyGCL{guvzl(LVo4Fc z|80x z72b~hpjIKz`D3#*lwD+5*D9y9-Pp_-)sn^on0!CON=V%Gb4>jQJNl=(il57PmMo){ z?1TiC1_{*KiOSLB6Jn!VOJqz(EWK!a(WIu0<;aEh%cQ|*|6YlM(|=8EDQ{spYUR5l zJffgHa4-djRRA9YD33(kux$Xq()&<-=rcf#oj@|^oh(COAO~Z_9|_7@D;x2fpGXAJrZOfy(itRL%it+m zX)cgI7Os$ZK0JqP_X5j-kvtjPg|B1nTvuL);D!wjXeG2om0fs9n5n#|M3%*k=>=D< zP6l&mf2p3=C46Z?xk>>01)4f&B|ir3c&)nhT!=Nh__Zh=#sIGgEk`Q2^0(kh%1HoR z(-$NX&jlH=iVXD74zc?H&Rrq9#$ipn!qx{Mo{PJ$Fo1*Z6@mH=sMr4q)I|f0 z$vETMAqMx0K^Kn!aA>`pzq7AZwf1GL=dsq|s#Zpz)`4IjRqM~qX= zeJ}k$)<-a6FzdTP)%QT9jGxQ;GFac+_sdo?0`-yERDE5V>swX?EL!g0W&J6vzm&-~ z3OnMOtSb}x830{u7jV8~P1ZH{){`hkx z+^V_^Oc(C2=5;bxxDO-v2cXzt;jZBv^(JX|7l1`8@x@g#h4Gkm(%6H5u!VmVZS)3wrC?U-lH9 zioLvH+WD&eXl%V!fuWu6KOK%+tW{k5P=zrI@+0&t%408#c`XmoM~B!jOnn2fNWvW? z6hNE3hY^`$(~%Yxm_1qNYOp)wR5{S9ZE2aIq@@?aa+fIGjXAOmRRNR~mLxSTupuhP zev70;4Yr`{E(K*BCNU%6PHTcazgDsZv_lP4V(`9(D^kk=7dsDm%BgHJ0!>|D4*;GE zG$pGmKai9DUUtcgP%;clpV+zHx~C;84gx*bd>=K4rS~#o6(b-$NM}lqUE*cT0^XpX zBC?9>N5oM+z6DVW4PT%>8TC;7K?LH3Aw!v5uxtDAk>+ElJO_}TH<<+ z)=zygP@r?8#z@&OXd`8LEL1$^0Wt9uwMcm!XhE0Nte-lpW`dd}@dF}pRN3WignorZ z;+<*7P$Ug{xT2?=;-4rKK3$Rl$NL#KNYus4r8dc{L=QxPq%B|G3{9*qNtV zugsNjch%iU`eRq$AogK4;PUJV8G&O)n)_Y@5ps0xLiQEn0wQ#5WN5hU7>YZzKY;_VGs;G+R&jX;t>VfaSnB2M^NCO$ z;sOU2YNbgE7OHiGXs`{qkT#Cc<1#~mR=P|@rrMP;5tSut5AYj#sBAUZEOve&>w^tj ztNLz2=KE25b>e!X?2Y1@2Cd?Yz@g3y(rogAv^mvVK-4+=ZFC z^;4%-(Iar6A1~q`2t+RNryHiyiRRQ6cDw(2R9D?0d_mUh;d41IKF4Kl{5h?S{w`jR zUPTp9@_HcF?P^qyZx6p({@<7aFGs?+{hY|t9h(T|>tcub{%ybSA#eQrE9C{`Y4Eqj zAfaw+dU2C{s&3tid-8vx*cb*!1}^v^z%dLYW680i@_-8zj$=O|as#eiEaIlMSkXErJaIhPU@B2sbNyjNqA>3QwF1*ar zOJ(tOlSLcm33bKe3e+3!N0=7@BOeq**C**}EC7-Vn=s&80Mau{68_*^L<)9wpH|Li z>E=uHYGy6mETD~rO2X+s!w9aU(hd{SX1O^PuS`Hina1MU<%ou-hs{w>5AQ}jJv8b; zzo0JYj|*84&|Y9bS~)96kuq{6BQbZ}ayQj0&Fit~{2}#4m}1|NCMt(uOPhuoV>Y#h z@;b`9vY8)?kpSk+`Pw(OpqyuoPP92WBhb{%pM~oLUh^AYFT@PXK(}@Acf!W31FmAj zmSr6WI#KO`@*Xox`)6(4ZpK9JLQKv3ape;N{!HV~keF#FGRgT5#lzvm^-=Wv zeHtvp4f883lZ>Dr2Yt1NjDG%9ZiIh>(ujjw3pn=hH+X{!(~QV#E1jO4Lt4oaNF3Zz zEkc*UzswhS3tfsoz^`HxJs}M8GS}UR@>uiH9DjqhZaCUEYtdDKrv8h@QaF|NM)JDz z(Z+Ds*!-Za`<#`Zi^>54D>be3UE~M}{2{*ws(uw{>ZINGFTCUEC!jkwM;axe!jO0q z7j@+@oVacPp;iQ%Ci$nV7_LY~_KaW{&?8DG_ z-4iTGgB3&0w!)c4^(RRx9_r&H-3hN$$-nYK@10ra#bAqM;kdYY{A%lZ*i#%tS(n0s z!1@MHPD5d;`Fi+N;=5psk@J%OI@FMJV1Z6g23B%0e%GL`dFwGu>jV2Q@n7l5srUa7 z7_R*Xy9D>sV4Vx9jJjHqm^+-naHQY{ht!4e!u{)Ld#DV52;c&J-)0mlMt zNL8*p{9_z&{)FHscg9wG{zdkYj9nt5xx|^WggiG0XV@oAcCK|-#qjyUO?=d$!#fCL z39xtr`y*aQPK3kfs!lJrHy;Wxrl;7M#ZrPoYjf{tVULD0>3WQ5To>z&?$^z=>3rB; zSaldBd4hLi5%-nXJVZ;Mz@c69PhpkfLrC=SX^1#|K{uF#T~P+5zvW&XPWM^`@Qd+p z$h;lm_eBKlt~UZNW5`U!QKKIma8N7x9a^DdmfN?<maD>rAgMCUm^59q7=>O0IqQHbC2PS;>`tknL%CLy7p`sOr(C~jDFA-a7(m!#8C>*J5C#Oq5au24l>mZ^XhZ&l;)XQ>#qAp^ zr7Hl}2-M|zKy%iF-Z_UwgDEpuRiFwZxs)m^JR}ZvO65+<)s?2A2x~yl(Hv|-cE&2b zIz%H-hM77*pD~x=wX76T4dVCn@g9V6havV3bEc>GGU2!&4XNJX)KqV9R+`uR%$xbK z>~J>n*Wl*imAIVaQx z=PZol93$st#W`chG&d<8vN^}FF7JtX8=Uina-kB_-xRpCv|$;$@waP6JP#o^`KZzV z0TvK85B0?PjO+fM8D%|iQwJR6&H2c`E6PE=PWy|b1e=hxSM2oRO}eR)7ZPHgs+JTZ z9c)#^N8A3YFtuz%!$EXr66MX1ma`E1kv^}MELD)oj|6EIQ?Y0as-YfS!d@2(wv#c| zGELk@@OD)z4=@vW;K|!G>+wmuWiMHd{DlFS^ zAHva$gNVe>a*5kfH*17~C7bnAhJ)EF9>XK9Sy!kmvRN}_7|qfc0Fyt9XWaajus($r zNQW~L14l>ZJJQJVYq6yR*El}xGV_;KI&hNgy1$Q>zq>j!J@Ady#(P5Hn2Zs z(T~6`;pG@6(0#4J0F+CJYv(Z=Y$N5NUvTVFQL>F)zOX9v3uJ+xEIv5B8>S|=J-7Hr z;uX7Gyyjvd==TrClIuA@z(Q#$)Nx$PT&-}s%@uSzsvEmp==fT5q)@%Qnnr0Cc%SQB z?J~WNFdQ&t|6bv=e9d(>P8C0GiPP>ziPLhi9Z6YRq`nBQ(_+hHs2RhuhZj~w7dXqs zGssK2PDT?k9_{^~OKK7i<1)_`IJ9U%Pic+9-R)K}7BHk=Cl}1=pmkVqq4cSv5(go1 zn7KR9cy+g8ppIJ^*!I!Q+7#x7#6@nj*7iryrFHH+nR}GXo#xQ)YeZ)07*N6A4B^}Y z{&-mepHvu`R_1cLsz1YS_2YA0i(jom(eM>2z5@zXi;nSlb(G~`=oc;573DOPW0gSM zHxU}ZwD5S9A?aHHs0z9sv4T@kK_^teJufMPMd48Au(E;JR4YXv>)XYv6(Dn0w3G|l zN<5?bix~e)`-g#YcZ1V>oGK(|D3(rI1V8WD|M(;MGrxWfrX1Pd3+9l0y23jV#3vTl zd&H9;NcO1@&4%D`)gfP$rMqTm>r(BQvKM12iv=lx>W1(|jQNvPVx%zU(Qr@3Jg;K3 z`}P1#pn9XrgxJc%fanQedCux>$%tvzzH}+Hmvp0h7z}7sSV)_IB&FDO5BE} zJ{s=9D7&c(PC*p#!ctR?*!jyO$yctqhJ-}_CC_e2@~hsLBws1AkR&%V16wRl>!Txe zrRat{1hX2?*nTS3|Mq>}&0H*C$AO92lq(AK{Tcto(IrY}5g&PyL61oodsr@={WnI+ zm01;I)XGdAo79!o%kfF3J0#v=Y1@VdCN-FHSUjbhS^%qV+ zvD$|LOfAwJDw9N~uCy=mf?8aeQT*G%-p#=@J6Kmb5Fswo2zq`2iUfxixw9hSG%8eM z>k(I^4l5T=&gX^w^})enAFgZDHo|3% zNW!`mDD(LKf%%Z%Jj}yn@i5zsIirEK$JLLSQBov0S9qKsbM)?+AxAOhy`_J}LDlLI?Ln zJ}jjNp|CUz;XAy2(5PQLENj!TI=1o{9b5e9d{g(p54((#CJ5lCePC>1G((z}0BM4P zG>(t97i3z+61IgJhBT>RSoIKI)qYfmCoPr?u3E{5GW`)B-p*D_w2NhGbj?=8H`AKS zN86PFgiN)vuOiyNYKF8l0aCewRCahsK%1#V8?IWR7+FPyK$z|ToB0j+OGv?03cOm? zpU+w?X)z;)t1yugKT=`RO7vIZT!!uZeHlI-@sS!=4;nA`itwC47H!*DSB@`vzG!2lwk#p=Gz{ebqv%8KUK_{zOTb`u~u|yyE3a>k*al-9SAx!X6;-Mq zbnu<+9pP2Tb}7dghwMen{=O9WQXtG_bWDy-0 z76V2RbG0p0APSgDQP5q90)BrW+=cW<*`U9S;`?HPR-d&Jc`D4B#V{3Sd&D4wVZg#I zU2nWola|?pr~PVWmn{X7|C&lhlFiL!u2^#i$ubt_!o#D=RHAyCLNyDo;a;}>2J%Y6 z2(BVvVm+UA+3uEpr^3Wc{2XD!8rvIbf|3B+qz8dozm77y9rfOC5!JsL+ccDH#x|92 zrsd${u!LnQvF)X><-u0?jM#by_(~|jRRm3ZYo|yASWJAP!bC=VfG}8jpqD&QP zlA%8;C8X>ELV6P5ZAgs?kTxqwavnG=@tI2E_g2K;gxBy{@#7!#mwRxKMC?QVf~J82-@dsP%Sjb z6F%r>MLHl9FKlpVC10TJ(!q_tJMQ%-XMn@4nHj0!(`gG!pC0nnsDo84azeu5_Fm$B zb2PyScGQEp;@aR{1N-VhXjKP~NcWwAO#n28*TG@9BiyHXeDDiU!Q8w^!|DzINYC5@ z;2}I~<1jcoKVKfs?GTeDlJG;F5;Nbj)yc?d1Qt4W`F{!3u=#4>)nvG4(A=NfH5=BI z9bKpRI;M*hvu#m!RkIHAA*z`9zCYJP6 z{{Dk0w?V+8U6?#iQ5&0~MINgVm-tfLObJj+j5~eSoq1yA1l3y~;EClyFPUDOitI(K z<1Z?id-Bk`2*>16tiI1d%Dy~68II1g zod%;?q>QvKuYphPobhSC-YOw_H^9iOHfC(X41GFoB5Ea)`}>`)S06|+RzEXqO9lVq z*6@plbK~7vvM6*s4SKb>8hKK1_t0=Q5IXM}*sw+>^{fd`lKKVLIvvQl*6^lM zzWeK@&$rk8!UGulLNLnU%0U9#4`9_EXEk)cFUiyv^{5Kgdo$lQX1tBN+dW^BB)AzQ zh+7}W_#OHRejNe+4i0~qyhA(*TI1wwuxoD}oJAR%c7>BY!8@U?1t$A3x@?)c@>Zoj zfn)a?Uevr9nrYtSrP3K96Yj?2Pek;)gr7lJf;tVHg43&c?(Bix#j_ z&rTl8*Qp2_#a!L=AYk3n2`trZ57s4!1WS4FZr#->Puy(RVe%Qwu97*xRM@fJAhEK& zAkdmEbPr;h{VU5mzF^e9vW#M3$%}G-PBy-iY<#zb7{|t;d^R>B&QLXuvTI~R8)ecy zaTb$s3>Pzq30;JkminYt?U#5QvHeS0w;xrqYLid2U*@peZ)5X-d@9el%Dwhd#5BvF z7{A!}i^oab)`)a{hywyiyJsyJS5I+35aXtPI@iHCgTXo_AGgZKBfKEZJ9t5Ft#n`# z2{W}ET3i~eWY%lO|1I*I*QlHBGTad=zSg?(BUI%O zDL@YwbIRcFQNPye+6c!DTFKu5iYwyaRAoNij6eM4>E>13Y0%P?UgvZ0nb`MXf8hUj zXa6)PG_0gN%S%d(4nIHHCejr{_np1c&b4oG-PK{!Z4x!y|tKyZBcq9Gb|A ziM`au0{h)Kk7-h8W$r2<{gp&I4?s|Mx$eaIUH(e^R={J$ZbVh8S_a4rOk9eoXF2Lv zDjtFyhnou=6Z)6O(NjG@rbg)ZZtk&R^WXl4w0@)L&S(QEz`TQK-cbue~xNG zz8?NM*T?*IzK9FwE2WQd-X#z>0b)p3)T&2I>PfA?N>U$=J5ELJ1n!tWQ92XgoLC*Y z8rJ2hPJL4o5G%&v=?kPOn4*kbn)w=fH5JFZUdXcQoiOu}%GAHJdHtpq!{5P2sdQ}s zx|A82BQOa}Ef4(}0FIsY?*9p@O=LZM!&9+cbo?HP-#}*A$iiKQDuTW!Hq1_jd6PsC z{z7`QYdVY5QIBLx^CI{mOoPvb4ddc={Gn6jXp<`G@Q*?36ud|4Z#iBeFzM^U8@vqz z@iq*^Ly~szkr0G`33zUigK_>%@#OYcGgF<$rf>RFd_}FbMf3NLn8w>1{armn0=NAnWtvNLC^V zt#xunl(fC$NZTy`qxMR$x8>zLZ}8#_dSrmFkFXD-Z7aXkht|6}5$V zp3L2Ck&@N{neVBE0jx(tSfhBYD__OP;EwYfVrJfjt61>R;dRc0qe2?)6r&0{%7A>4 zx&WH3kX|0^uFf6t^^PXE7!ek&e(lKJfd06Z>!i>*fjO@?;Q6C5#ts%MV8 z7RhM67U_=Z>DVWPJI1t{5a3pvOM>X6fbnkoQN61`Bz39mmIMiVD@o9ho*%M&ug z|K$233pH~6F$2$&yZ(6RhW~)|2XF11?Da<%H0*z3{qdXYIT*2W|MvCA3}pTPx&Ejj zswZtecr@?3oDZ%B^#9EHU?DL(k@;Zmbtic~I1K=gYd-jn*B_&a*Gc2IoKfE;zrE)D zPvy66X!i;6n*&Wdsq5Xpc#ehNsNdufBfbp<6~}NWyWpl|KkP?rHzn0@Q&NwwOr;ya z8*vr5Ue9dMb2b;AgS9?B!pK?AjU@;ZRVD=m4oZyGQSBtueui{%m!eyjzmrvE7dMEi z20_86_v@}N-p|#6|L^hxsL-K=mrJc>+8vH<*u><07;3T`!K-pb$zk zDiaz8SAn0T7}nXZ!(hal^QJsrHTKC^+aHT(#(wyi9PG_`O)KdnS5#0MsjbzFDuer` zeuMSu2pl6um9X$UxSwAhG&d6SHA*wPrGom?eV=g44OJ5qsqpuhY&dJ_@DQH4fBu-% zJZwhg9y&vm%3yqjGUv_ftc>-(Gd2+Byu2RnE%&2v-H~mO`*EEee*UDhb9JqqO7+!1-a%JCFJcUBH2Qhd@#_ml zq!PanCZfDX7_+EsyTYmE++DGt@uW4O#RP~zwX-})$&8P z0S8RbbPL1zmN$4~y40}CWFzM-bb+B=1BVIja$Jjovs&j^ z{@$S;u)UP(ie~*I@qmG=VbM+Rt*PF@1<=8KUn$3+4DD{~UuMTE4Vu+m(t}2v#;cf& zAJurZP{mY&{+@oTcocV?HDw=kFzzysIRWYpZ?T@Kqk1?>beD(z4nk6illdx!LWfGA z;_zt0c2h$UQ@rZu!N5QsvD>;=rN%Tzpo^ikf>(N0qg1e$Q&oe53MdcC=y)9aogC=l zQ;Dk7x9)(tMCx1d4L*F-L4AvO6qFA0sqdn{N}z?$K%_9YlcuC}BW z_v>)8QF{=3CiikEtf-lRViyWn>ERg{N`mqO9md+I|)*7 zz-UNA*lg6oU2z9}A1-Oa3GxWsFL^`H#Qz#N6j%;Blcm(RJTJFv4&Z}&mx9JPff4)o z0j@|5++GA0mgAUmJegBof0?z?183ZE^4c?aR;5;Yx@16koemDS(4YCsk#7Y*fSS2E zQTNKhgaa2U1P?(WC>a4CrUhEw%x}ErPNj3*%A1Gyg5qT)ROXlD1$@C4*4neAvKzor ziL5X5J4w@>P$e4GU&r{bF{a?paDyRnM}pt&AQ08rr1~}fFZ~Qyi9QF!(16pNZFqYpk@R}br z_-iGd0X?)A8N4}-zCxf^3{VXORj&Fs9cZBiIA_2K+ad7?z7D730;*Q>8hJDV|JcKO z8-s_Z`5VGl^5FLCp`aN%5P(4=-&yD(EC~n&A783Ps?z?w@82ap;~T3)b!7BKk`MQR z58v|S2#+=bM{dxf)@>m1?K_vv^ilW~OBn8Y8^00w$|1i|B3Cp0K!89~svJ&+Hf#e| z6xJ}OVVJ|y;TFyo9g&Tm%n6HAGB*Unc-*u6f$`WNLjv$(4sBzu~+lVQq-!`sche#O$Zk}+hMcH{U zDmyRW_>PyK_IVXVq&lxUjQo5pik9zG%FxX&_Ag}U-H@TMMef89jnlj)o{^W~@d4s9 zjES;VyokKvx#Xap_puAFiaQ4C2nLKE1C8P_&~SMS#I7=&qtd_qI0zqY^AMN7hWHzz zs1}3N*9%^tn>?AAgJJU9*yM2vRJXGEcy?Ntk%<|8tV=RcTbJ<$l zno0S=T?{2*ErLey$H) z7X3~-cC}4(D4pB(z$uGOUG8F+t*21Hqt`^n!!}eK5mNw6l%Z)F$^sb?3kgl@-UW z#9)r*pAGU^{xbQoP15nfs~is1OE=2avzJPK7Na41>2YL1>}OF*WuMJn#3zBzmsN`q zC+#*d-=l1Mb=Wb@XR5TPFGd1Zn7O(szaWH>Pg(j4 zf~k|T07Sqg$6_hxf_>J@l0!jib;Hk8-`NS&0KhU?363#yP}&pBz887n@E#jK>5vcb z8c`YHAxQfyJ4gd1J4mxK2J1>`(8R5m@|3e2OOKT@4~}^;pNk*-P_}QmST=-#?5tUQ z$WQ#N8H9{tzsw*%(831&>_<^5?`8p0dcM=GZfD)Ww^Up-#ZO*A6jw`#DaGuApmge} zo1IX_BaE2#E7_F=FgTl7L~0s z%ZUCmd6&qO&mCd~p7HXc`TN{~oj5;)y}=`YQejlN1bdn)7rtd3*!DFqs*Or@ z1+QynKwa+|o3Ag|R$`|OJt>#Q2AP_RbE!)#l{ z-;i#LQLlutRosbZ^vi-(;vLjM{su<>8GSAKk)Fjg)JWz)RR`Ywrcw}Sm+1nRX^QgNwkiFx6 zDtiDDRN2ca*(>u<_I@l*%RvTP++o9o!Z1DUW5{As@TwuHZj39zt4hNzeGu3vnB5I| zZNXcGp$KW)8$eX&e9H}Ub)$)_p#*OgFlmq_anqFY zF~Lg7_c5Ka_ty+ry#)L;pxm_U!#d!!MY>j zF}olM7e*YVZXKmAbIQiQg;+@4V%cidx2F8kB4*DjNiyZ<{c#C#hu9+XXP-3(#gx>Q zw!M`yd6#%kKJmRiRIKzrF?k{fZMS5w>5;?tKNbA za6GdYv|lp-f3&~6Scos}K!4IHw2hHfDpCvl8382&1z1wL^*smM_6Dyt6;Rz$8saIX zA)d(1P485Ur^~o44Br%|A22NHzT{~A{7e8Naq!g&sP0N+Immii2*YX9SO1T_FAt2f zDF1(R^x#Z5Dg_Z1Xrbk3chja#%9S)po3v>fnqG2kHp!-0NV3ZwJ%B=>Ei{B+L{t>i zDC)N&VC0KXFH8ZUfI>mOS`j4NTLTgiOHrV|&u8YD-FM&JhENK>f1G6Ana|Ag%sg|v zbG@@OgU6yh$Es?|__ew#lwVam8qTqIc;D1d7IaSKwvs{5y7zKpr^*O*OzF-!`(?%U z$IUY;?SqGP&1Ab1KNBq!5?I=?aKEgobywi$#_R7xyt;DdB6XFISZwvtxR0ki&c?pF zyB_l#?EJxOw6Y89OT4ZVb$SO_*|zB$Ht)kt=`Xx(7kFGc6;qoiRHD}$?pYSmmdpf-mpCt99*%84WdoaqN|OuS0VHy)E!<* ze{;c(IcS8F^PlVHj=ipC?8b#-H}cKG?p;jKvFmd*Ykb~)HDj-OkteuzK7ezg+4n!z zj2&=vpGfDcUQ~`-nlYZq%g5Hk{F?l{Ll#1_M6vM{pH;9=9(oQmW<}}qr+pUx1rO@| z>^x6M=3A8z5sR5pFgUOv@7gc39(Ip=3DXgbO|HXd9E?r6X0Tw+Iu;H0PO@lxp$qsm zU>rk&`SlC&ZygVZ|ARwy*9>(t8_F+lLmwT`u1`bG@3@`p-Gxt|kKYsEJiCsw*p9#6 zs2pFVfla4seH#<$$8r(qjt<44o7hC>{7coFsfiJrQ<)gCdj$)-vz6@rQafiH{c;D` z7IX)(%6cc+EIb3XiJCK!FpwQiO2#q~7QFK_hm*e@#r z)#ETVO{bYw<5@DOE^#czzcREnKj%G7g*K|4b1c;@-l}F><6b?C4mkN$F~5NIkV($)Pp`P)8L`nG<~j5d8^}paL9=+ zu9VKUL}FH2VAI0wafweQLMVByXB($tK)2+=Z&h6?(#{R6 zbts3`Fyb%1hh@71^X|hE&gi@it$fKJ+0X(X(w29spII;Hnxc-G#?m$VXno2nhFLC9 zRdl{zy5$X=jfdZjd}|WJ?R=2Gm%Pk{=D)lvGATL@Cv{|36u*OWHA?elKh*gE&iz@6 zbZ+Qh{e_C+*CHou=)dA{{5Z*8J{83uMh?IaKG=`O?jGD9>*pLC+&YM6U&X==vnNR` zIKDSJVM{!_ym%mXa(U-V2!AKu(+&NDxOjbV@R;f@CF$U}^5R`$kL@?uDpur!n_|mi z#*IU2-KRu36-K>$YjB%1CUYEQ;DmgY#J|R$Rh=ZR2t=4u zuiJ%Rx5TGF7Ic7a{o1l-*k0SjY)9S5fZ5JPO{xa$X|{tq!cJug>BSwH?NoP7JP&MD z-PkUS34<;L{XGGKU8rEY-tk;?PnVfw$-Ps*~U;^bw!&8X3(7{YN zkA`khF;}v*m4Xo(Ae?i($rH;KGzYxP4mGMuZ@}Q2rznq4yV`sCDopyq9&~@y!_+6-SdaOTz z>FQMNFX~tg-?h{_7EvLNy2lTnE_GyKpX4&CD>9Ei~OQ-QFKu^o@!K^C$95qA9( z*3=p@iSB7NgmoV^#Fm$td)2?4#2WH?e7vGBTviV@TMhY_@_s9R1iev1f-u$aHQC=e z*Kd}i70SDJ?$~BDs{3K!cm27L5Aye-o!&bctq$a)UT?RI(dh9V#hOD@bs`vJZs_LCh+E1zK zy?iXi$2-3iaiQvMSxQ4!y%JWvyIsn`RK01aiMs0jhzznk+#A2zhwgDd+7F@MpaNml>tNOM5Q_ag*fUkVI}vPp)%!Xl>r!I_$;-@DF9BV{!sjjko2}|ys=VKd-%4*(jdx&X`ku5EwL%?Y#Z~K%Hzc~4L4TYf(U?y>Bzgj4 z02vaE$=k3JvR6!gANj*k(VXs6e~^uWF7LcE#2ScMXjdsdO>fa7qs{P=kx}VYuV5N< zHb!jYL0E}1v=alQ;m1ep77LMT43LiI0O@!PkPaI>I(2;X_e|rXZzaY@m8XA;u}0m= zF_MgTq9@8w>4eS)7}MkEu+a*P8(a+$2M;!brBUU@ah?vIGB}F8ZXX;iL)~Y`6@1e< zIQliZV(D0~ehX>ebH{oJhYN|p5vxh2#={Jb7O25QrrD-^h8xR<-`Q_XJPT|eJvh1t zy$U+6EE0bzt;g>84?fSjjMihk>cI*h;?{e6>k&O#Iq25o!}!0BF|EhNWJnB-zRK4y zwd3M+wX%EEe=dY!9~>R8+S_p#k3#EFs{%<3j{Zp&86159UOT>y%F8hgUgT2}q-wys z0oN-$17G{lHgCfNaEUKelrO~JV`zFXbpt9yvds0#wyB&O$vI9qf1^1EQ@hN6xiYm| zFTiyqgR1*L$GZ8dqA#5AMX=f0tp}9%Tk%)ujpUvI5$x|*=KgZwSe(MV;n8SG-hEqe ze0OZ#WNdR(-Qt#)vgM@FE_+Y;gZ&viwiiAKPVT?zu5ypCpKMTLnmtza*WzEG=+3Hs zW*yi*vY&hmofvBR5v2W8YWnN(Uyg@#tm#u!hgtafT4LQ#R$3_h>#z(A2h&d;fQqmC z$*aha=qG>7kwt1v--ee0HT@8*T%nS&AJqM15goe6U6qZ{n^ho*esVuT=_jYbo~fVQ zfMC=6$si*eK|eVcbnGW%ioWn34hwAcZISYRD;}jc>f7&NrqwsI|CV^UAlVJ=3zEQPo#F|3U}9I<%n~6V>E;>K;E>yp65H7wjn3#OqO5 zaz3^_{I{48yL^xF3y1oAEPJ^*0!>*@QR^eTuN;?^<9rByuQ+@C}KI> zDc1RHInILZJ_B3JUSkKNR-nf`&jqFqM41b4C`yWIt zRW!N3h&MV-(ll;P*QcwyaLm)r=mIozTUko# zHiqkIVSm&GOUK&nR`i6b?knB#BOz2(*Ogp$Lh*OaO-gkqBw=4L4(8x;Y+N3|N3pRC zuSV&shwQLg3jVRuRu=Cda39i`9*}tIp z4E)d@7mebaeO4f@5+BJ$;?5;o)&59~db+Sx1WgXsi|LA7wY6WBUCXgvoP#C2=sQyL z%exvUMT@!iS>6>G%Vbm(zgpfofHltFR(5&t+k?(0;_WJ{{(*M8YsuEt<0^{Zh|Gkz z2M&75PxoOVd&$S}~TJiSWI50O4=$;iynA!Q%U@2sXHeH4na6|4!yl?48QfFW4GYI|ip! zbpA_A6PctJf&Y%uMF!y~0})r}1M!7gm_sUx{}q`9Va5(lFF!ppDKdqTA1HaUV~}0E z&J1oi)%Cr|Hcx;MI%{}g$-0MZUORG7*lFwY*gsXRQ<%5@2~}@!nn+hc*X*&_9F5sg zXT>v)^Je*KZrE9YqYJQ}UD5dgQ`J@ROlk3NS={WmkR07v$1goX5@LUKr-Q3WmnrH5qcJV_qiVMZV9iBLxrgPUIs}=p|j+Jv|M+VtXTS)d-_V*Y2 z%kVR_IoSOEu%6dGj%+H&rs;~#H`H=}*I78(rn)nRCj0_aN#}m0#5k%HNpVe02YTp98** zAKc`0=N{Uf+tK;>i`t-E}v4c}bGVvmee$0G0HNSRN+49Sorj+sN2-8QYzKZB{ON!ku@&C!+ zgH+#xxasdJ?`K-~MhQN>Vi#jYuPWAw3ze7?a3;PV3)Y2C%tl#uuf5&VA3p+d@#>b| z_yPon4N3UTAnfHB6pmp-J&oO#{l;}GN8pH`#)fTLslc^&Sn zShaiIho{DJAD+8=in_Y*)L72LW2T_D$i_K7AI6@m?tHqccw6+OdEM0q^*Q*}IqGDv zrl>3Nw#43~$U9g%i7D!Tut`DpEif899 zkZdb{x|+tbMdnu8)bk#%oXY~^QiwV4F@!_&FnSubgg)!~^DDW{xBIfnct1tJtNwQ` zKz0?Lru@};k0HwYxb{}_lO3?5^Rvxwu^$IAac5D9IUg`rMV&k!FNB5O5*`H@;`x9O z;h?AIPy~HGAY{0FOlACZMvmA5T8K@GLZ6Q}PYa-usVAWg6eICHPtW1HMqN*y#QA`T zmA^MAL$Yy5V%Mk(Rfx7^KY9?8y*vIcOeA}T#7H5wE3bFs|E8DBRCUaw5%Wi;U&%3S z`q?r%(yyb62edS*9mP0;0?rd@T9t|U59cjvGQJuvsqeGNi;#+espXuzB>o(}!I_j? zup^gzD*p_9iG%(QO&@P(HeAQhSx~sctmMeQ1}Bm{RJyZ& zZ0yhlozGUEvUJkmA@GBxb`ZzKEgcVAepS}ftLH0re1)q4`xcIHYHHPcjxo-*%TFus z+_LUPjK-hNTYo3wMWkaY*IhB*iXMi*^Yhl<495ldUCo9s!Gb;It6|U#iP<7%y_n0z z#43`a<7yn~OT;V^(=FyCF<_eqWAZ#8s!sb_J zZNtVoGz&E@3LQP5s_}u!oH>)==>GpKa&_m|De?|p)9S2$rJNxCr;-QjezgZgo=11r zy7ah_t(0wk$o>)A2(etSa5-=F9aGskcR5ymH!~}C&aEGdxix3B#ZN>Is_a^Zri@z+ zpI~7F6u%wG!I|o6u_@UeF}&)oWy`CIAJE}dVT!?ZF|ep`(OO4NTleAa=*fs7KXx#F zXFiX2<~~tg{AlcO+<;t-^{~p$Wytqsu9A%fokQ3NmFnuj-lp{Lby%a(Hw9IAUcs$E zSZh%yDRy0kY175->Qi_~X;~3YmX97%*3PQ88V~-edc8)n5S>WCY>yN(Yzn?0MM-6x^qlc6x)2TU-vbRnQ*bmA5pU~XW3je z8S`mO@FqWk3GCLiRm-wU4EJjpzmg?usIoJH7|V(lG`?At^{?vAi{1Q%e&=P&tGZ+8 z&@qE9=KZVND)VOlyRz%-%FbCkvrs-e%kUE8Eu3%O!uhpTSx;7W&d1WwWhk)ATud<5 z1|sf?jWG*HFu#Tg2U@U6DKpU=^d2o(ecY*=D4XZ*0d|9%kgE8P@EF7u(JAYr5G(Jd zIcQ#jnB6=2U$hDN9c#v82N}=8RJ+%@upsdme&3GOgEKlVMSF16;Pga)CY#@)Q|S|% z{BY^`tjgkDc{i1ee|WaC;=0Dz?K?&>uwqZNh>HrpWJv%lQQPRc3MxA|jA<*CCZ%VNiJXNQqJhC0>xnFa+vEAh?6^9E3AFpQ1dB z4cF>ebnM)NClZ6bri`W*lq7>$oQ;~%IS&M-V|mvh04$X%FuFQJ!}d9dg;@6(92WQH zjUB{t4uV3JsLbcf43$zIoDbL4q5;5QqlANsz-VO9BW0=q?JBF^G&VXD1%2?&Em^Tc zE1%j?)m?pX7B;#g!1>E@=cvA;0b=5whAswFha}aZCe3$k%8y=#3Urn_|M)PRe>}gt z{4DU5Em!Zu;88dY8P&S1wmNGUT~WhJ5-$ct`Nb%_Y4R#m;bvR?i-WStYP<@#f($2- zAR0IHr0UK{(ay5^oap{ljgP2DRNPFFO?weE>g@qaJ| zev{%gW4al)EfuL%(?hs)It~vN>s^MS8x|Zl!JLoN4XMvr9p`}N%YgA`@ff@dt03`h z^u?&_4Q1l@&-3_+p(HJTu?GHxIw<=CPd^U%$Xov!X%xBf0hU~YEJyY~Blct?5vD-Hs>R_zw<+_Gbv5@WX( zqV?2K!_iR5dYRfu-mTcz8rT9?_?*TZct}S zK@rwdB8c#7Z4NF47%aoV8Tt4HFpjD)SIxf0t7en!r(8Fi>9*Nd%x$ypM8_xktF-%O z2OdTNVMD-{L3K}QX?lzw>dS2@Ale3fz3s5^y}O6_p5y(tyAYqAwc0d9He%ubvmGXT5qhsArRUHmhfgdS0ZSt?JpXo+0%N zt7lX_SE}b~^}JL)FIUei)U!i9uU60X>UoWNZdA|f)bo1vyg@yC)bmF5yh%O3rk*#e z=Qq{!R`vY0diJX4_tf+I>iI+U+@zkjtLGi+d6#iM*KKBJz0#1qx0`wQJO&=c0}p12lfPYWG) zyoTX$3s&-RlO}B!()KiMKcsCdZO_nlKW*>Pb`Ndy@Ye3Qowje&)=QhZpZ;sKRj_fo zp0=B5yPCE)Xj@I&*=Ry{wA1z#+W3v2v=8MIwQTMcdXv|UWwQrfPit(vymXq!#j&uJ^7?f0}zq3spgCeZc{ZAa0zANKU@ z$fxZKw2h{125s+ShepdB+TNyZ32kxO8fp70ZDHD;q3tT#9;59`wDr^WE!ys-?Z>p; zLEC29zDL``wB1bGGql}6+sm}Ar|oUpE~PCCi~l=9w0(}YX4)pvc0O&Tv@N2ombOaT zytJJ~TRUyjX}f~9lWF?~Z7$mGq3v_DJx$wzw7p4NHf>|Eys~2#c7e1^r0wstmDBbL zZOybjOWP{iw$XMiZ4c9SD{cIZY|EXr-A&uCXxl{FMVx-6J8gq6Z%N#w+YzCdZ3>pcmW!l6fBjFp{3fmxEhj?Pkahwd zXDMeqcHc5C=ODcFyqDNQ5n5R!5qG?l%Kc!NAL-6~DhDBD+6ZmcLNBC+YWFQeRt|H{ zI)x7^TJTlQYG;fk(1$@s2pXZe7_59476t2pPuA~X!OF4r`M3DoOdrl*Iet-!f&Bl9 z^Ieo-jL{eHK}8D_+d!}in#oZKy&4wg*H4)HH$dM7{b#h$Ry~ryY*%Ew-He%|e0ZWH zGw1)v^DBVUSbS88a(_}|%c6yq{9uq-gU~afmD+vF-B&@-A7!zWLeS@q#UlrFXg{nv z)Uqs|^0w9Zl;bs_2y8mDz6-!4DxQ-dE_u$QPZt1FsC*8CVDxFE&kX=iflv8dj+#ZE z2z|B#u!<|6{U8Q?E~C$303nJ_rOiYdAJMKj@CFvp(F7mB!VFhF*>K@uCUI)8`uitRKpU zzh&lo(FLEZSxD3=PUu= zBw0NGgPumPR(O=p*X%r8C13!zl59YDN(opE7?1LC12D7@eHMt15;P<}m(r(4e7;T4 zFFs!(7_jri0XD-?DdYvz?ptoW3gz%6h0akf|c zQ>opzyo+Lr(f+n}(H52kTX~C(4qpSMPKFD8?x9a19w%vc%Q|0teoY?^2R?6nc#14} z9;Ht=9(BeirH-6OZz@`tzTcqos&Np(BLr{4hpp_B1n&VXhxrSFbC9INV2)vqauz}! z<+B3Sfhm86Wd935vOg1i0Kk6fuLMWp!CxCIWg7#viIYW39<-Z8mqTxWR*HiX`f!28 z%E#kO?ap%Mc;sZj>!H6&|9hbm`D}})6z)pV!nWmEQZIz|(?Z2Or_alDcmR(=x>DKN zaKCl|8!XI(R_4h62)KlR9S40@65J)=DrUmH04Kn_hTug2rbPK1gDhn(-b5cZ^~}X@ z5d0N@Wx^KQI!^NUHiB;h&}S3D?Ep_9M5T7$^6*utbPr}NhRdOFYNsgdTNsCu>uvzX zaT$HaOM!L}R01%&70)se`Ho=DgZvpUK z;eKOl6CX&1Qnql;p*s~V3}+o#8w6}5;A_TkzDZIJO>N@hqj&H*H& zi)!s*M_TUfz&pTR!1^5@RJ4%y9fH3?lXpLs6_B@>(Gq*HiDhdj9WDy2f&4KvuU>q@JPhX#)D*6(T9^<#;tOIF1-Ls?Y`x2tfwvC z2V#6XNKVNZ-`@#J@nAszBv^_E~|#lIUbB}G|A}F3sWh3d2A&q z6)hxJx&9IW%j37qw08hl9`6!dg3u_VhdI~>KpEMnTY2ziH4}S+jWmUk! z@tsoI+=0heN9wEhm-}pbw_cFJa+8 zT>0#Pr5ai(4m+9Fat3-P9u!R}&T&V<#$iQPH6CemU0DZ9v{JM%6IIdv8kS3-m1+pI zTPwqjtpR^~bV}2j)udM78rsESU*pC8rZQifKkTb&kNU&yK6-krnxLy991ezEliZW7 zs`g0K*V^if27>Lbnqbs5Cm3sQa!vBMot}^`91BJ1<(ZsFf~&5@7xp)~ssjzF>;;pp zIe}Jxs^c^`>IAyx#M&FvBb`o(AZxR)(ZO0spOwDWK$9y;0a<2Dww6TvVOLqOy*aSL zRUQcYRStqmQ-fyaWUI2RDOHrB$rh7a)gFij5bC8!11O6fITG?kTU?F7SZkB39n=ke zS8K4*7gfX_T32Oqba_}WFLy!wa71g$T^)uzV=2x37KY6BkM|$sutv)4*{?8 zMO?ntu;16T#?|UW@w5cmSC9_bSLcsLfg*c~7`eH0kt?z$67{#aA}ujR?P?0HYG(k* z)x|+2^cq)G*GpHh;UW}N1l|S6M-~MtVwjP*R)$faD#RcEgWla*U2qF zSuAc*A=!du>HAh9qfH^jqJh>xbPaQ^HGnFC_eUiLrIe6g3C6PU>-Wu5fC4HH2bi`w zQfLKy(Zr3pFuz@8S^;0O$_3@B(k9#>nvJwN=xbuR7q}6rxFa3WK%3tM`Gc{jE7xkm2#d*Y#B0(J)|J12@11y;i91^m zm2L9g6{zN z?^`><;#-3HCS*wp++AmgZqco-yo7m^@tyQBLZ%we>pW-0& zDQ+b9+Q&R-a_6w^8JG-FH?d{ z!61tAKqQ1NFmna3E%WLcvWMKmc*Be8&%sHC9Hg%vDyT8Zuwj@X!7xN>G%}2T1__eY zG*b!Ne9Nbmdpwmg@>rzD8L9bdBc3CJ4xx)IQDcvk{IyXp)MJc22)@+c-V_Yih5U_y z=0KxYcMFSylBtV>ddMNwB_#?6CyG)v>0Z2g(S;a$=yB?ZSWK);5GEJ8K|`5^qa$KR zGor>Nnr}obnpBrqoevGhnlg@1J_aw^w%LIdACIAqBbO1em>glLaS$^iCg%JiOe9VH zSn3Z)@cxa6*F;!{`oJa=je>9FC1AMc`lI`VxyHYGWJPacD{X4Rz&x_Z*S;dPz1mYP zHH>N$lafPfDCAYoj6)VH++Z#61=<(4gqy5Tw1rc5Z^R#M$C{6~J!GLx7PAyzIP6=qKPbHmmsTuV zR8?L1z0{>=xbx~3)?kgJG1i8)JXc#Rq85n!7!+_tMM8C{ zB?npVAY;rw#j04X=U!a%XuP;O(1sZTCge=@Qc_HsJjJS8(;oG$)=LMoG~=lz7=}ra zUH;W*FEJ9Cf-Lu2zE<>+F}&Cd0+9$;GftXylFQeO{4k7d{G#)3wG{pPn)$2|)oup%^Zx3sg{AM0-dlS@6)S2|ibQjItmz+Co@I@kbhcA-^la zh8OEp6a@=kNQ5;TRbkJ*zNRLOT!UO?i3C<-dIzbIBjHFQZ@5^Xt4XXq(8#in#IPQ- zf{OzoUjP#5Tx5oswUF~;;JO&oR`52UqQZhzq=+B&y9x91)@Hs~K3C=dmBhwtkCM;g zR5|Qw3akiV87x_lOzsGnTl}lB`qLOdL$1TH1yRlSY$9g%Wx>{1TRW_l%VnMH!ZMy8 zuP~R@@IGQ)V#@xOFM>8U>bfX`xpA{vs<4pSd4RKKsk%687Mc|F;;iJ8CeK2c%8IoI zR(MokaI1B;sn+5(C_%GY6l_O#ub1JFiBgu%pwWb&k_E%(T`;MX6}qau$-f$ra2Y@? zaHu+@wOe|Klw_{xi3%2cklr)yyhU2%zjS`MTMEi>0 zLMbOsoHDU#g;nFLv6vIqX_yNJIAF3)^Y~9GhO!ba#v#gPv01f?`&+YI){@0@iga2m zT_ZV#OFGW78n717>ZdC^saaMSE9O45s!G+=MW=baSkG?oMKDC=$~+Q`CzdR#8f)s{ z#rDUGHEz7qRgD!Da4VLq4~FSb!OvWKqwv#%D}}EEcB(7Y6Au$!&2+xE#q3=|Y!jVv zX@5_F45HPD!%idqZp_pJjcLA?;_qWI!?3xHY3VC1-{2uvx z5aif~eHSo0p2prye7P<86Y>FO&-3ul1AYbD^#csKteZ_;j0tpvSm!keRtwb|}{x?H*-~E*WiQ^^CD{2gX?0eTTsRP;39b z!>rtr!>!SMws<0L(ut0S~>YgS^Etgg>XKP&%0Wx1pLeKf%;s~c#+n6YfMjrHMXY-<#G|?2%&CX0(m3W*nxR} zcPsMcR-_jj5eB|(<@9{V$_n*@?lvo{Z_lnss=3`<$Bj#VljEniUnD2`@`rkU9d@+v_bAp&t#4HkX zwwTpoE)}z0%!|Z~ig|^Y8^yd)%v;6$p_qMQ{zA-$#C$@`?P9(p<}g{OyxtJHoreBD znqz-44;S+oF(-*xAm$lj&JnX#%yY$T60=>*)nZ;P=JjHJP0U^~Zx{0(G4B_1tC&xV z`J9-qi8&dj-L1*G~Oa7bkGW^EBb`Sm` zLnvmxw2%F9?a;SFn>~`>#x!(p@pu1C)3u1a+fBPF;q?f1#wXFH873ZMrV)sPNndCW z^{>yQN8}q4(;1$7P`i}8>GVm(A%}mz19MDbS4O`6J;-OL{jdGMIq=^c_-_vUHwXTk z1OLr||K`Adb09qj4mr-Xth|0gd41vR#igPA#pQLgm(352UtGGlbkXcZWeVlj!4?{e zzx;C!De*3xJr5f-s!QwYyc4`Nb+grSuXWBP+s5>ydDiLgPd$f~c)jPEwaNnfTIEO= zD$6|;E3J+`+%=J5L%vc>+fe-#VDA!&IvpN!rF@*V)X8hg+Q5^EOpP@{0cv{K@|w8rE1dK*`-_B8}n;x`UnZzSNwH}y!w%bf7? zXB-GEE?m2_>hpUyX8-zsd$(uxnkZJfz3m0l(M;*jP9w@2-B1kRK3pwLy`_qD@m__M z>Gj=1NW9S*UqF&vTIbc?Uz4#{D(Vr~=)|uMA_sQqI-l-P=UR zwVb*Z@50^Ox@tKq>|WPmGh(`AHAX%)b(O(3f8zIXR*!W_N0uJi%-0PJ8>yApP81A# zF(mPO8?n;^n`WyUJQWr6!$z{;DzE?3t{hI6O+y$x9-~@Rl>LJlQ6M= zZiN~YQOxc8B1rtC1^b~Y+9c@%`yx#2K*BFqD|Gq9_d$p=5h8zkSD~_UXdi@F9EwF+ z@M1PzT%n45*FFfd%!BcKU7?p{(~ z;aAY;m)j!&j7q&>zv|j`(Z)0LPuE?R>hOm$lN2^$uUxp|B9_js6cRK33Sv_n2C8Y> zt^MSiI~r8_CR`*(>4U! zpCnK_eZBZGcVi2q+nV%2pOtjqmUM3p`~9iGZBKftDS_A5sJ5~)zyYV9*~c+yXb zgB(LiS5-uG+m*wq$CCC{m{NEb`6JkVPUntXH6v-b)E^EKZ`4>N96w$TMCsV09Rm@y za}qz8g4@m7Ejg9pHeh=6(xa)hu{DSdkieTX=C*&rJ`E#l^mv1)IYHa6U^9Lstg})< z!?{f%EIULP&US^k_nl}!kcu&`K*aCAm|jB)Mg7?O3A9Tgbyfml$0)>)p&x#kK)6w0 zD4;^^5y;=h2b-IGYe;i59o3Q$o$1m`mo{Hx3&*B=OA(<5&3;s%jRNSIn4Bu3qgJZZ?ImNgOcIpnso&Ya)$NRqUGySK4FgA8lsR zz8HUfr8ex=25}xrP?gTsJ^Jg)iCI#X7aPm6moBmn!Ni*SjVy1dGIII9k4VelA?#LqHc$dcW+++S?n4caP{+hYFMz}k{E*Wd0B z2O1SM=RDRcS+?Iemqx7nvg_0Y8$VRV@7&ZLUF$`h3e`6cTV4@RBA#cnA~;hi$LgPl z{d3!D@#x1M*PKMi@{=rV6~`NLTQ&m2PHzqptWDV>q5S9wt;C&(p<@xk=;Nce4vzus zNzATW)7B7dwf>Y{(Y~TJ5NRpLuN}exwfES14m?9kNxlq^ZG3br$D^N*jxUniO!ciV zn?hsCd#Pg4Q_CttdYJM->_E zlG@(=diLwh3iaglWDRBaXLaP}L%Ce8j_iS~{EpoItlq5NoZg(F1NyRi4(rYC%jwD9 zmg}w`$n8C_FT3}kzR?}oa2?wL{{F0?+<}~)1Ga&xBe&y#{sXsVhd`9ofxn)tzA^pT zeOSbWOTyNZ-7#t?FXS$9^^WNUB_tXeRbSGV+lR=rYWqfqAkEO&zTBbQ{{4n>OCWP^ zR(?K3ucw5)qk6Lu25gL{FUJ+qak)!+a^1BdNR=~`HGn9QerjyHO{mix_yXW&?8UzA zx@F5q#9ePw@ZjEZs@I_>*zhjk_4E)$`U%ixzYuW^9(K&|N+djZ&7Dc>Z&9h0AX zrKz$I5BU=qZp@DoXex%s_)7?&h{`KvK{B}(K&?(x#P52Ea z{YcW^EBrj1k?|WmQvPki{}bUic%=N+sapQ6!f&wQFVWtK^0Q;6zeM<-6Mln7%HJXU zykvywH`wswryfcXGye_dF|a4*>feWufCn=Y^LHXtlLhnlB2=dnABz36vLEpr!P^D5 z2p$mJAviAhM}qaS>^PMZ*rh_&k9Qn6AF|l}DSs0mqLAE__N)-}O~#Xcz--TscrGuc zJ?oeJdI5V*g%=*;l(f-w=b$AAop6Tgv@Eg1u^eo?eb!8RE7@G+V5zeFk^ZyaEH4Zaz8y^Y_<+beFw%zrx`PM&`uJi9y-$7*@TJL&^}3q^G; z{3(yYHv?yqr&W_D-e-gV4tl;n{9P3lxlT@&0P{08S7m^nQb8xANVj~%P<&eZ-P@H4-A z1siz|*4_zzgExYn<kAO8wx4I;;=Q`r0S*lpLhxGk6(r zrt-^|Fim>xnCb18@O~oU8En#Pr>}vd9g}~X@INX11{;1<3#Ew3Z^y&s$Lk2so*zdb zqnRHUH=msHe(*PoRIA|6@-ny=I8%PO6m_!v?U?B?H}U*S!ZUa(j@jLt@c0`_s;j|I z`3z=M6QDmwPbgyMj~!E<65;=;@EdIS-&Nd6euMu3de%qvdrr{gqTq=6yH2Vj1oQWu zR3{U&{V!t3xJ4V-rEL09=fG_aOs?U|^J>sH*~0rNFw67(=O?9{6Fll)ch|4X8s@T$bbIknCge{XZ{=f2jEQk-^+-hXs|xmvC97n zpfu=wBXq~=3!6yJ`DnGZx z!Kj&DJ7#_j2>(V2&tTFszw4o?41c{s8k3)A2vGf9_zh0*Goerkej6r#Z@u!i#(zPl z$6&+n!n}pb@Y^x@d1e7sq3|1Q_}#QX8Gbt^KhHX#`mXRBZ1{T}@!K)^c}4=&{!WviT3}ekzcUkSAv7Y@Y}KC4{QEokJ0(ZGa9H2zl#>ZjNgvQkKgqx zHDCA*HvH~f?N3a8J0^erYV98peuE8v2Q5%E$ZyBw=UEa|UlD$TNzeM%Lr*BfZ^z{4 z85C5%7k+~cf4}lg^4l@_2ZaAklYYU5KV++~l;4iY&oeKm&OKJ=zrluofEFkkHGbFnKG-|oOi9GB|P_*DKm`mY`vX8ipU$+h5D{g+_FUrP%V4a#rF z{J+4N z(w!G_;W3lt5;Z^z{487)-*C;SGJ9!^#-G?n4+RY+s< zo8QlSCTjT&HvAnndd6?Z8+>(){-dzrlw8qvG$lUGwKn*76%{_&+NCz8`D;i-q4{!=FzJ z6b?@->>J;HA==~;g|9Q~aglb>fXQ5Br5QTWw|BC84 z!94$p>Mg-M2a77_RGl84hedUSV4jObbqcUc+4N(j18;HQ15Zn(4?FO$fw_KAJHqvX zZJ=+m#lIVv^OqwX>-jvxi|WEDy8ak^Kk$0(rJhU`>!ZE@Vtuk>)<<)0%<)rocm^AO zw}eSdemf?=Id5i`@EdISOC0=mOn!5o$|B)6*zmg?{B}%!_hwDdF8l`H3Y;lF?Cl}b zW5+5zztrI!goJWD$1~EX67tX@nEWmqCjZc{wEq<0H+Ug%MtL;33SY@%!wj$I*V^GX z5}v_~mgQTby%YR)O#W@c{|A#E!6W6z`Cv-DF8l_Ml%HqIQT<2w4L1Bkj`q@yDSycp z&402-mxsZIzg~MM(r?G)?-l+lh2LPqU*h1mWAYCO|5t?H;2#5LDo?i~J$B6S@*mO> zjxW&ZG1$n{=a9#a$=@&hrwYHphCkoIZ^z`{Cj2GBZ?NI-aPZqP`D=fx36=`K!G^!q z!EeXp=h=c(tA*cS!*8G8*TB(^mHb;Z|4l}I!G=Giy%Y7pj>%v0s3y2W_zgDv`3`*q6A*sGB{01BTkmG%@WAb-At@(c_{01BTeuw;aOn#n0N%f@g8*KRP z@lk#|CV$_bHUAsJZ?NGn(cX#rWXI$m5`Nz9%KS6f@Vg!Sc1(WPvzp*Y;Wv1s{I$a0 zF8l@?e!IL(za2CF9^t=U_zgDvy;{6P`t6wf?!Rb)tU{gs1co!~kNy2&{B}(K65&5V z_zgDk+vzj$*9w1y@Ehy{Uav({PZOR!{~4YgQyz1U+x-%r!6W7G6M41^zrlvTL}Vgn z{C3RvhlKwf;Wv1s{O;#;1P9NM@(^tJ>$P{HJnfkA_Xz!c!f&wQSBwaQnDX1P;(s1) zP+Ml|_<1%gmEj*yD9LZf(_@qUL|FSo0ff_+7L>(V+Zx zOn&!E%GFx3HPX?b`~Fx9bwd0sHpG{HPKm};(Io*ztg9x>*^{c=uY8?a0H=*I>J z{(%Gk)`4Gh;13*l{Mo7DdmOmZfxQlVsRMt-f$wr)rm{&VRV9ekx=ANZJs$zR9q$Cr zG#_-ms+pFS==x&tCBW;omwGa)3D6(4K2rOdX8L1^4$ol2->bb?b z63uV$!KIny>0`i9G#H*8GrZoo^0wBN>hKIEJ=5dT-U)s?Ccil+^Jd{U*zkuO{B}%! zbAIM4!f&wQ?{M(jG5O8;oJF&>{05Jd-<;dIUib|*{5_8N?O3J%Z<=7c@b?Qg{B8%o z9h2Xj$LT7Q@^tW*IQZ>Y<=>ztXc2yMj;Dz~pA{d9xCRe9CcioF^LN5;u;I7MOMW{h zzc~-Ipj^vuu;H&&u_xoVWAdBxL$4NogAISk!EeXpH|LE$E&K)>{tjB8Xi$DTCV$^s z%G)}wLh6rT(zE{e&;mt+{B}(Kl7A>~t4;U~CO!Fww0DBvj>*rn+o}E_{01BTdRm}p zFn&8GKhJ!pnm$L%Z}2AI_1a54$xnIQv_R2dcy`S2`rlFB*7&(PJcCKE^21S|dIUFu zp6jPPm!2vnnCH_|Z4}IN>ZxuO%=7B0`hZ=^rXT-t;MtX_{@o6|-GR@lN~P~~;B5{} zDeV2l5%aJnOUDznJf{mb`@PQ&Hmum1)Kf2#q)K1W`FIM z1e^V^uNr@ho2W{vHNDxd`gMgn68lYmBK~H7=fi@{{>;||oBfs_3O4&6Pg=n6I}-aD zeS*#YL!8&IE|)j^3AZVK$c28CYKLG~iGtR9g584MHCleNAMFg_gOT56KiMkrH~Y1| zZ|L!!Q2j};*+2E6@SFWj>lfeVYISYah=GwLi=AK*zC{vq2T^YwExovhc*6Cu-OlB z;$j`1+21fnu-UKB0nGe0`wx1>-|R0qXo==G`vb}aoA3RX3GSChm=Rj~P9`76Qwy*fPyoU7^0_rwbXo9}~n3pU^T_CHV4o9}l` zg3b51Ukf(h*N!}2)0^*Q4T8=0uK~g4dsg8Eq(}RGpO){dg3b4ZI|ZBX1-}(+*8g8L z{F^m@-i10mvmWmjY}VJ$5p34S{f7S6ntzR8vwqzT%=%&0qkkp-C0jK8AzmF{ui%M- z&HC?|g3bEvIfBi4tY5HMU%gDQSug#TV6*=Db3?yX$N!XIvp)HT;g|KlvGrO$vwrvm z!Dc+>uu`>rW+u&3e+$ z1iSxYDfK78X1(V-dlJ zYi!mRj%wD}tQTw-Y}Nz5hjx(inECvVTLizN!~5R=G1{+JHGV>{nLq6iZ019wFVgg8 zK69MH9f|o$n_x5F*do}>9}c=$$8Y8XKEY;u|0BU>{QeI^Kd9wf(kk-5sqrrboAL1h zZQ9?Ach3`S#;>;vHsjNsg3b8y{C1J=Z5{rv1)K4oCn({+qx~-jJ{aRO-sePhgJAP} zy><6DA*z9ku z6m0glo-5ewZ*3K9_P1Uk*z9lpvS72n_4|U&_x*bXoA3LN3O3*OpA&4p@4qG3eBaMT zzs&qJ-}lD}HsALr2{zyNPZw;y@7D-6-}ilj&G-GNVDo+dTEXV~{x=1i@B4QOHsAL- zZlHX;&x+~~g3b5+*94pI`|k-h-}ev1ID`D=`@T!C`My70u=&1UDcG!!ohR6=kF^Un z>tk05HtStk~ToB7Na1)KRyt6(#q=@4w@GdB^B!F)>A*M10m4DcI*?-x8I_^*O@3I0&9CHH0= z8`b>go|zd6cUb1$lXC={drmGQJ_x_Jko#Y*5^U~AxtaKo4$IsF^|D}dU(}SC_BZ!Q z-6XhQ?v440;JDzeg3Y}yFAFyJx4bX7R_;NWyHba5?xng>u(`Ktmtb>W)!D0%pNHc6 zs{9^!iD2{l;a0)s_rvQ2o8J%LDcJmec)MWpd(}f%>+sF*Rm%mN-!pjyo8POn3O2u2 zxmvKiEfZ`B zUM9FhFplX_^yYklje^bj4BrrJe!qUVVDo$UKMM|>qT_o-}`@2usJ`Wo%oOr%iLe{Gr{JbBkMBlpD*=cKJggz@AAIfDA?RX^t{31 zKk0I{2BI5BB&pbeYaMun#%K|>TBUK0!S^}vE(bn#t%@%}f2IRp>%h-A@bOoq^0ztg z&mDO5m8tZL9QZp9{5J`3Lm+JPT;;Ll%`N?-55KXTw54t&hjsr+>gywQR0ci;~k zxOiP^c%i|j@Zr~_hIg_9H#+c@ z4t$FPKkmRUIqP<=_)Q0XM`0`1q~`;T6X6}vspLucPt-W!U*y154(xT{r~`L8@XZeV0|)-4#tC`0 zI`Fd&{H6o%a^S4%Qq#Ae1M|*Ily@S&@eb^A;FBD9iUSuq@aYab+kvYb_#6lRq67OJ zIOxEaI`H)le3Jv;>cHQ3;5#)QW$Mqv4m{w%e|PX_cctd<=N$Mn2QGEsB@TSC1Fv)7 zZ#(cN2mYx8|HgqIb>OEQ_|FdfiUXg9n&g2lfSv|D9hzsZ%z&N=T?AbWJq!AD=rf?t zggy)UZ0Hi`Qs~*xWzgl&bD=AttDxsWFMwVGy%c&m^cSJeg+34ZeCP|HFNF3&2cR#4 zz8Ja{x*eK(w=RJWLr0*a&@t$h&~E59=pgiJ=rz!nL$8It0{Tkm4(O|(uZCU+y&if4 z^fl1eLT`lbguV{C3;KHKZs;4JzXaU_eG~Lop}z+Gb?BR+zXAPC=v$y~h5i=wx1qlS z-3$F)=9Z>*mo;?>j-HN8ZHNV0 zn;L>qZHct{R{Ez-nKE@sVk9>@08fcTap>;K@M$>v@w8xM z^=T>ye|X9?cfri!DS^OnK?^U=z-{${SI0Uv5^fZm5r>{r6qve5A2B)ACWZD`*l-b! z&ySqe9t^knTBoiqn&F)>-A)#?yh|5(aX4i1%*SC;y=T#qG226L424wq3_NiTBrh5& zSQ##uj)<#+z9t;>Shoftw;76xmDbeKP^dM4b8m5Hd}QkK#$c0w3Jz+Y%Hu9^B4lK0 zxqqd<6_JLgF2=cF}o@(v;r%AVb;81+kt|j>7Gy6448MmHPEm!tS`ox;+vF=KQbja znORd%fO=KYzA_LFwzuKkS?UW1Sdu*Tf3IG39oJM7=~R1^eBoQ#c-c%a92q_bii-=T zeJWXyj9)Tfrpf?y9BkU#!P?*{sIa|v75gSvl2WKf(0i_@n5}F%j>)w}mMMCa*|`ND zQ|5|kxQ2(NJ>qCI2c!(O`l8Lj@UVsDDK7F%|FjBA1ZeZ(Smu>Dh1%3xPc0-<4Q;u< zA-1BbV` z>d0L=`zZaX(cmT-XS43MLO2eZ4cYMTaZ#bW(EaITMN$C$A{X<3YVW*Ypq+Q;=^M!Q z>i(RHx|!a6)c7T3G_QG~l5$R9bser&Yw<@usjLw6vl~g-{zY1yKZG7!3 zaIHgYt2c3HMB1C_@uWM=v?49Ou)hg|f#|R;c|q}~H1J5qubK?~#(JjLDY2>p4Qi;r z&&C{%*yPU7e732qtiHQ_QoeXqhtj@Ue&nMI#Y7nl^l z4B2WtGwL{jT&%8qSj-Id6qISSfcGw_n^pEnKWL9!axqivg%W!;uPd#MhH*H)cc!>i zRD3$(w6MrNQW#9bs#>)KUhmxMg|kbmajgvQH>{EyGn^%B=G9&^Cr^~DvkNRrpV}19 zNPG8+XHw4U0!($JgfJJ?wyJW=i^)P+EUYn6dji$PBD{I5EEvNT2k;TB?@vKSUu^OI ziC8r75j}9>%tBA$r!qK8#xJjP5#Fk$i>iYw7DF;UmTuTLCdiPmxJ1lP)JHX!1q$vQ!9L0wx!keM7BBWdV!j>S7Y9*60EAUrx2AFajn2b7pmDoxp2G_ z_OBRzbj(26NH682z^e~BZJ1&6eD|$w=OEa;WNYu3+Ro0#hT24YEOaw7|d&$7glp* zf~t}9m+Ea&o*^}mcn@o@(=ye&X=(LtkCA1_W?RkMBU^behUP6L$L(yNS+^QNTZ>hj z&#qtNT<5cmFc|p^Qx}XhuWCvw^#XY(m$V1?YL-FQ;*&r$wftGFr+XJ&lw_~=6p~)i zE)FhPJf{fv0`Jv?a6}EbT6WT-M*ACEFjKcEB7H@q(HHX9aU8;~*WMT`N=d?edmx^o z75*rf;<&n5*B-zP_R-IFis99_)cRHSrpQ)M2-)zFvkiB#`gPO40AKEWEBp~@z;x>| z6J)J{c7NvUmpSNh4FCB`dmJ~5FZM2WW6XmIf$~kAwqdw~`NCok31)nTqfPx%%J*2) zR+{^!;fd80O)}D?tJNoVb~@(@)v)zrjaX;kB2~8c_5pCHb)@lg5bT(>sf<@yTgw4G zM)k$24_Um@?QJiZj&Y{$BKBdjJ)bBnx2}BqR6YqawODFX=KZPlSWh23#a=JEZOl6w zFUGf?kgqWiU6b-|c&4W=U{uu(8|rjUN{SP+t%`+c`P7Rkg|HW)dE6?vX6zY>e%$c* zD%xIN2=j@=%NSgWe5idX3EqnrWN*qOW$d}KS7B_BSr-1ii6#w`9g73yOJ zoFel+D7zxOPUr#Kn^Ky$y{QCvQSbpg;`c^_UWUhZZ-!YWFtg?=yv1nrrg<0D712`c zZLMydISqB(_Rj51>=~Pd^o<$m6X;AIgwrSIp7hzdC;e-dC;gk3Cw&s{Nf)9Z-D#RT zePW;f?Rwg@bgB$10_j3bOOJ7SdW_T4lRZ5>+0!#58;cOmuOyyn>0)@M7qZ|NC+-ga zB>j}CLyMR0i|$hgwRqnJRklxpa;r5c$2g8_4Ep_9oVa%V6K5l4x{)aQ*m8de+lE%? z6(zN@HSCHKwrGFS9om_9cBus=9lv~CRAYM2Ongxbu96L{YUOdbwUQAomVb&f8=Zud zm8s&2)s4ty%tjJpRh2fIyBRF$$wJa&`l=RR%F>2jk@9$C4def{cWv8k+e$Pa(+@CZ z`J%@(QP**g<9J1BANs;YQKZ8YQq&P8Tkh9)4+fxclT4BHrHQ<WsX*4EZ%gpF0)FCNZmYB$jH@a8!pWjhAZBVOpr#7rxpIxo|e1bJWSK4L`a=IRT>*& z_sYdRcaO}N7eX+^F8n!7@&9B6aDlvTYkPWzr+GCww|- zg16uV5SAZczit#z)sNlv6X@0A*4Zihy$s7ByBo`?c9=Z z4!PzP9=N?Xn2^_OXmAD<nsZqEEXQ60p02`sVlqs zmy3ZR4X7w1G@M4s$xVo7NWV;5!|P8OagenhmZ$1>|5%8@IN{+67YwrW&N0Sj0QI#P z0GfL!vau?l<^@#ZX7U~&luxu+@b_`?h6Vynrad==v^&aay#gj9=2!G%@>=D~KfD&I&lN<8Q0=;+*7tiQdUWU)HxY5AL3X9=*ht^yy!)CHaP; z#~ta~*pY0(%Bd@oIdjE3=dN7n(k(c0B|bsm3YmgapUlT2-|@(qf}uw?1UZo1t--*3 zZg3iG@0HhQ-*47=&Z0x@CUss!8z9@A^x(9}=GV~@+B7n#_T@*LefdKWmid1u0uWt^ zs<%wJpsSM2Ym%9z-K{v|Pd_PnHL`1vPy1?6Sxya-l&_4+GRg?C%LCwF`+-EKC#M(B z0$JYHZ{mo8Q*m?rT1w__^Nb=J(R~X|WY@3pTz1xM`hpx_49&5AeYb{*g%hTFk%Tm@ zwW>Q*f}Lo}Yo}6KwxcDvj$Yemax%dgu#Z_B^6)`p-Bcr7^HFjhTGQ#NJr`Ayd@s{< zyum4UnU$5eMT*o}wuJm*%L=sav!J#pD>@U0DZX6M-MpAW#=HXmH}0pF(RvO5Y6`rp zsS$2F!lMPLnbRoCr2wVlj9r%ZvUx0zVRC~D$&E}SSTM#(7^SdZlnmh2o;yB}z+Z{~ z?PG#Yv5bY}+y*O<_($;7S}njR0H3@H2__lE)YwXbaQyE8SQX5>!k^F!4d4|3w~Rj_ zSUPIZ;T6R8EuvW%f#E6FE7Y}%Fwq@Jig*XN%&ek*&eWl9#6N0Ay~4++^yOr8IT`;Y zVi5n^aT$rZx_9nN?#*rFxsaW>7p>sroZ96m;acsy>Wb5`kLp4s$w+-xhZfnoybh#n zU0yp{x-S=-&$hQ9b%3pk?fL6F}qRF}Fu@E3dnvj#HMQj=FD`?A(@RY|J_68dPZvS0MuZdy!HtDKg- zb|u2ty^UqWUaAM%Lp)8*uqb%a3c{q<+4i9UIir0&SUj|u6JtL;TC0?ExgBdm;av)S z&)pAhtx_MZ&jf3)>2FoZwKB?5Vt-US9v{Ek0_`B@bwTq5z2akBi8*`ubCV zq^&+5G0T!OmhfTSh~r<2S+3{U00jn}$0uc!#soAcPx4|P2@lHUaeqbOXZI#ai40O#X zT;mNFDd>6w@wrOzP;!&}j{hBd54R0&%UzJ8TgtV4@q0^b_$Y@O`xyUYJDj4vxPetN?xdEx2oCFiS+DsH7+WOS{KDsD&0Kot`S3stNv z!wiQ4+yIqj7=Ynef>$9Hzj?~2ET>EjIsOTe+jZaDUd$Q8f#8a7G6v|u@awkm6|weq zMg~IG6X8~U+@g;C!GEQnlPkF1hx?8M zaso4ct@!N*8y34%M>dvs!P>~7`{7`dYQ^kxt7`vvowgLm!l&IC)2p%2%|yoLM5t{M z2<7vyzkdinT)&@8!e4;y`xQ2QWH)6c^ZG?g{+K_ITMQ2TMJ-cY)Zhf}Wdu=S&j>dn zMN!VLgnJmu6OQ9TgcQ1igS&)c?kX2iypBlDty_2=OyHbNzD8^K#7yB!UOL$xWHa91 zCAU}Gqn(pe=Q1`;7fr9sF+>BN=mfU7;7mB;93wC(jfZ?KT2X=>UWV}F1V8PUSbx+C z_B7S0m(m5Q0@?ONtA{>vFq0bn+o@sfQD|KB(o5wNyZhi@(AluOH~ni{9a4<8wO5mygsbc%fpif^u0l zDsKy~n-x+RfrDyNz6B2{w5-No4CRDuAD!KTm1;03`mTFOaeHDLmEAF(``g>DCTl#m zR}l=%PX7nvVf8q-4z-3Q&oYojTnF-fCJ$3SIpu^lC9~e=5nylIvDjDW+4wfj^+|15 z@%g60kq+C9wxwbBE-XLVR6eS{l@CQUe{47Q0OqlW%frUHhN^L~vsk$Hi^uh)htuV3 zTFbD$37sNrCq^FEuh|rV2+0coIf2XI+ySwj#Kp~MU0ra3=c__2K0lgrUyB4)b$U z1YVsZn8hk4*FE9^IM6o}Qu6WW(79Vv2)ii$|2kVHsw^iilRSYpew8R+8}(DXL-gZr zvk4c;5~0%~avdAqpHOO6!Pg+1KG8{t6)$3KeESYACZnxLOA&Q(5?;f(9e`}Q|xhwqloTBsEm4v|H&Z@K2}MN>Qdo<2{E3NRWirW z<8zVWS$tC5<1(E^Kp_ZTi+;a@o6z{13}201Bu^Hc^8(` z|HWan1_R2Yc8jRtwpg`p8 zd9p-9)T5kCLvN>{{TLGSxizA&JE@2qM80Dj3L+hwDs9N`!fL+2HnzgpRP`6Q;`!z3 s=JUt#`4GvgWy-^eZ(x#<@>s%)HyTF1$B1DY}1~d?Xz(!31yFoOt0h4Gk1g+*tsa1qs0!kpb zNzG>5YFpddKC};3+fr-$@V3?lYc(Ob8$KEW@@N#SRH>bG(;7aC0V4bU&dj~Ln-9=d zpZBj9y_tLG^URquXU;iuX13@{Pby|bQB*vUh@vzhqHzk9OlAKv>ne*Kn(dmivkEUmfY zNAF$wtJh!M*XXNI)x-5a|5nY@*?(F8 zeD_axC+trA8oR3QxeuOy=-KM_o$HnsW*vC%56Ac4I@(^f@tOCkZ+>XqyZ?D{h-0a4 zr=r|uQkACwvk`k#Nw|E3$)YH|35qgK^h$ZU9H9+4Y=kAe(L0h8Wv`>5k_8On|3kA> zB|0fuzs!cT8 z__Dbs<<8c9_*eBLecu}U-b&w&==U>q&1T!PweOm3BKy8)==IqR(eIT?)sth*wjEC* z8^3;pqEy+E%(hVCHhj})SB4T_z^h{7f1N{ZR&AJpj9>3j6yGj2GWISTYC9IKZQs7g z*!wB!2%>zw5%0*V2FicBTjZ}=g}V8VL`6G#kcEHs1X_HYVjE=j-=+5r@_j44uafW2 z)BC-$r2Rd-Pp6VEQtToTOUS^#9W<9tSZ&j)Mw@Nnv>h}9=yMf)j@&_AGEyt88=J3+ zL?WARRFv9HR^M$XdeZu(X5X0vZz?j4Z9thy>-9U=4u6?u9={P8@cp{gcRAjWW9AB( zBWQipD$*WotF*2;Zo;1fCf^y8XD(G!D>Ln>o?2-wJBSMQc&>2&=i9j%l}yd3{JBlJ z!#nzAf|DP?pX}zB@wc`Wc~2v6yS478_(naK<)I#gS1l0rJuq#n2p{Y@VcmHga6NdS z(t7xfN^AHKHGcyl{#X_99TN)>s2;hiAqrDqqh*zffn9T@p5p)PLGb9bU=xi9whyV zl1{X~tRafiAEQsc?sV$6^>=E9@2uw0>K=Upeeh0xd)jt{etSk}eum&}C#<99XK3QD z%|AaQmG7KpQr_+K?MiPQIKY%2STP1TQU9djM^|Y)-X?I`jFIlaNZ*4|$M9I|MxBpD z^j!L=(SWTJWv}0}_IlqL)ids846VZRP)3r$EWCy7^8H$h73t}Cqr%2$uert;ZEIZ? znvo-Xmfi$0_28}R64`zy+VPI2(h}_J-&qZq@4~n}_yIa_3bOV=diu>3I#Sx#8*XlbpqK5*4Gk^g~d zFUWA_b24l}+8$6wOH(@fZT-WZOp3vfpWF#}IswYbZ2Wlxe;x$ItmznuKRqVU6KL$7 z!=NA3ZqU{_ls$I>8BT*B4+UFUOH1!0$4+k|LDgD+&>FZ?;_XH^TL1WM-$CW$ceoRA z*3uAhEY>3VmYCf5Q^LAS*>P5+g;PUdF zs=^MG1s*mvCKS{)d(ULPRUy({v2>$iJw)Zcjdt7W;gMPV^=uPyxj`*0j{^ztoOWs^ z6bmKYYd70G!%BHTmeT>~-vIJ&?tTgom#$RkzkqXJ$oVws)R3ppu?Uh9I+I>jAw z_KHqAPf>Kxc}xj8kIES06^PlV@by!Pxu&9j!(V*>kzHQ}L81mX{|H&p0g-Yqr4%Ej z$_{=X2;2`G^Iw5b07E@}P@{OZxOp2;>f2@W)zsQnr$l}$a_*QRa3RtOT%+3isM@#i zrz$m8ZCU?nx1ib=-Ta{;s=Y^6>#J$AA&+$)ndJqUWec(#6wNR^_RZTCJy0J!h z+rG54%zs}GJMQ-$V@{3r`u1CWk@IU+)*HTtEw{712fCVm@%;18fBe@2e{<|vJEjSv z6v=FHbOv(AuT6Z7zH}T03Qg`n(MS9>kc;2R5sS1)cs5n<)cnq)L1$k=9h;4NO>j|n86;^cWUjInyaK-XvK+jH1K{L_fV`T9`GnQr=ub*vFh=2Ij z+ik2w^A}^5GgDBtDa0p&>L?NRpRR)6l(8BOY$0;q`q;P8GIQA-p*5F8*4oPW*MPO` zW=E)ELi5L+;5V95TVqi?Zh*Yz)}?H@&2i3J@Sd;NwmO|9`JIG^l%?)cUg9vJhZc0* z&6i&<`kdX2uIi9GLP0fKSvH}$La((RqLhClL@L6>ETE@ApAbACO1DN)ngNuu_A;J|l?#p6M?5QikAN2^FiAVtvT@+ z9Fh%uvEvxpGPcO>J7Zg|vLq0B(9yZtDL=>I^G)WmnRhx`*G{LnaS^YDC9(F*&ZVXN zF;Ee~qA3&`)MFot#)1GXz*Y4|NqXaTJoTKz3Lo)Q2=c!cZ4z=$422xbk|=WM9i>K; zEp_wuoQq(FGR9#>)3FfwOFWgK|E0`pDdqD&B<8HvHxq}*@>oK7YAzH9F(>do-*}J1 z9lc8WWF;2A&A&h;6!gy^(;W*`??|RNoEC4=b`#~A(Jb>)x+zf7>+9AcUTsOlZ9!dZ zf$CVOdQ(s$!K-aINk%cFS%&=@koC{Wx2?XM_<|oV7B-4#Sk4S~AoeclVcOvSlRQ$! zHe#-<-bl@dz*TovUnyqBBCMfArz)XSV1tH&KB)us2R-w}@aZIzd3I?aO`{4tDeize z#=Vp`PK_UHINQOv7}5qfzm1Qn~ZV-TCHol7Fr z?&2j7p{}G!r~|yGEU?}b5Vo2|Q@#+S_E(5ppI~Lsb4j!cd|E&fny=U7y?W(Xy%E-~ zOKMe}XdDcT?~D}%L%baeOuvfsQ8M7S{;TkRIaWQpF#I>ha>)jpo(6bvi*D1t0pAvI zhq&}-rb-#(ayC*(8@s(p&r(z?GeNcPgHQ{Slrf@#XC@EMPf;>|28k}nFJff=tikyy zO6I>!&o5#`e!{;2$tbKa;QL7-LES|Z6DwBPuzj5U~SRF-P zdwFYl*S8_{Tp&G_($|bJ(o6Xz|HNSS)SvcbMTDfqT__B`0O|`R5}E*x5=tZ?jNSla zf}h<2dBUln?2?k&3bK1 zWlD#HrLi*x0{>NtU|KOy8e5kcHOmI#@ZnX#bbxn(6Yb;93C(%stw{HEFYw(cdgTFg zBAIQeA=^WA+DFnN1mKR4vyD27*QTJeiDdg@Qjk1K(LrYiWcxlD(<@`R!he`f07AC+ z*ip{SFH;4;_*Q>o3Mb4s?5pV$!YAjKTqDE?U(GQ{mIEsy$+Cl=x?0b&4_OAbPFb4x z0htAOppFQ7c;+r(+}EA8&E(DUwV6VRci@`5cD@&_uNy zU_vw~F>#c#x~nMb1v>uRB%|Y3i){Q#m~KEn==oURjRb-1RVr?sHu^rn*)(NmG7v}`5xu87yhA5X^2fOy#xDwO(cp+sY{kgL{=fzXiWxx`&s#vc`( zvV@02kW3CifknYZHWuUpg){z|Zb;~?6+AmL z$QIlDMHWX}^^`eNQ6NcHb_B)z#nvbhgb7tM#22$l>$ugfq{z~t!u** zF)-5hfErM~(P`Up7Z9|RR>ivJl@aSpoiz9s>-@L-g8<s7-WUCF?ptc(<6F8UW4>Q_Sw1fUZqghV3vAamQ%ClGxWh`y(G z!}Q2qp3yP}tcP{fZWtB0-fOxAdJeQ=uzJDu8_Ju&^hqxcI(Gp0fgG1VK}|T1v7)1y zEv%%?(XsYw=G>RL)6uf}GGY*fJ^U?d;@`o1N6nn~L0}12$;2jVi!TIY1p64o@`-HL zj1&B00>*)ty7|olRhIAw(nYz>Log+ry)-49ef_BsvxAZ~loIT2UI!}&nkHDPo`MJlD&k1d+?FUU!*~|{c_pLgwkUE6YPaxF7WL)nUqq}8lKPNl_66!6I7*A7W`)7)e3Id5}mGh@3i5T>w z--06MV_Lx3SL!A){4$!1Xi|e@b0tvA+TCLRMaMk!=!PV|?YN*ksz+G6q5k!;7RQ;5 z=`7M{&#FB;+&i*%LsDdu(Flt@@@uusp=bA&d$AMy4D)aklm$z2*Kf<-ZEI^;cP zB9T)5_yXWdXaa+Vo0ardfU4JA!~*+ z85r4b`o-~UL634hn?UQ?uLZ&^;S?yN(0-z8S{#e+58#jtTF{Gy9iZ_V>w8$x%xF+h zW09@Fl0fRc5$R@5oAuRZ1e$rLo3{%7W1$@J5Tib|5SEa{-M$od1^x?I9Rw_}l+28&n!-AP1?0`oVqO@+YOwo% z42WODTMT00TSqs@V4(e^cL@7QXn_5s7jw1{FjolOn)*TZ6N;T4jRhWn5ZJXWnJpMS zVB~IKqS3?ri^ zFbM)I3uFM(6l7)X$b4CRpFn+OGzE(J>+=QW83TQBn}X*!ef&`XuHHJ6^_0 zZH^Mn`lyEGj-*MajooTEWrvlNJ=VYAZ=np?}LxSLNz;qc^sMn}ClWE+FZqB)$C(^QHaJvjv$)G_7FUX)-2Awj{E|KMAaJvlF$zY2NUX($H40>gd zmMY5S%HS>;JSl@78DxzYS==(XR|Xqo@T3g3$zY!h`ecxHsVJ8x1CIzcpLr6v*;L?} z6WII)F}hyW`WUR{3UJe$4ct5_bH6BqP8lc@L`@ko$Q8lnGaPc)rs z$#_!mjK!0N=Sn=+;+c-;1oFi3i@5neR?L6m!N&ZDA)Ds^(OF{t-;SVZpCpK*GB_oJ zv`KSXTcWUx;Lr(|Hy z5EV`p!Nn*33o`2l8Qdm=PQBpJ6Tgj`w_hciSRjK28N4EcUKvciT4Y%vgQsP1NCx(6 zMB42#cv1%YWS~r@G=1Xt(8RBXBNI)0`hY<*Qg8$2JsvlnGCa%i+=u6WJZtbgjAt{R z20TyT`7WLx;&~3wFYx>tPdlFf!SgpfJMc8)3E??{=L0;)@$}+};7OW^d5_1AX9Aup z@Jzvz1L{;vSNyO4)2I9uadZ9(G3md+md6{D9&^47eOr#_K0Np1S%c?IJn!N;hUWyH zGk6sAKN(L7p0Rk+@LY-KT0CK-)0`)H3-T42lAxtvGuCsdi( zn-K7^XEZCfm$JS5ZYms1b$skSE)0g>xkT>w1D>plzyrgNHy)lE4SV)=KSl@ZPh0E! z2=$#SXruVRSG?nqE?$fMUWneL_rYjeD2%qyLH=kHQw>JjWPehKY*-2sq2{wfyWeH+ zZ^INy<2aT~^-%Y10u@>pIpDz5Iv}T))HZG0zHKC zW%u%>9onSuuJ=~ z@bAHZuQZBg5L!a6$ufX96RAR}vPfEBQL38vQBVQLFVN{3 z-=-?sbE&?aKdWahtP&eHh4)gnVBzhcgItkiGOsnVMpn*wLIQvL`=2MQ+~-QFDF=vK-rj5INH#`s}A z(s_CA%YQ)KZ=yt&3=gHXPo>V6j`(%n^gi1uS_iIiR+6 zc|rbcu{K22RPS}n*&R^x0yhLBvr8k{{PnZQPL|9OZt4rQxJ0y=-ZhmfN(Lc})f>MP zjia}r5rPng27`cXfwwfNs{eo@q4TrIY*Zb|M&eUw5SY>@XxAR(VKCpm3nCNDsdu!P zel(t&yP;ZRcL1hMcHGS`9fpazONA4e;B28psrpollAO4K`5eM!%{S z=$`=>X7!U4(;JP!q}?d`o&iX!`l#xS^9dZ!H1S37*MK{)HeM>@$I5u>f(wi#Pn5R& z#-w+~jirMMRb2!0)$9|{HSv#z$q6oP^!lzW?Z{Hsq%C)!%(8rlEd?=N=@6;|^+(|$ zQ40G!_W9Fl3BmAvA4PkF>!)B*Ba247X*cGm%G(Zu7^Iz8)`Ag$iTj&0y@a(LgGwC9 z_7{wA6sXw}r~w9Mz{B!WOC9-X-cMYX`pmlK;zM*5 z>gh_tWLue3HI*ooHgyK=-$dRP?z3VF>2vaNj2RjDX)Zc~o~g0%t48!6J=xgi5cA;$!N1A^MRg%~E#qIv*&u_*W$>g7o|3`SG5}wpoLgn^ zoD8+Wk(vE5t7Ns$`zTpu9-Ls{DtSdLflcCv(9GyPHW7iH(5do z#1XFjHM_{2x9+f~S}!V{p82`oW7c7FLxUtaMM!hB6TK%` zzR^F_GdpXkC32coLiHQKWAUN{MLSA(C2ghvL;QI#4+B=1GqHJej4zWl0J@pfCCcVQ zHbVa+f2P(9Kjj%lQ}LY&r|7H(+3$agaAhGhfnNYk8w8s6x%p^xlvay%Hbvmca9Vy( z)%oE-$8tdPA4d6OZhjEwQW%b4khmU0)H8bN0f<^kh*CZz(2YJ;8|?_M=fb#+sqj6_ ziLE=2*&Qx6uq5OG15~4m8)Ov#EF(})9%BMiXFwi=sp6wx_W_FLvpTR#Y7y)g32n47 z?X?k3$Qm7)S!>|r{EnelfsR#6(n{9ys-Ha9(Yr+%u)h2-mSr$MPbUn0 zHhx}$dL%y|U3J3+`T6z8C3oGUO!XC@bZCD5Gt)xoFW;Obgfn|-)g2_OjsC5eOBG^gn0(0DULg!~;zP{L_WS3l{6+|F>{hrt z^%L#);CvF?TH4pxHlN1s2lubhGZ156|38n!sE+I&vH zof=S=wH!6O`7`GQ*sKRx=y(lR0H3bBlnN~m1FQWbW?2}ZyvdQm9;(ooQgw~#8t`0b zOyAKfFVfIlKn?l}@p6lJQT?+Ankay$h_{=skcEU&^Z{14cx1`(S<3FzgdSMR9#YvG znQwmlH`<_&DVaEpQI$Des*3+;q7GBqiI#s%GM~r{Izp?9Gsnx+u=(THjC84>vW^3P z%RKAoT{8wJDuNZ(0_@^JX@$QlghjaP$4Av7N}L%mM)=fA{RbED(yqHp_z6mXxCLIb zp9~Y;(=htLM_j{3Vk&c~i<#O4;u+@V6`x2-!lo|bD`ezC8QGs4N&hE%if^M0M@(e> zuzFy3dx5!)xwHjW;;+hb8+@D6NwBE4@C3b{!gL{U77Bw&u+XAJ7TLVXA(w@yo$B+x zG!$&DeetkK(EeM-RSbrWhK~AAR+VdDRdMqas7R2eHpn8<;b`b`RF?i>K2jIS0b`Ns zIJ4$PmgERk&(7?X1Nae*?Aex&CYjGV7HQsLa5HS@ooIz61uUCj7eFbjaJDET z%kv`T5or@Bt!%KFE8&mei!L=)PGJd+fJgZ4WgjMfIB0g#7WSWk!W~MdqP!eAjCJ&P z$(3+Js@sd$N;qM?H=J0&hjwrAmin3%_El0zbweZmy$(A1LOU-b)$4?9HI6ef}YK65u!CtF|Y$&Q3m zb6=~56T`+7K)2X;^yZcilScHwsiBh=}8m69I@G_!`GnF-1n-7`#zi`MDOsp+>hwX`Wn)4*w6Q2@@ptb$F1^k0?S(e z73$7%)+#LH#QzV#(+9_ay_Z06(O~2l4U1?cHv236>O$RvNJcv~@c#nP*EpnFf7byc z*ZZ~+I}dc7{Kc5vl_!5uF{J$*{CdR@{CbGMjRAKBXkm!8;>y-hmvHjeCp zh_EjDg^r1S4t;3vcgQ5q^^xS)bfPnzL!fdwTcpiXcvDdyi1k~p2) z(}WrL2fcz(^gFaiIP1x71{RkO;{7$xX2jegc9s~<{&=a`1G1hxk*^G5kOcWD;y zI5uC)#d44WpXK3@*8K~_ce1_sVdcAPeu~5CI=MWGP?>JN%&hP~ze(w?ATM>WF(XOw8 z2;(EdzZRV#BFmz+dnlpoPLpg3D-yRyw%SC8b=EvjcqRmQdO{K$jq3#)HY zGao&QKxwv9?5UrVEd}%F?mo($fZVz9xnJPNz~Dp97vgfi;O5!LU3GhW#;5u3MaHM& zGCu9*!;z6s{ciy3J%sU2#!B->I=+&K&Th-f0ZUC}qasT*5c)t~(JDm4wsUeyNcyfF zg1&Y6m!F-0ib=k$6ylA}AIbRdvcX<3f`0{DJBXz*fUn@d6A4l(-E&g#GtqRB-n5vJ z#80Hd;@d) zCQ?QqMZS9eS+U%|P!s&ZKbo1rFZ_9eU&OedF~6U@aQ~S&&oLW3ul5nNd`DoO4f|){ zWwa^)zZQSK+BnbBkZ-BoI8w1Xaa`OI#gVO8Y+ihiP*bG&anuPhYc%Ktb$V33c45>( zssu`ky7_-#2n6azpN%rI7(XNYodKS1yuG9(arI>8O~oD`Z-sygNw$8swNAmp4Njb4 z&NW%7z|0p;r7Hj?lKRDq6HJEQPQ4_b&n?i5J zDx1L;X&{3|nqD2E7OMV5R2}RrBm57k{!*=LA3?KFbrfq9rBM`gR>eP^-Y}IEg425$ zwGb>A*h;?I^#rm2qFlglV+%DbMhlGwhk)No@T0rvj22GtkMb927wN%j4L+F*@n^^$ zB%%jE2w)!tgiHrQ0RA{X#E1o$7KGfd6FnwF2+LE0d4L^9hEqZKcBPmvzg(JCcwvv2 zf>p|O(4`xHt`m}+|67Nkf1AF4`8HUuPSCzbRKBUS{IMzs;e6&S}ipomEO>i(sXVn_g%L0pR{0DlDUmH1AD&g;n z3d(J;Vmu;}J$ZgF9jW0Kd_o}Mfm>~Sg-p7F&BNJcJ0=dmB&OieaDcF@7&8uHZr3d| z^U7^Ysjcf|iTQeE500j3!5!}b7LS!?Iv^e{^IQpqP}W)|>%>vKu1|pXrKt0tgn#r; zU<&nPZ`6(>Lu7mf$T{cHxEEt(z_DOQ%ys3Cs1VJ)mREK@&d(s@h-cFN|TqCL0$;I z$V9OZCnjsx+ZB(E-vq|zSZ7%?oaO1M^C29M zLHq0^UxHeMpi0M4#1?v=n}0Z#<|fHmo@<%6kG1<}5_D`_WC?cGgV1qd8zcDb@ujOy zO(V##3yu>dRq8KD=D@z^-%rL7kffjH3)2tXZ=xSv(k%&m9Vi~&HS!o@(AkagBPVGH z8H;*jmaM@`J(LjWIVN``OB^J6Xp%m7cf|n&c#3_v(gSPOalHl4$WYR{Oq}<0xmQ8< zf#qSNiV0f=W)@PDnnV;hT_C^LKYw~3WSj-6xt;$8%MIS4itJ60IX$RDqz3Z0i=6xU zBFsFTc1ykiNvB&)J3t*U%(t9wO(3~2;dHC!L8#Tey^KPfWz1zk-Je7lH)C{U$P8pm zS*ZeGfW@Ev8(_d*mkM%Bfd+jmxGKK2U%f({ zS)8BHI{^6mnT5~a1snczCW8Gie$I=j+&=KxNxc2g%H2Z*+2&Qx%4*%0VbopQg()~ zo@i25Mgog1q2y+u7ctgo09W|Gkw=V=Xv+UEbz$SM(n(U69Fo;X1}k5159Uo8X+NUq)p_w~o` zR&31dPlm$~5EuR`8v~VaHdeM4u5B}Urs0C73{!CcN2gwDE?(m1>Ud(aSfTp(`b%k) zQvJ!B7i+NEE8*+(CjFO$uUx6|zyB4@VoRO0J}W$UV7!7y&l}+E#KZiveUISAo&Q*A z<70m;$QkP9q>w@;A78U72@n^M5b&WqVb({nW`Ch2`!wuRY@UVLvjFQvwllE61QEGW z%d6XstHQ{0$>LsusoOaPRRvYwdCP_l8Uk_gkg7bnWrbpkf41r0JqYQcQNnm*-2fE_ zU7EUik?5dqcJ1$0Nar1KA{90h1*c>01A4$<1))pDULSJQ_bwo73Fd3&&3B8Dd3SsW zvL$s-`s~59NndhNiMHPW`|##UIh4}uJD~mEr0NO`-H93w*|5lJI?q07sf!MEV~)w zjSn#{K^U|u{jOB-I~o|UReYuUT^S9;QKvSzvH&uub`18l0?&zo2d2okR)t6gg-d%1 z`$^DUPx05rW98f`wDnWiL4Ta$`3v2#1r+#${7{MqhWLGC>V{A`*w{VxC6f7QXAzUo z&A$t!-M1^lICJaA>8195J2}k zPziVheli8*dLRevyQP`8nH#lu)>xxz#`c#Duvo zgbH6I@qm8|W5%jEK51B| z=j3b9nT!I+&ql$}D8sU}8Wru@)F5Xlk}}B>+kYOpZ2>vD?jN`MT8Ac3K}3 z97%9Q->K39*rl%d$akjCb5mo&+$8TczB8YAvKtFbb6qCyrM@%gJy$mtB+PXsct`rq zK;LOBFwb?FJ)Gh}f6Wa~Tr6B|`dO1-P(|j(g64{B{D?OnLd; z=zy968d}0nU^oVeXSCjK?tYO*l^7??j^sM94w~R^C{D0c$Z7ReV1J?dd-0bfd9c0?M0dflYgoz9^W$F?stC)&1jwa4_f8EFxhz<2Dp% z$KJ(YOG%sW<0PW3M31o)kaZKb6ADgIz+d>2nEphFSf8HF^3pPAW_RJaj1 z5bX9fV?lD42{r93j@XkoOHmttg0%aRW=L-^N$jfqv$+<#c*B# z)5?TE0DG_zJ_WaK1nTLvY6}eyZzDf742binbR2eb*A>7Bq2^r-OFsgY^vQOTJ{VYM zdeV>^kf0`qyiU31nTLvDix}=o1Z6-VZA3rU2eYN za=j;GWKTW~{xq~$-&|pxpGW`-!L48av00iR4A%v0fix$k={9bw*zbioTbR6sp?ha5 zCXdKHnhkd>AVVhUzQP{$54`Sd-DlK?Xeu#OZ0j*00RbGR-9VPM+tu1 zv;m{?u$FLw<2`@5hC6InmhT_x>QuvCOzjDN*rFmH{P29A=LYaY6ZqlzPdrnIALbK3 zJb&JkM*J|J_~H48$4dM#-|R`A(2QHOXa>Sld_=|a?IwL@Y{bWmX8pr)4p)jU|F~2C z%)F(qD<338p&wy%Ofa5UZc9T+>0n-b7uFOIKHW%67ZIz6b!j6uj+8&}P%n%YrP>l9 z4cK~xG*HlMNCTrzg%U(y65+7xuBq1X`kc|2BnW}#K?S7cs zBR~69EpRUDhvXVcYJ(tK-@I{n1TxY#9C-*2Uq6E0Go_DaWUZZlQ=WtfB{dM?_=2E3Fg#5w|k$l~u^LC$!CMjo9sZJT2uF$h%#%@= zU@J-pEF`GtRvJ@aA;BeHb;#Jxfd*g!)%Rqb0;)@+PzCZ;-=0X1wZ+ziX-mdDLo$^7r19xcIns6ISq@Sg50uN#YadCzg^8n>+_#eYVzZMn~pM z^465DOyzErHjFc0f*;NAA(kj4#CnsP=!Ye6@-ZKt&0cdLKMi756W`l|HOtwp>&b38 zjrds51d*iXU!;K#`4{01SG?O;9@I;_wDT;7Mbv|JzlmRi9#u3!0#S%P_CqMkPxIv{ zxD7IYDpS7Sn%(^Ue#!fMEvj&L#)z0G1^CB~A}n4Onj)?o)CmPWmp0aE1I>3d3Bp!g z9lf55NGFl9rTj~{!^SYAKC~2SUK#iOnR;LeSSFoz<)Q;QUMp$2In0$tf2Lwz(v`a{ z!8?0fDtin3!|FW1_Gj)f@1@jqKUCr@Y`3@wdM|ECk|m|}ic07B7Ujab6k}si_^scF z5ap2k9B22m4a0+fP=!X{|?k$WDAtQeqmW6R9>=m z(0&3X&w_a)rgVSuhJc@xok1pNRx(+?@hU^!cx8tX<`NoSB+%7N83S&-veS)M{UhZ} zmVYJx=^4a-iuK(|V-o>}|2);VAq!i$SDl`pWlw+s5{?kmlN-p>1lHu0U^B4?j}Q^oBsk!W4yx> zpEXpjdgPM)eqj5T(yp`jQi5Wl4#mw9iW>XIH0|!|K0W~Q1COh zC-4#1AFNMNeAxJ5h{y&$V5tUt(q2TmARN40xaZ@9obZ7o!1j^nQ(OjjuRMi&v>%C zmvJV9aZ6C0t&k<3m&vs3F?sy+X+7Kus9e zgs}ZW){65j#0D(ob8FW6uj{o!5^jg0XRg1_)z)1g~H9$p11U{d`W0EBlOBaW{ym}t=`Lrj zuc5rKF>WBSDjnO#8r4qJ8yqL^+j)WC5tx}=Wh8R0me1o2YvpUUN=-o zoSj2=Vb%1e!`d^d_5*Y6IgDi)|MD5p+luAc(h8<2fmNyfv*hVnXswYA#+gIiM~FcR zbLci<4*dwnfcu+6zlL2IVc1nuB+C=?7uN^j)Drlx^hLJTeOJ&JIkU&a^ifF6#rOKdP{bZgTUD~))N*iTddsJBU$wB(pC-oL2 zP#8Db*potJ>p(fg33Y#v9P$)o;C^D!q@i*>fLuEBM-UYR^eBlRS{%>tC+S||YTB&! z7v_WtbAcp<%>sYH{%aDDCCu{Nrm?o$|uLl62_<>***=`F0)Z)K(F6>LUek;y;2Vd65qT3EbP9K*u?dlrMCB`0%^`7GOi zpv!kAeNFO?bc|}4Y+jd;eZ7g+f1Ef9tx*qjd5^=cW2smc13IA2!FCYNRrT_3eFp=N z>N?ple-Z3Np3!B+OZojBppl|Jh@bFV%!Azns{^jH_Ak#NgGf64$s*&2MOaPnl?L}Z zA}rdl^{0ltlml*LSTmGx68PvbI`v{N$k>hw7gpEd*+!9Q-);9u4a!c@7 z^5*-F8C!y!u-SiSkbi%t=$O7G_`ObJOYjK!eH?M~L=Akh=m?*7R4^f|1;olpKvKZY zeIK0n*PMbQBVF$VOF?sqMIrx?FMI;!s zfyF~U!!GfDf6*&Q9!AH*$iXjxwPo*xhhO$ye^GOwXjdt}jJOjnNq4^DCeFowi9?_I z?jpdXy*D@i{sGE^rEeF%?mfJsPFj_n&2%7vOtQZ}A(4kY9k_;yrE8mvitRW;XB7K% z8JIu(cmG2R6TMcg5DQc39(`dtBKIV*|C>k)6EOePYi+{k&D62vr#|}^vDnYJ!}=TrRgkznD3lhn<^As8jLOR29k*NaqNC5n{d^=^--F?mH+Q zqx~hR;F=pR*0t%>H9Pfc=V$KKh8#L6wt7at-fX&Z1MW$yz6^k57NyEwq?@#GDpeZ< zLPmrXf<8m&T%R)!d@LX1|pm|Z5wWuAZqj_=w z{e~F^cEJ~fM*m;nGy$Q@SLF&%gqwmoU*Pg08#jLi6Gy1aOHnjR55ig0Eu2Nk{tbSO z9ta~4`h%YMHbSeJ0hic>YJ<;z2A5dj&4;B5SkP)Wm?FcyrUkGR*^05O2P~U;2aEw& zjRyMn5iRH2^;JsJD}F{#|7IaipK20Wr+{SWmgUzpUdV8vO)Q8$iX0K@q$>ADmEYg0o4Y-!YA;?$$?PMwL|W1%Xj z`~g^0*uvaW;-Rxx0cHmi6H@1-V79f_d|0K`T)+wZH)2 z2P+}}dI%cUSIfvFyrC4w>Y(D3;p6~Z$KdbnFIBNEvRH#RhfB+DY5ALW6>)su`zCz6 z4|PGyF4Z=_PjS;xcripzasZ`mKKy!>a08{yzQuNIe8RE3!oSF_i#?)!aUX>B)l#hy zjk~mlGMqev{R53A(RoXN08p$@^wEByhSuRv^u9@eAlnB}Wk&mDP?}>R73%kOinyu20iDM_J_7NrzweJLS+en4Q1|J;W=Q_|Qt+T$isvK9U= zQ&}?ZHR)KBgp%0JJDs1adZ&WM1yx>&W9Er-igVUpIwzl&iu@dwpOcBx6WCXUaSvCC zE3FlxCIQ{PeZKYSwm`mx+}1_AqW>1?GB%pI{-RTukN%Qg?595dEAS|?u|gt%l=okP z=SKLgP{mje8Q0EnDTwjKJxMRmGt7CVTg98 zd~ZYm+Y?^MW*Z2udOFWdyrZOdd4*Uq`msBj&+zvivVXLS#QOJ)-oLLN`|SNg*Dw&+ zHk&2%j-mUPMg2=h|E5s?Py!q$$sJjOAIFGzsLw9ZN&Lc(?4;hqHPIf@{TCPPA^JzQ z*fP2VQqA5CBj29bo)mP7P**%x9 zG!Ywqx?bo%W9Tj@{01~!UgdStYN~=Nmx*z}Sya@C-+$77e|3+zqvBOq@O2-5)RTvE z+rnchjspmK%>cc^#)Uh*8pqTf^rSZKgy*L`|2%i6*W_x<7qy8qk0^ZJ_r;j+01H>dFNgb!?3m!r-t5ys=NQFb(l@8%l=bViNDrHFmv^H&5jx%I z#u0N{Ji{92Pc*rpnw~_0ucn7sCoYgZQk#p5jK;-9SYK6b=AN!s(1!UqYM5)b)-~XR zPT0=jy%0Ri zO4w_QpaV)5ZOq6|d8;_}s_TA=boLUIFp#ZIiFl82DE#q(8FGK+7&|_Ff=9`qB5?E_$xNSycvG)|#P5t*ImBhjKyWb%_9O(8jKI3ph z`A3+K{+dp#(_~l8k#{_R9jiEpy`R5$jU3g3KsFXx{KY0Km<#{v*QpOSAw?aF7Us{b zfM1UDC@q62zIGGZz{1k?B#Jql$GmC3F;Rm?Q{08zs1=MZ5`GZ1`qtadueSQy6X@)y z9$!W`3;pq_NMu0SJ@TUjj;!c7suAH*WLWTK5ek(+wRn`r9&h@l`NRgq*u*k6Sls?sD_j;72BW%wEC^ zsZ9f}>e$Zbh+^C0ifwoE2ILl|)aVT$TewYR+!B{@3$7zWMpo1ry)y-~OTU_9@D==$ zKSR33&|}jR=aY7?MClu!BH!lAp2pw!^UA+O+8mMA|GYBgrt``?Ru;&=$a&>&JaCco z%0EUeVk?@+oi=KneQrJuMippl#0re_$^@N$UU?kq!~7ul?~N}VJ+D0N7?2k|uY4m` zkmw2}_-kDMze4?Afgjdjmu(r?f27S3Y5n_8xkdkDWk03=U%OcUQOltIe;1q01Nu+U z8U06nM*rhW$NCQoOfe8ykG2gwA68-e|?6aSiCL=6vF~@aEkXDD`7Avr! zPu`MCCWuAqsbp2fISSwl9Hif6ko`|>@-ob7AdSpYB>4Gp3fvx|QaEL*Qoxc{;=TaM zokL*Rlu`(@Dh1MNCx7afk2GrXJcu7bqzut2l40P-DNOOx0lFtt5H5QmSDwh_nlFO| zGPq3!5QR{KOa3H*>t6Z_x^73z{j_#h1YN6?<*huq5-vRn_!A{%@j@FttZ-{!v3^u+ ztH68VR&o9eh@ZP9RJffy5BTVJFhteI@VO2Q>Z0e*HoPEkg?ec$=jUt{M1U_kMguCC zvn6`|4D$*8#I_5sFXDci5cFI8i!yw{q{P~S8$I7EI5$A1aBp zi%lvxJh*UhgjU2(HV%=-CKVQ@wg@TA(Yno{pz|0maKYkbead-+jUk5O#a-gKZ;DP< z9)XWQC$7whEV1j$iq7^~39mnBt^1IG>}Tib$N6cniSvJTAm?8j8iMn`{%cf5mt0(Y zSsL3kGsmO-&(_)x=;OGc7tZ@`jKg4_d_jCWz6f+I`+C1WZ9W~{x&P-sK` zNCfoJklxI3-;j0HB72{_+UlO66 z{|X@#uKp(u`nC-LiJbRh{mO~=@AfQ*Z}*o%Pb=)_e4 zh6{NcKlb`SNaFA@HQ+o{il6;FRiy&}!`_Y&fSUE5{E571BhJ6f*L?@n{#5*;&s9p6 zqTEP-yq871Y48&hHxJ2!z&nT0Af#4M$FX^beRQ#Po~m!1m680a-gWQxauGVr)n4eu>CNQ z(0w=frRR3OakkK`a2Sm*1!=POxy}!8TU%>T$qbJY=L6?D-^W=}Tre6`rUmXW0R+At zIkO`{=LDP-e+8=DHvGO5w7YG7XAgD>8*%ZcweFGxA?|;}if~R%lQ${oj40ue;{Fw= z#E}kM?GGp_{WZ-vVC+0Z+9z%ob#~B_#s4}Bs4s7Z7FdsCw2ELLGX(?rbj8m_il11{ z1@kEC1jlYHO@uYyM*G`y_jt6%1tz-k;S?~F+2ZRRzUDTtS@g%`JCm^?G2%QGo`4e! zbRuL7`8L%O-Wn1L@}cSBHX~Ma2uBrtXYiBMt+lzyn>+=0M+`pCt2yE6tVE>K&!{6E zy53E-H4(*=0~~(@FT=Uch<6IOv$&J*riMtQ5IsfOl~|%^T-tfpOsOg*A_A2`IkUlK zUA90KZoCCB3*OKF%giZL7u^4Sb3QFeHqK-dcw8A?< zP9|vYC5Mn_^{}P9^*PBnYPxG{CgA!M6dw*{GN@$bLGzd3EtKHZ{}>~a<5I2l)A2%s zW39t|Bv}50W^S#+J>>Wx?cDl}e_~Xjp?94?C~HwgE#4Qtps}?KHLh0QETGUA(Fb*` z7}SVoq&}kNd7$P(mO>+svCjTiR+J=KQNqJxgeH4+-3@Z+u133EuaR~RAw{=H^e0Tr zgvRACSg<@xq+@QUw~SAEmx#WX;R@Xb^E}+QR^I#XL1m3Wg|S5~uyT^*Awgu>0>t{C zB8HWp`aJk|CC+trdcVX{Zv6sL7@i?f_+_BbUw(=(;yi_ulUmT6H4jvHN_JzH%vQe- z-S|9x_)Pp^C1|K-c$93uSeiLIU3QpgH9VrxIf0B{i?I7AJ9=0q*Uv!=rW*`kB>w!% ze2~WKFP_5BgDR@xn6-X8SbETWA1L(SBhP`8h8B|S2tSEcloGzKHg}Hm`nso$TXW^bxbFw&pyn^{`2UCE~ZsUa>6?nw4dA!_79n?}u{P zbDk2?nv@LVBxLH_$`)J^Y-&&3-^@cWINI#zxQ?n{{K{Iz!^O@sEpBPRYBVn7;|q2#P}*@tmQ zJk42%tTo->&?FMhl0a1FEFXH}re0v;PK-|6Ex35Kollev;ns>{Q$@EfN8}E;q0V*w z77jJ=-xBXH!V|omAIE!GrKN{{cm+Rd2O+cxVvUqQ3v~(fW|Bb5+q{Vl<&nVxC<&k9 zXTB=^wt81iS1A%Awn{>vwYd@j&m?5-Mp8i6sh=~(g zcl8rmkLf~d$`9o1g|MK@t@tSvuNq9wDwO=}>1zd0^;WIz&YFG5+%5>boyM_&*zjF#tDhN1^uZat?HgOpnjliVsOA-NEO>#68c@I}b2 zYp2LzOUFF_*W}j4{6AoU5JGD*;k&ljFgRlajVPW@k*PiL=;&8PlyY7OMn zeKzJyV@18eWLz_aV_77yHt`AH7E7M=Z;TgLrG1sQ=2=Y|{N-@~NLX|O&Rsa4GY)P; z@W(i$kUj3af)gRwBhk%q=gau2pNL%&SRI+IxN0W}p4&+9Y>O;OV>Qxb2*IE{y<5=PXe7&U`qBT|6aqOhsWU) zFZi_4XY$8~Cmi;DFuaURsi|ac3_3qi_?9aqQA5K2yz28d?=qM{oe>kS2B>I<-z+MJ zk7ql#3+P*fkgAFIX75BCqE7Ukvw6n~5D6v$9G{I0;Y%Q-q=>En-taKw9q&6g++*KC zy=xkWKaRI?eGDuf;bh$GHXIR+&dBe{QYz+$zr3fxd4y!vZpba@?Yj#9)#b9cBI=%YSC!iM?~G9m}^>0+a`4qh$j{&}*EY{RSQ zQ;v`~{uNUQY9Ngx$CYTvz(@GYtAz}Fj9B;T5nE+;g(>_F1JB-S?}0hGjpf8rKL9^kXuhFkgd%4RW5kIfB6Yf0()NpdorCcD>>yjU+vUuU~i&K=3B7X z2hv2rrNt5NDSjOl0v%EzGZxHY;Gkzu{(_E~;rA0Go<(dwI~SfG$o;KoEaW@d=Pq8t zKPKGa{4Hv;BxfElci>m)0%_l&JXEj7-xQrm4dlYOfb%aNu+{8ls<#LJ%IH1r39SkU zT$`#je}!?JQC0XV7dBm=!mQ!n!`r`#|H{hBB#Hl-@%YEBb{9u}Yd34%l}P z%5jD-9_v7PKyAR?{pbb8DGuwsLt*_?9M*ez6BUB%?S-&jBCvkzK&)@3V)Im>9ODzP z3(6P@`F9G;UKIIZHYD;-&Nq;MsZ)210R6)sA$=rsYjl18l zLreFacsB`$fz$JI>?Y3|=E)I08aPI*`)J@8-ia-r%}0ZL3weDGaS3wp@{T5BhVF*J z18{K*TdXg&;kedmb-@Dfl>UAi1flod?St-_qr)7AM+0w~i`5fXKYXg|#pwUb-uu8u zSzU?WGnq*;z`zU`FiMmtsA#Z7Bi3}#@^6xeCJY4#n$&~UIyR{co$z%14-$&L2FeDi{1wh_ z)KA&C4R|Tv`-m4)U@_2w#0(??JVUsGQK32T_nof7-EC= zEn*vO$21H?UVx^F{EpNn=<=G4-GYOgYanz|FB@uPtjiY523%R%v3MOGk&+HT0~%^t zKU9Wh0%}?UD!(JOMZ6@`k5Tj2Q0>MDF2e3!-y*(0*G;$T!1Ig@{9n|6Fs}afrevAo z5MzfK)L(cUsn;XSr{bC`c-+=s0XFlA3fK}A;CE!B1Sc!7>>L$HORbe$A!vN&u37s2>DRR6UbqO;P38AL3}OtatI{9#(~cee3+4f_VezNudWit^VS z5-N)v)^;Gvqa2VPXZ*=Xck47FhK&c6p;G`J~I)2*=n@Okap%Z`?!48rc{~e zo0V0sLuE7UZS#e_PgH-8ckCJOmO0%?2r9|{$lS~a#=O-pMIWzryL)|yjQUOLmbH2m z25UER18cikRFhfMCW|C_LQPC2*-w&CrG;qa2n7A=;;v0qq=3R2BI-yPAcizR*OBFB;}g6Qin+OU>`pTUdyjh zzyb}=TUFZ+Qqj;qwDgO{XD&lbL>QPFC^=Yv)76;QKwk(I&n#p3WH_M0r?2C0u-O`H zx5S1S!*Ag0>8bo-^&RS)i{aT&Nw>0ctpq2CoS1mAWh$;qJ3UJst{~SQE$cH1xf(Ea zvg=Xd;-?n49+OGWwY4dzCbRqSoLJ^tx!Mz1HrsPz<%(r?Ph{m%ppZRKZ3K>T?U1?L z^=xw*8x&i+;XQQT5u>Er_3YbL+Z%bWjop#|hNpeyP3#xQx_9LiE()+A!w^P`u_u|U z19;~hcRl;Q)wa*}Ztxuoz?WZYlyq_y)K$r5NiL9-;ONw$94K7%8$i+f#0pPkci=Og z+CzaWHKE6+OrrJiDHHjtej>NEAopg_EFS6;bbD+cg&ccdr^lpeFp=uJgHt^{3lQAb zUzxG&KRq2Q^i|efB!4`S{2r3`+puOZ=>D3_5-B8K=9|~=NF&t-n4GsT3No+V*ENJ! zxs4hwX;G zqP+yH&n%Kr(exf>qJq8iT#wvOpzD|QFYmIrxsLrfKQ))afA3byzQozlWMXSRtH1w2 zzH{Y!k^cUoe9OvJLlMc7HFZ=Tu*M3E9P_}NmiMdJ?5=Xzx2!9kqKggP*d8LaKlGyHb7r&gn$i>fir zcD2RxIFz-zz9FKDaD_E^@|5cl_#&3VEKkewi!isbTiu1xzV!=S2<>hXwu7mB*+tyq z8;eZuBd+v`>xvBF?qcI$0YNov-nuM@Bt7lIA05kH0BkobV?|CGS^c)*u{Cf}b(1Wu zCEPzgQ{_=S~Rf!2Q5&N*P&JwB5A6Mzdt#9d{2CAPjL8%`Wr)Hcmkdftf zzk12cn6mDfuBwkru~?pY&EkHZr-kQDo)36F=CQqQai7OCp2rShScathv!=ZN#n&{Q z!p2{FB5gXq8ACE1dOYMX9^6K=IU;Ja%IAq`LNNren{HyF88EDmkI&2-EpRQahh?I_ zF}_b2-1X9%Bd{h!M`zStSKX;ma!@^1#I$=o6Eg^fXW`<&aEx-Xzggd*-XyLc8*a;b zEBEO_W2P<&+_HYCm<2 z+k9ZCtu5s0?{v4Ndg5f8yX$KtA2j|K>C2?rWHm-y@@zQTsV%LUTKxd2_3lgW!xEb? z*>I@^CBVR?#zFSi;_%6fVufsaOor>AdiU#t<{Qw2Lr`SN8PpiNeR#PD+1583V<_05yMG&Mc({gc=TzNhm&R>$wOZ7T|81mpHqTT+@;Go!ju zS9KQ(7AEVqUkcjc-DOcfWhlw*yL=g(22%fLjp^(lpMxg}muw1oH-^2tuy}boSEy#( zlAzybeZl6e5d2?zHjRR-Gyu6cWw==lE}h)?#U`K#%7qIo`JL=yYbe#N4k zgmQR}FTOG>?9GA*g?a8^UK{^AN<>*a`z&_W>T5f$CRMmL;zDxD1-N-KCzh*`GXw>Y zh|}m6XzH8jq_1rx=^-M;tqa19Ze{@KG=vLhXy)tgg-tt=nc4<)(hEv@{lj%LGU*%Yo^%T8@ebh^w8+@eMI`mzYpb zzcnLsDBh=J6u0}-Yg6^KlN54xLstSyO|#Sbl3ezsw%`!tD(wZ{K_ge@&mm{bpM#0$ zZyLWYnlNbme(y$Vbd#QMLJM-R$60RLdUTR z+1KZ(&ZWAb*!`{E9O1#t=Ha$l-<6ed-RFxV+Drfld!Oail6nV7YoRn zSlUjv`$~cW?@>Po&^f4@1W#IBg(s7=C%dYFzH5j-n9ekdQ8(`dEI48hQ<(2_avKT$ zO!mTOy7oxr&lb!8f1kjgO&N$EG@Zi_4nLD06k95vT;6|8|K#$1JrF;*JjRb)!LF~< zYK{LL+a^@)Z_w}vV#8**xXK>BrVttC{sDO9piEDXNL23}7#grmH@ZEo%Q}t9 z=kiX4r(284ebs%kr)coA)2Ye#snJggVRIy^cNq1rNH{~Uf1{zz>Rb>GOSsrVd3J)3 z|A2iR6B0vnmpXqMAk(U|IhGeQ7rWHI!t)s2tT5*0rB`x_%{AH3FUL2jdzybN!vX=A zdi_4Bh7+-5M#!6RTu%ZdpU4%(+?ltp#yZ$7O|_eXaF?v!$4a0S(`FX4-7MyX(~Eh5 zV(v^W=7q$*4QsntCE0^dMO{!EJci61gG=*CN$E%pg0*dWXY_*Fb&sACSOAc%pI*4^ zrj+_gGD#;%PDg_z*`>Z=CW&K)TvXI|`P4YpnHsBZ9xDCTMC(q^eHJ8s;Q)2=F&ruFHjDRt!TMAOb)@7-pS@J!ii?W)eAGw@gbOPTMSvTo}7tC=Ea`E(@E zrV()l34E&B-^0dzp!WHHx%O@|iLrcwn4Z!4>bGCjP>cl!jmk}^(Qh(l=h|jZ@SyIr z(bX`AW2wb>wa{B!^Ts#xABTOWgq~K7|!J%S<+z}3*Ov7q9FM4Rnfu!l^tD%Xya1Z~-7g#J%#iqnq zR6iFw5n)KZPu-$FWT>{`e3@k&_tvG0p`X(aJY|lnS3gW9*-nzj&1rgrbkh!Ry*{Yir0Nn$UU`egkm_{76=u3# zly<5zGa)K%MZu=DTRgq4NADwi;OucqA^{@eWG~_2N%~70X)(jZq{>rxc#_h3w9RR2 zYlGrLjJ9w@(QuS^Obn_jlk)X4t2^=t*6A{diV*Nh($ILKco5D;`#=PJ{ArEz8KkPZe+E8>tx~3YF@KH+s6c9YxafhLv1ZS^(dGziCC7!WX&mJ_&i%P zL&K^0eLT&}ZMboibo&y`=Q=Ibx8i+4DVmQJx-93rC46&fm z3`(4NEy5?454a8~Gj_*Ni3o98b}tckr+{AJH^HvF#{_wi26;Ci*Dn|bbK%U&RfskOp~18=l+0TT zZzYQmUI^z7rN!aW`RfXowify%R5>6s(VSX(mlTN!$Mc1uHTmaad>9p?5fJDJ5r)$; z94IvksNJpU>o7T{0esF0W5E4bk>jZk39Dbd6!V>KKPE8mwD^a!UoD(3dLbizgu3AB zdoBJiW7g?Q9FcOEvyj(+HeX9X1-oNm0=>@a$;=k4aKkA=&VJswTC`9of-0aq?o)Fk zGMTdLW#&fz`Ad4rNRj@hoaQ8F4?SK$5$1{^1Y7fSHdHsJ+i^ZnQ0Q1`o;$w#2Gdii zgZ_UCReN{iQ9r{?;dQ-|QZeYoE~b!cEH>~W~D*t0Egz$h%Pzo9aaYm%Az3?q$Z za-M&5Rm$-o4n5+D@gdhldLcyiKXdDZlj0N_uMGi)tJ$kh4%8+4sG~LOqg^Zq`F4m(5C~D|n7&UhF z#4s7&5_cG8v42=;23ilMV$h4rwk$bT1cAq|3Z&QH@L9hdj2;4`{5Y@Oi6@=opIt1T zbj)M}->EdF=_^O3F*1gW5!m&43TL_2Vx!QqK3ju7d6m8%{xGeMx$94U*42PyfC))G z#g8CYj(=qa@~<)qZ{^ezVwog-s~XoqtGDA{C6H4Olu_{&#o`Lo(I1?y*=mA0S=BlI z+$%W{2OkW^txE#KjZ&QCH-^Mey!F6AfFPu6jH5`1-FsF~iB z)Jz@(!;yqx){6dGb7%ty*Hc15bWoES4$G~+R2`w20fxg_HR8@aPc#USb50dMf11d@ zsKNGEO%)@4AlogR=J-^;mZ7`WTG$O5wfi^0fH(saHVA$Fft^hv)o@Y~OPv3|B(p&# zF;bB&E2XZDf>UXe)bkc;TW#YoSHpDPOk}8EyhVlE)a$G#$ywB=N*I6Okt`P3r`xNl1Zy-(r#20K~3GGq2ST@6iy{@ltd&LiX42^&owsm)w+t;ZNN>7D-H zlgYJK*!^Vxn=l(J>`ZDdsh*@~(v7Xy0V7ST_htUFDcopLujP>dfxJ*n*t^lEuG}lL zK~q8(W1}jq5HzA=dwN!Lkfd2he~JgTtCoejDzOGlX-%BfkqzaSF;t=J zUIyDP=9g>n75lYWo*n*680w+v#psL$hVnT~K15o3DZGr#F@g7)!%tkQ=k(+Z#e5*l ztWiFzpj@xFbI!5e7MbfU_U?;{#jiNuMY96-Yj?&nWLhjL7JZZ6TGu1L0nx5s*01`b zR!E!0Ppf#Ggc8Z;5CuqKR$4PeYIAxRWOGIsa_iH=IL^rc6&58PwqlFq6NZ+%TgUk< zkxvk9QEN^>i-QWSv9)H%sHkqE17bNf_SOsrucdmId=8gb7Jp0iTYSRg&P7Lur3dSE z!qN_g)S5B$EMcs>XQU(Ow6G1I1t)8dSlpTX{*d2q@r>nt5x+}$cJb`vd4=aXo?@Pl zc`U>K(m!i|f;8K3yRH9UdVlyiUNVMfCSx3lmm&IhsQEQ)xYMK*+vxE6x}}!qt^SF@ zI<_O1GKa2YJ5r{;!0=$odEg1zS?C=TbIpk>2=pE;4)zXlJu($aLk%*!$Kn?5i7m`9 zh{AxVJM!jC6N|$q_h=Z~fzj1P-z1W~b(C#n2N&Opit~!5;a|v1_I*jVZ6MkAnJbv= zHw}asOoN2{3n6k;*r+~#zd3(W_G2cHM$y$}65gXBf87k62V{=wW2H5gSevX8jjEjy z9ot@Ccb~<-GCrr6AQaetMW9T_fSYFK{HlN}D%RkNed;PR)F$wBYQ_k*ADD;`R6u|0SH6;#Oz%1e3{EekLm>n<3@0vA=?P&;-s2xU3q8>ag<&OBTrd znKFMTfq53YS1gsYuYtYsO}_>gxaBEiYg+2G70T8$adDUJ?$k^)&1xnp=NEPR=!%QkCqJlohmFtsL|$NHxIGhCST&oJ_I{|tDS zirsQ}nfqP)Gz%B!Kbo6F(yuP3R7x$aETarCe zVanoHm{|N)ma_0YcU&)gOZjOP3r3dMO|6--*u}1I&6EW$_L(K=S>(b=@m06xFp{|Ch{n@3=u6&(c7S1kK1R%+J z*>#bA<;~JHidPZze&rbFKH8yIybLs!^jh3F9(J$ecM;Dmyx+*LmuDxBmGAHHdo|A# zo_l%zH>{OHaeDuVKR*VN$0(g-j0~Qzt{xSh5yyY2_&=QWOqi4Xat`LAnf& zM4XZonzE!qElWZeTwmK{35=H8OigorET{j*(E*ZAw4z$VIPIL?}H62Jx>q`5>RnhvE$?GmQI)-fvL}bLL z?3D#y)IaKV){LyNm}-PV4w_K8T)aI?`#%XD!Ut70=WEqR^|9r|2T*L2>)YKv^z+p9 zlk_KTt!ikhyAUuW<=PoMc6&{(Pt}qfP_fzj)DL>L&w6M?w4<>PKrdOYg$ukma`^ot z(T)|)MhBlSWl7l3#$0)y#Gm@wEDQ44B&=&REayD#kmSRKM{GFwI&O659m|iSb5V2* zS^kLnf=L0}4(n%TO!vIK?2q(9q6-jlYxK99PK#W?NX0gm?b~HbFm_x*6fHfX@e@3h zi%L$|dz>vDXBD2|a?2<%&XX>8jsoYKSF%KHDD_qrM$76ZtU}(o{NiJg@PfWCa#ibC z2Re`*cxc@4uy35bBkk(gNQonOLVxgI)U|o=;(m%btL}BhKzy?PRKASbYu%=RTaHOz z5b2vxsFTW^Nu(*N-a`k#owc|RnNSi0Y|;~$biTB%31=wD5*^T{O^syAF_9{Sm-q+$ ztvQqp#mT@Oz6st)3@OiG9>-^~$LnxCdOh!Ra9E5f+Kmv*Z$wAP;b;gzq*VmmgZIr$S+z)=Fku zE9bS3NE%U9vGuACIFsPULO3k3dGFiyh$lApyt!(}GOHziy_w6WuKp6E?|N1I4Mv@u z66dTdoWPQNJM)VV6-o_T%Kv>0tZ$*r2+1nMSJ-{(@Ev4dVXvM=P1FJNW1vFqW`O#z zK`NG0zxp!E68}X?(H6N3XeOlbCpmod#Yg9WqWBcSVSIEp@A@jY*78qcThl|MrJmhd za5*@yj>CY28!Yu$V1O#(qjSkNFk}+vISd=vqAXu>2hcmVzsKuek-V@qOlTU6p3~kL zNDvN7g0tuwr6hlDAi2y(YYxe+sWLehkB`2N3Ym(i@^yn$uY}W&zBSF3`sSWmh29YbsR(NyZ@RQg{lS7QbZs=sRRf7c!Vrb&a z%n)BqJlt>xOJX7_7ZhPHVe5_+^)3FYjy1@_jIiA{xZ7N6D>b~=78e#F>8M;h< zgW5Au=q^PUG8NvUwo(%)Wrkc_W&sKXxIxuP7?Q_>k^wQ7{D`i84Z4@r>(0A(T72|E zN{nT4!q{Tmm2@A)_0Bs(!X3dBi+YF{LXbmZaDXy zU8bYj&K5OPM|BQFwOR#w*X4u@Y*a*aacVRH+WSOinQ|0aEEOpgpkh4_4McYp4vG#Q za?4F{QN4cw&`1Qk)dM82-UwzP9aKi7NcMoG<{=bL5DhteJBsX0d(FN~Qd|CAQsX}E zsI<|iMx875v9FVQYJX~Jn@=4qNx;5w))Y<(8>jJ?9b<{3z`+HGCMGMCB0tXOLOmxp z=2Cp)A#z$86@NcDWo6gDdS#w$GLFBriMe=Mx2qYq)@56JnI6j2b!=~fJF+X*oLcyv z&AsZdX#Gf+(nio5%3!`h)$@+eV!R zogF~}V)Rimx10v?b<$U~bp48BYUy8f3A=kp7!^dh9~sI}YoFz(&|Xo&v^uU@M9$pb zh3=U;)d`=BQYZFjNQ+H3^;KemRSwCZ{``F)O@o=1OWQ+z%FlNNUqUFREe|nm;Vf_H z3Aj|dB!0l5e#mbuol`bZVZ?kqYdoD^{A%#{1+GV$C?wdF+ttXguwhtXquk{e0l_^_ zz5G4k)6`L2Ylvqd=&>)f`X3cdEkmetK`cpR_U&g{l9;x=>9z0x{jT;sElF4iq z-=Q)`sLUBEbFV{bb>zCac6GOOX+o*`X1lmHFmD%NA&|}()lx<`vMqS#PKK0vmsz$< zEt>&Cj42WV5)LdzL*xh!a0I?8pse8PY)gfINPI=MTEJ>k5vGsn7CTQBgfViE8&3K&LvNnuMm@ zL29muiPGKE^8U;!{)pWqB#^??b& zH(E_-7pgDAnv3sl9bJFpT2R5o%j#J}tnMA@@?}+fS&1uv{fwYlr{hC!P|s|uj;2ti z3Uwh;uWHGoc7pfdW%4Qr=u@{7lUUa0a#};kVG-n(I9jLcdDWQfFznxcl=Lzwd7Ayh zq+KH#eAsrna)3ppDkiDVx-08k%zteg~cFN9x}wRF z#uv(fa-Ui!u-0pcYn$qF*d=Gn&|5KC_IG@>R?65KBWMH7T5I&U`W7uRiY7|+jLAOL zdy@>-3d%SV{K`a*1STb8-b;;{1V1Bvu8qm$?<=nvT9Mxrx;VVr{_(%5C%*%XQ=v@t z9xt+-{0G1JI|~*%T#q-0<{%IVT#gk%p#Xr7GCnq5Z$4!U9?1NK^^M;;=HKL;X|4{d z-eq}}y*C8~4=sASqs`{d|FzyuI#@&GdIeTRy)TEnFQ6S<=Hp&~%5hS5Z}9i{6nz#t z+{YcO@u*b32ec>@k1^PZ!CVP-9z+vb?%b z&jRo@82*QrB8TS^N5md8A_nuniO&l2v!M3n)i)WHfN1i;hIg>MbQAlP3)rjpU)fZ| zX+NKnNKEX(MC|vm*cseD*>iGL8+Q~8??xLAfF%y2c_!Gd1JqfL5gT4Uz49-QkjmeY zQu%}ZmCrMCpIP})W<;{`-=lgE)oGPaR_~`!P@?i3RQ`Svr!=i|bZX`2vC-2Nzm5{( zfsJzYGE&*7;;_&n$ry*cFW`uzKi3SO?1Gn(k4E`OiyS6lu=ZKulKrFfoz1P}s(49O z`KoK=VtvHhnExB~{u;X1WTV#{dJ24;gDCX%j!;82#2waup^oq0$(K5bT+k#Cz2P_u zjqC=joV<2JBrght_=|p>6OmvveW}K_Go(wPs}b3l)G}hcG!qPT1kFn%f%71kxx|CG zBbVyP*dokH^0`HSItz5d)kVhlrGT*3xDnE6f&c{FO_ylwABA+D<8v*!h*+cGYR z{a+ipZJ5YUP!D&A@72|DYEv1SdiK#Qa-QC*2N*EX^y}(=F-FG zoP@Si*Yq62XPz0EY*o%Dw<<|!mkzW_2<>-#rV!dcPB^Vq{e<==;Ljkmd78Kf2+h4M zh0t>4;}Z#O2-(j{Xv1s!2~C@KaI$f-h0#QZGwH_iX3Spb`elYs-S?PYE(1r_UtE9k zY81In=K1Z<=f$jrm=9*=EiY3QjBr>FCLzz~0%;+ah%xFsE?m+z1xAxTVE61;=_GgH z>KjQ~zhZ)V`bqe93j>RTyet;uj8@r}Sx~?@Ddw|mJ7Q_aI+ANJNe}?cD`UMUXg_cCBA)V4b{ZL|qJVJJ?;PzlkOl<2y0qZQGq;*Kll_*a!2n&cOL}+w$@9|Q?6x_ z)_B*o)qCEPwzl%~-sQfyNpg3mfK}fSm;h-LCVyw(7X^XNz-UbnuC-6=Aqr7+fo&|# zJ<{Dzg!>;@0ug>*pd;jcGF0NYl5yEGc3X&3myTtZtW4(;%CZZoIhvmTB*SSON0ih(bY!B@7##v1nUAvQGAeWBr# z;S%Gc*AgKG#oIYNA_VQ_W$()7;A#01y@0!z&VX3_jG3XH3}(`h2}>7Zo&x5_jeL4t z&#j}@_Y)mMGQGyJBxawQ7qAwt&zO3jX*qssscY?1V1DXX{Wng%*r1Wm$L~XH_IPRFYwJtX>W_a_K5h=&xxUm^f7~x0^8@AUOYQZ? zAC!-Z!0h0T^q5z`e+d}V1H%OTeN4fnSQ*IAkH@a05KN)Ix1|22iGiG%3_73s_PRvN z>pe^Shw437vi2;uCOdSpOhc1XH(?7?`EBgI_iw^B-tEmEQgd}hD6pMvSjgMvX+~wDvG7W zZDu!(PE_`Na;ht87%YzU8QeIsW0Y|_%jOtaJVu%@;=^P2omc= zFPMn}2c&8=p|#dkzbbuK`YQXWS?RCGZ3a@!)#%ahs$X>jM-`cI+nk1Y-5)7>XnwpX zf9JZAUFO|^mxUNl(%VKW`a0}5EKeS*eW7N^!aN4$CV4lunTHc#%D`DeBY@osvd9Q`^tBurcwq~84o2gqZT&=Z-!17R_5i(xqZDA=M%96}-+#<`dG&oeUT{R)S$&brMd=eJ^i`aP|_)~iA zu)AL$>iXry!IpMg#Kg@Lq?3vHy-+3I2cE01ZMoX;ZfE`Ku-c3gmX()5!!RSz7|Sp} zjRhM~&Kg1%8$zJawb;Ha>07cm|2Ma*3;bZl+{FbC-FhyPYJ{XRYsN!T?V-vSLf*Gb zl6otZq}mcB)s`fwc1UV#M$H&sb@p`RHM2}9H?8};?)WxO?OS!Du9mp<^^^GviFKGH zR>Lx$k;pbYnJut~($%kECQ@jveK4)H4bWP9YT0dbl3d3PpHMcLQ%n9ICWO*NUC4qt|@ng;0bEulk((drVT z!4kPfE(4o8v9loXMu!$O_(%}fh`F!&Mdx8>Qh9aQE?NH**P~a`0#C9lgDU|3F zO5Cm~anArH?irxOc6I&Q6iRGAHzkfBU4jzZjmj75Yxh8j?MX^}OIocdal25Wd>RWH z&qaxkA<0ZoBAj#C)_S&muFccajP~(wS9#uE9LRdEE-esm#fJFObYn)DSZJwECv^95Sj^AD7 z*&P@~85va~sV)J0*Oy^ts#yO=&r^3_L{nXxnMJES&8|mpCWZ@n4R5TTRmRLT+iP3u>cx&= zX4Uv@Rm0k4LrIyB?ACEI;nr zye(Ags0yCwt{d&zY~zHFYKCT}g=e^{Lc?5}IeO&};yM&u{I|L`d!DE=-l=gf&g+&V z-l{i$TUFq7R52-lxT-flsv3qOi4o`ptZVbUG{99E+p6B|loVCNdaK_2uqx!qk5`4} zrBw}Cp0>q8#lUlwaZ6g2r+ryw;JhB2)jy&tZVL?I=9SbWHdN4?Ud2Jc2$-4JFsb13 zw5pITm9=J16G7-EE{YI@N3~%o;Fula8i@DxC-_4 z`^wd;NS=wSpq;Ci5awFDmE7g(B;lq6%dk|9Z+30&=B6X(mjqWN_JTS>XEDgaExnmJ zBGMD7SY%vBvZ+tCsIIk^u{Ak_m=z;e;Me}I7v3t7b z^;&1d{#dk22Yvmc@XWZUt=2X@mhO2yV7=LMgy>n1^+j?XyV zsQKUNOGf@zWd0BOBGz}!3b~A1fg}dpA{A)fcEJr8*fcvFbw4 z$NoA>^+ixIka)KmM?6^cNvJ9|tLTKA?^RFB`HlFd$p(1|5FM8!5Oz3;F1v{tlbof% z-N2}*@O?O z8zSDmNK?nQUS5)G5 z22a^*^TYOQ!dZ{-7gGb_cO^V6fjO7)x_mZw42>*$@lau8RB)S}EUVs(MkqR^2M{(v zdkXqINUgbIM(so;4CKCcz9v;UAy7VbDb0y^74m)PU|zY}2z zL^#NIz6$=~Afu5QM`ZqshZc8<60gvzHdz4Lv1;=x8W9vt$hAM`jUI7FY=h`bkHnct z;&`amD9J7_o2y1}4jHjkR8aAu()@=H82^5l?;%=9=nydrr zlP|fikWIvKtkk>rdELyPi6P!U`aUl`n_di0t81PZlS=@$PfTAjQ1tZLpFT|vDn(t@ znP7nC%K0pKm%+){TK!eNt^UQL{iqkg?{ZWn%bcupes(*ogv|O3F_cjwc!ew=r4YzZ zM)%L4T#mJ(2S_4jP{5@{#&q24Ch=;gJ6A?+7DnrAYXLlm)*)wdF;1CH%e*9i7&Ma0t6VwFqL zyX3@$Q;~A@ibj0a-jn{z&81V$>#U?tBuXBNeOsr?jcp}Qu0B5B9;s}Lc-tT@)}xAw z#jrQ)Gcl4fV5GdUY!(j(fTE`pymr7tKa*n%!AsbWLXPf;y0k3mg+ zON8b>Ks=est9F~bYDPb=I_^1FU<@oy!E}3I1b>-WstT+D+hDeJbRxxYog!0Gz@ZX2 zh=UCt%F-f7$JRL82G{1I3}IO9Cc`QPotM9_s$hv7=D1)o+tU7I_qLPZ(j8B?%dAFAZk{W{kpUn6<` zKG)_yhAR6s^ZF2@z#y%#s=&dBG(2dLFrbayaO*G#Rn5v?HBG1JZtk?(wiye$nZxnu z1-~ko+bJyUuuR$ttf~+%JB&ad5L}ykC}ws5iC-ThCNzgF$39Q7cWEnw-AaRlX}`2!*r6uxt_**f5h;VNeKidc<*P(U9O&lYR|%ZKTPnMy!TSF zumrbq~(C$D$U^d&}bK zMAcuZ`7#a$b`OtQO;`eC?SE-HAIy9I?o8f0YTuJsBG1ZuM`!Kf?!cY_-aDEdh4)?! z@R|$H!Fzv+NJu2AdGBaH*FDMPy4_LxJJI>?^d?JrC8>sbF5NN!yG#wO?r#~G|d!l%bZHk)wsrc*D{ONIUZ4Q!;%(wHU1mRELC=4xlE5V=c zmAE8-dTrR*ii1z#Pet1zYE7WgWxOiMn)eThF8b5{!sy6gvm?QuQgjM`Dmw(zDqsh- z-ldK(bos8i5JN#O-E*RTvkU8PG$-oa1o@zO^MCVJqD~KKp7cXw!CN$IMky`wyy<%MnlpLQnM=TVf+vm6|I_}(UBzeeq+6)C z$&+s4O?cAiV4jpa3zq0iN0I^_O7Nr?GKofQ6{1a2uCCHEDs2)5QnRE{drLn{^iYx| zJ>pXzKzqWH0)-^x4%?5w)CftM9O)5Zd>%AY1-Iu4K;cM#7GpCMwVCQGjqic-lzJ}RPI&CUlhaOUN4NMKOo$z zs0^9x>#yi%8WPK@z9WT$bukGD*IxTXf`k2@aIgoZBOlZKl;B{6UEM`zzYl$fy*iPY z(G;fkD>|LY!T!cZpVe+)L_`-nPHUOaH2-?B$(u>*g`FJ^XO@`juFw;Ihr07Y8smMu zpLcb^yPAyagTNeMT(4SW4h*(um0dUeN$=BSa%#%ZlT&5aqh=WQFoaqXg1ECX1OFD0cjPnSq1oTcxz%|HI6{iD7j6 zU&jn=CCdOa(5a^-5x)KXnSn~Pq;oO@Hxl2^3|x^&tOahfrB+(t2C;rhX5b?x#{Wl| zff6TD?S#NhWSyx3H@(873fvy@M+anU)go-WEn4VKE`Oy&?$5x{goG{VjTUA{V{B;O zl}X`znY|-EHnExbrWcW$%!}UcNYnny$(G#b+TUxAWkoyo7qa1JSrK?KVVDM_Yr#XG znn4jKkY^L14M_*b|7#hPKQNsn7?cRF&`p9tISFr>%Ag$8--8&G0|fm&7?dBDne(s+ z&HnBT%7e_|{|yFZ2HE~HgYsW2d8GP(n?ae#?(wf+P`Wb`oP}mkMrls;uV7HNkX;y* zpCrM|Q@b(1z^wDXkU^jx`^MT%=-rv&f4=g&1M0(if@?rd77^0aulQfTfUI zJ~cG<~iZBm_(y%Z@Dctj&2qiWa)0GOh;$D4{1f^rf5Z;_T%86c!t$@w-ixhl_V0kKsq z0ysxcVOkwsSTI5#=*MoMIk7?jd74*^EmJ30+(l%GNRNAri7ZrqfG9y1N%O=X%uc-_8(GnGE{{Y z+jS)hDXcJ~CYO_}wv}I^@I%k?TE<*br6NZN3| zqRymjx@M05!a4roa{@V4!%7)3x_^h2GOh5I2EEJ6IVhfG3Hr>?V(Na1zcNX_J%t&G za{-XRxd2GuTp)vU0jzpK{Wk;Ir2d=ELH$<<^erEm)W4=Vjn#OI_c59 zW-ck%_tyJVk8E|9=W_BUnZ8Wrf;UdxDR=n-S0aGFEDAi?gf5yOlD$O}9MPE~HUf%I ziA7zpYLM+ykMr7U#~c@Yweo+DHD+eEUQF_Tvsm3&qSq4RgWErKJ0?;`vmO5msR7Jv z%5{bpjC>GmL$#)fBv=OPZ_`8?5Ut!~HcR}a7|SQpEZLY#)7FXLAlbC5Xximbibyn# z0#0jNH>`7_ZH>J4x9y4VN_BGk+xDef``bpZ%0wqBO~%K;-;L{Oarnpdc->Y%76R0I zGFAkCcdTmz9n;fd*HLz&?CO3q>SULg9Yug)3VO(i-KY&TpNq7&l7u5qRAksIk8k$R zztO_z^MCF}F-_vX(9<0F2h<57hxcE=J|x{i2li}Ff9Td&aet_MPcoxo*QSPk9jS(7 zh+RA=)DcbZ<#J&x@r$VAg5d8?b-h7-dRj2xxl>-eZntYKV?fNP^t8DB)*@gG66QQc zq)34sJ}tyi0dyOneY!K<0>i;_7+r8Qa`?vGa5S}<`SJI57RAcni{!r{B9`d^>kPwt z;w77icRF1hV4<*bg6y8=+AH%oSUTF{J<4D~xy@R%SM_*%ae8{x??57AspoC)y}dUF z_D8)(StK|{gI$hh$80EBG{l$q9W`$CCpLm~%Acj~BWX>pe;BuD-#0@)%5Q4u5tExq z_8~z&fy=mFg4rUWo%#L4LIi%Iw6Gb>aFUBpOb)p0_+aJuc71|3@(|sVG{C4 zh?)B3XfYF*%-=aLf8R`T)aZ4TzY5}-LU@-#$GI4v>F%Cpw|^L4uhNZ8Ll)Y5n$!Hk z1HAezzJtZ~w4P?G8Ssy004eNdz&FhRM^CfE41kg)i&&))ro_nL*zj0;J{NyG-PcT) zo8d-=ttk=WNQUfHi4c1-q*>V#L1_}i>7k=prR$*aEreiX5)y0g*=FU+H&=gdcDj4E z*|kylV6oHDv(1rwxA$ywC*RY0w&kJ}?sW`VNY#?VY>GL|E;WallVK)HNYG)6T_W|h z20Kp$+tNbT*r>$kpNF-?x+O_2e&AlR&|?hN+#AKtgkQ2>s^dP0U6@G!`(T?LtG_0! zSg?)T45TnhvYHR1=R4LM=!{z}-1U@dAvV#Z0n1v7EQu%g@1Ig=@h>!vsKfV zlgb4Q(&zPuxfhVc3mDe9Xz4Z=Wc|9Dt(4y}E!ca}sw1&X!};rb2ndxN9RJ+r`q+)cMZLMCl^slc%A^B>FMUYws5_ZwDk{2G@uQa@4B|@O0Jma9hkc}c zeEk~p<97n*40|%?|Qsb{#eu zwt_pcoRS#b;Uas5r+ax(qfi$wX!=V@OT|e$dF5q>e}db% zbwZZ0YJwBh|Gm`a)CvdQiXN_phFx1OyNB+zF3UM8s!~FSMvTH-d$UMpSFCskrC{&hgaA` znc+G+LAK>1KX$Di5$tk=S2(I%Z@a>Ej$=FMcD#nTw*1cK3jTukD%bs`N5dh%En`(Zm`Wk4(K3$N%i;(rmYeGpvvN`Wh%{cs^K z_p0+gcHIxY+~F0ptPXs+W6HJVz?rx`a5mg>d#ka;>W+7s-4qzz+?5vmtu1)mvFxgk ze-xkaZHe7rv~H1(qpOxVnLBN5SVi7-E7>N5+a#XfTjh5@VGdp<@r>WgeU?lvI;|_R za>og{>x$Ck0#&PqzN;TPxb9D@Q(5IcR%@En;a~exZ7|aWcUYx{tyYO$*B=XvpHb%b zcpm3@lxHo^Djq-2Jv_#&ZypTIdh8&-ieJU=A$||>+s$t`zeo8!%5N{fz5Mp^%NAS2 zC>C3{tv7)VBQA|@=h@HGtzl2V3QfxfX|XYD;N5I}B1G(&reXwiB-4id*Yt%~74#)K zVZuNs4FB`TKkB30`EzJN{8$7`+j#|6vQL;{q)+msPZpNyK9R&5s(F8u=LMeig|_i~ z*A>}>1Y8hO!V1dTks?4S=Ym5Ora?` zfbF0{Zk}wOT%L(MlX-67xrGN@=YZ=RezW<_<~NJqEPmbmO1zU_C%+DU9sJt)wGZwa z6GwLf?;f62JR3CZM1K_8z(7i0=xh343ZY5!LbxXs)tf!RltMYet;2D@)6X2R=fG;lIjg zrc3<8jWMC~nOT`vZw`FSZPf!dze@(19XV0=JD%aAwW zwaJmcTRnUu+fPebd_`7#1vZLA)q90oR=5oIy_`KHv~lNQ&eVxp+I;-P&mjwoBDT_k zomE&&@;Y0mO<)azH<%W?CstD6Cfs!0{D7yuzOMC zVEV+OlKEehaI3{jr;a7OFp;mVAEjO zIO>F1%bJE;=_}@1VeJsl_TBk3;4CnAD0AQWjJ&gjnoG;oRd6N-yUs)~OE}Eb!iqxOx2Y8_Igz^KN|c?`7@r(9W|rmfBg?`p$J;;w}hl&DQxK4Qgo%{{)QD+5!L z6T-cPH#g+%6xK;2vwD8O~0NC?@bEVyLY=uK*n-ItiFJ;rX)m)%ZL6aOx_t)8MJDH`s@9i_b+!ybZ z+M3kMt+KN6JB=yQJ}zm2BG-H?-iP)6w@)*2kHS>~R+H$TrIV)H?=&D=no!vr@+8n< zvUDa;5^3gsgerkGH`Y;COQ_VYzQ9*#lYF7`qPH7mDo;`b93CAU7^%j}Hs>Jd^5TN!y&Ud{O0c(me1hMHTRfl=~6SUQD z-wSieG#m}vzWgSikKs*Q#R^7Z-@l+(k11$E+Qqg6+8r?F%G>|pPy2bj|Nru*3m1M8 ze=4zOIIG{3QNVpu@lPr%muWr}3w{4(H@g6ENlg zYAVllJd=1P@Z|7h@i=+lY5orUsT5|!rO``yR`G0*kQAOY^?fjp^SAJ)M=PXU&7VHY z>pA$-Ug|<$Na76+{!HST&y(aS&&r=l>QBd?YPd;Q{aoB9@uvyc&r!rCo<^P~o;IF# zo(`TE4}J4@;7_G6BW}Nq{^rTynatDQAOD9x{U6~^=eAlqVN2D1guN9a#0gIy;$xu> zHVyHqyafm)L?}`*O*}*piwRS0J~C-Q^qYS`6ebI)8LdR%5fs~<>FPbon$F* zTY%DVNX4Fuler$Y@tMZ=dE2UUKA5R?kR`T9z3>Cc`9Q9E7cP^R^O4`JX#iP(8x~K0 zfjnKEv|1IAFt(G>yPlRn4ptv7en#Fj4|n4tBt_i6SJ#tQIo49wfXLxo%1S;}L1D^6 z(McH_GB8UQElMOC5xj904UU7?&ychwwiI)CfyMDD5~`k_W7g;P>X#8jaHQdb9T&-; zTp$$5R#_t9cO;<*%(B@cs9!xQU-8k4Km+pFQhPjhL7Cc_LugkExwJJpn)|jv2#kwb z`iRAXM`-9kZq?D4AA^$thDGF12tLJWG!jK6opSsedKba>j^hrU*XF>u(w>r#K3d zyQ5Q#;R-5b562x`w-^wQ?+tkm%H5Km12hq)MpCInuqalecRo+js+Xw-iW;>CgQu*4 ziJUD>mGcrbZ7! zs)I=mf)l-CwBk>uYaObH!pw6X zHHxMrj+caCEf4OAgR3m{I{UR&ivU$lsB>6r%-d7w4EhVo)K@PPWyoID1{Ig7D~a`~ zBL1Re+R*f1IuJ12y*kI@A0A(kqk1nSrYc7a4CBpP-^ZkT9RET0+y*g{nwDYBKA~NQ zYyNG9EvvyyxJ4(NF`?eoAnMdYFq^KX)g7VAPOh?EA{`{{ELWSsve8{WPYiH7)QeC& z^oZ5E`!x1*lB0LDu6RM^LCzwJRRPUyp%sQe`;9=;6mf{lq;9cw$E?LZfXj8T`go?P z%);Vp7J9E2sMgv2IB`JB{X%OakSziNaFqYXu>c0LR!o4v;{FkkVvS|4dSfIA6eGL- zmj}|U+{6V`*UwHKD|9-oG~<1Lx>1@POMgkb2Pioz&cZ*S;)!_w7i3T4?Pj)^;#${B zgr{S9y3v9?Ft&|Y@_1w`VZQkF?6mvTY#$J@F}vM;WuZN2#Hug?I;$f-+k-SX54}r(anenXerkxxxLVE5tU#^ z+x2sq;RI>2-;&LyLwy$k4`@@qn+5HcQc~AiNmc61%{z%vyjF1C^`IHzjvZoH_ixy0 zG}WX_<-~Ok1FTpm{W#Ulm+@7A$M0(jYO^>Fl)ejGt&4V1w4R?XNtFC{aes%O&$_?_ z(g%c=GIhl`nis0=V=_wFBEHBpLV1G*p1!`)8sqL}wjO$mB&QIZ%q}?helCb$R-Kh-GB-$~cFzTLd!_V9F3F#|uXVbXyqvhF#C79+J5lUIMgdzIBqT;b*+f3x8WG z`^9RRZNlH~llS;_*7)eh;XY)cUoSNY3%=&fO_cHCa~g|+zk75&1p=pUk1XaZ92OYd zHqYl=u6>T@wdGggy?l7!JRE+ZN0^QI9Pty4waAzgwJg`x`bL%mTibN{b#J&qGUs(; zU!n`2K4-&E&n&CG-o%Fg0z+3mmRbM#p(w7*z`N9+*6SW&wahhIyFLR96aV#rL(1(< zlCRdxGb2zEiVHC|2(ks$!%g7E$*$i^`1b|bc}pF(rFdg8?B5rh->xfxDIOBkq|Hm9 znhfUMEw+j#X6R%qijJ znMs_gKg;Pf^}DQ0x&Lp@&IZ28>U#W1lePf@3DRPf0#(XHfeo!pNeT1aN zvhA`}prh$#%RSrhr$L#|QKhG<`W{sc?YjD4^9D7u=^pcR-S&!ceB|x)glwnc*1;%u z*1stW+4p6=p$@X4&T=(1^C`Ze4hpwQB&nH48AUN1cE&bQD_7O48LKs1YMfQBZk+`3 ztcJ$Bq+A?{w1WLu!AAB`xQB=h*RWDpxtajx?40c;A(D-e1`ithJuPgpoz~@!nXh_U zHY}u+$PCVV}8!>^FS zAU-66XuZQ6M0Pog58lLW@l6pHlMasadyz#$13C*?DO=rmGO^Vy$N&k=R-QUqd_`)5 zz9cZ=Dz?#eP^#YOHcGzuM#n%-P)$_fowz1AM?EVd+O|k`bsart7OQXpBePus-uOhj zJ5{X!-msY4Q-?HT{_P;P4+Rq8LLD(K)PJ`6(ka~6Q!=MaDHovCPWniAXx||eQgg?c z&o8PUaEuWh3RrCaSk;>+O$S{|WG{{Y(MHZq^=GMrI$1b=?@6)3u9jE<>I;u*G$TJ^ z>vv=P`?WvG`{`W~o9Uff5@z~3+E;m+z*uA{WuUgqxGvj~b7=djZ0EopHZzNF;`Y&j zJ=RN}^KA$ytM3vs)&EXF**Bb3VSLhZ#9@0~e%!X#Ba_w!n(e-E@f>;N@PDwfRbbyT zM&~^DboAuOTHEo!v1rbVc;-P--fFG)bsJZop!{isuV{F_}p5erc_D)ygWO z;3i|5;NL8U97Atj(dC!78~Ns26+#vJF*L{b`AV_<@VTozFXAM&89jPQ^ha_IROPyT zb4ih33;{H3*08Vwky4dgg7Xyw3^BDF^H!!p?c;*Sn5XveV=mc1mS)rU|5dLDqgVZk zPaJYmxR_#b2j-ox7xE;vgLHj=3&=Vr{3#2oDsV^A zeE($p3ZiE(?YzV8`$vgdK{m0#3aA?*$?Cd4b8}u%5o{Ez{!rr&_*+s@7EOOZq%w_n z^D3-!<9iHLb)QrleDXUas%i1c1EEGqD5;hJMxn+&&IDM7KWOA%~ zM&8D$=TRwJy$!fD!Dqfl(|hhoWZlI(h{v6npFXbDg6Np60R#(v+4 z{mKwXx-LP5b_pi*QWiay`{Vpt@CaS}|A){C zy#awxMzB0H_sM%>2;F}Qp&1&XSqTUUPy#|s17_yudguX?|37-@<~Tw#g5|T~({>iU z4udSqM|oRhU5cd?wmywA6Bl7+A{W*N4fn#`j5 zQdW_3C{)wqMHG)Tt@6X)<`y{p>FV9fhA68Dw1u57h7E-f^$@LAp-mxg(3eU5J8B7*xq*zn{&FFaSH5fCRpSf zT9$=S(9?UH4V_t9kf~dsF-M{htWk7Vu!fMP%Q32OYZl}(G&812V~_=Qx3R$!KByb4 z)#LX|bA%z6cz*7j=C&&@i&}CEdR#vdKfNmn?q=@n_`ORb?x?!w%R~M8%H1aBuY$R` z@oN!^KICNN`kk&uj_|^}LU7pCTn#^#CTb2=Zx-q*${Mmq@VvfhmXQ%!Vl64Jp0Oy& zt%PPX&Vj*`{%h0}K-qr%H>)(Bf*FzjGN@An!rrRyny_tGPKhGCJL#VkfS8@D)Lb*y zT=g%WSS>+E1RJI;Gul!#*ksj4y2&O*#;C{j%S5nLAH%mWDyMXK<%q$E{O}aWKTQx~ zglW-|FIUbYn{rI4yU9<)TJj8tjmlszSd&hxtxS$feiUSHf zveO1ySu>paWF z?Md<<2t@3g(n62G&7XvgN1D*~>pK4P?MGuAR()NzWm0pX!^(3U15Jb^gfn}orJVSM zs86SvO3jcaw|@)-#nsrz$H)cSQ_xk7Qy#>eu)QgN_J zxlRZjR8{Km_tOYh<88vN#IS~DVkv}Pn_NOU)niOO%+H>-K$JYMZ@j@k;cbi0TAL<* zNs%O~+y5mCL&3WeqM}}SILwJxnDIfU)YbG^jC!<&2eaTnS zihBb$lGYl23OH2Z0-Gs+wn4;srGt_>N|BD0sEzLnrGfsQ1sV1xH5Hs_TK#ET!AVPH zBwbx`34~(bqISzgl+m>ML|eh9QdDU9AQvIXt8B|kiThVt5q$&!f<^mO{n{59oV>(Z7!k!_T9$5Iu z5gi$kY<-Z7&fO}4%=AYzhvv^HS5+8G zu#Ln{PB-&b8BB>UZbGD=?7r=rWfeOm8;8ot>R#Az?-cbOKh-k&YDN{u2>DFk^+Tjz zz*=qJB0?_0{rrV$B-(=i3ts2S++-DIsgEsJ-@b`jDDBrs9NwP849ZZi>mTmsRz}jw z)z<|;Jx5x**xf*)!H7i`Sa|q7TJ37^^wPIS9j@Q6!l;y;c)ECeUsyL45xnc*0?fSa z*;Rq=ZB>E6ZLCv=t8p|LA{I;s0IqV)NOv!`x%utlUkCrX`PW0zymV=m z>$>S#8mzXt%Jp%lEbc1TOV3uhKIC8Rs|%wXaJEiacnSRZwk&KBMt$H~b*#!&j@iL0 zzHIwz!XfZ@o_<&;rp;#kzVW15>pvDVkAv@R#mWz`866+ER#49?U~pZsMc2D0c@Dqe z`%JTi)E3I#`^5Xy8W=>w6j*A|g$IsiR=Fmyz=Facy&Tvh501c|41Vl^cO1dAY;_(z z0I(a*dWc>H7FIKG)(vYlGi7v2fZWb1*Ee4Mz_tF6#WnE|q}2YnND$a+rak*o_ssoR z6O68My?>y}<=fA{=c-&0e*gLGv<@aqN0h1~hh2YbvF(vA%Go#H?J8)&E$MccrZS_8 z3MkSMqsQr5gfjm*Uu6SF>6pwVGN!A7Xu(I^x(OQ;**6Kjcb72X{Nq($;NB!HNTj$>k|C7^7OK}ko02YyK9C-F=Q55jQMjyejrzd1fNQjNLW7mO=OG4 zu|SobFISSQt9~r=bNps@4m$(32nAksJ$E_f{V>y)ndj)(4`%+Sob>H7CWrix9zcW zbAPO^7A%PTYga4Dz{R}XBK@+am7N{Rki7dE`l8jGpAav-X*dEs;-u~a*DQPXzM*g9 z14r#F`4#c??t4iCXJL7Mu=(J1*%`01^S*uyECJ852|?i({43meV9OL73>(hu`eV{7 z^(~O(ZGlb;U}=E^mdLEwS2MlKOn=o9NfQ8E4FK)meQ;HFhWy(n^8-uj@`|TrbF8So zVgjUb>KZX^CAgZHUXR;tdivcr4Nn#w{uMqGZoNKsO)W33 z9g+^)w9taI!nH&AXl-{|J6qdG$4VQ!N{{?$=)@Zp{;A}#^{Wc!Q{XnRn;cGFuMd$*LMX%#HLF4S{u!};|mnTEVgS2;AL+8kfXq0TFpca`Xr!eXjIl0Y4Fvp zqGZ+_&!CUFz?-$TY?!)GSC&zKgEP8~`@EqVyCIH5eKvEN(ZN_WruIkRcv{VbSdP#l z(EIb}fz_Q=;8ApoXRJO?xQ(&;KvA?FHLM>!4-+DtHng>AmYnmzmDw3%(C1S39<*m~e9veR>y&*7P58en&xq=RoSY|gLB~Rc%vC8#^6Rsoe-tXV!8rRQtt>=q4`Reo7Hsx-I**UYH2dUF1Pu!WHQLRP-fMMU{lmiEHI- z*D7Q`I8I_iqq4_RWd?J9rsU$OWi4!<=#9kiuTUP1e|EW=%#lHBf~ZWW@USvS92n#pHm1%&mO%@U7WoM9&E_Is~D=&JoR#vr5#R!g`CuV(Jp`kDP-%Jsp4~pQ}W9W8eI?QMj)~ zaYNRjr7+S+?cCuR{%&1q^wLM-HMPc7s^r*D4MscH&IO0nTWl_^W-gi$fDG%azu^T= zZX^R+rwco+g$GaGK~V^t{H$a>L7I{0^aHcv6wG}wn3BioP4ZMN5H(#M3X*Toe4ckjXD_E19f4O%@u!LZ+SQ($-lFax}{q8+E zABq5QeC}$e&)JlbyV~tb&Rw0xz&t%|Xz(mt$%b2*44gm9%0%r7vG00kG<_@Nn;SXy zoAL4U+<%izd(pOWz-`Fls8w)6mcE~uGblN$&*bLIGfW8qt^gRug`vD^NCKwqb5JvK zU&=Qw=`*;|o2judC5zr@xrvG0JYKruXmp=XhEFQd5+@`d`kyf4;Kxg$XbeD&l#Na`Kb|wPkKk)K zquM%p+dK7_N57f({oCGD0cNpw5xD;yCc0d_h*x;Ip;X~`%1b&$;%Pu+HB1XB2A;Ua zH6GgfjcpDL==*GzP3tgbyKg2&b4N=i5p>{a1v-anKuXb>uA&!niEq%bfZP?TlA0yG zVYU=j(0AX31<0k3mYlP^w?efH<(fdQ_9dbWWeJPc6B=B<82Z>x|57CEyc%s5=fm+w zpA9^Wj#w@u)%f5(qig2DNw46_&G;bVGE#XrKG4{9P5J;U#|7nO3WH5cFcoPcm!b;- zt$UFMy%LRmI|uS<^ct^n=(x|;D~S_cMP2MH$+862e+#U|foHCZ20PH+Ys2OOoh%k;HL_9AB-nT}^Vu2lTU|1c&y4rq9+6XDqGQ?Gp^S2|` zvm(!1*o53qZaRDyo-SvcXFMl&Army91_C-&gm>>Yx#B{@rn7}`iqvsPeAsbD@!<=I z4=;*|56?O!K8%-A6+9d6i6WaSM26qWd;C*E50)>!WX_7kbLME8DW-zUwYhA8V<69- zLNB-)g$_dVv}+SWaSa9+pD;E$jXNA=>JLn*z+U^9X4kiO0EJDbt0BZg$hpbDHhfI8 zuc~}`=w^4$p`3j=2k>(rjdreHgZQ5>*KA&4Dmc&jKnii_0@vtgJ6V|HyUY(1hH)?^ z=W02V(Xj6bF2)Ld2g)U<3MI4DdFhVuW>%maoGg)P!eJNL9pd%E5=j?4ywNgsgIVfo zoxFNTxPJ}X%!S6H%o1Y}j>|kTAWqT=eI<{~H~T<~jUs*7+pTbz%$%iWg8%(wsW@iM z9s3b?H=?Uz3V;JGLvwDC%(+XLbJ^yco1o_$+A4oXdsS+g+0q(XbaLqF)1jvmu_w=1 z(cSSUeb^d)rk|cE?pqfeD;QL+HJer1TCy%G0tib8ZhGcAG;>e^pJAw&P6A3?Ct!W( zF}#ZQnf9~)DNFFC-r;h^*x{j1+v=Sr~a+&(&J8VZ6ph(c}sE^*zZgX$#T8V#60ukq`&Q1O+{{k}3;!x_ zhI%H0WZCpEnR#TAumi$6qPCUq9j(rxn=0Ai;u$i^be!gL)sZO^*crT37ZkyH&pYgI z!oNcBqiU2cB2WDfD78|KX0lsjjeolHb&PkUK@(9UxjfLGVFrKxvf5ylda8K`(GkpB zBL@y9cJ$I`1nX$JdCH^N&C=}m%4ByE24_S4ysvKjdbi&j*zC6X*VS)M%S!(KIli-a zI8Po%@o+v5{;Q0lOlWt$Q7U)77YM_=3_E-^AE`{N36beJ&GYb8dQY?1ov0_TM`DFn z50{abVK~T}B1S4Dm?}`aJ`kBwya&-VY)^S!ByOfitKBLu;ipO0^92!@B&gq$5Ep^% ze2lJ(!F%UaZ1Xot)L6) zn&@<_=+&e8?QZ?{y!sVy!AInqx?esNyMs;o+iI+%^9UFQ?-tdb*328c3ia~S!V}@n zsfUpdf0vw5bZ>hgDV4e}mQxH!-TN>U!B~!tptJsVdmUigQe00haiG<{1S9-zV}sjx zjv#HhS35V&zxg;3pQL!f4s+{XBA6%kw1KTElrkvyT!q2C4Jz}{Jin|!IrQ}1Kg*T%&zh9$O^ za`jru8F?*b1U6^l|2x7*)ma)x$BW}H9nCWMKuUhP@&YDdMY^^c}Xghl^F7L}{(`~h|PZc($OzB+lqHJX~j8w;sCc(0_W zAF+BWvH9>{Y1ACeo$C5_8YqetP=;}>y}IuZ6yzF*UF~@$8f}2-|Ady~DPl3AvtU7n zXX@62;UhYUSLwonq2Ag-ve{dWXYQ>kKIg7=y6&Xe94N%)d@tMMAoHz4jb$3j-QnIe zPjQzk@S=c}xKW}GE|Q&5-2d}{$)RL-Hg8VvbHGYQn6aK2tySyw~U_AN%L1eBb*P-fPKn*-Z` zxhZ;ECi@$`rN^sWT?d^}*UF!(`4c0qSMV69$)>H2a+9$5w{m`s+zt~-FK?PUZ*`_0 zEeR9lK|z+z=Gg0}gOIDKlch3UWo|$v(wQtVK20s+SNUSN0Zyx`?ujKU)p{RaE56esQV>ZWJLNv_`FhE(wt-EtP|8{T0l` zI#+`PZKC)5AY!b}2<(=jv-paTrf4T`X!Bh!I6fljzKiRxD86=ax9`IGE0!(h_dK&{ z2ybG?>k9P&G9K;)<;?m^vIOpMilOd&b~ZC?q-fMCvuiGmJb%`nSFvh zOyn0MNq@F3VQvSDou13LKD2htc2iKH&W_Km=asrv$ZBrWcj!Q2Mi?{-HI{SvXEkmm z+F)b<=CQ_A4kK-%;T&yy!PbIk71rnhVIp3-8Wfg`^PK^Ri=~cx^y86~&=#ldc8Bai zX!w^eD@EE@rl7boIf{H!i~N`37O~KQf8-1mVj@*mmayAZDBJ)>BN_288xy`H@g>gs z{en87{dt;IxRd$vJhIn$Oi)$87do=QZ4_}Rb~XHz={Bzt&%XEYV3ar-5BQw}pdnN7 zTaqOFLF2y7$$@sK?PI<1r#0-`a;^Awx_W08d@eiJqG%^PjMrMC?mlW#Z&$;GWcG4t zc>7Sw*-{*wk4vyGRga0dv@)0)7R_Gq!oTsoAppA;GVqKwF+ z{V7&osmd7o_Gk<`WhmuAQt%dK7G9xJ{~(LO8K_OOyBhE2Ti^=zr2r4QM=uLk(V@9( zGW@w}k4SNZvG}Ug|CjjNa!M0evqbfQ<~K?z)bD<;OODJ}!8qtelJSoCTc$88Uzaz^ zboHlT2es05PwQgXDfFa&!wicJ9;$G75;uqLIhlCP>K{cWe=F^VCoq?K{XD(&&x!E} z7peSW+VgxlY#?P>!##3$%cb)igOnWN@9K-%0Bxj#OK&!JAKFIk183JO~9P|qz9 z?h?F~gV(9HEfFkr+hlFR=cu`)5I+sk|8mD)g|~cKxRcyRgfa4;mwT>na{c@-$ZAYC zta`KYv~L*QzbFfn!tYaYf4;rScV6zTc2`3KuettA|2A(FV_@j2Q$4K(mhQ+cxwks~ z6JiCJyH#cGt(m^-a?kZ&8o1qU+wjHQ+tW5(Xyj+oozSqUcwZHTB*-CD*DTIWiOZs| zu=_-&n(2_tgimS#_o#ejPOur7LQ?p$3TPZNsWepNsLQqZuIf*z6Gk<;Kh^DDU{u&W zdwgl3d|7DuXT@f+*a2ntrzQb}^ED)U?tTmQrm~9O>bL0RBr)xw9^68GD0HjS$iKyt zeA=bl)p9A9{6{|OX<@RL(uh!TuiE=hlVcGzFAhkU`J^)R!svc`Hv`7ib4O%?5tRAF zh`JtgE~>4Wq1<#S*K3zTbB79bpH^t#4f}s8@!Zdq zm?S0s`>{BhpDi)zKb6>l`m=Cr(smO^+{8K5JtLOr_)jHn`do?HGJo-iC0hSeiP;Gy zn&VT)Pzaju?TR=2v*RNWBa|D{RGR?5wX+vZP}KK|rptK7Rn=bC^wB(n#DK>q0tdS7 zaZsn;56%Rd6bH@ukD!h?==J{*)EWn^|2*jF4U>+D1OIOVFxoN_UWKp-`bZ~+_TD6| zF>~KG=6RQJABTMD^m0X++QPBOWJg9r>BUtqYdUtZtlT%SRjVx!xe-^M@jE`|*;`fF znV@b0D)|8m#8S;X6Wl^wn$KLsS0YqUHUcj@3XWzowpVOq3I zyF)yjTrW*8e!gT`sdBK)9}H z#kPQ|le&Y&dz;P)7IZXa)D{R9d2tjji=p7@+?E}>ODYQ4OM(T@8-qFycs@3Lp>0Vf zX75r@47t{7sfY|T8J1}NBSH@kd$)z^HLj&iF2(5l1#d7z3kN!QZLi)EyHS(Kth*}m$ z{axxd-YSjOwUH~$b|98ajWr_pQ>h${>7Pnd+I98nN*qM#I@ez%Pf}^`)jSpY1YgVq z)<`7z`xFh189$VszAQ614Aq{8lMmyCtLo-i@Cc87{zoXDhzd}Vr!BPJx)ozfqc|IL zzkL|u3)2Y2Fgk(-+2WLDh6uXQJWSS6-e)iPD}6*Dm6Uqri>k|^x872fWg11koO zp~1G{E4F>1MZ~(;bOrl#$X?(eqgD*NZGyV|O>jR9m7CITd;WR&y9p)go|kAtS0#y~ z+HJ4B#@MwIN?#xR9cbt?qFKMp-CpSi|DZ;a^P+G7>a85o%v)(!!;1h6 zAarCgv2cpBWcmMVDh+w1;jwDiQ~A9-!`dduR@5M#v!y z)>mJUNjU=+$UN%n!~3a_8YSvkEl|vkZP-M?6#aN}CNUF0>a2ir)X$R^_)|;N?)^+( zlc}u8=@*?1ZAbKb=>a+%=S2SLxyjj_^EOQ`SJ$Q@k!w?s{YuYVooK^sj01uH8PoTY z$$c9O$zNO{`yif*p*$rlL{E86v_kc;q|8Fj8!99fTiS|>$m5iZ(CWmCj9sLaT;<4HD%5(;zeI;F zS4a3j3$OoVue+n(_gNG6RSbJe{dh}%N(k3 zbh-Q&E}(U+&Bp8aWlOa5El70v#X-7j;?iB6+axFZx51jk}WY0#mv$V$_->3(pI9G3pIFqWs& z%;S(eK<6}joX=Eqhv>T?FEBWJ!?Dn!cLRgtZ%g)$C7@QQ{z?kZAAFni_=`YdQskJxMt2d{;4?!a+kZssHN9DjKP1epH|?G zBpG|?4O`BEe4zsbB7x*;La-;Uo`v{<)xh}N0|xA6y1t#3_gS{da=YtGtNX|qnsNKE>UPRdM7dPpZ_B_{n%CuJul9o9)R5|jFL(yYWJXR)+#PGVA) zPP#N9>A`utR9`CTL)e#Ss09g7)$4UqUSiVSI_b*9q=$799^JNlfb1 zNh=bQEK3FZ>k^aPI%!p6QkG7-Au(x=PFk0kbd64`PE5K%C*6{mv|cBzPfTjiNiqTB zo%7&kUaEf}>G7oMzi6nf2~cYvtm92ztIJADpA%mO`t2It(AvH(o+#q~y}am;&GA&U zkaza51_lm5YNmBgD|U|AA551NNK)VHLXwCpHc_3$o>$qQEFY45=XuXo-z>Arw`6Z> z<=-#l9F}geyF|7eCr_43KBw=5xe)pvG5a2Wo{==)>c52Z$`|I}X!T!+KFMS; zyjhgwpG@NT`8V49X=t4wYj5cBA26^!Z`E-Iv|VK@{(|?g;aPkc+mq0rrl^0LDlJ_D zdpJEx|ft?KgMhX zr6VU^Jn9!@Z$q}FN=O$~mpcE{gCApKhyH^FB_mRw;CyKbjqRm-!p$aB?>7IeU*l-Z z;-4Nsx69(65_w)t=Ue1_Gx-BEIWk>J^gZ%g*P+>+^)|Ow?inh)>h!|ZH`&s!*Sm>! z7NldceqD2A`19G#&626R_%Xs;tnbUX7IMQ|q+!my!Bx)fu==^)*Ae4=nGKfv6xGJ1 zGcAWR8l`U21w@>HZ=9gMCU579&yL@k#o4?QSHv8IP-T^Y7u+OqY4Xv`0>}PA;sVKz z#U(K(-|~vUV5Mt^oS;ny5P`v~T>2F0YS>GIafjn-=(fwlC|AQj^+SfM;k)`%rtgL# z-^Bry;%eMxqaj>1o6CPDKJ&gp*WPQ?9@rALH6F zN5f^vojG#XzcghsW5QTOnXvE%uBNdXHpR8W{u$U#a0$;9*y1$r^y>|4RghC*M!=dB zb%dwK$}sWTN9`J~W*)rG`zi;Ha|=S8-2@z$h5sb{nJPBjUU^e0XSTQ+c2Y@Ek*|b* zvx{7f-ywe@KQ4TpLp>$kBL>*6#@~Tt*ei|YJ}6(3ny%pucauA=rVixDk|%?gg`%VA+A&stCsJW^_&4xUrV6BIzw7S%dCLp`kiT?nV4lTww|MLb z%=5T*9ONOPY0)|1S7?VGCnUS81#h8%*;k!+QJ_UvKH=sfDa2FoGSIoZIO3f z<$VLkDJjrA0gZ;6o7c&3avK)Dh@64Jue)~0<+rP0xfH0bH}9AND%I66m6Re^L!b1Y zue!*Wqo+#=sTvL4%1d~QwekWUsVC1=tnk{x`#9uCyEZ$muDeI^m8Yq$9U^{7Y}tCJ zDyDoAU!gA-j1hbW3uj;rAS4|3r;SmL(_FN-iS^JcbK zQ$zM*kc(PvVIjeKkVQJ!R7@fxc3*5{lbBNj$HU(i)d6#`%nx+4FV$-eKgqm z{iDo6rQ5TYa|&UI0oSJ>wSgNExv=NRl0vFi?NkX z3SMj)=+K>_xZ^f14qRc~G)>%s8R+xfw{qYUqbrm@hoHkm&BBY)A)=dHVZH6mmB#qs z#ew$-HjdjWiNY<04|ZwYnagU&UtQA}ZS+pyvfrlA@#h z;TUw_=$unhD4L=#v@^AQG);oBaPC8GW;x>7!$^)ZxX7!JIEfRAd=BIBRnocRjK^2V zZ;J8wb^Hb%f0&-YZRB0D^dd>SZ$T_DaA?w@DqDUUZpV%eyi{f6y9t&QEO?J6C%+%? zOB~~ZK7NTeUC>Vha}F%yDdwsS#rS0vCCj3Jyg_O>g1Z8hbsp2LGq}7fGFsiArJoBB z$Y(Sja5XroI^;adlmQim(w2)12-|H4_H7x)9`!XOO-5hvCWVYAJ0=O5xJ*6Co-6UQ zl~_ z@?9G^UhF$RaQsGB;~xR5?iAKl1z8bVEvq1O?dV{!idtS(w$`s)L@J+GAB5mPXeOQ;86E8I-v?PTd^{x+B02f-Y1mC-hT#vb6 zP+Scz)+=|u#`11Wm}NWhUa&$s$J60z5Eu9c{p1KFL7~k&{#U|Zl4O5RSoV%YRFQjG zyo`1NUG=yGuqjLO-Oq8t&xbD&I6oY?MT{dsh*y{vOZX z%J47cXN$IZHIS@qag5pKFut!TN{aD)y{Y+o#3RJHpwGzGbTe-amyE3JDPh?tT#t}Hpxf-+mV$;zGVK7WD3e<5n`C?*Rk?i9LXy3W$-^9gXkLR zFX4HF;TeY>Ef80&U}^S<$h8~sHd4q=HA-JCv)$rjyhgbmJDd3RuEt$#QQ;r)2d?6W z{6O;XLcppI6_cG^llmpJ(?3xyB2_lMe%cW8t`m{R8oaDAB;qDiNU5=$1xFCCf*#{L z_wycH&c%#q>>P?Y<|*bbcq+C$uE!7zQ;_c)5?Vg+$#i+1B=^F4DR9g|hleu&nrNsi zo`~e-q9L$V+S^tYxMG^0@auWJl`J!ro6w&@%>7s@*HVb(Cb2c@3ld)z1xY5+2VxKL ze~TWNh*!Z68I+m+6OsA3{u7%_r+xS}F7CtYUvNBdXXP$GaobommL(W-+~Zaj{W6hO zsYO?E7^vyhj!BM+yhRM}<7Q9dhT3Q?hb+1pUIUyB_!;wOhxv0kKb+`Df0*-_T=54! z$#Q*bC*;UT@g%t#>ZrrD3kM=eGY3I;AHDmtmXK5Lp{$d}A49)fyK1ejUHR7GA-0$h zT;1f4P)3D@SZV`;xPrd3kecjs{j53U6cJz)f%iVC>0+SJKk($+#aR~^<=d$+?Xw7t zHmghKd-CuIDX2aurvQ;MJVcv@Segn%>c|K^AVTFr@eLeD$T1v3Tg>W4QP`;AtE(^} zMguW=c!;?sLSuj!GcrOhjgZrm?~Ehl91bCc#F_SwrLeKXSBKLkffxtGxZxpwp&^#K zfN+hBP%Tgf!DaIaQDIIbo_5u`hr?=_S?73496x-Wb4-Y{fH-S-h;b%X6M&d7GFBo& zH44)_`DyWPN*fNL7QjF@ox;+GukL3i#6%z_4i6!B%&uKa&j#Y`krArU2xWNkGvWwk z42RGhv$}IA?404N8)rhC3&gp@LmXvcgU}=(CXI|xn=JprOizAh9HGqN5c-)etd`5; z{K>;tS7Sm<0but zH2WuSzf5$a!X8gP7xDFRvX$R6e7#5D!x-JSsQ0bmA;j(ph_``wdw7VSX^5r&2IAi% zKgN#8Q(|jEGl_2+ayV@#KG! z*j=9tk5-9U=?TyhYB9{J_@W6Brx?RPI8C%nsxcy3Z^J!M3;&ivJzNd1@P7KCBit%- zyuvp<`EMp-{^sy_{ZN-zdxSEDvQ@xZJsB1l;LOe z&vls)oDs=Poe2S%sU3mLtT7=VGfR(;w2QkM=V`n?_T+z@*j*#=Cu4MxwI+WuY>Otn%caa$$vKytr5;W zKh{Oop5ffH#e_HmU8yk9GU>{QXkDz)I_AkgHZ-}QGqoced~9Z|XE^x0(Wl4x420!r z4YAZDEFy4ft}3@pr58UmWa;b$htx-ypd=?ACq zJd%(mBb0URx_D+U3`aAUKS)gNT4IWDyz!VO;J2D`*bt4RgX~?d)tV3{hZZZ`l8i+*GpFS*Ln9pYjr>Ig4Nx7!0LYG z8LRuXeOCARyjSvmIq!wM8-KUDTlQPszuIec|DnU`?t9+qzKC}>?-{(W=KcGfR`-@x ztGmA4>TaWs6V&nM9;^Ff>i81x>v-2!7qd>kx-8Btlj}LImrBVm#7=x42R?zD&~;-vgjB zGf<f4ba62!`v2WbtcJ;atzDL&{9hPX{+~|^ zKcoD==ub?&&nW-j`yjL8bISkSa^cg$2~lhQbJ>}VP5mj=e^G1@)nKle4tqz%J_t@d zf|K;)hz1EgpTX&OVxTB0{8LV;@Y@9^t-?QQ=+@RK#{8B)T9N;vWoa4*E| zQ%?zvjw|@Ttj5bA?q%w9m8)NNavNKwe##H-PAWq;bqrm~{$m$uam{-SA6ZirH|DCk z`4(SFzGz-ug~3K#(HHFt(en-bl%B_AUiAC35|xQi_$pDeIa^{1I-GKUdCtD4j?hCP z`?&jN?xC*zgEP~fQCze7Cg2b`IkY|+v4x7Po)>BlW1nKG7I2%F6aA~1%_G@*_n-7G z$6u18TE!cX^pAdWzu}lY#!)bkE6}i89fh>QktwZVkq&ORU=XPRLZ; z`tEx(O#KcW3URVl>xmWZUf2VI8%Lp>Ej>EqS4E6efWsFe_71Ty@jFFFHP#C*`Ha%0 z=sQcxp_6D^?m0*pc*zk>@1?zg>GF(ap>(0BuEsJG#{B=f{|cEk(tj_<`;U9ioucz< zmNkTgsdTN*j)C`_0?*tj`mk~EQx+v)9?K*OG*U-bJkw55myPF0ROvnnM2Y$`@btFX zE>WY6wJWY!ZmM409V=B0l`87BG0^|VS(Fzmiy%LyPC6IfD2zh|)}TZq3ONq%qLtq3 zub+85xZEAF@r1^_i|B6~##VXu+=fbImg})j)aN^0k69(zS>-8k-fu^1`XYI_El`%z~0(6>c$8hKDR_%Y4J;WS8NigSt_G%01(0zgnYJ7FS z@p^ZKIO`tu+QFP?_zz68@+!m6oqyY}#i_V|E10vI2XJ$QHmbPF^8V}K)8a4t_3r+? zi-tnW^%snD`={Cn=;vg)rv&z4-siL(xK`4AN{Ym<^jRcf zN71sBqR=7@1?Bs6SDnSu@`nAj)q`U?s)EHQU&9-WNfql^%a-14EDAp!CH?6r_M1s) zv+|zIhRKpC9{0o`9Z@yy*(%Soe%UL-Pe{+m+xP(#(!hm&As2{f}`S9f%`hBbN#%@@@qp~nJrrT zCYY{s1a5LXE$}h(k;v#k_tSX&kt8Ko!m@fxU#mHB=uOwts1=wkEdBApniDdBxHa5A zt-x6|t@uRM7-kLrwVVgP?o0%w?;QOtR^RADv$H_)&}zqz#T$nE$FFyrDfHlvdFgL) z3(PEFB&EN_?i+RRy@Tps$6o8=Ez6g3Fd`p@PynfTJ)$@r`;P{Kas5#-s!ZgMWU`5u zj(cu_Mg&7X{z8b+14M(x)tJK8SIvN0LOW5zu=OEx7L<>=fwdbeqSE`kn$+1ZT*F;Q_D+RP-2!09Z+ z_B>HieeXBfPBA?gG&7!E{Rj!-DmYzCW~2aJRBWp8tRPc_k&`X44~XaCr{*4gPj)(~ z+n8HK`PzwehN!BIB`ok|_sM{?+5PXCU-5mEO_DM9Ng0d3ZtU3)3xH1mHUU7fv=BJoq-uFm zWwC;>C-5f8U`uMuZyZTlKl)daQMU4O0g!$&dhtIAH(IXJrn0P6P(O!Yu*%h{QS$ew z_EM3tCcFdFHJUEA1*TVlnQeh)TZ>AXsW z=V*?&Xq6jB%KL!X4~z$sh@h0{71)@`CV{u13*KGbgMuS0-%q6{8Cu2rOw|bgrUbNWkB84}R5x zHHUG_%U{nY8!FSVvOru%iMy~pS+|pST3_@q zK(Z{?z%R&m%z+&05=m`U?4f$s5_T6ib6NB^(90zY#W@wB_qowHDk6Wa^=Wb9Co9X#n9i>p4{3pvg?YTd7)8~9kn z!?S+BPTmU~{dt60Y7`L*8m7XnhzD&Y-h>yUw~Wg}M8@y(HDu2VVJ3ggUG|XuE`#G; zFVpP~;}x~hW3l|vimo~Yx~Ue(+G>i8`CXb3Sh#nwtkbF0@~i9|VsTB(Y#yiA4t854 zi=ScHSDmVy!dMFUAjANtt&vX_hwl>o>-Jp~ zc)?+Uz#Ydx9?C-Z`h_er8AddgOo;1dJx2JF>lLDQ7t0vMP|+?w2~?mq+ai&cvemKg zvZMpGv-ImM^``lHseZjwy=1;F(60;BUh_3izvih&&DSgS>y_$%&DSFRTBQC*Uh8XD zb+GeGU8_{1q+~B$bjIpx5TC$O* zS8(ku*c?o&Q0Y}{U7m&7(Nr2&*>nil zto{{A5*LIjO7$}oWapJkJ_*-xf$Sr=R~}cQN(mil^y)8_VnTNV@0G+axR>?Aj)K2> zs?cWn4zF7k4e}K&UQC8fRyI0U$}|SmC|wSmiGNA;-xx|Fb?kadie?M$_vMtEfXb?i zha7O6FIUqkn`2@6Drjk7sXZD@i4eXe=Q~uA(@zaIkS+K=Cf3|{v+2!y2lH5dfQE%u6 z^*W+(bwAHikoqbaIAm1MR#vzA8GPY`(s4R?%8~MTk2O3w)MK;bJ@z87nr)sWJ@z5P za(a)!vl29k>phBJ(>gT73~dED17oF{Xk~aJZHpgv_|^M~y{wd`V$zT9I3#>I2Xi^G ze*J{{+C9vxifAVeC|+Al+HxaOf80W+`ja1*rCh3(0I|Aq<-R>mcGl_}WN-$V9MQS! zS?wl&%P3Ej?v8e9!zVdC#^>_8WQ7;pk#M#Kl}ml~Zi1u|M(*W%oY_gmAL(1)me{X@>}C*y|Gn$Ckk0 zO}GmjEbv_)7_9Q26F1F^3q#&SMVP}PW-Eg?`tT01$Y+9>(!n@X4TtN8;3@&j zJj`ilu$a9QBks_WF-=oE9k->aiIQ^u+Tc93A`J_?9_EE?>Pg1+c6bT`8>+PFA{f!} zApKkL{m|_9Llr$8J{unOy_SlS(3+&OWvW?n;$4M`eGU}7!}pO;=b7!dx24Q3>d^*AJRcc4T+kH#ZgH3^d7mQ;GWJ!$Lrq3=_Co_(99beRXei*R`x~aM*S{fxm_X|VIn85Qh)3eTK!6LA z0&O--tqdaQB77RtA%212m?AJ>gCg6Bq_!0%T`WK^6yh2fE9B%htA)@ZT&mPHfP!J! zZfUYogf0N~>$XvW`4-omd-xW(Db4aYLM6DN6C$*V)|Szg%k0w%(x&a_cuoXbDs?@* zPwhu4=ABbnWkcfD92m^qlw?CJB!Y^jltQMN>){Rt0K>ZzEnz#h$=6aG3%rWpA;0F& z=86%@-9ov95p`_(vUd(~wN`F-)E%$#CD$D<^d~oE6h+=QR`+@e`h02fA=jT;*E*k& zN25-*G~plfWL^}M-7>X^9Cdj>4)spk0DKirnXn%2m0thjr63s}#q~`o8WClsUakXP zWt`rS`7*6*X7S*puFbA(b|R#YYU6qigTBaE9%l0}aBxD`z@fI3ImSs(*VaW(i2EHN zpWSdaZrMxKOPsmvbArnioxzkF@Q(p%(zav_y*3aWd>tT<3Y-5ZBoF*t%<&e2kE6>e^hWN9|Qon0tovn6o zj!Kb()@`HIvrp*Nm5CuCVWIY5-Iipu2bxFW--ngBXQCu7?Fur=jSmC!X8TjxY_mfft(euNZ!fg!iGq`qp-G9M z(7b|7$-c+d%NiBGLa9dU%r;wrv$`2xhe7>QjkJc#5C5jn(xlv)G#??f3$Pf%9I(yIQ240nc@~&Iyd1rQF`1{4fVd>l$BLUG5ye%L_@c zBGU1#&@<=sD;;9x3Tv*t{ish|G1mL&=@*$|jfHWp2bY=&Ae26}lC`B)q zgcgHm&OY;FOYD>FMRBjZ^w(0476f6ZBgB|^@Grwvaq9!wRUff;u^$Wx+xGmJd0>i0 ziQ&Z34He_9RY-H5y@(~N8dyh~Q;SWMG_`ZL;JK1G!biq26~ty)M}Bh8Tb?wn;P7*4EVw>Xp(bD)vEjVAOu|7^9Y<-X9BMt&v;gA_Gp-t-fcb|IE^#O^%5G;8Jl*GJrtjI6I7VnPa5z=jcAy92@R{;FhRXwewtu@GWf)Xk+ZJ|pME8y zKU_1f;KXN}2Wx)ty~7#$g6sCvWYjY0V4BXA<6OB?Kg7vJNyvUVN*lAvWcb``xQQyS zwpeTy{#dc?EmwcklU~Sp6300CPdx-*`#fg+(Oo5SSkSC=@J@L~wiq}$W5e58T3fDC zKA_3Ha^5arYctAM8P9@(BR7}he~UBpt?$tJ?AhSaUSb+@9XtZ zsch@J^|{~XhRUd2=XbUjt_zSBmYbFOTs}AZN0C;~Ys6oli$4}KL1tuRU48EN;|YzD zP*$HCiYI(a67uVFcf=E<$jHU@x!5?HWo(y(toqzXlVSS_sN1d7o+rk+2={?LeQNB6h>lhtx!2!=Rn5M8959W zKgoMioJDI9nR?<2vQV7T<13R0;aew%p@rRS%E_Wz;OW?SaaH>wyJd7>R5V!WsJk({ zZu_F_>}^epvPqvldUUXIUQ^|zftEZ9-zm8xZJ~m@OQPu=oZ71bHBVvLtIf^}nnf0t zE#vRtxP`ks1im(jsk7UxX=}39YQZWy=&3-dGjii@AnDlyBg(cz|fyXGWp%!$BVc#z|p;(N1JwV<7PM z)RwnXY?n6bhWig2Nl3T~y5P_Y@dl^EKZObzi(CIBE6EuxL}b~GY7CK1(UI!PqYV-{ zVR?5X5Oh8&g;;g(8Fu{=??maW(>n3A*H|dyd>k zB99s40_}PAE%G_Eq|ei`;SH|GGHOBK3j`x;v)7-jdy`;fyUm-V($c`fUgnKN^T@wW zVus*>nHl%A0Kp-ZHBD|fBDBpZ6JhQ{1d$FdyaqH7PTA*8;e;|E`-5Ebp$4Y?j~c6q z#*tRfJ{Y}XV}ZB~JRaS+FqC$mXa9yTFH>1u8=zA|BQA{R4B3BH0wa_qgN9xH-n63N zLb+dia2|iSCAG2GPMsIvr(jrN(8aWUnm7qCo%BNc=t~DaM`WQmkslX3>MlRuKOSCl zADl~}(ecRnq($aNZPcF3{*k(b?W3sx+u3GFzpQyma3*{%++Hw=E%zKQ)u97_T#)6n zFBs+jHQ7_!mP9QP>(anY8J0S6^z$s(Z%>Iq*a{;b>eRnTo0g+X0b=v@yk`$hi(2rh zn6odERJf?_@>Ra$f@Ti4_Wr4I-19j@9GB*u@3$Mh5tuUEGZtjf0KC2I4@bsaMeX*s z)KyEsbD#g%_7o6Ylv|wPcToAf1*3eIQrktYr)W~8&;h_FNXO{*7DjFQH-f5!&&FHS zRv7*!LuD3fq0sPbUcs3jryyJ4d|`s4C>EWXDH+Rz51YFi=Vxes!BL(qBOD<9dgA3(y72!kF_pDh&89n8@yjmf;(9=0M5*lZE(v0|Pr4fFQ$uS&90wT*_#@%8R52 zxQl1u$D!!oQDy3_EzBJ#0Pzl`w${j~|HIw8z(-YIi@%f1Bn)9-0tAQDv38LVHNJ3P=wls~SZ4qVwD}ltxXeQgK_Cc#X+G?>aJ+-Z;6~zab5KI73K|MAK z)KszkjhkvznuLd$|9AcNOcK<3dhWUBe(t?!X7BxbKi6-q^;?g`E0+n&mP?ZWNLx1B zGoO_obJ(D(S5MEX4;XUdAC-9d`K)+4Q-5?C)XxA_1Kt_0=0d;dX`Sg!tj z7X?|!GEi zn|nv`EJvs_1-8Nt)@LZ!W?oyNe#LFN#fG+0b(1J1FbvmS6o+efbA;MO>UNvd6?#b= z!Y8@q!ge;=&1swzIQ-+j=RtC`s;`io7Jj!smwHKP*4=US$G>pk(tTluUUEdkXg-%;Cr;GY zIF)BjJYHYz>fyvKXs(K+M@pQL5{HE#3n3Rcn_RA*5*JsCn98hB3m`Vh5P#3gP?D|l zSQ#vm=r~KhB`HtGUgIr!@n7sm2A+4PFzP zyTIr3A`TrY;w7V_C75lL#-=Zc(1sF+Im&S9=*U86WJF|Hc4V2O zexWOs1r7KcjQ7j@uy@9&JzN7O7H9@-j-8Y#FLiARS$68S6uHBSpe?C^VWHi*xMhyL z&Sz+M3a`J`4INskR!BdQ-^SPFkoel{_*&+^hizNsQ~x2UfivQGI$`0e7i&bal)Fn^ zw+G8A)eDkR(8L+I(zf3F0(r0k9^=F4s%+^?Q@`dl)H%7Tr8C`b;ki}I%(QLmAQhX6 z9C^3TzCAdk{%V&k7Yb}+wpMwXG`1CHu_MPw_D%3KPG0g1d zv8tP8Vl_@Z!7H_V{;r-b0HReHvbwU>wt?Koxn`7IefY4ot3yYp0oO!&2!4BC71Y84 zB_cS%4o?e!YrYgPOReoMASQO|nfAsRJUwXwxZI&U-r>4;uxCSWPi}cTU7Q)>*(6JE z-lpR5jx9(B^`$eB0G0U0HRIF=n{~mHbipzpu@8tAZon%%x1_qm&+{y-b#Yzv9BHS_ zGGC^kywv9Xy^Y?{U~=;UW9Ok1($=#d((GX9uNeB{YNE?rkqFv-;Jr|vW3}DySXQB) zeUR$BC@3@sC#YXjUb}V!to-^_NQ>AS>a#?}bXOldKh1K!FFFG^!=NzG%^*Kl(X!NFi66W5M-RLQ zd-E7fsUwC%XNzBy9UqfJTE>pIX~1ot@?tKx3hVfcNK6zN;P6IWT>c$3XOTOR6Am;| z&Qg>v zz)&tKN@F61hFHrysKgvl@VZ$U!QuW4v3S>*9uun{jU$ZS5_6p%i&7t+0=;pc;n1xb z)QjY~#h9!Q)gHA4*3kS!vhLz+$GpHBCD5m(@FOys`L^Selg2Vzd$mUL$4Wh!XPvp^4YFWZ}&6 zmZG53l}a5BGp%Vz;(`V(JBAWLW8s)_!`bjLyQ)oweN5@Ubm$SLyd3_9!|n%B!> z7+8Jt0v8KyN#6+%ok(3jG7)KoPSv6I;E2;g&(8l4p#Fxj)1PwRBCv9&x)HvtY)qIn zwO#o=2Na=*vcYJH(WivFm0s!M0@^~M1$#Vw@VfAOU@hs$RoOFS*(_BaxtsE-;op+w ze6lYfch&8&Z?V`yay56W5$rPB?=$+)-+A#sZ#1jab7J*k|8N{LkEgH8wJHOSE()rl zgN9kwLdA^s#OP&xFulg|&Wu$T;tCG01is}~3ho!%x->m z`dRCvSnK|bYpV-KGRvQ_;yd(;@01n4+*-swZwji!O}!-7LXuT|M0p6OXD*(!Uzi_a3q9f z`^aXntT$8kX&Yh@_4tQZ7kYbxSQ-_(s%8OFHu92Oy53%YhF%@XeR7tq{F-#$Yz z6`E+HH9xU-mXy_Hf7&un8)xLT5A>hS6L^ixh`lX`EJm8cukccEF!q`}n$7X*LW+M$}*hL9qk|K~ijg07*IVpPxihS|n$-dXGl}NqL;n79{1zJd;R@zVP{cDqtLttU;xNHNfIPQK>(4T*-MqEjn3&56#1iDXNu;?e@Naw5V2vgKMBR!Rj*r=q zFiC{o^k>)P%Cvm#RT_`Pdk{x$hrqT&@xEZTI-AlMQME{ys;Rr}GB*DS-iT0PYj@)F3HtykU+} zum2>uDAZ4Qr7gyvrHxAuC5b++18v4DWkNd$JWyV?_R51Y)9>rNHhl$({$f7T&XAT-l;Zb*G*o zm(gLChW6xAuUW&w4oqOl1jaI8FR>6pf0^9!mvp;zKALGy3gy#1*O4251S~JFRAE5P zSv!GVLP$+D7CM`}&c+lId4eJz%v`x@tW=Yd6?rh{Iy7Vr3v#!jHr~wo)s#<>tlnQ7 z_#{xd`Ch#}@8j`511e`xLIS9`(3bxfiJB?>^{TgitPA*jpi;>d8cX(Z(gIZ8=8+(Y z@*vs;s5t4Nuqw87aXPF2To#WH;-dYc_#L=rj0;z`+)qZrv-pNn8;Q=~C9<`M-$K-1 z5yXlOha!NFJXy`Bk|{IPT3wfrDQer_bzQM{h346B>~1-cn8(PbX_QcIWN92P63yeQ z>H3j*sR#F;tUHODjJlI4pz+>JAy|Sr>V0llDLQAM=%o}LYm{f8+%5~~^jTiA#zy1B4%3tfnYvq|l< zG9eKViO&9H?)XJ17JVQ!yq79kT9PKQ7_1ASUwA0j%<=qZVzYiD~zZq+of0v4gZck)x^Dq)d@%_;qB{&COVhE z+`^KfaDB?GKu%L}%0-PJQ97t`@jv{jQwSISvw5w1$4*=umg_MJ6dPe_r=i=FztfI) z0~GG=I7pTL)J4&-G}xzp$B1&=vDdg%)`Kc-Mifn&Y@UtA!Bz=KCf_(H`D=_wqKkVH z8OqB1X%XFPX%J+DRZCfXs|-?t^Q>DgL%fLsK(+KRmRUpKlYFQ3T~A7$hN_k}fT7o{ z5tW5)|G*lDLcMg{cU>Wqwp}JVaHUmXRL8KAgr+&x<~=t2bBh1FK$Yz>t9XIvVW8q+ zsinlwv#W2#S+UM6U{F=WI@?kU^}67~1Ee{kM^2q{daA2StQHx%bZhWEi!fxKq!jZ)*1Sck_Bb#Kv#12E0Wav68oJoIRw?zz}Xb>eXArd+%CWC$6DnZJChA`-#(W#hVGrUxIi<*|6oB0N%e><)wJt8C*9$Dc~#ec zzaI=wpBDdc$g52fv<#wUHS4L6 z)dTHR?b$ACDwrA4s}D=`1z6qJ=G#5|@?L+UPljW+)$PHMEWd*drH92={<(va*hRX# zvKPhgyfr|HGvNUlCih(*z`C-g$!M{bK>kjlv2H(~(Tcqyu`B_-g=Gndeg04PI6RNC z485`P_ga1SJiprGe&S-f3!N3wQPrNUy5FPx!yy^DyG^yS=$_Azo;TC;EdbV4Ed|}t z==~to6%{p$LG#L@QK=%o1(Op8AlO=b6$z?X?z#r|HPR1#Z1k9$;b;*V{WgTcHc5{c z`J!Pd*xr%=NdF8N1tu9ft34{&EHGph=4sjZdvknZYw0vbZz5g~w|M6fWB7(1HRFTC zuzqL_yyqkL?YkJ(*jkb>nO3U=zuYR|Jbn?Hut{(@hr`j(s~SP=QqotdpL26sWzM$B zOtk%zCuC7zXx$~_wX>)k^?fq5+j3a4s+`wQuD%U*Y=X_T$LVy{h9MfT_<}u^#+*lC6B`Ho zxo8KVShfV=1${9afKiby8VX+w^{&DTMDN*$u5&Zo6wqL&b&Pc7JkGmCU&(cKO0vgN$`Mn{a=4B=BtwU@i^Zla-qH6fMjZukqY zAvG+pXkOs*kjf667g8C4iO9AG8w$Or+~KE*r+;L|X=rBb4?OFiuj5xsT6VW`djj8{ zIDA0yL|$K##v1tPZcPnt486?_-l@>@sr4__5oQKLh#3ZJ`ismpzZz241biViBH)=9 z$d|U9p`A3Pu&8@lZOtr;!uscJMP$Ah75nop!zjeF;2`Jnk$YMFOFCv^BBh&@)MMg| z*cI*wI7EVCSO)`>7?rSwTi#w7pkLA+f9{~+_uDIKYF4t2U3btUk;it2Z)3~(b3<+E zgVI%pzB~s7dSa3j=TECyNyZB0Oy=bFuPuYda5G~Tp^md&N5|lb>w+aZQ=(IC<`n;s zntOEg-ej~pY}ciakR&Omx3Zv_OMG|uEw;6GYYqs&TN1_!5VgDy@XuAQG+a#Eid2Ta zas!^tb3~lz7DnbFB<+f;IT( z42#Tjg>G}$a97Svv(32NslIxH%_fe(^hbaX^U)P|r}0fkvT0!}#X5TCI?@TzPVWK* z)aNwjISY2HgWnX5@0#rRN>_YkW_)Fq`ZBAA5nig((2Yo{)=`5F!lj_`h4?Kw@msRv zw@g!G5(&}kTU=3DZoG>W&B20~3%U#9@dKJtG~NXUx3G(!h4-Ul_YfbC{}q~wLGs%c z)l^SO%`8(5Z^8T&`#y_}oAaED%Hn~%EVWf8kcRAZYLN`l)hTXrv*l<+$Iri4P>ZsyZ~Y&PW1B<7yLLO93bAH+CshK*GyDTMFcn?Z*Nm?>sO9E zo675CcU%mSuKkM42sIb^FTr)uG1!aVZvXZ2=yziz(kTyT3Tr}~2d4yIfacIXq3dt9 zKs$Y{KPrCU2CAp;(XAr$0H|+^JRkxRz8Ybp$H&}HQATflT;#(xctxlu6^vEHB9#3O z3e+l#@Uv#pTH~a3>ts%B4@()c29Q?yVnuwbWJnf9P)>DdL+T|#EanJ!Tt(-@FUfG7>?=squ|W(#w~5cDftjRf#Af zpuN|wg}t^WIfIRqSY`f)$SDqa(w55xOnXwUk*gzDr$;77mScizom4S|299f$g6AK(h@P1=yL%Di+J!`d9T@cnAW*LtJ6Y6IN*(WfeO6qOe_QN(d zCd&L-+&ehk4T3U=q(66}>I6H=2p%==5N-_HZw!)@(Yeo}FL%aTM|G%$ZQo)}dWvI^ z3+d{@#m?3ED0CvBqS+b1!YbrzpJ?WP^IQyN8F&1Ua@>zQoaO}a%?y2yFYQG>wd*n2 zx!Kf!?Zjjb2NQfsv}v^KYOPL_fVh?_#$_zLgenG^fP7H*;y>$Lz=r#Y$q3e=YBtJv zrP^}vk{#$vWB*ab;qr3@YtNpyWSU}mCd0E%)77c?WK>a1@Src=tuT zyYY&8vc!E?Dyy#kbedlZXEr&N*H;6BU z`e0Qw%ey1m^)gU-cJwHZ{PuS5t1B3wcJHoxi1oD9e%WZ93e>8*HEmvK_o<>_hS7Ro zPwlJpVpKFF&hq%$CEmJLNgcl~UpqGGcHc z!J!ne!GTcrtLol`bjiElr~Z1So=JCD9C1dy`+TY|8Ir3*cKg)Ws}gC1xeyKI^SeXZ ze_s#Uu0~h%@;J5Ch^x|k{SkW0Zr|C`3u*Yiz3o2etPg2VNR@=%u(1>(%OK=16@o(2 z=nwC+_xiI(e+X<}MKG5LdqJD-vtv}nKYR4vvI=!we{lBT;9?10kV6LVZsPoUVFU$7Zb417B@-dK|C2m| zE!r*7V|HHfD~NoS$H&~OpzZT*VHoRNs*Vu?4&%t!MdccdE&AWpfVfu57h{u>zH;ta)%H z=4%E#uLB;%j+C(*Hg+1rXrj=SV@dIzvWZHyHy3#rJx{%uYynBjZuhEeT4G(`0C3_5 z%t>S#=FNq%^a**&_?TiTT`1wKng<2HD1DLvMZ6qqubrS&!EBgD8o3y)3K6Zd+%Mnu z8r^9#uMdsjD3s1hiol->7v$g_)0;JQV;>X{M`lrgdlhc$P*=D7fC>i5N!#gDi)kVd z8=2_=nZ_}Mfi>AF)@WC$v;=B28}UYci9eO7GmH^NOaGNi;-Icu;dJz&2oPVxI+S~Z z(9v1k9JPCQ%fxnjv+61%OFJ8v_C=QN3k;1c-QVVoXPO!9-u>)4TjNp=9U3&DHnCCd z!nt3Nr49ducVj@W#a4vilkrIu}GVVu>*4X!`$v9!=in%(sSUDLYT979qi+fG?vlLcjrpco&Qp@JfuJC6r z^QT^mOV0eZz?b;@0)M&ujSi`zV6dJ8$yTR@=8u`-S22k`j} z80D5~1F@h3acv5e)pqgJ-F-TA7xRJFafyt=%R&L#^c1ur0GRh~tQc zc%AW}s<2coqTb!?l4D#kvxC%9eOrSYS5cM;u14cS&%M!d)=p$&E?{w`1oA0@TxhBz z6GuU?Mub{ACU>YR=d=PYG~EAe{U#)`{UM(KZ8BKquLR{yXAKvb_(Qe_WjWLJBUsrhTFu4HVo?lp*X>O)S{fI} zKe^8uuW>s5NfYwwns%~h^5!*qKeo&{H@xhQ{DCFb-GbCtn98~T5;3TY6-qmCbi2H- zp0zi!_^4cq9*+mlP`|nj!QELQQex2XVzuZM)|FT`k!y}a+=2TD91T3SxDZfQwTH$B z$Haq2@zhDwFV_k@k!znoOL@7JkU>5D*RH>%Z!}O^l|!poPqL@SAxSe;zd7so*oqjT zR5TQDP~4(J=SWbXc#f>lz!&)9aVB4>))x=?a{@?dK|tA)aBMV6&4d96cdt;HR_nKU9$xq_!Z zwaW8>`;JUr5sF+hBGiW$)>OV?CH$1>evg8RW>kkkJH10G)?j@6=D=Xk1Q}Pm*50^S z?EpksBZurS5y3i)suBD9niY=aocGv7*9nqGWuAS-obvddbj3F^vr$dnQSJjKbMhF_a|_M z)t3tfl@u(Cy#!XzxVU$C`;3p~1zhujbK1Q}rD}7y-;P?{@c_9js8M_;=x-gGKvzC4woFY&^=QDTCRZd4Psf=I(th8ycQY%6a z>-u+b0=)c{5fSj>w+nEA2+35>g3EA-3TV18i4m<@M_>Lal(|^>zr{HhyYD2a#u z)Hl&lE!-M$fJMjtazZSh^G`kWqJ^7ThT61Ca0{_e&+ED^JG}r*3EF|6*`Rb?7^6m=RktgBd$)b&zF((d;NH61|`yJ^QB;1dw9c_|LB# zhLvv)a|=xil-4`~QdFs?eU+BORu2@^Y|{bbk^yJd?9u`0$$*hH`*pxSzG7uT&HBY6 zqpd~RL!GmRb;(XAJng7Zn z;}u8)9X>yJqQxA@K{?mPma#ZA$Ez-NFvp9DiAL{Xb(dE}!lEPuf`VFpCKi1nTKfkS zuOqTuDDO!45sB}LJRnT0NLVz5P(jka`}FU_`u8#YyPIEiyojH((9np4xA1M~8iYZ; z9iafOH;RH^^QoqNKn7zsKpyt^@jl!rAL!p*c5Ba=X-{dHnalDvy2JJ49hA65*iOiF zeOkaKug)F5hQ!7uVd;quc?n-l_~S)eN}97f64m-rVbOMqgdgR%ant+ycN@Q)1r6`P zk23T?6j|dT(#)?D7`?1>_L8-3K)>~b1kLB^TPKOr6LXyipoHumKF&Q9z|=6_2?!>UB)#wo2=9fqcBhsQuaV$ zNI3&v1k>bt!)`U#9iB*{(DP1fx?*nqMI za>k{8<}32NPVeaH7(Ds0t%Tkbl{6XBnwI_OXX|AV+eC~Evvex^M*Dpr^DWnI!00dL)jn!qfpgt`+qV-DuTT6cIlvD_-~8ymt{ z*3G&(=qe%rOflBYaU!=o@9Af5>=;igf0J$YmoT2PUDin5#*~X#`xwzlB_F#pwu5xD z3kJnsn2diLSR0T1RN_~-8~z;}c=nC%hM&vx+wO*+$TR3}_`W>XaZ4=EC3w2wDFY*` zK$c4+EE5_H-@~uZ{W!ub!)7Fa*sQ45=JUn1@?L!FHj=0pxCSwz(pFC7rj)sjVF`}t z5CrKPR#5(D<=dpMPh7E6pzJbNy?C&H0a)s8C<7jZdbv9LJHQA(;A(Clla*A#pHn=v zXM?)e?aXc0>yjKcYl|3q8lzi9ACN1uCxu!_ERN_d!erH4NLag0Cs!OXfjm8}GngOC z2fQ^`i4_?og%ufe4URCh8Y7fmd}HWD9J%ei#>M>$w5K&wN^2+w4TdyNH)ihIi)m9m zrqWcS4ThGx;N>f-3$dlhta7A$l;3usH#VCbA;p9|N~7rN%8(l3Za9Z(q|bR0o7@Ff zC4m|63o+*`{Y1=w9{Qphioo80q5%Kk+?m`S7U(Bco1>dbPcKD22i`Ym zo5_J?taNY-I~`h&>puDv$l_jqpd+-niA-{NuK_@>?z^gV_&40&y;4?w?~Q>Kq26x=riOaI?GDc&u3dM68f^^+Z@rF@r+?Oz zm<#%cz}R?7J^5|nVS-Gu9t^!QyIXTb-h7COQPP2q$G#(j_k596h*dmbSNc^4vghK- zhIBW4mv$QNP`lFt0hmGGcq;Zg0)r##PJAO+VJ#dzl=D3;8=MBPMS#GZ%@nrb;^?-e z#8s*nxy@gsMQsjDgO{NC!|)p8{Ryn*K5O%WNsC> z_)X;TpJNR=qikDZ9oon)Mb?wXQPviIl}5~H4F4yO_OP5ROt>w!OiE~Xa9^ZPDw*1m z-K|A|boaBRr%YTa@avR-38ft{#P~=*}nmo5k||f_F#HstF$W`{K(ij-%?}7^i;aU zVSYldSCIlQQ|l+N(pqLj9%vwWL~Ae`Cql;yH>BI6j}T;4*f?ULp+S=QsG$$hs23Pe zV&MR^j{XO}#HvZF`!e>(7RGf2n71;gSRh4q8N93^S74MbkX8f;`A2@6l{>UuwmabL z4#r(ZVkYJB8W?Jg^Lgg@?$(s#SH9^&a3C6w-DSyA=?;reK zT$n1Jw2+j^Mt>Ju?HIH`$+ZaE1smZMX9$t!b)}@33o%t9jPCHk4Mng@ePHNUR^k)P zrw$Bb2rC-@yB2xkU6z zv<5a}AtD;FQ7JP)Rq|oxSlH|U-v0+qf+XJm{pSB3-oJ*t|1#cx1&Igneh*(3-Y+nE z0PmNjZ;>X+l_2|B@cv1X|C4zCJK)fR@czf^X5BIf@0Y@EY98u-{Fzxx2p7~}f)c2| z0`-?qY-PF|ej~{EAR6G|t1KEo236AlkMfcn(PsTFd)@-57V`N29U4G7^(h)a0zaDu z&|{FG0pxuU4WLW<{|^ly%fX@np5bjU4KO6{pU?oZJk=g>{L^Uw2_B#U7JQlp(D}Yc zIKbn7LIcRUloKmS1IUd0D>Q(l`=8JNlK;O+1IU=_!}Wie2GCfddiCr2^x?#T2H2LU z`ZO9q(n)*%+cZG3BZFuF35pG-0nRM_pV0u)xPO5L*!ne#1~5VKKZ^!PcKnkxfD{iv z{l7p1$i&O2nf)|?gnWVq*n7hO4X}miPtgF9=TkI59f5;r06}m1X#iR0ng)=Z{WO5& z_%CPxN&mk}14sq`8Vw+W{{KQ6KsxZ>rU7)OK{SB$&7uL;AtR`1fV&9#Od3G){!P>K*IlP8bDHowr}J2|27&xiu`;UU=#$)AR6FdGJG}-5d8%I(1AU*UQ>=k`6KHsr!gpt~` zz}e`G<4d^3L}bFbNZYjAy9?+h_I5Dpgm#-#EK+$h#Xg-yTOf10VG{I3mhkWwiZI#z zV3cxscPV!B@b~$*gzZqw?H24Qub5kDwBXYs)mXI-_7fyFAL+&)>KMmC->byRNq=PH zX^{|zt8%WZ-_U#PCGj_+4K!LwhlDnukv-hla01F=WHDzWi3>y&dK@Z)?LPvZ{Vr{+L0WfmEC+(l{UaXkplb%+F(+}*Qv1mt4? zdXEkgIY0S&ny>idl3zW_tE|2|q<3?AWjrPn-YdP7hQ7W6cK_oNrS2qQRh2(|N%W@= z@{J3`=!Ts7jn)uOG{ia~hPQ1&w@+O!#TTf>ItR-jw2?6#3lD}gE=hw?i&+vWajlL} zdnRI8&fp&^)R_{R99gDY?mtAtsk{Qs_DZ8oPy76JFi7#y!$*qIR7don@A>NoeKhGI z>QBtH&u7|iO-_5Eo?|IzNa$8Q?YCOfZUwdIX>XF=*S93*{ep$G&e(}$5!T{Gvgq$W zWcyUn_=NKfmC?RT@OX?*C9On`@_(!r*r~fc zO$>|*24gvkq=NGvCL(Y)iYR~=H9Rn49?BfeOIsgmhHB*TjP=-NJs#5!c6aEg_yWMc z-NRF9#?(i|yqHXSZ(nd!dzySoEr@lD#NgocQ18d52hWz^F_`!kOA1{B8L-ZNy4`$$ z7PX1^Ce~0zl>ysEtFzJ3|LGJC*xP7o;kEPjWrhAI)VR21G{n&X0x_*UFVXyr@`CybBIKD{Ld- zI(N}GqqVUi?G%$x<>~S70r}$|26uCr+Qu3iFTdr>X5?jNHVoEFf<0|8iOFzrilZ$0{7m*k%28=c$Pm};grjt5gG!YWIOeyU&4a*fA2rPzU;vIB4W9>4~bfg`H$N5u3dw&2w( z1386jZw`zz*4898UjXGTd^)KOiB(l$!clKpFI$nMeZ8nMNS@hT2WphCKA8q1|s zg}U=>5^Fz?kBUGyxaZX*d~;=#sU2)ZAa7@6NsZNdJ0IOeE0H9A zp9;Fu1cG6S=`B9!#t$x$wxRxTxnuJW*{~=HZN68YAz5OZx5(>@V(j{OT5V>vQGBJV zI^tMxKf!ZNrDN)k%YLgJ-c)=>c4Pf+IMc*1cJ+O-QEFLYlVrs--m(9AduECGjviz< zthC)39Ie0RShL_$Dbo1JL~*Q{X#8nIe*sdhwD}5|*jDo_vDPxF{-l+;TpJ+t_ZWiE8;KUX}M9dXQ z+-EYapxX)3fGk>)UFlPQ$^ndF6=atS)15nH;4d#+s@7axSNk40-wRA>nwNqTg7NOh z54az9n(4B^9CJN;*K~7#D1K?)jFyalQm}(Mr?cpa;Bi2KI#YJ!E=S}JDGvoo#49&A z3!0-F1Te;)A#vdx0nuW*^QWZMX1LfHv420kahK3IT6UB7$PDDFqjgS@2t*61*4Q1G z*)$gj7RYx$K2l)ZxcU<^>8nRK-Py&MIg7`hf$^@nDW3gn-T~Ux721L?Vgao*)a(@L z#JFSCwsJb&Ug9K|O?~_LpeD0yqYGUe>i3+YsO8m0YIG4=*vOltUX6r^vX%om zw1oDYiubb(^`WU7qGgf4aB>_p3ut_5#ZM%_KshKuke=C_PiQnvKc9A_Cl z@TtioWxH|Wj^ZTqr#5~^^15D_4cu(Ogx=w5Y;f<iH04OdX1VuC3HHe4kKJ#_#Yv}bmE{ZwO)mTaiP*cEIcQL)4cNs}C`AzE`?UF{Lwn$E-}M^dls+JV*#c9kJcR6%mJ6VnROq#V{9oQ4LXXjQrjUhet8 z=nw@(o?S+3&kDkKW2cd){eW4@`}Kreljo8&2Vw^f9(eaa$FM!YV?7@kU8Kq)MR8tc z&tL5aR*mqGZmn~b+e6wlLl@=~G2xoLtb&8QIeBySywTHv+5;j1uNbdOJggQr^=rr%K%dBvRZTi&+!Ql8)n!Bc27#l5arC0~h&Fx>!TAxVI1va!n5bH7N;4C4YSgOY?$2jj4B zJi3xmF?v7xMJN{{@e#3Jl_0F^k9IKt1DlsiJ#gtP?){vMcTOan#RiIO&*WFVdKVkH z@iDp{iOQXSv{A&|Bhg&_F77BJ(doR4*hd~uaIeu?i`9Y`+b*!+McPqTo_{f`EE`KY zq$^j4f{6iehZhlvTKDC_FIE?pqz1oWY?T(&tYmTkcok~;xq79^44y+$s362SxbMEV zLXBB0EVUexSIr60venbkV3h``j{?a_y_Z%JDos|0`$KOh)R?p6eaNuz45BQb!#!_S zh_7m2=x-_NRw0~N7QwYviZB;tG6ud%Utoy3lIqMf)%Bf3+XA5KQqHr|3=F_ot!M|= zW4+3(zD#&DEXtHVwG3Pjmp0ZHgHo1ei)XK z_SHBtZMhYy`!)^jnDq?I!w^A(T^O_n+lc6Ibn_Uk?J`ECl@&G8yhP)wbe(!6*@_|s1>8`8*oNSdjQ(qW}`57^~rv(SA@!D~Yq2~aSW@3>K2bkxzh~)jC7h#s~(}Vls6};PvyLTU!Km8l1)zF3sF8uUnNY zeprbon7RIKO$1sy>}!%8&7xd^*ne-JT>Q|W&ErhNbnv@ZCb3JEPdac#nK$)Q(XfW1 z?^LbtGdl}cW=_F%O-haI9kq6zEGt3a4~Y>QQG@}Gk7xHM{pH5j++3;7VdVh4(Og%L zk;H0grMjLCAVUOEaYR;?*n|*gdx42H!rmg8I?f@hQI?GMv`4|{Xpz*g4F;psKmj&5 z4;%x(q;Zw1?mfLkyGvH424^SefnWh`unwSl64Bh@asnCk!o}L$3CGK*7o=(P4eh+n z4Q%eBZr#>#gqr6YwWy+XQt5A{Tdl^@Bi83n^`|)kn}5_=ss8<_6rMcTkQ{-6Rxg0a zC$fa9SH5o{>#lMz@Y0%Ja`>TKqrSs!lFQ)VZD>Sa-ElMob9@w5;{aoBsTriO%x1lO!gECb6Zx#2w)#je4Z@U-_!VtP7^ z7pVk$(i56{_D{jb=mp{prP-zH65kRt`m2gkl|=5!opTKpuD>sYmTPdnadi%yEm&3~ zEq+#TXnbvsnvl&P7^Nu31~Q?7W-OH8Y~_$(;Og?6=;bJXXGgBiL?t+(@l&qe;V`WF z>;m`ds81F6M=SUu%Ct(mIwx{ zJ6vwPI+nY`^LVYfK_AO$aFQ{NM@H*#76Y=z?)(=I9FIhc33WGQ5#sk$RTm<#AS8pa zUBaK1IUcATuvVa+n48?;F23Fb|Ecoy21a60jSQhySN%zurwy+dTctiuUcD|Vl=&?w zRr+k`E=0mogFY2py5ZBAac2KNLfgzV$qZqvi2cTFXfw`(J*SN#`NY6e93s8)q#nJFQB7M3wiSpS9J+k9vy{(OwX2Ds|tztrp;xiJ7)MMXF0FkN5Y?bQ9 z(_0k8dl$x)C?AV2x`@lMzQkt<2Jfvh(e2srD=;X0g1Q^3Ir=Kq`2yGa**ib}0wW7H zqn1vQW}_hM^Qo@;lM7L?k_Hx{R<2Dh#0QGmW9lLRa@sCZVM2=UXm~omR=?%t^nTlt z{XPvx$x1Y#>p+U(C_Td&8X%k^?MAKCr+L&fz6F#$~FAabVU3t9FNf zOvkE2+oe&L8)3;Fq0nGUW#77x0OO}gaAek^60SNL(2ccvtP7eOxz>RhJe^Co+42da<6tJO|B(^a^+lysq24ri_*v?K zs9r0xLYU9Lv8IzfDvmtAtp^FR+EU9i+MX0RQ$6J_ucRyr^=@4C_Zs1Ua00;IN)(`$ z!VAJ|npCjMrFDD7PvX_UqL63`YyD6s<-Tw>U^?eME9v61}^=CDEf8iy={P z5)?iMOw>FCvouht7VqUV< zFLW-MiuhxCNva?8hcG-5mVd;Gu;ty2MXHr>-I1`I4CVpzU;TPGtwfvp z@!euYJjq#^H`P`LHwx=h!t3bObiBozu`E42Nh`$CgWs;)AkaE$DFu93qdkijAtx9S7Av@jgc-9?bTGpIi* z#iKe(4x~aOpPuk;d5Uy;^ zv^r3UEO3pQW*V!46RoX$P`2^~l0Yo;)O<)>dG+QK?|`6;vB3e{aguFL$rEa>r+^Bb zK+Uo;OIE4J3OonYv53K$y=JBrFqQz2j=RVgb$QoQve9y$RB)g-zpJ85t*wzJXp>Zr zN+~}~ws42EutI(H8;LUpHBRCyb?YnCmC4{>ZB1rw3SI-HVd^o>9dMbI{$rN^J@J_t zxB`XCKr!Zso^Nto-PkbP31q4+%(*%+bZ-6eWAu2{->`blmG2_WE z92tuBynfSm^+XQPxPSSPVBi_*!FxeC54|V6V8IE+s2g^mxNf=?TX#<*9e^#0^7zbY z?08j8P_!;@va)K=ZtJ{;k8wE7hFtsM$%nnp!#R0s(JitB5iY(8 zme_{LqFQ_zQ59unhsP1`&r#p*5b7i|_I*Z*7;d|Wxjqjkrjoyzc`vUxyws`Qr6h^p zm2LW^@U-mn?U@}d75y1>aegkoUzGxL%wkDJ5tp#UxGS%!I-Ggvo6f_Fdk-(B@Hb-O zA+`8Bquful>upp$)H_0QEbYakU#+eTTM!AhfaV@f;|2^*u-;RJX-8x11~B0c#?4X+ zFm_{OsP4}xnF#7W^-KCvfr+BKMWYwpS$?^*ao=s%pT~$rk2W7Q+&6f|u}C|QkV0Yi z_tv*um+EgJE9V6khSX4Z_$=0QJFYMZYWE&GHJ4S1spDYgVS48}ytMPM4c_44rRs3H z@9@&D_yM79!!c@9Kl!rIQ)iMf_B!9>?(NS_iE`Hd(?Vju(m9gVN=EZeO0ZpK&x}K6!bWm!d(Ll2fbamHB157#myv3$ZsqTG{=UoKDE@xJU)MKNGmr51OWybJ_cDJ6`D2|6 z@D?h>^4~brSda;(Iks_xx`uizBOgEdJ_9TIv6VQqINp@f=y1>Fe!@OK_|bCA;|yyY ztImg`lr!YSO;qRF#7B_3l6Lu{h1=lXt#xh|@UiN+;EMAoS9r#>566(uZ|Ak~S zF^Orp3DqI-iyl=U52alF70P?mR$~4-c0;oU93wROG>rQD$QKS+SQ8*Pogj|$EeW*X|746DHjxFBX@nCmbG?n zUtpC*y`3oLUq(qZBN9|{ITP$e*rinvOic07=bZS0BkK@^>TCl)A5IQjMyOx?OpY2v zGM39?(hxf@y5Nv7)!~H+Bw)F4ZR3JV25+{alFyMyOu;Ohj9a_)X`y)DhB4}!g))q~ zC%?O!3%eHf8;lpo5@AstYswC745Vxrhv^B_He3Bp2&*HMUV8}i&dfCKloQ|mI6?r9 zd7)0HRM|AC#KZtoHuhxdPM(LE%-yL?BT5<<#7$@2$^5`aO$*4LWh_0$-jLOEIW^*S z&)sl|e#vv+Eoctc3KQ#&&%n=2#&UB8K3CTToU@k%9Db+yzCUxhnGuR-2D3>K9IYcA zvzG*iHZ4qnoTVzJmphssZNlkLWO0|VxYt4>xi@k@zDHWirO{s;0bKcdQ7M~Yj-M*0 zRiK#GMd$u(_8IOSOc9F5q2@g>B+tV!R%ox&^ZKgM!8DJzYYh%wGedhF^mmMz=KlSg z_73{U6_j-Ir^GG9q7DCd?{o%-k;o2bz2KmE#j`U1-8&sP72KH;yu{cU>P!td>xD|M zTg&JL&+)vu<}B55F+;q#*E+;ViRFOj7Ht=7I3A&@6Ufa7axy*bX*tY-%f*yk7g;E+VLP+bsP% zL;p6*FYC;5lRHKg(8$Ef2}A`}EO4Ix&0}n z`u>z$!wQQK=vu*Wja9!ThXtnJze~V$tdD8*=V`p&r(XWJkDVZwJxszYN{g<<_FGq)STth;-`8{8FRC}S$BZ_yX!Zln-F)us?i*~-tmQtg4NqY3 zB-H#A^1bRQ3e9hmO3G4f6aGZV7DBM8XYUyOAuLNI8olcs;e)F$4#F0NWschPqQb2D^;l6W z%}kV)pHVPdeLJA#Hg+pfs-zTjd zL+IFb`>>*1y+VS}H*#$dtT#2!&WDv7nY{cu%f*eerb7;}x^I$X&M^>JTX4ERUGUpzw}h_0G#Qr-+H58*u`9!VA@F!yY-oGyT; zkJdI-EX9a;Pr7{zd6rd*B*AH6<>kIIE=#LHmWf$Js?e_KlF^sQxG?d&N}g0v%riKd1oL>&Rm@MM zD3ND;O;)8jmgvEuR6;lxkZ~3y<(mur_9c)C1qc1ZE?*uxep9W>?^wbCQ1G%p?Xv5H zOyfW8J_M7-xW!6AY&OC1!%VHOyprPlDL(akUEUI7%sxiUnA0J@3v)bwsvYmyyZ&s? zOB>Jh?A>st=cU?7EYbwc<9TWQhn~F~-}Ah*!RgssE0^8x+*IP6Z7-3vWlz7cOX<2i zdxOI~Gxy6>JkV_J^vpaYulF~bPgqwy>o6s|&p)H4S5`~vO^K@>>^4P~iVRm|>8n^@ zi!9ycAEIs=!_>a82``~o^)s=j;!)^3MMV$?J(1=k&k-!bIW%rI20Ew@fruIxfI-O z`7I$|rkHUAf`YW#8kbyZB4i_PplAL0RyxSIWtVU?c`{YoPwvxYc>`#+4gEj zub`_&@Q~V)c$fDdSx$dLwXfRT;SYH8+bjJ=Ty$Z_?}Z7nE$EgztZh-Z+v_ep zFX(Ld%GHXk6j_E0M*ha#0x=m4yhG-LB+Xbqes@(d}Zh#9s2kVF$nbb}=N%oL&8eYQYa&+F7$cd0Fq3mGR( z(rp(xvC+wv2ZqN^fKxCDMhRmg1M=IR8`$iwKG?e;eOMJ&j^Z&^>@O)W$4kg+&tqdnAo-0sb>_rh~_hr@dM zj$!h_X!WnSuc}8{G|_62#u7NzXckMvWz@;pXb#n{a%OsZH(Zh5XL<+s@U(I!eX1Pk zkTE-~JI8vJcj=nFHuolP-fX*fnm{Y>^c$N6T-m)dxMWU2U}BDd!p#Dm|$32Q=^&3`PXhSi20RBAnS1wW_ zCB?KMz>+Cm)++YwMQ*Y|qamLFDUjOBr%nfo$9TS&9*c#X|(xtd-@mB zy)0wise;|g7@_UyXBxg~iws}hB9$e}bC>f|=JZ7_ia}ZI^Y_(cQpt+=Oj0J;+Pi$w z;ylNS%@RVYY2q6|yaL1nmxR{mO-Ikg6Udvs<~+Ot7_L7?uFAt1fh)8g_qV}umS2G4 zKRVSFIyWx@;qXsMvsXkg#~=;TjsXgqR~Y)c{#J*y0h#?Wm$ArISmq3-Z4-#nT3+^a zr!1yni5CiSMXq#4xXr%FwYbc;q-tr^bvqrl`2POkle+}?IM`;cK%BV}U3z!Jk0=Xl zHu`T;J5~pxt}Bdy;f&@O`91Z2wROego(}`($w6TFT%HeC4aGZweXr+(RpYQK?8??d zNbL1JMR^pE8z{%2;A#i7`OHE2zwjA(_an=|@RK(;nRgs{he@l#Fd&e`(j7&D4r!-m z9{Z&IOiK1+oQ}Egq-3smNE+=6Va&CnQeQhKSoJ5P(uJF4Y!0~_UIGzr_jXEcxL0d6X2^s) zJRhw7Luehw9W!>wjKG~RA!j?0T6Q5V{03v-GD>?r-i}oUl=7X%$@;&^ct&bFuyr$h zh6$AWz#T0jui^N|qnw|@8Or&`W4w9Vts8AlLaDS|{XvfwWHpT;KrH_S50$HYXs85E zv5jD1F%~)UTcO5ofpejU*WDnvP~u2MM&P?*ds~m}lNZs1J5%HoeUC;I&en|xT>6kS z4caZ-z0Q>k9KZ0^V@7RfxcgQt2W3LLY)&LHM;lhYM9Z;~EXg*UMefN@Nv}$bRAas) za*13~_8PB87daOOkLtP$n(s`Bt)}Wk>$JzpBW3~Y0)v6Bp9ROM8NYQ#ORMp9)t^YP z2cx#b99BYx*fxg1_|Tsd^==cP@2fO(%-xVfvGt%XSmuP8ygUBsNjJRDV6fV!D)mSS z$D*U#yKi6MY$kZYq5KwKnVOEh;lv<5$6;-)(>k}-@2=n|W(Krxdkd@kIY|c1!21B0 zMCL|f^pNk+L!K@}ew)nK7#T%lZ}{a6qoa=h6jZHnR={}$*4)B-HXeiFIzM#69i8jm zm}=|{H?KSYX&F#FjT^ydqAT)jhTXW*5%EM;%gBBZz0NrwWAnO9T~X*nX6@+9B09k2 zNPH&Zc;OKWVBFJnb3Q#N>@aXn*oyv?&DU_Lp(X*61#^(sJ};YPNoym&N1$yVK_JFub6u(`NB24Q@}Htz%hvY4Z|q5L7oc+uG}{;+q{}v%Zbt9lL4bRcXC^ zw{*&}pZKoXB@~1Rha}jHTscX;#4zMo!!Ww0SMunlF25S&NTP1g31Q&k1;_HU@t(VD~Qu0r(pxQ!9eonREkaUT*TqCuqzI~ zF6wxW?QZjxC0v4|=A)&TzenJPE9*}JbvLfPJnEVdo$K_ptSLlR+ey?M8&v$-(Ms-o zjAOv-eeLP{;2fA}Yvz0igRDyw|DI@1KYW<2+~!2*w}*gVMjaEd^{&4Au3Rv}L8cuv zLJXkhSPh_q;3nBV@dFVb(x=h?4oQYSOejOG zP1FygV0Avequ9XAt2ph!2)$Fi-9-?z{(^FI24N{BbOxqZeCGPU2wmy}&Wbu!a9LrR zf+7tRRjAi0G>(iB%D&Du&tterzE$3t!n$-Z#+>3Hb80jJMpx1rZ8l$3_$+@*okYKI zAlzn!8?EMEnkp@mm4F_mzq8=wB|Y8ZK+vt)$&)PHobCR7FcYwhJXBz4x%&FGGTyzg z!(fhy-Vx%Afia%G)g$wJqK?TG;%jxU(sKwKI3d2BSlR=%xTxhTgKH_H78#|Kl7c;S zbnTc5zcV>1kI7VvCH`|mb7WL7<5!`cMT%NThy4~O`Wf>v>m}W4xY5F(&_x1qB4P>U zcf*euE{FZ4tZUgp(fDGKh{useQ~0_^Mb_eJM!fLR zE&K+jY1fQz^NRD3Nt9MMdlL82FB4FLFG7TJSN&CAnX-&UIk=+SKU8>-W7g9jIjnv` zN^8P!P!wFmhG$;Ry#g`*CMUX5=ZK+b6xDrd;bGlZc5782y+{nEO=YDQq42|?yhQQ& zt(86+SgsX%k`)A}s6IAFyA4rvtGi}lqUpoRRY|JMW0!e$g=j8+qHV$9sdmvdHnKHs60TvIYvmPd!aF2soY6FE>?DA&ra$`SFHiVwAo4HS5 zFUsaThfQy^7B0hDt92VBbHA7XA&TU>!iZUNlQJKKZ#G!L=6qAX+Du!KUlg^l7 zUQ$HRbWiJ=DWTfzcmO}o5_xix0KsKk;mx55<`}=vXk8`(j8~QR>AMA*k#gGBUk-Rp z-e1VY#Q>;~9n94x@X4~j96EZs&XXPp?k~M44|d6bL~4)H&tZ&(xJ4F~NwHF>zCoK3 zt8EK6p0e5;#Oc-csu~X*f$xq_5OKpNGXIHLyGSGw@8$ccI0IQ-h(nia_-Y!`=(wO- zOfbqJ;BHt$Sc&JORez4%%v)$(ASL(}=HyJ=X1^lZF6n68%@6(qCV`93;1HuD|IGs@ zFQ>lf;;uy%<#1vv^g4COzJq+WOrwWtyKL^TEO#`=>ekN?;~c}NU|~#Lc_p&?S>^+I zxo``NEDUzJ!;g?Hx;7pYkqjLmlu`fMcZcudQ+oFvPZqMwxUqotU~l`Dz#@MNK>rqY zj&2c#o!t#`8LSKXo#cGk-S|tM$f&vRe1Mmz;}TD+`_2b>#p4(%WiM}-#E>=>ryXl_ z6pBSxVWXgHR#Zx?XXpBNsFY#hvc_|ARlVs~yKL9^2af*ct%HkcM&7dJ}c_xXWivWdg0wXI#(cncA4nk`ut38nGMgg|&nCPp-02kAJL*j9B1h_0fdnR-B2P z5m(kXvG-(GRj3O=NkZ5xWLHV)_O^7J+C_51W_pVVnCWR>bB^9q{khg_Jw+C45N+&YBk(rCP@K z@6uE{X+B07(#VJ8M;w40k#;{MKjHx7h_wA7`6)PfIc-Izpn(kpHH2iKyWt=Ujx{m_ zvAj8DBKsWR+*g0%#?ZPS>T?D%=oWXcecaa?r8nTIA@q$K@HgNLUTT!Ch>y# zt38V>#wz%$F?$ zfsh152q8a6#*olth98wkaG)|A)7o46)VAIhE8a_6ddt1Ff{K~|mjpx%U=6EHck`?Q_n|5U{V$^S+3|gKUoNGx9n1UuO0Iey1}2ua2)e{&VAhlJUmQxKea{*zsY% zJr|ZmZ>3+4?R)3wZe0jl_|!W`-#L2hue+6_?|%Em#nk5Q-^u?|>qQeP$L}zz+Gn@n zCLB-xkmlHZY~RHKV>ngXrBAqz8T#GUize#+=Fz2SZ{OTOo=q>RHeX|<-EZISe*651 z$2!d|GU18$bjmgirZeTzB(8Ni8SWbei{4WHhcIdw>y)W8pHsiE?490Ov-O5q;QO95 zbeJmFHagaDw)WUk$G+I!o3QA|T8^DP{{FFj$2yO7AJgA$J@(Z*$9A(ho3!==8|%g3 z{xy~C&88fy8JV*C*IZp=^QY|SLo4q-o@{%_?ow;^-P**YQP|B{bEo|C+uunPNbp2I z_6t#=nKUwmSFN9Ob9-v*`>DJqh0;d8ebdO`o_-_=R!vOW&CaDGE{y~Q*j>4H!bnx_ zn?~NdyHZOUS$QX~S62o*-TuKpf3H({(sszoNoV4Z+`Idjgbbc=yfbJdNphs#NEOq* z7r^{n8YJcAXt|m2jgnsA8Y|(UD&gRlS8@7JQ>p7qW0|~@d=m{o%h6)A;`_(18pb$V0c9PBOD|U;cQm=3 z=Mhlu01?-q;+&s`68i@%MSZy?zI)RT%|}h9UnMq3`d4P}Ug1Ek%(=ar#bLLsaRH|a z7~TbN3kUHlnV2}D+U;-W4!;uT_Pr2)wljrcliRNJWXc8Rs6_y)K&E9`Qo8h=?=i2c zIkS(kF1tcMimb{k;N=wXc`0C*Mts!4i-S9a*|!BI`f}${%y;jln3^j)y%*b;i2iDZA`j)gFO#G%1qgW5H*m*4VSKul*|wO zP~yn#%0BPjNeL0#-0;6k7Uhz~wc($GFtg$}C)AyZ>{CXH)w%qfB)Sv57kzgw1;Ido z%jBgWqfZ{3X{=hmK>NA=>o+1MbQ4uJBHCjc5kGn#EKnN}f9Smt@hgQVvVNaQo{}S* z>BYq`SAnGB;&6(wAn-*vGRj?522095#O)}DsC|eN(S3+oj)uloNgySCu1|P}@h6IS z>_eEBvvK4K7>ZEmEkh)x+JT^nSTAKB77@x+B+<_8x#&;KV<-%@w=z>-$wC8hN%lEI zjBqgfOntwJ!Ish4N9uL+E=hAI!*EEC{rp56>Wjpo+((ujYSnk8JJE zp$kJ}SmNT+dAAY)n%`Iz-`2qm}Jone{NMB5%5G_CXK9_&5tbrVc zl_%9OnJsIxydK7C+Viq7smz)+l-t_OZ2-qpHLzx;yrVdHXB8VR3C@SUqTom~R;+M7 z3)`}*^#ez02iMWO^|^D|+cxKrx1VzoV8m;%kw-ey&tx9{!dd6!(wf7SPX8gES1O%v z?jO<4@h0b+`$n`oUu?Cvv1;>l5CN-U;f?}692;@;(EFJ!>8&H$r;T`Jz7=TFu9AJb zC0kZvS(z=T+axRhVCS>W?ETJ3B;$8aF@S+EMcPGrmCo^HQ@V4Sr#riy6I%m+A%PuW zcVtAHT%<#JY-V|dhDDBiK;}Ioz6=a9zvj3&8PYk=tH)=6x$KX}asS)&0Zvy|#?0P2;lsr_b4%zC9+89GRFDzNA23%{Ci{ zs*Cj9zmshzHsY;qr&+V0J7BeQ`^psAxM|Y7Nm#_OAu?*>{-Z891Wt#^ty=H{atGjN ztg#>zmvNOP5Wk~&t!)DA*r*+mH8|Hm)-HjEN96Cg#+!5v7agy3gy%M|O(0O_+YoA2 zKiX%le;wTVL2ByfFbb((paZ~cgDfGGitOe(Bnp?>Pigztw#nI#)~?~HpEW0460)z- zLkwcMg)ohiM*sLU9;y1s#^HZ-#_ zcJ}F~E1%Z0kc*-Z63TO+eELDi?tB@`N_m)l`H6;7yQsHx8cSf!E@uW=jx02xd#nmJGAx=R;%P zhVc#AxiW1sR1%1qHgQEwn+z3`BO(h|rcFd*K2#*_gm(3kn2TwXVal}0(5PvXL8fUF zmtopuDAMv_%Cw0xa*`jFo5!r1%nVqv^aTq`5T+k!I+N2dxao|$A;tN-jw7G!7V&-4 z`@@guv_$4%H4fOR^Q6gTY^Nh5T4kB@>&~;?XZ<6=o&F+6*K=pf+LAr^)oIocc?s^F zW%m_aPbg+D`s!B^hArA;eUJ*Q7D2v5ec431a(8gl>yRrOD$rG%WGQ^ThuBD6+t78_ zPRku=AEnsGs;kd3-_Ba-2#n#hQAo7((eRS@!39;DASlg~+2GFVFI}7#nT#^eS*DtZ zE?a^st>DMQTR%=QmEw`H+S^#S4q~mykkwC55@kZPGW+R|%f|I?-_WX+QktLgf!z@l z^@A11ZN60fCz7))Z&UYn)k1p#o#j#>wX~I$`_bUvbDYhS`Jzqu=O#$6?4`a$AwrF4 zU#`ZITvcC%#PqhoGyVsyBt|-Afxw^`f z-8{!B%@xgjHmV~D`mZtGhf=*@TTVDABF_a!5v`KNcB#Q`Bi;vl3C-n|+UfMMs%)+2 zQn--4GnqSksq(oj?b;%+egM8B9#12Xm&*?O+^VNchZ6G^D5WgFu1ZU zH_6s7*q6%>99Y=RAyW8l?TglrlI7IHUg_O~#*Oc0pX{CFNaFaY91@iVPBEI@>PJ)S zb4H%2^_i-FDothXu80=?%0=0#Bn@++J>9L5WCM4!v=^ltPE8s>yWAO^Fd*W;!#c1y zJaZqLDK5FGC~)a4-^s9JmhW$2`z+t7$l$pmp-573gJ~&Pj|dOZA7@Y0I2)nQ!y9zV z#lx0G)O-iGk8wWXF5`=Se>8A-BDDRw?EcbD4OgRJY~46!*8G&zoHGSU4#XQaGx|-@ z==#zU@@mIctISOKj)G#6yU$E+4wj3~wEjKWLT{r>CiIB}#+$X2J+;8q!7iKMH4Wi# z;L;+gXpvO3C{|GwFEp0j+l5s0_l{^qm*F)l%BsUCLEIIi!PYdh7WP&!P%zF4CC$-a zFOMb_9!I%Hn&lpLVKX>iq8);rIW)qzqLK7v3&nJYN;8t&@*bNlFUbW!MfxCwUue-e zLb<|+^$ku-bA-M#G&~SbQgiMgz-_rh*=)9HxsD)qj6w;9poBG&veyM^8p?h?eC5C< z?z`an3`r+h**~Eb)W*2T2!)qjc9com4fYU{ak%D6B z9vLSjmZLRxt8*ULXP5X_kFu^ZW;((QhQA0Y$qG|SLO^gnm0DP7;q12GDyvo& zj$_!u+?B{mEv!4YbMbrMbW>b4%UnI9iYQxsZ1-li2&w!hc@b-~tfy~Ci7r=tY>}z; zbl4wVPy2G``|e$seu(2vuv7OgG?vx7Wxcxhf@SsY`n1Yy&)MjLwKZ`jS0YkKwX|+! zX>G2o!96 zh8C8gA17Q-sAi_Z`JV_byr^Qa2*qlPIUlf6j;d*~!}4L~t9sW*=OSIV zAW~C&Eg1WU(*G=HOW<#Oi?@jyWf()%V#U4r>rDj}4qG))%lr!(1a>SZ;I{d2eF8z%}LX1o1?50iSDH?yAXX?8E@kV#C{wH2BSRFVio8o3cw^7hA z5}Y-)oO(IcP-USy^{ioqgdlkoO>IMHym8VUBNJPkFLl7g9{Tc5 zTMkQ|d3Q=j_@}X-2${VRC(-5~frE~vw`pI~29nSW&SvAJF(XH=O-tB-8yK{O(oL>yHCG$NWSj zn8S6#GOjrWtMpN2NhMU}6RN3APRmX{iTN%+1pBF1;cm6buI%I<6Y@g?GAKLwtO;3T zK!#=~+x8lQ`Ffg^VIC*3={H>0hykiJl2G~A`puall49K2ox1_qdhm4 zbJ{OU+e%9WF3ZxkiR;wPpd|8=Sn=<=f(>{dbBccCOS+o%i31)BQ|_$ax~9svBt7Bp zd_f=zX^jN>7U>Hmv+%pY>utdoBwdtNR>2Vx@=el!h{;03$(APJiuDW?`ZX|@wWOvZ zczuJ5nL`oF>$5W;Zj8?EV50SEVZ z%?KhM^7@8aAG^O5P0H={VL{x;_*e`)((9XLfp^8gqrJW>I7um!z5ZLku^evj`Yu-y z&{g_jEW(Xm-y944-559>+e{X?EC#;G>npOr)6Yx(X0NZ<`f_V5!Yy9kYzus44E!yx zufPH)#lYjFkujVorT+^DqGF|=;H8nJ6%xJr5x$tsmSeRu;GHq>B&(ePKOF;4wVD#} z_s>gyy49L|@vAR`Quq3A03{3b(z9a4@ap|SlFoYd!OGL))zk36By>H@Dpe~ysa+Cw zZcOB8kc(qJX*XqTNSxR--WE6!zIH-(;H38X#>ojAQks`1$O7YwupIVRxa=D=?~A9k z;5sl8h46qQS2o1hA~8UyDTXE|S$;=ovcvLcgeGTL{;{FSV<}q*L*pn#IJF-&ks8~Z z?6De`Wh82Oa_hw~vE4l_FgWrD$xgp#AM~eTrJje&TAl>*R-$q7g2WD~ATg%TAWr^y zT1s}Zx<~`Mlq&H!bCjKY!lXiH+7-l+o!o6gJ~kj3*~vrAQU50cGB!JTmV?;OWi^s=7-d5eUh+lM%TXx^6^zumC$-r z8#B`XqQVHX6&NV=_ii%AG+|EHosv`}G%o7}$<4WL8t;UEQH4KAc;~tw@PRlX;j1+j z%r`)ddJl(eOk%+PBE-O{z_$Q4kreLNRjjyFMLh<^zGQew#Kda3KO~0lW4)wfe)+Td zA_zH3N?j|nMt)BOe$Jsk%=E_&<}Cd|@j%7qVZ4)*_!crQ1sSVj$f$8-n#Cg;qb)h1 z1cferw1UBR{`a{Ycs()A9+w}(Z z>ela9?nu2%xuf;@%DqW1P;Q2Pk8;QAdCDE8XDfG{o~hgkdO9xGG(?u?=xzm?qz_f@ zRNbZA>AFL?UfrhLIeO23N=fJH-O9aB*Oj|S?^JHNepI69iqG~;!RcFJ>s<~Z@YN^w#O{;0eSnF zx5%^4i1)bizAoNF%6nA2dzDw#&-x3>+bP~{%KM>spH^O7ygyUk4)Oj#c~6LUo$_{z zca`#<6mPBa_K3GkdC!V>uJX!iRnJ#mvGk=+#H(6aY*XrE)rU0k-k`iW zeyQ>f6|X~i<%Ed-)o!V&TfCnu??~}}th}Sedt7;M67M19%@FTiD7nFCLc(*C< z1o1wtygB0ineqzV(|>?h6jT~3(10=*om6B1+I)HGhK!4#^5I;-{gdUb+H&03O`o?h5zlSM6Sg;+K6-EOyFvw#)*?kFI>kw=b74`!};3jErQ zR=69?xG-z!7HqHygHyZ7f+d(R*sGf@*k4AO^Fi|zrioiD@Ed?78zzWvS+HFuY?#-F zgwZI`znL&ts!0~?XR##Vr#u!oXat0{372zmfXoQC! zRp5yhxYYzdroed?_%|k4NWa%N+5-P5mb{ETukQxy%PKR%CIudDfft)#nIXJBw*|h( z1j}sUtwL~Tv%ZXp<*-$K>}!2w@iEAZCNqmUdWEb1>RO{}I~CX%y?{S5!7U1G3}C>o z0an~n^TRR$S!0+le>5Y=WMmCvz`roTGAmgl8SujWe`R`0{`mK_+gCA^g;k0mejyG0uKGR%x1bG=0x04JMZnfEQy0Qj%Njk*dCAf&-W%r^m>U7Mr67^Hy+ zFPagAJ@EPr(g65hOtA0?UY|i40RO-Q3(sJY2EZ!;o5>3cVUY&DEHonsJK^;iqyg|0 z6D+KSMH&ESm|$Tu;z$EuhL}0*jjb(%Cnm*ddLYyk<(1rinASi&q(hm~3^j5RU?-X@ zYgpCgrmX!Wa+mDtc5AsDUpR@fWNW7@REWN9&)P2&TF^BcrG3HKn)}vw2U4*xYhQh` z>$xOhGnyN_xkkyCIKS&(cz<#k60hb!HcJPd|Nn;fOcv z9j#v`hYI(seSbK*G^>)Q1^0F4rem-+Cxo`iL8NU*Ix!`*bs0z)yX{=Z!dIXB+we36C-oof>TK%t>!2XVN`FHMqLw z$K6_fyBH2Rn%%B>j%u&?A|;$B_p~>pWbVri<-Z;x$lWVNtMPgj`W2!#uT036Qvh09 zeKH#O=LKE$Ckm_OcW8xsq>R@Povq>Qy^RBD6int%csRX1v*nB5s!*L-3tsmpwr6a;QAmBOc zyR}!O(P^#`ZM1x74lS8~ToAGoe9a+T_TJTRYJsCPK6)FSiPHF)Z_mpA;Z876zf#x;9^?r=}>fkp6jPrP87NcAxvm$I?GiUTULo zgF>njYWYWxbb=k{;YQ%VH!7ZX+iFUd`L_KwDPdmMkEMhPwzi@>f_%dMnNeT^b3%c3 zh0(nmRJEk`1zmk?Zu)N8QA$Z;{?Tkq!C+1}Nh<=IOj8EW*}>pO)rf(1G?HTN_}azV zQEO}w3{94I84=|@;j8e zgo9l%tq{X6q5N$d`=P+=cQ&2r>&Ms6pWJk&f51L5{PD(q6F21lHrSKueE0!)HH?z~ z=}@ApIrp^*juk1`gSA+wmpGSFhp7lG!X}mO@-4knOyaW0txadr{pn3-ZuVa%hKK*y zbSBUF{qdyPbjI^wT2ohf)0qV4!#4o%rF5-k4!+x$+QngU>;+R+=l8sLd!_4KCkHS{ z&AF~jz7}rl`h-P?Q53+dZ`3@`XaRE0T5}mD^Bej$b!Fsia83y)Or~830q-B!s-d)w zF@^IQ0XdLLI^DTW%0RK5>(IoBbb0t^WDxRfCVAvZmyr-R`g*o*>^D^s^tsAL}{{ z$L8zPl>ksx@QJY9D5t-tscTHr8He*>IU^SSjnTV66vjAh_n(z*@`M$VYx;Ovv5NE+QiRpkhkr@ShhAzK+ zqv!O5xZ#0*Q*&|rC>LyP&fhbOqXnH_ z-E%$TApbFxuGa5cm3aDHI~d}5f_}E!14A{>X7Qy5h8YEQ{@`xXT6=C=m}Y+DTlk;f z1ceBGvPjf9`t!c3-}AOVp*Zy}u&f1xoa?*QII3iE)b(F@IfcDzPU|^)sBmj2@Jz6? zk8|BY!1uSODPIY()sc}bh{tn)se){Q1{`1c5tNLk$2er1$U7-c*jI}c6 zPd%H|>5UN`XrYflpW=9P(q-rXDqtw^SY>vHGdPVLIB(|+=HS`!)ywkM?R@xFd3*UT z^|k_YX9v3Okbr1mj+}hja{w$`LkfY*f{pFA0H!(j*aE3yb;5J7Ymf@a0rbhIbJ5y0 z0`|?C$BE~x%l*&zlDW0F@MuZM^GK-i@lfOD^^phXHV5`_Q5M#8Km`s4ssZ(cmJiw6 z;M{I={+QBgHal+xM&f#>{p{3jUdbVkvZLRMQKlJILPg2iBz}dp%A?rK{bu{9;w0y&!J4Y6Q=^#85U0_AlR{9UD; z8Cvj`Xnggl3>CgRIhOgwwg z>zb<87|FIKy3%tXJf5`QNDXWvAr|#VL!P~%{QZ@oz`?K^3?SA8QAmxH$U+M|!(do{ zDMO!?q;q>dz`a^vf2-~a--_wUS1^_Kg?6O5Bq2OP6-UlVH2D&-e{X&Yr%DiC67NUm zYmH5*o<}P~Q~GJUD?`puabjpi3TqwXHq%db8uRWK`x9NBR}x*nh@X_ED01;j4b|c_=2kHO3d5|*W|R{RZMBckS<%?SLeu#)x8!lU z8U&mcz|NZg_4Ln02QQQ~MDD#76rCmps?cWa5YsG+B#mps&yyE614PozX4iP<_5tay z1qP?1v=?Ej-GzEIu(ToRulfH{vJe`S422FSKPWo_TC1g1Zyb+ol_Rhj?3FpU52rL} zqh0CT&Tg0k%O}}|4s6!#CAlFof@Vv5t;J2+#$Ncy{SKsc0?sm}Md_(#nQ{59-O z{|xP5YzNsmwc}c ze~)Hddtw{75@W5TO^q8{xyW|y49-&^-#nfodiZRKJ$R#ax9dai$`LyAt@(Rih!+v` z6EbbdRZQe8mbDh@KY!jpC+keunVUHiCb&XIs2hwY9kdjfRAp736PnDyB|z$Z9)RG3 z7`h8h9wZj*=7uE(2JLL~I5K6gy5>)bC_bd=1<8_W+Udy-*-`g9#Y1`gDW@ho`UH}K zl@6OBnl%YoWx2ILq^``T#Qxo;Y2pH5O~lM-||mJ&KEnTNqj6u1}cW(QT&OoKhS z^(p+ncX{7n%P;Xjl2@v8)-<=f6wmi%ZbDg zp|W%R7SbbK>V)ze)Ob84t z(j_GkeG51t{DhY0cutHjjA+en#fFh;373(~>0?z*ykEI*#B1KQtx|fL;zO7`6v(70 zf@KcHSI>{-`Y$h=RhU2(1Q{|TSr54U)8&oQR%X2**$1vJ(w}>~SIurf4sW3FLdw*t zC#oaKC7`p~2zq6^!slISwyX!z{J-a(%@w3DFFP+S@T(&I0TQQDfu8{X6HOG!)VlQ| z2{4a?1;5u+e|IgH51d!$r*~nqQO3jC6CzfM8;Byr*T-K1W~^-9rZ8g$?IAp_i5b$* zW^p!Q~=o6dMz)ddk^}4y98Z*tc*&WR%7IZV|JJRG^Qx&;#QBa9hhcHG)(3@NiPuMeRU)M6HKf!~FmbLEq2}6i`d6Zm*Qxwn%Ktik4(M+XSIdAIfRctj%zX0?6`7ri=0jET4C>$txBZv< z`b967FVbHeCJij-PUXC~DH5}g^oQ49d|WBITdco7fVMiSzlBqz?brd~(SMLcSu~|D zt#zM1W(=UJZmM9>VW^Kmh$DkPmVf%O|-FvlB)vIZwBdcdhV zXHtj-!HOiUk3~{sfGLu)@(;!cOHyXJ^~qAS?#Qz$u`Aw;%~igHoT{I`#k};rZR8Uf z+)Wu|%$%|%1>~H7aR{PVPbL8aSsDGu-nd|b-3tif5;p}73NA^qsi`(L7k-aC=J^t; zLdVriXk>S~kKmfWKQ2SqpM0uMAF{rlvl&L_dWeI=Qg|U)`T{bFM_M%mCM# zc|7>8)JmqSuc?)qZ@=L@dp;dC`};Epr!m3mAK|t7{O8nS9#if&?(kG93&M5zX$Gs? znRst!(O}HE|4bzm(wJY(X?K)RYjftcu*d%gD}_w`Z>)&aKuBHdlqnZX3C}*&Co$kv zb83c~Q-%0@nOTzC71aX&h6bH5?+##}am}Kdg@#MiE40hx0;fxvxuu2-Zbxu`Lg+HW zYJKA7*{3M2c29I(iDJ8yHagc@<>eZ8a4A;iT&v92u5}7JWaYU6le6;D{JE5;)GE(d zG1X>zJN+}fR;P>MKRO*tg%^zSi`Ls1<%?p)o@y1lpHw-ng14#)-V_UYwH0!xRPY9= zld7OW4}>IKgdSA=KCWtV5;XIab32C&_xZDmeaR(U|0Ro~?6wt-wXMe@Z0ZbX&V59Hk^KYVIfWsqFpu(hO3?Tqb9s^{qdY2{28+iEo_n z3T=@23N_L+WWcgOQwL<5zt;p_hccTVNaDuwK8&Ja!aZE}q>J_~p6WH25||lDiV*qT znw>yPB+z0_!n?$qs&f1T6MPsRiOfgAZipq%d4Xk5rjb+uNhw}Mw3ZEQ&R5Yd;ly_| zfqF?`xJuwd@eWc!21v(Q}VtE+k2zXpq>)EJJ3+vC-u zMh=VWGfy${7I2~!8^0VY=aZYv)u*xY=}tj3zQUd;hDVZolXNm*b`%%rRcwx!c@nU} zu4qyLRxAV9e~qy#(b@mIzg45%G{AuQg=^$$-u`km?`2y59h?zl^G3N($%|}Y=yN%H zVTv+-dNsXZ+B68B7#ZVz!OH^eDly{7aS+dk+;zbHj|k8sN91IeuCGI)4Z>yJwo{HF zt{0Y~N(^cgRgI&UBZKF_A9A}RM^mlSdK@vAgCRw|LpawJ0Iu>1o<#WNs|#DA(CxYno}Ch`ezrG~}U7LNNx z2A5OptiTEXRTzp_<3e7z8rUd+*w^&g!~gZ9O5rMb&2ID0%(_!@@=qb{$Zg`KVQ8m( z4$x9yqtrn*#b?} zdcxPw(o4mQ_14R^l%@&e?hFj1JPuSk74E93Ik-1T8^D|b{Zw0cDLMAG@ZSow_y2lvUDI|a?2CYB@%C8?pBDp8dj z&7Y;God))84n+9}1@D}&kERWz7U_=xmBor|Lw&VK+RR)dKl`t$ceFpxmtowy+Rp8T zuFQQL(Hy2WXR*7{1fgE=$cQ)EJRM>m$+qj3q5M^wAI^AJ0w^TZwpSmGkt` zmqnly{B)5C9txNnW3)nqnJul2JMF=?IibeKlql&0Olee<^jawY@u(}#lYMxIJ&LC)5W3!F%Y#t@B!LxF9fz$PR+_056K=A_BZ-*JT2 z%LXN_q6H{Vi*x%p7Gcic_h=K(B4cV!8<&lUX_MAkpTyNVn0(0<3E_s&#IvB1NS8Df zpP0hlbtM|f%?RbUAO!jkDyRjvX)14#IL(L_18K((FrdsT6|r*9+P1_N>7Z_gFkAcx zo?1lkbdqa|+7Ufjf+wt~pJdG2TQH@b+WMRfWcwMSz)}!P1W%DQ-(krDSOBXkv;{3% z+v%g3hY>xYW$4*P8&1?3*R3n;_9slia=ln^LIBlrXlYAdPYY>_0P3%Y!l|D{^0!H! zp)iJ#?$>;bW{j>-+WCHGrM9;+br;CjO^KBNs#{6>5ho#l`bY_&Fh^$ypguPRP^Ur* zlve~$Up_Bo3@tc?$VvoI`Cm>k1yElq0n{n(NL2!;&uLdv`qa}PF+Wdj+$>lxifo<_ z!01r^M<8`&sPU69Mm!NRZSE~((nWB@l}TK&B)#1D7#ec2b$p6lP%VE)IEDB!G(7st zk-M-zr@L5aI3M~Yn3W3#FtkLe?k%k+^9-nLn8_1_Zru5@;PD9bRC`9e7V@mKV;ZJM zm6len%x*U%rZ$?p7phn5RsKhZpaoA1Es zFQXFECqk>vGChOS30foK>_@TU9@Gdn17sw#!Z66M=n5O``ZdjY0uQpz{`L_Uxd+*YlV+<+w%R2IU~ zBZI=ZE}vcj0k!=(m8tEZG#6fXcTE7O1gjQa2YM8Of8HCZcgB!96cCICBNb9#sgQc- zMUncHXJ~?!|A^+;kpaS2L$sxgLzAR5uY^ux^yOSGo?R#^RGB(Uh zR#z(%#W#2^7a^itO;UR6r>?c1o?|Rzw)h;O#wRG-C)xtN1p9z{F<@#xj2PVhw*6G< zvD6M3SPS%-fj?`F=ppSi1{qxl^||BpdrT5^$AdR(3wCPz5B(KtgFUlO3_NnjUpTd6 zCQ(U%^1e@8CPib22Bb=epSQ~HbK?^la}ucL{C+!WLASO2&5e5~!qfJ{Pd|$P>uI&ol3c>1%r{BCv|4xu5Sy)r+SS~Y|M=?TTHlZwI|%SDJv`B z*qe|sE&H{GFL;u2DNr*Ht7- z%u_rEK!^Xwp6`>?5>HIss~vhl3A&E>hiAXxACmp1KQ;SE z;L`rKMXrq?=Nklv@gZ=?`zRqQWqIk?i^L(KM;mNkm4+T52j zN_u^M`fmS~H@7g^`qR>PtH2aLth&KwH@d-wMcxsOj?*0@T2tFZzWPU-2xCUFo8raZ ztp2~cSj^0$9%*b6e8YPDTH57eRe4!e<;{y!<;}0FimJ#rt4C|Lgx`8J;R1eBdP$JO#QZn>Bj^d~B4dEQ zAp?}5Ap;b2k^u^KX@@XEMJ#_Bfe9T*No@-=#7h=R%3Mil5P$`{Epvc=?2w&P`xH5B zJt#xDKD!rP2KpnX>UEY%k-?Mr@|2hlGz>!x6WhI+hj+{X9b_lxZ0OQZK~ku|kyV)H z{GOa}Lw~i<70PGY?ZK1^$Fbn)TGdp<+609Y?I31Rn2@?K>4tiWd{j)tE8i#G{@bgz|dl7;zOF-3$D@PKH58N@j&!04f zNLrzeyfAGD1<5|h$poFw1I6ZTWVif+uUQ4&=y=mGg(DrS!# z!0a%$c)BpJ%)V7~TB4-5U(HLF{#rM-kz4#DDbQgGMA%rF4o@Tv*35mTNPLRrNt+5J z!lLj2)`e_gIM*YVim3L?Je*bF2;8C-Bx$MI=QP>}E;wAKuD>E!JKOrc3+)S7@l;x! z9h0}E-5VTQf#dWp8zT?Rv1~3`<(8y_(%MD?6VHA)^$;p4AO;(3XN|D_W9oiLx~*hk zWhk$og{;BGLH($Epx^qIRVmyU-!GgjHr}Fk-Wl)Ec<4HN%ti3QL-hNev6O~>flLEq zEw2(J*yyqq6tC#7f7|$KTt-khRQ8@>b>MI?r|rU=_SN$J+VH!W1oK@RY&o|O6OWvK z(zpRS~nOsiWq^7krbH-dkfSgF~a+no{>e<(G$J2Csc z`cK$Y;&QrOgG3aHuve_cpr|4nr(Dc%(M=}V{yE_`$#SJukhXfNbNeo_!-hrn7F(rr zS%*z)9fj3y+nwF~Tk&n|vn62Pd|#zA(9T2HFz%bJET_i?TV3HpEWFrBYDMuYLDtxu zxI#;eHk>-5HGHiA`94&Xubc!5|H`?OHRf4+d-zS{4{WxeJz(wxVb)E0#<}k2^btIR zX$95S2zP=BBU!45%9^@UPHt*&WglFAiT>UHi0a@7Kh9#Rle@O`tTEV=wfZ{IpB^2vF`8U};J}V+i|12?JUF`K?K1SWb zpn?L=Kwwks)k`R?gj+Q*tMRPdDScKS(8PR02C|o!LJL1`2x8>Z7nFJ)8`|L$f&uiu z%e1yCJ3v%N71Ow$L$#-V)oL2kBf|JTnWws%2*m^dQR<^^#YFEv{okX_S<@#HQLP@H zubk|?GmN-sXYl832hB0JAZ%7{+7{NT}v5kTap69w&g->=0#BDgn!OBBX` zT%R)j&nprWKN{bLZ#TZZ<2wVX!LEeBq0D{bJN=t#6q=MjcNYtvhGy!g{$?KX+UsxhQ9N67Dkij z!uchF{4(i2LK2t-`OSq~ zr65WGxUx8Sm(4#rGIqQE@&gP%$lAQXkkGL0qS|u3t?Oaw!b#hcLP^^v2PbT|1wQAF zhDhYDhFV`zQAEi}^xu%51XnWod8%09*^-iTeFxFePUrYS^W?dx6hi#)6;onI5B8~R>5(@Oh9|(18;V6HR2y|3M{N92B zz3cntha$btGIJX}P^KMBf5o1EQZ1OzD$B8O@Z4-TcqBX`-Ru-oX8PS*rNzZSf06#o zcO@Mm@%;+)f8~WTV4bd~tDedi=syNRf#xYKmM#PzP#mxP^iuTjEWKP**7kxFGqMKw z`!?q!Zi0 zBaRs{(?4rHN2eGH4e6>I0fav#X=7F}rdd5@Ii-wF3(bNI=T8fRkh_|cw-Cj^m*~1R z;VR{*Y2hT@YJR_s@65s+&j00RL5sHomvRcXNalvideksyZn!zJ!V#Stm=y{zLjj|y zrUlHmKOId@Zb!Xvj<9G53wMVvLujM(p@%_s^oYkdKw-HIX2I^~U2v6fAI{)HK0UuE z#dv#2-kR^`F057~C@RO#cUvEGqaW-4{Cs6!GfH|4`fBs6<&x+_m&IVuSulGH_Ou22 zltwVJtN)<|dpinqKD3Iqe7=&^l1jBT?n?<@tQaC`GE#9qG$jr$w?$iUP6|Yx_YP1g z)jwcCFOP<j&qJQcndUIjzHD;$Au zlg@1Y@JfcFT+*A1_2yHP#$BG|A2xAgBI76nt)SNT9nNQ4QrqQHul~*TkuYZ+TDfM& z-*=+(S*0kn&j5%8eHSc+`_XF}hGxok( zzK@8#@A+5WFO9tql6QOTy++=@m>I3#PASiyWAE;*ydR0ZxBr&+-LdzT^8F97_hs_^ zDc)h%yVjrkD#Cp=j^>GJ+TABI+x4o@xyX*D-w~vVAm@F`mrt&3e5#11hQv5|LW|v1 zK8P&?)&6bCIlbN|o%ar{r*m`_)&G=jz|Zmu5Q` zd2Y4%ZZ8FP85du44R8S)B)<30e#I#NpWpwx7Fe{yZd=at2+z-Ww(`8h^9Ijfd6J&9 z+pgvr$1{~@4$pl&H9YHhe!;Vq=XsukJRk7%@T5IYJf5*UlXz-)*6}>b^9!D>JkRnR z;5p87g6AAhzZdMbVLYRGCh*MRsp475^E00R;CYE>KhK9e-8^YK?Y0|vCh&N9YIq*x zd6ef@JpaM7hv#*kPk3xE+HC`PM)G9vOyrr(vxsLo&!arQ;n~S^fTxq^1kYKXAumxU zo=H4KJd1d0c$#>A#`7DV9X$Ja-s1U$=Sv>>UH!7*ihrNW=CTj8xlZFY@oeIGk0;C{ ze=Z(3PX%Z6vK6nGvJFn4kHOT7x{I&Guc48i$`{DBTW2vU23zPy#(rXsogb_ zX9CZ3o*JGeo=17M@a*7u^}qqtYg%6BxvPWs4|#fc(xA4}d8QT3&a12S*Vol}OKU4? zN-{ETwF#`Ix}w&fS65%5AU1(bDs8A*Tvu9Oo?lv9x}>6>FJlBgb9qI5P3fwVj4`*W zaC7QQ%kHlz&nsP8QC~W()?ZOyTPg{Uk=hV`c13M@MSXr9GL}{sS>g@nO!oo$TNHPv`HTE=gpikdD@f`Z|f7|0=8MFyTe_^Sq1s4Nx@x zV`ls&;&&7O(YW$7sE)AN7FXBWme-dlG`OX_rbg0>M~lg&WmIsLjil)hx4*8=T~k-P z#8zFqytJmeT(T6nY6v>PCOCRA{Ja=WN?!H0#p2lF@pnd@+apcj9-VQ6e4AF=;4iJI zQN8S*QRjD0t_#$byGM`7xX5>KxjwMWFJH$H+p3$ppsKXKqTD^bdhz*5+;VT7G_Z<8H7?)u+`~`>SdB?@|{+W*Pa!wa>Crf0eteE>KhM zt|k293i^uyqJobx+RM!PABL2+n_fr9{-fk*yTaPi#k8Kk&b^|(+FxOWudi5A4PvaK zgkxw*2C2KcwzAH>)F3FlRQuhPr8K)#VvMw;ML*oLE6j+h3C*@Dtu3pNz*2jOK_l|Z zrGiy7Whv>eC~a_;)-WQ98t6OM=pt7BTs{{ApTn-favCcSBV`(H?iXj73sV zZ9E6Wr}(SfeuL_{>lXXyxCR2;Dy=GgLod_|)p9Sdr-z}I?n;n&F;sF%y~0>2DB-1T zxqM9zHrgW=CaonX0fLMhPOH`;IFQ!_OFsAjM7mlq8b3vYN(b2e{7DL*qd>|R7j}AGDYJl^z~pSgsf@pRX@#3g)CK(Rx=MFB zcr0PaUDC7qySmmLXsB>6rW!Gfu&N{BL8VC*%c~irq$O=o#t2$mZ;XmtWk_1z^UM!2 z+EwEjRE{)cOp<4Lg`aMxsC82H!h(r6xffHo{5mj`&X&Y04eE4jhKW}N1}-Svwc09E z+KO>lOJXv3KtD5BEQCT6lWa}%=D7>}QvF`Z(2TaYFtItQcR<=TE?j=VU$L@x5b4yo zFtL)*esKv`8vRYFWgHvC$USQp1uveH`B&vnZxYQYDESC9##KE1*QqU6yW=!{`S_a%b# zU9a%9bx;wwvGVwEQr=$S%swy@3xLUjuw_*hW%n~W714#h^onEVEK~SmW*#Yl8pi)1 zT*Ff4T@_NOaj*1Zb(3Cj-z!tAB&vvWudvJN>!4&y8)CGK{w!6&8CVyV^&f%*IK0y(ue4xlN*Ex*16{OD<-5U;DAwn^gyQ?fNXKH0 z&kJ^5J4iUi_{0V2osLzIcz6trFW&cY-zQ~G8Z&09$>hv77@7;(IxhTVlff~AHWVs8 zr&l}0g*W$L;wsQ9Y!TZjb@c_yD$1%WtIJA^<=GseL(

I@dgM5TWmmp)drLkYvw zKNDuh;GxeSQ@!$w#<4P%im|>i=pfx#@Be1;Av=l>G9rGnI7V2b2MbD}FRSu|BRUTU zzOKART!`Vs>LoPG|5=;@VUxaD9IIWV2Zdw$#(B{Pvsv9*2vby1-@qXKM&-2fEC4rz z&_X;)&93-Aia({o-#hyMZTuM(EB)Uru36sP@^Y324YNyYms~IheqEnhg;iWquRc`_ zSBd(6QI1HM`{iuH8SXMB@P=EK*Nbbjm8nUcy(?p#Kt0?tTeEdxZhO?S=jk5BD&AOa zvR){yuP-$dXT1lJ!fgYb)Fr#IJ-`s%2Z12(j?8w{el6^>s_hN|KHXyR4KQ z2*Bgjr<%GYHrm_RpDkC5c4kKQ#-Ipw^%LfNJGQMSVC&ap>~}}jn65~m1g74tKqgFr zD7bjyzFoxIo%i??cGse1HrE#qCb$+;DcPW6n?q`Bt1PWy_ClYzKA`&fL&9bd*4k6u z^v~>l*C8ipu(`H<$L3n}UHm*9Jll9O9zd2L4}KTVNy1xsjd!!o|3&Qm@i_m`pRvzg zYjd%eTC%vbpvdS`%%J9_+`xhNSvR2 zkh>e|YR8W+Dy<1ngYtl}sZ&v)Hfa@f^bO;!4I6L}vZXc$t!-R(I|6K^1S%_G$80Cb z+fANU*;^?0ruCGC@@4cYyL$um*?4~0bLhJWWtaBzN*jJ%`EqN^z4aB9)hl}ylu@um zw!X|2tL&yNQ{mX-`oBrfm>Oj8{lkivHb8XzZXa!F?owV@cF=-pc`3pZX;IV5)8dO^F!#bxJ?RizPCxomya*0M>(zHn{D67~(2SNx;+ad|`a8vGY8fK-xS@BW2g z*VQbqm|X!jRj`9Q`u>VlH@TUF;_G4TqZ$=4lDQxqSs_Q`-ehdWd`%K=*@Fwz)I`%0 z`chWfpvLgh(q-SG-@b<6b>DTIv2@=rZLU#@V`G2W&3Hh@ad*MY8SDm^1*E%;E~fb^ zSm4O!vq{_~XZ%KWBx0cA7V6_!X>3T*)2yDRS1*O6&`v_kRT)R$aEq;ARjt2trLnm> z-iUgWm5`(={qL?=2~WqmibRDpnq<;OU2XZ*4GpsEd;R$9-KCY#c`NeLilvKrQ-qbW zM8n;5y_EL)#_OdhW{Jxy%4$lDjU?%YXjlRf)(muhg3&N$dJ9x~Mseel%h-h02kk29 zF5)4WIWf{#QbOuEiG#8C*Kz!=KXB<5q~kW zJRY{=8!8wR`ylc){y>cX{=aYNQHry>0uZ@vACUvWZ?+ z4Kr#a6Q9a-VKhduFPc|Z6Ifb{*Jcx@!R@x$ZsZ|%GOzG6x!of0f{F^DHrodJPUc^0 zzIFeJIrnwufg{YhhjHJqxjKQl@h>~Xdk65>2=k`Rb(FZaO|iI(fG<17yv(x}|K-F)k~2V%{XreU12{0qG`uDjE!9aizhh;(Bo< zU(va^k9Qf{0#C!0bVP$f(hA)Pf14n%guK;uA~nbizRl%_C~l%P54z* zWDxKi+|jtXxZ`l|!u8_bhPw>+a@}xRY@Y;NF4TiF-A!ZM@wz3pWjS zEUp`O5bikK>u@LGPQ{&zI~unJcN}gL?o8ZAaVO$##+`)w3~nCo9^5IoM{&pF>bTQz z&*I*Wo0e^N-HAI4Hyd{>ZWiuz-08TBa5Hgha4DtwRq}rw?}EgeafLyD2KPI-2XOn~ zcH&C^_25doyC&FObcbyiuIzzk;JR@q;QDZ<;x56x5BGlD)wngdkK$f}EBz`;4x4$G zf(YKS{jKm$@L&&c>3_kuD{+tWejTph`Dk3hFTslwzy<$pciLSy;tax-e!mG<`divt zP9X>$OTT-8%Q%wpAb7TjcUd$o!xd(t376q+dlYv$?k3z7xX<9q7~X@s3il{3&8YAh z@@4Df{kyn5xPtFV-?qE3530t;YTTi`%Xqj6SMW~8i8YP{f2RVM@jMr|3AYNj5qBl- zgSZ=TWt_?QSd05O@71_64rF|8;a$dE3+_X>M{ys)?Z#b?>$uDA>W?eq;Cr}(cz+mo zB(98`3AiJ1=ip))SB<}Gas9ln!QFrx!rg?c;cmm-h}(jD8SVkxp|~=>hU1*zou!8D zEbcnoVL5i!2Hcx)anui1c&V^Bu;b+wwbg3#QkKZfZ>SkG*hFX+D62AMaVSii%V%b5 zQ(MJmGv#zla>A7c>R~Jv2O3tPI}=rxv6V-4F@!^|5N-rs)ZhV2>z63@PYNXYEfbXw zRUnc7889h>Dwj;9R$7FwwDdKaT*ZO--yf66tF+0vwl1)w$_=w6nm6!!R*3_( zal(7VqoqrjRoIWHuWM*9Ywxb9u9b0QtO2CSVED^Kd4fKoIg}2A6cV92TO77n+m=Mz z7CuV$T1u*GO9HYOx85m!NwfguVZkd)msZ!TDv{4|wNv{fvgt@6N=#9`B#G#4i6oEi zQE7RJ6os4{%Id3^F$K!rN;J-5B}h0g9aeu7iMqsvBQax*PBN%pC|PKURW@_IL<}Q8 z6K<0VrB?>LUPibU- zU0GcX8B6;MuK7#i%cuIXqyh9Z+Adc2^Sd#c(D`873KZ;?#Io_T#I=dGMtKRk8k9Sh z-U`u0Dp@R;4%}>i*42VDZc>dO5wY*E*zvfh0-lF^rmjzXovc1#46q814gM(HQX{Eb zs>Y414J~{SzZ$!7xF|5Q&uok975~4intH}?&s};Uj>fB{#Be<>&P8xoh|&c(Y?Y0V zYR#{3xMF2RSwKkwg=1e@3bjz$f~xGQ%G4I@68vV-aUOnGGs69d1y~Z+LtB;$qE^?` zunkay@(fELYt2PJF^-l|`epUivNnQBQUTE(6{=ya5-r-;P*EXWYhzVc8c+Dlwqr47 z;Jb;tO0i19Tklrot@rq1Lu(D(Hb^db%(||+rkstSx-vyY1h);UhihdSk1F!r>PGQf zC{0zYu>t!{OD&adP;*1?IYlk*4XP;RHs>3w2!h1%6*t~vW6OMx>TAk-Jl@KCJmHKs zv71pqCMLOzjVZUpP?Xy*G$|JT{FGvFH3r?*7=*Nd0_AK$z|WY3!kPu6@8>6FQ%jY) zT86B`G)sLHxH+3ja%wg+@~SH<3&_0A_dpHH9b?H;ueR^m3IV4i19TrnN5>?((iK$iHJ3?iMavcaF7qLCP4vBC)zZavD2FMOao1EVM?0DH z)P{{gGt>Z5^eu)eioPvkjWx4RLUb)Gd}JPv?0L%%t}uV}{k1ay@!OUw|0`a7H8-|K zHCD1qs;YhW*DS5ATlSs$27h4rij}K`CFFO_;DH1Br=_O$>(^I)4&&D+{zs^9o?h+^ z*9^P-vLS;9U3$qS0|yTL-|W2$d|p$!$G?+CMFl~TQoJQ4XllRr`}?MCT4|*fO|;Po zO`4=lG)*FxY6((`pa_bfD5{DeOi=_u5he(Vjwx!C>CiDnhZ;5gf1kbHo$REkI&;qd zbI$*N&d%q_Z(W~td)8Xdy1aWQCnq1kv%h-wGoAtXsg*Pyaq)u^_8Po*;yy$6P1o8CicjOMw>}*On{U0<9|3iz^WG51lbXT5-TJ3X5G_s{ zr0uO8pdGD6wTrc#+RnJ0gLdw{^MIX4?~KZO+9ZVf|69U|-YhyZn<-j#)p;7{Aa)%) zn`N>TVH~eDu&zkii|`QlB0LPl!$b#$+H>Xf(ugl{HSsPkEtlnrHoKzAxU)UGXqFLo zURB9#aj#(SRrKze#mZx5*~027xXdPi_|LA1`7hM9nG5YurG_prXO_gNqyrcmdgQfs z-bPh+iKWVA+v`SI!Wd5*vf2E*xa3D6afli}wAHlH+R0jh3KEmk1A0(?Zy=9}%BD5; z!alh@)j6YC`{$p;5zbgM` zI=jc;Sm0Q&WUX)b-&We*P{~@aS()ODsiJYwC6_L~?D8v`uDt5%CD&YgUGw!f+_?0n zn{R2k^|srW-Erq#%kRGD-WB()ynodL4?fiT@FS15J@)wTS3mLOQ)`}n=Gpe=o`0d^ z#g|@Q`^u}Yb-w<_AG+Rr>+SA$-hFS~`yYI`{*NF1X~V~#e7fpLW8DCyh!UeR8i}69|UFk!Z&5)urDRoOSlh!rl8{&~V{J7yoyc|Gzu^|8)H; zMevlYiIYyvo;>BWoYSY~=AAKZdj6R+RQ>PX|9?dN&(%u#eOV>{D>SF(Ko=^(WTY-SQyonj-SuU zdi;XvtOpExZYgKYW!&R8++f7f59=c?T@}wgrJiF+c9cqEVU<^PRaHeE3m;iC^@O)L zPA}qaZ&gjdz+Bg?klz>8YU3)ZYD@e1O4(F?dOd`Xxc5mT=Gc#i;W~jIM3m*IwYJE^ z&41P`hDma!)<|h*sdEDzlr@kK6m>rX+zZSB<(wfOlyjRxFcB;R<-DdElyi&);J#oZ zDCY`IpqvjhgZqOmpq%F|2W8>03Y7DhHt-;D4R|ov0S*N_K{-$92IahEJt*e^8$nsj zYz7Ypw}Nt>vmKQ45$$YsE|Un#IYcrj=LadE4YYwHz%)?KBXsas&d1G~XYa6LEy+z6fmZU!fUTfs@-cJNeCn>i?1HWm`W)4*gf2TTE{fi{rg zM@s`|fI29G>H}rr+%kr99|Rx+dpwv84g&MR1h53$3#%cMKMsOUs1ND;NRSfaAcm;9PJ6 z7{@@h1xx_9gL{JsCFBE428V#d!6YyZJREd^K`9+(6cf`@|@U=Umk#xYPX1@{4$gG0bp@NjSq7zDe)I2-K-?gMTChk)C~A555y ze=7L^_W^C-5O5S21byP4Mt;N}%oBgGP~1n6A8`j4h&#Ag+;#e;xP!~Y9b6^uF8Zao zgB{`yc8R->`Vu?1N$er&OYGndv1d?UbFhO$1vAN~U>5ll%qE|LIrL93p@IGh9u5|Q zG8T^2)EG_{wKCk!1=E;o0Id%Ddax1v2wVa_2DX69!4=?jU>o>0*bcrAc7pGM>%a%V zjo{PZ7H}=N9ozsWl&Lu&8SKJ79DD&x13SS5jQKJrxv<|3W`lDDs)ZQ$=gt$a}OLx9XNGPfmRzZxuq-`?PG>@tT{V^0Lru-^;1z&F7RuocV( zUkCHS8^99q8L%3B1#AFUgH7NE;8L&~Tn?TJwt^kt8t^@E0qN}nuEqWi*bRORZU8?7 zH-m40+rTG4KGL21B9H{G15>~iU@G`9sDqz^A@D{p3)~3ifzN`4;9Fn?_!+nW{1dns z`~++U{|GJvUj?&h$78`&*kz6u-9mJa)z~Y*LhPcWbYL$Nf66li?82T6F2{c~xE^~g z*o6PS;3n)#!L8tZ;12K+FmWz-kienflb{W37o^=pR~d!92^8JK3;M8&&d?0sBrp@Z z=pL)^7ab@EdmXqHe}*2d0Q;k087R6(3-0@Yb=Xe>tBIEeHex>qOv8ROxCDC~p{z?5Us)`)qI&crDn3`$?b=`#dlc zycA3!oiLb#{cri2BCs3(q2M~~)4=uE4*@q~pAK#TTfpt$5-@Szpya#26mS(N zy7{4C8uol}Gxozk7xptj(M3aG2KLLqZ18?CADj=CfXl$`#2W@yWB(nPK|YTG8?cvv zP2lrj3-~g)3Ty+{fNQ``@DJd6@HJ2){^7u8>;<5V?Vp3&u)hQ*RSrsi4on4Cf+6r$ zFp+pifO*(&0}H{kz)swqU5 zeIj}4WASFi@>$zcE|tFuP4TISr9V5C-}$j}mT3zOK1I}=Jf*RG&5Q9Zq9){-8;dtP zmjAL?{CTnZm>UZ}H^#4)ALPhWALCmWOTRkCXHG1gx|qE#mjAibpgi+>>P5BdyqNo( zSox&BrN(MWPilr+Pew^aF4AfHF}R6rq-$ffQ!tBsq-*01sZcVKr^&b?@*(mv!{8xd zGPP3;bE#n-k6C0T9WGN1b0y|83_c<&>DmNsBJLtDVwNx>GwHa>JScLLjx@>`DY7H( zBAFsTV$Q=XGL)`OGJby~Sk-2nomSvbFZk`cWWG|guN?egY$$uth zkwK{wRp(OnvD%rqi!2IHsUL1$VIFVr7nw{a)oHkkT#8xhL1a^SNS$dm|Te5n(ZsHn@(uSr}(E6TJpBQD3>yyZ-iH7k#RGO$how&)Pu;n zw5imm$h+iC@-xrK^JF8>wMJX3c9Fgy=}Ot9KS(=@TuGl0v&f0^?AiCb*s`4n1G zqZdg#s=lN8of%uoBmGZWSxRm8L*XK=t07^klw*xr6q%MfQuRL1sM9G%9jSghQ9GSD z<`^#dknviL=OROrKb0pLuO$_k>s8+yYt*UgS2F&a{YSZ18gb43BlVjTYd@9y99*pO zr22#E+g6zyXOvgX9jfhBpHXc;)~GvcyIRAWbur$!k)!4?saKH;Rpu;1W>uNT82M9W z9%J-lRc6%=s?6gIxvq`1fRw?Sp30vpgPC@YQA=jp*+#3Wv~!JosI;?V=}CR7G*sHB z#QLe!nW|$owv3JCV;*CfIZBynWE$w6&zs zzl~ISss+sSCL4KC^)}Hct>T+wxGTPsjTTV#HZWi5QA%1&zIjI5D!xj772iywOjcff z+hCs2!}{j&G$hxQ=SeZM$n!KKzqO1oVpA<=rhjIvEUHbUUz+tL_$j?w?j{K@>H z!i=%B#~Fs~Dfh9K@HrOu(_?KZ`B5W?;+boVF3Ox0YZnPKB{tWHImgJqIhJG@C6jup zAvcmA8S~Ev&Ab&+Ceu8N@!m9-5Xv-{8rr7HbGf0ZDf2nZ6lR#YhUTN(D~vZsnr6|o zlv!lLG*{7brukfpyNt}HyNt4?Sy7d&vyvgxELyLUOKBm~Jj;*|PzY9YK5nCO*yqRbzHU5Qo6fZ{V5$o z$+0rae^ZY?htp2AUXuPG^{jNkxrSURolND&)TNY7!il~)*C?~n8Rr_~jna|T3Qp@Vn+Epwy--@nd z^%uLDnG z8Q@`Gts_AhwVN&GYcMCq+^@Bmud|rh6YB|cy~TWk#eAd1ygI%&{1X;)66wH8lRdY6 zpkn@{#?C-5nm}vGo}p>BYaZ4@<8cu;(W%CvBW4;d>duQ?_mI0vrOY)VJ#vS;m>#3{ zq(&QKtg3%;R~im`v-0Ei6F^$A9to|`u*9Chnl@OAV}DW`G*}xPpPVp${P?}(aqGsu zh?Zva<>Yf(>(%w?IeW7KX)~%Wv9PR=2cf85z>_HFxqEB;CV?$f{={lLgBu$!Z(P(! z0)sAZy!?{Jp?mE`3YT4W84acDjX8}?gibr&movSQ_#~2((?mpDT4Pfqu{4q?D=SM( z+~b ze6o$1^kn4fb(;iF$?F8TiEcR=yVTDZMqWX&ORgrx$|fjt-xzQXm`gm- z5l*9TNLi*(cG0ymaTi@r@s}~P#^9sUk@3`YG1F8!h)P%KJ1R}1DUI|iV)dia7QI#V zOO*#1+2>IPxr1otr>e)U@?{NS=CQAv+L@#6DY-n8`8%2VD&haaSo&gd>{8bR-@*gi3%%w7*hz9N9d{enmnd3 zR!+u!sxe;n^3KC9?&|6HbEW_Ab>lH(&9AGlhZxT_#XzxK{FY>M;R#N zxO(D&jPul)_;OI@jP0PD@#ZX0XPhnIf!Mc#2Z{Sab;j2MrieQ@3@kifoq@H1a;9aw zK%GG~gT@&WC}*vI`jW4ldQ$MYE~HTuZOwmshyd7q%$~;^p^;!#Oldu2Z;49ojKN4-YvWL5r z-^{O_8Zqmmi2kigo5uWWV|*H21`(w|#_<)TPvuja*gnzskt9szYguT3nRBNRqUXNQ7z`YyKRXt0#ZI zy5r1{awF|>V-;zp+nbsx&kn6uUVeLhiL9LWZ>HB*e$1LR+kMyE zOMRL$W#(VimDAD}Wv@GrkY*VM;xo|rtw_Rb{+qLbSu!OhWp2j!6n|LntZQdBW){q>w^=T;Qf86N`j}-gD`Ht_^W<^h@B5m&ija{r^{->+PWMY?BkuX=fY*0M zmDAQ}VgmaVke0x0bD^GRYxLrHGkhdNy}9An?Y-pftz@g`i9*2P%M?58*B+SPddY z+X9$t>q;<-W#-H}zKEqPGiT1`t+1w9y$L%OO!!pP^u#GGn#JY_JnL%s!Pd-~ywQZ8 zc(Db9nHO?Zl+USTAIfxeHYEkd^sg?PgU<}eN;AoYG0%ni`lP~rU9##@ArCvM^VSr)St{CKTU-gr_qTfDWx3i(N$OfMt+mGyzS6wWWNsjH{-CB_#j*^o2d z0bEoq^=8Auf#h#i$il&8sYz@1|AMmP?Bl^104fWhg1PG~6zJzdOs~ zOI%*u!>=Jr_EdTO!wp!0k~eER^sA-bn(hqCzFC%;>zCID9kh1)6Bx`ikU^` zLzvB5%Gs7M)fV>_OZfJfdmeE&VK&p!uIHPr+OmGfQ19u$Y@M%Z*q`t1V`hJaos*lDBO! zv+z%Dmfr}CN2}&cCT5oK`7yJEZ-|*Cd<$l&XUYF+%yOGn+`BQ$-L0vZH(AVy*DLoa zxR1gtHvlDX`IzNaoy2X3nZTrQ58 zrLI=R%pwn6F|+KNZ;6>DZ%H>Qo>DG7W|lh1iJ7Hc>SAUoV{^QM5QhPx^Ay2UIj2-#gzYxzn-%3Y+sZn8p=m9MNTYgr`^ z6h^J9`iD_x60$Ckxawp@?jOn8RMun4MOLA*Qj|RiGmM;mNJ@g`J*dujN_VlR6G~Qm zb6EE(lsu}qW*j*gmlc=VxsVfcbqY0bIN>FGhH4LG*D$h%RXH|yC8UgUuc@AOlcX%S zQTmp%Z!M-1zi&NDo_7t?dmpK{c1_;0mnOBbYdlq_1G`IW&oXkSYP)}$vfC_N`@73s zcG-tfva+kcx~;OSyR0UqR%Gv7?&g`&Hc-B$US*vwH*?gUvf9ItldB@yMBSaTN@F^_ z<<`Nj>8hF=*u9AGk`pQ8z^&Eae^)8(8(;1)$%(m~xv8D9IlH7GH^ik6)k=0Ljr2UJ zQQ4P}`)+D)#Owuq{iO#d$B3eDvkjHy_g8s%P)oi)G)oxA#gP>Meon zDAZt=o0DdqcXbn4mEUtnIi-hat`s z`1i(_)5L*zNFLwL5rxvQ!WW4EL7TF6{a;feD^!Jy2VVQO0j*-j&s!pY! z$P6blsJgKwx9mi2S$-uUxnWDw_-NSE;@{9?mKsiP9g0j{Y{OD zs{g9KFSnSbzlc6z&S_@7%Py*%4$595PrihSFTJ>77Z+aC2P4o;_$wSV<>@Jqs#{ zxl5RV>PO;b;3s?%A#3`LvAE(VahtKX#N5m{;L)QFBxPj`& z8dvx&C0xqwed{F+yB>2Be+eg#HD40Pnuho%Ksk`4VXYt2F9SpW`my?%^&|Bryt+wy zwIy%jwif$(C>tt+7DK{A!b)ApW6h^EzW62oku#2Ey=9U*O2M8AnPrwR1GTLgPs%8H zDI{E;h1XuVm0)jx2Fjy^mw576^JwKEeu>C$tA(%Ru^oFSWXh|A87Pm|c*1KnX>Pah zk~oQXaApIU{(|yY^CWTB?WP{GVsRyoRfxU1A3q5!>Hxgzb zxv|ERxcP)@>c^`E`w9y$2{RBcYdqn#fN<+9yrkYXVc*t|pM)EzoYuI)uZ3`__w<%i z__?rWLe~6AxPkat;|jkugsbbvZ!z|zkhNVU+(7)SafROo!mYLNlR8?5eM8Jm{3V<` z*0J0gNBq+0Lsnf#+!C2TZTI%Zm;C71Ly+0V5@w)wvBnc#+sH>nKVA*kn=HH}%s{-X z@r2hv&xI*HmoyCTgNA9zW_e9Cd7F3)-${_ZxSl*n*@my^EvuP^xC=?UOT11?8BDh| z7B_-u@1*XUwz$h9JcKeyOVStKd6>nmWPtQ>?s=XK@0ss13*Xil-}XK5eRI;D`EIlD zO}J0xcPQACxd9AA{Cnn`4G*&(3SxXK_P{qSuxGw2EPPkT_^#apUq?<~8G0SNDLW=g zJIQ0BDMQ0oDj6ySRfyjI{beZ062_FF9sTll;QU?FHaSY#LQU{7>#hZ}xUI7AHpBNp zzKw2{#YEHJ!J9JJ@d_ghglCfn57;H_rUj(8GGj2V&S_g#&^vg_})2f z&wRI9_-YTR{3e6a?z?+#`Q4uRX2HX(hx{1dvfc3Qo}>C^8~)Ot+QId)u!%Bv@tE?Q zgqas88g9nC*3U1V@6OGgkK_8R{S^0}DE#Xc6LoshGQT)pW@Y7>yHx1y| z7K>LnTg7iAEg1uv!B)sD)2e=PQwft?sN!@E;MX`)`I&sz$M|mU$9MApaXVshJ+XQj z`jDz)8))W7=6SNvQwLJVS6`^=QQYM@|Ajrbc?h0nn`dJd*)ISM2D|yU^Nv09U25UG zBF1<19{85svS+?qEPQvw_$IafdVXg=zh}Og@G$Ek53|%m$!_?H+?^j6mwXWclYD}W?^4{D}Uh|DgJf;oRVMn&o29Q|Krd3b$`#?U-yq(*4MwQ zU-?E{uKcAeUlVqB^<2d_xFn3}-@l%Mcf|OBLm)F;Tfg)^zCnevgF(m)XKmM6x5XvT zhOFsX{g2~2U?)Qv5+L?mb)%9wv67^DkKOPU857#@Xm7vVf?3>lfJUI$zh9HbBbUV` zkANg-1?dZxw5fht4VvSrtaZfC%!l;T(_`Vy@^c8>pxa3Wc)xUqgS=}#w zL%;I;`RBgz`^($NLGgX~_xJyqcOF>N@9%%X0e$^D`=x*Qfqnh^$L~J)*Zt=osr)y^ z_}2B~f5vfrIfBw%tqpyGe^!-K3U+VD3!d~;>n7b*5 z)^?Y$XV2)%w|}~Gs{8u)PuG2JU;qB)e(Aiv{{7Rxpr3zRzk2sI^o_sD;{V~L@yTC7 zQVz3x?G}G=|L666{jKSj-xi|)$;fO$3O8q06#%_mbT@~aj91K z#2{lF+aI&g=GB8V8*cef^U>TdfVM(58|N}mVT>BV<&gXcyc%j2JO=+`HSJR3-T>VP zJqN9WHbFa}W1bwOg`jMx06Gu423iKmh#Jq%Ndj+X87yxI;Vmdbw0*TCeivvt=`7(# z7}KVXQ{NHJDXJ_LYi3bx*{mvlQ83xK6JCQ;UJYN%DJ>btmv(B3Cd#+B`IQCkGdUwZ zrIb(CmKPhYv$=pCbCxeO<;e${WAoh zp#yj5`N0SbV{SP`b!B4BEvv7S&wlr$vBjucs+TAE1?rg3n#5 zTv<^~Ue#oN?NUCLPizLm4i;JudA--lUcL)DV@H}Qz4K3}tgkDQtl~jk} z%=Xgh^`$inb4qJw%V)SMi%X49Ve#ghsp=bM>f=}1b+Ip(NlYqn(8OA!9CJ!*%pTVv zCF%QpG3~`&-T3BKM?zj{%{;znURN5sW1?w~4Vqe1Udu`3Xe-W_cwcujk8iuZfvLs4vcSijBmS?NzZE zU!|Kfs7Gq@s!UPRzCs#`t4d09s>($wv^V5!K^A+t(H=&t%P&5t!jy!mbrok+asj18 zyWA*i)jS#i8LOoAI|fbV19ei{n)b8!PT+k~GBU-a_ytStn4ex-2v?UO3lqxukhMfM zzIXSYgw3qsGLTC8`989ccYbblX)&LnFP5K$7$3dUM#4o&NM2R1+-Ta{@mZxs)kZaF ze=y8rjF0v$>?>_!YR%|cjgikBxm~2amvBa9nei>PlAd-Zpj4N3pS0_4y^B@t74g%r zYGE~9OA!~+94G>t7YW`2WD)2HJ8^2=H$|U|6Ny97UKW+SE zF;9;(zMLqj^n5X~Mf^nqW>i&LzxbzV-zH2`KQlB2M@@UzXoabzO4=iR=K@N9g_PdX z4ymf-J=K#d{^Ki4PMd91hIZAia{*jV9Y1x-_-v^P$RS&+6HOb?&I|3ufkdRl%3FbkD+gPdalKR z<;Ko9>_WRfeSeeQ`#XO#AVo17bLAEUncvI9I^>}l%#T-sRmKCVRYVBC|z5nu`^>o^;@AD9M;Ea)Ht zr};p+bCLlb1!jQ1LeJ94WQhYSqvTuE&&e% zmx3$@wPoP3;BrvTBvybU!ByaKU>jK9f_?;<&+@-3*%pkmHmVe$-y{3k)*$`7jk9Nb++%bOLl|%zig0`CS1?diO&T z?kPy}_ZB4nA41}vLZwLk2uZz6`7-0#$A-O-Df)thGoRXXYwApMuYRyyg7Nf!=Z%ql z3En6llZ;al8#P^-mon&!o5WOJ%prHN$N3vb;xwAdgcIjl&G*QcK>I#D{4cuOh;cd!!|5NL{gF+Z z`O!HaIr;|1w&=a}pKSbz-vnM{##BLMz8VLuJr~^$>VmqVbzRw@}L5!4624C`~s*EYJ!@fWzY(!4QhuvptVpp zvg8%Pzq#&(jXs{1?58(P$Sd~t$WQ@NBxh@$o04JMdgl|>C#`z;l{?Bay3hJ$gj<_~Wg zxBp((obc$K89%+SJo9gh4!Um9B~NF(5PE;*+dC&7z2K$yGOAwPxa6;mub=YFjjP7A zUpDuQN1lg_{C?eV2uuU)_Y%14$D`~2Ps`;{J+RKMu*`uVSCP0k;?>HZu2 zLHC-+|CT%X{x8l7zj9Xa>N{_kvGc5zTkp1YTK;X1&L|0fdfGL& zR33EcKcX+cH>z~lpYsoU>YZ<+-3J`I_>?0~X?^AXZ=xA1pDeFUmwz2~hTF%U z|Hb=DU-;lJ(U*St<*lN{2cFmU(5C3g*}wa2^4jN@-t^_`(Hqw02J1859Qyoik48V4 z^UPBJ_=k^r?Cqt|)MH=$bNe$vd(qYBM~lul^TmrE%WXL5*_qJ~zd8Au!O!1t*&#n? zMpL8r{ndZp@n2oM>cr@Ut#@x~FKL+2{qY%*;tK|M9h-OFr8}=*6u$nSfnnztj~r+3 zXbp|H@*UqLr`)ne`{l#nhNk?)BOcrQ`Q8xKaz3$P$OD{ZdQ~D=&z4dNq!pAGu8>^d* z?1@P|kB*Mv0zgew%}ic|q0Gn-KWi8+G#IxTX6`0%pRg0FYU^tFrTK0G z_X(?x&~_8DZysvYy#y6DmQ5?KQuBax0KeJ%pq(SHjPj~l<1L(KDXsBq7xMe~Sf&T^ zpJ~nO0BOYTNEj#28Ix+ODyc>*|DJ>;K|V&8f&sv_+!SHF?x%n981 zsp}(ZebST*L3J6Dw~A6TSC%?DqgdW)+BbTi__UOSFx#k~U#v}ky(DI`yRF~y|73ma z+HRHg^JdPW+?mv(aA%C5`DU8$ncQ8StDN@a*HTaLfoFAnWid?609JqLGlmSrJgt5e z(%<@wCVl0sqO@{OU0L4%*7#NRbu+7G&#Wn`oHI}xPMgW$ZTY-3HK7Ja*(VBg<~**8Y3@&-Ou%eI0K*K6DIm4s)hCOPqH*KXo4A zinva7<+^_7`lD-^dz|Ms&kvqsz3JXlyn}sr`3?&d2j>OP3tkv%4Xp`X7`8>mM_!8T z6)lRM8(kE=K6-m}Mf8#AlhGHWe~7M&eiHpM`fc>*D4Df!W(Oqb`|F45BlXkuQvEXW z_mbYFf2Qxy^#{X8Dhy?R6+r%xi) ze0`=qTc4-b=@;mi=vV5^`YrmM`h9w<{(Joy{YAY~e_Q`R|5)Fof31I~|D4SKFVp|Iz-5{R{gR`}g*L+T$FFjsqNr zI*xRtI!!P>gQJmBHaV6!njK3i=`zQ1#|p

fGks?%d(jTnR2OtvJp#$#uFb-!;=U+cnQs=eodkiR(&Nv+EYuov!;_t*+m@ zo^ieC>U6#B`oQ(EYm@71*LSX;T$+1t_x|of+{4|+x=(c5-MQ|3_e}R}_dIu<`vUh} z?v?I`-K*X2x<7P(;{L+D#r?hepYAwMqUQk5p`If>sh*QO4o|=n^<;bUJo%miPoby8 zQ|77gRD0??3p@>;M$ckTlV^#i*|XHs;#uZd?pfhkkAFgFYxuax zwUM^S3z2sse~tVYIUsr`vWOgHaK8&k)mQ7M+iUGZoa3FtTz1#Fu5|Z!_hs&rJ(qe$ zc*l8f@{RMa^bZa+1)q#+Ih;KcCr|&tzR`Z1;~&nTD}&mc<|=npx-NDtcHKZdu5vx> z8tfkI`OY`kzcTQT;LpJWLn)!7LdS;ep<9v2H$q>At_WWnzB~Mf@Rwm<$(Kfr&u|7ib7ez*S|f2030|5E>*{s;Vz_@D8w^*@@Ka!D@Z8X4p{1c$X~hr28^V7Je-}=ToD#{7 zoE4cBsgBe~E{|LtSscA3`hHYf&Rqwxv9ErD-lRXMCo-CyLU|WEr@623ei4WZ4Gtwl z2+*d&?XQO&*SOF3TO$2|ifgS3gQWR(I)s z{S-Z0KZ`NG)wRY|?mp0an0KW2L~ojJwC`MBOW>}+-l3_XtI2OmXjy1^XhmohV{}_+ zHRE(?`0wE(Bb}0dw>tA19&8AH5nLOp2`>)Mi@Xu}K>RlHZX+N;|5V?s|4TpA5pX== z_!}*DlFRM-&V44m^9b+RfiJ?VqS{vOP!KjvAFrQa*X^&`-?wkFXF9SdbB-g=k-y7m zm*_m)Io)}+bEWfLSCc!%Gu&fiv`F)e^5`Cy$L9%oj`5w~d&;-jcf7yaU*}(dOgH)$ z`3qoR(e zFIpA7M&yE>wPga#J30F0%rl4Dk6`S6z`oZ0DP#5Cjugi%#^duHcQW#JIX-ZF>Db~( zMn*H8r#p+7YnD47b-uv7INLLy5$aXX2cCa;F7`HiZ}Hy6$n=i)OYe8yAH7HT7Smti z{X_i8^pafv+5T(kk&pR*@bB=yA2>Ok8+|z{n^xIm?N)u3 zy~>{GJkl9*p5@GUKkELo`%2Fv)b?whw>|HBKJ)zDqj?8=le`CeXZRit3<@3{92pD* zFQ#YQ9b6sU5`H17+2V||+*;>P?sm^lp8dU-dmr=#g9l5yvdNVSoNs^1-ff@Y$a1ds z91+M5oE!K{;OWrIp_`+3M74}Kt(7o;)K9eEZQslBH8bvTr-NRa>00UvdmX-UzO}wL zdd+ao(7 zS~MX#C7Kt_j}}A=rA>3|8(x_8t0ztUg#dlSYF^Q_RjTI zd+WRlymxzF^M27YSL|S{N$@55rZOTF_zHa`lK|fwuz(1!n{ok^8vNtkCV@ zr^4?rQXCjbkN6@Dk)I>+(W9ik8{>?-0}j22dFpZd3--4d*}t;?WY-)AI*xXnh>jC= zOr#x_J05mC>G;U8xAQRP(azD%A6%!o>)nm+d))tUkM;$96}~mTmweAfeqdHQJz5#9 zi(V968ofXIT=doGyU~x0aXilWMo5D0)+eK*HKLn6qj%`9lXj*3V*6e8Qs=$ym+5zZ z@;ZH+{564B0+)nZBdbNum(!ov$9+|QNB^Gj>nOC{iS|5tyTp5tS$s63Qy#ikgX1Pg zgY!r9mVFt2uJ;^>Ogv1^KJo4JMd-at{CE4;_)iJm8~iZ%b?}JLO`+RE520f|9qJ6d zi$wn=^lj+J&_3aV!^6TZW~RyEGs5%2jp56~OTssXmoeYpAAU5vI{ZxdrSNOvH^c9T zKMHRQZ>HV95C0t2B7-CQM-Gk*i;RdI7a0|CMf{PdF|SOG%!tg4lt$)7Y9b3Fjr4`9 zBR57`B6mhsMjk@5c{=iZWNoAi{pQ2Sr;$yOuOi=}=lp{HJtUeOO^F^EJvMq$RF8V1 zk?6SSMCy1NeWoN@&S-dEv>|#)^s4A}(VOV+_e57k+oDe}f4&^;jJ_59Ao{21#^_(8 z-$b`XcSt+5#Tj!!yq?VbGg5cxK|M>K!Rn&XeuMp8`^Wab+aLEm5ZEc3@*Q!;9ga`r zNUJ-}m>0fuedYQFedPz&KVAQF#k&W)hoDs+@IANdaTPorJl@_*#t=>M6%I5?0L zI4p2vU|OI!P#(A}a6_Oa@JwKB;ElkBz~2M^2qXs&588qS!L!5V;f3Lc!owq@BN>rv z&%%yzf4rh44@j`J_h zZ=F9n<6R?NC%QbYplb&D_v2{apSXPPKe*p>f8|c}O!7QUKmEk>S5J!fLdNfFy{j0x zHZa5NL^nIsXY=W3WFPwu@gM1*&D^*e-RpDzzx;;=jtSVQgO|^#bH;1iDm(<7sq}3y`80oIf}ZX9ahKtIgF;+J~|l zyUM-U{V(^m-gqCHd*G>s;MARyoYl@Dt|MHdTwzzhSkWEi8RogtbEoGO&%to33!RTPxia($^ZD$E zmJx60rOoUxwCKz9<+R@_R?iMbgiZD#%m<4cw>n;T9Og;zF7RE%I^sd!>%O;r=LD?! zXnUw5bWQm4@EwtE^yfDid9<8(<6hY?#{8x9MspRuL*JLx_c8WS_K^KL`-}Ds_H0_< zc4wROdFN}+@0<%=_fQ{eS;KxwtsKFc)y|kQ-d*dy)BV1CU(ZqKQGfRA(f zMx-cmPNbH3__E0Lkvk#}Fz&w}`6MzTIx>1fG(BpMx}*MRI65Xeo{@esWBnP?KSuv4 z<*1GqHJ|;VG-lBNdc5AT-s#>_ z?-k61iL3)hpo`mme%~0RIoJ0))`V5QMZP7zrM_jf>BGJ!eb4*47?T734F8R+1fTGy zQD%1_h<;HXXbP;Nyz2uW2R^5!e+~=|9uOQJObyzDQyGn~4&D^>q7nWf{6TnVM0SuS zq5l;`W;2Rh#(cLj(i(X@@-n+PpQ^d2FxxomgR{wb9i#2D&Vw0QUqT|ja~+CA9Pf6zr!%LV>wW;u`U&^5?iby!x!*!MHn=}$ z-2K+Q-L0{Ik<5x@q~}CdBLPn)dlw~WUKg?}@g#cqOYBIzg(kki^SS3M&$piKo}He( zy$7%YJH~rFdt+Yj7$odW?+4z4siBp=djAFfD;SAB@LwIcK5$2%C|DJIDfmlpG%J+x zk-2DZQ>2}mRiFQzE+wnc&(j;&6I;*j({N^=6Ins}*b$p#zu*3ty^Hx~yyF2zgEh`k z?9^;=?{M$uIfNX0JYzhyzR~_K{a^ck@gEU5nO0aI_%d*F_=;$Av{gplk7*S_z3Y5siw!_3IT13vW1C4o^vZ}6~?lU3+S)}3#JHiW(jY2ky= zeLbw-XM`)l4}`V0cw?l&iT%ZoCV%F-p1&Utbx^7HH_ML zof&nG^B>M%ocp*^Tq|79(z@mDt35Y*g1$F>fAr1qS5fCzF&CyY_WwO_8ofvBjyLvj z-bW|?*!~&)_pkQ9*}t{_gPG@0IGVXS)I`L^?Y=VyinFxa)9>qytJt`pdQ@-pI%XRq~i*O{(a>?@s1uUtae9%RmY z+V!&QE!TnW6VQzoyO+4{a6jTc+ViRBQ1-w6=H1~v(szdMaUU7j8gJ}ved9RR?Q&z--gUR@G4zvnT%WnVb;Y?4bdO+U&2v||FL7V)zQKJnI{ixblkN`po9@54 zMUy_1^?bT#vS+%d$a5||=Tgr#o?AS3dmi#U;US;==6gA?z}{eQv@ft`5C9X18g{zveY=NtR(QL7+iP~#swc6%d%??Ss ztAlx=)3w#L&9&XNgV`a$o#-xcm$@t4)y$p?+zqTu7Q36MT{33lH{XETZCH(#*^U;p zmYtz4f46^~f4zSLI_D<;X8#ud*4SDwA&`jvnH(4zNC^yQ%&!PkGuAH%Gz1z0ix~r# z1e%$XThK$62Uaj5wg%b)s{?BS?dVi%1D)({bqChbS2qOopeyJLhJqQv%wSe9JD3y9 z3+6LY76wa#Wx)z&^SYodk{Vfn4o@a^e$UN1$Hn*%vS-*c>B-sjqda@Qy}({*FR_=g z!(UCW>Ra1tXL;8htbYisdJfg zg|pSU+S$$?bQk;28`yi^!oKqkb}5rwLtVpNsb~@|SICv=%68?s3TUSa+Ngo{Swh<^ zL%v&SADOeeTiKzmitRt-iUSn6KpUg2(K z_qpA@*4^b^#|XZO9q4V0g$bS{c0-4=qcn=$q!1&x>^~PUidQg>H?Zftg#G4a>@~Nd zL$_L5*cO3#qTNp8fePXqG$Bij$&4(Th{j!(7o&G&7pb zZicMODp&zGL>Hr*EsZWiKWmMyjsDTc8c%i%o(+&fCplk}nba6MHY z#eQIj)U(l13(%!2Si>}+O)o)rT82i}%1(E?z82keoxXvyj4k>$&R7!cN%olS|o$USV(LOrxEi*hNp=fL^!7zRkYFp5RDw3}rVr)iKK9 za)cb2#%j8NGmQ#kO}&_1n5CRztl$J=HM8?t_S4pJYO#r4yX}9RgoXYM851obg>fzo zEy3r>@ML*%IO8bfe50DPjYiHjnmN;0&Ur=~XBi!64c(k!Z1imQY(;0#yougqZ;IFE zP4ntrpEtvs<<0Ttdkei~>{KoAHhP=bS8VYvXWiGv-eLzQ9^IUFY~-Y4tFcF(=u7sc zuntUPCFt{I__BOC>|z!A%6!$n1-?dK6LVM#yZ5VDC$8~zu-Dzq3TY#Is#|^A+1*NH zcQS=i;;q5$iQkOpo{k3MC=9NZfl@{g{SrvCO zpKN3{+0I;&%uJF-OJ=xJeeLvwZq_OreA|2p^nn!raH9`oApLp%5~RPvkpE`me8HUi zJB|5%2m2t&lrRl>4;d0)7${+em$|(KDVLdC&EX>D8uC4qb&kll%;Pe9HwG66mjzoX zV+VT>oxv_crne%^38A4#^YBn=C`37PkmC|0xq{NxQQoD-3Cqb?m##j(ajQR!Y>yIZ76@mF&BhM9ZSp(WYn% zGgT{lhpVG&q8-uooGWgTRoZgiiNjgDrYGo$#ymBO87hOFo;=Rn3-m%`mRfA=8pwV@ zn=wPJV{Y2a&4eASOJ#OSWnS{dw3&P~7||5f+2{)9qb@YVjm$=yjrk~vnaJkQnTdSH zTvTA3tD7h4OPPb(IX~|~2Hz*vQ^XB6C3|dPX(c#Ztz5(J8igk_{~)lQCWNhGmT6 zUFhuF*c(dqjq+vxKkZ$4I8|H!cLp5OA+wN^kc|5rnTjM-B17sDDncl;lc5xjLg_Y0 zq;$5S4!`Gl-}j#%kH@q2-fQo5_Wpc6>+}7t zwbucq4uG+u6wqcAk<)4Ri3yPE`I#K{1xpT1xJ0ggXz`vLPI&2^gK^;suWRfai2F4qR@OfcOQG@Pi zQ5Sm|VuM!lC$bLPyNmx91C{okF74d4ew!CU1aaG;;SgEFY#A& z&}1&SABBMQQFUJELp;DQh(Hu%0a(2Z{r@uK*k8Zs6=>Z&bFSBBT6hR1F>oxl7{dr{bD%dBw+qk2 zgWY9D=0kXxpuoz*uIudRtmEKCCF#4_k%bTebTb%3P z;}Kr0q3!Jr)4A07`f^v6Z;RcbfzDFm>Ixp-)k=ricpMu&m_%2aw zHE!iepE!N`Sv)Iyh`^C^=d(}0_BXR8pOE>;d6}Z(Q`^<4k)HJa;MB^I9k$QoNiAaC zd2KU-_P=pk?VGR=RKCBZE>UITP+(K8+J;i$@-s?pt%`y((wqg?Lw+xJ(=D-8j^>}) z9T(x_+A^GEz#%)!=GFd-P2<_~%2j^5!bph?y{@d)`T^w2N-pC4VT}~aq+fYx%l=Ro zxE8z4E3t1frL9?jd^qRiG4UKN%;wOK(*D(X?LFoK6~{%0xrLEwKNS?`$NZ6beW<81 zUF#Bm<7{H|AYq@NuQ3*oh)K4CEF}>hswgK0GmFOqkU|kow9JE+84(=(LqyRHL_9y9 zS8p)s=4fOMjVx~(asB$rYad*zIT0~*_bR*~!XNbG1HQ%~JO&Iy67l}??mvcJd3hhP zk9s)nb)c2fv+3~uoUp->=C-b%3gT<)d8O}i#MoGK8(Q={)eOX;HN78 zEbdmv;1kaSSu~>h?nudziZu(QPmS-J74MEYA=dBkKJ3NwQb+xQJ%jlyGJ{fo_&qqL zCHtXBO4)VaDa>tst9T6K)htcP(%RdBWy9{FRg?BkgTeAqgPV#b&#dU&Km5SNvB;(P z!?4&Pb`@s+K-GW@E7v2#+?#DeT2|v97}Uo+D0h@`TJ}8XHM`P*hddm-ZXW{0?6_7; z{wyr%>T)i%$QG0LTe4Ilm*=$`-Q^SIv8F|`%!GP{K9l_GldO7*Nkbz*-FNV3K2P1_ z7YC;Ts*H9I7+mpfVwzsR6uBsMgCmx3*HU|dy96F~a|d`?!pn`MW9#8S=0&*SS>Ty@ z*mMtj?YD&``(WKjGAEpkPIRW7PPV>O2eK$4jBa4#;hoz+LdlP=u15dsAOj)x;_AY5G2+jQESb2D1VN6?C zdd`ld3*?lpHg1W`a+gX3AfxEsA7$!y_@W)5CHAVS`7X_7o?3k4|r=hV*2F3{g; z5F^6P+A8UPLEK!%{n;I<3LWo5We*ihET?$Oe9r1%By|cCyY)uj6df(6){3_jMloQ= zxBv05ut-kVF7X$g!yMLxoGi29t*Cyy zp0~Xucu0(c+7&6D^{??MYQXBg@omC^*UNvA&pADi)|a`O|CsIgWzS{zyG;@ediPBB z60gg}XF8Ccwno3H4oEfHsyi#xt;-zA*5Y&`XwN}Ed%ZfF&Bu3^@&r`+4?iyToTGN| zBoaKnguDB$jJa9Y)>5xDbsl@K)$!IaNTCyN*|=k1|Dr9%hp2Iv@@(+2{=1p0u*Fd$m+2t~#4YA`{1Z2~0$300V{Z0F^&q^{x| zqLu-jr%2| z-5xzsJs7f*a8`Suv&~#f)K@=DhM#F~n%Y5e?qpM;kmI)z8a^2qA2H8(V#BCf^~^(M zH+<{C%fib|zG?A)oI}t{1BVf^+F~z_av0`M&vSVHKjQFO01}rQ2+%hS@GozIwct?B|T==(Y#8 z{%lr{4MTl;U+5T!UwT(2t5X`^>Qs1kqw%|wYIm1at{Sno7~-S28<{8Ogr{IzWLDG} zyzI1V7C1$*%H11lnSM>$gedSXy2Ez8o~dX9_fKq*Tc)#eJ|58AlI`L3I`Z|tINTTmWD~IxT0@VB3p)$`1hG!zrT#*08S69sG_jIan2hoZW z@l%9SahqMW{@1?V;aUB?vxqAj)I@wEn^V|gdZ(QqMh`gP=+}O@m`=45Zn=71dv%M1Ho6! zbCl{WPv^L=w}SV)Leq(^x_B%$RQAiUw$8Q+-yEt)_4byxvz2$GD1ci;G|HaxvYfI++%{J^Clj~vu4p!F-(e@9wO8dnN8eY*tFfTtaM^(zfCE0eK;y7 zWvA4mZ|};{SMEq0XG~Fc2{^@H)t~=7zrT}I<;huhiTdoebyu;fn2ukc->o`nJSjPI z*q|bO%>`o6lV#JL);?~=dx?6RwcR*!2h^_Qt!roT~NqJ zi{@3UZvKDq1iLaQsBxsPIVblrf7CJqbCWMlPElXDL;PO(j9-*#d1xLje9w?(p=qMO zlB~kfyU$20Jf4FGg{&Ihq$1{Wr}VY%HUvI?xIx^>&g@FDGc~(XR3k9*MfrV^R{UXv z#>fdWH9jv>1jC!#M`L+KHyU`xX3DMnN?6&zn0S3H6aPG>AR~%%$|1cNQBvdz+*bikyoua%bU69B^5G69KFbMGmvi<8eq461L6M+Y7u1#J>cemh>2%8+h z8~Ge|AQS1#f;fl~7D@G4EaT?Of2mSEkvH1&ZOm(38yFbM&f-1`2$b>%cf57d&5~O& zW4?D`}ius&pRtWC_DJv6rA{phW`;h8y43`FXeX-P%ws)*YV z#n2mvu~7Nkdt4${L@>45;Kcrk0O??Fh0kxSe;v&nX4o=f`Yz;GAvYGsdfyQ5iM%(u zNyp!c4i86vSRT`LR+Vc^{`eWAt@%VkX~V?@m8yU{Rq_?*EGzCFm0?Xz9q`1J*i6WO zbT~}3Si)J;&m#PXqO`YHuj_KYaL6fW*KDBK*Ihp77aF5};|p+z@0`APz=T5O1f>LW zsNxs5q4ZVEs_5-xOOdyoi&Ew7yyYFqbi46gwY7h%ngM!Y5?&YCgs3vH*o1Dygno9x zVGtP*t$8Db#qf)ut?>ru^lb#KsAFP=Ff%ba2D4-ENbre;I-t#dFmXs?p$ytAIRA<0 z!n`yJM~oJa!iH{I_}uUss~6S#>(8)2D3nk0bkf&F$u!R;y7Qub)2}R%MBq0)R+Bh; z&M?K$cK~mF=eg&~&f2B{!Iv4`d!qy|G!g@i`f}MepJqa(GlComY3)y+>%-20IBa?Q}$c@LZ)x>An zE|5e7+?(LMB;r{Fh4(ezJ8;-c=a%~=6T(vGhDzdpFU>+$A|num&B-1FVW5JG#s7&i z|5af2>1lyTAaU7EM_=ZrY-D|*hQ=wq*t~Tex?_R8>DM|aEuI5D*BBLw&P_(@l%!6a zYEl(yxt%!_7n<5CnN9SUUU$6ziR06%sWqz~Jw3WAs^`M0=<~j`iNq7D4sh>OGNI;4 zOWl)jE-TwH!s~eYlwOm3Vsd}D9O+Vy$hI)TbM~?B?KXlBGAr_PJje%>JU3)}BxThH z_6O8NCibo;i!=<3u=beW+jgs;+9x~XQgfWDuEKHtea|hUl#GFctXU^MWIGz&su(}> zge19YkYK-IM|9~3C--ROSpQe=Y zS?Ias#U~3=SqD=2_=j=Sx4D=f%Afy&0)TF~B8UE_Zs;u3La?E#e@8bKH3QA;&5K2F z@SOA>feiS%1hoW}(6tMv@^bk`Ll^Yt`}4SbU-ui?{)3nen^{i$0UWs5Mu9SCLo@ecdJO(#f_UZb6P~l}d zJs!8&$a?mCo-i}<0^iiHH*cAi{Vb6qQT1rGOyU~pTy!b<2NGWkrd+W%eNU$0X2C{IVKEpaIP`xZMp&-zyz7^odcsCTXfZj? zf+MppNz&tyRbO`D$&mGA7Q0lde(_}d1=Ym$G3MgpjSUe$FI9cWE#qkzhP|muD?21y zM9#h6!|P~TI(;R}Keb6DMuEA^lvj6s$)%oj>#;EA5&`MUJx^XjZs}snX4Z7vxs$Qh z#nIc1RTZE5MVeSzRQmG`TrW#%?ZrnQ*C!Sn=A9<k#&C5VZ*ggfOkG;cNbl_gCZ|SYE{goV88?PK+;t%$y?5J>#f%JIqRtd~ zD13h1?Jy9j(WWf_@TH4Rb#=N|YOKj9UX}6aAuh=`5`H@E8+w0F2{jrHA@1T+=yFp| zzaEs@R$@DrsLWQ>f5%HIdpgh0!?0|%r2pDeTZ>Ej-R|X=b(yH}arl^@xfY*D!?M9} z1oM}>$3&)KK7rPaqA>9KPvv)$Bg*^fGoant2K@widX`d+2} z4kz`yx0BPNjM_ro&o_@7+x9m{c4fKCMR$*f6s{0^sp({M@9xLQfkJ=&y`H4j8b5)w z-5n#@jmGK69>yhK+xe1^J!aAD5i!{Hf<=RsNoP~uD*TEKL+Z|1TIsKDJ`oh=M^sQywY8?regeM=l(@IdC(nKy?n#;(giO!=S-b6O`ncfA`7!7l&PN+L6cl zYn5xCn)=9hZ_YXA;ontVc>bYr7re9bz!gz##9u4j3yyq$#vM2OwD7XC4!row<6&Is zcQ~%S!{zuPa7>lybextqFmsT@F%cB_k!*z{SckhumZ+6EOlLYAF8;y4)ZNhuisApx z$Cxue{gL%8N-7|!8^2}F`e|8?PLy67%5qF(X6oPiEJx#6cmN%}C*i&~%TYA|x67T5 zl2n;v+$(`ZwLQNQZDEHV=ij;E>z0M_?w&FfB0_9CJKy#%&*7MV?viW&EBs#$M?W`^ zCCmZ1dwT=+BIjIH%(3WF0GJOz`M6K*4G`rT&#hJkWgF2}$Jr=%<5A_j=PtSKhMN{R zWZOvt2fD}cv!lvQLhk?n?>|5RJvP`VbvioEzAnS@0{*3*NB4OilzKK@iz~Any5X7- z$#OKmpqs97NZ|Q2^&CA=pvQ8)nBsH*)Lazx7dMJm`Z@Uc9BPWYu0tjnX<^(oA4x}s z9^F#V@$j`00bPDS_%GjaIz;WL3`a6&7`V=GRk0G3YbKJme=MKO86wM^jWW^hWMmMk zsw05uCuXqPO{iAZF{M`>Ls48*jh028NEOLP5q$C&(j-@<|H1Sil^!_(X$R8^&kt?} zjNuAKDc;Fy_AXGgB%0pKQ8EuS(Br;b4XxJAJwe0gsc6WkD9H>D2}HLh1IflowG%TP zkuLE+E|zEpn7pfHQ`Pr+%=K^upqqPiBcp3`M%X3BUIQfTB^6P0V|IS-Og(l({vY(! z2Rd1y@pL{1ad9#j^S`RcW^UADp$q-R+jQf$`~p4hpDxidR!m_=p0{Deg~)8PGUIsO zi06;2=lytoRV*CmaMU$M+_8B#cH9Ekgeb;AoFH?+Q`e%_4xoqZoZ)^lLg+rsY}) z!i(iRMY_leD9w(lV0KRhBT(!hD=6tx!ET6eRH%7aK-bDc2gT{50n6O2*EdF7v8siM zS*YpTvIn+`LlDn=q3LF;7=(gPEkezSZ=wy?gLSU)fnQf#pKQmNxT6|en<}~w-#zth z7VWPaCojM&^KDtJZ0A8SgJ{J4nnj>&5a=M@pQq?BLX1=I&$Hg2f%hZu{v-ANRWVdG zqs`N|yCnRL;^TR;nbSSGu_BI-H|nP143uvpP+9Imu?^+GSmp!y9`@ntE##s(*1!uI z75TZkaYa6$1oPcj&hlLe1~1a%75N26lF20bZ&ASPB&(W-^=O->N0UcxcHtp$e$e#g z2F$JcOC9>AhaXb^^n?5Lm)_UQw%>fB9*;{9W?V093YIl4&6*mUn4!m}XZVY|^!jb# zTs?Xyxpc62YHo%jh&tFi;`<};V1)DY62o1eEO+>l>X{DEG!xd!$5JmMKNFtNm6 z*BGusNl(pXIxsKM&BY$Q>=j*`^obtr_AEJ_?ePZ9aXpB>BL0MKA;M?L#^b$2E?zFB zinrnHQ`qp5M2=p+GlI_fHV_9WGH}wOMZ_2 zlq}#R3pBT6m7s@iAni#?^80L1C`FdvVL}m)+&nH-Na3azc7`xY%w1qn zHb-K{&XwqOd<#4jh<1Z~|1HT^o*O7@tjPM(Yvl38x*;IGL zT~V4Dajws39^Yt*t#o~IKE+7L2$;Jo%*}f2iu}A}Wv*^cbL*wLJ2J!^SPB5^sgx95 z4FKw%{$BRCH7dY@81Q9>wcAxkKx}PBS1di>;{F+)B{`_6CCdYHHrW{ryqYz%hxn36 z=%4Tm`6UIFVi$}tJvIo{5OjFZ)Y$NhpxG!MyxLBE)ZtX@Y^MynF{`Xk9bo3xi_j4} zhow3~=@+0q3I8dwbxWdP!dr*60eeC7w?ly;>r^y2skIEJ*0N9=QvoTE)?LVWACmFV zL1>UtUo8CxzRwdk+mr)-77y8B05LJAH&(-rht&{b z)f=C=c383xd$qT)H{?xN6aDYnd*t)J?FFZP8(`9Ghvz@^c|O$ZnR=w@`raa?D4eI8 zgJ;O}HmI?NYbMiFd%+PP(}yKa>eFOc!&RDkmu5~Rq+V*ea%}K2Z1BFgz8AbBc6j?z z?~VcQWxj&|A%2g^w8HP1)He#hSM2b9oqA`77c{p4#Elk+ArzDS;+fw=#}_xUkwJ5F zzEj*AdLVu%Gd7=nt0jX>$gvbJe zFJLih9IUAle+Q3dPTVyTH~!N$>=w5`z123LILpOdUDv5sl8vnTNW}M%52Y&710Enf z^^Mv+lzFLzmN&hYSOf5S^rAlzTzDV^%o$aIkiZAl1@`r~Kl4!>g0uNb_XCyMmziwBZPn=1C2vxbS{w!76 z5u)n~`Ch8NN^gehOI%Y3SgP+1l#`^hT9j&H4+p2^f3@jyfE2~abs3R!qgydL2Unj3 z`4M-$d2NF5{jK+@ZA(MH@1*Gu>-wh+_U$-hH77^{HBfeEORi!scvYCTqwzes(3 zTmF1+!);J#pX$f?5Yw8Mo!@ zo+SfxGnii_IxZ(MZp&W;Y8?ex6{-|lScp^Y1NpV2Q*=x9JdQ$ZJ!%eqcmW#!I<@k_ zk{O`{oqQkiz*!Bv;l&{F;SjRL$xD%ubp4ds#>uy$p@7-07eYB&>Dcb_3v_L3v;#t~VdMQjj@O;{aZY)GL z%|=_aitfJ63q-diIa`~1&`|OBPchM@7Ew+tV9jPV|EDvpm6ZvN*7*_^JmDN|gS+<7 zd0|)Wq1h29baXx0m}u{f4fv_Ie1Z5*OA(Cu{V6Qs{-hcKD-J?#>=!eEPtXkEnz>&$ zXF}TeQTC80pp|dd#&{h-u8y7LV5S75m2cOb+x4=h@Tqphv=+x~0wNFz3`k-mTH_x} zsqFEucf6hkgj!g`hM*^zZd(=WfDvOqkqF^6>kB$Jr|{8}TdgE8*c<^%zMAN#lZRiT zPVRzAop1&Vq3wqDiwFME(=dfQ8W;;@quQO~rXqA_bj27qb7-i5Vm$K<@mY0-w0mWZ ze?2i!+c@W(g-wYeweMmgK~X8$vc+f9xn#Bo7Wa?IMw1|gM=Uf}U=~%vko7Hb2h8oF z1*MNI2gyHbX(-p+y?W1Ix6Q9@cqwR3^+>J?(G2i$g;voX!aS1?X<-c^_Ns1t%LD!j zn6EU96nA`_Om@U*Z7?Tc#f0?GRT5oaK|4Pd3= zsF9qrmd&zES``hjDaHL$IM7@CSnj1Kn>lAR%o!nuqEg-TL!}9wf$pCIqk~@7e)E~g zn+|mwtg_@}bZcrBgE|0lnFkw3Qrzr@6=!(LXk{^}XvF-4N-P7;oa}}<2lePON{H^7 z5kb={#X~NzJ&4{H?|{Y$h-7qw|DbM+(M^a4yi>&SqgSTnasV2BO^;7eDzh;U3-MPP z#)z4$%G^OXS5XI*)+=-)+b?_kpvb(G0;<=XC{ePe#CJpTHKxSgWU*$#EqEP_J&?~S zUZ<5B|R3*&l4NY0TfI*CE#2v zxWKyj8;rSL8wa_E67$8D?*JW4PxE2wsc-a|Zv`~}4o(L1F_UO@QJ~?EP0plFb^|Oh zSa4U1HMGO>8!=>2`s+p%S~0Tm5d z6MV@gJ-Jy=HU*N~BRfM2n(zVX%$^E5V~Ks~52XH-jU?um>u#OWTrf zE=_`eI0u@;`b=f}x{D9rwH{XSVJ;ui|E&1{^r9U&PwHszlh0}YlJ;Ipny2hv?MupG zyi#^SW&hfK^EjCUk)N`EfzFU^Q1PB;m>Fn8iyi_RLcmX^7f#VJ$27MUeu zOA1Q@mz)hUj>u31F66@iKFEK4=t-7>q6T_^%fMQa{h(d-Vz8ZB-Op8vfq7pB!_@Yw zm@HItm%`44GDk8Zz=k&O0@=v3-HFLGtL{6>tUB3ZvWr0k*q8?{HX1ySo-Il&psD;#-I$>|97e#5hLjk>2uT@S(R(y4TLY!{3lOC^ zaZ;Kl1F4*}f+nxf^j!J9FCoaWjHF|*fD}iLp!pbv!}#zqAMF3gAGtHHOvxoUSpuFA zMH9$EFN$`11!jf-m5s6{?e+`#0KEp12*VvKN(=&ss&4X?)OX_A9hf1pTmv!pgHAz| z)Pu2!rBXMO*5r|(V_l_mcGiCzS)-kzAgPrTY9rCeIn#Ws;;TF^jur| zJGS)Aw)E|`^bc(5hivH`w)8u;^buS7EC_Om13FfqOSQWnX7|?p6n}lO+Fj81qTLI% zJ0l!!v7G1*NT>VR-}ir0_IEXIss6UZ9hHKMzQ4ehzRZ@s(U!i|mi~z?{iH4Zo-KVE zCiN8F?N}CSckhyTHz~Xy$MPcDJxIIr89W2;))$GlS$DhReB!$~xfgg1Nx?vRye)mD zExp8+{-rJbq%Hl5Eq&OQKIPn={+(n?FSMnpWa#xDw+*?y>*(|1vV2S+0KB z?*0P?4jMc}^9&t!!tk6EN92zD4^}gh^rY_8?M)J z?Z@>gF4=Y>*8l(XADg|V9CV(J>uOvzxK`mZaovaOx40g~^%Sl+u3fmU$CaK8kmxJl zcS-r)WS8$%O1}SSyCvUmD3#-VFT(m#CB$-<~q@qo?uJQwWV*hrGH{eKWR(vu%+L( zrH|Os!_MoG5#O+-C)m#rSGt%e`8BOn@WE@nf~b3luTbVLH4m1w^SehECmZf z=a07Zc3b*ATl%mq-47Ol)ciKemcH1QzQ&fmBbBC-@zpZ@VBC`F?Gj%l({E3~AilQr zJGS%?+Hb5mev&PHqb>b2Te`)TK5R>$JH7|bHMaCmZ0YT`bXQM0=QQdZvB4(p5JlxL(EeF0PMoeU2;p0*B)STw`z*;<^x5Ij$O9 zt8o1m*K}N0u}Lk_itE zOz4s7VUpgLRVXWM)b@8jRC0r>$=*c;m`7CT8=!%01gmaFMt#|hItbo z^s(+*@k>4NUwZV3^}qpEghNXP>85c%9>g-hLr2E%}`m(GV-x4_%5v{GDg0$Vn{Koqis*`^yy3&eB7n5l^oGLP|V#)US!1$$Kb zQyH)1rBSyi?Mx-gi!4hDtOj+kGXNCa5m?NYZH>Tt*(&meBUtb6c!8LsU}00BsT;m3 z#7UVaz!<6*exf%WaRtj-mY##44SFIP5p4ql01CA8^Hb4-aALUi!fZXdcdzbrcHARt zfvvZ2vrcFTmKv`&z30-MA4?doh}!@|+fb2T*#O=O!X#a(AkG5R9pYKMO6CWrdny$y7I9Pt!r_b=H)64YNU4^ovC#^4pF0cG-Z6}nj_ zDsiWy!fUlW<(xS*KJCn`C2?18VK-VXER6rv2j;^^uYakl-}br@uqzyMP%V;*+!O7J`;>@bSzqE_nD;XQu3Rk6h{BsxCy{KfVQC>ie*D< zg$CbcaZ)c`u|6^(jSKDFv7F$Esdji9%EUL=j_8U_h~|a=3*Y18KaI<9bj*<4nKPNT zmsqILw+R6T5NCf@e!{qax9kjKMLWFojpFUULLkKajbPBVD884$_fPF3i8|pcUkgV` z_-t8?bULmT(@_P=t)+i1?%!m=S`S!j#ixIlD0M52-7ChjY;?tL`Y*e!lAS2ISHfx( zP6;bjFP`5%e!Z_29lze?sd{x&wNk?0D}KvwQvC@Uf@~nuCfSuI1x^2Y_T)&}a&+WB zhz(vR;MPUM*^U17sa~X?RdrLd^0O|7AI0*qN;N?03p1fGT;ZGPyV5s{+dKB6Z}ZR_ z+N?%x7Q%-tzv~%m`3OL|aYz>qpBc~jV5#8spoW&==dvjqr9%uw@ z^fnh~3jLB%48>@MHbK7V1>gAr1ca+b|A*>7(CWrg0-8B@j7oL>@OP1M z%+7!4oa1$V7!WEf2=m3xcL)-D1Vp$n5M7arUJaNbhxiV@55)bl`vb-tc7MQp(bq7? zA+&c?YnEB9nJ+FvVPCR^4O*5WX|?14=(8Q)0}F)e{}wLvm5k1hAT}N2=dT@ztANtD zHJOS}E-x9K6*1^w1($q7 zeoJlO5q?ZA=?g@{D6~Ll4AD@7zx*22a0>dl%V=i-xM-X_YZJ0BE6R61UcSn;>tzx$b zXUoS<@m-bJEv`|CM)55qtYETbr2XnGoVR@Qd~m$lAhN@N3!h+ey>=K`Z z98mIANCD%+UKG`505XRSmn$^>12_WMFl4YquDJ-yPW85I`_dvk#<2E6?1d}$LI z#jPSH=T)qkqx-P{#-65aVINwMIJHl?>r&-VAWuQHVkLvdVvl9hsc0A{X4AwREqCYj z)MzSZ0OCF7rzDTa!| zVJ>zN#BBIr6T|L22-Tuq6kU3@-n1X9?KW}7>A(O{b_G;!xtvBM8KSzdPXJXHVLh$( z8)mWAlUS>G=}r6%l(oaW#YGGGBadc@B58Dct+Xxz#~RWcTLX=|SQ?nh z-j2Y$gzs1rN6>gAzm_rqO&!;}sfZog zt~c#-iHTr6iU6a|D%u$7C!A=_8k!oG!E#X$1Q$#5#WK0gbe5dd)*eVE*M!XL@h~Q2 zeikhJly<#u2Fl(DpJ8iffZ(lm2957}xJrZ}4aFjRI5(cj_oTY>NWfSH=6G*!(AgC- zmbwEp|IB8rqSY{1G178YNm=QyGJWnK+F~N`1>0>9R)o=laFLp;f`u7@C*^R#fT6u7 zAm8I1b}beTogN$QR@Rlx`b#2M*d8p~Su?D7XP|6XK%2A+q%Y_&8Q17+w`VP5mhut| z&N`X>|3;eY*!4DhE5hRPI3f{0)`$pl#Oo)wMqr*Y`d(~oY)TCph(K|>AB*^tRz0ANaDMlhg8uJ#4n6HF=T8 zbrWlCpq{@l9iM&_{?iDjH~uAGfq!b3F7|XDB1g@m3@zeND#6ZTH}@aE6+XvmkBoql z<7wZi#5gqrd>7-XP>rXzIG!}o#P^a?#(BDN6UcWH$VbSaq1PH`)_mQwRd_LAOGHrT zREY@c@2T{LFRc`-V~IJ8hNuJBGtgFv4w*E*WxYrba_{9=O2N?+T#g`fXHCD{4o#2FeVbGt_;g{Dg^dPONac?q1a0p-&e2Nq%i3mf%)Es|*%qKr7itPXCgbILZRCZ+i4iDSE+-q}{oV zh0FkAd3V$x@EK}atGI>J3!|(#@Kk{77a5U>3f)58bONhy>U0})MfO6gVXS%dkXxSj zu+YfB3$t~h;Y>`0<(5UKCFE=jc?X*p>0w1B$0q7NZDR}6tc9OGOxi)$0L3_~u+%`> zm0F7%7aCcMEp_CEba=ItVk*3Pf&(+)$d@q#LJ2#E4}7$)5dH}os zyjw{E-Kg^DMm1=;EH6mK?Bn93v22sKWJ1IRB{rc25K*=e>(7=+B@@TfUX-CP(6i9n z;|ee-tQ-(1duydDQ216Nv-tI(`JOdB1jpe-2pKz%-Jj^&e*CEPwsD>aPSXgEtK`c8 zpf+aK47jsx1;PWK%L2hW;Co7Cn-$}7PjAF?wA&kwsQDRHFR;FXII0*2eUx>YK9Hou z5k4JSNR^pc-?;Lm4>pZAXK!@0sWO^pCb>p>OgM z1N0>JYR%3sNZb#@MEzZ||78oTN-{#+y7FqWQV+n^oGlSfTuXBNr*U!tCmTKw5I?Kg zFkX#=6ojl9LcXX5=b#6#<@Ba-b?$&pFap}xz*n)6Mt4M<(d}7Sj*Ii~nb`1Gu74s> z8eb4Mo{mvrX63V!rkcT1ZG8u6+!BnzkO&iU0k-Nui(Xy=GqTkGW~Z0fUNTh??P=+a zm0q#}dgK%Fb{@NOH@zN}3*+8gJjIsfQDec3jMY8l!`W+yFd57udWo~R1L*O_*|5((s>!cHoQ~!y&F&Ve1?%G>MIwB$T zeC;wMH0py~6gv1A{!BOEuRM|Ez)l`n1b$1r_sWOxr#Kk`Wa07y$XP1`^=tqE>=$9K z;e|LzuNf*Df|h??dQO#gA?c-#x8eHr5Hy_HTY=CbJ-Rth{DJZZ)q-kZ?h35444+%u zFgdrums`7hB>a1RETU%T=gECG5V&w$0_!%hhQk^bm@2Y5_u!~^pe|n4^t|M;DBN3A zBqeG}QmA`sKQ1-;m-Hu|5Wg|ceNtc?y~h1(=diU^^xladOJDIc^d_{M+cEW-kG#h;)ooNNpjliVR=8aOU92w$)kG^%9Uz!tE~#A!Ue#uG9|%Gd75i9sVb zF*Jnjd@@7#M6&P!9tfbh_Lf|SR^J7gkkY4hVCuswoP4rftN$1sA22IDwYTOvBB!?a zax+>cHD;JP)0AwYIGeGhQ6m2Y1S=yKi_>fvY zccdS}``xg9GrKG!;?j+wboXNA!-GR8@pLz9Rkhe_oB=#D118`b19(f-F$3QKzM-o+ zX1F7RaiAA6Dm@+lBpZ_-%Vxj|z;nK2_TP~mG%{p*57J+wvGC-gu^D9kq14B)r&2dq za~hB1wepU13McrmeXpFV1o5dhT=wtGpor8O9@ZaHn6j?iZ=D`$~2hBG^22QvE zJEkc50g*|qK1)+)4u<;5l zrMFt(sDJ8Z-H~$L#7rHV1~@N?XGSPE;p4z*mHrqBXS@XmyAMGTg~m$j^Nqw03OX<- zs$B)y2iY~xgH1c;7)qGPNc(zHNy4)r$P*v0QN2OoNp6C?#9k1%qZ9k_ni5mjDx`3N z0gD*FA_mGT!@6Ab$`;CE7AbpZ5I!Mj5_@qgRx%_fH8w>UalMuGAkmIZmvA3Hk(7Xg z5Hn*D3?Q_l6^V^*{w)a$r|k{8Tb!VS$EKU zCunx)IJL{1>-KKUkou489(aa7^~3c68>S-i?{i2DuXay7p`{xABjf=JT_n&ZPlA*( zul6LK)3Fm3lSdKqwK~Sn1WZ5ptOy=_v~4ZhVB^aj2i>Gm`I0kO;xLI46!8Ao;AL2j|^28Y{Jj9$LXDh5`cKRqe+Qex? z;UY3dtEPb}TTe&3wkm&zwq}Td`(KUIxkADy|?fwo6Qwcu3`J8I%XFJh2X5;P1e<$r3nU zW)fv@j`8Nv<+YnRYw*$9NpU?#%gmj8=H; zW5m3m8_;NCl~Q6KA^VH~+NfNVJ!4u_`qGsSy((C(db|8ce+Epvp2bd|fEo6sBw4%FH>J8e3S5pZoC$c}@3 z(#TGotdKH(Ssnvezr>~O4}?sjm(M$roCuShnQjLwL3C*EFty@i05IO_>oBt_OBbe%NHAcWXFkpX>P zx|Z(8%unvYdga1E>0D2^=7~I%r`1Fkk3J6@CGAtN<%CZ#3iN0r#t-_u3b!h%cUT+9 zlVv_-{Q+|_+B@7y|HY^Pj4gCXtHWg>OJN(@A@&pjShU3rV=p!?z8JwACk+*Ga!Dnb zUy6!_Yeru0aM-U?t>=Zf^P-SQtv~j(_}p2m1Ckg#&1f@5CPpZ?_G5&q@Y<;|E-@49 z6g0YcG+QXKml~lZaf%xO$Z2)nC)!XPl?tiJo@1|>O}$5l8Xq2Ip6qIvk?M6A>nTwd z<4brBjKz7;!~L{7ZzmNO;CPmte)qwL-~BmLLi0y8QVY?)x;`JJ3M97b+L<*%8G>qFxVHwTV)hv zt`p>|oTuMl3Cv1-nJ3QiSThmj2ate&fxVGu3u@FnSe-SppMiK6-0qF((D!!jO#fQM zjO|v=m`J;~A<`&LeHh}PG}0a(UV)QDzy-7|K4YvRO-;~7rT0Ar zR_uEQr5IFT#kc(0O~wfA?g>?ltVczxxZA3@6VH2PNZ@FM1h!)=;w;+O%tm0lSM2Mr zzE8li?{CzN2rmC#q}%z0ZiKq=+=)QRz4(L&dhumz-)5nVNBn34Kt)${183J}Cn#w+ ztuV!ZW~*~tYRUUC*PJYdchrE&9C?~28&;wMZ73F4@_-lH!7kQ#JW77ou&S7AH~=Y0 zuX!*HbAHi=;#@0?X#Q8<8Oh8J*07wZYJ%Oac6{)YTZ}l>1f7t_3U#l;u%mSjfkX?+50o_pKx|vrIyPc&f zkoTD=CxOkV{ET+jm}{gYQQb%dDg7okqtm!&WSHQO(E!!nE?+g&c-NhTAXOurXG^O$ z4*V+YN3JQ)WpFZd2I?@pRm#8US3Y>vt;%pm7gQespdpGUAd44aRe|yPdiY!&;R{e< zV2_i`4)Hc5Xgaux1^lhPB&Ly8iDAbk7pk;ywfZCGnnsWkH>|dm7c`J7Vk{ajS6mv|T%M&q-7KYS!LkmVas{Pq z8&1XznK*Nus<5ev(X0@wf#J9(h930E2`CIe{ly>TmH^B`Xl0qc;1&!gDtWQR-Fj^F zp=8^#k#fB=4Ubn_&f}Z$NwV#h_ZcF2F5T zeN7$i)2Y+=qWdy@#f`if(5J4E>Wr^xpSz+zEv^AD2(3z-BWPx&j>YMoO8Hc#^OUkx z4yK%n^majeP~UM|+*kt4?n$51OE^3uRGu*b1aUGNH(H2CL1z;zG#z74lTAky zG&sr;ugllTx%gMVbJ-xom@&5liy;cDcm{YC{8OOE?o!7-a+1M|o8f+;NdS=?>rfO> z{u{StxWq0fcj}xXHJX1NMqbRd6EHEk?4q1X zO=vh~U)do5nYG-H8=WU&@O%8`o_tJqvUGts=`5!1k~!kW!oL0Mok>#!BETQXUqlhI z`oR78v>1+J#IWo$o@oSBZG+E^Rk(X%Kdt_K0>*K6TXAP>OM|@sIlmTncok+zMF+-# zl76eKm7xu&RIA5$#8fbd3a|I;Siqv`d74CWGBj zTX8Z}7J*qxH9R~qU|y)IT zh)pi)kp2lX=i*^mz!O#sEU>YXBY~=X#c?F@7d$mz+yEvBn4|Mak}3>XVagu9mu-ME zDj3tjKp4j0A(5Bhc=&~E9wCa4q}hrN0gU;fCic|SzT>Pt470U(LvB%k0%lr$i4Y(5 zAvm230BhCkc|5?x_4<)a@XyTqp<-Yl`qv<9%@>)9%l)}=|8U9O{}{!dz+1)KzvM?o z#o#rmycBN_z6)^f7n3_BYaaw4u=e^SZ=p2+e?QI;bj1B`$;{q&S&Cws-&}SEsz9@f z#5zm^DUsBBNrF=nJFYsV=Pl2Jyqw&9L;iZOb|ri8b+EQEr`lrbL1gM&2^Kh zfdORo7MAqQyLwJ@(D?6sFCK#CsbqIb0rFxHpHiNnMS0#hcQhUG}LWalu9 z>EEjkqJN1nS(lA~8dwd-SD-8_KWM5ZYIXmlK#evQ*$IID-u+MZj}&*Ib&}PPX?~t! zf^~8Ke@iCl%w>BmX@(;A^SdtJ7`o$rNc;*CN_OLc1tJiRnVNK zdx8tRR7vkRg#ENeg}W0fY^Rm?vu-d(Oz-p?LH7Ze^Tc(}I2>Kg8C0U$#M7UXN2F;$ z=^T9);IcluJ?}A2iZBkwe$W7v#3MM87Zsn6N~|p1xI?}<@-%k9cEx2qJH!>T9x67p z#izZssy#ON<}LF9?qYzGk;F7VLP3O`U!%B~cq!$7L>Lc@-Q#K2qn%ZC<*)<72&hp2GI zTodpSCe{>bT1Ba>MVc3m?t)(RZ9LdhpIs|IcnD2BwpK3oa~q1)4XxrumQ<_vqwDI+ zU#@vkPZA(9pLSp`>6cTbi zamLG`UjkkudO`CzV50D79^Io2ot8(}i99bCnh=V}5j{Wwnv0fmHzm>D1oy7Ab;MGU{=#Ef1dppH9c)c%=1ox%X%e ztT`&LXFP1~K}}}LQ`b$vV(@~D3j$-wxQ%w1JMjl^Nh#*X0UuFHXR@67Ot6C zi!+RH?Zzc=Eync-E}W;I-u7?$hDYBSff%5%o3*+F4xFHkkd}HT;{LVh3=CfXR%xk@ z`y27-sA#~Zbey}eE-O3*WGH%z^vPKbO8Yj!vyX=Q*NFl5%1v?WwF3WIZYf_2MITqF zT~zXv+31R`I5psBDBW=v{;b2~>DvD$0O4EwzDg`-sssnc-XWg5M}Z;)8#sW%oTxx8 zS(f-7J~}6jgZTb&KWdl9Y@q%nixP9NCaOgpbDE2H;?#jRAztC2~*9WpY zUfjYah9Eut?P629P>U*by(+ZMUg*c^LcdmpCaFSEd!ZXyNdB|te-j6p;0&8!;b!sv z$3OrBgOh#p3)+UwdTfTr+}d&3!~8~$M>z>gr))8d37wqq3qQe5DP5a_i0>}$vEnv~ z*tb2{aRim}Ws!rA^<*5oKO4%EI5H@*p8~yz`YnVh2A$=a>SdcJf<5*3d*t7!f7`!N zzkRy3^d*oAt0hwFX%ab2EzpPYIE(O$drD$ayY9f~;gXvFRv(55W!2KFlzX%~H@4IT z<>+mxV$+1B)uCt5<9b#F7d0;%CE_Ys!z1}s01=xEnf2%VN+esdV6rCV9#E1nEx%%} zWwOVwfC7p^Nfm@zqZdqd#(}ilU^ejDg4;4&qOL#N!D7ndayDT=ZlHIp%#_Jx&_v1y zUF>{|a=;Y@ObmeGvQ926rG^U7>j9SkkfgpT*WJ%rX9MIZ5N%vOQ`m^pN09$xIVW3S z@_d_S;Uj9+Y9~1oMTDjfdjG}`SvNnN%@1w=dg}wg{xt^ZuhLh8?zm~?yAjR{Ei^-X z2OF&|zv<~g5)uK#Tg8D7Ne668Y{_CUFCEV4h^X=t=3Jbxq@!=srC);Hosjnmy=M@1 zV#CfFKRt(7S&7NLnB7O#f zchVy$goBmqRscQv+kLb%zz-R@JRqZ35otFDAp{^Cj@4=3nU!q-VH8R&t)n*>T zYWwM>)iQKZRi&XUHf>fND)(&7TcR#j))@viK5@R{wje z8amQoe!a?LokcYTy{*0-Cgb&_y~rLvp16teu85Kg80f6Yo(T3t?oOP_`U7T_g|dtS zm<&aW%rhA}7<92zEBL^0*~$2U!6JssIv6f13rY=@k>c3jpy&D;ytxgR=GLyvMNsx; zh#-O}Tjtj49>aq+rWQ>AsrZ(&H~n{IhqU?@+gp|OL)^o_*I`q-67ZU1N*iK0hX#slhLG>DQG5^#$qHDK>8hM>*KKX(s(e$ zoSceibd02=+yVWGeGWc>e57#$zi)@14lQQk4ut38)R9O( zU)c&&=rbc&%g@C879(s_NAHuY5XM(kQ`x7+FZfc~T-#XVdx*S(X?{3-MsKMK`v;Bx zAzF#-pz%8>rYzWmEbrM(`dP7a1>=I9M@r4-{xJPdri4x;cVx%rVm5b-othdKmJdeWI6TkkI^Z;RGw2E)h zIi&z9NXj%PqZ(|Qqf!$r{TlWh&Wq3^ap(Y~uaHKyLt^kpfMv`BHuJpL&0UE$p;6es z03jr|nia8qpiYta(=JvExr6B2&g5mV2p$zd5j6Y#DGwvtm#oAhf0gcNm{JuP3X2_m z&So3z0wM^DmACE#Wo%!L)v8i7q%}s00W1^jN_*`s?tV6RxjcV5a9sb%TMWd9)_ZRw zOGkQ1~831gp$93*-VGw)t0%{dM zCTRK=VPR5(=y4yc7uYrg#z4rebGxr_tF%ISsY0Pg(94%s1s7yajb*_iv$f_lU(B1N z&t)1)^lbPW?~~hYW!=;v$T^X$;$#B)8{jUW9V=HaEYY2ZKtXPqjULLY$$laa9hGpg zq7j>anv+rGkVAvic9g_;r&nV6MAdj{g_M zM(0F z%lS&m__qVbzZVTR>j`5nrs0p(_cHtyCC=klK^V>WhVatm2s8z)vZ4@1p2iA;c1ie5 zDB}LOj|3^NqV15Iqw|t()q$L_sA7|(lE|qIoc8_{Z~rtcN7QJ1;RW3hD>nRJI)li7CJHhREd-Jl1yB0%8-emkry=PyG0T06AYOMm~Tiq4|Rd^ zs6<@(2BQZ0`3mv=&-wSWLbCw#F$MH|`mCe-k3`!tD@qoOj4bIj1z#ekVEEj7O~7mo zC*Uyhjlb~8HvR5FsFa)xk2C$UmhjJl=3mO^AwU7T)N4} zLwlq|dl0@)VVn(&gPNZRFFUh0va3c)M5_u%q!5MGhlnPyUu|<@AU?sDu08P9Qq_k5 zMhql=3ezZe`>XN7E*t!nC&3i3?1fnHJ__~@h!Z(F54Fu?dxGsc~QX1})gj){cW5y}W z4&vCXyQ4C%ywYdx^c8xXBS?M3Gs;E*NM?8ufS`6a;v~Ye@uea=Cv1=%h0Ch~&TS-n z;$m4Irx{-22%m=vmz{-AWo3avVAj5B6icHbQqLnRN>LB|0e(bN`D64a=pdI|-8Pec zDW~00`kk^9;_MP`+r|l$ouChdIkk8WbGNvCAcitdxIs+pc>FFfq<_}L^CGjY!zBj6 zHA#F?$tfEpthtFd<(+@5plYaDejmiacx)8x`NH5zHX4L87w_R0zlK-$wD zaAL?|#C~%RKe__bW*-~kyRRPChUk?`Y0F#)7=o^rFSQ~50KYkcf|syhEN6|ZGf3kM zz2~69di1N^ez=k$?!YRK$m-&55=o+sm5H*mSz9?K$*mm25HSkFPY1+E$_i)k;|<_P z$O!9XqUbFiM_@sRJj5M3=AlTD)YrtWAF&f~Ol}-8lSoDz-72gZHVN1zJc+F0ZQQU5 zBMo|IK<#a(BnL#CJoEv-m1@}(V}k_yzlgdAxQ_O2s>~gqA_`HCj~RJ(1w%JxQ$kv<>9wj6}xshQ&$JsH{y83>~#yghPXLP(p`gx_c{#1@?u z*r2dtuefkIrrImIHfLeKqtw47h;c~g(i;fT0#`ZU1Q*a{WNmK1F{*`|`FY6MB>r(L zAPhrc+iSkFyYbWs$=z~01W!orOK@fff}rr(EcsbZ8a1B>icll|E|8ts=hY)Sx)0az3SWdM&J7K$jj!QWMvVZ)$V~@-oY6K&Aw79^cY8} z6`8gH?pW!m;%o!^vKc6`7Jt)&=8Vd~f=v7f7|vF#$wJX)sOMRc3&1a2UtpdKpA{_I zycG7_8H;Wn6O=jx%&BC|MZUrepMlPT4sRkhJws{iGHgkY`EunE_S~P85+%~2EElVJ z#UIEc0_e;i^5KLLSF@BKq2#P1=0-L~*3m{FQ& z?3mER-{pQDhQ|#2$S_t+A4ukhq8l(@KAy*E_+6N1K|*xUwfTAS(5H%6wX^v3;tvp< z&((2@6+ti0t8T^2B<=OuhOA;t*}2+=A@X@bQ+N=L87fBA&8WIF5XD9o#A4>*2h_LJ zPAqVQPwkb3kcTY%Nab#9SZ5_2Z{ttE`4+)WKpYRf6SS881b5xM$2u;uP1Ii@*Mf6O zrno6HW$@uyikC50?F6wQGNDtgbYWB^U|xnbii0ieYM9a=A}-D;)6p`;ouO@*(!V6D zI5Nz_;IWK`yJSp2VjdBFVin4PvMq92MkD?jEc;lSwACt|IQ>ftJ#W#jVbEEUu9Cvq z22}yrIZ*b2b~{fbL;o$ex9@kC%l1JqX*f}eiqa(6I;x4M;`o(Hd1TWF>&T|w^1^Da z95{o}LYWDw>g+)dm;iQ$NOvNkyR3ivgB2zs&{wNnp)2$5nXj$+PE;1Dq8;v~?Oxj2dph6JvgTi_T1cu2x*xtKJArTSNKDA)yfLlH_wT+!By zM9^0jk6h&4kRg#e3KF>iP8EwA1}ko$O$LYTNtQ233;|M}BTM>6TQk|d#3Y^%AiIW= zddQuyejWq5_{U0&#T%ui_%@uFg)g-Yk}TKqB#bVckkyK*Lp99V2H`G`&%z0$_T#fU zrBx;CIHzUB*z0PKt(uLDo`171vnw8nq)uuf0cDHmCGA3iUj3{jQ_vWzDBp z^()r{fzlLDz%Kt1bE?U$#t#Mu~#+QfzRn%XKKyVN7DYDG(+ zS=Ax>7MP88>c`h1>1}wN zvvfSV34fsiutSiCodif(0U8KkT?%`}3t}<9E3n zUY4pr-T_gwh4hQc&y+2$|BEbNH&Q`LzlqHd*w1?d!9(=-{edvu+=7*?Tb@v{`haSc zmkwrFdT~sYJWdV)>SzF309o&)tasaGJ)>>g#NW73&BKAG(V z>q`IBT{1(Q2lo$80hL}V%SEL@F}H2v_-&6> zQ~AH7HVsA3oB?FLa2iThF`0X~8z}_?_Vy@>mb8Kg)ccMHG<>{EsmR7CQQdA9S z+y02PY#;dRR_u+4L?9_SHYvD-TLP3WAuk3@uYD2i4;^z~M4p(3IRVJ+ZOwF~;?dwf z>e>DvMItve$?Xp)4?91Nm87qnI(XDWuk8<@PwFTQxxa%YkH%lCi?Jcx-%*EzwZB8Q z!}~l5Bik{(Z#&$_YsY<0u^ofgpdC>ET6ANeoMYQln>?;R70%n^H>;uXE1Q+>e;N8m z;Um|p__ZwVCEWvu-+H#lj4TbAutRp6lXJ1D<#b1p!*LP+L{5Xb2{RUSb5bZzga@Md z>Mi_=zf;0rDPdpkl~Cq-xy_XHfcOm}R(`EaQv4#CVyP6tp`~Ik&c9N!H;8H8@P7mm z?Bj`ooLj?#Ac%eDU$N4_SqlM7k+GThk)k$;N1Pvr3L+SEC$;z=L>+wrU-)VER=AZ{j||zZv^P zXhQA;e^Ue+zJDHGw>ZuT#^Cn_W+DeOOK}&E6JMcug0b%%Z1FF}ZrDeITKV@58gm}T ziq-EpvUTDL?at*e9qXlYvLmjBIqPstu?fRDTA7Dqxf}fJbaUoSzGvkWZ?-KoB5m+n zy^SjNi_?H0exj<4G3zFXma?a|i2@*|ZJ4oh(|C(ahNI^e97cyW9Fkc zdLE`nz+MVrq43>SWMP=AsEQE6} zwm`EJw_U?2y{B3lwuuB$|m&Tu%^+ikt;^vNOpy?@^*g+Z!qmrI0MhRG1{Y%M-uR$la$Z?Y@P~VKKf1e3a!4~v;xbixt;0v#KC(JwL`V)POiX0RS8;)BMAo_}&Z*;|RX z{pf86Blpk=N|E0uy@1e_X+?qEODf;cmQ(uoe0jbOBXn*0_cKr>ZTdHK;bZFG#{~G? zgU8dmEig*&jzjO(@#`|syHDpWrFU}z513so{`(xFVghL$!E(1vR59q7>i1jL_#P^- zR)FsPX2hdLXj>q5bB0)p%<C zYPHo?d$HQLT4`-bzzPXy5=6OK1=I>!UpaBS09FF1%=cUSoVg@iq}H$h?|J?_OlHnG z`|Q2;+H0@9*4k^Wee)bk(x1_Vh(DtX;V+}alM7qp)Lp)BN1d^e-lhqi zGvr@oTnG>dbWeylww8hMelzkyO}izJwI5y{Yd7Vw<3&AqR3?(89y~1Sfe2(uJ;=ZQ z`E*eaa!?PDm*eWeqo@ZvExGoIq@8pb2C@IZtT^56O~0#ncY8h5*f{ zc3No&H&_~i7b3|k5e?z$R1HDFAsWKiR1Lwrn=@~iGcb=lO7mB`V=qLPD-~f3>`0(h z4FRmBB8a5MR7z113jQk8bhA@o9sY1`0blq13!+mfC+z1VWldd3Z;TGmv;`|Fo?acU(m(}iK zwX!l?bB;oB!)H)T=j}o^N8SnVsdP*+)}dG^QWT}b1eK*P4J;L z?h)EGZ6QsgOhUk97ZoOg-Lhtf{0|G=%UH60KP=iyKa=83<>g_e zygY2Z+G@V4l$Wn7&Lp~dtSnaxE&$0wqIGhjYi4sQMSi2y$exoL0;{)jeyi{I;rW^(ImO6mzzRKLrJ`@Xh}o~-8`>d_iWQekV$nkm#MmY4rb^Nk~= zT2vL8p)OPvqv>pu{?CVwZBH&6?48m4w}M(4v^Dq8(d zO*Ym45D-14{$n8)pQx_^V#77E5Gieta1zD!zK=y&L>h69|GG2F6FMW6fr$3wTn3x| zMzkMQwFT^o5$41&wV!IVpYE&V&&}t`$b<4T=`a6@@?-VsSh>Y)pC~{1V&K551m))& z)qPU2@R#8x76uC+g?9$(9<=#cc53Ee!^=RDFm)f>P3Ffo51_=9L z%u~IUU~>8r^qezhm`aaBE>4sS_3xPVo%$NiH)7)@ydHJOXnb2_qRF3l#5uQvGz(bv zOOfkhC~G5IqFC{>ncP^}DZi-tAtUo)*+QvVg=RAE&qM(5TBL9)zm)nTn*v)N(Dp7_Dum+4{() z3XIgB=?ou?7G7ZEwm*AS0S}|uU0Vmnf;)RFTZyzOwh}%MhUy+RMyR$i_ft~ZzeqK< z%0C~y-zsW6%smrY!)AgyL5lWQMYoCyv(Cs?7hC+py4ulSV*b-q+ce2T+L0!S?Tf{l zkC(x69CT`~w&*#y^9)dTsvUa)TyDyW8a+uO{erRHzCPW`XEyg1Fds5^FPx@c8LHkc zyCni(uw{@5^P{LbO(;Fjv{gUGCS&!^ioHhlP^I`hDqLa+3RK_@(+sUrav!64Xq<8+ zWOXoiq@mSS+OkPvhF*o*Q)tSchZ>_-iSpy9-ah*~LgSF8`5E+`Mxr=^(!`a=(WM3NmU5ArN0rvI#kd~f z2kS(lZ5*>WRomQoP_S|OQKr;f*CcAsqoVep#nnC2mXR&$=c6Xj{w5`Bsv)={u@pEG z{%vO;-rKQQ{J?%J^_mJw-7|uYszsI2-^vVAe1oT%T<{#Z=r0#N{&C*0xqHtk-_J4L5J)Eo)|WGn<)22* zFQyo7&h5Hm^{gy*%W`J-mt)P!*65Bk+MQPkQQ6;&zA5PoY9R{(wzlh$yg?GUJC*Zq z-J2vH*f%tBYVIJyk+p><%X^W$S7?$Pt-q6A?n8Of8ZzWTxEd=!9XnJKU(&kMesN^f zXHrs+^v}9Dl6RqAc0jl9(_3S9TuQ%`CxiwYG0?&|=jir!_$&%L8SPsSV$=Oz2^m@b zsauth1VFWgUA>0Uz1$s!?X8cJmun311FC*^aK}F5 zVbw;p?2!RXHi@Ei`z~oEwf0-h+Ql3owZoTG?HD%bmUIb(WEvYE2Zpq3a3vGWh3ay| zU3jYaw_L}`$Hw4m&9UqC6k|74F8KFV<7NM<@tPVRFNR4C88)rNa4|WHzH+dh{;gnR z*HH&c4T&{a=N^8rzQvfQ4%X*K9;`E@s0`N5!wptU2J0Z>ap+)uEEtBC7|A0K)>&odQL?%! zfxl;c*pC!=RaSkqsy@MnFUQ+HzG(Q+Xg?fdv}HNu@{w#V>em2q%Xy4uh#@S+E2rE# zpDs1EgBl>^FD@J~B}XkC#TAd7S=zEUaA#swQ4Zbq4H8#pt(swXtvQLW!eBl^nH+yX);@np z+;7jmK_$avHBa@@zW5mw@_dd0CPh-w-V9y$r$>w8uSh$FQH$XCC-ENz^tjKr^xdDa zG%b3fs+1_D)Ji}5Bc}2e@mkY`!3h&H4<=6W&%+<=;x<9j#A3r~{y>Dr*RQjJtN45Y zQOci=ra58D5T6*pBYSj>2GGKdXA z$py18s!J58_c3YLie>9Y18ROwRV_|)lK6HHfAj)QoHUe=OncQ1Dz>#%ZKVCGjcy#` z!uz!|s|=3H()Y0<`Uu=g#;F;@#?o};QnK{mj;UshaTX>yfu`1irqbAoGm43koGyn)UhqKuobMto6|8`h<9NM#*2#=T5q#n@by8AV8?m-g zS)$uGxe*ztY$KsSM!zY76dadl@yL$2B#SyIDOW6vpE&j+dnIm=U@jZkap8T^h_r^( zeE8OIrZZdPN4&MiF^rq7Ws)~5Dh^du97kDlQC?sXVM+=P#C3b?Cs`!*8B`V6K+4e` zAn{C~N<8iXT}+^RIu4!4d56V?Jq{f|;?QLu4LT@Wu#|wCqzgvYVF1qqG7Z3Y90qWb zo(bUAB%g4mf(-;Q`Nx1I~{);Fl=M?gm~Gt@a}Wez-p6b?Xz|RcDK=Y5hdf zEM?O%VpV&L2y>Kp#A3+FV|T+ddU1%2a6x1o<>t#Ur@3Qmkqmt70>aB%5M!RP@#1hshs1-(oXJs6lOz$rneZucoxGXMl@9>>NLr5*?f^q(#$g- zV?ByY<`W6XAcTm2jb#3WRf-O_SI?WPs_^4U*eK79vzvHLf@Dqi^moZC(z|7IRySbWcJa&1S3^IdYDJO0qNkD3&r}7`8|P< zTh8UYXycrfLFhh$ovCr`)CzX02(yNLgtyMdN0aQuLAFrIpZwLlFbzM6PR zRuGwmY*6?wSg&$co12a%wyZ*+afF*P;qz0`6tfZe_gPa%s2t2<;Y2yQ5Ou zEl#v6Ts2bDA&#Tv(x|X}xgg`txFWN5)g&VbhIYsu4qYP|F-J0l{9D0P2WQnSg<5J_ zi~u`bWQ>DZPhQGX!>Atteu8y7%oFE2j1i>O?Y@wlY~3N0;L!eG@e*5fM!nnso>lqR+A>r zyvl@duC=&KGwz^f5q@O8Xv@|h{}jjNpKB#CN_>8)co+r_@n(+{8qqs21XAfG`UK<|3yjdrFp_9 zPreVw`&g?xwuXdr;gc`nQqp4T&97K;hP&&Zp77?1&F>kI4*_T@R9@#^Mg|&_; zpLgY$(e+ml>dt{&M!DOudDcmDCQ#Bpc48#sJ~zW;Z^7$TIH03-&M;J{`}pmS^w%jg zt68B`pc&?Nyy`!NTqi4jjArnQ2=WRUz3A`j5|EbBf*BeGqp7hnHXa13L#CPBN zsrF1HN1NvZ?_;ex;O8 z4*2WIM^TmHf=ZuFGwOd#F(sHuILaachI~E&zT<-0^FLKoOQ&X|9|GQ6($NHXtTC;Wcd; z14eYt=Jz2jE$-IRk5XESBVzj~3lVLsqREytK}5bnMCYD^Rx4>&AJW_M&U@rNK}$(R z=bijM1cp<)!H}H-L%g?F#bFrR4FcY{tK@E^`W8>5nvj^b51nh)Z>`fGqI}+ z4{7`{tHM$e{+Ucjc%))Y3tkZ3XKr?x*-i@|e?UZnnkSsiCrfYIt5=yq(2ORW5}q*D z3vos!KS7Zgify)Nx0ezmu$ItQ5s*$$0@9h)J4GPsA{0d9wV3gJ#=|XX(;}01!omg_ z-qU4V>P|3$j~T}c@Z!~^-KjjM!ZlAA>D(LH(m7tHb)@ja`{RHOIvilL#>ew6=QwSN=>_CG7mou*zogoz*Kl#}cFB`r4uL*)&<=!9FYOZY8FDfQY87iAE6<1+g-l zf!RiZaP~0UR<a0YGRi`>CvAYq9rh$E}+DrfUJxfv;0Zre zRv_c;vxWcUipWA@lNUw88u+oyJ2Afy0A-39p4eaRX zDv_o=u;1^$N}Va^kquzPwb#UktmgZ-X;S9<1yFie(iWC4ct>DAP5uO1t6JabZSM$a zOkl!`rXhf%^xlYRGBq^N*?g(lrK{;uXDKyV2u;f8f-AD0q9;vG9x+l=mLo@0h|~)@ z-NF4Cb@{Hy1dcE${4O;`Z)LBD)RY^Xp~`stRxYlT zb8@tm9g(pcqo+jlM+5sat?S=M`$Y6ray?KzUu$o5##)^rNidi(?~hBv>M`T8axfnrs1;70HO@z+|;dd0* zkU0*^Zz6k@oWJ4hmX9oMpTy96nHV;bdgM4%SG%h+-FLhj@hqONAMJQ-U<@|+y&{SI zaD;R*H7M4yCra`jky(Qu*2+A147l2>3iu0c@776njCVne*nS7 zj#sVt)4Sf(i6vi3o!(GUl$X+3WiZ{D!=Z;?)cRI4eyAzrQJ28ZIPZ|}{|3Ht-u~wB z)l4Fy1in6zpw%Pbt0aN16N8_}<`f=+tYgE~zkwgOq=q8V+n!^kCpe^{C*v)+W>4~f z&B91pjGf<-J}P3{clfN^;(QT)#dsI@jGo9)6gb*UB;`9kff2L~lVC!Xie9t=2*jcn z66rX#zU(vq$Mo{G@v-&Iqu`_ISn;vB*M9>aoJZgeT}9H*+3JiQnb|NgP9KR(dd$h$ z;Cu?)k#Pl1?abK*8Bdo8>RTu!%W`PkBGwY4a<$oCnZmMk!ZcW8W$=ez%<_D{;s;vk zF5L7_#MBz;{{RJTpK4dO8P4ZeNT=-Gqg@FvQ_AU^IcB#zC=%x(kU^zB8gAq(f(E1+ zn;dD;P_j|g)3@BB0((4|o>Tx98!y%RW;?ag*}GKsPq9D$=l#WPK+*f5{k?NykN#>_ zXN{@&7J>q+lY7}35n4ayPO{kj8=XvHkl#dqr((E~`F&`A*L#lC-|LsB_BZRl)?Z8h zxv8XBrEpQ}r^!DM^5zQVD3j$>7Er`WVR*{AC5xxz3s^z{wZUq>V^T9rt`waOcE_Se zHO1l}XYARMSQU=I*gQ;wxw2jcq*;?8wi~x!CX)wRe+84d@nNP(2@g>uh1|<^xSqV` z>n~dXHpw~KU@hwA8fo&ptHp}H_eN zvW|3@9+>$G6*4Zq6A}x6!iFNpe|H7=Z{TC=Ye&Jy9mkB1O{fD$T@b$!d?f7oN?({v z;=6>k^qpk%-Yt4?L#!tJPS^M%Ta|!yEfZ)Lht^;>)f(e~@c5#zUr81KafL2d2TvRlPmWHI5nxWa}vAYU7~=Tc>` zuFDkOw;SsM(sm88i8XsJ zq1y|p7M<@2f2Rt!5Zo$%P%4%P`wJe&4y|EKmQY|jIb(e|sfkpNGYwn*m?YTmcMn0| z8`XiA)=ZB&cWa~D(K35@P56qrZd_?j!*z=!9)bP&{@#Jg-bBR4TB0~e_r@DO*2+#8 zrDwg)F)2)ot`$U6**GtSCoa)qJdsRe0VL-59p2q_UBZDr(FFKV-Oje^EjY*HAsS_4 zySnR8eI9ufC&s;pS zgR+G?tB##>{Ex)3;6Zg@o!U5`Vphu?LP6EGx$sG@o{5_tWRt4RZZrCdp&CAFwb$NO z-E@TZnxwt-l=hku?M-eHdkfX$5j(C(CP0V;HP$3E5BS?4jrqh_6Rg`{vgIaY)Exj7 ztb2w%?CuaK!|H=ZfAje#^1K^H)blOIzit;kJw6AligCfXT!e#2;kN^Fwyo+hJBlMP z*Y$k=C>SlCcQ}kre$eWnLZ{ioZn(rVRC;)y*lMIlRu8@fgj^r72P5Tq_}bEnmgQ;$ zf@?S)hE)bsE+XNPW1G)uu1`0~I`7z~-SsOONV3le46IGg6KRlji7Qqnj_GC$Bvn#y ze}QoSCY;{D$i#X@W=-aTVw@!75V=CANR1qI8C#V>tnlPSNx`47hyJJp@Co!|J$o>L zzOiwF92Y0Zcj!=*gCIUHn9XEQ^rZ7zmLRo8T`51z?sa}we)pi=W5F~|WJamLn}TTr zxt;3`-DpLCRU^@4bnqNnsg&H}4e!%AVGzPG)Qtb;_(Mk>{9zzVGBo!|oHqc+ma59S zE|Wiy9{*7OP&r2YY2)nS_JN8${DI2AEbIZw7U!DP!unDs3l%fgmS;^j_MoQgq}!6j zoSd$OF0)$hm^0Sdj7?71L$^sQSl%-XET>GqZlm9=J;jdx36c+GN5?v(lZSR6(!x1M zAJWfmRnOJrN-!|Nh{YaW<2j>TMc9MeJ|35e9a`fHI1Pw&AxjR&5T!~NJtYh8m5gNd z2$3w1f60R?R&q)DJX!n%o+{ZT`#lRjEI>vhU5qFEE@lo_=;go5c7 zw(d4b?^w;2f-8SV{C>hUjB}`_)Iv79jOo9Z*Cxz#qDMN`%*KIb!d(2HS>k+ywPgje z4j$;f4j$<3PiGl)teN$OD{`CNOljC&y;Ud~Xf~2HqQ%Ab;XQwXA$jm;kOQ?`;oWj< zE}H=j6r=lbNW)j>7sqA(Uns;_Vt+&~3>O0HSEzlSaQ2^B-!`bz_ORE}tsOW?v>0=L zEAOUwt~F)@5i!W=T7<*oaZk!TXO7@AB17#8uU}Ecx3Pe&L)U8$B(ZZs^;ed@(dszGq#+drsyt)Laq}l_#olb7yv3wlyO{)OOA_4 z%+l`uZ=eVNH$T&c-6*D@2pJ)^tkp7p|4gYHFDAKPZZ70>O%+RVM!OLjD>EjX1wv?d zYP{WAX}9VK?N&*<31@3&op~0i;!H-jY|`rklEXBpDFFe-4kzK!Z-#Jjdo*9 z0crDMY15LE0*NLk2dq_niL^$Km}?KEw!~bOPX6r-8VlAvWUlG~W8N&FQeKxmK`{6J zrWsdSB}^B-9>_5ZRT<}4g(_2h_--mO$IUE6zHU{hu344oK~sv)J!X9LBXnRAK&*EX zN4L0M914PUTMOh|Q<#LWG?bUTSsCaunzr3s)^6zNT%#VcPkFRI_HP! zHc6Cxc|IJcW~O3PUyhWi_ehCwMR)iG_-hr~n{M(}$@MQgGr~`i4pPtSM8_i%c9(2a zg}2EWBj4g65-9J0a-~WW=k8XH44dUpx47!1+b0&d9UZrx882k|Tj^!H%#*^yYuHuA z+F<;WiP8DI5E33jy5lA7PPP5Z{ATml&AH!qt>z(zT;W~857`Z^x+F5Hm*UmR-27o* z<=*8JDp4L!3BT?5mD#pAFy~b1V zBI3)MbR8qFOF1%&IM0UHh+Cd6Zh1_}MC=19@5V{2Qd>$b{Z}sTlZ$TuEPTt+P1c4X zyO50T9ygAEWv|DB06d}F3eSKjLw1-4>wOY54Z7)##E|v zH{Bfk+i)CHR$Dfl*v6{Bm-&7lH+?yQ3)K-%ZHKt+#lwhv-PzE_wM)oSji1GPljN2Qhn}hhVT)bjkydxJa*2UlD;#s-q{!iHpl84fW z<)9qXRxN&}ru}-q?s&te39}O>2Ub52tSX{pDzTk6VVXxw&9Ac3dhGNFQOA%tYN0yd zzR8TZsb#}VB5thq;`+RrZ{3u7aiM&S*9mW}htNWo&8(_i-YoTnejMP7eme zs0r^-380rRQcssJ;cL-?zsW_Ua54SW7qmXam70vZjqgH+p2&^tx4&W>e=&U+eMhnH zcm}hWQ?&`{58Xj%VT+&LN$x}@&yl`f2#xU_y5Q#dXlT>=N!8?o4X-04&e&aqCjXqY zXY&oxgU>yweiiDGpGd2wz9fdWZTH1uf#=w-pi>PdGg)uA7RjX08qENa^@h*7{spB- zqZ=t)1BZk)w!0$ZoJi3kWfOu)-1v-DtQ^~A&BRW(WzjY5#v&P!$mDiR_RrwTfaNh# zlWmO{o(!LeCxfhbgRGZMSaeOcF+`|V!iE{V&^2cmL!_(0xr&%sialQowKH(HpoC zR;Ra+&rqG-!ruQlPEf`DHUnDEBdnK$R8-b_a;7Zo@9Sy zs!-O+hjep2&zbqx3s9SgVl;J(=gfTeg9N14Taad}@9-GTnTh!>60Zevw~P86AKktZ zJ8($>BYY{VeD{DX!m*4C@&te5VX_lQn33pPB8tkm`qb_$LHegu70HvmJZ@l<@j3ui zovj!)jb8qBa<2PlaShEj|{& z9665$Q=1d?xN~GBk#L(1XK)AMHXHSD-XLC<&|4*(of zGb$>jY|_jctn;xB_a;N4dptv0q!~VIjotSuTAQnn{z-sd`YPScHW()J!sboUPr~vL zzpOFEbB=dwziGi(5g}wO6qNgfc=_MrmK?>ghd zT$}CLw9Z^)p6c)y-X(IcavlELvV?UQ!)7R$ipkfcEqjUR+w_S=9MUP%U3GJT;TuB>Ean(lI0(0&Xym2pFW700r3#!QlQp|3LIdZ1?1OGW)&@gQfY%XONuR*9-qG zU&f!)qUj?yOSy*4oYK8NLu=g0G6<617X(KNx80yP<1^0YGvr2lb-SrR%vgnU=rhLc zy+N69=}65daKs0NBa$mF?oyg9h2e@@ge&fZoyK_U6Qh4G_0|?WGO<+rOpSh~ESzof z!%vJgUfP;|hfaH{iujxH&J3Y5I1LixG_e%Hz!-8IovVH@xQ{NetZa?n&*lC|$&=n* zFbibWJY)QTn(?v~GmTN#S7?jEH76LmrwQqs1S0~u&`{jhRz;*dQldh07Q7&erIL@0 z$SK{YvpNr651T7z*g4k|xe^!NjlS=p2xGn`a#=lc2KJxjpCS)RIb#}VsAD}u&&qx^pLt6I50vT_w2tIOMj44=Ba#y|5K?Kp=P76 zuzTgbeW#AePt+ZKQ;HM>&hPEVOL8pJ%B*v_xy=5EmSwfC<`5KENv#{p1oagJ4)peo z!ye(g5IDFwE2?^QmM0t%h&evD#<6X-&>#Jlh=|_4{`}3CL+~iyI?He>FK3V0vFh+k zZVaRa@Nl*!qz{P&&FVT^e19$%!$si0==zf^D0K&-N$__x7&nlV*KH3R818q(3xwTs ziN?`_B6%jt%sWXcIl&zY2&_Dx?M*zZdoS=o_1@Ln{gZ0K`dq6B0M8z07KvQ^+TPYL z{l}#|IWzI{yi>@ZnNqd9M<#O9c2i#Wp7cuieG#T9%u+X%Y=qy-!L~}mCwhfLFKcYh z$P~_}OQ`7_zvWsqk8`W;BS6Ah1W55J>%hOe0$@Nr>Iz^}E5KP2rzl6X;WsO%w9!_N zkWP;X1xHzF673vz36RK|S~|^AAe>tAPb8Lvw?m36JSJRuY?kR(`)62nxbCr~X~9^Y zzeIQ)ahk&GRH>6F#Z#X7-jinyJPXFs{kfjeU`}fYh>0gs_|bUbVHhkBPK}OClEB9@ z{X-?TZCbphU$Y8`g!m~$5t;I(fN&jBAl#u-Jo1!^z2}H4IQ-cvPg^ zXG9R2k#ZJXm#i@bP;@zC?IxlYjzml zk=DdyWprJo&>oOJuLEE~A6TIWXjY(pYev z&9;Ib%isxBDVO+^N*2ierI^aZ5nf0lU|hm0JpmP-WW4rmv-Y`(xY8jMl~q#audI?X zrL9$Rn%r9Of^atHby$&}P2;c$&ShiApUNI{He>aWW|}R0ECnBr86(pbJ{}X26nx+i zUQn~~*znP2lXt;|DNc})#aQ!cPkj97T3S^S#UZ#zkvAig12WJr0DP)=@dDnP;p#we zUwU`(;wkPc@uHd7mrcrifWbM7raISfrSNZ@Kq28HX4pw#&UX|dTAa-#CL*?4h}Z}s zT8uN*;F^|QK}0|hvEb#*N;u# zn1GGRR6QKy<|3M{712yw7UJ58wz4(2uWrtFJdwhF#z8`^2>ASBKpN)`Exz*wzTNhh zV(+wPLu0*Adtj!<5yY zEe4A?G+2Vl(Lf87FvV%8syqv&&3Jk*?{96-hC4EQP1wWZ=DN!e9rxMiHDlnq=Gt^y zO}Ilr;VE0Ic8gNxN9-kcSzjC9veIboH|P1BfF2_uP>x^6siiJAVW_ZO>-V z4{atxTU?_|3;A8wm`$RsX-b)sIGUlDt40J7@#bk=aJRYJ<6TXd8BIai>hi zNdC{QHUz1(Vb=dexBBf`T7~eDaK8MdA_}!21llZ*Fr;2Mo-*!H^d?xU*<$u+`v_ye)dwzyJ@h>xR{|G;_ z^0VVla;zV{)OT<5DmOpR6tQKi6pjn)&pbj z=LboExh2*S+}BH6xEs_`=2!0l%tOqyzn?;)9GPiW+r}JOE5nZlsFqf=WxG_ug0rPD zGhxB_dKi>nRimIaCV$Ml!EMdFYF{Y_VD0Lhlv3g+m;&V9Me1Hn*Pqi2+a*%r24m|A zff;Wi|C!Fd=lg;VHDG>Gmn8M=B>YhPXt=o3B!jQrp^j)V5a56RZ?IG*wNv^PJ5j$rZurQd3^= zPhirWXYAi6lWy{Phzb~43OFkvQWM`m!0^%~h8Hx->NBjj2Jx0={G?0XlFU?-3H0@k zFz)++#)5Tcm{V3W#!jZKVBMwW^?AlfuEm$ooVQ7nbdSh7_~Fe1(`*l)lxBO>`fla> zX+E#Fk*~PQ==#JUNvu~D78dg!n z?TU|5)<2~gV`oNhiFJsAtSqQ z58cRq77aZsM(;}5vVqyj<_-Hy2}ggEJ>#z`cJI=F+LEDTVkOWT7K$PRd{x4}b;)O0 zD|?~jAtXDW{(RhwO1kL#uMpZf=Yj19(NE7=z?CO*+Fg8E`AyK_5(d~a7&|?jD*x!( zZ(cl#z4ch-pDU1ivNG852rs_ttS5F?y3}l=#h`8`)_f9Nc9~x z6oIH!2}F-zy;hP?O<9{Z$OYCJ_sBinPP;0`=D9BV6~>~g>LnClYaz$rJ0!W zPZEAp=uz^IDfB4$M}(gCY$~;NF5st_>#n=1^M01pWen|!gOP*yzLoE@`22z2z4<w!*YBqZ{#PwE6X2zUc#BTL& z*sPH%C^1fsxTyb~SyUC!W7En_2u=TW=W^`Urbx8S5CYKIsy1s9`=YQ6h<+RT2DYZc zsfq`P@hjY_or#ZvR=V2=&gCss?dw?{NV#O3F%oM*u~a1{A#Y<#eSfX=ZDk?zy0!V+ zj6J*%tsvgdtBu$tOd&Hzag)rxd@(&EnMLOHV7|yN?a``RjOV45heURhT6KGen7)cl zvqgBVr_8!`wAN@7I`Hf8Azn(su5A{*2F@Sqx3{I^q=1)q2C84{tPhiJKUPctRgz#% zYIaNJ92Jsnx^Rn00N(!kZWcRpH=o0^#Y-b-WtLL-tkNBYW%%EC!mGiWgn5}61>7s* z>7o1=d%~Fo6ru8N{&Q-RY_+>Cy_d_U{8}**=W3;Z$cutGm~HB`ttX$s=Q;A zuMgQNs(MS*lC5gdjiUm0jIynih(rHGMe8UEl2~1N#La>^s0mnwuMuvM?|+NN>}U#G zJP66YMv6^G=-4lYzRE;4(}yOC2E4c=K&76DPcnlQCBlvK$|7%M#W4Eh|- z|HIXGF7oAK!3$Nq;glrU@aN{@0E)nL&aNQI z`3v724!b(TRVhqkV1jAH<;}w|kDq;HPKE_9NXtFugUFNU&p6>IDw2UT^VF7;EI3vu zI|dRlD%Md!YI&^ic5a0mOnYgQujIl|Lx~tnxplb|T5b!po;CQA?;hm-_qgHVfikEz zKR@>N|9$QLRj+&Ogu5+PH%-2Cf0$MfP|FP7P}q#`BurqwW(xwVBrzmkQia8@yW_7) z)VyzhD6;1xB~{YBu=sIH@)P`m{we-R2)D7qyG~2DVc>tDg&CT%`Ns^ERdu3du%oJN z#(E?kNah@@*~K>8O$7U;To5FIP~s{XMW^T;D@euW<%{~=T;+<4&59LHp!z5z{DR5N z;xS;`jMMKBBxJ@e1wkPQJDIs7Sti{qGf?nxq%vNWV8}@^0jT1~T@>GGsn@<*tjI6jkEH=))M9i_O4x$WsIbMUYl<)-VEi_+S+5NRx zjk4k%?!CF@d!Jn*@DzUB{k``1dlx){H>A`b;oGN;&S9fC*iryb~GPEEi_UI4&6)QZzahjEeA zm?S8r=PEFE1v5V$32(bifH*l7h=27z1PIkQcrDeZBUSqIB6^-ok`&9cf z>}yl3W;d!j%t_Rl{eZ$l0(Rrn-&k8h%WX`?klpyfA80a!_R4l{v2op_0`tTiXR}Sv zj5GH0V6uH&0fljyFfQVGaC(7y!{|d@g!6%59Fs(FH9Wsol@+CQ+oWZ(-_Qpn(gXVR zZ6XXEXKa+R;h6=-z5ECpQGCQ^6@|}|6mrK!#;pqO8!*QnTvHrg)47AT7kn=8&OS*z zJo6c@_aC#tFZ_L@+u8BV*_$yn&G(u-8(=*0OR8Jfx*xfGt=80EU+}Ii0PH6)60Q5V z*ztNJ6ZX~B2X@SPeEUbE=xlG|9MZ?{oo5j*cHmN(jm+jF^no2^;;4|@>~W<%|+ z6mCkja!-;Pf)GzhsY(w}u@>Y}jAd8NsF}YPNHs~H7ej$S5mqny*eFK z@{&pi6#EvdQvMf{1epBOxQ!0zBaVY*Rq|LZF&itVF{^7jV5&m_4hJ6#UK~C$&kKCl z6-Cd~W9yWQLpX1%pmBgY;HN+#f_μzX5)fPQSoBwSz&!C~KO`!7@^IE^=)UIx>Ofl_?Zd(OF&z!i~#7J9wZO z2D`GoN*vI@FCK@XNkt)ykBmswqB}}};)5#{73rbAi!MVZFWkem@fluq5|F_(??z6R zog;9;Pre2JLbMVO$$SI~TU%y;TWQ9<;$;{*xr7UgoRq9)*}0E`c~gQ@YZl~H&L&0+ zrdw*?b{RWK%|d{|(_ZE`Xy&cD^`NW)dO?uyg}Y=A7}PEQuxYCB8!X0((qFG z!VEPB`Vj)hL{LtltYpD`IkWJX6IT+dKiE(ZkaD3%R!ezfsnlmqk3@S;s$*GdkzkPg zD3Be@%L$ChvDKe1qQUusabja+=+6|VsG}1eZ{%Fa8&(_1G1bH0#u&6es<{NV@Ro|T zF@}*W8<6UUkZQS9%#8s?#|6^jI(e{*2OQtod4hu# z`RqpyhWuJHj4|JXss=vHGL~&DlCKFFhKuitwfbniK)b&+bZJiGTK}kuH!Jqil>ut` z@)gMu-fe1r1>ebbx9+oVe%G0Ed1W4l%Ea2t)p_1V6A;szyIl}~L`uG968H2-Lc+`e z>dak;VtU031S7G8A>YE}+j1$T6rC%rix zFKUf{QT0r2BJagBDk55MY}zRRdNnbqx8?yr*L zhY%^hm*v2@yi;=$92^N{(eGoS5|?VRW35?y=qFxiw07}{v~%w zm*;x^8Qd2AyhX_kiIT>UA__SU&U-Gb++tUOJEwh%5ul~ckAWF460Nc22*8imY_{i^ z9ZZj!4Fdh>1oZdPQV;0oam#}KBLS^D^huaZ=wCW94*m8x^i90gt)Iq>6D;VZLjpRx zDlbaQsxwb~O8UMh4BK(EdzOOJvBuvUI5P*I$&nhzA(fh!r^=-rd!c%vy74_Z8il;D zD=}T7weJBNq9M;%mqW@lK=RuQpWPKD_$*9E69UlSNQ7dep9H*auoNkT4 z6AAixiCfXh(9grhqx@8Mo@kXtK5R?XJdr{^x1A;cxt@PmWe%@d1^L{-OANrOL`ma| zQxoL#pxm{{$A1Ro^C18#@>zKZ{7T-;f%N0BuM*hp3D^f83VWXy{weZeXq;nM7nKk0*w6i|@>(I^@IZ6C0 z+6kl4n!G1-#38h^XLy2k+WFZX|4FQx`2W?gZul44xsR8+)6S@~4of?~pzW`uotK#{ z-DsyBvz`gNn}!tUNz(nfN!W7_fxRc~{O{0iunXlW^p1QQ;%?#LL*XHCrn3M z){E40x>mi1RSPv%0!K7s?T?jywfpWtk#Vm*`K2%8*)qhiSUYLws>AIlhho5)#}p2C z=#C5hY#9z;g=AFkY#OFJhWjOgp)l}ynLoqPJ}1w4{&xQ`R()IG*3*rLA443sG0O;p z-RsMCwr7b**ep*er@8i#)uwmXR`t6htTaoc*OXXPE0j@W($M8%yY!UgOp^Sx@kKiL zVI`TtoRSWV9r8{w2xmAEBoLD5taNdWwk+3pA14gJ-0iyC;fzd>PG&lrR4>;6SYBlO z!5~K>Ec^$M{i(ch@BIE82%=M4BdtBPksZVbApB^o)%=KljgzRk50oGlvnL@T` zua(&M5Thi^$|EHY$t@7Lh8Om0D|01Mk-(|JW-?mO^pA~!GbkO&FTqSlZUDsf(faz%>qPT&y!)WyFfh+l^IBR>o^ibFT=hzcMJkt z{Q#%7@|AFVS*v5;to(}2U3(o?F4R+uHE87VaedF1<803;k%1*m8(4J)V#7$RyWMK* z6i6ueLS=H56w5f{`Ss~_z`e&nuYx-?!Z^WJH4SsG;+Fgi2-RkSZvQDlwp!wF&w38` zoYT7s3O>{A*l=r!@#Zg*{Y=tt)mhv3zNrsvaogLY$iS_7*H+#^o9d7YrL!H0hL!yt z8tzWQ<;Oz8L+&{y5?)6K|5Fl%SP!M&QXK*o`l=rJkv@H|G3C1;IFi4#Mz$i`pyBV< zDnj%jjSl-ccU^ZIveRUeD;kGt*1~ek;WBsr8R zBrB-}<1}m6lSC^uF_LmZO?e9GVyB3m_F{gz?PWF@Ry>CE+qsUpAoLtNEmQ6%zQqn2 z&K!LT3pW${3~|5-WuC=ltne=s#QbowJc|_G<>D)p@e)myt}!nEjjGO?AJ|D|!u95o zOMPZBdw(jbbO5~0gULaZWs|*SFE(i-;27r5jLgl!%h*u{qmHe)+wNR?$)C47&uVE{ ztu>%K*|_s3xAUylhSk0?0Y|yT;Tl%^PuC-}$&A<*xNx|<+Jbkm@jF$qgl@ha+>qXh z0hURg)(MO@SfE*JqhR>%ap^q}irxj_!?~51n-#`)b-n6^N*@s@v!zp)< z%NY7?eq6#^nNeN1s*}s}RZ$@3WO1rfhVOs_bbiYDkaDa2=0@|BQI*(T^gSo8#$t2tJ{4y&W+KliRgX9oHncX< zJ*0FGB5P@6XiGDq0HgPY!;oWpSdfafO9>YpOpciEWU%)X3!Go>&vQlQ{vGs#VBbC# zAhuek|F3bq0@^nWUsYG6KCQ;_ulj$!?d-#U2M;424 z&fRI1b~U7!j{C{L^^rPa1gWW3_R2DsZ8hMT-sM#CnbiceJgBWAoWE!!8k+m&RG~c>-ETj8v5^^&bI*xl4@A zx!hJQi4@LZ32?3)ea}BDp9e!W&-Cria9h_Wn+}9m$5yu*gY2tak^U{*bCqpzc6}iC zi`5ltX>+`1`iqo0w1_`{thUmXR~~zjjk{>U*l@;O+_*fioNa|j z#>Jd`<&3Q!8_Kw=#<6bR^LN{aRLg|0uSV*YP68ad$+hZ)Pe_srV?`YT7~$rN!HZBx&)+ zrxYz_HxE%1xnC%<97==^9k5zYN$H`KC?*C)jc?NplNwj{tJsT-F#!h=S7iM0B11fJ zv5eRM3iwkLan9%bhhe8t0$zSDUqVO6xyxRRwLwaEXOs#Zod>aI3u@I#_wMj3+RA>$ zHPl2k{`Gt5OP9%Q^XLB{jbII25N#w+{9D_n1AW^KM&&-A?}K?Bx3 z)CO3O@)ZY5=v%;wX$r8OKy|oHpf)Ce!f4Vz{9<5UMrBT%>MLW};m;6;kp2|aSH`KH zK6b>`n^cb(My0NT>ML!nXQV5_AEyZaCnfItEW&?V2>)aI>#YaUleB;1#%x9VuS3{Q z`)2h_(f^GvWv9^p-uX2N`aeuDe_u5RD%Bi-))z+mF%K4U)00=(x+BBhF*cO9(3}b~ z4VEztYL8(W>^0Uk#HWEbZNb6hG#Irka;p&;H4~%?i}|f8mY4=_r=6EN4dBs2lSiBe zXK_T@QK!MnTGM6e&4GF>E<-kY9UJ{cd!6a^{=AA7@8~qOwdFfi?Rc%xnw;sskJZOw z{%rNo*W26m#=w@Yt-+RqB4Emz9Bw5GiZeYaZ?c|V&w4r&9cgZHBHx78&A2iCS9Z7j<;uJ`3oEDzP{cxyFbrs?-1BJ%g`jj zw$^y6{21-XyJBk!J@x#0Gjb=I4ld*5D zK7A7zo9Z|z=)o^S84pTCl4DE#?%<56Ho)oIr}IgmZO#LOj*fYK%?5hA!tch`bOw1s znW=ratIFO!+JBz3-A2PiMmg5k70|Ygrs+)87q=V!_k-VS`a)jf#Mt3&T4~4aoE$5Y zjZvE_qej7+sYXY!>Y?sLIQbWew<7n;2s+FDE(7EZuFf;o4>C*04I_91f>RKnlTK}T-vG`wVf!b ztgqA4T#om(hTmGnv-Ih3q#B%6PFg42E?_E5CL29~nie7E+`MnvaJ>qgIE;@QrL=n5TsjnY~e^!u=q>~hDE|uw~x^eCN z5^6tQ8(ui9D%}RX6*|R&w9dGMVc-Z#f#b`0YO|1QUR1eE;$rMM>_W<6 z$(;{^DJ9%GwrCA^31YQ^G&V=H;j3wFE>}Ow(1!2f_f5eA>Aq{Z;m*;9zr>AieX32} z#kCWnCrVj2Ur|ndy0M0UEer)2?Pb*y= z&6gS}7tP=eHr$Df5Cj&3z|=G3-QgAwesAGz?$#aXSR0MLB{JNpe$c71pWcWWeejNUU1v0hjF4!_nqX1%ywvZ>K?08-)Pyfnm!~YuW{4+fjd>6K8`oVPpPm z@P7}6Y=EqmlGzk^UyD>SwOo$RwR=X$kI?rsI!{+W&UlV5a?X6{3V$jh&OI8}M7%3y=pS@9L%VjsN36c>sdH1k}=%rXs;VCXwZgdo_(Pj`$6bM0NC!bf2!L* zm3fzePf#l+x`P?>)ptH&G~}#uEp3u7wBt? znk_~ryFoCz7vzp{5*=50abz2csQDd?X7ZXoU(L;RvV9BI9dFkSqL{03BhB4Kb5!qY zd>IPK(d|5LoA(Ym3Oii(s5|&!2De;gpX&Ul*VT?sw8aEHQx8j1%?=UnFOSGznz2S& zsSH~1g=xv@BdH1Fd!6yK=29(~#qQ}$pso6JMs>HWQ-2iXi#zY*Lfy>!0%p^84(W&0?)MT$ndWL#v2 z*%TGfzl6(}ySpL}ij7=sDmcL6Wul!q)6h!yuz3vTw?P9livst#$w`t%)*c!Jg2Xn z&+H7+eazQFvvZ=d3+XGVQl9%29_2qR>CGiMYgbi(W1 zVX$VA&ATR|WcvO2d~*tI;MOXn9veFVqREH1%$F_{{*LDcuEK;W;Xb>VtFAYV%NS5` z*d$dgeUxYlIgL*Zwz;WO2?cEWJiNs>LOqlktBirXm3W~_wPL=dw)irIGXF=&r3{A_ z4k6NppHnEnrTb0>ko=$J+7SSDbJ<6mk{=yStQS|u`}-T$VV*E;%(^7x57yYygwOU? z5l+TG)J!HKMCRY$F?-1Tds2`D9%r&M8{oG%sG(0}HSelt3{8EaWUn(z^B0NA;LPwB z@HgGxJE2<)Pv{m|rf$*CDwwMZW>T<+p3#%8EawX3HygtCYL)maMa{T|o%*<%@evFeHRJ5Kno%kn zkvH|S+n!fiM&pfHO365IYPyYGNlVEPuAWpfPC~zE*1!`=MwYkr{S5SrEYUCIELa40 z;JG&DTvY%xCN@;W}AmF+*>)zHs3 z*y~E`=O4)5N$LLn@|EGwmoD={R_D)|bzY~VO>0~tzaRpw@h?K}Pds|UZ=wNKtF z$ddb(MszcE#Wf;|qT(DRsVbt7(um#{jYx##6piRaqXQRjDFM!=8WZ5zs?t585vdlH zN>u7U{n#Kfm7*M!q8v*pVz4^@Oruh*Qi_z8DxrK%iy24D+6{aB@xbx$>f^isKVUMXRbO>5HjCYQ#D|{EO zFW8WhmacFCM5lCxQT*_PzMs=srhXivEA;2KsVj8Eb%hqCD_mmg3hi-Sp_~@dz(?ju zBNaYSng-KqTw9PyqO^q^r7f%_Y%}=1&pHz7f`U(8|Hs*;up_%$jCC_4zEpbHZ0sbE zj;m%xNXCn}fiVS^${oX%&=;s@aRBjow53`}hfLcJ2{QKs&B6`UZ^YYlDuK&r>p7ODOf9Q$Og zY4{)RdL2exKN(*Z)zFPORAKLAyO`1<-3t>kLQDve?x(7IMi!}w*e<20yaciAl9%|L zD+2y>uyf9Y5gwW(=3air=E?^BA3 z)l~d3tETAQo4MChaiC10JU1GkW~DgX$Q6pilbL3umr@+29Y%2&0Uh*E9CTwAZ;9fd zUQk+-rEVz2;R{H`R2=4KFhY>q-eD*QrMp1JARx)FKbS7JTe;Ry9SVx9OVJ&M%sZOy zFpLWI@M6<7hS~T)9SkjEs_%qmlqQaBmH3v<=g7?_`g_EgC3<{kF3AJZ*%=Iab z1Ba8jNHTmlnTrHChp|21z}>^jT#xrwfoX7A>np!WJF2_$an$7?T*I=fS9cBulSYqi+#w^mn-9mgQN@(U&lq7$?L3(hsu~| zz-^Nlskul|YQpP-k zD`ZSps&V?5Wz0U7ar&!d%oAZ#u+_}_hIErLr+?N>#(XM2MaEq9qoc`~Yt^hy%9v*p zntMbU)3PDQlUs^s3)?tqhXxzvRuu;jnLmF>yVo^jTg6)L;jb|^9oq7r-B6yS$;^Qh z&|0zCH0bx1XZ{Rn-?{v!l<-!Uy~JmoSGKN=W~`yo+t&KRW@Slth6=nxIxvfSogqDa zjT?hIUe9~5-O~F0jNlFpNbYyGkWX7Z3omZn!EZX4p)1gw6{~rb3#VgKU5>Xpw}4AN z;;fY17mMe8(3-}AtKG|`w^+)vIqoNXz&oVX>uB{Cc|)h{9g9y=4mK+9=o5VxsNIU_ zxn9TCd7Py3lJP8Z8gwu}hmu;;n&?T(>sL`v(3tNXd};b}+eKXTx)gJ=*!dG1Wr+>4 z#Qs>SEemSQGIf82{awz;5Bn&J9D={*X77;Q5Y2kJRFx$Zc!{@qbggV_@Fg27)iMxb zD3XU~gO#cb{^;1%H?m34x{HzF8nl2C@*5abRGTHWu}1*Dc{Vl6E2qBRLNm1){Fy2@ z3;3+&vkn|-Y_Diq)8}40LlRr-&D|#tg+?H7e3rbpMY(b}a+AG>PK}#9+eY;T+}^4+ zZTALa1+)H#8*{UOqc(#-s*&2PRmCz4oLKgKX;@mXmDYuPUy|yan?4ZwmuXOK#}SGx zpO?Jc%iU_W#{JeETD*1DtW1~Ot<-tz3RyopqPR!k}fvOrjj`qvZz!Tg3N_Zb|Z$!{O#~Ftu+7143ASrqrZHm`|}esV?Eu9 z?{p<*2929TrwXUelNA-Bf>)Pq;`1u=WHa;R9Knp!vATYMnkRHcI*>9~vShA6`mG0u z9nWu#9E_QBWwCRYIagMrgSQs^I5}5f9u+Vr=86;dv)EeSNqqXm*23hfb9EsI8Jk>P z8ltu8+#J=SvuhhODak{Xmpt%=whH{2&`D-m=ys&8yCd7)-==Kq~P>e0@0IUnIc* z&-{aASL`pR$2O{%WrFNSu~--r`NKO(Ua!LZ6(wo-I%9W4d1>~O-{+hSbL7pPa7dB` z5gzerwz$SxR;uD;CY`CqDmWlFp(U;X5Z$nVU^xFTY$fhqZ4ND}?K{)@-Qo+E})XAX?T(42rzmPVfx zqc2v%f-0G+Y|fb;AZl~YdA0C();S|8Cg85E;-N|?h+5MaUj8NXwR*_s7vAg+?kmvl zT23eRvQ4u!cX+ki-a=%Ow)m%znYQAz-{MW0HoM=HD{umG%VCQhpZ@mR>o~_|4G$Oc zFkQQow1&35t=YbFIqJffdv``}&KX<831+Q(Td|jU!`uiOECl3(Y)#+Wn&HbgZ)K=E z8RS%Vw{~V~joV<|=7n97L1gqMI|#3EY}s1>E_ZN8b`7Y_R&A4yHPXMgC%h?YuOSdK zlK)ERU~F8tVL{ccX@sG-#&$IDV-cU9@OhNaU-&%FX9J&i`5fevGbhb9kk1G{9zNIb znZxHkKFjz>Q##oxor`dAk)KV%4y@mtOoYgj#xw5yAI{zcKFaD`{GTK7tGTAOiE+um1m1xO0%D7G0UM>bBh0W=mc&Vv;dK;mtF_zJR@-Y^ZMBPlYZfJ8 zlYkpY)wr}h=~64ZM?_xDF9@B5y8ea`bd=UHatNCGE!K&+$VGEtJ( znW3{2bZimM+`LRF{@7eN<5cD31_xAR$_l2dk+SS`VT2u9m_4AhV7fF%lDnmCu^H}6 zrzn%O9%|NYjLk)##q^P)iIJ00qR2ECr*s`1A@P?4tjlp`K*rC_uhTuBl0zEQ{O0P3 zIcQy8XE5Hs#8=%176N=4I+;0}3O*yaNFmp^GZcpbNj=aEJ zpP2Xv{DS4_vu=KaUWs^^rVw~9fe%Yys|0ov z(n?6Tg!D*AZ{#5(2c)#ZMZvh+OZMDeYna_DX=G%@ za3$Qj++aN9B~u}Y@31^;*kBXaOe+ETixzFvzm06Xp(FIhlYJY^>+0Woc4}K@`{})B zM-#aN_MhH+gt@c(FTM97{{DRzO@KSg9%e#v`u82Mp`&BKdia>!kgC<0VYoLW!6y5x7#9 z`JGK*tprv`ppTFWLVOZJBMJ*5edP(0 zPy{9>^#rkZ=U1d=*K!BRAn&kaYZTryds8KUe^Cy!Zo~(vwGNk(2f}0e^1NGIwLi@X zdt&uH$wKjn%xzVm4VUehXV~Xl@C?35u=miDDmjDfVmE4`u|{~K54%xWnLyj9tSsb^-hk~|XJ%n2kISxrQ(U5jIK^w(@#`W}Cl{UYeNvGY?H3pRw-GZ=-~6vq71#c~IBja*c36*NJMNMigz&q+o$ zZvgF)#TlF*7D~P)dSbAu^kSX!MrEIJ(<_XMp^N5GxAM+XFIyZ!17)G}vOijo@<+WX zI(tgUxx^c4xUo2ZFR+=?sJPpiRuisrug#Z-cdgg&?4e7M*O=51@hPxfMmE}X8mFNf z?YxM$axcX!L_N)Jz&Ui@Hao9gTY0gZY3}Nrwd0*>UZly^9UrJUX?01U<}&v>%O9;u zMe@LiLAn9jsrF#BZDh^MOP};R*u+SMhihYax(@exJFgCjK!4PS65)8kp%|%J=`qNJ zNcw)i31JIloFY*&ILRBUqs)+*(q?2yygBSo_ju%qNpb<@0B0<7HU2AemhXHVXBiW0K4XHAGIzUsln3q-vKuvAgy9(h0J*tM;qknz(djLMPN-V8t77(G784Js)VlKIlxTHR7_wPQuhqx4;qJeYm;U==1#O zxKzoG-Eu(0rMDs;;$FbB=@}V~fp9)-jHR=!_Uo$X!S4i>>mlr8<>_@GfaW<`LQ-UXrFqf~AA4OrWYYu#uVq`A9VF{Tj2Oq~ zU>(UGrcSs*h*6wZr5BE-`OG?wdp@ub*Oqfs>Jo>fJa2gNT#20wi8_sR$?fd8xsGQCp$zzKKLkU=X20igzN<^tc=KGGfUm71^_6R> z5x7vS4skcB##5Ji1orSo30xOFd)~itU8(SLHCP%UHDq}7f>CMQR!3w_7~ zJ`c$oJ(|aeZBt8bhULVl36MFKKcE*33tG#u%Se0FJ@?AC@5G3Y^PGWg0C&Tt%&rrS zFKAev2Ic9qkYlh{bfQ1h+?3et&2-$V9=p-aAj#B;WJ`RinCM)=;p3SPPhXe-1o3PtCBK8Fk$ag#sr*jr(lF?dSF(!0! zWh4K>SlWm_GrRvh)% z*Z1o;^$`g$sX2mG-O{?sLorF%PR1r^fm%6ErV^W=(S}mj7dCSmzYdjUoZ0OsGi^kr z<<3^dXr#JnezqN_Nj06xlW9k7cu@4RQdhE9eKbKch~ROt?gXvbp>8Z=#iIUkalb-G zmS1i3dF4#c==7q{fhp!}jisu%zs4tjg+v%~?y?dj&0gKA@ZbBUl-5S@BD`H4B1Nd7 z)gQO<$$3t-pC*f{R|KpNjn`e@tu`?5 z&c2Xn+!$+ylJIx=GC3rCnIWkl#YV}qfZ+<3_t}SD8^cQI*MI3(mDM-~FytxZpB?e=e3~qr~QYfmlgsm zF!&MnIOmlmJzIpmN8=U(#;oQ7;?ha{TNuH0;rXG4bzU^p!ZWP(qlpdH912)dKCff& z&@H~@4O$g)@&(sKW9CJ*<5CER$?HJ-JH`9XV!OQ8&dDcsVJPo#s9YuP)ES5gz`UsG zUE07{oXEDW`EYrG-)XCJjvV?BOblBV&ga2Hy@B$hN#wjgC%(>_euQF!HP5cNPNwF; zdqk1WR1;*@y40KOFMxP+lsbeGxXNjz{$!J+Uc_dQu1$#6Vn#g2_9tGsex>+de<|0`j zGFg%FcJwHwbt#gmzgpUK^Stb0s{AkZ^l7rYb9}OtLH2zi=Q)H>S>OUgr)jWh_CG1W z8Vs=0=c#%22?hkq%F>2BopUw`~TQV!xoxyq1a1y*uHl6{ND8p$*+5y0;M4f+rcF0`R zBCVcCYjaopLv;a%HwHK>wT|uQOsD~up%VqHO3j>d#)*tZw9<9LGcb-IGIGV6XUp7d zC}NPsQ-#O%I-sl)eYxhcT4Ln>r z;qvOLy4<(@-Jc$6_p+HI1?4Ne&ep_9)Z(0oN@}2dMR8wy9t!=$`WrvRLgqV6+O+CG zwQV)O&MOoqPW_7QJ;^}zbZ@wQhBL3a*4d^0i+RDPSS3}?bZ&iDs>H?hjG91ot<@ry zyYcQ_EyQ$%pvtw_Lcz>8-4};tzEnvio_1yH3N|ENdWj;Vzth`!{l_x&pwV{CKI@i$ z@gZbNEn6U5tILvG2`oa_Y+qKEw{csscC-sjcG6wI+XQFUDd|z|=_M zLk6OG@5){^a!zK(60>MnUpvy!okYsmM7(uQZ$h}1j2CPmQ?yY%O;2I2y5|8@TDC@} zh>>asgD<3}eQh9wTv5=8pf$Z)7-FRyes+0VV|4+x13IKV^q{7F>H9!ymyf+ZEi-EM zl*mY~e~JyR4frEpFsyHSsW&`C(t?3H`@(t70x=fda)T_8W+k&l^QydVF3UP(-Xpnt zlH~{WTb_T<`~JB5TU;vY1uJya6ZBhzE@WxLJHy`k)euk1Y_YpOKs7bP56o;qz{D}T z@5S>n!>4Wnm6qLiyqY~mpS?TOAK@1sOvEb1CJz!ggcMdp5TUR_4X{8fokAAZ2)%(^b=9O~(ddB9wQereoQe(OGg>eI_Mz%3+1)NSqQs z#Wmyl zZg?;G>I`z=iHS9lzITPQCA@<4jcbLC%S9i%Ts#V3uUZt7IPU;ftTa(r%ZYaCzVwL(kQTr$wY`GE{kHIAbtbK% zBVSXiX3Ah#{#f+S~h(D8(UIHhbN)GM&M^1@JA*aK6k$VFCPtd*Vr1;}& zo<;eL$-iD*pz9b<4qg7mHJw^T*gEg9-LPBL{LM@T%`a7_=%g~*>Q6JICxXHyPZ?NK ztMhWIWT~kMi><4Fo+=5mbwFBvNe%%ua{2*1*D`@Ds#+l@jm^$}zTj{$D2&&8teZIW zkptOsF@H9nMgyydpdcNn#!aI@5#DBE?uf_K+(=ly+~I5G%N<^1$EOae+$+LAOu>9) zNw$TD^S28q5^Y65NWvp(QFU>+MgrvJ^mOV8|6A%oi$vHZUo#stwx~CT;62Ca&B1l7 z0CbCeZcZE4$IzG3>!YQW^@H|YdcQcI3f^;)x-rYu_`r&_gGbO=c4G^+%qGHXbqLV%kV66hhJ3plL=WK ztO>riFzHnj|0-}&3G-0y9t03R7ho^LrDH>K)8l<@&qrnk^csN-#U0(w{XnN72hg9}XT^0L+JgDY;8 zV4r#zWTcKMicRdYkEHC-kl5hBqc3Kd)<{Jo|%&Fq?c zBXjzso;v55%`Tse5-6O1OD*-%;Q&q|XFQd_el{0jh?S^yN2Z)czS z`yGIc*JX&SFE0y6isZ2}G6=;j<)-q*U#k4_R7pv?iU(y{kLmeAHm{6{ zpcns-mEX%MWhu!zNR`~T3BV>?16KFcX8=dB>4P*};Kl3IHO8iolt!)&4_Cc)OqKIV zr>mJdF@-bIAFmhv`yaSFrxy_9idnJqia7|ArKyssQf`;JhCI}jDyflg_#bhB90EJ1 zu*QTX=kxGvdPX2j7GD#sGGxJSe?`lJ@%n{-1LQNJ?-qw*a%+n$Rej}w5G$iJRNh^0 zO?m!`kaNOB*%0+L&o3Lb$dB)+-un2@UA-VlTX70m^L&I&NnR*Gm+$x2w{{j>-||KkkaGM~ytyO&7~Ler)364|9>78v0$R zS>&paocjHO?SU)U1YJEn4q>-Z2@*_HN3^zC;n-OiR$>(u*1}dKal)gx3KQ}RkrqlRw#&O_#RIGf zEyAg>F75|a5-Z~PbEKj-%#zn}1H<@Yy!zvK5~elPOd z#qSw@_wajy-y{5f!*3(M0sUuKK8(#dvM4s^v-NYJH)C`Do&1QuAI0VzCGc|zIT)Ms zNjmc5*ql!#s4o+DC>?Q_y@9XRw13trJhD#04J+bp4a%kd!op$y2op@(pw|~ehLL(c z%jjJgXPDx+qMQAGRE}t_C+qi#3mdgYm{$lVl&By1vnWHYV<^a(g5>=Z0S`D0^;`+I za(;By?GtWhXPuhD>Ogj+hab9Gt=zBF?{oI8gyUG>y*0;`LvDphS z(x&^6^)oB|@NtrglUa2Jr=9MF926|Ij9lggnn*Ccs63#hMUIG5d);H6Ox=pl8-}q~`0pvptK@vq*QW zZl6E(vS1v2;YzqeC(+B5UfZebUSEo3b<@Qk{M?XwZb0wQ>Pz-bS%2}jQr0g!;!_a` z<&Gc1-e+8N-Uu&J6ZQgNv$Wm-c@hzoAdOh7)41J!sBNqHUB;R{8qvJ&J|!8tN8*QT&tGxLP4K)Q6^k72U<}V*7+5M)lk^hKurqz_w&f{ zcJ%WUc>n39+(@OG#9JU%k(|t(%_I&2Ni|jtC)DtPlS7n8e+bQ@{=8mKps)#Rg}q=4 z!8JQ0Z&HD6BsP&+JydmmPQ{sOC zADg3`MyhtTc>eHWt}EhID_@j&1S36j_ki11PxazN*O^-Etk=nknkCs_6=b?8n}s*C z*lCie2XZ5$qFuQ${jqgwX-+a9QNV-NIv{M?W?%oI(+`hfhRG;hb*L?$Lc(KV=bh;u z7P-WL{_tG9!OpTxWaO>j&u3PBk9j8?KV}cQ-!~u4*HHsaen%9dVh-AbkH|VivLJ| zPRtf@Vmf4mNl>z({JF|mny=6Dac&Yu9C|}5qdhq+Bi8y& z#S-$UyDISvSsT|Jc8Mwey58u$vPwU5IulRIP$N7T-E0ak4>*SaoIU=w&k=ll^f`6^ z2STQVM+DYKifh-e8Md`ZRIEBAN7jLZ_rrQI#RVy(ZP{qy^ z?1KJh6`#gkD4V_tITjyjDumObp#T>cKHcr|Go(VRc@~qvg^KlPoi9AtdbIu|?L0Ko zhx*>=uXG;-hA#;^Hg8^hCVaix zv#A$|#H{X6XOogCC`$f8ZK#&PhSGGYb=g<05tGB!Xi}-GvVnpS=v$+V;DfBS=)0xX zqwRDWLu>)rjy=67oBP||^m5Ll;{+?>`5v*C(*BXPqzm&H*SGT(=4Hu#`NH}c0{x$1~y}`WhK-KV&71+*QBcoVKTe5IkA%Di< z4C z*>TU4B+?0TO;T}<2p2Hhwscu{NiwE5mLthj<*^0X=~PPw)<`Kd;u2GS;#G2(HIrU0 zuu=DmZ`PAkJ5i16iuFW)m+E&Y7-M+e5l6M=NP#MpX=Lf8{Y{uM@Z%~?$R0QlN`G9zO-;ZL|OqZrn-sqLfEGwwlhx9&e$}h^t8YF@8-Z=M6*Q| zuynUhGd2M@&>PZ8>e-n`)7c|_udGSU zQ!f^qn&_+7>PyU8=M^!n`BZC)&C+-x*wITEZc+cZRKQ!P>^rnHZITh2>0OZ-m@81> zUfCpTCyUYT+qNrTE{mgM|~&a$r@Fpbd@X9oT3)BROQVVBGSt?(+D^1T zAokZ?$P?SeDJVIGV8&{Vq#eW-UM6YZ zR@d;L({LW-UjLm-bc2&;V8IO~f6wu|kfM6^J%(qPZuNBstVu6DcAT`B^JJ1}{+Ida z?*TQEagimYS>cPt>W{36S|iUYa7?c!Yhe1&W;rVMcW`*kUmZA zmZjo3jikwcX26wM=g0{vthKrt&;I)xJP>0&>5z1zC|Bw@n<2%m>c0;XMPKkG8~0pB z=?2&I$>xd|&6etF_Ajj^@`cCcecy_23P!#855L#{PLZp}L+{vaM}axp?Y6|ZcHVZV zQ#B5TpY_<)rI5h_?@`>+yXYc3^ECV>C#zFOJ+DNMj9fE9^1K5`J|@qMY@X9h9vG`n zZjxqfU;1sDjwkGD$_Pm{Dq#xe_+<>W#a zhapG^4x&!eD+5_Gt}lIurk1*DDXm06*5EbljV{&46p4P?u{?7_E1E^-FRkojcFOY3 z%8i`M)uO&Q{FYN)zN#3%E#FYBtEDaHqbtx!d1v0vrEzD(GV&8vwC6LCpU98SEcHd7 z1HjEJ7VzRg9ttRmf!JgLCGbw;C5dS?8W_Vm2f~EXi(M87oy%8~h~+BwSpeQf>4=NH zEVnw?8V64>5HzFQ+z&dn;)mZ5zR-gK1jYJr@-Qn$z0Ka=Sb4x7-Ibz7U(MKy-~+8$ z8*2E35uVQb3}+<7>fZ3>h>AtSmr~Iqrf$z<9b0%i;~V=QU<}l7lwx0_SWM_I=dT_JRm}pGQmw$}reCvV z*Z>Nvp~BMlV}8M%2C^rxi>4`ibO)~JVrE_uavqRmJnTY`t5@D-E7GVE)yu|D-)j7l z(@0jy#loV1s!xUA&`=Uwklk31Pqlr3wa&VpDU820eV;HdVr%xnCE$S%?mw}d_DQxe zsrqi=S=4m_&^6DZ3!cSYPzw4WpPzPn$=x;ll7hswN93H%+|e4kec*lhLSaleKQ0sa zEy8MXdvm>$fMYiJL0Z2Kc%@zGc@Jqx|{j%CG2u%Q=*jksD zP10@fxztqFGb_>X$-aPJA5n2nj!S@tZaj*lFAGL;0$pvvZF${mg4ulu-4%bR=@ncX zy`sVuy`qYrk0HT`OjtXHt{6LdNjm8zZ0YK{3aj}}y#jZr2C9=4)FR&vbx>C1 zb9UI1>v~m9I@2UF;ntoMuEZreALF+}osf+OJM|=)W{lA7V55< zvS7-rt#D?RZWbR+{=BY3iM%}n{4cfVmv;qnrWVF#mhw0O#@}YZ@2W%OkYJrF+Lr&- z86BMumuSyKTTkqqT0Dd~icKx_#~Z~;FU6&1j!Zr%JH^Mn={8_xuUksi4 zm7(8|(Efk@{3h-<>W8p&0JvJ&n+qCPOzYrs$mPvP8{r=b(!l#*#N&O*XO~@!7CW%}Lk;%g&xgpJMI%PvHye3LSw5^}h z^iFd4>B55&=E=q{@SB$Y|K&He$lf)Tr1?$D)1L$QO%3UwG{0$H`f~ukiLUF0ruj{$ zr$77oO}=zUn%~5gj-)sIrfjc-R{NjNu-ba(GH<<89ds_NsxSYv&+lG@M_xp(@ql2p zyhca-&J8x2XkBQcb=Oo{QCUXL=XM^#g`c=X_$#{U_oU*(D<9Ec@)2GA3EEKlwv^Yx zobYI(3*~+p=>1|a?-{fVT34=F8*WM0PeAkPp$Omr6EG>5_W}nMX1UU5-Qk~6 z=+8-=+L{m{es|puFiJ0_bHz%nR*daYzx{4R+)v_ghb#7lczCp?D2@!_wNPFQQTR=@1whlg_!Bu@lF+Yw z(uXG|N8`(jp7>+aY&@IqD10QRKJOWn`%<0Gh?=9;P1n*=-Cbczape7v$6x<;9ALje zuHO#rw?#(Zg^`7g8{kN`Ht!8DcpyJ=Ft|CxOATUDN&joIonkK8kZu9gZMP5Y4Z>TU z@O)U=&g{eFo73C}%f0QLV&1EHKP~-!67Qo;a6xllWDD}4Ib477mn$#+ey0C&*TwrM z`tMQw_lW*`7(Q=?ZnPVqwa%XRCy0l<19tSR*Ikie>UT6B#K$WtUYE_3ldbUee&iey z<%GM1@uJW8W8|!#mc!PLk9AX?^MUPD3L-WpdZRZ-2o3JZ9m$BCM~$GJSPQ|sCquL= zg5##KFaME7I5RgVD2IbA{8=LYHn4l0r3}B%K!2EMlpbCuUf7 z2(6vH1rh=MCvY90>u#MnG6JBkeZi`y$sUZI^;&X}nxE83iteV4RLMtoacRf>w&v)q zhTMTJ({7Hw$cqF=ijRHfpRNn zjBtRP;Tf{fr4qv@Xh2KFa~-9!*_cfPizhCmMKaWj*Uy8tg4k@T)}UctbXBQ4GRyJ% zzTrbRQH0F>T-;X((phCU%yzRQ(LP1cZcdemG&{jbsl6MMV^ukvuZ?}KVo?$GL(af| z+7?FSBqxQYtx%>}z8u`V@5us)dmi5>3kmvt0M9V)`Hc?ENvtB#K)zet;}DbOnMoO0 zo|))@e3@sKg~J0C7Rbed z5Y2|6=wFH4Gnm$$UY5eW&ros0EHv(cWNjO6E!#)hdgqz-hye*YZ|tZvsO_&DYKID!CHkPA2m z;e;blMS=BKOy{>ry{g5a>tBZth|Db@8ny7Yr=^GKZ#7*~=&zdIwaDbxzaC(hUP36( z{$%qBNET3l8pWH_%iZH@Pt7v-YL6vA=nD=WxqxsgkO=(^i26N*K?s~+k| zrP9aLZZ%({yD&l=nq*oK87H+zN(a=uVu;jAsw+sPe5P7`-O`K*pGysu5a(eDQMtSa zHQO!}yH|(&*dte4k;TZF)m5Kt-L@Ct5=6Z2{&wz}8fM`jYAa$yIqvWnbw_`Y-EeV^ zTQw4ZJ@_Q}GmffCF54y{A&1gaYft(#}jZmdSE;8x~oy~^~l%-7@0A4@HBEUUYof-h44xO2hNIEjdk zmf46eDfU+{@3n4EG7$cn*(138KusBxViAB9{tGje?{qB%6oh*adB|<-Ia~LnHD~IZ{<^-n> z&v13S-DtJeb%ITAbLu)$h}b+cGTFSL?s_B&zFY6?ULPo%zoBkACpd4jVJxf@$`}-c z*A-jqHs$bI8;noum9Q!TUzV2&kr|vM2Zc{1P&B9ai~-`q(XAt6^^Y?WHys6_vwZ?p zS8QTV=%kZ35meyBvrhsBE?ws=^9f5q+@3!SXkfn0d;$|2h#01RCZTkxVX6QDW?5NNAmK3e2E{C?WYX zbtUEQ{4*CWyVaXwzB2A9e;)W8zhF8LL0rB~SKs-k4$sr!CEs*d%qHqz>c1ZYTC0gt zhLrkcm=%3@NmDfg(g=7$-8baCi8Q*^d;+Uj-8MtIWc(Z3(ak+H$Q8a!gdo>%qzTAV zULz^0@0OUb-E>a0+Kk}rA zp;|2>ZJEqZ=Zvl?6jo}mUUt!6H3SEBGRk%pQVeSQ&6+WT+CrV|C{78()KP)QSy1Mr zsNsIWiiRlJj$?u)e*MRFH4&F}>jXjqH7gEVw;#uwx{f_)H(+9AWXx_j594?v?})B0 z?sbJHsPn%Z1r#anRcA^BP((C+S#&ehQx*r!=(2&% z_}~?ae|7{&ntw$jDpPf*_f?;{cBRUf{z4Tybrqq8m4(4*C+v%(s+Ucf4z?TYLg(uR zE$^)j-~~MtFKbkLb?m-iL%yB2PdzAK!2Np4m=Sm1D~EX=^7Df=EGtYQ)!6B7d2d}8 zx&V*nq&flY>jg6dVr2}K_&4-hz|kJ^)D9N7`X_&&ABFdS<8)fRt$IClnG3~>Gzzs7 zgF8Ub=nvhl)uTcUGvMmXh3!!|IMm=Ss0Xy>VN_K1pSNGe%OJ)Ga-rSghh@YTgj9Dv zO6CU}mf)=9bR`P`S&(m|PjOM@f$9aNVN1Qv!WMpA147k#`|S94sb$Kayg1ZPh9ak|ILqs=m=1DLj-XqhU4w zjR0pz%eIvT!gsRsz*~Epx2^iFzi&`+cn;kEN95dQ=hdaU5p_p=o%C2I=u-PWH0-+u zDM9QNsIBRcIfR5_=OFMNjDN>#_@l8wiCThn{=PPE_*6NY>nExIOy?P!Eu}FXGK3IG zg8iiACV%rd-1nL+3(^VRNjK#=Ri6&oM@W6cw2?vQ0@-NlH-F+9BD!{@*J|k?%C0`g zYJN;!oS})!m>z%i+EPaAeT_nQVHt`EG^0g_TDD2;kt+28I2i-5)^zd>^R*<{aOp_t zp6Qsctq&O8grJmAU({gK%hn-VS34 z0lMmbw#7z70ln%mc>^ArjrCQRA+-ZNLpQy(orFqOhz~hB zlp7v<$az4{RsmYG)xoJUQjIhUQpG?t+gUN&j-?L@XS%JSo$V~B<=S7L7xP2T3b^oC zPEmiA?6HR>yLv#s-z{aUU+7{t>SCR_9585dt3PcLth`6cs|r=Gn;$;0vst&1MSyJ& zon?I$A2wi8nrj4dG`5Pl8Flps(pIF00lA`$-$Rn*jmYU}*0GvI0nvLGx(OAkM%GEx zjDahBk{tZcsf4!8VvbR0B45C%Ep=wQ9dEKI6raWCv{L6gZf9t!bRmv^MLh&uc#lcQBj!v;3Bd0f=qbbZ&qHDp<%baOhx?sgq# ziCR8I`fA95t9TE^^vuZ3jSZMSA?OUUJKZ@P69Ak zO;s9mC}^tEZ5fmFso|6x-7H|%wRVVd^Oe#-m!&0StNO?{`%9RBBJToB7l=J8Qa{Qa~Xg36aN;>W51p+Gxl^oT)&WU%bw98u z&5T{=hOWIzruPXw9N=6R%U6#td=5oKs_UJb1sZ@*3f6rVJ;T`0VWFz0%fxRYAmCu| zPEbxzT6Gf;HX&Ff`vm14BxIarRfY^-AsKF#vB5?QWM5M519idAsU44y?M*6*t^?CO z)ybdGt|=Sqrd>MFhX9j$=`XSZ&VztyOXHcA_C#z3B62Nbkhk;)O*i_a$ICB8khUVa z((6KZ=C6{|nF&5M2Sz634~D_(;S-%{J=$D$H#H#C3<)AoO^`y_qaqi>cLkqjo$Qbe zB3JW1e`;^?tV}wSQv<|o(w8LT22(QJ4oE?hQFXu1VFsBEKw2oM)?&FMU&2~Jhf%x` ze}OM=$5y8Gf1MjJ5UrPq@KK=Xh6<_o?4RjYyl{{p4m&sqt>!LTPON1&tZ=K}4ven4 z5VYcVMEB)4h70=YT*X$)&rIrJYPFMJ4yr~S25wSE7+2~ahR>{C;N}=U z?<*3YFJTQAKr76Gm)4HGzHW67(n72PQ30-gIJdbD%CIlr8!iK7!Kh?keopu}UfuHQ z4iEJ=4+^`R^TQs4x^yHxn^{FngXR}zd8+JAoAJu2h zZOnpr_saNiN@b*2OGF*a_n4$|cBl&<;n9^G#wjf2Tbl~!H@zWo++0`bn`_oXMkH3` z6KeqonfjBh>H3SQzcO8aw8x#Co2h-np0BQ5j!9}i@UX5ONzQET(Kp=xTh-aRuOC?V zCPq&B9_`8PuY2hKP&aLsx)*#^-MRm#x(|xFql~-syCz$=x4-WH?EdP0drjSMi5N$h z$R!WxxA*^4_lkjaKmD6bzjONQ9`!%e&7?}dfACdx=lq}Q{^Y3v>uqYf?um_*+rQrK z-u=}*msHfA_@nOmvFlCZ{$NCd-R_B^&Y+Eeo4~h z_}ylIY8rF&G5J3G^}u{TF!{b|^4amGNleawya%cV*4cJU-g1-o@O`GvrWY7IlU4Mr zg0YK=gSayc#+Lc|<$E&tx##A)A+;*C@LSEbc_fbC;EpfL@mG(Fj0?tRK2W*Wzr|flIJme^J@a)LW2@z#ERij;z13Y@ z)jior@p_6JeR(-wxd`Qef&~YTc5qPkqeuOdk9d6(ks(K^eL6}B=$g-bTFt`E)jH74 zvIwz4(R`y0dE07Us$U4Xl9yO1H>^&_`kcJ2cHVPm3j(~COD&r+3UN4MLC=n2{K)g1m zavPsMbq8#0DfVCFC*QFpnXJKhJYAH@4dasBP#Mx_DWg7J#(k7gjjGVvQ>!j6TOQW* z%ZjSw!Y5jf&PibztD!ybrLFEsK2%_8y4Ut1Z;)GcVJh;fZtv~VVS1nymZgM-ScmjdIUL-+$$`FAD2mD|K@c%bf;RN zL+>0IxJ%6-&~|RuI2@Nlf!@^M$hibaDvVuAiE5UHHn)o^2X!{8bIf;X=KEChEoG?j zX~;A`#`xbNLBaSfy0F+Sa`pw`LpBl`ifu}VO0mIsiv*HG3S~9Uj@=?#E(s4#$ikh^ z(IGnajDBJlM?ZI|zw&gDz1pRIFK->mc^u)UFRkIc-jo*>a20Nd_+Lu@sg8=7Lq6{L zW4m15{nWIhNp~;qIqn&(Kt7`Pd#p)XBLw=b2FF7$`ji6MqrcE7Ah+w#hhJrpr}lyY zoV?jKmtD2!Ao7bqYOk5if%g3$3ygTyj@5acOBPllwf9CHl6bKTTrCIIo)QoiNgG~{ zYOAUcY)iG`vLw>$$D|n=sO9Y`EX~B{=d8|k_63~CO6QP>W#&U92An1CLwZSpbaRI{ zX0M;yy47WqqHlUNYMN?Km3**DBm)lvtHqk+XjV>e3rg4W&qB`VI&?teQ+k4j4q^Ks zcj*G`O`nVJP;{W%md~9LFI)pOVrd+40e@DULX1Vs3N8#lTzY!dV7V^B09PEIgh;IY zqBDQzPG)k1n!Zbxnm#uQI$f{6Dyylpm^4;%n7U1i^|cs{76ykwic=-$&|um27cv_m z=L*+J!uRKo58@mHc~A*{=S3BU_OTnV(PcGPkdO^Y1M6B6;cq$hO9b~lp3s^Pt=ot5 z9*V^x_Lv!pi};AhPy}nXtvDky3B^PST;75$Py~cER7rf$+5h8`po=aqC2Z zGh{i-sarw==?0c@<&slgE11?H(lZT}l120h?m^vR-8sfJRpMH~6?88`<-JYSG6@ln zx^@Tch@aOVa4`XLOI+`@D|e}H>C=Se>#%$smT&xu;tcJI(ZnpTR`3SEJ0h+qQ6h_p zQ6g;AsN_}(GaPswjJY9NRZGxj1_M!RzN+{FRg^=EFOZLBb7d{f=lx!yc=f6KKGou$ zi__ws3kQgME@3+sBj;Jl{j&%S{ExJf9K^IS;YWyDt1YA8uuJ{BM{1YV89BMy<2;h< zT0Ra`YJ4H*rK32RYl@Z=NSCbXulZ|Ui)bp1miCh#5UT^IkN>fL=ZtSqkhDTKK`Q_H z_RQ9ZltG^PsQ7ot;W=mIkuqKVbNyA*w=YmV$5#D+>$^~})O{~9Tj`FMi?|EDk3XF5 zeHo3&^nN9Q{Y^l8;(u?#m-!iK>;9DovH`9<0 zL^wyL;dOt_>yf9WAuP>np!*<}fvw!bLjS>A89*-^`>Gl!%PJ-P(NM!1Fj7OYmDt31 zUGv?A+_gJvy8uS(Le6$A=?KzWteV~gjX69j{DbJ>@!{|LnCRR)6=IKaDXFAW}~Jb;(RsMt`tc$%2*p!DPe5Ego9 zER)hqt2u|x083lS7!BQ9j()fLn(nb^2$GbTP<$mceWu`JI}c}#&fl3SSw>fvdS z5oSg%p29qi9A^~<0~fOatV|L zx6m+V*zYS@ZMCd6?!XMMR{i(a8FrS$V33a$x1w7F!O}WXQx6(e$^!JkRb4kA-Few` z7+G2*5%IC#CX8~z4DkG7ke}1&u811RzGH=J7$^LVZx1LZFH;U&7MK{Jcu8ynux4+) z(~j>5ufN6{J}uSGH5+&(XWBQGz8Cku7d<>|#h}ea6yMR*7GPF4i(Y&5$WXsEt*t{a zP$$st2Bc>8blTS+T5@Snk3=LkV|$fLOG>cBtVf@(ZC;&wTx1*&1!;L;Hw)4*KiqRB zY!&_-T{AqKELF;~O#^i4C0kkUL>OKz1Lo|35~5wQYPThp(o91;);oTfawvB0QPPFY ztlJE!me%pCbD&l*sJ+b}ee1Bl&xJ3DJ>e04r`B7KIM|_mA!NQAxZEeMi z4lz2B+=Cr<+qUAwvu(1JI6Hl5fV3ZbNlQdj;Bk$mLP*WlrxVtuu8?qs>vUPA=u9}o z$x%9ApZM~&P=qez*cS=}!2ya*mHbv0cQIQ(Glp`XWWXP_t<%wek=iOb{?Rkk^?@S% z`+8Gfb$@*er53OVfh@c&8CV~p8M?l2QDCYwn#x`Mh^|qywb?G7XGOQG(sNx5@;uK@ z^&q`BgDT{V_B>+Z<_?IPmWlhNiTl=oxZ^W%F%x(EfVe>>jy*xSH<!~xJ<{CzlY2-|ilMZ1*&hv!i##I2lMyIAbdiaMp<_PCH9Wl=% zL;(fw=>YGN#gNfkix<7j5=@l@X^b5&d4~_pSwxrnE+nA|`j-ycLGhPRh8^?#7TP^k zveLxvk=RPl6p4aq8}n?`vEMVX9VWIc8~Z~YdzOj)n~5EijlEpQjx({FOsu*kQ}Qew z>oT#wGqKyVu~jev?~w$k$(367U6mqdDwF4nP+n!M{w-o|X+X*%|96PvF0 z``OqE9s5HQ8#Q?Y+1TTC?8PQ_jfp)u8|&7w=Nwb7Hyist8mOrfpNU;%^1joO8I2wt zn`>gPHnBUiv5)E4x4HVEqnDW2KW1Ye)UjJl?0F`3V>b3K9s7WZ6*&urY-u*OQO9mD zu~SX#ylm`MI`$e9d$x)FRyKB?j-6#c&1R!SRw&l1R_*rzp;*N?tOt|1GgGPp>G`>YWc9OHIt7;PiRp09;Su zQv?RObQ0nx_s7Fp6~VC4GV~NLWstzdr{lSl!m$E6VY~lOcVI$mU`Sga<_QuAl;Nze z{JX|2!UbF8h*tCX?DI?}IyXFd%V-HY6JOLj(rX|zsmP$%W7#mFz1Pu3?d|=ob&EinSc4gvG!lOU`c5EFHhIU3v;ph z0uJd78p|&)47B{B@ggnnqmd(R&9)aDU5p9K{m^&71JQvjI+RLfbmg|t5g0yaiM^WP zcFprkF&xkR*h^|<9K0HXwqmaR3AuIx19=vgL(2-)u0HaQr}N3DG>T(zDX@$xnFO#5 z^dE4|3%Z7D>b;SVu>@`JIc%r8H13m?#V*EHK&ifa%lP-I#h9TOn$na_!d$@mqem~a zZV$s=fg!IoBfWy29xR`VOQkgyZNYvBNeeSVG~ zPoQRx)$$uA&hOaX=#kOZ%>a2TUPQKY_P#z%#EZFm_P24nr-LSvPR0Z ztBetI@8TtenkgFWB!ywi9JW1 z_BM55UU%F*x2-3)ylZnIxvW4}Vl@q6#OjS$kZyONe2>-qbK*rE`kmbHRQ-1nBWkr= zq6Z~?aVso_ObaxZBq0XVzz$1m+N@i~lav)UB5tRWL(N!N1kt?GI;Zvof74-(PnUJe zQT_&M+E!0ADtd>MKd-xAL(h5T>h}CVd8?$z^XL8D*^$^r({Qm?W8ES~TM%RtYK>yu z(IYj9agaq6j|s=dYuLwUTVInpP%j_~)YhN=%Cu^-*5;*n=O-D=z zkK;Sl_89BHl`J8mFz&}X&NxdmcRB9qgSi+NwSz`J!9z96Ml9?kJ|cl=EtvZdBT|7m zNMZ8nn~iG2Q4OOP`GV>rhb&I9hY_qEXEi^>i|yoZ@kz0gM;1*qKR1{fs&i{{d#i4Q za5Nq@`CHadX);{7H~Em>A}cQZ^7iPaSI4a2AbI+?M-5+Jxq@X`WVgri(Q4U8=(ifT zG(N7I;j89J)&~0vJ7(b*>ysJkuWtumUs>OuiD1x+qeq6U_|H^Z!eN0hrAw^lQ4$k< zhbjGt(a}@-x6DgR`laO>s3o=TDcKAHYAe)`$GLU5)R&QNv7OPdUqj9yzjY^e?m%~E ziINTCW0MR`uV!_p83Z$^Pm}R}UW74F5j{LR;<01nlDHOqMnGoHAUp1^*CI_h`3aHN zr0FAJ!LEOSK)r$wC5~CZ6GEqRru$ZOQP%&(O#T2}mJY6*R8|e&= z_3qYrjt`H+p*pVLVNyWjT0uEC0x_Iv<^x3wB5!_$D8~Sf0TLY@{hS|7L#ezo^`V?T z577y$JP>g9S6^Hj2Jy38x&b&Z`06GE9oI3f2*ggvr+z!W?sJxAq}^`V z!P*!c#0~P~!DtzrgeI1V`Z6qH-?et2ijXjq(>Et8Adjk&qjxO3fT3{Nh@=4f;t|ZLiCm)a(oC-gAFE4(5*-%$~=X{p3 z)jVE~9cxqVNSumo5wKh5d=y}}Okz$iVW#U2E)va;IG7@*R$Z~AEfx>;c^I_XEhcV# z1P_!K|#iMt8YCoXHNv#niU1fhSaw3cz!4GE5^ZZ%R?lN z`==!2MBV&-Y5W$c(s^a`wemq3E|L!B=S?)37~0yF_z~|^^4T9uC42VjN?`24cUvMk zmrCO1?cu3xvFX+(3#;l@^F0LW@o1Lp(M}wF*ATp%ub|^D;}Fb@ugMYFoA{ojYygCx zH9a9ZRW!PJ1;AgP!ZOQr z$t%5`cY^8 z4?48`>#{@y+V-!Iq)#HoNWU~PI*h$BywC ztFK66-2QE298+Ta&a;c6=T3+W)_Ye%D2~G#u3%j^!WKO1_i^(q#M~rvquK#(#4vJ| zpQ(fj=t|2n)}ydBN70SRcKIdU$(m60wcX1H`SpE0N7!j{u{}ZpR}?7=8z^ZLu*E7@ ze`q53Pp8X%cr{RUZLb)YtXBgs1sMQyO)vIeZscUoI?fSWL)d3IM(ml%yN0efo(||X zbJ$dHdN5KU=Wl|ba~yNdp#Q~9eKBSXQRnpfpJbq2*pHejT5oOs@)xnfQ&q~rllLrC z(p_@38Z?R!P^lcCtuOzvM4}w(59E^dj))Ba(FGeV80h)|w-0AdVAqRMmXA z`riTPH*(Q|Gnxn+3Fg2;H+Mc>@u2n-!fQT{6v&C>O03XZ?BC)G`q{))`s1^;1)Bw9 zPh7+&dT`)IJ5wcVff5Y+&uQ|c=$g{pr3b1m!Hh!PxbWVp`8nZT{tecd-ld*1?VRPm z5n8yaH2Dvj{dJx8*O|0Gm9#(hZx~A2!KAfrj>vqP^lu>Wj5hLPgQ=W4-)3A!hITrvY>hT#NGS2;i z7YYkfVh3xWV8B#r3&v;lOA4G$fSl26ZD3&Gzi4Ls3Ogemkg<=I#%I&_Mhp981lW{X zMxgVzT1MajJ>8;Gs$~R3D&Ss%jEn&LvRMmb%f+?O2Wf(nSD!lF2nKx74wPV*fYz|S zrdz1*kpg&1uWa>id5eOl#@#ug_}B;*>-^64pO&}7?E&*@d(%Coyzuz&sFrQ327x(< z3vr~->T257?&301_(TA>`CdC_Y<%_0VRNTnnR-f!#yZ2LP;GJdIsVNT@C{*_E+5#8 zwjJ!EkuRz9z&TlsBUX9h%Tmd__>DO=pRe5^w#$HI9d=$TS8rQEkL5aIfTY0yF@v-` zq8C}jVqu=m4ml+v2kF;7mP3^#hp*?l{G;$Gm91h&onH^XeT<#Z;xddG<_E!DBD($! zl^{mbgPq7*nuJ;|Bb!tM_Ebp=+$?Du6B^dHOtXcD#%5<^vU&`(sUp}wr$6HU>mWB^ zUT|1Y$cV+Id&C19YMuO9C49c=>Qc5Krd|%(ciZuA{DT$vm>xXLDLL0XD}$)KJ7h2q zBPKPfren=^1{0Y((fnBfO$#V36~hrUs&;@(K=dmmQ1AM>5L?1mm22kl>SR;*anyab zAV|wlaV@%#HZTv4+vpT4##MN{#>T6 zH1mcurOc&F+Sk-KDW7cv+l5IZNoK}GsqSQn>ec`UEZW;qPFPEYGvdEUE6&*f8+F>`mQULdueKc~yg?Zp40Fzt5%3Eu47$^QEr`Lp|P zC8hj7?!POk>i@F;ifF)>_8)668Hm+E;?F7BmxF+wjXGm**M798sEsZU99JbY1yA1AAFagSJbLzk-C zDv-=-5eh6@R@Z%EgDUwKzvu@*OT84qF!co324a%Uh;sc0hoCKzo#C%hyPwODL-^w` ztqPCSI%w&X`J|+!f3lq+>Us*6k`i-)AmXoJ2G5h`l~q`ey+2m;SSp;Cw9SBBs{0ek zW;IVD#RekQ=OwP>^-IDtXF-F@of6P*4)PC~yK&5(Iz=`CsgfU_$I_*t#Vi^z?v*iM zB=!NgixIuYSkc)2ykg)+w6EeNUU;^0eOAlll5dRgAT!~qlGCAjrChfZn=UD1w+FL5 zf1pH^eQ_=MjuOlKR;t~_#d0$SM z9f(?a^LB_dRne;iAc*v+Y)m|a6{>(_h>d+#!Zl99R0;4+%TerC(T$*tJ5(*6K1m?XuL#F1SWJ$u4WWwcHt;qknwD@@^*9OK() zUv8=-m+K9p|S6|K8f;tvA@>Q~!ApMWn<@+5dpN@RH4eY&UyKPN>RTk1HZa!p1=dzx$oE7cF za@@hCsQDd>6Y81hKLhEDF*1s~-q8#a-bVBy&Q0x+6>QhMzBF;n6zSYEr;!5 zFXNWD`L9~W%HVV0?g7qgoN~^~njWsjC#UmDz)9%zY7u!iM$f(u0R;T>ihf(C=fC8G z!UF5h_z|!0AzEIMIdO{ah24iAM_72GSxC_kHh`Ajnb;rd*m*kkutpC;&ObF%K^**% znk(B6Kr>e(SXT4-(&aKg<0N%;ek3>fmV|vDmVByYm@ZH99(RgcO?DuPWXy1YY#5bJZ{9 zZGa6ky2}kWhh`d~k_D)at78slOQ zy+?qtE%LlX^_;7_nStZS?yF+_O}191tY3F}j;9GUg4I~aTMlml=YX>xF^i^y*M+aR zCg5!MBV60md*yXk1e-pZe#LbWM+Js-Ku83JwEL|exBHt8`Xk}R{-zJFxGsEU-H`oF zA2#^w1A!s?Ypow|t=wk)np+w$9)``0akRoZ>>ZxxbT_@(dv3~VI@&rY#}zJbI=XNW z2<3#Pqf6vDrm6kmBcG%m97Bo4)lYYRs}TB*h8KPVMwOPk5dl!d<)#<*l}_(-$7u>Dj`! zN5}kyH{_7nP~3zF@x{i052K-KF|ydg(wShITpUoH!C z;k&28<2e%|L)B|9fyflu1OmU1ba{twDd8>wL2}@v_mMhI8l^9L#2#j`nuEO}VJ+x1 zG8M-ELaL;q4*8>^z6Ia_ht)b=+&&<3WIAe}kFA7Hp>?cGQQ^~_qMf7!=~qik&74r9 zXooC-R7r@k?C4ByDwc3wl3IU)IycYjDUh9 zPNJC{M(tIrZEb6>U2JcAYp+!aE+j;g0Lo@7xK!d&Ipe4Vmyjqh|Ihb5Gf7a|+urB* z+~>dXJY>#!&$}<*_q%^}@wI2`Qo*d`Y3(fj)WsSW^1=@@D{HIO(xF&`TEytjm(XKd zt1Pg&1s>HsK?4^VHljpPs*{^2Y+RS2loWi1By$1k#BF9bn48!aMSW z#I6B*9ThUcXIBek8+Ux(F^&Of1&V$E{;4u)~^YO8=#^W@*C zO^WX(nmM0)`$5Tz{=WP$@g4zZ#{?^~;F}o)3X08inNQr0svCw9+mn9NEjic7|Z)B5TfyI7V5P~NjlIVqa7DLBkbEW1-th2@J0q{_Xv5R$d(Nf}JYO7zJ zeVP(#MMiYyoEEen!YACr)aGwKf1T`TqhtTB2^;I*>ZxyE-kf(1ZZfih_N}I`Rn^6o z&>Fu%HTz#rXIj!s)j@kgCow2+P5#xZ7D7!U!s$l*#_v=s0R&S|%Ra=ylO~U*ePl%Y zckySiQH?}`r|iho*1J0Tc2D&ESE(*Ckuu__$bKj^wIjHHSJlLK^@ev3G3iNKI+OHD z1MfVCxS5=RW-X}tWV`oe(~TkD!WT#gLy@DkB}*Ugws&r7vroqEBeyCclZ zm|)44WN*m3H9Wp0YkEZ_r+&k^&0~`JzUsvW6RAEor{ zP0gCWd0rN$$X{Mr6tqHU_=bs3tCjS$6eDL0oxc=8<47`)jQc2V)aDb?HXiH_ z5Vf?n*L-sgLj_b5)ufNZ>D`<;oD+fIecHUvXxm8aY`ne8jxvvxkH@oPIGUTrLy(pO zc8#4Q^KoRof^Z6{Xw}@r$x>a77o)YZnOmg^^V-Z8iJV73Pv%RLlyq(zmkGX&E_J z!onht05f5fNYICc<1D_O;@{%FS&lQ<(*5(fqr~Bb$QlgvKA@;Shj06=$mfM`S0m;{ zuxwv4FMNs;z~ynKZzFh7vAJ(7(C>wWstIm~8N|pv=zT3bp{xzh5k6MwW$nJUV97SM zKYnICsV{zl*YXKy->3bIwZPFO_z4@^tU?14=BeOsH0=3HxMbCa--X|< z)MgkYW-^xE@}it^lo>=2lu=^;bPT(C7uB;mOP~|PuDF1K%kHe*EaSF!)!`nF&@m)g zcLx?$s~on~9sydFA{LI%L*BJhcDK3mN z%q;4vtnFAQ*Rrt0bv&S{U1vEs5T<1EBXQR z=$wA>;Km~N5jIv(HWm@Eu;2cZwXxjh9&A0?SP!~oVPWQ5!?EGFn>*`Zm3LJT~*K^u}2r8^^&KGot0z zu1Swc{{| z{mi8whGlAtIu^2PE`Vmq`|+S@Dx*j{=#rf(#E&3~^v|Z~B>-m|Y}_iGU>Ms#)W=($&4XsN4j6>6 zThe@H8)@|3hpZ?nxcT21=MzmJYtQAHe*}6&`>(-eTdG5QGS~bYd_t)5ee&&o^=)|s zf~-T`T%H#Ayu*%iu1tr$d0fl3%xdl{hkYj({Z|G=RL88cwmR($=Y^3hn|3d5c!$YU z#X@xQU+1xFja=e@oh_E0B3P>JQlS*NplV7_cT=8WwW&zPd~<6MC*#mZCoLpTY^Zo5dnk>1Y{{_=6@QYn zQC7S3+h*J={Z(9M0>#ACD3YUOl8g{|2wHw>P7=FdHHg^Y2(<88@gzy0(;TBaQKYgV zpM(BQ6>OR&(l`hds9TXAVLu>_V9;qmYV`&QHi7AbxZ)Bwx-x~8u?3#A5TW6NHaZu? zzkRSZmnZW$VXv*P;Sm{f{6?hDFPUdPBai~|Do_U}_p}x{2GV$xlth;MgHs^K?~x@& z?oM6K2<`e~r=7T(?dr5qExTxGMO~NfvZ3fc67RWJ=ha_bUf-gZ7p-pA%lT36 zF6U}NU7bHiZz2?PZ1ZQGb|J|qwr(35+bLfi+mXkV>`HYc>viLRpBaaOJ#7xv>fY2U zPz0QJ>1coUXWe{}a=|#4zplurR6*ZaO48~L3K~sNt$t_pttr7puhxX@m%qS#D-p>E zpaBk#n_*zY=ej`{t$;E&Y=G#Tm6z%gNlhr#X-!TPohF%@WMif)p{_3WRVtdYYw?$4 zU2FFT7rj{%v`>C?F{@~`0mN*xdg#`ko8{8hnK`tVkoD-CKk;4{9mu-*0(MfW;CO3H6_v3v?a4MA9Ysb;mC&xT$ zX}cOv^0;(vzE{S)Y?XxYX@ukt8jfCnZ22T>$caxX1MrO_E9R&tu)uWdyGiynAn zr>u3b$vN-F&Q9l8Io+v(9-u7p@2t2i(~KVpo16YQ>%BJaQ#`AHW(O7Cpoj?Y59{_9 zKpCuM4+LA8A^A52hRo8-g0)bhEL3Xgg?Q)R7xZqwDZsU0{(h~TkA9irvnz2QJXEj3 zL(;XDP^(<7^rZKC7{14gbr zStcL0m}So@2JhG}ednW+?GWwr55D?Cp703%j*L7ab&Twsow6YnPHishV`8<&H|ayY z*CW$BGD6h4j^sX-j^c>;?+fRIV&_ZW^pvAWX{lhLA=y&x_1??F)Ny>|?8Z%z$uPt? z_Or6;%a5lTV^=a)C_M z*3D)!`(Anh;%DC_ql>(U>`#T9hEHfJpV1=ob^h*J>yWRfIv3S3=V3M!dI0~1Un=j6 z_>!#f>A~8M(uzSZnaiG_+L)5xU!m-iag*F_>NhFHg@x)c5*^FFOHRvERQkA*HQ}>$ zHRYlwJi;qS_9R4?E0$ZLOY4RnJ{e$<;^`<~qjToJTLrUuwj~Of$FI=v55p7y#HjP` znQz6{^#H)O1sGct7HIJ4v;KYeX+PvB1-%`S8&T*lOcl&LRZe*T01*JrEG|J-)D}Eb zo`XD-$CG(?%QvEjw)X(Hs@%acp34IKwr5T{6~j<%EgNbjsQKHO-YV$=OC1zb@tE@h z)uZPS0Kg<5itnLG!5USYwu&>%(ItLo_nB_ z4Z*@PJ7O)O&^dEJ!S$xKR7H*5WDmyGn_8D>n+wEY8oTbgppni5cuy5A3Bsj5~*;9X1q{f?4J~kfv67qhN7j6*r3|cT(;W z-URrhjgk%O2IwX2hCWHMrfIuE@LU%bFmi@G_*#yBaVSz~evNWbSQmkfrf7tO|@)0xr1k#Osv72)G~aD|bRh1}+wD^jV3+QR*uI?6y~ z$7Z=>;MEKp#sl1iv(Wtfz_Wj5q0KG*d`-%2GPMR(EcFrX)fO=i5}vZw%^y`x&6Oxj zW#UYtVY3aU75CAYU(0=DIj1yB*@xiSFpqXA-y7r1W37}0k`hs%IOUvhWwveqtin71 zbL49Fz*xDsYGJ524sjMDC9Tpmv;RKF!VtQfXZP_E;Sv>wmjVH%k!1}{MH84Di!Cc*H{+gQn#%vIgOWjP^ z^OT6qc5wosD6~87;k9pe;q8%cO5R(^D|@h9UT#n?hb*0tt9g+<6F>W9QJ$#X6>R^) zY0i}_a(ucWckeJCxX9Im zJ2%02YX_pKL+F?tPXLCp*Wo_Kc<8bzps=1{VMotV>n@~H1>zu z4*?!d+rw62e3grOYUUdL&ulXR5FP~}z5{2up&!t+TKhp8yJo!k^ka&}S)>{f=|QrF zN&FiY%=cJj`}`ij$QYRTxEJKpH^{@WEHL*`((0Fav#KPzImP!;z#rViOfavuYTh)I zZQ1AQV9KGavG~yfR|Zw=g6K@S1wI~TBdCluYjkvO;C8p;C9*5f187RcR++IY@X(7& z#nI+xsPo{*@5;fp61i{yWTHOEffL|$u7PyYqPuy4Z&+oR`02ZP`$5?Sq4tB$xyG9J z7p!sEDgmf7Tl{Cb9z~tm*_sSLKDrHY7_e%^l#N8BeNw+r1`3#U{Eu&%(vJcE%O&3=YsMpxDzOo z8Pc4X|4iRpqfw2o%Gjf;aI`b!atLaT4^!35mdetR`nhoTWFyIdgx7`qI8#bzVRifK zRq<=H^!WGoU(if`)a|a#e3uF;s31Ha0DO_&oL7|jLa9*dc?$JQp^Ey?vm$3^zDcQb zrPLHkO&ngzDl$M}DRr*S@qg>*7QC#dXB^gFZ9SNpW2{NYnlY3!UG?GX=NNey^UXI? z1-p*Jp>)6mLAa!T)q?B@WUVtyiS0?uW#6EjDdmVhhh2&)C7hB}!EY$WgcpEEPT}V1 zHrr4-V(5wAg1;MqH{#=MvH5Q#iENmEBDG0fssgJU63kBOkqT1cxd&|L;{o~9^sg2jzrp3;oJ?XgC_)FkV(~fn*b_yGWv923qO8#?)@#51>d+&9q~k zY+qz#UbdRRrG?HklLU7q_{Iv)pBaVQNeKfy+PD=G{PrwHu&8 zlUILfe$JzznR2{vh_P~Pi#^kGmFz#WBKo;K^3~*XrM8k?$#Klp{@2p8RlCD{Q8rwF zOXZqsy=3=x#8!AH7Z*XrWjk6E2bn}+Nu~;_C$rsggdto1Ar$}E`Y)i!BwHVWoXy)| zT+zc3I`c(2bdBop__X`G?0qw1D@%h3IOn#CRi*_@j82*$&STp0vKtxwyh`uqOTVQy zW&FZ}C=F$yZZaY4t@Cz}*jHaU85+Uh}kv#UzF#0}W?L-sy;D#NYv9tgX{!pOOVaeQ$|^S_Dw?h9Gj^l8Ei zOT|AtP7Bm=`VK{`<3t>mBI&oLe4R_*aVi3Pw1cj5Y&6*|MqmMW93$viI#Etlc3p*a ztQ?8QWY2P}dic$(YWi61vW}JD%~DnRTzxT7ohG8DjZ{xs(+|nO+0q&X`H}s<=_}`J zhB^p!74vt6XV%5aS^~Q=ZK(s+5_om^d&S^1HeXVDZgQ@iKKEb^5ocX&ToPCA!C==0 zxp28??56lU%bYe39Z+o*44uF{NsE=qyl?~;Xt#IB5j=6QS#`M%JA!%a2XU;SW|CcM ze3B@a#tOzw5KA(r+<%V_;u)jWBiq`Rs1;nI|GQe##XK0h6HZFObev$m|7(Q`Ts&0D z_AyzNhJMW;vT^0NEI;ZB-%uV2($2EM!u+TeWGJ(Ts4WU%ci!9^Qu>KD3P z2chYy|8TCPV#F!BlsLlt3sWU%(bL1}nGEmhIvABpJh)j&+pl0I{+jtV zl(8|lkRTC#?YD!bKSxv6q(tWydSs6w6tao=O1}B;>f7;5VDjy2|5TtBuZlN)&kZ;kRy_iw7vV_Ua1px(NgdM{T(li&-S{>kE(_{#3fVW)`>6aM3WcMe{}G*aN%G?etLl^6!kuEn0@OYrQW>c4Xi1fH!26b?TJ7Lj-uJd^g) z$KWEXY3mfcdw&|9dD9(wWGG`betrJY8So7ESr-3YQQO~eY~`B>eRSw@rV^(ehBJIR zyI8SIODBj%@4EpB9}YYi5IL+*H{Q^VPf<=+VFYfl2)BsG{5|HD{+P!sP`wdy*xZm* zy-9>56A((c2?b4}mm!QOxCl_JoQu3om5a=pK+D4Xa`9J zT|)Lna?Lq30oU4<{E^=0&u35MvnRHyJuwl!1Tgtiz>5lOAryp!r~>&KuM|NXI8*mK zUGm_g6clj$86Yzb_FJTSf za7x}5hPl<4s6afBg=W{{d=~8_X@gCKKvc;m^4hHyrLFWL=B4ZJpwC>f5H4%B@|dD2 z?J35OeDX&1kgUz@!DH}QhPqL7U=+iuW7qmIw0i-GSav2yxfx^YsbY2B_DC2cPE=`+ zQ;`Y`YbTg>!?Rq3fRiRwKaDQEq*M2HEe+vIX&2zFB}c-y!jL%O89%k8Om`JI@Q1MnxM3Z}Y+2ubFr3XV}v>7i3zrcbO`pJ&U%{DL&QgQw^rT%#?P zQ*ixH2SLn7KLPhEO;jnaA4P?u$d4?2{*JkdTRfmnUA@+5vfGVbwUI?1w90r-ZSYg5 za-9&+!anvZ5F3BClwA+Fv!6F`w^a{5OX0& zpn66{w7S^Qdh`X$SDErz27!i{Ra}=f3>=cdf;{|B2YVh%E`$AyUGw(_+sn6MgS8JE z?AbC{;jF9iUB{Nv)s|HffOu6s8iGShcgEoZ%fl5KYAWJ|ZG-xci#+w(@cE;x+)bSb z&gx-3^0x$iC}D^5r_^Xy6tsYi`Ro?R-Lf6q`^5!EdY!CQbmk8Nk*V|#4mm$ z%K(+Hg}6?Jw!;uS@s|kX2A)iUzyvbp+E*4;`@MTtKanJHFU)hu74Kf{?w8o|a;d3t z18NA=quqXp^-ny`7q!3CP74^&%F3A&d#nq4eyJ2}qT1+8h-p=-;76)b$mM2UhfZN) z1+Sn%|M4U0`~ViRI$7LIx3HgrM*3#*5rVn?Jc#69k;B|d-Y(lDHlBG2kFmnU<0O~t z5)I_I+{+>;ob!;>^-$4+T;S-V$~`_rrHQEUOLB+Oveyy*nv0Nd-cyzmmYa9RdzZo8 zjc=kM(PA>3TX<*QkQ#3ce_I4Tk@@@eLR&rT`^xz2gVBEXGIxBQ+x(bHWZwxz9W)9a zP{qc7%pIIpC%tkur7My;M2B-bpCWt`8?aZCm#4ZCw=!p~qC97=x?hSAo>vN1O2Jqj zEZmLZv)NCjgZf!p)OejGR?YqLEmd%Elt`$ZN2$a~{n1*K0$__yMkpn{j@G&|k|iZ# zDz-)EPD&}N%=~&-nq@{6X=Gu8!~F9I?FVWuhULTj2$ULUf9=w2!HcSleF0qXA$>5x z*l~s!kPvTw4j6ABzdwceKU@Mlm4y4Wr|i}p8|}Y3j1S_Q!c(LD%Mj|B56UttWa<95 zg$hsj0Ws^dfTYQM)XntV-lS{&NRDN63rDO2mxkM@tWIWL{CbLS#7~()kd5fT#j96@ zzoVDDq&03QDVoR)&xUh;UNlh{J}H_Q6+Q+pn2|O3$JLsCO@@H6ExOg6_@xwIw>Ky8 z5DyqiBXSa=A-dJ4R6_#@ELM`79l1HW=TP*$1JSM7_*%(HE|D;Q-=-2h_h7O%nz$r9 zFPaz~o=%geNZUt82S#X36IkQ@UA8v1&(~;Wbg}{m#F3JK(XFlP8=WkXx5?`5qtVI9 z>6}=9@70o;wr)?}QYRjglMWK{WccZ^H#w*_ApCZ*TalPWnVAL!xX-{rnzANAdD^@% zE_jjF^nDIA*+vY{To?7u(3+N6U(!njI`%D9fkJ7()J5eLWLH*m6x|q`geP8rofvJ1 zG(kwBqlU7$$uforP4R*mDhrse%JRt?s~h5Cftp5>&3#x`{1sERrVj+rajRX2kpLGT zQX}Onh=n$v8*f$cDp^v_AhvW|?$_zDn+x^W1(O1?I#*Tf#1K5hSRGE2>xyMlFAzEh z;@t8mH{|G3AVcQgu=oiLAM66Tsw!)%LTOI;o0UM~VzcElhS2c5d`lOs)28@I6M2&e zo(lcsbBDUxJ%lPxx~!V(?itG5$Rt>WEqh(GE_`5uASY%C+C`Rbb!1`%3E=|s&jJht zwwjxG0{`@h*L_rU({{X;4m(GF^Kk$QAynvPbYQ~GQ_Pbo&}GBqz-Hd19=Ts^rgyjE zZ()1IW^WO<}e5b(op=zUlhKPA@^P+$ipPwD9 z-C`cRo641Obwo4&d>`Fq7$UYxleDOp<#Q8DM8wlo4P|{KO{t6Cntg6$svL@_c{Rue zc&dGwJ!*R5OWKmTW(zf0^?-^phxq^bCNqi`i#1jU8P^ELCCVl;1S=>Zp@Nmdi3BDT zx%HPpAi6d5jN#7pr02h}=wX$D1a=?bvKqAmJSgnY?r-DZ9BtlIwP$Re+|a_&$$6{jhioZzj^@6bK(*;z1HwCGMX+ntq0Us`B;7N;T2 zaT*lbmb=oCEvCL`34^$R=iIJDvz4FOE@)g>;X=Z2-B3%Yir8Q$SELFaAAw21Iy_c* zpVt~e*=_OQA>I4p%}22*@pbYiRuA6KU(upVAo-T9(rWV{W^yV$g1Xqe5wUY(%iLYF zg-62nx(a{VSLFp`R~7Rgt%9oxDH3tTt{R`nqWoNg4#`9pD>YGt!DP(XtPb5mheTO; zD&%r(-uT33>ZR7$RinVbu60=zu-UG&vd<#BTo4xlDYU0%kMK7xEV?e7lV3!!q%;3X ze(GYgN8qS^WkkbOeLcOzmXp3EuaiCNlXI{V|8s0zspm2ZNIIk{hY|a7CP31~h(RMt z@Ukv#q`r)6WdC%JI2 z<#4KCMY`qP^lW&`7o}V7BK==&`7;?sY<3}SE>H#i-R{vC&ur^hXC{ysQR_;7|m!N5rPYuEO;xq9S&t8xW}^|JUB5&dN4^(!8Hl zuccW!YlEO(Movo)7#CYe-`Z%w_K|@I8aYwcjLKaa7u#_gN*QO9>)_J?})Gf8d zt9r~78w4lNJ$Rcam#%VH$7xT^cW1oqT~im`;7MMkJyqpiC;nb=wYT(ybv)S2Ki{b? z#SxM{IYV+#36u!op2xeAr&4{I^DXY!#Q>eHF94QvBf1SzjKk#M*Hgc$-=V(&f<%p^?;Grs+Vlkz1^$6ZFHOfoU30oQZLyM?LL56Icss0j(!8N z69!|aY+C4jH8M4Bh`WFJMp%lRv~lhA8}6YER=4R!eu-+QHP!KeipON_?#p>HI%dbG zW&P8wO!@Yr6L*l((Y|diy|*ZftB%O!3<{TJdCb zqs`bvf_=NcWYZ6$Z`&niQ*B5409dklL9~6ZZr>QJ-5$KY?Yq*xeOpLWm$zYO+D3Q+ zJm%-UL^o_9`%7?}r-$r2gNr_%9<=we$|3uw(N)W{Vu4*?%&V5CA`_yk*4o5MuBzLd z%6Qp<7_3%36SQNV*O}DJBK)4hnFAXwPmNAtW zY6}SrN?Qq?xv;24JeK(R`Y@?H!bt|L1({c>x8R&U4gG9LnZe z#Z@V}JE_j1vtQy3?!)!cBXCN_Az`G4V{B=fUq)FCafaJ>>h??jd`flOy6&NnE$j?G zA}vEE-edj@df1VGoUui7MV}KjFhSzNuQJSLQX$F5>HFJPL&b=KstuMkU!MlHmntZ) zE_n{En5_!3V9q0x(Jxa1tJP-D6QP=mRq)Ho-8b`0?vnQT>*wDog24)nnBUVcr$kTS$r@ zoATJI-M;2k*Amu#f1q(|*cDrq(*NX6<^X$A{+2zQ@ZIM3qjEm9rgMO@Yi;$s^hVtK zJ8ixk?29S_yTkUts6ECOT?M9-NoZTgpL%`j#_+eGeRckqn-4d0jhEARa|C9u84LRV z+9A^`9GhJffu@q44uOX&I^ZrRkMZ?&y2376w9(>+`m^NmCGCFWeWU6|pyPUdy_~*i z!W}+M{!EoW$H*ToI^c^m`n?FJu?kO)0c0lgbYp80;JGE4ZEQ6<*HNb}R@I@el?#39 zhVTWtw=G;T!$y_iQ)YI`v}7A~G)8^O-{|^*o^?Gk_9o@8vBWq33R+BA)Y?=72CA!$(SCX2i?HU{Bh<W%xuD~w#2tx9WcR*zbOok~J~jEU`4s-c_{Y71XTZ+^3lJ0QWb z8o4Ohy=--)F1G4rGYKSPT8^%Zu6lVw1nhMFPV!H_je~=>^Yb(ywqxeIyQyAM{>v(> zx-nL|(JBXioz2H%)4s@PBd}Ya+8%M_ew@tC?dAAS-H7Aq>G1{xN2ztG^|ZDjJV9O$ z$1w8vcEZSZSv?=Vd)v2YTu0V1A~$dfkf6Rx1#6hea~}GT(ds5YA4>C*jg~& z)qb1WK7#@Kv_|eFn>^Nsmxza_8_0vl46X4RdGPMP*{w$pIc~;9iwJnCNz|UJy4G*( zmw-CZgc4wF4PFn7I8InZg z?<@GiW(iMWn`li!x%cVywn#oP2oA~66I)2to(k-oafs$36Ig{$wy=*s!p1WV z7mY6x!poc?eTvLc?Zf#pgM%HA&}nMUR*Q4eTNtW#$8mrn8LoC`K2MoZjF&P(n`T>y zYLQcawMG*0CA#6BF?#8uzMd7ahA+5beE!ZriJ*vP@9y;IeoSV+y*J=Jw0ajo6Egbe0un?YU0)`wt5?aB|E!c1PHKgBFOMWGG-27r}76Pryho(Z|^m2D9y z5ZZ20DylXY>3(-z?k@8YP>!_KE;7S{hwv;R1nahI z1;U0aNcy2l+G;*)C7npp57J4$wUWk>bZZofsVb=AO)1LK4 zzk71(a+MGwZ43tkRZzpi!!VoQ6?r%XU^hKLC&;sX%|xnswUy&;2ewhxp>v1 zA!A#WkzfNX@hdO5m-vky-URPl!2cR!7k{hG13E{swqA}>H@@h0aNE@jmfiR@xNm(I z6#9^jhJSuAr8V8btch{p9NY|{uCtZqD{Hsu@j2O8mE3%MNS1CBGOY{9o!%Oii#F9% z+Shc8%6QUFlsmmoFJFyMW%%YgiagX^D7n!C!ZpgKkg*|sUMd&0*HqaX+oho1=PR$* zntml^(tQ+ViXZUqZ#iF=sCRIz}~h z5bXsK*ohiY4jd|X>DV7~)Z{|2Nz|CcdjJ8MvFgMdJYmUuHLIC;foFYxXDO2uaZ>K1 z+>mhv_ezi4L-c7icCXR~dEDgD8V|~rXnH+Ubx`w9_Qy$VcvQxR~W|JZQ*06uSU9>)by4>KW~0{YsLmMe#N%L>GYDc1(K%McX{;a z7N303jZXr^{))kZx9QI?-?qf%YKpJD?TzTb^;+ZmBt-{q&>H`s9&Th0sfQ)utD^%; zwMLC0Mh7BV;|nTzxz^M{`MCavhO$@Ou`X3nEuTrJQcH>^f3xP zRmo~yIY5zbdLZ|cx)X%#NLtnYYAZSxBbEvR6TS z6gP?WtT;INsH*fvNuDb^Bk!iYYDJ}*V?=FcIW_viIaS*FK!0))%fwHCN*hsC%d;b3 z1p0?E=0oPMaD{Nr$k1Fg5E*4v3qjDva;!)*;UN^F@9htG-w9~*-Vx1^CE|i8{*$e& zA}$)?Y;R(&g2b@WQ`iiy#^GLD*i!~bX$x^4_wU2tIX)A?X~k_sBz{5c4mKyZi-dhS zN&`|$Ne7DlOshZ8^oiCuk`!tfiQgnE1eO>Z@Uhcgn)r}ekBrvqQ`bh$vqS{RucdpY zHyn6`ueY73$Db*>Li$#_)qLw_z-}ziEXYv~LK?`Q5&AQdPYxZ{w!g?hJ4SZ5_8eCu zZd3vfrwV4%jKE>h9%X2yh>;dl8l61C<*#}e`dB$NNwIGaHSA$^@UhK=!Q(LU7g1rV zz^Q7O|0u_aT+-bM*bK|}S?c@WK9CmD-|M}n5!+1`foTx#$nLMpHM~P+#9smHUX$=g zvR{1RGi8ZfOLJt;oyN-ab!LU#@=~&%EH=~vg3ykAo!McP#gjBe5eOmTC8CpbT?r1n zO7`Ba%kXQ98Q4V&ceA%g39cC(DweEuM>+5tJRXJ&xlF*Gr4M-D9 z912h4?{(o~{w@yZ^LJU~Wm(nSq-8xB}Wpq>0gVC zsb8Hn4I_S0Op~PK{nN`-;#q@i(reY9t6HS$iZz}zIh0Bd0&r$mkk z7}uzCqQLY3$pMTyM1yyByyzDko~}TAVUc-3yl6qoh-=U0qSkuIN_4a2)f!^$N#aMDs_)G2i~de~V-8Rj8iAG5;jF{}~+f zX(^NLqu`kT!TUeLF&~lqU&b-Ns~R4TV?MdY)pi(;NyOW{Hf6>Jn)&2?BYOnReBZ$i zx;*;1OKU8nivM@xoBNP^{~y6OAEToG5x$xGJ?l>Re-eUL#C{NU`!c?HH}@zQ+mZ3j|D@!1_7REcD?k9Zl}&EpA~D;p6Xw)Ew7x z6ce+XAv?3-%O+i7iZr#0#$hfyM%t6vDa?~C#mz6{uX@I8xX)MUQxaaVS-;^88K&_u zku$=1q3CkeRMwc}3>*Z31eX!QTOqoCNo_G}Az1Lz38EVr8}*(7Q7I_!U;cQ$8RAP* z-|8Jv@$2XpmzQa+fS{njmTCaLQ?BahP2n-8VVBTAkoR^1?(k|J{@Qc+D+05j%yGTg zqDx`>UUvw7aYeO?>+Tk3CRB$u%5qbAvad#;J(JXibJ6Yyg6sw%zj{;kqM>sne_kH4 z^h$dYP^K-s0u_b2k7>o*9>#V$n(6n|(Q;el@}OZ@J>M8U3iYVS7;|Q+tgRt6n5SPS z)fhdh_k%e+!*UdI*ONmkHC@Bf51b*jL^I=_Esf12qcG2d4G9rSnY&aTLyqP8dTF9$ ztNFZ@CX7sZeZqQ`YRunQ&oX*g#${Y+60T}Ov{fcTdfv8#FNPr*%$1Tk{V%AoVjDpmJrGa$dw)yzK9ih0VKV3g!=nkDK>C+xf~ z?A2b1{1?d7k%**3HW}f?i}&USXjCWOeXl=@cvyow2Jfj^u3=jy^WGzUWW_S?naQ)> zhwqxR)G*jJm`JEyBUw;3muPjR4_XOjHq+!Q#Et}XpQ9bXnGMqMxIuQ}O z;&VM_8wx$cb+Of%7F`pM$Q{_=vt%XC3mV5rScEf!u`%N8>j&7s2tyhk!e;aL(8zKw z(Wi2blq2KaW$7j#kX%@I4?56F6ROl+9G!8(iCmA7@vXugH`}>kyPO(HvR@E>MDY@* z=D?SBy^ciFb21H`Fu#y;;wo-zm-7Oir2z3*UuOmiqF)@05Ebr>!Q|se#@^xR=obef zW5vSA)8!nK{%X`X1|6)!&`Xo>sB=Uu7wbd1Swnh8o?!g4LL@WKiXT=6k4-Wid--@# zxC+K^%L~RXa0Fv_c<5rQY-{bQwz^OL1D}b#XcGoY4z)O@C?6}bOFs$5?>dHRlqzP6 zqoP@P&q{6L!;uMmSsS{t5=UkN0a&&dk!D>`vx; zH!mG+w0HXRmUvR_=r-PrF6M^pmTcUVzGlpJC_N|P5lK8JIH65T7&^{Xlvb&zzcJ9fuQk#%ns@0Sd%SbNTreqtqOXC4PNboBZSbM1Gtp2X$g^Di>CB+1C(T7S~T9s!QP=o$aGk(^Wcys|J zrN)4crMqd~EoFMmLQZ_p_^GsJY&DMpN+8no&T?ptqF38m%wn0-Sw;Y#c+6$fc9R}7 z?y&l|Iew{wWmu`XZQ7VD%^h@WV?u7t?el13bPw;PyqEIsZ^k=dAvmK$}`qKWWO94%PpsmxVKCIbzPs$6*6B z%N288$^#d)oReV8d4(hsVa54O^k52}k|+APb5%jG7UgOG+&sJiH3pmScGyxIl5ZP3 z<$J^D0-aWkBTI|_n8KOOjafa5Rff03M6e+xyL{DA$U<5gj}ZtYIeNcKj;`|Lde!qiZ`!MmJd}fzi?Z-P2J6EfMVSM5bgUP$=Ym(}Mr^k=NXL zbq0q`I?GsSG=n({3VRESuK=V3;_AAFO@uv@!kN$lTwLT)T7VWt>0^uj;lnh16TpEx zjonZ@Wqm5vI=AX(bKd7@4vDQDCf1L$Fvdr^l757Y=PSy!#&U+K+xNmuE{z^^-t})ZhhHGe1|0q#^)A_TUnW2^UX;prrip( ze_YndU%||3cl=7_x}@ktUwOFb#BhbL{HClhKHhK10-|OU1#sD9@thir&ngVs+x3!u zJ)U=dy~}~;vQWv^2oab!Wc$j`iU71`O=uNNtls6yd^F}d8WO+YrVO7RO*q1yXd*v6 z7VSjrFFQr(;rwJij(Lya;ca<9N6NWf9&&hS;~^MRTgs2Skfc4f)CKaDr#;oFE-G#* zh4@vR-RH(6r|CCxsUyfh4dw7*@0o~l&I?sQYj{h?e93M?3+Wz zcD?+}uuqNsTp71qCVp?*vZ4TCt#xaAE4~+cmP97>t zUQe$ROPDt|K7Hys>vr~Q{bJ)B4`qi+c1HHfM*0D~1TIKmWVrzAr?`kjGuLO?Wh@%B z%dngZDOHyF;=@+iAuJH58fYP7je)|3d4mVXD6_L>$bnnNK??NXokE2DIC@%E*<)R}Tgs)D$oTR=zsM&7z3J#NIE5-i1nkkLc7DZ5BWV0dX#{f+7eGm2 zsNuW#8g+@r^8@s%{-qJrq(@Nw~h^b`{x^NBmvW&}!gB!B-EzteaBQb@8R;o7BeCsgRoeddH|;CCOgqpu0Z zqxCdbS5X|Ei177#xJ3SVAX`OY*kWz|pK!FvCTC8vO(xp~WE=FCA|8qqS{jy&)({uV zRb(*|7-z=3Lhx5^A~X4mBla=P?_k1kG`NZ8gp;?=eBmfz;HA(o@hXox`O=Z7_w>k_ zmGN2Gb%BcV@JZ`LRRsKBI?3@)nfKhGu9>C*8Js`%9R4G1$ql-(7e2&Ff!#o+Q^}*y zAq)SQHVgBp^9a~*I!ocxqW>;Mqp8!i#s_(d&&R_C^N;et7V|7sd-$4!Qk6NF6*)zU zEL}?Wt6)6D@2XcN&bLaKb}ReW68Md=MGt02=8)aJ)L+MeMZGO`Y6RUm)px6a8jbl< zlUnB$l0j>)csE%ywN~~oW)=Q;@HWkjoPCTEQv?(mkhCQot)``XmL!a!$3RfLYF5ASnw-SyE+hC+x4J_u^AD@`rz+!k{s; zIu!F&M~}m2{fFvwLIWS>{}-xnEz=257RMz3{@<8#y;`t%N_@{ zdK*@gc|#+G;>`>ASQ%ftQ2jin0#|cylmnBQZl7qi2!4Np9Q?SdPwv0Vq`l{*y&?Iv zI1DuIe@vQmJ_tghw+duHrzd^3f@WJ(C^B&OrU6Q_{bxnatgD!t9Vr2kedOz4iN;?- zL{IXSX7ZgOBVvPP$24%Z#0vI`Z2CQN|Kg8f1{K z!t3ti1Uk)Vi?kHJOkXb@NN3ujqs|->`dd^hMH4$1kJt0vET_Basi}-NNm8ZYdxGcF zKdii=X5U9n+W9C; z_mR}9#$8uY7A~st?p-=X-Pcv|DgZnVjCPtk8`S)aO9(?PiBo!ik*_XR3e%@gRufj; zB}L^#?%}K0m(_eA;YwjkREZC5)*t0vMsyR74ib033X+-nRNZ>?2>mLVJ?q-Jfrczs zU6+$jd0NeY2BmIn27Y!Jw6M(aN{^H{@kogyj+D6Xr$?ysjp2z_+Z(@{^yF8Q9+4zs z_cgWM7V>jE2}OpU^u?$J1EOGutSnky_Bu`s;bZno;D`8X(4$v^#!Hn(j`6GE(UO&K12)T5sKT#Ysne}yGIuJv*2<46E>A3SsubsMe&emOzUY7xciv}TlA+Md zw|}B62mNdba5PzsU2;_}FuyB~-wYvT-3mo*t&uE8&yy^0V%fTK2rSIvucv}~RK}lf zBX`IkF2z>!7KpQZtgnAK9kX1c6DJ_@VI$jIa0$7ORW<)fA%gRUPv+h;-xDyg#q7Tg zd@BFjSm!pi>Ce%QP1gcjV)@mipt`40tjfPFO@j*vJUELkOB18tPo?^ziVBa+_BWor z1w1x#o^&jpKL-rZ9H}xEoF~|zal7!=L6nxjir`Ifb>9B#uMm{CLmt{<&I{?4)!MtK zLHdH#Z#93Lu-Y1B(th+2X$)Edw+z?=${oi=hoW8PqB~N|pyB>#K)_mmHNs|lR)%Vx zb)ldWA6ju=B9o=g1#)>_ClxOltn&&n6PEyRPhVtbf)xH-7l@r6E5;hXywb@3)m%oz zJj0}O9$UqD1dytUHy3fBD&sR6$x#`<7D(tEsFdL=Q2Vji?Ewr%(i_}#6@?&%JV9fe zdG#uRVDDH>5rWUKtEN>OEYOFv^CZ;}2&z!kR0UUG*4b2i;kYv*&3XG*-UAAAF&zD3 zEa!#UJkID4)`Ptx0*`B6u~~JrOzv#iAAH-)H5t!FI)ypgSk%ijvYZOH9e}@1+pmX5nWvI5AtFyvBWmvfS@ydM z69E#`F3^q7$Y<%6V=G@?sWr(7UkFNwk@G(XEx2Y&9TmGJ?h^UIS|REm*;tLk;rbwmfpE~j$E+-p>E)Sy1C4M zBe(1^P4(R|F*rlO3FeO!vF<|!Em%3l zpC~Mc^ZQ)%L1T@Yc_9n`RxR%j71hYvG(0a$G=$k)fr9}Qk>hKMta*gW*4N7I%3R7) z7YEVG_9!~&>OShB8;|J5Un}Fw3R%ZfLk3J%250)AV)=HA>OB|;{Rl}dKyVx&eTW#f z69<6NPEYg;=WQ=EeW*2I{R{((KOq8ASMqCqI+l1nU*2g~J*e)Guk1BYL-G0sYN#|0 z4d-pIrT1Ku@Tb^sm9^l41Ln7Hk;AT-}78!-pg@HO|0=Ji?MJ3};Qu}5m2qsLVC2LdUPi?3> zE=%A7Y$^z`)i))O>uG}dlS5xCNTazV2X3aZmC@hVuE#EPpx7U~%|W|*Y=mxH;E3J1 zjcj-ZjUFHzk&KN9GI%88JQ7z`y}}oBEaV7BfI95g)c6eyr(6)apqj$W%$v`Qkpl#E zLFCZPyqUiyku*P(m3T!qVm!ZiHx*T|W>QO~w^(@Pr>iG(g{q>`i~ks&25bH{FVG_1 z!ptJ+T>&}m;sMlKoOqskho1+b5$D~n&ck7{LbET=>Y+z_lB1X5xLtIDtsaIdxPF@7 zl9BmwiAqrA!|Fh+_t^ia7K`3g#^mN`1Nyn2U{BU-O3@OL$C)r=l{}$8=!&D&o&li+3tCTAQL?QUzzK`nil` z9Rax~&ylPT70J57kS-1xi(r#2El)cO8qPvV(?9>l@fbQYR^r4XC5|{!;=b<>D{d8j zQq1zB=i@&&HoP0&dnYh(Nvi?Tn|zj`4(T_o~Xz>iCUI%1kVI#{+z zt_D82N$q%1EAF<6YL`MB@2JyG@4jUuthkK{!FW{B)?TP7ra9DZme%>3u)+O3Z9td0 zg6*c~H`wdhA}%oy6q7QhkHF;Zt#%LzU3;Ki?`v~Mis(U}y$w*F*R*3rjzsX1gdM4k zeg2}+?(n-X=v_$Yibk*7%h|4*xIDehMp}Jfv#p?CCz3Xi@)oXWp*wpW) zGo_SV*K_`t^C#zIN+5`7P35S_}QCsnAlLNTkATy^&Cb?t9E(%n8*RZ}>;oLq$M2~Pt^Tkq-!p;jX!gd1h+P${W& z3LDpkw~Bt|9|w5B_V-Kc^r_qGbniB@(~NwS#Zf6^_qV4QTg1UlG(zzZ#Q&4g-q-F4 zTR{nvXFclTQQAqK^r(YJX&^aCr8KtlE_EjJ2(zrdOzpOBM7<{Cb3{n*_;r5-QVQLt zoxEh1cJlIWAf^x1N`Oa1NBL)jixM8Bsmnhm2RXlW~?2eP>D)kWH})0`VK%eeJIBQP>8p z7^BB8%ral5x#&Cl6HvysR^jgW8{Z0#4{7UqMlQ`apHN@FNQekliDCVXd$h*Kq$lJU zrA2?qV|-qYxrU5*IB&HrU=&l^!&d}n*gQx$XYlLecQUGRk)@1l1V_+$)@QQM-Of{> z&X--5tj?rQAblD8)$MfiC0U+H&nErm<0ZWxY&dyRCjEVGf}2N4`Zh_|;8IS`;fi=|gs)@o(CteY)|H7T61j=@bxS>`gq!XMy8O z%n1BJAl8zGb{p&u)~->>*BS=4@L^T%$J%9`)+lFmzQ(Sw6FS1bce_dcX7c;+h?9#?l_}}>?TH{l z&R1eq0mfiu6Rb6dk>|f@ja*zyN=*2D-;otQ$T-!y;<`1z)kC%BF7;urR?IHJU>1hN za=fR*(!oW&#md)(8^I1s-xI#*j44pSoG+r?YQ_6L)@nY+VN+y^R{WZ=T`S(MPHSe1 zQ>%FeCxcL&KSGx+v%$M;$4TS6uLn36cS_@8T`zcB+J8_cW~}ldG#FXfp~Rdam=+_CCB0py~S$A`Q55DhxANXkwp-D@Rfla!TCBF2N{a**UmC$TV+ z2RN^(|qQ`$o3w4`h)AR52M<9veO?NhkeMk zx24mwNvC$HtKG~?CuWgoUdkK+T#2lwnu><<+cMl!de2V6@#BN%p!J?5LU?&UAU_T7akJVQ zJX7$hBJb_*IY+9Bf<~k~8uVmESNUw=GWoRbEkNRN)gGQp4b|URkm;nV-~t%x0rzp$ z3*^Tb9Sc?`gE9~L+IJ{p=*YL*BpQmY3J0yyY>Q#V=ev!W3)0zUs(ONu?y>4>^U7<% zjCbH*!;O+rmZ*Sy3fz+F`*fEZq(xg-mcygVdK}54!+IRWW485}%VU=Hm}g`~d+g!U zQr+Rn{Le=!R2*!`6@ZtVB9-Oyr(|?;oIH<~=X|EDVQT7U96y7tAjC| zYpQrBV)zGBF~}JpM75G}iKx6Ft{(z}Ush;dd7iL!6+)G3UZh^+09oXP;8rlJ_=~q+ ziRW4k!STUgK)qkZ(MQN=uW%DlIG+ETom_*^9fHMr+gB#Q%yI>fwUY!1QmE(Zq@#Xb)RPbtq~ey8!foZoVOSMoa@AXZOF9(_DET91CyhHji-#~$;!Vs*Dl zIOQpiPzsT1Q&JmObA}Xyg#trXao|J+J~cKk;Lkv@{m<5=`{`qoFv= z+gX0W49kNt=OGe=*@N0%8=hF4cgefq+#^3RXAP=TlGDfY#``&)a@OomAN`n=Egeb4`U zp4Ue*`|Q2WKKruv+H0@9F63PnPicqQvl^%{??QRAB@_ES+^l8u$0zw#-q9ARxGJ+K zk;&rCizG66@tyIs&_-y-EQ*U5h0Drcf-M3ejj-`<#^X|N|EcO`HVrMcT2((U;`8>% zak`%)X#E-SevXLu^Eqjs<&4P>^8HVxZ`boz_iYL(-M5?KsYG+7Z`Y8=;h@wP>W{Ke zUWv5$GTma%>auZli)F3i*5=!9jgd9jlU_uA#vh5nTF0+zTu)|p?m`tpXTOBu<#hZ_ z8?8GD#H-?1znhF>eFLJy@0_oL3%#r3SeKAxVZ{x{9V?g&3c-VNC-~8SbA(Yrq7g+F z*dJFY&$HJj+aR84ci8hr0o5GsXOBx3*aw54n~t=lZ7FnoYtTyFP;mgVIbq0DC?7r+ zl59MZgziM*FdK~;$cHaDqm}ls+e-LB%s#^75pnqtg+=VYeh#t66=Z?Eg(k%fTITCd z;-HwuI_0YHKo!)amd~taX)jhp09EoT5ktReT+xp3tbDvQf`wTs+_1XTvVR4%NHJpm zvtw1oBNpTc_7-gto?qCoBAR~N6M%4G-TmT3oDa&}(G%@|GjT!YR@de`RTFT82ODhv z8a0M$KH{hj4X>{Iz|TSMsQ+v;JP~Sp&b$KqaCx$4Kg01--WN`3t+TwrBy3;PEv-Bm@n9o&2r9muaG#N(RJ1z zl-o#m?a5IAXK-6avK~Hr8zqMoOb+nM*nx!1^x;PkdG~#}2@id88=Vh>zUubI%BF%Qjud=bRJB zbZwb8D7Y z!Hx`nHhQf{_vSNTf#I%`^M={Cd?T>~3Y_1G4stZly<%f=#?khHvCjRDlWL4ALqjOf z@Mm=HKaFfq>Hdl5{+kiB%yP#CEyCVnDDY8vSp%^S@LpBnZ2FK$yUZbhF#H0hor)Py5scl0wAt+>vlU1yj zHU|pr6KI(wd|^IEMYtMW0{verGhwbS=C56kLkJeXe|MGDyK>2KH`4xvz3s-X7o%Hz zt9P7d{!j=E@lF@NZz_+0YbJT+3(DPUCL5P<_dkFKPG1vv%F) zA*^i?P5Tdiode&Ny7^ReDxQzOPVG(7ueMoRsJ-!jTRXn5PWWEE;ry$&uWa>lgEF`S zZ1jXC^!HgC=?z2bYdpcphr34ma^*(3DRk{1-(9V>e`30jrvhH(*osTc z8#6m2j-8DsGUD#7XEkM&wE9*%ANuU>_io(jBZ#1G64d*YCS}v4!$+8!)uHA3KUxJS zI#zUmYo!Eq=-SL#O=CSJtputHq4FvQ5L}XT@zCWVL)J@h+{cHQ$-wza>)F1zmt5G7 z+pF?&?V})X%=sEmx;Ue^TDt7= zcr#k{VuonWhJE=2>sgR*=W>7-IrANSw&E4VNe2c=7%X-w2u{&gq`TI={k2xRYt*XO zP-E!j8dcA)b~jlu?o1kPEX}8XH5KEYlZX1e|5iUv{Z#NYPdN0?v-pKrO@XbFfFEwI zjsh1_P_RG)48BLbHuw&C1fX0tU61U#{NpBUPqY|l=am||z|Ak=AE>chpi6-s!9QF8 zZnPyz9$(z?iTbj$nP1*)Qa=UtIydjP{HC@CiEG8U$E8r!X-(`O7$(hIqTvTWDDbLD z*NJae+7x+$nGlc}6iHiBnh{;3bo_918=lq^HNW)Wm$MccB#6G#Vuo+*;SGN;o$99W zPq+$+BvQ_t=ucQ1=`RCB!3bJYWJ@4(4^8@aZwR3F4r^^K+bmZh8S0I^7)qj6UeB#` z%bGaI(@Xdwj%Hc*7ujIH?L97B%VA$wJIuC!##%~M`vEL~25BSmjsm-`4jTkV7~w%4)y)10L*upB5p6xGE}`^$fd z>|uu;=E{_{m~OX?BoT6MQxLqdNWHPczDEH}(W=aOf1=oSeyA&*0f>qi-Zh@~#sySk z|(u2}s zRiAiTDP@0FPiusCu&08R=zY{Z%t)*Qvsh%?(L(ox?;VG`=1Qx#J*z;zY}EAz!sj?y zd-Y>B_e$mX#<=W|=t564T6+bWEIMORiCx4XE!e8(qu}S$?CU`1W#ZWcRLf~vG$ou z-e>-57v`9;t!8j5K24j~Nni;Agarz$O<#?nQ5I*mC_7CI4T2b7D)Tx*~&5psl#luy2!kHO& zHGh{5IM02CdqTKOI3};7(c@@PJP_}hjedWH>+$?_wzsz4@?WPH9HvQqcxWI5UFS{SL;K)OIl;jdwB}w-6MYo ze@jaK>nqB&`{$?)Q}cs%#Z;mBqC`QQuaCII)6uyQlb(&m|AMqYzcuO<^xb0FVkRsA z(2wE)iC{eV8S5hPU)4-=Ec*#p)>YUB8ujk}oU5nxKz>z-sVbP@KiitptID-&PLAcv zc5JC~?VQuw6eHz^5nk8UIqz{dny5>Dm25-X2#FE>xQ8mgR2$!D#+P=S<15)O%JEP> zBo<1Q&9L0X;CW|Tup|8|X8Z66jcclJ66P}7?@$UTJ|e8ZaWAQu;)SQ~wHCjrlwMs( z6bV}5>)boAftpTf)N3j6>E!$h2Z~q?4pTTix6i^#ztNt9;y|p;ewrV-Rc4*Q$oJJ2 zJoZ${l>@NP%7k4@kNZjxKRRsxy+s|Nr>G+gMqRLveZ%msBdX(jT?~3$AHk?ktC)yG{cDn-^-3Q#R}Tk z%1;CcuL&e=k&Jp8|CalG~#-RftLQY!g^!+xVB?VWe1EZ9sSE1$Jr z>6~JF0H3!>jGMMrI~wf2A2>;$c2pB=7itIj-Y(m{AX`zaAfNVAQ9+eeJp%{e;Fl>e zYWk2ZYBG}!FR73(1f2G~D0?CMZZ)H|&7Q(Ia}^E(Fpw4l8NNL~v3Nz6@Trt6;Tm8Acp4%1tin>DQ_o|OeG%+7BA>6C z-=SbH2S-_@Gqg=ItW3gZx!4J66FE++TkKB`o{UBB7L3WVe<|r(PzUUoKLJ+o=3N+_ z$QUt>J`U0}gPSGcseUKZth90i_f{*0 zgPG~@6&=3L&njIFa}B$I*AgF(j;l0QfhwE*+4k{C@?A6pAR*iBJt9C+J@TL7bA2(l zk5HFzuPo_sv;F7&!gDKy_);0!c-vEHlnQ$EmQ<}8FrEe+@wu95z!Sq#8Zg~wtlFD8 zs3HyfqGNs`;~hmj7M_yL2V(_UXzmDE9u*uni<|v4KX%bu?IY+!khxXl#eZqZ>c!kd ze=iR`^n)H;HLkSnR5`aVw4f+yLm|hbO3TKQ0$d>2u(Ug0sE#b#TD}MM7%E6Hz4q5yHOT=l{J9FNP922a@5*QIbO4Z?O32VMpX)6n9i4{D+;TSoW@V;Asj1@F; zxg9+AK;Tx7^<|}Xlq>)9&Dai4`FZ}K#!J0La9(Qv?oEY@c!I*w>3ROq{KA|@-%w38 zOOEm(KB;H`oOa6BdL_Pw-=B7L+gj2_@=*q4c=TFChtbK2?x9q^-R^;89rTSVOXk$} zi$7&F?r)P0tf9TC1NZ}~OIAs|)$olmPx)=AnD!FwFn7{`7E=gpFXBQJjy7`{=?4>P zau{HA(G#J*g~@q!t1!UF)g=Z>K1bBlvb336|Inzou@0PJJ7_^d?70eM2o-9J{+%OO z;HYBaVe-|nlqoKT_+Hhau-Hs^XacOa*j@)F&Gj0XqB9w&)qGyO*bs zLGf)@Ao4!ycc7dsqgJj*EvW{}!n{*1m1iezOM)BRiU>1a$hu|X;kuX=b$l$c>t)Rc z^_`HA|5RNf%;A%!8YNc@L{)bC_jAbY;etpm6kMv%gnj>AVaFp_k3iha{KH zB++LOZv;P+QlhrWs_Dx%g#6xEdVu9oWqr4`y5cu#(OjX7^28m#QmU;nD|*jA7iRbQvtIDu%~q-GSYrjB zqjTb$*$!eY^Hkj45Ln_ZzikMC8Ga$OA+|O06MhpFNu#=IVsUq`?0Hq$F)HJnemm=Y ziqsOmH5R#sgw7gADps%wNS3})ccDOtp+p&p#D`3E*{nWgT6NNYS%IZ$_Y8Y&^;xxf z#tJT_A{oYi0HiRWI0&7wmkHAWlZ8aX#{2Sj?7@G_$+U0f^1Z%S+xEo{MrM0j$wHEs+Yu{c6|>@ z0@3KV?3)J5eC~)-plCI?!)~Eyq%fXBa#Z&iP!Sn+(VH7l>+#K$;mlQY16#Nw+S|^d zK26Ph))$`g+dGu^=k_Gk5q3s}3S4rwG&va-td?#hxEZY%)t&yxakxl@{v&t^dun1c zzFG*+)v_%+Jj*Z9^kwM9a#=W~%GClXX^E4P`S?Jul9N%J>~r5mvW%j1EKnl69_p*D-8|ToG zC>vvoxlTyRCQl&__JpFKm?HXLTJA3UJ7mNy42sG5%*r$OLIGmuW-zR>=jRQT=TP1` z`e&H_Ddq=OPw^&5&Cvr(6-btfYRbo+p;*4DQ1>&?RNNUnh;rTrT0+AA9r;r&f2IWw zI{eoL4`$*i{A}+It7di!m9B1va79cMvM4ZPyMkBew5lId(#Z!^FAsR?pS3omah1VqkK&+OLNTd zRStXG<(x>_53;#y{Pt%jV~-P@0+oZ{7rFDxOygH?&mC1|{Yhkg+I}hcoTMqv4qRhB zA`6ejeP@eG@f}rAVdb4kKdhZBk|N7#kao1Xb}qaCmqI?`a9WS71d^?wH5=;`PH#n4 z-aqhj5Zzt2Iabi0YS>|D5<1uRI;5cTu{`U?@-b_x8QT+esvnwYEW3c!EzLB7@JYy* zR8x7usO!r!h<;~CwJqY{Q4nl)f;CrO1C*+v)_+2C34aq+)=p1_b2JifyhU(Jd6s?M zfaJud&*Zj~dKQD493WX%2dYYTO)%>F=OlvU65Xc>oB#TrVRLB zrZCyGn(xG$7JW!I+9F@Y^W`8{V6?BK)2JWx&G3X|bDE2Yq;N{}gcGb`rB~Fr_WE~5 zFEQ#B6IWz!ScbZ!gk4~cjQVz8cwUD60(saLXBhRZ@(x{U_oHn|CU zrB3nJ;FhqBm=!c2|B^wJEij#z#5$u9mb7WkCje*}N!h+?W`Se5`m-x=Hs|P3LdXi_ zO?c+bfz0Itq7mT$1}-09KZnj#f-+t6ZJ|s;M#O+%FOreU;PF_Xu)3sOTM{_5CBeu_ zu_TBNt14-nup+b2Tuy#776v)w`<<2S)V6%bVJ;t7jaGl%{h)xVDQEdDePVy_OFDgQRjTl^j_;2N+WWzCrT3ogB*v8AGW%(m|b`& z8 z?ZLFf;U1oSugT$lIETwP|Evy89HG&vM=gj}6xmnnQ@k&3)YWwcQ2IW?(jtmhaYjRV zJ2{aH>Zbg6iaaXY_|u?b3$apgLv}O7k7vv{nvFl9CA6jitQnfjL+9K1`$4F2^_SH1 zq|hk$8KYYHGZG5};#?yHV_Pp&bZIkZL7z!nDg+nC4V!(z_YM=zQ^wldeW1p;FQdlr zH`W+?8YC)Vf1F_Dr)IKee`LIZ-eptdIq)Yqu6boTUgg4ErLZ&XG+t_wsw=6~YBg@y z)p#H~x3$K&x3TLJpBl4U)2Onk#x(qVZ1!HB_5gHWb3A8Hn>lPJVGsis8n134U;Z^$ zI*5~1Wq1h`MT>YfCjpI3%$_!u@h+>evwc`&taVr$?{&dL8G;)Mn~ydc{sBbtNOv_= z6K~3_tw{5~Ux_P83IZR}aGKdbonvOEyXWRr&1}SjO8n9PGE_G|`kvyI5^~H+t1@4S z`u3rJ@<6{XT5;ZVp%uz6gbLjZ^kwCO+A=4>&i?dyv?iA zYGDtR5l@YYg-(rUSi6Ozpka+m4u~bv%e1DJ9jT3O6`JfnxogwL%6ZPwgwodP*kX9H zL6EmR)@V<2==e-?Xhw9}+VnU~**>(i8V}?)cI29kkpeT6;mO_X$=&J=@%g&V3r3n& z-wEN&o=ShkV^P!^&g=^q8>RXRqUX)`za`)`-rRQSO*WndZo<+E8ZZ87ggiEK+*3zh z%bEFep^S3e8!rBvLe<3Koyx!JPS!IgYrB&biyJa*IU7*x^>(6$?EMgp>nvbCG{aN+ z)P%f;?DMChIIym|XUH(tS7+htEH`u&TKpny!gkeuV6zhC48iO_pDBd%9xhfdSsT^l$A-L&|6r*Z93OP5APtLdPUwWt8K(2EAyn! znU>3=tKA6xh5Vxvvbmv?1DU5{X0O0Sx-W-O+i9`?eCKH}`(1wZn^AbL z1sA*W`b*2tCmti}1yf#@mN%XfPc^gQs3)J6W8#pRA01?05U=TpWKFht1G6SAP>eU2 zs^#)BNQHWkI6CvS+g*9jZRKmz^*FtUlrnXkl!`UI9NQxn7!w@Vmt~!f*oXc7rOFZ<7|T`EQxDbkgaO#8b=*--B<_q1v}i)zV;2t*X_*f z#k-Fhx;SqhbGE%CBeQo+T0U6Wk|k?mLcT1Cyx^q5?3M||QV{LO0|KoHMPy`vzY55j zkRP0xP1+$?khH^MMzmhIl9vnOA}c>yY1xXe!?oZpe?O5y^!DKA^gKBTh;;K}y-m(Y z@oWPHlna4eKY85k&d7N{=fnb8YR`@$ zy}7Np2x&$Y20|SD+@{)IVg;2T7elevz%bd(;3|6yIe8VrtQz&{B2w#HHe zXeF@0KPWNkb4tW+7QCcQ)wmOpb9UZq;9p>Y%;zk9*!~bI8<(;?aqa02+b}Y{`kr!l zg&oR38CM@~op_6BC=w^Im9ee<+#2ws2e!biei7_70J<3^PofShG?qURncmah)d=n( z&)2wjf|EGYL`#jOatESYThZ0pe_Ru9Z3Ht4iV+P6+OZkzw4d9e(XJ?gb`@XuP>!Q_ z{{%T@e^XB8uSLI+JeiMNaLUQtK8t5Lp2tt-@?uW%c+S~eAI}9@{x`>S){Pu_+=?zM zyb%MhB83@7{aZDz)<7oI%ez`M&v=>(`{Zo@fv9EjjZ9zkyfreUf;?_@6XdZPV+B_| zpuIWxokl$cMt!4Ezjc^QgDm}jJN`x0*45zbr_~n6owIOi#&F^ghAn)%gt~LQg-^^( zdl#x(9_wa8a!+M3qS^g^26&a0Hmu34eXqvD)v0Jd^sACvXM~L663u?|9k$T6_*R6> zLiSO&GKoVem{zIopSE2I-l@oE9V}zt^WdTvzn#BB*dUH*5S#j^ke7k_+jjehHhKzPYh$e7F?`&Jk0sXB#r9i0WHHDsqrHQq zMTs&6yN6{-bJ_d3eO8Snc!@c^SvdyaqsZIR@QIE){7Tn5KI;vyQN5AuT*Q{rx?UV+ zR7(~OjPA3Y)Eq2#26F9L>T`K~PK4ejcH`UaX4TYR&?;p~(<)$?fyKMDUcY z0IXgL(;&<}cUjbRb+U5d`?(&KAE6_%1kbczqJlWVn2AH7q^-ldqJ`6C>!9~~cp-Ll zbXoGzvZ%7qQyEf;9(dKPhG~Cwx+ zQu44W$%qcBJ+N546Ybjt(@Wk?FRw*mElVBmh<)6-Z(zf@X$>fdNkaq^KpHyK931!g zluE9dEGuk(v zgC7NSb8eFNAgJlj_YV96+POJU4EbjdG45@RW>T2{nQ7d|@qf(B)&iVf&upv=XS$pD zA_9neTe}L)xml{PzuV8PSwnvG0~GGr1FXEEG+0=P&FQ|1yni)9JJ9$^-f0xFp;sZj zXOd^A+YAIcSd8on=#5|Y{EVS}zy$OXgb@23!Je_im1sZv*GPI362K|dFsS#*ed^-^ zD>TV2+^DHB8`x@L0@4DDje4zBmbeX?H${Z3>h3g8XsvK$|C9iY!%D26Q~8+j58#?*L7Gv=%0>fgAKp(LW&0v`^29mGkEBO#>aI|Q zU+K>+>*&w?jJQ05``%$y+(lmiu;RyI&V>oEZ&%Ar?2jbwjSzjcAIOwgm4!Z6-oHYq zpE&Kmx5%(gDkA4oowHl#j3CF>IgL7p=n;AE>YPk*vEK5`m# z&iy*)PI9*EoI7;RY;rc}oT)lz0Xb`R&IFZX)iUN}{!wRMs56!9!IigCXAaPr3TIq- zKh&9-l9|}APCYwxX?1aL4c8!UIFBH?fCPVm-1nHT;wNqfE>K9qCkex2z0U#ccgs0z zPC)T$tsIQizG-i_)E@rCI4%r{jd){u}w+WS@_7D~ST)to| zy##ed5haaLfX4(-=}Alk5P5QR8?e?ofi>3@P-kU$BJzgn!*~(<2vk>>v-W_Y;&d6G zWo!D&V99Ev9G8sM+`YHpqx@Kr0vKVg5!?WbuGR@zp8C1ZcPt3QFXi5(?b`5ua;K!IFm zuDSly;??nDbIlEj%BQBh{gY(zHHqTuQ;Hu*7GIkvz9FUfW{UOXCR=c)OdlY+=VKIr zn%YDYX9Ms_5@3J=P*a-#SO7p5f*d=$`}96iOH+V}CM$Ve!N>$An(>INGGP9agn0p& z+;($~%wlEu5ly7K&GVxI)9i2$di}qQO6E@q> zxbIUNDP2y8?56Uw0?|kzG*y8>nfeW;|#MU zvzQeux48Z+vn5N?fY|cGS&Be&)c5^%^@u{8c+O+he_uXsk82V-tqSdnNmqr|$$M3y z=LEhg^pZenD>64*7?&vGAM8QW?L@EEEckz1=RS9J-qyFUn68C5Ue!<+@Tuz@}-q@YVlJuH2(%353+CAZ8>WK1)Kp z4g~9Vpsd%|5Mv@~mgK9jQEWsJq;g+bvc2_^b-W=JXD6T7{ZT+PO^fWztl-qkMmiboMDD8C{||MX6Pd3x`X!rrxhbh!p^0|iPaN> zX=265d;ej@%womNO!vc>{u33#Hs#yD(TPI)8J#Gyf2b29>=imu zYA;cVT>E~V;kIY%gwMW1C-6U`6VvReIx)kp(uq6m2|7`3kI{+Q_Qg7}z#gFziZ!wa z>9o*lJ71?Cmvp91KPBm7uS%<}m6HBQr=OQ}hfcpB>DP67wWM2hx3U(o3` zN&i}>)sR1>(;brks7?!!vTJqvu%!JueN57K>a=jD_ANS{E$JyboiAyRP8UkLT&Ig9 zeSuDokaUqwmrA<7PRkL&&emyRo9utRqWUh2&pxcvQzZR?PTwi%cAcIr>DP36futLB zx>nME)#>GueqN^^m-I6_Jwwuu>-0)VFV*SiCA~nWUy$@YIxW1SJwvA(Bz>Juw@TWl z(@#lytWLK{x>TpzC0(r39g;58X0{XwToC4Z$(i)y9)gigC9yDMKF>UrTFZGV7#a?KQm5XycW52zDB0so}64ZNg}04EPg?Z}GI2bXD0 zi&m*y;Z|E%QIWBVlHMQSh2-}hz7uV43El#v0><9Tzn8tYm3P zd8syUr+G>jC%MNa?g(cWP1Qco+&=3s($+4s1*Nz)QttMk=CLPfMDX@woF*=&ZCFCL z`9jO2{}=&e3*(1C8&MLcpu?K^e6_!D##iNg!;?`&+!WuT;Q5d@wcF3?QuO!OxB$7N ztBTxqdkLjvmT88PFBBze7lwYOE*+gL9g$k<)uopvOG{HrhwD--W4c<52%m4}>5}tv z+xeb5wOqb=h^tvzG%{JMFSXX4y0nBm_4*Vw1OiKM?H6_F1<7}(rM~+kT{5aPdqGTzmIC>VO%`RO!Az3;*wREs9^(0Fdq?X3Gn5DnoMCr0xW<3?) zT@5fX2_XAOD!{86;EE)GY%Zw)&u9P{NEx(cvf(HUqV4jM{h$V@OxCcnTMaj9035~3 z0gNhSZ%X|{g$9_E1dt6Y6`)W9R3!mq7fS``?4!m(RD$&<8oB|zsR1S@0c5{Rt>JGP z;2TK**#uJop3ng0NdVayQvv2`0D>vS+tASs;2I4uhL_YZ$QF9aNM5V~T*(?_V@>@; zz6KbZ1d!b}72r_58i#R703kuC0NXXdHc-sR&xUQ&n>(Fibl& zX$tI00a5_7yM5;@4S+FV9I+O312~R^p3W%ZtZJz32GFhnl7xEM@@@e28X!rlmp$GM z;Ku-{s%KEZw-nt@9gKjkVT1x&2~hU|y-ow*#V$bwx_zQd10-qpvKP7m^wj_*$r@I7 z131DVhPEXs__Bs>0Bsr|NyL}6b^}o> zfEuI@3TUmO?5QJJqHE})>2|joax_2}O+VZXAcB?vHFweUW8DB+HGq=QskWrSA*8n9 zw;G^}re}8pctitq(e(Uo0Jm#^E}CB04Zx!Tx@dY)H-KRppo^xD=mwAhfNFgy1@!k6 zZb5d|1NikJzl)}qcdMa619Z`JcQ=4%H9!|l_jLnUqyfexadJvGfaw~bi>6QO1~66w zbkXz~-2et^fG(PTXE%To=pWF{E}A~O8^B%-&_&Z1bOTrofEvkK3KUhMK1Ja*QrJ)G z8oFru@@_TE(*Wls$KmmA08=$U7fpYv8^CA{FgRJm%5DJtG=L)Is^1NfBde|bBF zWWUf2WCtL*sNg9T_%2N?tyb(7)8sB&T9{r~&Te-JGZ0>U>PKTkX+$0~>dhQ(`g)e_ zvyQ2F6lUXr{E&BpW%gL|p{R0(ytZX#EIAar9HRfq5VmVyXlk1$RNWr(e#Fn=@Z5B7 z*kAm?l302Jx3TAQOKde)+)`(wwBguP>Du(rr;&PY8{pV&nD&?HP+H_U$*{b(*V-Vl zxP2jShvgiIP%X5uA=c`#q9Jc)pIPqLt8!EZ4xVZj??4Xq<}pk3VbDR-oMvldEchNx^=rd#t)@x-LAGu*P9Ck zSHy^|3J+%CUjK!+O8hL_{eE>4^@D1Z3_kW}I8Iu5ClNMTjU~<#{JM@U>>nRWMp}>N zbqIl6$BoA>W^79^DI*@Qmw*y7b&WDbKdH9fMH`6GL~YfU5w+u;{?ci+TE|uw$q4R# zuLO@7hs{nrRC6_Cwe7aiwl{Md&0)KU@@s~;S#f8g9$r=QZh&6BVTK>f@P_9)s;w>P zzgKqdt#&m%RDfZLukpQ%E5n&9tSYA+sw%Lf&ha4-qN-%m{ckfOXePWZ_rZx7XpJ}K zxYJY8j@u5as?KI+_iB4PlZMO8?o6Fo^RzR25B47^Gb?B#Gm9@gHM0kq**`L~sOyI_ z^W!ttG&h4zhR4SyhA7mtTZ}ZiNG4YxQ|1=PV=k5b>%&96lDrmFS3@^fOXJch&d!_66Lj@v<(D?Fj z5??Yyx4g;%I(h#)9?O|eyR3KdUK72KrwpEqwE=sG$J*_2wD9o~8(nQaj(TfykebY4 z4AL$$geMIY>UO^u|M+hGaT%pbx{~toE@bWcxX*&pm7Ke55d*X0H4_A!zCn~GxcTwq zHW0^#0#B~jCU|Wi*Aj9#J~NaN%?=(b3OGEW46$3TJ|=45X@5t|iwXFQ_zeiM+y{N9 z+<<%?x;+L3>HmRr`@x0(mu?H)zWHa}==QfB(scVKe*Z7smL2*3hjhE{X`$OsKae1f z|8wYe7HxuV|MUJt)Bb1C?b)=ei*A31r~i-X_J<4p4c*>F!PlePzWra1ZWpHdn!x<% zIOazy*(YGO>+VVrZPaiAi!px+RsYZvo<#h>>fgdkKUo!?y1yng{V_bvQDkw)9Gbq2 zYi2l0>oZ&{;HK$Jd&oN{6KaXCou||m*W+anZ8o#EylDP_N@HCbk*Utp5__NVtERb5 zEZ3q3%oX|kivPC9a^Mb)rT9GrX*SEi= zPI&wq&wuGJu01iq`2JWvS$o2}s8{X5+srXLjb$ZdD8IFlN-lD%OB$7BN@Oe#Dc_F{ zmG2a(@8qR?C+aXAU0>RVBS@dMT!fF|vGDjEW3%V?Q*oGd#e6IB z1|{8J%3tG@QBYSXk-q{^d!p2+`&7nCK-O>5u?BFR-3U@jC|Dy z7)#G4NoD?5BZu|-W3!D%?k4lJFV&tX@t-a@mdcdXp6F>T+Y6)~2hO1!FtGNF^e~n_Bb~$$XRiDiuV(+Rk`+8o-+iUWMziUqnUvQ_n2ZAbj*98aNR)i{zIf}6#~zk?mVEg_6!qpuZ|A`mzOVu!m z;Miy^y_~%Jdy{*803z7=jucc(|6w2#)L5?|1_QC4R@P$bxtQ7rY!KXZo!R&$&NBkf z20OBhrAI(6-&5wxf?PVTHK$ahD*eANbPFTgV`zGPji>AY$<5f7zR!^?U6g~3ptzqV#le2M z5TCVQ(#jgItI1eat)ACkuAk@kqPk|f6RDIp(B3Yp@j5njdRxG;#esem)0+dmE2ggx z^rX+5BVs8e+RJAspz)~q1JtwPrp!QQ#aaHpLUuVutTNZiqW6TRLgscYx(7p4giZ^Y zp*h*e62w3AuuVS4ajVU!&%$;Bnr*BiJKYl=o$YZQ78$^ixjjr}R%bNO zcwBet30to$VX*{Wbh)Q)Phd2)zGzxIy^dXt2ZwkanEG#Rj0~ae1LCsbfn z$onE4tFI9g;uiJyZYjV2HZf(fzNqPJ$Ea7#cs)x4tNc*Zle*$2b7w@V>=Q$8`Zw9tva75**f&RWqdE3n0gyrli=|D6S1KU-2(|cB96Z6|V zKi?FCV$c(3fgFni;LV>gK*woxx#j&^X!@T?ox^);Leu}o3oV3h=8J1&{-PLvJEZnC zP#Fg(_BR=-c>2#8qrsWRxr2HC&)5lXpm9Vl^RBnNFH(zlbI98m?O$Vdz6}zsAJ{Og z#hF$cTO9JX$l|E`1pPnD+hWvDU2j!4S_?OV&e2P)#5z{f8$A~TtNPu_;91FGRNtdU z*K&Uu0)bT8``ema?_)J)$em+h-5$y}L%8}5EnttTj>+lpy*K54{+VL6VJ+FPlD877 zaoRmk+&&INbNob#u3UGwl4)#U2_5x6oK4%~UMg6leZ)T$UNCS;A^!9NDD8*(M7LF9 zwj|yr$Nw8|lK|Pjf1O&-p*7LxvC#P=vPBjzemc_e4@+o_k}ZNn{yt(Ir3*6qP~wl& zHQb+xRb;c;CebjvO8Fm9t>1!?fNIqFhyXAX=;J?wX7s6X5#Xs(>;#PZd>oquJ`tZ* z0OsT14aX)sk0pHGclX~>M9VIcAvsfQr22|q4QEYgKok!fga9RFf3Ul2Y#txnH8v?8 zJO+sekGStmN5c2!MdHOH5*;C4JTOEmWacQlSxg{OJb8SeJcdxFU3uKgs#UH$a%)1j zTzyjc@_1ZY@hxeEjAbMMi1tOIbl!W~KYUxJe^NG=Zoy*?;|XFP6xxf(EWs4b0?Qio3pD|9{vPRz( z5>eI=x)#&uycY$>!c!dfm9QY46Y|sGCH#gY_=3O3(Fyrkfz05{e0CJEs5+&+@9(2& zDQ#uk|DS8vbF#BZ!~P7nMl&GKUCmIkZT6Lf&*mi`HP8>3?4obQne3&-FQ}a3cF&V1 zW9!`V5Pr%{?^Nh>oQznL26bX;uw&q^CGR;8$6`yGGPwM-GZ=@mk43vZG%J5K@M#f0 zLm~5`tj_H7u~;+LiCQ)oUH3V^)&vy{92?H<*d*y1GgOV~QsWDB091K_$R#^p#3W6?(*?$k7+=Mp4XsTv~AktzaB7jJhQ}R?O<}cUR4n z$Qkikk8e`7mINoU3sa@{D^(KL*j^7oqcLXWZMsHv>4D1x_%+%=_DEhP4%QAk`?N1V ztX?+i{>HnQ*{(_BtznJq&`T$(96b!?npzrox{-Je>rv^?FX5z;?cV#6>SUdRDvY(W z@_SayD)f()6a)UEj7Uwzg+|>6)F~~y7cLVfkG{w#iK@^?=qpLBO+Z90q87%+Sh_^P z=i1){-Zi0rz%MWVo!Xe%(R|$cT!_Wl&>W$PaW6~ra%zGHzg-hNfqSLcCR}`2x%QXs zRB+gTN4FLQu9pfsC_J?_-%_pdmq*spfbQ>{Bk%m-EANcdJ*X2FoN;ZmiLr=-VxRS> z#$vXHmNq$nK2zKP2(rTwItIu4%F%R}7YSJrMfUDOOl`Vnt~*`k?@pKb#OX2@pDy!m z$<%96qI#Dy_N>8YZc47fB9(L8t~(*E7o%gn2F*1Kq^pw(lPfS~z0~6Pmr2SQIzg|$ zs3(alfBdV$@ewkNx9{n`WY)@}wBI?dU`j#d%x;6Jn!{i|!1+Y>S)Vj-$p&dRmQ=yp zFiYwhHv3Wh1F_X5XiYNI&{6RoqCyS%udk`N7&my~f)Sta}CpmqZt9Lpp=`GZYrVLib;o*0{#3yX63b{RVHb&e_Tt?UO{;Gx61A673qpPrUP zfDUphm5n`4OYKF+aJW(SK^zIN%c!NeD*Unx4PI{u>M=7Pu4K3`lvNcfW7jY8_cyT< zKZA{`CL%0Ui+wh&^H~llG?va$_?5-TDc~&o4~%!zX-@?Q@cxk>;Kn@fUvJBs&1>C! z%-)}^2pt0d#9PMFbEw6h!<+Jov9yNA%JBEoRNcGnFCoGf?l6s|)#QYi7h>5KJf3bm z@=YG`RTe9lbh+9KmX4A)u*b^?ovj??HuFJW_-}%BmDUcp&GYOR;H0WiriXMXY*qGu zooblth66|N7dHm6Yh~k*GCvMEyrqXuX6UM0KQhe1yhT{#4`-S3b^trhZieH5GKa^k0KE+Nj?tALEeV%keQ&!orChd~G zb>ky1BeP8Lk%~)%nS_xH-jSImJSF}(6({+%ct_1RHZd$~=`IH6FS{77EWsLo9=|MR zzw>BTR=^P)&gdtdOr6^1Irv{hHs_WRLqGRPe8!dSQnW6?{QeL!lEx9>BA@j`0Rt1{ zbm2pq828F>THbbZ$huA{4d-1&OX5u|q=`qfGP^e^fiuu{r6Yl_mL$@=aqU--X5D8p z&M!z~?7v9bN+QmFzGY2@qwJ0~?WbbR{4vszqo78fC-e=?Up^qswJ@qtn6vqhnjHLr zv9%^Dma0f&VQ0IwRk+ozy)srXocbW$FZwKmJc4*D)a!xVC5G^pp<6SfGmmCv1itO5 znAhJws%qv$IL0_=%PR^;3xh^R=vGWzdfR>AGF$|;DwFpvw2Y&TIOrktH#^$(9|{(q zg{Lp^ridGinf!ppQH-ra2Jc&0Dg5BizE+;PsMzYfZm;c&3zkF z+*8+_m{~t4YcB4$LH1Q4FN7UTV#^E-g-wmnV*NVajqzcVWukWN0SC`J4t* zQfIchT$&x|IW(@Se{-^fzx{7DLOB%^3j>#gr=&-R1Q)S}OM{F0r};-F!D=DRk#n{%6KcM|Y-U(EHUffabs|YrzAN`l88-hF z=ltx|$9b-Cw3!4L$9;gD?9E_9n+G3yEa(lWXNYf(l(EDSNLdPBb*=DKlfk++*na!5 zL(*SAYGDPfJPV)nkje@SwXVuOm8Xgo6nsNnKcMQcKC9ccz+`YQue6MC<~M&*(zNrKZ>C*keO}r4kIYF{|MTqf z-zjvbmn=JT5qUdC74LD5ZuufSBEX%*b}o&e_M?^nEGY>N%n zBe=Z10|OTY5Agj8crM(gyxK=SaoDczuonuO*;6IYQ>^Cg9Y&qpmRJRSskln3Yg2zM zj2o5TMdiZwECb{;)mECr z?NB^$te{wz4W=IHhbMg17Tn~tvGCu7M^7`+Jo>!VEOTyc`6G{bG|ekjuUyG1 zt3j)@$Zr0SeX)GbwcS6{S8?em(*B!b1?S2~th}?ONE`wc@T~k`?DLP6rhOx}TYk{i z=h$Md5wA!>%FC6d7zd=!84ok|CLmcy@lKW==wYn=xFG7L&c8gUKQ}s7uwMEE%=xi4 zXqBXf0PvGIK)+bQ&*K2_Svxe0m3KGAv4W-Xl6;S~t=ih4BW=XmG|q~rG!6r;Vk0X~ z=foisL7q7nsr?f}>_q&Z;JACKjy?_^c(-)*i2q(Zw*=1iRSfP+hJS|ra=zN^puB^R zi82DWQIq7nI#CXhXZ%QL%rOzQAQvmMd&n~$_Y29X9a}LjV5lSGoAzCO)I1UYt2sML zXC2~R+tJb$my68^A1`_{QhR(iort|~P7P|loZo|>KU5)qVhPU zZ_l`-Y4KQQCQQVZnqe&MyYY-YVF(*Qjd$1^a%h&N>JI=O8= zfu7{lRaL0Ms2k@2fZ$DxTjt8}=#aT4t(NCd03k|6Z|<5W%3X60UzoGE*O0qrggN|E zcg=wvW=V6%+ta9@%w4nh2rYlwsNc)|@-|- zHyXi(8335BZANe|Df89%wevP(nOsA^tZtog(>T8$wF&M3BKPKz8|6J1_H($G+*-Hr zP+$Of7U&PcNyxU_kHo>m8HC(X_g7$xvI9i&sL2dCJr(Eq|7cn#*@O3RK=fFL>SBv- z~HA}vbvz*uQeqC(wqgGVB*2Vczr!d~7k~V%wZN zYI+i|RrFJ$9(ecGcygrM}%eyb+CGMwM1~LdoqQi7$HR6$tW<<^8W%MD_ zdL0vq(9{nJVE0>DM0HItXn3#ZTKZYFE~8oTx-9P@?!7NhOJg;F$Bo9rFA2(-j;(qb zQS;N@@YOL^D#Mq~7)DqGTas(TQ)ctr1Q>HSETR^NiPl9>UB#GC%HU+F(Bs;U8V@OR zty&Xa*OvJ`dFxQbtx#NUUE?dEpR9!5tb`o35+dg+fX#sd4G;_Tf*buJ(1X97{#Wn_ zEsMakju6Bw7Q2$m!0Xs9%K)2;sd^cBQ~_X(0}S_(EmM+{&*Qg!=lpi#?hb13JLTV z6$_32CY#TH#D8xR|CQDQxX?O>d-2Y9#E!>$9W{zgaW#rVQMW>WZ|*j=k7&$S_}+#7 z(LwU=KrC<)+81$zSL@gEKFe&qSQBzELM{HmPk9`NWv2SqR8;>&nXH6;dHC>;jOFYE zB{{UZKxjOuc*F`ELK(*sp7NQ;xau%&=Ai?TldKK3@i~sl)Y(HIUY^{B+#`-%)esiK zi+iK2H0aCymzbSlYzWC#>g%_oBmyuaz z?Gfd$@4rr4#G5=Myj4CI8Dcd-H?dnFUZ&c*r~(}ts|f(Ifgyw444{Z8@p!_;`J!Xv zdQULBWA0F)+gPKBO^(oeG-&2JP|G2#B|L@@(D+_hoYtP(I%G#pyBwlBxWJ!rxcHzlO~W zPT}eExQe@Y7_C=6z=IzlkP$bF{27sEs#6N*wKn7dv`6lS-5&847b|eeJ0a&}sVca^ zm*ng5>7fOUA}-;3`DU;PHNzPMgbvQgPOG-sL{JiWd9oXR9Inb__SGz$P#*vlw&&2?jF!3gHN?&>%>eL_na)DpP3LtJn2WS*uotVjN4#_E`huji?LO#0pYx0qt~@T%3c$2&@l^z6M4&LWfpV$&}f5{gFwo5 z!R7Wi)@p;v!RXQ{+EfGS!4+KIZ##rt78+bkj4U`nkMxVg@M!lpd63uEvas= zYLqv0*4J%RrQ@SSuVOolI%I1xGx$JuT40RVB3cEJeXRyBW7m;S42t*ig?h-p5bnPk zX$0YKAu|rl^N2Q*sK~Ug$&M>Z*6j|Id#xN@7rKFsvi$8KYF*3gvZ3VelnT()tK01- zl!Y2)Gjt8(m2e%5M$t_Kbk(;g`Reqi<=H{@gZoWUK1w>-@)1ppwhi&&D4KCqD zTiv9YoOjv1uJaW1O%>9_|0M&~E)xmu{4wTUtDQzd|MGPWj)j35~R_E1qIC ziNoE^L{BCdNfkU*FZ&1b);aRwR!llhswDb+fA+~iwh895Pk2IZb$EP6coK|uC<9-! z)fTRPLA*{l-1gv!p7VMT*Xo9-M7Jshgy1HGbZN+tZQJMCF=w~@=}o~%`&>R2nGTD^ z(}+qu&$4@_^Dmoc*qcyKQJR$eYBr z3tG+Fr{aF?v}^8V{)A~2DL{_6tY^@p^ZMFr{*aV%)!-mb;-i9MNx!yzmCxoqA~u-7 z>qJStL>!O5)C&>4+(E6IeKKaeq@#Orx3`K%389GV@N8rbnMkmAm$c*Hwp_(VLXjc3 zvK1`)(rQjf5s;wWBT)nWDxNxu2Au5U_XWt`<>J#V9tsHdUbf4gz`+%@NAwGL7D-C3UHm<2)Qv@C5^rhUjSQSdQo5$q05S=Pf&V7n17F1i?wG4>$ZTE)AF!7f{ zDSg%tis0yF2;7WZIm3ewq;2MErNw}NYJ}LI+r99Q%$PdD(@rLx8#B)FxmQ+^I2KpV zjc0M&eag+7%stmGTtK7>lOSfM74hmj1IP^;>tL~X?>_dsWIunyMJ+y^!?Hc{`JV7j zCxge%nZM7dzZf}e_(qP-_hm=X;x0p^m0?ujn}4A$Jr33cPmT&WgWEEq5UP_U zfh5?g`yt=3p@EA8JdM$y@@#Wm4g($?Z`3<#g7&l;vu>kgB6mrPjxyIFfMfSQnJ-7p z?eY}gD7KljYwwrtb&<(%^aFo_%HofF)aiEuSgBmrG!_=3?4_tA~n zfwRb~G`w$@#iBQv#;TJJd;zGDh_2ww6I%>WW?(RX(*t9yjlqr#fA$i(o>n_Qo5l}! zot!t!4m~f!Ejxk0`JI^ZNAuh(HWp_bZ66rx-0vX1Z%pF*4xv25pV7HrG*={MB2+n* z&w~I*^4W*G@SRzoT@;#aMh*$SAs7=7G9QsY^*)0T02wggrmheFxDhRSUuBzhFO7i@p z?N3h#a{BMH`}{V6=5i6ii_n96P8*358xp_VJiet2YHUAkgy}pYIu6v-SQR34$)yK* z3=Gf^*Jy}6afoMuV0apMtg?>Eei8OrJxpsGgHy6i>bTrD^9W8hRHWB!_Jl9g`axFj zs2$s595)Y)j=Ov;hDOiII3+0|LC>vA?~<=DE{$I}I`BoHoz=jL=6% z?R~RUye7ZDvSRE}|JlCq2fIzIrmc8T>My zhSEu`+joCP=f3cS3|F)9=sZxj3dM-zhpSu-MsNnX8avo9PheK0K6s^|`OK}p&;_md zR&C9u=E#FIm&!dA`0?=15i+}Y;mMf3=nMNY>~SjvkHmqW|2irCHl=DW-s%fa$*@n} zq6Qr#AR5_LU&$MljyEJcZ;X(0AF#&Xj1}C#8UfXMvqJ6NL~u!j4c=-myjzcMu2ejm z2O4CxM4m(aO>(}ab0VvGmIH=dIuRrm>Rx1j=M#=Z-D6rPH~Xh-Pw<@fXSjV&>`g0W z$h-C?k7|xu!$-LA)O*w7l)Y(K7eE^Ta!tyG3}J3d<ec`9#USKf~k zdE&D<4)<^(?=uEk=NS(RE+_K$rQ}~j{@NODzf{eQDJA78Z^$Z6)Px`NWKF_CCGy3h zYV8yp2UF9W2NSuXfWx<7rs6n zeNiFOe}qc|E1+V@`z`QID_fMpttqauYc<$6qDm|AXCn*;)FcrHO!KSOUbt}35RIZX zJNg~C5-88UKwoGb)2a0v8~ZFKt9(oIKNnPbdydypw{lwh3Zirgy^!k z6H8Kzis-bPb0d*Od8znW(-qF+YQnd(&cKf6qUQu-W!~Wv9;7TLoXrT#f$d zKg<>UPx|aEHD|`;WpvL3tO|gAPvdU5MDz!7SlnLtA-f#o;+ruA^kJ{01 zbeqnu`TSqxy$gJtM|C$mE6eigX0L3?mVAlViJi!am8>0;D9%m3MoxU$*h*p`Ag#1( zOR+AS)yk1W5|kS_gn%%Ynrj86txKUbDYOoytx8iclz>P>Yg#BOq*Q4`t2a&Gx^JO* z|7XsBo}FE-9G9=(_kO?MJNiAE{m+~^bLPyM`|LhW-xq3cPrWw~W=yzJX)VsyWX{bZ zKlQE_Nb%Bl|KaDa1<^L{rLW?;5w5*Cbv(7bMRpfpDvw*c!e{h;kL&Dn+v@19C#~V& z%c8^hE^vD4Z8UVzg2(y67QE}_(Hrl^cLwmD!Ks?B7ZDH59yJhpGV;V7F??=*;*Q2g z9~=%1;eBO~k3d@7t`n<%=_X10gV?rxlF{9Z9ePwuuCI^Ocqa|c~v)Yf;S8+bPM zmY2R5gj2^cE&Rs|!|g4_x4iUtVR(EhgP<82ZtdC)hJW1pWZf^@O`h6sOnsyn-7}c< zU`+v=e(5J!C!&f{{Zo9s!$#pHmYXXvnB~;?#O}28jW{pCgDJx9#;Gxz}p(9 z#*qM{dF9hsBmdddM+Q+>Q>UIqxBui*lStnBg#D3?sgK*B-Em-hnGHuFa#JbL_|@ah z+nez+N?RXZ_|&>biq!tp9cuAtSW1KP%a47{ zoNRviXGTozMc9nyt@XCCSQKo%Lw5%M*%sNWF0ZlwJ2px^5wL=yrYD04(Ze$`Gnx7( z!kmh{;Ut$Hc5wCA)e`Xa82c{IJUe;x!48uRV*>gJIpxLbx2J5abq2XxmC2Ui)SjYg z#00cTuaq=89%H71by({Yb3d~s_qT=Y$Kuzr{yPS{*XpiEJ%4TPjR?R>Q-Rd!z9Dp2lHnIn^!1_cocDV+;_KOl*}3Fo{YP8} ztbXSWl4aE&%jL)?=9Z&4uho4NeT=M$O630M+<&bDg?xkNJFc8hReutxUTXW%&#{XA z|ISUu<$5hHjMJ~WUGY-->*(J^|4#b-^dF=D3Hqn$pP~N({qNI%nSSX$&F3Qe>*#Ny zzlVM&{bBm=rvC~0U!eai{g>&N?pOX1`WMk(NB3@a3Yf(Qbz%KmNh}?}brnyG_b@WFWK2E=u;ZgdA z;Su^#`Z4<0%(8sr^j&_=pBfC=_|e}`|LnXHi^KP+@93N#e?-GKHqEhgji1qUF20!m zzEcP8l5iZ;nI1gjrqqnfJEP!S9L5w=i)US^)U5j-bIe$q@;^=A+@ZLhek1)>`W^Js z^pDX$LH`u}GxR6vpQHcWH@}IicJk9k<2Q?3kvlcNopYH!>p&(Igc@__zV^L$Zr`_W=eF&Z4tVR{Jv(;Z(jMR3)@tK-?R7x;Y)cGw zcMc>n$=!+m#GzCM+|~>Ky+=}+-o(-N*m`6M+?Gjn9Zn^;Ci+sD#LoU~D$}13f$(Jt z8^15rpG;+T4$Mcd$m&K~XlZS!wWHPWWok15ztM8ke=VU>YnNkeAFZ@+=a1KG zdzhd_Yd6HA5CR40~v_YT#_$G2l;ip4!@p( z!E7d#=yOGKII6(`|M3F;Y4V>Y|B+eBIcSZ+n9iPlo5hh#mo?+|;cGTtne6R#`TFL) zBhiJ*IBKIH25cmn9TzA zb4yC`?r3A8^`#~X-**|)X`$b?_Y6e0OBF>MV{0XHXa8U}(c5dSIl5;c8{IK5)Srwt zu8$RoM_bPfrLz*d-ljIj=`Xs!JCR8xqq}-K^Vw`r!W})msr-nmZ3J~2-7(bPB`qqS zW+QVEInmw^Cb|lkyulIdWIg2QAmlY`%^icOOcXuX!Jb3WZ9SQkt;wjP2Fo z*8q&@eC(*tJNgry&}eobdS9j|o68s#-h)aV1i=Q; zwA2?YIwL)K^hgG^k5MFg5C-3g(c@6YTDJ%bdeL`VcPg4m-8+=R7?Ff>oR#$q0(7A# zM#~UI-`9gGMoCf4u6K?m&`=73kSsIQ->>D~fVyhywwye+Vj+nmr~p@iL)o6*p6pRk zVKACg#=|N)#KhZ}QT32UATg(P&wl01vBcx}riqzf~JY2g)zR6S;CIFEKL=|`J-?A>+ z2_bh6z*Dvz zq<|gO>(k}N_d;Um+vB%;D4QBCBysK4qsvJJy?V?Ks!gB-(&n`Ti#Bf55*DR9*aM5+ zc3}PbC_3}xedy4I-j>y)m*#?=bWqwMtN&yo+N)h;&1Sa2_0AcYP#gF{_i zsT3?tYfI`5v$6dCX``5+b-DhoD_1jnyM}s)2BZ6Eoamcf^%=28Tj|QZE75Q5U?839 zhrL+aLzfZ^V}6p7rJ329vi4nE~{I zeS^7v5cQm}NwgteIK8&O3#Yf;exdxc%fs>Zg88r4rhMV_YS=k@w2fwe7IRkEt~Z%N z9~D@mF?aa$<7nfWB<=dnebQmrDOvj-tQ|P4VjRqcGp&vC!-b;VpNOEhx6?OJo|lgE zIAJ)0&P{x`?b_wBn@J}VI*(umA5QE%lG)_v*qBc_gCD1C!Tip0DIYecjz1nsRk|Ene=XgtI;## z-2}Bj!G69v7i#y_pT~#sese7r4-3ta6ycAO=@hK6+~m*UZtqZb@4;=Da@Z0T;e&j3 z_CwLL#Umd#y-FpimSXZcA`De*gdi@SAGcJ%xoAHW-`cK5R-ohpewa+PqjAanE6}x{ zpTz6@$485k#z75JFhCxlb1jD%De)wLVf;sV%uvVvp=2c>N(ic)viNW+W=MFHlWifn%C>6 zhke;vZb!4u?#0AP=k%KJJoyIcoB&cttiQBBMU`f<`Sw*HcaR=kmYs8H!VAw=>9t1p zC(th)-6}IM%iu!f*7WF5xAYvMn)2*vHhF_|`(pjjGMU6t*_#%pHXzGrS*2(Cdiqn*89WYRF4>Q5eI&}!%RW*O(#${~ zvUBV``g8)jJ&4+5qk9LmX~JIgoFHj8N;o^fz9j~ify@nUH|4f+t-OW%>>pUJ`|Q*3 zef?TuY`@DPINaOqfBZwZgjq})@ru!T(XaP$dTU{QzI;)sk@JB1mHGR=g>=uZQu~;O zAN8^+q-(xd={n$_kM6UiJNr6xCsvorPiUEO_~*0p#x=BG_~*;_)1;e#-+Z2OEWcFw zwZix7tFXK$5icij6Yzb0$L8s|Mf!f8f1K3wy-paTZ0cewP%PCPO!V5BRW>tZ`;>5) z=N+Hbbnd*x`OW1TA3v(`kq6a}zfJwoN7WypA9+l%p+8E0gnoykCq6^|g>rAAQsWiH z%QZPm_=!16AEO>{4%6P57))*21Wj~e%V02NJK|jUL2NhWB68uWfrGhVGhIqO4Qu&M zJ(TZ{9H$=WPk&v{TV43{$2ETJ6Y6*TGVw3v`=@TzdUNSrK9h4b|1aF9^uv{k$5}6< zwyqcP4s=psnPPZtAA?+XEsS+PHR;+ptByh^c@*EO19i z*x?+)=IPMEgR(?QmuY@c%IC`Ad^4)$7%k9OjOCb3Uy%=Kx^e1lHhoPq|8eR|%6ZHc z7XGZ|-Q1syXHo}yh6@Ugp8k+*rE@1scIMNT4twUm2tS?1$pCX+MJ5I@fyqYiLEZ55 zLkm$TKg=4_>OLH7OD*vuwmOFfd9I*4U{^U6v>i?7cCiQgv5BeY1&~LN1W8z!55`;U z{taZ_{FcVeGG6Y)iS#gXlz{`YP6)6ArEIK^ZT0?sY<}ZBsy}rI zdyPj@GwQ3j92ofrv#&16Y#+tfI2lKh)cs$5;C8uEd~D8o|FWk-iFbJagc;+MT|+aGYqpOvnE;{HUeT ze}!}}BVNY4Xk)2qIS<|4>y+Op{PT@ZcVDUF*fIFs9=~w4_6MhbQ`_&FVCAkvo1^GI za2|c@{=Iu}a@I8@rmW@*Ge}{hMh@#ZNfV9XvsQ;B97I1SmziDcd_kgY8Y!y>=Pl043``_4eHA5?in1E)3VDp zT^3Co#9YlK?o0J`0@=Y9G6i(&E)%IQd+;(5hmt2#UA+n2On0gZ=s^g25*9Em!uKtf zuZr!nJwd%cOT9}zqj*5hi7#wVBt{u8L-_W-G>-IAgI%~2g0T_{Tr>s|nZ3dm*yZf8 z!d+b=nZ#!0fE@e{_6*~w0Of=#GlPLrrR&qV?@)hFm(0cohj7A=_AaNwJtC0jv?@g7 z?riSvA#ga1V-fJ_#H=14aLhTFLLZRCIZ*FGIqgeCi!(P;4i`0Rc{WMA%|w$uhk9^Q z>sf=j(DdD@VH`?!^i(b<(u9c;Sd zz_64W=14!ic8zsVlC7BQyok z#znvREx7XrBCH^rqVV-Ua3Z><6SWv!^Tz0!)=g`6Z(6he$~9|ZR}U%2Ts$K|C^5Se zJ^gLnnV?t1E~(gWw%aZz?F=4Ga3F(=W~;;wS{7*i*RJC|K5xFy35DG<87E!g{JJHg z=?lZp%o09V#W$mm>;1alBR)x7OMIGmfcOmYXNV_>-&2715j+0>qSp+~Inuvcfd91s zM+(wkOYG!HmTQ2^U%q=RF8mHHPi07Pl-L1^Ced`kzogPM`ocGEtaI`$DxhD%3W<`w zg}9k`GjS{N&BPtVZy+8aZXg~b-cEd)csKC`@eblC;%kY`F_r%!;wbU$#4+NH#I3}& z#2v(!5~qn$gh!+yO_UbO4M)1=q z(zm$&(Dip~N$>hQ*B``4@7llX-0=Qh}}Z!95IJu6Mnar?}%n+>WS|o zjuFe4E3Sq3s6umqnC56)|IF!%>0tc*q#q`B{rfRu{34ij&FoJfARc498y`*+yZ+9N zCxzpY>wnLZ-i^;w#3ST?j`%_1@KdUfhluNm-FW8u_lFtZ$oL*&Hy#AzC*#G2#Knmp zQE0k}-%UJ1{5bIm;%Z_y9=wD2B;(&ne45yeHxtCG89zl_>FBBNi;2VU(el5YI7<8k zaWnCg#I3~dB0fO8gt(iyp4g3FD~XRW9$RMCogjXU_%!h`;xojAfro9GK3S4tn<$y; z?@77-PL3$B=D_t@Z4q+eYpAQ6cggV6C_KWzDvCG5l_l?*Veuh5BSRT10y~EWkD8u= z;3~T%Oa^z8WydBZt4AB&!+Xt%%ptp!cY;d(X}Jz<1(o}38sp@$^2(CO@nyn;?w++| zGw3dG7=v_}93RfzOeMXQrhj1QPv&h1p?>c&E3N`24q*n4v!l$w;2^aV z?d|Dz{jlygiF&a)WiJ(LMxr)*uU7=eB~u(r*@#?ywCB|a*2QwB*WT0LJ|r9Q4nyAd zKp=2%;Rh3aJ-tWUCE6>sJ>!yl1`w#7*H?ulu9qDW_V}JaBH1n?A@{+qOivn12P+p= z$3ePIdkIF%;e}&Y6Qa?8^1``yE-AnkSC#EOz;-7q_W*55$)DjigKm63qJ5|zs~Kzs zc=v?@z2=LL{W)wF$fbP>LVId2v?o`1%IU;5sF!xB7psK9_Ml$+pdGBC+6QqfUIcUY z-!2L4HzTaLrazUvZy>{ zj|%l=w)NjW2vgSciJV^Yt3F_sA8hW!7kCckvdUt6*JdQQpOfvl`>ff@d8uwVwcjWA z{@XjH^&pOQg*|4mH+$za&)!@-wpo0;wS;+g%X{>G*(7UMZ)j84k2(qBvi8l( z3lHdBlR(k@_9Z)(a=8_f+3~B`_-8kgwMSNV!rzXMPAoLDJcTIEwNv8YyI+ER+ZXIN zq(J?$r;1G2UFX_mR8rW{BP)Ghjy|7LF5I@`sB6dQu3#cbYarGj^M4 zpdU@&TBQ5B8NxaG3rjoFYJLM1l`}Zh|Q=7$4J@?$^+uMJ*Tv$_66Ny9? zz|B`zZCw$5x+{x_P|2Lqxn=Xhpno-9AgFX`k$ zXMVzZ-mc3FW86OD>!mMD_uqxj($1rgsGZ+U-|@fM=uW_u<|=bH0^T-cw_;SrPjE5Uc!FXYdqkN)3S!(oOa5wVsBac4z_&eTt?1^_h`R=FQ^WM?-9e@7^KKP+uI`QF;eDq@<|HLnk zeezSk^66jwwO>E^8=v{j&wlQ=e*4ttpZ=XMeDQaG@ANZY`u#8e!5{w7_#c1ePoDkL zuYT>!*T3;+-+b;{-=6r+^MC%rcmLuq&wlT({`&hr_?sV2{_T%`{NmsJDuw|Gf?!_sBTS6s9*y6WOf zRKe+I|GP3EPM7!kWY4{VCip>&EwhZJ00yQ(Q;Dnh#%`=sJAM5U%fFM=nKrjY_%`BDrXN&L_Eua=g1X3L zAhXBbml9#%5RdOmik^db`MRU*@YuaR>X(aA-1a#PrNf~d+foM;SUYd)?R7u!(US_~ z+KyXU`U60_?CtGASAX);4jJCcMHupz@6tiV$WgH-5GfQ(75VY@>mi!AlJ1d<;dDC( zVOu@P84GFvN9?HX)C~uOxAk-#-iqHX$X>J2>SqU5_nuC+9Bsw- z?|W%#(8Db8cbUO^=EGXyP;1c1D`+8!x4vP}Ibyg$sT(W8= zcIRy^#O^$}mDru1#)-?B{s6H%FYF+$WPCTVJ5Ng!yYsDK;`yW>A$IG!W5n)!ca+$j z-<}{|$n;~xi-=DW*Aky1cIT(3iQW0@II%mwIz#LhrxV0W$?q(&J3pQzcITT@#O^$I zn%JG!og;SVW9G|RpHcD;6R#qU5WDlcdg4nMA0=K*+(^8JI7WOaaWkf{ zW5g{M8FP|&Gw~_nt;DB^w-JvM?;t)yd<*de@lN8i#J3Vp65mEVMa+#YGfljg@#l!+ z#O4pQ{_i9X6KgMudk(~JVthTZ>(HXaZbRqvsPYT3188J?32`&=9O72uQsM)|bBVi& z%ZP`G=Mf(x4ildsE+;-oTuFSIxQh4;aW(N-;`zi=#0!Ye5l4u_f2ifHA+9H0NZd%g zh`5;;KhI`eD{&q10pi8P-Ng7AFYAVh@ijo}juGSQfYzNL#@G3*J4uYMsabcLcm?qp z;){sS665P*)=d#diO&(^Yh%`h|47S^uYFlpPkae+Bk^kDW@3C@%eq$LONkEgr-^SS9wBZa9wpvPJVv~g_!RLr;xokCiO&-6Af6(=h4>ut zPU7$%Yx!>_t|z{YxRH1laWnBA;#T6l#0QAu#NEXEh=+;qBtAxb7x4+=HxZvCP7$9b zK1_UuxR>}W@x#PZ#34>V&JmXqhrgobpGRCzTu$6bTtVDSTt(bU93ehHyok7)xR!XB zcro!Y;-$nVh*uDwB3?&4PJBJ_S>l_Br--)_pCdj@9QhM1Z-^7BC~+xqjCdY#3voGd zoVbFxgSd(~O}vzNg!p>m6U2v!PZG;p48@%$E+sxgJdgM+aXIl6aRu=?;ws|svs&Jz z#P!726E_lvIKgWsE+uXyo=1FuxSY6~xPo|?xQh4~@lxUw#Mcv_A`WrFI8IznJV9JR zJV{(dJWafm*!-!M_j=-b;t(g4jl|`|&BPVNt;9=-4-j8ZoF)!MrM7UWLR=oT(2NpS z5RbX^#HU>P)k;6^(i2a(^u&`cJ@K?l->B*FzM>IX%ajvGh%1Pr#G!RcA9M7?EsmZz z?&xDm-{I(q(~h2a#L;h5`cX$uJm%<$PdWN#r5|_k#1k(5292L|@x;?EzD48B*R=c< z#1V(LX?)b-R>d)gcPVahIIcKOT>60G4&tT6X<|1o+@fS=nDbDo(F~LBUdBhbP9ZeM z7=M-lCy4)w_$2Y?iBA)c5uYJ`FY#I8Zxc@uf0y_i@$k5m z?-REYyLG?;;%_p(oA{52hl$S+cTit$opg-xA7%U)@nPa9>D@Z+G~>G%Ur+r?TM&1K z@iYT-me}1}og)4{B{xx~cl!Y5>#CpajBjRqDRG4HZe0^4ekbEwNbmLuVvMI5npVaK z`v#2v6w}9v-$&d*?AA?b;@@HX2=Q+cyLF6Pw~aFXNynf0&m$gVyjzDIV0@VIrx^b$ z#N))z5l;|*mUxo*>%`N<$BE51RKH&$ju8JTag_KA#4+N(AZ{U^AdVB?M%+O>PMjwG za~IF@l@pIJ{yW5@#6KV&BmPU`Q^emO9w+`H@dWW76HgMqKs-(SX=3wds*leRM~Ht& z93_4~ag2D9xP|!liQ~lIBJLpmTjDhFUlWfI{|)gd@%M8~W7X8a&=n&~Tv%{NuQA0Unp|0;2m z__v5-#Jh=Gh<}$jPW)x!FxSy;U!{Zb#~APSJ={J`n(=O*VVLq(k$!~nZr@{+<#qc& zqm0jz{w&jT+GEBT|J#f|MeO!HMo3@H_;JSXB|gCX8i^+ue-Ckl@hgcZ8J{3NM*j1O zry0*-){HWK0prbcT0b8oju78Ye1h~5;wa`=y@uS3U-|R->Nyfi}c$)mKcbM^y5uadujM#ij>+|Ep5#sxZqr^kR zG2%OjPg36tiCY-|A>uf38*vBmFA<+&`bETP#y>@ThVouRJi_>gh)*+pE%7Mh?<5{) zd>!!^idnv=UBcQh$D=D zoH$DS>%=kQBg8GlA0wV*ehtKN#=n`kk@;Or+`;%HahmuKiARY4gm{$r6!94GY2s7F ze?~k`{59e!%D0qwg7J3~yLtPMi6xth+ z94Gx{#4*PA5VsHyIC|na#2v&xB2E*J5|0pnl6aK(Y2q>B&k&y?-a$N0oF-1-G+$h& z(H_3b=*W3Leg&loH+x%+jvQTP(9$ItpTrFSadHnpeXX$+=?>aA@8EkX_RnQi8_0H-Y8PAqoR1n&C+ z+z)(5z+ddC$?PyY883Dv*wKr9H6hl`%f-%`V7+b}7kiUT$DE$1z;D0R~R`1Pp$P>!Sa zM`CfRIqjE(qgvR#D354n3u~s|>N!`heYT$V1bWu~Y^QPSI5)mI`D8rP@lNGSS^0DF z%D5)EyLqqnKU;!&(*8uoOLf{`j{I~^kK66HcwE1~J+MdBQ)|$^R8N}&xm8b_gMLi)lp7aRPg{fb zIB4xg%jwIZ^5@Fw{yF>8{I>@EpXQ&Fx6|5}3-Du=6Cm1B1xr|N%a zV27GdJc!qPcC&V6oEJMQo{#hh`Q>d3>__v-wJ*(QTTp(VZ+^Y@*`6U^{=H~PemlF> z!_v;~49YWzn{yK4EJMrx#voqh+8XpLPS38tmh@5+`RQG+BJ)>?-4fKR)1T{qHNRVf zaw>gWU`I;7IjC2q-{r|8{NEJJii+1h^+J(k% zDM%kLh`&9s59RNAQPGF++aHYMid#K9koY~`JV0U9e-J`3D#Ac%+JMcdhlPJ z_9va-(1ejT$4BSwQmg88p57JcS!8JfSGPXad3zGG7IoUs2|piq1@)%!^52i|g=G0y zSAlN5(F8r~`byUUhiEmfeI_v4tJC(^8OW>Hty&#@S0KN}=gOnFCy-C^JwZJy?l0h< z4$7zTZWZS88w&KP@i{wpSXXhbeTntE@<{vX4D43hTNmogkMEihpPwGzx6Y$anXUrt z>Rb6A3hGaBcVIV)`^<1&`u?E)G~TT~U3t=;KBYYAg7T#UyVdkEt5K(Ts387`$4}N>S2s9#-A`0>JD+O0aBm$=;x+{3l=c(;opSlX-HGFPYTI=8DK z>s+Z1x7*^@y}9R)edszNC%>D=yAWMR9}e`V z>z%_vzoqL$x2s~H7g0;c^o!{h<6;r|T3yUfWwP zUT|Mvf4ZKN|LSy|?{=Z^I}bL$oc$=4|Bhbr_vwXyu0POqSxz3^H*mXK`2BI@EcNf~ zO|kq}=jO$($8gxSc!yn!)O`oHTZZ2~u=eA2&160(^_`PP=i#~bqc~R{#qwXB?o+s3 zH{mDsF$j(>Ugv*~gUrVyN5?_1%(MM?!G64G)Jf##gE=hwB8fo%IuF%x&mUL)aDP11 z@ImOk32j*Rz}$LD+M$N$(~Et&+@-vNowR~w{Vv~?K#9x{osiji}RopL8&O>pD>X`{nh+{qpKQ%@IhUPWMxC z_N?B66A{tnEycfb%{ACR+YSnKci6f6R;*{X z*--tSmwc6JgC)2US{%mX+?C+p$31chyV8zLt~U}a+Sk#iQGN}6t)^^*#SEb>^%@3{ zVVN;yCM3V}IH$~%l|)LnZ{I#w+#6z8MZh&io8t#?3;5bt?5_AcW1>;3{%}Wk2b?j( z>0!9A+!LN>@Y^8xsT2IUYs02&WaJ$q504;&Iqw*G$0H-PbLS$5#~*(j6(5U@#7B;S zy798+_+2ANk4)n6W5_kyIC5+RsSL8|?(PnU=MAUR_odS__}BBEe)ubT4%A3|fahlW zhx!d(glpRHyX$wQlBTVD2;bG~G5Zr)gScb@-2mdPkL-kQPylHA^^=6kdyBmSR}la12#DY`-`xC9^UuvkHGf_`FpE6kx{_Y>>dvwkfgrED7hDW}q z`8xhzeo4c3VW+MgTHb{}af+qCmJr!@-JTcThMgU^N1CITeaStbY(t8Dpm2QlV4T>E z@O{|7+3N9W1D0_7noR!B9sQSoUSRgGuV2v53z!>?-t3Y8H{ww#4RmrP>R5akb8@bP zA6x!f^@;Jox-nuIBdzD@huabkB5Au_4)E15n{93_tat;Vk+9wok*c;v?#@7D2C#IEIpU(|TF zu4*Ly8PjhgevLRzybtq<82&bxYP|2E32p5l`l$i*GFiKdIE0Wiu*`6?_&kUnC~ZSB z7Rx+e!ZnTT6D2JtW&_Jq{>=e@mqK<@25fKGZTZSdstf5w0-66sZBHlb?LLG`?t^)p zH3!H4x?h05aFzM6tfu;dTtp8!r~KDLLry;l^noH@7QY&_7E*RY&O!LnTMEZ0N+Ii) zUZ8wk2v^7NntqAx%GA~Ymuk?vhM~MQRIR4iL{AHY#IiRc{WvmgYqA0D5M^eZ6 zT%{hnFq@BpE@L&5$;-j<&(&vf{<1HUK%TSlaT<2~a`h+tM8~4PD5M*}{{bt#>Q?G% z5Fr{b7AJKmmXlv|nuGG+U^WK&xNv>9BNx@3Xz41eZ_%V6k<3Zy=j-x&Ly%t@nwDCN z($=!TVjp7XQdX&x9-C9na&jCUzhA^&WK5THR?(oeUy-}V=G|j=FkHU5+?;)GFgg3V zaD9pG-1iISmv2u_v#$PUN-z3!Ha1iKtG)IrXLN0#cI7C>E7wj{-&dRULH%up)^t83 zyEf;SNZOJ}=JJ$vu-3iA$c#~JS?XNYwiR|3DtmcaKT=oHcSvp$mcY{q8<9R(q>f_l zBR!_}jnWItKD?$-3%YVf8*t^x_3us(uiyV_Um&(BWfBRrXYR8yYL33{bN$=Z_$?WU zk@2Ls{$$1}Tz6w8EVq2b_6K0C5+-}FvIZ4h%YLfrLS}h7uk3{$r2i95h*Y8<=`+Nh zWvAKaHM6#rPHN%*4gE(^8nF_UTIyd~p^T3`=vC!3L}Yh%BDNtTs`SKS83*y-jUKLK zYBf$zva2P!NrRt`Fj0&{S0S_)+K};RX0MXdr&!cXO-X+$J5WR5BK@t{m;TSC+y?%5 z+ZePga^>vI*;lTAm3Wa+xQZ6Unsx5r_og~t9eRLW+=wqH({f5K zH&%*`DPl!?aC@LwoY-X>Y-}%VZGRC8--bmCB5jYI5BS`o!Ulawe*AXGE7qDZt6)zR zn7a#-^Df!L--O)M-GCbNW3(P*W)rm>W#3(T&wg{0O>iZ2Ec0UF>AT&KtjlteG4LQH zjpA%q^z25Jt>y~+MQ2F53skZXom)TRMPepBaG$}ue%Hs430@>8+Xi@V@u2my3B?IS zNO%Gf)<=Z%H{gRrOOyn6rR+zGWY(;w7z+~|kY@9G*fceL$j3iiwJdHprJ zba4gxJNE3{x_2Ayu?+QNy9T>7*r36l47OrqCkN~8L_fAruycY<6YRTS%LKb6*eJpN z2)0D98^R5jwl_)cIj6sqd-GQMe{%9Aorj;MKTdyw{v`cr`sN>$K0<#v{YLsR`YrV1 z^bZ`+baxYX(@)dS(jTV(0R0jAkI^@8Q$ELtKR`eJUJXA%{4x4p9@X$M;!o2*N&mC- zPtpGZ{nPZnOn;nyDf54p_zeAT(x0IJ0{ye}zfXUX{)_ad=)X*Vn*OWw&(Z%Gee;i6 zo-qA-`i=Bs^jqj3px;e@g#H-)ar%?=&CAL^O23tUH~mrir|6%he~y0mr<%Tsem(t0 z`n%{Kpx;e@nEna+r|D195C4<$jnVI*KSKW`{R#T!pGi;O*Z5-^tyUYdwV*8mpsbWn04*#gV`jo3utf8cJ~MY1KQgU;%%fp);E#65b*8I z5VW_a5}mSn2#0*K8T=4fdpmw996uk1ZB&Ni1suIShx)O%E6&A=pm^)6JLWg|Df3>u zfZgt4+=MRrh8qleeC%mpQ)3k#{T+0DxkVG=uebv5^lO3-noIFC-E=udX}p&Y50aW2 zkVbm?o8UKMOZ_2yek+~_@LY-n58%V)h`Rz$6P~N^tif{=65N2qm*VpSc;1RfT*r}v z_E-HcQwZEyfJG^nnGX47@qvSm%yjh1&$`K5O0)Ql@~M(>hFyYM4hx zo@d|vYtsk$2i*N==m9@Fi1)at__J{l{qiqE^wHUrCVCr6X7Q8u^6P-MnmV?(nvQ*KZ9854YrO_m!Fnbx z&RFbS-X|$eD<*)BmF5&UVc1 z<+~N(SMzbK03Y!1X3(dJ<(nQ`fJeM|*^53w{3e_yv;vQLSlZG_V)xCd(_XyLPZq?7 z|5fD^ev&>$Ea}^T4-h+fhKXJI#yl+YpZ4%B;IkeU`KLWB<*WanIsMrDJ$x(T;~ti& zY`2H^1E27)$UEWTTY#rLEcIdjEtj9*dSdw|kI2*PVUhQMhow9t9+v#ah~+d}%0KR5 zNk8RbNgp|<`3t?Ij}ePLrTlT?ozT9-r-|iW^giHY1^ASQ_aOc(vE1yJ@`V50l~>l1 z$j`$PANR1xm-g^p;1eE}@{D_U8}K;~?*Oj;EH{pV&u>hecl<9+vt(=3zOPI_cp%fhUON2C|fAn%LEs`#z`Cmz3vc zL3+0LpE-FH%c@#-rgh)TE<=$@?&Ic%%gSALhGgGm5W7gu71HV6Loqr%6P5L{@X*s< zxtA+@II?e{A+lQ|J1Vkw=V&A^IgyoI#qSAxJ%>)sz)hf%-H}7sBT^qE)@gc|PVODa z&V=s#$*mgV#OC;{0UaN2PbW!BSqi$2)|*1<74+SNdfZPWjqx0*`$C zYi`Bp^loiodey7!ON(}9rc*r^4;O3bv^A5ffkOUr$|IZ$!{vUY>}RSy&5U<96${hJ z?u%$h&aUJxyt7Cve35)a&$<^W=QeTzqx*nzqMkrKWs04JetkR?)EBdy{+Ly4UDh zOMbkxG?7^M40Z2Nv}OwU%q~wpznSug9cYhGyyeRoNv_39d&@78?9ycrCf{6eWst(o z43~Bz-^G=(ON&xhjIJNHpy9cDm)dIOtVm8kWtUjLFCeY;e&p=;Ny1rfHj0j2*<_bb zbfJ5h(nF~$q!Ss1mz<#qO<}zDKeE$YJiYAn$~l2phH{vlPU=&3p#8Q|n4jEy?*k_( ziCU%5%UzivH;ITWUovrX9nmGqgS@p9rOZA0!N&rT=W))N@5x7qZj{k5J!$oa2x zg>p%+C?|%l|C$-ErylYf{Nf7ZogSp#RW{A3kWOn~`?6wuBtFN(-5QvgpPUlQ9=LNe z^AT&5({DLd)S8sOtB_94X4H1|9#mnxoYTl?CHFsNM9t}0+Lnx_GHUD1T)B-cwkiRGJnGM_p{d>iMp zXA0t{3gXRcDzALwP3EI+{^j)3$asfaiJd;({LJC}abM;~ViVHNwcpnMBiH}PH**1UhiJ| zRaHx?=0&b4tqM1l&MB>mM8f(DyJ8=5FHPSmvJGuPS_AI=>3eUt49H7A;P9S?&3JwA zkHWTO5>&<>TJ2VHx3dA@;==>o3{AXEPf5 z`b&21k@hOSw43#p+-}3=CZ4PX<$m>QgflyQ`tNnq_vkrQA=iETx9z{^x;4-3EdSxH zAKkF?%ry-kJ+lf#U7POi9Kw4^2YVAoQg;t#@dnW&8SGv6w%^y&f6YdXyn8UybvJgN z`w^8$_uP%Qg(P}|!84l^`VlXF)cY)H zgokr-CMKU-@CaYu`T0&D%_QPa7tr|hB>?BV_((~qDa>2wg_q;)=P&$y=V&A>{9vi+ z0KaBDv$;8l81~{%;PY%U2oK>YGK=%&kbHdS%h7@~Q-~igpz-NN4l^gmBZ|-GlS6nG zlSA_H-5BVc^W{x@dAWG;Mebu>T&wrl#fvX)>LHW~@h1vsG*t)I&m%}vj~75p7tlzYb3z{jjdLyDX9*J?&iUmMzP|J2lW>WR<0+KSuOCO( zf)D4bAD^zUenkEV9?5S4vWCmhR}{!5>75h0C}^B(#piC&kK#Ffo^-<7wk;&|^&t8A z&ewl*1U8NMbODV|FLip#i$8@kG!prgY^B4ZU6PjaqByhXe)=>i&`el9@F zy#xfGJMj5Jbs~Hu4<~^ym*nd^C%c3Vqc1sy_+te$KE3GWj2AzN&xL)6F#=p^i3cH$HAv(UGC@dv!mLLxkz^YazHz6(EGyxvY0(77~H?r|?}1fL7@ zcC_M)O-_6C5xlVFd}(5kr&vF7*5e_3eSIB3nhx-7#xt9fm|-t|44+?57U3nli?u7s z&v(8&QS|ZCh(A+6@iKi~QCoI#o}UeGgHK;zR(dyj&~xi~&ws7#VZ@^GnryO(@@=gXCb zZpRQmTtMT~i|$W*@e}x5ti1~_$J@_e`1{V$NLVYO>f@iV%l6-vU%Q1>HlZZcEK;zSk z9Ou0Fdc0`sd~yiSVsc16zVqccjWpfh+k$5{Cp<^I_!IbCtQ`w4$J?(D;qN;~BVm(B zGllr^0vey*mdU+T3=#GCTr7X#<#_w~3xD4^8VL(Oit>YBi^t!mmCsTSBVPO%KF=nD z&iyUG1GBtc|#OL$LAv}x8A^G^um*W7^41;gn%g3jc z&mzaD7k>($&u5pyvzQ!`kMDdrjv3p((-QaaFj) zgtK)fdXX`=;rT4`ScOb{9Ku|uVq?TqJYSY>SW{-!Y^*j*_AQ#MNk=+{9}bzuJLd%J zH7Bo=-}z2%u~iA%g_jD7KICy>9qvVg2oo2(X-@Fl3mSs?FTz?KpdYK%_2Q@Ci~BQT zNiXh3_>$*#_>x~I!w(bROZ*P_lA@ua#8hl3i@UNlRL(J#Tjs^fV#uH6Rh^UzU3%5r z5;M20%(T?uE-0Q?Q4SlHoM-U}!VF%TXv1C%8^IsKQ!8PJD#XGgNQ3wmV8=JKaIRUn z@nW+ubdf0w>Ti{qz?W=)gr}E0^RUQ=`XApp$NV{-yYYfX$=AnPo-$jWP+i#6CCg1+ z8~ly)Ox=c>Nh^D{%tY22b2pv|=97=1-9j448(}S%qh9c|;boDMcRtp1epqNhnOT7R z7a;!y8!9_o{-e0e`v-U&pM0!*{IF1UnW^4bVX8NjPtNNoiz}b7IfZ+{Kf&`ckw;{F zwcO&!m1qN$QQ~u0co(EYIeb2$<>hAii%ZP%Cw z4$YsFYm@ITHSb0nm3BFDu`%z%v(2V~3<&qbLS-eU?089Rm9$aV*4%8lX}J__8P5Zf zM#7WxVV~7D?DGhJjQInOU~6%2e-z4%20}&BqRC+ky&g+miNG z0ndA{F4cUIn_EX7)W@0mRu?1rZ zZP>@5x-wIjt%c1lGIg(1#$B3GT)Hd8!JSLvsjlshdWhHnCv5I$hOK ziF(tv7DHRR(zdmR6=h~cvf9)`7or#G3nmZG?E7q?@K4Gl&uaGqR7Q;4ta_Qmy>ZdQ zk8je5(wh}aytt>}TfInsv`_mZ$gE>KA}I`VE&C*;>AUrzN+V%>MiBz za7S)ziXoq3`5!2f|CbB$Z(;rsd^tk$-z;B}fa@lfcyaObDU2#>%e8i_uz>vr{1&kEMA5K#HfUUx5WE6FOBHEfKS6EWoGHV#nZKu3)3|nk(ji} z(Y~C0$|q?C%olahDeT*9(K{bVpt8t*n{IWE19K)zLCb(n+Y zhoRr}X!7Ps7~^ffh&DWa(3p?nqT#ca57PKp^oKd_NI&ckkL!QE z@Ux9(G>dsIp3_dI>{{f1l?{{YS!bBP(D>L-7g|(?_Hu;@PnV_V#!BO>WN!UpqnZB# zcs+Z$DNU|7<4+p%b3DseX?c7cT0Rf+NPM$zL{JY6)tFax>Ut(##IDbRm+!_ryB@<2 z+{pOwHTdFwL@YGoJ_ldghHu}Jhu@Zli{!cM;`}_vnddb5uY8+jZ??jh{3Tx8b4BtK z{tcKT)^EfbZJ*B7#){-QUXW*+c?#cXQuEmhUtEG%Xv95OBwxuRR6R$=<>`5os4Lq> z%FV<(p(i|%OHju$m$B_TY{T{+L)}X_cnXb={dA$)Qd5hzU%Mfa4lS6A_0bh(0qQf1 z`dlUBLlXA1vC*7*%$UE#lO@l5T#A7L3$X&a(84maFpD`0)=CRAmGMw`jtOrmos@Z$ zEkm{f6M2jicwP{`H-ya%ua=tmSSQLDWD4U=nT8?WNW7QU?m;BcuWp=U`vm2WIn#s2 zycv&M+vQ{J!~C#@H5Fz}w#KYVM$C$h3rx*%Z6z`XI8&sqKf4-b_gos|uZ;Jjn16^p z?U2bATra*vAz0$YJqTay`PYbloA?=G-_9l9hK4fJfO6Mj{)4f@&Y7o+$aBM*e0j#f zPvn_q{wv=kx#PYUe33`u#XZOT{d|Rg!|Je|vqzze+T)RFnSF{b>IXEPq?K~WbGjh! z2yD4k2;j!vs`-5vzPKNDC=MqqG%I|&=ek7lXuue;cwcTF)>0(j*roYpo@AMYbL7pM zPcM9NzeX%H;(l7B+>(bKH#d~Tbj`95bMG2g{)vk5u+>3#5m~-mAWI8%5Jfpf-?y{8 zyNi@p_=Rf2rZ!n=YTGJM*QoD(5nW?o9X?hPGB?f%nRCcv6=e6Zt|Ke+`livLnRRsc zWd*w0LVNv=%6HZCRxRd(@I~HVBK{2VBP}&i_Hi*sO$I*l`r%e#Yf?)jg&!7LTW!{6mz%Z8WoGThrDkoY)~uLbHrX(-WV|kp zcCotJtj=DHHnhsD-WWBjLrYEl^y10diG|~`kE8oL4Q6?^9(z34=Rx{le`n)jGqM!* zjb{ovkvjKrs1Ebejq6Mu`fH2~I*wznb`L_%iuTI~H=+Et)kYJxFe z_F!I(VqUZo^cUerNkZnf%8-c*{n84|jTc~UJl`zEKF?CDcb6VtJQz%rV2DwPlwZX?v7#a5^$Ee;g}j@U?Tj7k8TY&mr%BV&D97mDk6id2`IXEto~dK;KYd8ZaK! zVlBS_>zWFVOVMb^Y{D~a(_;(+jRB1Tjp5joPh*Uab!{R0p;CX?U&3B!uojc`6!t;u zUd3AK#R@a}O=JEF&$Q%a$NjLyS3ZaD)VZ){%Z=bHp4uz4Oodo@1ZfQ91%Fe>A9d&F zr)vPaSJI*L3*9S8uMC-w;CYOB2>-2jX@tFW2WyqentD2Gw{U?d|L6n z@WqW0OImT&>~F3izL|I@vEM(6Orb*+<`CvIi;@*)5&Hc_8x~AgPgbUNjl2Zmi!tY4 z=&h0KOzd;`{R=#}qHWuqkG0=fj(%qu`kkfdcWU$dorPh{%OYms@%htLlNIUmj&MBG zRBoEOMF!-DJz<+)8tqYN+iE~RU+C@rQ)tCJwAsa`W^%!V+uK|vYn@kXP3^OFSVJr~ z6TgMux%h49#>$7e8{!P&OhH`e(n@nF!Y+l3OQ-867f;lV+Yw*-f}t`qgnBH`%$-E5 z?67SZ`{2_k_hsPk%I@QaOUlh9*i%@EeS}5eSv6fTDf3yGw}g*q{YV|jcqLEz%KZ92 zg*tNeKMlK-ab?qlq`=(@j*~(o?hjb6etk+FA?Z7y--b;74zQh9WJ+QoIrHk4GqCxl z;&@p)v?OGfJOX*D=9;QdIE3{hdIGeIrPzylaegS0tqz5gRiTl~LgtU~oP*4(q%9!M zATB=~1Uwk~Ama~zXT3KI|2XofR_slV+SBI=l8{vyP zNL)x8ey{F>Z$%!-4VvZ{d~yFk+;AE69IDf`?8LlryC;RQW#Wg}vjbhj8mv_@=2cGP zoFRxsUxWBFhz~6-H%mM1Uf)Dye15vRqbgnry@%>6Og-jd^_Yjrdar&%?exM)tdVTJ zE-(%I3hGtDUo1Bb*)Znm^HBGguWzWEZn#9|af?mu^LFlR=Z>Nm$-hJLm-$|IiHRUD zySKToD&25-m03PK7i;UqX35ht)3qR7!zGdq=U8Y93tmxO3(szk=X{LW^Y>}nR-R?x zS#OpUkwxZLq21gdkX6U!?*2ji*OC2Xe-^x3%>4>9hw&B2&hV(KQ1 zsS%xG4JhlL2IMRH#A(X7v%x*tkf|LCnZ2BIg0;43yY58ahJIt=(^z-f{;M1q{n!TW zzZx!{1KEDp$R3U8Z44Kc%Iix^{nNF9jsN{aAv5poA=3r^;LyIfS;kZ&2QHY1>#=$h@jHy{N;L>+6q&%m*J2 znQw#c!|-doa~4N4@Q#oAY+ko)Vw!jmf>+U z4cAtiHOWOKYuXl;tl3yovL;kflCwgstCon^hLjgiuB`>-UHra~xg1Z2FaHL}AFaav zOEvbVE3ux#KJ|v>(@Q7oCl-&_rfU|-xL1X7uhJ~qr(>^_12cYe>G6=+iD#Jn_TY1; zhZ|6jm6_arxY$z+=^A2{7=u1-R)#)e@>{W%V;tSL?Kc;y-3Ins88Vff(oRBVf%rH} zYdDS(F^2tV+a^$Vm?t!}v0dz|n+z?hFw3$Lvn;v5EW?wVa}@M6`LvlQphaD(+Rnj!`Ja}zNyDr zP|m9BGdLX^kEF}3Jr=Kf;qy<(`-!h={!fW7;|Tim1?Y^jpE@Bouk91Ad+gD~6!rp7FJ{E1Ae>^x*j%&JBNoVC_zli#FeWThe z#&N7~8&DoQPn*b%Ex-B$w86g#nP*(R2(Jp6ui;lkGZ_D5Z&d8CLuO2BhoKc!W<_=Z z*0l4@3g~GC_^!w_OfQ+N8*jL*a(e^zKkBwdp3k!}%Gx13E~zq?WS3y>y4YNTas86# zgZ?RweW*7qzPjc|b~RHl&#`H(O=GTsK0)>fW#7o2nc8_pg^6UUbPPv-xd81$&XhI2 z8ttXZM2=(Lu^MA!{#?o0v-D@=#R0Ff$;?EAe&Cw&T@>WJMpZ(Mcc}o@%cEO z8;NUd{pfuo*KYr#5_1fk>A5sZ@p&^Im!_O|L7Z%f`6VWWM{HO8!uTx++rfD8YvisB z&hlLPF@#Owxsx(+?2M^x)W9~duiOS3feu$3x3)1McVVhRHO8H%ioVmxU*}`!|FHI2 z4!d7|Jg0ND>uT69Y!~C1?RPVElMVHAP5F-;Cv68E;3fNm^Iypyqa=@-XtjwxyV69n z7h!B%fpKxUiH7QpN|x*YPOd01e~o8=<$4jH?~CTJwolA^(Em%j4#{~V=FQc(^VV=x zxw$C&`{ttLm#_!;jJXK&F4^O9^RAkjGRze*U)&%o-ii*V%lp=rn2+Llm(yiI{~jtw z{cM;UtC6t}dRT@rYuSb+({+=J(2~_|q#nQARAT-a&nF!pxl{G2y#6m%0eNbqAC+-$ zL(TMp$?9=mmW9`rnC*BRkMq&~Rdb11a9xfzv?Pr4GOR<|;KQbuY*>^&U-}M5_@+mF}J-Bw~=+FfE!vraxGdEuVxLiDc-k5|SUE=E5#qqkF=v1=SV zr^mSx`Z_nK*Y=Nl2v|?M^8aRAiTO63@3^{OBf4B>)?l0|+-uPJ+Cj|M?k+lCJBzY~ z>cdzU;=x!_kA4*E!nBT!SSOq~z^pSz8?a(_XVIbgR+aRqrj*UaqJ#D~6%J?)m6{F2NrC zMR{xHap=&tjc%N6%HGjMRpuhB#cQ#?#W*i#a>2ers0L%w@#cr%TMEc!GXe#?Vg4SS$1D`54EmAzPK4m!);B z3|qu_=i6gp+nD&x67yGh#+?lmjLRnw_gODq>vR$76!S&cI@axWf2KzIh2wTlb0R#B z`w<pnph`jp%~yYhlLh4hCH{%(mmg~#CD zv-PEZD6fu#3os7OHw&J&^VB!2%<8&q3Bnd#?cIE2+k=U6o{G6B)?UGU6nh=#nKz6# zG~$c~eHrd8<=KF3&)``j>jli$BwyUEm-T|}gFG6f5CGX<$MUA=T4NE46z+cvw7>EX;;P{KUZQ(K!1}fqg@Yh-VZyqx;~Ee zb9u;=cS5cTdrzP9HOPZ?_6qdtE6}g6*r0ORbwJkbUE%x&bGka{xbEqibZBLj`QPoG z3tUav-~aci5Rwpza1cVW%PrRq6-77{LPn`{qRY{Rn1)kmav4HHjNx=Y-E$kwxXeLJ zW?YWJXj~iPlFOLPn34Pc^F4c==9HM<@Ao{<|M~x)=eNB+-rv2>+H0@9_FCV4>74bY z^W6#U-U(@){<=?=icAeSQ->zJ;8Sovhx@>~_tM(-#-sO39#PM~2U$PMXM&~PRUre8Os{LIo>U(1Hdw6Hj1mlRFl_*Vn?Ga;aM$~>2 zOP^``zxLUw-u6~o_QG`)-;=VyG~*WidvF#aYy90osDl~p%bMO-+hE-G!1IeWNB0?2 zuJ$wSy$ZggL*Xem4^YsW+vd`@G^>#z5O!o7S8jD7sQ0DZy|{l;=P`Xu!w>PKGa zNARbeCbzG$tZ1ugt!^b3>TQO4;~Iec=DT%cmED6!P%8+FCS0IwOzppOP%4ct1=3aZ zd`7?br-lChL9~FBA!OBFbaRa8=Tl{or>wo`>QPnCzO=t@cEfL%AUX7|I_Z~4ziFmL zw_mz9^{uCV^qcIu`84(9qu-L(%_puWA0MX8#+9I+brn`-0X+_2BO3)M$P>F=oz{T7)P{rzzD)aM~Pr^WT`hx$?3 zJN7}pebX7ey={Kpg=;}}9NA-TY|Iu$p>*hOH zPd;5gO{u3I)Se|sm)27kZQ=OOc=_A=NqNtHxN&bEFYQN+^!M$De)~y_{&82-v!4LG zzoSJ~&wjMyAL(`5mGaYX25HeRU&6}Leo*JX4aMI0)*HS8;UWCi&=fYQ9OauK%?(oE zSycmxt?+kONC_1)X}~H-(E)_$_kw&UNQ`;Xux&i_DO3QJLKmQiP|NW~oGmmA@_>S% zkD#>>ye)hj{^rOvz_$kxi5StCn{Z7z{PKumJFpqH>;e#nV(Mh)@UW1JdPMx^3; za(ONeofEFzJ#DIA9rs9-E=ACbz_2LV(mk@KT2lifB2nH{M8^maKAIdI78M*C=#D@R zhyxI)O=W3PzbF}H@{~nKVH&rvntfDg+ZN4>rFq(Xn8wC6~xnoPa8{-uKD z{gcsTlCW(%Mq9=aj8hrI7*{avU@T!QW4yq4mGL2?(PUvi9T{yIhcHfHoWmHyxR!AT z<6g#6#)phXo$e7Rg72_$!a>j>@Mqa{xEf{SW$1=`g z3}alvn9QhT+{;+Tc#F|sicr2eqYa}A<5Wf&;}XWzjN2LW8ILlSGu~l*$!I)P*k3!w zUW|^66BuQT@r=og8H^>2rHmICA2FIx-^F6ZXvgTt=)&mD7{RDu+{l>5xSR1PqptVg zsk7eB03Ks}ctCVWAO&@w0EYtKDQ++=I3Unj<`>}=J|59kf=4YzY#NzpbVOjFNAMhk zT3F0^(3UhO;>dsi3~)?Q>tyH=?iav5ca0gzaldh{1GM8gG zDLOD>u{1DZZg>RZVfY6+hr?ANiuq(tTcVp^SU^Z1x1Mv32t=F?+Hx9aVCWvHJ&vHj z2%QH!K}X^o9T9<}VADx*-@KjX9>AS3@(PRy4Gu$bx{Taj!^wWZk%6u;{s^kBZO8BQ zw)N7++Q6oqf?7rI*dG{>TMmY!T~fEnM}`G>%7eqS$HRS(DC`s}qwZ-rZ{!scIWh#1 zJ@DH^vT+b_+lW~I1Fd0a!rBE|qb|Y)8`kt1uW(&g;vS(l_=g7sO2dP-t@j;8eb-x; zYtM)FtW%T_^ux|ZlcPeU{=&&{3-k*>n|Go#kMQvM(elyJVcHIbPKFN2b)!$FgkgHh z0M{69t+s8#Lvg~;C&SQNju}oy5p;I&yg~aK9UX#;Y?O@k`r~@7=@J})&Ke%E7_}Ip z?K`7`BO;?{V^^A5^fKjjiNM67LRC-I>N{RbJmrD@!E=NCDcneiwj1?EDMF9(3jeF0 z;nxfXI54@k*|_ssTWD%U?cO;uQnxu5qphcuW+~+?=$M`T9b+EgLl zkkA|$Lq=1=WZG_uwqgAT1yU#G_E3L$=g0Gev*L&FMRMBZG_E712tGsT`Dl-Z=;ql}o1_G>fZ?5EIJ7+1&--L>0M)MTZJ4E@X_vww*+-2&bbPS{>>h zk@g&4)t(Jcj2e!cL^)V?I$s<&pHe)d0@&c^p3_lk&k_1AXZcr<w)ap6n;eqvy$l zgQNNcX?<&bAMMtjZA7;U4+%u0qb^6Z{TOGPlCW(woj=+O8(8T4T>l2s;B>XFh*Rp7 z;4DSlFTI|qZ4qs)$pikbI|jWOa7QiH9pQRIX<*=dI+OruFpkkg*Z$5lh!Jgx3#08v z(mqDe@lSLePxdU)=#c108SQ0M^xV0)@8h_g^f~o_8R22t^GQ8J>(ef4TYYk%FbX8K zuPHd%WI9^CcJC(~X-#wZ(dVvV0Tbua4mob^+t(D7GR}4K1XquK4%$0z?ilCkhWd;S zNBGDH@(9S`>E`NDlRtvDpuKQJs30pIY6OK{ly z=+H&Dn%Igxq5|y1BRxFClikO-d3lN_yL!4#p6cpiC+z0!<5kogi;zQIYh8pHZEIDK z!xZGT7RBINt2CuKmbdpqsdd}wKi-bfDR@T#=@#D|Mhg9X>()j3iDtUo? zJ{{|RUUyxWPsh5S|J}N7J00uh*QM)N_w&D7*KMcc-{r6Sxo*4v?c|e%`xuAK0;!$a zK)UM*y~!n;-j>ndR~kUgpoS2BjgL3$_?r%7%t&dpPWKh`8Gdb8^BI*(+Y;%1h{~l) zA*Ho|@O5~tD7`a8=>s5IAIa98**YF`wA)N(>7I;ukkFQopS^4MO@GFtazY_7B!}>) z2E=0#>QBc(^-(}n=QzfAkd9?JM4zvKsGJQ@PiO~QPX(!d84w+7HbnXMLv&1MAo~0g zM4wxrQK)@%ZRU`6qtDjf_#OT%@%M8t&|Tr1HxN*YW(thkS@DuA$x?-u zD&#+semPw%eEin`aj%6W3FE$hF#kxF{|n?ln|3R$9d|peG7Xcg)LClEUz)1jViIm3 zCSCsEvY4BFdERA*I=ONEJzsvk;u+$3Efuz`3KQ;k=^E$^`CbtGX#k^)F@#ah7{wUF z7|XbVF^MsSQN_5IQO$UYQNwtFv7GTLV+G?a#!AMAj8%+J7^@k%i^B03GnzA6G3v^< zX6v?${TU^UQbun^8DkV<45NZEiBZK!?Mq7uTURrdF=`mg87mko8LJq%AB5vEV-zzw zGD;bJ8Dkg~jERg%j46ytMipZ*V+o_0v5Zl}Sk73<$X#OfW7L%|X6rnogi*>UV~k-; zV$5L7XDngVFjh0F4hj3MimLtmrfYYh_5bnzts-idQ+Lb%uFvUs-givzdVbYChp1D8 zc9LupDE^z{tb5$LbzM8_{KsqD6CtF`yQZ{GaM-ZipIBpwSebA@&p zc3apEUr*9561Lust$VZg!T5@kc5z{!cVg=vY`qm*_hRdv*}4x~H)ZPqY@MDZXbEBK zy7$OYY+YB=Shh~jXS4+D5bE1eSmjo*&s(zfM7Azw>ucFMJ(tju#MbGVg_abyj#)gk zi;}I=vlJ~Vwr(k`a>Z<&o`Gm7Ve9k^NejP0s2@FB(V}Lbw-r{oGPd4@t!vnNSGInE zty{D8a<<-$tzTv9-Pw92TUX!#kosrUW1&AtJ-t|te+^QX|Je5O7-1Y2Gg3#?uSwnY zWOhK5PUm(AM9;d5pv}-;=sffrMBj7n3yp_D=%BIawi^nY?to*UEzmyb0`xo70(p68 z0u;)&L$cn2abtvbeEH@LJ)ct_kw9;7FQ5S9uoF7Zbi*QsXi(AkqXnk0C=Dcnf&a@I z{AE8kuCXQCO=@iEvF0_l^^=x5Td_H%jm{PyJZvf0Mqi(7zpg*oslS{$)BfoB2@-MD zj(zgps)FO62TL@wUUj?OZrw!72g@Z3HedSG*|fnYJ&Sfoo_(!!`6aI9`ndQnC0`G_ zn05Azd#9MA=Oy7MD%RdpoE-DjCe_G;E9Xz?G5C|G@`~6|2d}NW{_OJ?50>Uma!$Ro z@aI#%_3XPMuDgqkS=-#|LbIQbmp*rSkbU9zrw@J_yX4ceu7Rh%*e!eRQ+H zwkFYW3DFBrx{dc9bt`+*;GqLbcK_lzKKu5p;m2nUU9)53j5o8gs#3*jugtZB{LZ~v zGhRY}%L}Ik!<$@6 zm(zdMPBQ|A-kA8wmavw~|8P2X-Zs$krgz)@=N>z0ns;3>ru~@woN1E@ui28KfQC(X=AD9&}f&_ z=7+ZxIb9F>DtWMLLC0NZlbx))p167NtD*LOYnC|qO__dV=`PRMmIr1#U3%2_lZJ;k zu5A6n#mU+!^WNah9`~22dO3ZRpL*+HK>*B3QR{;0*RKG%1i`M%8PT2{IC4T*T8{`CXz zWSvIhiO8CzGuUF zw-dgM@t&dP0X`+|$!q1TshE`r(OYbui9@W|P7{2~MOve&!+ zNbOg}YVE$>e6#hB?>+To-)+@?LrpR^GCT~YslIyFd|^kI31_mtd>-LJ!Tz;Mt3Tfy zzX0@($f&+tJ6&-(Sn4uocSSFQhMAN8H5*`x8T@u=EEqP~3e-x&(_iV1KluGe{&r)&W8CPM_g~STPS*GW+Uy{-l?%=Wt2MgCYFUcz<6hg}^h&HRUkLe;+HS7i^A!>p78E6`ow2_1!lR>R zhtHiI;TIP4zJ4-wHolA&94fEVqu%WYwB0Hg-vxY!-=yQM?^+;~_>cWB#RJVJ5Y1JW z1ny$C8hp&`C!jeVEGUm7=*?_ja66>HJh@8n1he(y7g1azQ**?#X^r`&!Cp`jY>N9d zyfuEa-pZ&}j3oW|N&2ysDCW`u$OhXIzlVmwCcc6^U=y3*0mlcn88{RVH$DSVJ{W-; zWUs;aT@3g&REj)RU=KV%l?_3Cz!wmub9l&{3DI%+f)AKo1&+f5C#BQxYf2$%6Z)Nv zIUdZ&rr+BHFq?j3vkVWg+WmsRLP{Jj{pO|}9wxN;L0#-FVq-kO9z-5ucSr-9ew))r z%yAWDgR3E`LlW4rGt%2)zhDYP^;d#b%qA}FBBblb9@>DkmUx(xVq2meB!kU^-$4}T zhM5i~eqyt}I4;=4cF--@#2!#JY+tbd z0O7n#K%=38Z3YHG)K4gWjPWoWKjOPkESJSl5^M#?4aYVV_XV_vs1HcMs}OBl0d{ag zym;z|;0p*Ip@h+r+O?(Pfz$O|^K!1g822va&>JR$yj4000 z4^T0F>rA{vd0W){nbH z@t9PQ0_77ALdmf8W42K27IQEBog48}h@GIdu=QiHP>dFS3fcGuQdn)#e z`9Jhy<><%Jp?EsOq5jB2r0<2h!6wE+-mrPrNe+Hu6+~Ed!7rbD@gCa3}?_7vx~OK%q=A zxCzqwAMgpY>G!Q4K$K3uy*bCLToIe+YzepuqJFLhbum$hQ=zrU zLkx$Mu!-BDy|B4?u%U9avl46(f^*#w^#`Xw+WLSynN7d9J_6Cc=r_yFLxntMU_7Mt zx1e2^VAF4bqnNE9GlgQQbPdONM;(ZEkck-Q9Xtxrek;Jma-keGn7#mg8+r8Ooao0u z(T|Zru~UA6WXMna6^eyTJQImFflUmKLYu(Wk7uGE>x5#SD4<)&Lp%b#giVZCh&m&N zhyvUVX|Gd@@a_vDo45v&;uwiLAQ^1pZf0vhhZx~_CE!koe3TMwv6%H4a3Vx)A_ey` zTMc$zBBb+RFtg?0PG(aalV6~{s3*l3@%Rw;2I!N%;AV)6aZTcW>GrI7cav;p{po|Q^3!~p}(R% zi8GgDJR;o}Tn1_T5~z!*M7$1JArJ8}#KSgQ@mEZxfv`V-BuFPNfV^NQfdvqiSqxr+ zD0T?ZekHy~1Dp5|+76r8Edjm=HV>9U{V`8~2K@G8oJXWSJ6I>I+f4 z65?~H0yZ&ZBm4_&VgzK4bD`Xj#@{5A#qaKZ6{ zw%cGMj}*KH(S2j_XE?6yXd~>)>~ow$$PN8m0ah}*3hcQE2^)b@&A#5JD{`}%J@AwYL0_{LN2HC>a zpYNRJJrDT`egNAN6Ce%jB=Ey;(C=X@z_?R_tv~PnWu)om>ervgpXT?^foyskY1#A) zu1T}^iO&ktI!Ipr!x%lA@60> zp(ol0?0N;)dS@I9=zSHRAzeSd1jU`OyoPHE(uuZE32YuLy9L44fR=Y~9f2(d7v06! z#D0^&D-iXE3ee~tzE^p&z$`;#rs( zh&V4C7jXw9gRKO0F=L45AQPMyqM?z96T>zGZ#KZ(wsaoB*$pu#55}o4I2v<-sc2td zC(My_mChIV2Sj5^KV}HU4k^VvvH{fQU|Y;zOg>XT4hh90F~VH;j>zK+E@_8taGlkU zYeMl(E_4*3@!%7{mykJZ{CJQHg6O)SA9I3YQ8W@`4qfzBVoOK`TMX*rbPyMIM$8J- zpLnDT^1vpZBEcrccNNl;z+ToO?YZDVDYJu&CfArvbApI4w+iJk2ggI&dmC^QRE%08g+j#S8clDuW#h-iE0Dm7odckEi_-7ebUC1Li_hPCobpM0v`=rUO`ha0x_t zV!`Xot^g+t6v~l;Hz2BK1=w{k=D*~PIBW2Op_mT}wlBDCxL|Jw7mq-hNRI{GB^ZOS zJ;323g>(sM=q%z=kZubGLsYjAP~(C&M>=ul7#uHbA8^iC!9EBkd0=0T@Lk}GiI}(E z-iUh%&XWr1A)x&vNy-Bo6k(SVEb@z#(1;8-YB-z(Ww-SE#}8DTpCT%pWF@F_%PR)a@_gkvcMDEx$FN^1_#s5??-h7Y`F+9TOW^mAUIu>hA?gM@37j4);c?0c*&Bcqjju4e82B$-`uZQ5c6|j-V16&1B8?FWOS7Ls2q!YU* z2>ETmb&yFv96Na6WB5(j2f-_=L|iiLtKc&ze* z3OgTsvJ>$cU=!ykG2Vy32ZAQ4LLJ25=a3un6oW0((f?tagL5-*jIa~I<4}wX`WU!0 zQ#cn2ut^r$WHiPa*axEH;=vgZ<@W(sv2>cd?R#dw1SQ$1cWd0|fQy+O3;qBFV87+y z8;Hs@SD|m`pnoDg3AD)-wk3K)+OYs0hbVs;_>9>hc_J_J?f(c891h*?^%C^-nn%y9aHKzLW%Z+lRWsrg$ej-1aT{G}5<&>QnHm$WQ#`wBT>6z}{zs{I*~oME)%w?0#0TZNM~U zXMi0wLb@2-#_a82`*T9N6}W+H>?;}k4x;*>0vmnL>IRNtwhI{a1I8Ef%RsLmMV#0X zZ42Iq%wRtR=U*1;90J~9b|n~mg{6a45M8r~v#-OaVOw8N0Z|=@XCOKk8nB9`OK#vk z3evuR0Dplfe--FiA)H4!xE@MEnMvR)C>b`Un&1{dO4zr+<~N0H&4>{70pip!WKVv}AbKIMa!n|zY_YhrkFM$3pFs_j&0BrRV{U5eDI2xjM@B&kqO>Fr} z#JNx&FaV16Ep z6xaZ<38xKmAMwIhEzx=S|LU`Jr@wSLF7NTgC4C6@b@8<1G-{fcn$Kqflh63Y_KI@ zYFh(Nj64}&G-4__!j1v+Ee$v+?7iUFb_QDC;squ{biLaSwr?+_^I$MU#}WcMBHjQU ziw77&HtHM$W{PnvC{qQt?`)v$dsblcE~r1!&A>}t4Yc=EARhz@0*VF}M<e!=g0V}5Vgr@-cYgyS*;ZS5eW6SogU`LKx}AvQr2Yz63# z_ybh80MH$A2$V?o0B=AvHY>pSLvbuf4*|y`)<6YpDLB%_fHN6x#JPZrT~Q9~Sa7DB z0p|@{4kkk}u$5p5q=2mkk3cJ6Yru0*BJ2xbYj@!oEx;6LEz*h0$Kn`ZuK3tpN>Y3FpNK zdEQRv(C=Yi0E-l; z8|-3mSsdyNTLF%VN1MZzf?J@Muv5Tx%dubhQY-KT1_}g~W2V?39IPG)zO4#1uOr-%Qf$amXhNzv_ zg1)I}E2I;R({Qd~6DL7*9=*VB=?0t}*GC(0C`8*111~|b$X^Z?WuQG_7lS7t8rNmu zrcC$<*vX(K8})}x9`d07D8K^{HwyQ$;6tbaWfHd* zqHiO8JNRlhjte%o2Qd@&p%1`51-AUcKzm$r@DP-UbhG{NuTU{;Z}1qT^)29#FHvWt z4+Bd`u!(EF62`?^u;l^4HU|qK@`1(R+CyklJbMxk9)>T)w#3U2wa-Pw*7IZuVpNaEMV6Y5OE-aT&f5=@sC-tGF)14gnPqwK;M1HM9fL*Me(r;+&EVRztKe z;^Esk7T9X=t9wHJgW&Z0$cJSx^M~e)#wi}q!*pPEUdOm31 z#8BG~#b9hx!6w?82sUvKv-g5dW`^tU_>7;I&z zy&nhx4LYG7*q0IL0#W-D_jkszA%6)t1F<6M+TjEC?_|9MG2|p2aGe4JASrA)sD>~hq?Q%1V_*}F zM&ev_hmQgWLDfi?fb*bAq|3q2A+9U-1*##7E+_}AfD&O7UqFtXQ0GzDCscvISrF49 zU;Led;_{w{ig691SoIX2R^0>b08$)T54@A1c%c;2lWZcz<4neTDk8<)q;w+1%Osmf zu`tOdQryF}c)vuX7?YGvr1+3z6Digq*+hzSNH&pT5Ry%#Sb}5|DUKl7M2fjrjDA9- zIDwQ-q!@u@6Dcko*+h!BM)e_5Of^a;Qp_{5i4^aQY$C-bBb!L^yvQa}JQuQw6z7U; zBE@JTn@Dk#sI7<;bBJsr#pa4w@4SK+obd9 zj_Hzgw{&T`ce-!7EM1YFn4XlLl3tu%lCDm-$Pj1PWbhe|8IlaQ3~7dUhHr)}L!J?n zp~y(dkY;&j`DV$oZc zv%Rx@vt`-k*%jH9*;U!q*__H)Wu~%FiB&c#&KEH;QMaU`lpmbFW^s?oYGinrnFFsl{QLV>8O+_-IP+Lw^F8*D`S)jWuh`knW9uGtCZDBF4Z{I zEY%`aoNANGr#hxeQr%Lesotr+sj^ggYD}skH8C|QH6>M$rKO}P(^P4EmSdJGyEt2slbDl~laiy%QRNipl;o&$ z%5pS0*&a$m&KQpn#&5Mp z%Ky_Xl9-v2smd(LEXyp`ib&fH5zYTi6TdsGmEH@@MF*hYwm0OZqmRp`% znOmJ}oM(||ljoS{mgk)(%ZtJINWu6h!PqGOn{lDZugI^;=L*aU#07kTq(EBWTOcn` z6eJZW3yKTW1)7420(`Tm(5z5g$QMcqrG>tQ@cdrcp45~ zMhp)lfp_tRXHmebDB)4mshZS^)T&f2%?v%0hgXrpqsZY+lHf^-)6{92w2HK6-M4^s00&!wg=ShXYlQNVU#Tn`hO-4mVRR))7 zmMPBUGbNeQOy5j-rXn*bQ<+(usm|17R%BLXa#?0s;w(N(k|l+=mcvsg!Alossk1cj z(N*xzX4&Fw9v)f>?<~(&WG7`S;o;QT8u;ld_-HfuXI>>yNmafoxk{l*QYlr%Dz!?Z zs!&y_xE!+_aSop&$&u#x=E!pt@QX_LL^b?j1$-d~KPZL|l;lcteRJixirl1JWo~h< zI#-ihkz19^;d^DA2KNJi?kYojw81_du~#?j*Bg75Vc#*>dm{FqqWb6h7*~ONc$8m_ z*3iF7sWBQfb*@!r7#CuU48G1)OO7$3z$i(=I8kDx6l1KYF@jX~S$t~%NtiZB1+UJJ*?{kQf} zvwU$rpD)Rm=KJQ$^A-6?`O5s_e09F2-f@a=glXqzQz=nzU%XER^snW@6)T ztDy5$`_6*;F13spzJ!N2k-(ow;Zc0yQ#81OqHsChQQ+ReOnZI!yX$)~u32hawKTYH zRp821g=?4YIwG#;eo0<)$E3vdOt@<*!^kbi*sa9qt;YB@#t61}&z)2vMsy0sv62L(F^Mns9-!~E?n`L>kYw3XSS zMT_hL@R2`0vhxoQwYTQG&_{-?+ShC`GBOfBp$`zdyND-;hewH>NAexpHsc4{+uQTP zGNWy?epstn{l8U>cu^Pq1`svi4C6)3aUu~~GhT#mKbW>YbIV!bv+LvE_xnCu&@!{| zYWL*C+$U%L5D&KT_BE+iT+V6zse|9JeY~Vd$mDY2%vpe$zDK@(y3kx}*Uo zVy1j7PCa`&v`LwJtbIzqkS_N=);P>a`>IuZi(dw}{e0_?h}1jJGk(0-);_v$CiFTA3E_-Iz6X&!OF0e#yqBllH=tv2Cb6Rgj>kW8AfbT#Frbcay%v~R(6+PMbUA%ptNo%sR zJAeLrXjyZ<6Mfv($bxU9s6RvPeu&c`;?hhH-njWo)z1-;O9GO=ei|{i+~L-!=sATS zKltt9kJqQ}*?H=Wxy_f&w)pzA^zgoQe)w{CSMMzYg4?Oa+@E@4abC;vptuz`mNg!h ze5a(lt@zOJJvOVJ&VJM7=9U$m?gjq(am9@zLGF8IJ=op2*MsiA#2o&}srT>uyAKGR zy-M_j`^=r92A|~(?{?(W7t4-54o^7oJV5p!u21rVQTv~-?Rag@81xSVoyw%et+DyMHd>r9ID@QY3RnS(HpxnM(W0{aVwK)frwue5hix_lLy+H^DS{M zj2g9S>Jl9>#}6Ts5J%0vIZD$G^oCwCzeQ1j_8s{4l+d)5xsV{H!B5d@v>`a`J84fi zhIt$IF~#XXOtw%&3JPK)+}^?7!GVowjBp3u-k~4w&~L!t0fT4oALvyUj)v{7Nh@;% zit|H^8h^2Kc!WG0zkNr<4-{fYwJ~hfqvm7Uq1aQmN6)~Bg>XWV*tNKic#H#v@cW1M zuKYdjUgNe{wQN$}ZSjUK(|UzpE$LqB96A5!*LKnwFU*fFT<0w6=Daucrt6c+{U08S zI@RUU-ek_;>G)s1-n-w$dj9Fzu0zkcoN;a$**1Pn@ZR3vZS9yJ(Z2im1)X-;Uwbjh z&%iS)_YZg51~IOgeOH~iyY=qtwKu0Z4L`B*>e%WJ``udHhi9jvG$entLf^ z=ceF~1A8uCdDPduwCvQtPg54OICxWZFlAdiqDsCt}KhqoZ#m2#`301qm4~3$yO+4&5H?e zJ?%Sssn?NKvBwubK6zw;Ftp>I^Kno0#_sHGe}ws*Iu*6;!nKcnb-MDs5mWjYJ}&?mRhow$6(Z+Q_1!7e8j?AXTs5g~fp_7!@Reur`%X@@-8Yf*=8Mkag{T@4J4>v*PyybbN8 zg;8g|QwBPf?owsg%8Uxs_7_Bl=Vx<)o_89pYbaBz$2Ub{XkZg*_mgXx>O zf-@%LcWdmkjD317d3ke5hiM+FK#O~eC3CuM4*TYtLGzY(HeNUK{``KQKke{>}681DUdW7sn|2$K!bIPU+q<2cQ~>0p3f#DKG+Kp>B^x3hlol2*%*zA z?4upyiz4kJnTOU6^g%Uw4HA0)mDexW&#q3^zEP2pef<6U1UcB@Zjm2GmFr|QfbYlK zEBh+@=xK8uO4-M+%9CIgT z-)S2oaeD6KaixhpH<&8UwRm~WXJOdH4@_N0j|^*8eBW`~t|6BjFED#)wRo@M!~EbU zueN_-(x&(0WiuNO|7_;XHs7|23+3z_o2h!PxBY4NlNmXpqSo7O`?|Nk(&fOh*D=YH zjwS4hPn=aXeD9>x#r=BQefZ^7apP7C9?Y|xdA2f>pJuzt-RaA-%T9hhqKnMmbK9Zd zsQlv{hArDzaqOT~xluG9-=I0%)KliBj6I6RKiO*DK{9T^)?C}pwH#|x+?Yhvb`$^n zGlf0hSMVG*HO~~DZX+GUdJh&9UQA4WL+|!u06*AaK#l9Ncf?&pKYK(5;`tf;_}X=% z=QH>w<5mXKM%uT~-reF3$#_&C?u`~k2iluzM;4xg8X%b5!kTqMw*I$X>ej}B%e#H2 zoeDjRpRlhpeATw?kv4Hx9?D$uY&*W5)^khK@Q3lv>OG!!UnKdQDlEI7;okL3xQ*BG zrnf)*dD7$~otkefcs289?$UzQ;w9fUxxD(c@kg19YzGfGc)BtQ?E5k?xA5FJt1~T}y04j1x_v}4cYC|Yd*G|vORbBoEHcZ+t(fyH z)+R2}?p3AFS5I;ub7Ov+^l154mSK&9&MaCU`D|CEOWM+h9Ued4{Cm4C*Vhd)`=ig& zwG-TSn;IWEyGiGzO3_m4T4QcT>6ah&YLcFLe}SRe_gSAm1EWp7^~UU^S5|H2CyyLo zHspHnhWRqZlsC&fYhUu=zvvmY&V7L)zew;eaz2b7pzNo#Pw4yC-A2D!&#ZkTWquBQ z{Dh~}KK_w?g6y@o8*gpa{~y|H9PLOMjDb(VVajT$xxiZc-z@o_73+rT%+@C$is-8y`;1v?_GW7dBP=O@(UGDsMu zJ8n$H6%iF#`xtZsipCQgPVO!=nAlj--g!mUxvuEBM2v6kvzqm~^&S}>i|!lwl-yX* z`P!)q_bqc{kHVg4!V8DRWQ^X?ptbb7hMy%Ge=;WYVsKU7 zhZ$R*G%a=Y{zlfhwQ5P>!7=GiM`vZ7{&-E!;O3)$*D z8EZ|xDvq14`QWEyldT1pk6aAo225{OFzEcQ?_yt`ko-2W#{(0GM`v1}3>{Kv_h#hD z7Y$42RSy`neA{O)7oBns+BeSiis5%FC(awBc6lAsVQ!blyE{f5Of#LnxObc3t$uC& zGSBkknSOD%P9LzIlX4>>sJ*LVv&FS#8*eEqE~MpcO|tZtd+m0a`?^=wya{2gV#=ip zTTFpVJvgv-nI{4_($-kKgtzPANp-*c1y+m8_r-fEyKQ_K$^2g2bz7~gbOLrH_ z?dSGeFd|=`mUm{^z1Z(IrrsWEZ*}(mZ%uAZJ1}zOMO^v`X7aPa_W=TDfb^^2m|# zjcz%vnHMS6G!KXzwqs{jznoW=H@a;)r*oC3;VMto`y5sGT}-|1Z?Vn;z;A@|^Z!A= z;jG(=H%J)tkNAxmpFwZ-n6rqB6I|~SK87EHzkLr(=&vg(BBYKF)%l;d%L#dV+d6Lh zecMhHoUj`|ns;p2ggIf(!04ay!g$Qoxo^EoQoUEKf9Cy`&S#Ez*ldRNp5MEiYh7j= z+pXt9RfkzteTK9v{gwB-w6v-3t7F5Pmlmyg^=q#i;wgiQfBN&>#^~mg_J(Dyn{o34 z>$nMK8IPP6tn)W*HLl>&Y?sBq4>WJM`sw!36MWtz?P}l1bVKVGUlr|}bo3MJLhBRX z^yrn^)27{!1vUo5>^7vUyS2Ev-F!^y5}B;%vuq!+&yNdsnXEscsy^OQw)3pyJBdqX ztExKzCf$rjIqV*|+S=fC--xAFm)u=9S5EJ6?|D?f{M`@cI$z#Xy!PU~X4n1{iO+1c z_aAQD&SFp8XA@6sGHdviN87vc*cfjT`RELR=hn&rQ8+k+Cgc z(y#XMhHr2i`NBXX;^PwjJDib$*<1Inf4!$yN_fkfm*b5M?M?Jv(i`zz|N6+t9&bHA zRE{(`>^{fg_O!329v`3P?$xVPPkpbCcgsfcA}+9_;_2!1hbOzP3jI3N?T^)&9tF47 z+IbY6xpv7Ze8Jf`qZJPW2af)wOV@dWD~3<|eehR`oeSJ;mQTN2d^n?{ouXftJ08{t z_*u~b112W>O}38P^27Apv)?>zaj$&j0?9satEFrHnDZw5=iT;MD?hnEVPeWq??!%i zoHCyGy_?hULGHP!`91t{Y)mI_taiM3Z^hH^r}e$L{O(<)Ppja9;hHa#GR!7E+OaEU z+Ovgm-tJGUytkVA9KRTJv|K)3y)xm4$;Yo4JnuSVPP4q1o0p!=-xGVMnQ3l=&V9b0 zV>$MD`X3LxPwX3eYhQkor`@yr_PjMY?{xY)`>Go+Qo|n(Tl2^2WuInUE1Q`bZ_pHf zj%f5(>ov5G7gfX8J)v$8@n8K;!@%sVmnwQ^d=_uJHOZEZtN*x!I;iFQm0bk!qd zWkkv9Z69}ZE8OzM{?08#;va7-XLp*v@%7G5jvhapoMMu{`0k)@A}8$a z{p4YRjr*z@A&rK$aGR97FxJfa5I>{$tfHou$C-co*}hee3Y~otE^fZo@j&(dqZ@)} zxAFS1=(OXGDa#&&{P}p^kzmsypBuY6KeOr9-(1<&?bnf4+rFG|W!{eUh3h)L92zcD zHaGCzVQ}Ehr&7lqmJYp^ciS_h$;|XNX8f^T<@|1wmE~>&_IobhJKwSVCIKPr2J8vp + + + +// vrtypes.h +#ifndef _INCLUDE_VRTYPES_H +#define _INCLUDE_VRTYPES_H + +namespace vr +{ + +#if defined(__linux__) || defined(__APPLE__) + // The 32-bit version of gcc has the alignment requirement for uint64 and double set to + // 4 meaning that even with #pragma pack(8) these types will only be four-byte aligned. + // The 64-bit version of gcc has the alignment requirement for these types set to + // 8 meaning that unless we use #pragma pack(4) our structures will get bigger. + // The 64-bit structure packing has to match the 32-bit structure packing for each platform. + #pragma pack( push, 4 ) +#else + #pragma pack( push, 8 ) +#endif + +typedef void* glSharedTextureHandle_t; +typedef int32_t glInt_t; +typedef uint32_t glUInt_t; + +// right-handed system +// +y is up +// +x is to the right +// -z is going away from you +// Distance unit is meters +struct HmdMatrix34_t +{ + float m[3][4]; +}; + +struct HmdMatrix44_t +{ + float m[4][4]; +}; + +struct HmdVector3_t +{ + float v[3]; +}; + +struct HmdVector4_t +{ + float v[4]; +}; + +struct HmdVector3d_t +{ + double v[3]; +}; + +struct HmdVector2_t +{ + float v[2]; +}; + +struct HmdQuaternion_t +{ + double w, x, y, z; +}; + +struct HmdColor_t +{ + float r, g, b, a; +}; + +struct HmdQuad_t +{ + HmdVector3_t vCorners[ 4 ]; +}; + +struct HmdRect2_t +{ + HmdVector2_t vTopLeft; + HmdVector2_t vBottomRight; +}; + +/** Used to return the post-distortion UVs for each color channel. +* UVs range from 0 to 1 with 0,0 in the upper left corner of the +* source render target. The 0,0 to 1,1 range covers a single eye. */ +struct DistortionCoordinates_t +{ + float rfRed[2]; + float rfGreen[2]; + float rfBlue[2]; +}; + +enum EVREye +{ + Eye_Left = 0, + Eye_Right = 1 +}; + +enum EGraphicsAPIConvention +{ + API_DirectX = 0, // Normalized Z goes from 0 at the viewer to 1 at the far clip plane + API_OpenGL = 1, // Normalized Z goes from 1 at the viewer to -1 at the far clip plane +}; + +enum EColorSpace +{ + ColorSpace_Auto = 0, // Assumes 'gamma' for 8-bit per component formats, otherwise 'linear'. This mirrors the DXGI formats which have _SRGB variants. + ColorSpace_Gamma = 1, // Texture data can be displayed directly on the display without any conversion (a.k.a. display native format). + ColorSpace_Linear = 2, // Same as gamma but has been converted to a linear representation using DXGI's sRGB conversion algorithm. +}; + +struct Texture_t +{ + void* handle; // Native d3d texture pointer or GL texture id. + EGraphicsAPIConvention eType; + EColorSpace eColorSpace; +}; + +enum ETrackingResult +{ + TrackingResult_Uninitialized = 1, + + TrackingResult_Calibrating_InProgress = 100, + TrackingResult_Calibrating_OutOfRange = 101, + + TrackingResult_Running_OK = 200, + TrackingResult_Running_OutOfRange = 201, +}; + +static const uint32_t k_unTrackingStringSize = 32; +static const uint32_t k_unMaxDriverDebugResponseSize = 32768; + +/** Used to pass device IDs to API calls */ +typedef uint32_t TrackedDeviceIndex_t; +static const uint32_t k_unTrackedDeviceIndex_Hmd = 0; +static const uint32_t k_unMaxTrackedDeviceCount = 16; +static const uint32_t k_unTrackedDeviceIndexOther = 0xFFFFFFFE; +static const uint32_t k_unTrackedDeviceIndexInvalid = 0xFFFFFFFF; + +/** Describes what kind of object is being tracked at a given ID */ +enum ETrackedDeviceClass +{ + TrackedDeviceClass_Invalid = 0, // the ID was not valid. + TrackedDeviceClass_HMD = 1, // Head-Mounted Displays + TrackedDeviceClass_Controller = 2, // Tracked controllers + TrackedDeviceClass_TrackingReference = 4, // Camera and base stations that serve as tracking reference points + + TrackedDeviceClass_Other = 1000, +}; + + +/** Describes what specific role associated with a tracked device */ +enum ETrackedControllerRole +{ + TrackedControllerRole_Invalid = 0, // Invalid value for controller type + TrackedControllerRole_LeftHand = 1, // Tracked device associated with the left hand + TrackedControllerRole_RightHand = 2, // Tracked device associated with the right hand +}; + + +/** describes a single pose for a tracked object */ +struct TrackedDevicePose_t +{ + HmdMatrix34_t mDeviceToAbsoluteTracking; + HmdVector3_t vVelocity; // velocity in tracker space in m/s + HmdVector3_t vAngularVelocity; // angular velocity in radians/s (?) + ETrackingResult eTrackingResult; + bool bPoseIsValid; + + // This indicates that there is a device connected for this spot in the pose array. + // It could go from true to false if the user unplugs the device. + bool bDeviceIsConnected; +}; + +/** Identifies which style of tracking origin the application wants to use +* for the poses it is requesting */ +enum ETrackingUniverseOrigin +{ + TrackingUniverseSeated = 0, // Poses are provided relative to the seated zero pose + TrackingUniverseStanding = 1, // Poses are provided relative to the safe bounds configured by the user + TrackingUniverseRawAndUncalibrated = 2, // Poses are provided in the coordinate system defined by the driver. You probably don't want this one. +}; + + +/** Each entry in this enum represents a property that can be retrieved about a +* tracked device. Many fields are only valid for one ETrackedDeviceClass. */ +enum ETrackedDeviceProperty +{ + // general properties that apply to all device classes + Prop_TrackingSystemName_String = 1000, + Prop_ModelNumber_String = 1001, + Prop_SerialNumber_String = 1002, + Prop_RenderModelName_String = 1003, + Prop_WillDriftInYaw_Bool = 1004, + Prop_ManufacturerName_String = 1005, + Prop_TrackingFirmwareVersion_String = 1006, + Prop_HardwareRevision_String = 1007, + Prop_AllWirelessDongleDescriptions_String = 1008, + Prop_ConnectedWirelessDongle_String = 1009, + Prop_DeviceIsWireless_Bool = 1010, + Prop_DeviceIsCharging_Bool = 1011, + Prop_DeviceBatteryPercentage_Float = 1012, // 0 is empty, 1 is full + Prop_StatusDisplayTransform_Matrix34 = 1013, + Prop_Firmware_UpdateAvailable_Bool = 1014, + Prop_Firmware_ManualUpdate_Bool = 1015, + Prop_Firmware_ManualUpdateURL_String = 1016, + Prop_HardwareRevision_Uint64 = 1017, + Prop_FirmwareVersion_Uint64 = 1018, + Prop_FPGAVersion_Uint64 = 1019, + Prop_VRCVersion_Uint64 = 1020, + Prop_RadioVersion_Uint64 = 1021, + Prop_DongleVersion_Uint64 = 1022, + Prop_BlockServerShutdown_Bool = 1023, + Prop_CanUnifyCoordinateSystemWithHmd_Bool = 1024, + Prop_ContainsProximitySensor_Bool = 1025, + Prop_DeviceProvidesBatteryStatus_Bool = 1026, + Prop_DeviceCanPowerOff_Bool = 1027, + Prop_Firmware_ProgrammingTarget_String = 1028, + Prop_DeviceClass_Int32 = 1029, + Prop_HasCamera_Bool = 1030, + Prop_DriverVersion_String = 1031, + Prop_Firmware_ForceUpdateRequired_Bool = 1032, + + // Properties that are unique to TrackedDeviceClass_HMD + Prop_ReportsTimeSinceVSync_Bool = 2000, + Prop_SecondsFromVsyncToPhotons_Float = 2001, + Prop_DisplayFrequency_Float = 2002, + Prop_UserIpdMeters_Float = 2003, + Prop_CurrentUniverseId_Uint64 = 2004, + Prop_PreviousUniverseId_Uint64 = 2005, + Prop_DisplayFirmwareVersion_Uint64 = 2006, + Prop_IsOnDesktop_Bool = 2007, + Prop_DisplayMCType_Int32 = 2008, + Prop_DisplayMCOffset_Float = 2009, + Prop_DisplayMCScale_Float = 2010, + Prop_EdidVendorID_Int32 = 2011, + Prop_DisplayMCImageLeft_String = 2012, + Prop_DisplayMCImageRight_String = 2013, + Prop_DisplayGCBlackClamp_Float = 2014, + Prop_EdidProductID_Int32 = 2015, + Prop_CameraToHeadTransform_Matrix34 = 2016, + Prop_DisplayGCType_Int32 = 2017, + Prop_DisplayGCOffset_Float = 2018, + Prop_DisplayGCScale_Float = 2019, + Prop_DisplayGCPrescale_Float = 2020, + Prop_DisplayGCImage_String = 2021, + Prop_LensCenterLeftU_Float = 2022, + Prop_LensCenterLeftV_Float = 2023, + Prop_LensCenterRightU_Float = 2024, + Prop_LensCenterRightV_Float = 2025, + Prop_UserHeadToEyeDepthMeters_Float = 2026, + Prop_CameraFirmwareVersion_Uint64 = 2027, + Prop_CameraFirmwareDescription_String = 2028, + Prop_DisplayFPGAVersion_Uint64 = 2029, + Prop_DisplayBootloaderVersion_Uint64 = 2030, + Prop_DisplayHardwareVersion_Uint64 = 2031, + Prop_AudioFirmwareVersion_Uint64 = 2032, + Prop_CameraCompatibilityMode_Int32 = 2033, + Prop_ScreenshotHorizontalFieldOfViewDegrees_Float = 2034, + Prop_ScreenshotVerticalFieldOfViewDegrees_Float = 2035, + Prop_DisplaySuppressed_Bool = 2036, + + // Properties that are unique to TrackedDeviceClass_Controller + Prop_AttachedDeviceId_String = 3000, + Prop_SupportedButtons_Uint64 = 3001, + Prop_Axis0Type_Int32 = 3002, // Return value is of type EVRControllerAxisType + Prop_Axis1Type_Int32 = 3003, // Return value is of type EVRControllerAxisType + Prop_Axis2Type_Int32 = 3004, // Return value is of type EVRControllerAxisType + Prop_Axis3Type_Int32 = 3005, // Return value is of type EVRControllerAxisType + Prop_Axis4Type_Int32 = 3006, // Return value is of type EVRControllerAxisType + + // Properties that are unique to TrackedDeviceClass_TrackingReference + Prop_FieldOfViewLeftDegrees_Float = 4000, + Prop_FieldOfViewRightDegrees_Float = 4001, + Prop_FieldOfViewTopDegrees_Float = 4002, + Prop_FieldOfViewBottomDegrees_Float = 4003, + Prop_TrackingRangeMinimumMeters_Float = 4004, + Prop_TrackingRangeMaximumMeters_Float = 4005, + Prop_ModeLabel_String = 4006, + + // Vendors are free to expose private debug data in this reserved region + Prop_VendorSpecific_Reserved_Start = 10000, + Prop_VendorSpecific_Reserved_End = 10999, +}; + +/** No string property will ever be longer than this length */ +static const uint32_t k_unMaxPropertyStringSize = 32 * 1024; + +/** Used to return errors that occur when reading properties. */ +enum ETrackedPropertyError +{ + TrackedProp_Success = 0, + TrackedProp_WrongDataType = 1, + TrackedProp_WrongDeviceClass = 2, + TrackedProp_BufferTooSmall = 3, + TrackedProp_UnknownProperty = 4, + TrackedProp_InvalidDevice = 5, + TrackedProp_CouldNotContactServer = 6, + TrackedProp_ValueNotProvidedByDevice = 7, + TrackedProp_StringExceedsMaximumLength = 8, + TrackedProp_NotYetAvailable = 9, // The property value isn't known yet, but is expected soon. Call again later. +}; + +/** Allows the application to control what part of the provided texture will be used in the +* frame buffer. */ +struct VRTextureBounds_t +{ + float uMin, vMin; + float uMax, vMax; +}; + + +/** Allows the application to control how scene textures are used by the compositor when calling Submit. */ +enum EVRSubmitFlags +{ + // Simple render path. App submits rendered left and right eye images with no lens distortion correction applied. + Submit_Default = 0x00, + + // App submits final left and right eye images with lens distortion already applied (lens distortion makes the images appear + // barrel distorted with chromatic aberration correction applied). The app would have used the data returned by + // vr::IVRSystem::ComputeDistortion() to apply the correct distortion to the rendered images before calling Submit(). + Submit_LensDistortionAlreadyApplied = 0x01, + + // If the texture pointer passed in is actually a renderbuffer (e.g. for MSAA in OpenGL) then set this flag. + Submit_GlRenderBuffer = 0x02, +}; + + +/** Status of the overall system or tracked objects */ +enum EVRState +{ + VRState_Undefined = -1, + VRState_Off = 0, + VRState_Searching = 1, + VRState_Searching_Alert = 2, + VRState_Ready = 3, + VRState_Ready_Alert = 4, + VRState_NotReady = 5, + VRState_Standby = 6, +}; + +/** The types of events that could be posted (and what the parameters mean for each event type) */ +enum EVREventType +{ + VREvent_None = 0, + + VREvent_TrackedDeviceActivated = 100, + VREvent_TrackedDeviceDeactivated = 101, + VREvent_TrackedDeviceUpdated = 102, + VREvent_TrackedDeviceUserInteractionStarted = 103, + VREvent_TrackedDeviceUserInteractionEnded = 104, + VREvent_IpdChanged = 105, + VREvent_EnterStandbyMode = 106, + VREvent_LeaveStandbyMode = 107, + VREvent_TrackedDeviceRoleChanged = 108, + + VREvent_ButtonPress = 200, // data is controller + VREvent_ButtonUnpress = 201, // data is controller + VREvent_ButtonTouch = 202, // data is controller + VREvent_ButtonUntouch = 203, // data is controller + + VREvent_MouseMove = 300, // data is mouse + VREvent_MouseButtonDown = 301, // data is mouse + VREvent_MouseButtonUp = 302, // data is mouse + VREvent_FocusEnter = 303, // data is overlay + VREvent_FocusLeave = 304, // data is overlay + VREvent_Scroll = 305, // data is mouse + VREvent_TouchPadMove = 306, // data is mouse + + VREvent_InputFocusCaptured = 400, // data is process DEPRECATED + VREvent_InputFocusReleased = 401, // data is process DEPRECATED + VREvent_SceneFocusLost = 402, // data is process + VREvent_SceneFocusGained = 403, // data is process + VREvent_SceneApplicationChanged = 404, // data is process - The App actually drawing the scene changed (usually to or from the compositor) + VREvent_SceneFocusChanged = 405, // data is process - New app got access to draw the scene + VREvent_InputFocusChanged = 406, // data is process + VREvent_SceneApplicationSecondaryRenderingStarted = 407, // data is process + + VREvent_HideRenderModels = 410, // Sent to the scene application to request hiding render models temporarily + VREvent_ShowRenderModels = 411, // Sent to the scene application to request restoring render model visibility + + VREvent_OverlayShown = 500, + VREvent_OverlayHidden = 501, + VREvent_DashboardActivated = 502, + VREvent_DashboardDeactivated = 503, + VREvent_DashboardThumbSelected = 504, // Sent to the overlay manager - data is overlay + VREvent_DashboardRequested = 505, // Sent to the overlay manager - data is overlay + VREvent_ResetDashboard = 506, // Send to the overlay manager + VREvent_RenderToast = 507, // Send to the dashboard to render a toast - data is the notification ID + VREvent_ImageLoaded = 508, // Sent to overlays when a SetOverlayRaw or SetOverlayFromFile call finishes loading + VREvent_ShowKeyboard = 509, // Sent to keyboard renderer in the dashboard to invoke it + VREvent_HideKeyboard = 510, // Sent to keyboard renderer in the dashboard to hide it + VREvent_OverlayGamepadFocusGained = 511, // Sent to an overlay when IVROverlay::SetFocusOverlay is called on it + VREvent_OverlayGamepadFocusLost = 512, // Send to an overlay when it previously had focus and IVROverlay::SetFocusOverlay is called on something else + VREvent_OverlaySharedTextureChanged = 513, + VREvent_DashboardGuideButtonDown = 514, + VREvent_DashboardGuideButtonUp = 515, + VREvent_ScreenshotTriggered = 516, // Screenshot button combo was pressed, Dashboard should request a screenshot + VREvent_ImageFailed = 517, // Sent to overlays when a SetOverlayRaw or SetOverlayfromFail fails to load + + // Screenshot API + VREvent_RequestScreenshot = 520, // Sent by vrclient application to compositor to take a screenshot + VREvent_ScreenshotTaken = 521, // Sent by compositor to the application that the screenshot has been taken + VREvent_ScreenshotFailed = 522, // Sent by compositor to the application that the screenshot failed to be taken + VREvent_SubmitScreenshotToDashboard = 523, // Sent by compositor to the dashboard that a completed screenshot was submitted + + VREvent_Notification_Shown = 600, + VREvent_Notification_Hidden = 601, + VREvent_Notification_BeginInteraction = 602, + VREvent_Notification_Destroyed = 603, + + VREvent_Quit = 700, // data is process + VREvent_ProcessQuit = 701, // data is process + VREvent_QuitAborted_UserPrompt = 702, // data is process + VREvent_QuitAcknowledged = 703, // data is process + VREvent_DriverRequestedQuit = 704, // The driver has requested that SteamVR shut down + + VREvent_ChaperoneDataHasChanged = 800, + VREvent_ChaperoneUniverseHasChanged = 801, + VREvent_ChaperoneTempDataHasChanged = 802, + VREvent_ChaperoneSettingsHaveChanged = 803, + VREvent_SeatedZeroPoseReset = 804, + + VREvent_AudioSettingsHaveChanged = 820, + + VREvent_BackgroundSettingHasChanged = 850, + VREvent_CameraSettingsHaveChanged = 851, + VREvent_ReprojectionSettingHasChanged = 852, + VREvent_ModelSkinSettingsHaveChanged = 853, + VREvent_EnvironmentSettingsHaveChanged = 854, + + VREvent_StatusUpdate = 900, + + VREvent_MCImageUpdated = 1000, + + VREvent_FirmwareUpdateStarted = 1100, + VREvent_FirmwareUpdateFinished = 1101, + + VREvent_KeyboardClosed = 1200, + VREvent_KeyboardCharInput = 1201, + VREvent_KeyboardDone = 1202, // Sent when DONE button clicked on keyboard + + VREvent_ApplicationTransitionStarted = 1300, + VREvent_ApplicationTransitionAborted = 1301, + VREvent_ApplicationTransitionNewAppStarted = 1302, + VREvent_ApplicationListUpdated = 1303, + + VREvent_Compositor_MirrorWindowShown = 1400, + VREvent_Compositor_MirrorWindowHidden = 1401, + VREvent_Compositor_ChaperoneBoundsShown = 1410, + VREvent_Compositor_ChaperoneBoundsHidden = 1411, + + VREvent_TrackedCamera_StartVideoStream = 1500, + VREvent_TrackedCamera_StopVideoStream = 1501, + VREvent_TrackedCamera_PauseVideoStream = 1502, + VREvent_TrackedCamera_ResumeVideoStream = 1503, + + VREvent_PerformanceTest_EnableCapture = 1600, + VREvent_PerformanceTest_DisableCapture = 1601, + VREvent_PerformanceTest_FidelityLevel = 1602, + + // Vendors are free to expose private events in this reserved region + VREvent_VendorSpecific_Reserved_Start = 10000, + VREvent_VendorSpecific_Reserved_End = 19999, +}; + + +/** Level of Hmd activity */ +enum EDeviceActivityLevel +{ + k_EDeviceActivityLevel_Unknown = -1, + k_EDeviceActivityLevel_Idle = 0, + k_EDeviceActivityLevel_UserInteraction = 1, + k_EDeviceActivityLevel_UserInteraction_Timeout = 2, + k_EDeviceActivityLevel_Standby = 3, +}; + + +/** VR controller button and axis IDs */ +enum EVRButtonId +{ + k_EButton_System = 0, + k_EButton_ApplicationMenu = 1, + k_EButton_Grip = 2, + k_EButton_DPad_Left = 3, + k_EButton_DPad_Up = 4, + k_EButton_DPad_Right = 5, + k_EButton_DPad_Down = 6, + k_EButton_A = 7, + + k_EButton_Axis0 = 32, + k_EButton_Axis1 = 33, + k_EButton_Axis2 = 34, + k_EButton_Axis3 = 35, + k_EButton_Axis4 = 36, + + // aliases for well known controllers + k_EButton_SteamVR_Touchpad = k_EButton_Axis0, + k_EButton_SteamVR_Trigger = k_EButton_Axis1, + + k_EButton_Dashboard_Back = k_EButton_Grip, + + k_EButton_Max = 64 +}; + +inline uint64_t ButtonMaskFromId( EVRButtonId id ) { return 1ull << id; } + +/** used for controller button events */ +struct VREvent_Controller_t +{ + uint32_t button; // EVRButtonId enum +}; + + +/** used for simulated mouse events in overlay space */ +enum EVRMouseButton +{ + VRMouseButton_Left = 0x0001, + VRMouseButton_Right = 0x0002, + VRMouseButton_Middle = 0x0004, +}; + + +/** used for simulated mouse events in overlay space */ +struct VREvent_Mouse_t +{ + float x, y; // co-ords are in GL space, bottom left of the texture is 0,0 + uint32_t button; // EVRMouseButton enum +}; + +/** used for simulated mouse wheel scroll in overlay space */ +struct VREvent_Scroll_t +{ + float xdelta, ydelta; // movement in fraction of the pad traversed since last delta, 1.0 for a full swipe + uint32_t repeatCount; +}; + +/** when in mouse input mode you can receive data from the touchpad, these events are only sent if the users finger + is on the touchpad (or just released from it) +**/ +struct VREvent_TouchPadMove_t +{ + // true if the users finger is detected on the touch pad + bool bFingerDown; + + // How long the finger has been down in seconds + float flSecondsFingerDown; + + // These values indicate the starting finger position (so you can do some basic swipe stuff) + float fValueXFirst; + float fValueYFirst; + + // This is the raw sampled coordinate without deadzoning + float fValueXRaw; + float fValueYRaw; +}; + +/** notification related events. Details will still change at this point */ +struct VREvent_Notification_t +{ + uint64_t ulUserValue; + uint32_t notificationId; +}; + +/** Used for events about processes */ +struct VREvent_Process_t +{ + uint32_t pid; + uint32_t oldPid; + bool bForced; +}; + + +/** Used for a few events about overlays */ +struct VREvent_Overlay_t +{ + uint64_t overlayHandle; +}; + + +/** Used for a few events about overlays */ +struct VREvent_Status_t +{ + uint32_t statusState; // EVRState enum +}; + +/** Used for keyboard events **/ +struct VREvent_Keyboard_t +{ + char cNewInput[8]; // Up to 11 bytes of new input + uint64_t uUserValue; // Possible flags about the new input +}; + +struct VREvent_Ipd_t +{ + float ipdMeters; +}; + +struct VREvent_Chaperone_t +{ + uint64_t m_nPreviousUniverse; + uint64_t m_nCurrentUniverse; +}; + +/** Not actually used for any events */ +struct VREvent_Reserved_t +{ + uint64_t reserved0; + uint64_t reserved1; +}; + +struct VREvent_PerformanceTest_t +{ + uint32_t m_nFidelityLevel; +}; + +struct VREvent_SeatedZeroPoseReset_t +{ + bool bResetBySystemMenu; +}; + +struct VREvent_Screenshot_t +{ + uint32_t handle; + uint32_t type; +}; + +/** If you change this you must manually update openvr_interop.cs.py */ +typedef union +{ + VREvent_Reserved_t reserved; + VREvent_Controller_t controller; + VREvent_Mouse_t mouse; + VREvent_Scroll_t scroll; + VREvent_Process_t process; + VREvent_Notification_t notification; + VREvent_Overlay_t overlay; + VREvent_Status_t status; + VREvent_Keyboard_t keyboard; + VREvent_Ipd_t ipd; + VREvent_Chaperone_t chaperone; + VREvent_PerformanceTest_t performanceTest; + VREvent_TouchPadMove_t touchPadMove; + VREvent_SeatedZeroPoseReset_t seatedZeroPoseReset; + VREvent_Screenshot_t screenshot; +} VREvent_Data_t; + +/** An event posted by the server to all running applications */ +struct VREvent_t +{ + uint32_t eventType; // EVREventType enum + TrackedDeviceIndex_t trackedDeviceIndex; + float eventAgeSeconds; + // event data must be the end of the struct as its size is variable + VREvent_Data_t data; +}; + + +/** The mesh to draw into the stencil (or depth) buffer to perform +* early stencil (or depth) kills of pixels that will never appear on the HMD. +* This mesh draws on all the pixels that will be hidden after distortion. +* +* If the HMD does not provide a visible area mesh pVertexData will be +* NULL and unTriangleCount will be 0. */ +struct HiddenAreaMesh_t +{ + const HmdVector2_t *pVertexData; + uint32_t unTriangleCount; +}; + + +/** Identifies what kind of axis is on the controller at index n. Read this type +* with pVRSystem->Get( nControllerDeviceIndex, Prop_Axis0Type_Int32 + n ); +*/ +enum EVRControllerAxisType +{ + k_eControllerAxis_None = 0, + k_eControllerAxis_TrackPad = 1, + k_eControllerAxis_Joystick = 2, + k_eControllerAxis_Trigger = 3, // Analog trigger data is in the X axis +}; + + +/** contains information about one axis on the controller */ +struct VRControllerAxis_t +{ + float x; // Ranges from -1.0 to 1.0 for joysticks and track pads. Ranges from 0.0 to 1.0 for triggers were 0 is fully released. + float y; // Ranges from -1.0 to 1.0 for joysticks and track pads. Is always 0.0 for triggers. +}; + + +/** the number of axes in the controller state */ +static const uint32_t k_unControllerStateAxisCount = 5; + + +/** Holds all the state of a controller at one moment in time. */ +struct VRControllerState001_t +{ + // If packet num matches that on your prior call, then the controller state hasn't been changed since + // your last call and there is no need to process it + uint32_t unPacketNum; + + // bit flags for each of the buttons. Use ButtonMaskFromId to turn an ID into a mask + uint64_t ulButtonPressed; + uint64_t ulButtonTouched; + + // Axis data for the controller's analog inputs + VRControllerAxis_t rAxis[ k_unControllerStateAxisCount ]; +}; + + +typedef VRControllerState001_t VRControllerState_t; + + +/** determines how to provide output to the application of various event processing functions. */ +enum EVRControllerEventOutputType +{ + ControllerEventOutput_OSEvents = 0, + ControllerEventOutput_VREvents = 1, +}; + + + +/** Collision Bounds Style */ +enum ECollisionBoundsStyle +{ + COLLISION_BOUNDS_STYLE_BEGINNER = 0, + COLLISION_BOUNDS_STYLE_INTERMEDIATE, + COLLISION_BOUNDS_STYLE_SQUARES, + COLLISION_BOUNDS_STYLE_ADVANCED, + COLLISION_BOUNDS_STYLE_NONE, + + COLLISION_BOUNDS_STYLE_COUNT +}; + +/** Allows the application to customize how the overlay appears in the compositor */ +struct Compositor_OverlaySettings +{ + uint32_t size; // sizeof(Compositor_OverlaySettings) + bool curved, antialias; + float scale, distance, alpha; + float uOffset, vOffset, uScale, vScale; + float gridDivs, gridWidth, gridScale; + HmdMatrix44_t transform; +}; + +/** used to refer to a single VR overlay */ +typedef uint64_t VROverlayHandle_t; + +static const VROverlayHandle_t k_ulOverlayHandleInvalid = 0; + +/** Errors that can occur around VR overlays */ +enum EVROverlayError +{ + VROverlayError_None = 0, + + VROverlayError_UnknownOverlay = 10, + VROverlayError_InvalidHandle = 11, + VROverlayError_PermissionDenied = 12, + VROverlayError_OverlayLimitExceeded = 13, // No more overlays could be created because the maximum number already exist + VROverlayError_WrongVisibilityType = 14, + VROverlayError_KeyTooLong = 15, + VROverlayError_NameTooLong = 16, + VROverlayError_KeyInUse = 17, + VROverlayError_WrongTransformType = 18, + VROverlayError_InvalidTrackedDevice = 19, + VROverlayError_InvalidParameter = 20, + VROverlayError_ThumbnailCantBeDestroyed = 21, + VROverlayError_ArrayTooSmall = 22, + VROverlayError_RequestFailed = 23, + VROverlayError_InvalidTexture = 24, + VROverlayError_UnableToLoadFile = 25, + VROVerlayError_KeyboardAlreadyInUse = 26, + VROverlayError_NoNeighbor = 27, +}; + +/** enum values to pass in to VR_Init to identify whether the application will +* draw a 3D scene. */ +enum EVRApplicationType +{ + VRApplication_Other = 0, // Some other kind of application that isn't covered by the other entries + VRApplication_Scene = 1, // Application will submit 3D frames + VRApplication_Overlay = 2, // Application only interacts with overlays + VRApplication_Background = 3, // Application should not start SteamVR if it's not already running, and should not + // keep it running if everything else quits. + VRApplication_Utility = 4, // Init should not try to load any drivers. The application needs access to utility + // interfaces (like IVRSettings and IVRApplications) but not hardware. + VRApplication_VRMonitor = 5, // Reserved for vrmonitor +}; + + +/** error codes for firmware */ +enum EVRFirmwareError +{ + VRFirmwareError_None = 0, + VRFirmwareError_Success = 1, + VRFirmwareError_Fail = 2, +}; + + +/** error codes for notifications */ +enum EVRNotificationError +{ + VRNotificationError_OK = 0, + VRNotificationError_InvalidNotificationId = 100, + VRNotificationError_NotificationQueueFull = 101, + VRNotificationError_InvalidOverlayHandle = 102, + VRNotificationError_SystemWithUserValueAlreadyExists = 103, +}; + + +/** error codes returned by Vr_Init */ + +// Please add adequate error description to https://developer.valvesoftware.com/w/index.php?title=Category:SteamVRHelp +enum EVRInitError +{ + VRInitError_None = 0, + VRInitError_Unknown = 1, + + VRInitError_Init_InstallationNotFound = 100, + VRInitError_Init_InstallationCorrupt = 101, + VRInitError_Init_VRClientDLLNotFound = 102, + VRInitError_Init_FileNotFound = 103, + VRInitError_Init_FactoryNotFound = 104, + VRInitError_Init_InterfaceNotFound = 105, + VRInitError_Init_InvalidInterface = 106, + VRInitError_Init_UserConfigDirectoryInvalid = 107, + VRInitError_Init_HmdNotFound = 108, + VRInitError_Init_NotInitialized = 109, + VRInitError_Init_PathRegistryNotFound = 110, + VRInitError_Init_NoConfigPath = 111, + VRInitError_Init_NoLogPath = 112, + VRInitError_Init_PathRegistryNotWritable = 113, + VRInitError_Init_AppInfoInitFailed = 114, + VRInitError_Init_Retry = 115, // Used internally to cause retries to vrserver + VRInitError_Init_InitCanceledByUser = 116, // The calling application should silently exit. The user canceled app startup + VRInitError_Init_AnotherAppLaunching = 117, + VRInitError_Init_SettingsInitFailed = 118, + VRInitError_Init_ShuttingDown = 119, + VRInitError_Init_TooManyObjects = 120, + VRInitError_Init_NoServerForBackgroundApp = 121, + VRInitError_Init_NotSupportedWithCompositor = 122, + VRInitError_Init_NotAvailableToUtilityApps = 123, + VRInitError_Init_Internal = 124, + + VRInitError_Driver_Failed = 200, + VRInitError_Driver_Unknown = 201, + VRInitError_Driver_HmdUnknown = 202, + VRInitError_Driver_NotLoaded = 203, + VRInitError_Driver_RuntimeOutOfDate = 204, + VRInitError_Driver_HmdInUse = 205, + VRInitError_Driver_NotCalibrated = 206, + VRInitError_Driver_CalibrationInvalid = 207, + VRInitError_Driver_HmdDisplayNotFound = 208, + + VRInitError_IPC_ServerInitFailed = 300, + VRInitError_IPC_ConnectFailed = 301, + VRInitError_IPC_SharedStateInitFailed = 302, + VRInitError_IPC_CompositorInitFailed = 303, + VRInitError_IPC_MutexInitFailed = 304, + VRInitError_IPC_Failed = 305, + + VRInitError_Compositor_Failed = 400, + VRInitError_Compositor_D3D11HardwareRequired = 401, + VRInitError_Compositor_FirmwareRequiresUpdate = 402, + VRInitError_Compositor_OverlayInitFailed = 403, + VRInitError_Compositor_ScreenshotsInitFailed = 404, + + VRInitError_VendorSpecific_UnableToConnectToOculusRuntime = 1000, + + VRInitError_VendorSpecific_HmdFound_CantOpenDevice = 1101, + VRInitError_VendorSpecific_HmdFound_UnableToRequestConfigStart = 1102, + VRInitError_VendorSpecific_HmdFound_NoStoredConfig = 1103, + VRInitError_VendorSpecific_HmdFound_ConfigTooBig = 1104, + VRInitError_VendorSpecific_HmdFound_ConfigTooSmall = 1105, + VRInitError_VendorSpecific_HmdFound_UnableToInitZLib = 1106, + VRInitError_VendorSpecific_HmdFound_CantReadFirmwareVersion = 1107, + VRInitError_VendorSpecific_HmdFound_UnableToSendUserDataStart = 1108, + VRInitError_VendorSpecific_HmdFound_UnableToGetUserDataStart = 1109, + VRInitError_VendorSpecific_HmdFound_UnableToGetUserDataNext = 1110, + VRInitError_VendorSpecific_HmdFound_UserDataAddressRange = 1111, + VRInitError_VendorSpecific_HmdFound_UserDataError = 1112, + VRInitError_VendorSpecific_HmdFound_ConfigFailedSanityCheck = 1113, + + VRInitError_Steam_SteamInstallationNotFound = 2000, +}; + +enum EVRScreenshotType +{ + VRScreenshotType_None = 0, + VRScreenshotType_Mono = 1, // left eye only + VRScreenshotType_Stereo = 2, + VRScreenshotType_Cubemap = 3, + VRScreenshotType_MonoPanorama = 4, + VRScreenshotType_StereoPanorama = 5 +}; + +enum EVRScreenshotPropertyFilenames +{ + VRScreenshotPropertyFilenames_Preview = 0, + VRScreenshotPropertyFilenames_VR = 1, +}; + +enum EVRTrackedCameraError +{ + VRTrackedCameraError_None = 0, + VRTrackedCameraError_OperationFailed = 100, + VRTrackedCameraError_InvalidHandle = 101, + VRTrackedCameraError_InvalidFrameHeaderVersion = 102, + VRTrackedCameraError_OutOfHandles = 103, + VRTrackedCameraError_IPCFailure = 104, + VRTrackedCameraError_NotSupportedForThisDevice = 105, + VRTrackedCameraError_SharedMemoryFailure = 106, + VRTrackedCameraError_FrameBufferingFailure = 107, + VRTrackedCameraError_StreamSetupFailure = 108, + VRTrackedCameraError_InvalidGLTextureId = 109, + VRTrackedCameraError_InvalidSharedTextureHandle = 110, + VRTrackedCameraError_FailedToGetGLTextureId = 111, + VRTrackedCameraError_SharedTextureFailure = 112, + VRTrackedCameraError_NoFrameAvailable = 113, + VRTrackedCameraError_InvalidArgument = 114, + VRTrackedCameraError_InvalidFrameBufferSize = 115, +}; + +enum EVRTrackedCameraFrameType +{ + VRTrackedCameraFrameType_Distorted = 0, // This is the camera video frame size in pixels, still distorted. + VRTrackedCameraFrameType_Undistorted, // In pixels, an undistorted inscribed rectangle region without invalid regions. This size is subject to changes shortly. + VRTrackedCameraFrameType_MaximumUndistorted, // In pixels, maximum undistorted with invalid regions. Non zero alpha component identifies valid regions. + MAX_CAMERA_FRAME_TYPES +}; + +typedef uint64_t TrackedCameraHandle_t; +#define INVALID_TRACKED_CAMERA_HANDLE ((vr::TrackedCameraHandle_t)0) + +struct CameraVideoStreamFrameHeader_t +{ + EVRTrackedCameraFrameType eFrameType; + + uint32_t nWidth; + uint32_t nHeight; + uint32_t nBytesPerPixel; + + uint32_t nFrameSequence; + + TrackedDevicePose_t standingTrackedDevicePose; +}; + +// Screenshot types +typedef uint32_t ScreenshotHandle_t; + +static const uint32_t k_unScreenshotHandleInvalid = 0; + +#pragma pack( pop ) + +// figure out how to import from the VR API dll +#if defined(_WIN32) + +#ifdef VR_API_EXPORT +#define VR_INTERFACE extern "C" __declspec( dllexport ) +#else +#define VR_INTERFACE extern "C" __declspec( dllimport ) +#endif + +#elif defined(GNUC) || defined(COMPILER_GCC) || defined(__APPLE__) + +#ifdef VR_API_EXPORT +#define VR_INTERFACE extern "C" __attribute__((visibility("default"))) +#else +#define VR_INTERFACE extern "C" +#endif + +#else +#error "Unsupported Platform." +#endif + + +#if defined( _WIN32 ) +#define VR_CALLTYPE __cdecl +#else +#define VR_CALLTYPE +#endif + +} // namespace vr + +#endif // _INCLUDE_VRTYPES_H + + +// vrannotation.h +#ifdef API_GEN +# define VR_CLANG_ATTR(ATTR) __attribute__((annotate( ATTR ))) +#else +# define VR_CLANG_ATTR(ATTR) +#endif + +#define VR_METHOD_DESC(DESC) VR_CLANG_ATTR( "desc:" #DESC ";" ) +#define VR_IGNOREATTR() VR_CLANG_ATTR( "ignore" ) +#define VR_OUT_STRUCT() VR_CLANG_ATTR( "out_struct: ;" ) +#define VR_OUT_STRING() VR_CLANG_ATTR( "out_string: ;" ) +#define VR_OUT_ARRAY_CALL(COUNTER,FUNCTION,PARAMS) VR_CLANG_ATTR( "out_array_call:" #COUNTER "," #FUNCTION "," #PARAMS ";" ) +#define VR_OUT_ARRAY_COUNT(COUNTER) VR_CLANG_ATTR( "out_array_count:" #COUNTER ";" ) +#define VR_ARRAY_COUNT(COUNTER) VR_CLANG_ATTR( "array_count:" #COUNTER ";" ) +#define VR_ARRAY_COUNT_D(COUNTER, DESC) VR_CLANG_ATTR( "array_count:" #COUNTER ";desc:" #DESC ) +#define VR_BUFFER_COUNT(COUNTER) VR_CLANG_ATTR( "buffer_count:" #COUNTER ";" ) +#define VR_OUT_BUFFER_COUNT(COUNTER) VR_CLANG_ATTR( "out_buffer_count:" #COUNTER ";" ) +#define VR_OUT_STRING_COUNT(COUNTER) VR_CLANG_ATTR( "out_string_count:" #COUNTER ";" ) + +// ivrsystem.h +namespace vr +{ + +class IVRSystem +{ +public: + + + // ------------------------------------ + // Display Methods + // ------------------------------------ + + /** Suggested size for the intermediate render target that the distortion pulls from. */ + virtual void GetRecommendedRenderTargetSize( uint32_t *pnWidth, uint32_t *pnHeight ) = 0; + + /** The projection matrix for the specified eye */ + virtual HmdMatrix44_t GetProjectionMatrix( EVREye eEye, float fNearZ, float fFarZ, EGraphicsAPIConvention eProjType ) = 0; + + /** The components necessary to build your own projection matrix in case your + * application is doing something fancy like infinite Z */ + virtual void GetProjectionRaw( EVREye eEye, float *pfLeft, float *pfRight, float *pfTop, float *pfBottom ) = 0; + + /** Returns the result of the distortion function for the specified eye and input UVs. UVs go from 0,0 in + * the upper left of that eye's viewport and 1,1 in the lower right of that eye's viewport. */ + virtual DistortionCoordinates_t ComputeDistortion( EVREye eEye, float fU, float fV ) = 0; + + /** Returns the transform from eye space to the head space. Eye space is the per-eye flavor of head + * space that provides stereo disparity. Instead of Model * View * Projection the sequence is Model * View * Eye^-1 * Projection. + * Normally View and Eye^-1 will be multiplied together and treated as View in your application. + */ + virtual HmdMatrix34_t GetEyeToHeadTransform( EVREye eEye ) = 0; + + /** Returns the number of elapsed seconds since the last recorded vsync event. This + * will come from a vsync timer event in the timer if possible or from the application-reported + * time if that is not available. If no vsync times are available the function will + * return zero for vsync time and frame counter and return false from the method. */ + virtual bool GetTimeSinceLastVsync( float *pfSecondsSinceLastVsync, uint64_t *pulFrameCounter ) = 0; + + /** [D3D9 Only] + * Returns the adapter index that the user should pass into CreateDevice to set up D3D9 in such + * a way that it can go full screen exclusive on the HMD. Returns -1 if there was an error. + */ + virtual int32_t GetD3D9AdapterIndex() = 0; + + /** [D3D10/11 Only] + * Returns the adapter index and output index that the user should pass into EnumAdapters and EnumOutputs + * to create the device and swap chain in DX10 and DX11. If an error occurs both indices will be set to -1. + */ + virtual void GetDXGIOutputInfo( int32_t *pnAdapterIndex ) = 0; + + // ------------------------------------ + // Display Mode methods + // ------------------------------------ + + /** Use to determine if the headset display is part of the desktop (i.e. extended) or hidden (i.e. direct mode). */ + virtual bool IsDisplayOnDesktop() = 0; + + /** Set the display visibility (true = extended, false = direct mode). Return value of true indicates that the change was successful. */ + virtual bool SetDisplayVisibility( bool bIsVisibleOnDesktop ) = 0; + + // ------------------------------------ + // Tracking Methods + // ------------------------------------ + + /** The pose that the tracker thinks that the HMD will be in at the specified number of seconds into the + * future. Pass 0 to get the state at the instant the method is called. Most of the time the application should + * calculate the time until the photons will be emitted from the display and pass that time into the method. + * + * This is roughly analogous to the inverse of the view matrix in most applications, though + * many games will need to do some additional rotation or translation on top of the rotation + * and translation provided by the head pose. + * + * For devices where bPoseIsValid is true the application can use the pose to position the device + * in question. The provided array can be any size up to k_unMaxTrackedDeviceCount. + * + * Seated experiences should call this method with TrackingUniverseSeated and receive poses relative + * to the seated zero pose. Standing experiences should call this method with TrackingUniverseStanding + * and receive poses relative to the Chaperone Play Area. TrackingUniverseRawAndUncalibrated should + * probably not be used unless the application is the Chaperone calibration tool itself, but will provide + * poses relative to the hardware-specific coordinate system in the driver. + */ + virtual void GetDeviceToAbsoluteTrackingPose( ETrackingUniverseOrigin eOrigin, float fPredictedSecondsToPhotonsFromNow, VR_ARRAY_COUNT(unTrackedDevicePoseArrayCount) TrackedDevicePose_t *pTrackedDevicePoseArray, uint32_t unTrackedDevicePoseArrayCount ) = 0; + + /** Sets the zero pose for the seated tracker coordinate system to the current position and yaw of the HMD. After + * ResetSeatedZeroPose all GetDeviceToAbsoluteTrackingPose calls that pass TrackingUniverseSeated as the origin + * will be relative to this new zero pose. The new zero coordinate system will not change the fact that the Y axis + * is up in the real world, so the next pose returned from GetDeviceToAbsoluteTrackingPose after a call to + * ResetSeatedZeroPose may not be exactly an identity matrix. + * + * NOTE: This function overrides the user's previously saved seated zero pose and should only be called as the result of a user action. + * Users are also able to set their seated zero pose via the OpenVR Dashboard. + **/ + virtual void ResetSeatedZeroPose() = 0; + + /** Returns the transform from the seated zero pose to the standing absolute tracking system. This allows + * applications to represent the seated origin to used or transform object positions from one coordinate + * system to the other. + * + * The seated origin may or may not be inside the Play Area or Collision Bounds returned by IVRChaperone. Its position + * depends on what the user has set from the Dashboard settings and previous calls to ResetSeatedZeroPose. */ + virtual HmdMatrix34_t GetSeatedZeroPoseToStandingAbsoluteTrackingPose() = 0; + + /** Returns the transform from the tracking origin to the standing absolute tracking system. This allows + * applications to convert from raw tracking space to the calibrated standing coordinate system. */ + virtual HmdMatrix34_t GetRawZeroPoseToStandingAbsoluteTrackingPose() = 0; + + /** Get a sorted array of device indices of a given class of tracked devices (e.g. controllers). Devices are sorted right to left + * relative to the specified tracked device (default: hmd -- pass in -1 for absolute tracking space). Returns the number of devices + * in the list, or the size of the array needed if not large enough. */ + virtual uint32_t GetSortedTrackedDeviceIndicesOfClass( ETrackedDeviceClass eTrackedDeviceClass, VR_ARRAY_COUNT(unTrackedDeviceIndexArrayCount) vr::TrackedDeviceIndex_t *punTrackedDeviceIndexArray, uint32_t unTrackedDeviceIndexArrayCount, vr::TrackedDeviceIndex_t unRelativeToTrackedDeviceIndex = k_unTrackedDeviceIndex_Hmd ) = 0; + + /** Returns the level of activity on the device. */ + virtual EDeviceActivityLevel GetTrackedDeviceActivityLevel( vr::TrackedDeviceIndex_t unDeviceId ) = 0; + + /** Convenience utility to apply the specified transform to the specified pose. + * This properly transforms all pose components, including velocity and angular velocity + */ + virtual void ApplyTransform( TrackedDevicePose_t *pOutputPose, const TrackedDevicePose_t *pTrackedDevicePose, const HmdMatrix34_t *pTransform ) = 0; + + /** Returns the device index associated with a specific role, for example the left hand or the right hand. */ + virtual vr::TrackedDeviceIndex_t GetTrackedDeviceIndexForControllerRole( vr::ETrackedControllerRole unDeviceType ) = 0; + + /** Returns the controller type associated with a device index. */ + virtual vr::ETrackedControllerRole GetControllerRoleForTrackedDeviceIndex( vr::TrackedDeviceIndex_t unDeviceIndex ) = 0; + + // ------------------------------------ + // Property methods + // ------------------------------------ + + /** Returns the device class of a tracked device. If there has not been a device connected in this slot + * since the application started this function will return TrackedDevice_Invalid. For previous detected + * devices the function will return the previously observed device class. + * + * To determine which devices exist on the system, just loop from 0 to k_unMaxTrackedDeviceCount and check + * the device class. Every device with something other than TrackedDevice_Invalid is associated with an + * actual tracked device. */ + virtual ETrackedDeviceClass GetTrackedDeviceClass( vr::TrackedDeviceIndex_t unDeviceIndex ) = 0; + + /** Returns true if there is a device connected in this slot. */ + virtual bool IsTrackedDeviceConnected( vr::TrackedDeviceIndex_t unDeviceIndex ) = 0; + + /** Returns a bool property. If the device index is not valid or the property is not a bool type this function will return false. */ + virtual bool GetBoolTrackedDeviceProperty( vr::TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError *pError = 0L ) = 0; + + /** Returns a float property. If the device index is not valid or the property is not a float type this function will return 0. */ + virtual float GetFloatTrackedDeviceProperty( vr::TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError *pError = 0L ) = 0; + + /** Returns an int property. If the device index is not valid or the property is not a int type this function will return 0. */ + virtual int32_t GetInt32TrackedDeviceProperty( vr::TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError *pError = 0L ) = 0; + + /** Returns a uint64 property. If the device index is not valid or the property is not a uint64 type this function will return 0. */ + virtual uint64_t GetUint64TrackedDeviceProperty( vr::TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError *pError = 0L ) = 0; + + /** Returns a matrix property. If the device index is not valid or the property is not a matrix type, this function will return identity. */ + virtual HmdMatrix34_t GetMatrix34TrackedDeviceProperty( vr::TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError *pError = 0L ) = 0; + + /** Returns a string property. If the device index is not valid or the property is not a string type this function will + * return 0. Otherwise it returns the length of the number of bytes necessary to hold this string including the trailing + * null. Strings will generally fit in buffers of k_unTrackingStringSize characters. */ + virtual uint32_t GetStringTrackedDeviceProperty( vr::TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, VR_OUT_STRING() char *pchValue, uint32_t unBufferSize, ETrackedPropertyError *pError = 0L ) = 0; + + /** returns a string that corresponds with the specified property error. The string will be the name + * of the error enum value for all valid error codes */ + virtual const char *GetPropErrorNameFromEnum( ETrackedPropertyError error ) = 0; + + // ------------------------------------ + // Event methods + // ------------------------------------ + + /** Returns true and fills the event with the next event on the queue if there is one. If there are no events + * this method returns false. uncbVREvent should be the size in bytes of the VREvent_t struct */ + virtual bool PollNextEvent( VREvent_t *pEvent, uint32_t uncbVREvent ) = 0; + + /** Returns true and fills the event with the next event on the queue if there is one. If there are no events + * this method returns false. Fills in the pose of the associated tracked device in the provided pose struct. + * This pose will always be older than the call to this function and should not be used to render the device. + uncbVREvent should be the size in bytes of the VREvent_t struct */ + virtual bool PollNextEventWithPose( ETrackingUniverseOrigin eOrigin, VREvent_t *pEvent, uint32_t uncbVREvent, vr::TrackedDevicePose_t *pTrackedDevicePose ) = 0; + + /** returns the name of an EVREvent enum value */ + virtual const char *GetEventTypeNameFromEnum( EVREventType eType ) = 0; + + // ------------------------------------ + // Rendering helper methods + // ------------------------------------ + + /** Returns the stencil mesh information for the current HMD. If this HMD does not have a stencil mesh the vertex data and count will be + * NULL and 0 respectively. This mesh is meant to be rendered into the stencil buffer (or into the depth buffer setting nearz) before rendering + * each eye's view. The pixels covered by this mesh will never be seen by the user after the lens distortion is applied and based on visibility to the panels. + * This will improve perf by letting the GPU early-reject pixels the user will never see before running the pixel shader. + * NOTE: Render this mesh with backface culling disabled since the winding order of the vertices can be different per-HMD or per-eye. + */ + virtual HiddenAreaMesh_t GetHiddenAreaMesh( EVREye eEye ) = 0; + + + // ------------------------------------ + // Controller methods + // ------------------------------------ + + /** Fills the supplied struct with the current state of the controller. Returns false if the controller index + * is invalid. */ + virtual bool GetControllerState( vr::TrackedDeviceIndex_t unControllerDeviceIndex, vr::VRControllerState_t *pControllerState ) = 0; + + /** fills the supplied struct with the current state of the controller and the provided pose with the pose of + * the controller when the controller state was updated most recently. Use this form if you need a precise controller + * pose as input to your application when the user presses or releases a button. */ + virtual bool GetControllerStateWithPose( ETrackingUniverseOrigin eOrigin, vr::TrackedDeviceIndex_t unControllerDeviceIndex, vr::VRControllerState_t *pControllerState, TrackedDevicePose_t *pTrackedDevicePose ) = 0; + + /** Trigger a single haptic pulse on a controller. After this call the application may not trigger another haptic pulse on this controller + * and axis combination for 5ms. */ + virtual void TriggerHapticPulse( vr::TrackedDeviceIndex_t unControllerDeviceIndex, uint32_t unAxisId, unsigned short usDurationMicroSec ) = 0; + + /** returns the name of an EVRButtonId enum value */ + virtual const char *GetButtonIdNameFromEnum( EVRButtonId eButtonId ) = 0; + + /** returns the name of an EVRControllerAxisType enum value */ + virtual const char *GetControllerAxisTypeNameFromEnum( EVRControllerAxisType eAxisType ) = 0; + + /** Tells OpenVR that this process wants exclusive access to controller button states and button events. Other apps will be notified that + * they have lost input focus with a VREvent_InputFocusCaptured event. Returns false if input focus could not be captured for + * some reason. */ + virtual bool CaptureInputFocus() = 0; + + /** Tells OpenVR that this process no longer wants exclusive access to button states and button events. Other apps will be notified + * that input focus has been released with a VREvent_InputFocusReleased event. */ + virtual void ReleaseInputFocus() = 0; + + /** Returns true if input focus is captured by another process. */ + virtual bool IsInputFocusCapturedByAnotherProcess() = 0; + + // ------------------------------------ + // Debug Methods + // ------------------------------------ + + /** Sends a request to the driver for the specified device and returns the response. The maximum response size is 32k, + * but this method can be called with a smaller buffer. If the response exceeds the size of the buffer, it is truncated. + * The size of the response including its terminating null is returned. */ + virtual uint32_t DriverDebugRequest( vr::TrackedDeviceIndex_t unDeviceIndex, const char *pchRequest, char *pchResponseBuffer, uint32_t unResponseBufferSize ) = 0; + + + // ------------------------------------ + // Firmware methods + // ------------------------------------ + + /** Performs the actual firmware update if applicable. + * The following events will be sent, if VRFirmwareError_None was returned: VREvent_FirmwareUpdateStarted, VREvent_FirmwareUpdateFinished + * Use the properties Prop_Firmware_UpdateAvailable_Bool, Prop_Firmware_ManualUpdate_Bool, and Prop_Firmware_ManualUpdateURL_String + * to figure our whether a firmware update is available, and to figure out whether its a manual update + * Prop_Firmware_ManualUpdateURL_String should point to an URL describing the manual update process */ + virtual vr::EVRFirmwareError PerformFirmwareUpdate( vr::TrackedDeviceIndex_t unDeviceIndex ) = 0; + + + // ------------------------------------ + // Application life cycle methods + // ------------------------------------ + + /** Call this to acknowledge to the system that VREvent_Quit has been received and that the process is exiting. + * This extends the timeout until the process is killed. */ + virtual void AcknowledgeQuit_Exiting() = 0; + + /** Call this to tell the system that the user is being prompted to save data. This + * halts the timeout and dismisses the dashboard (if it was up). Applications should be sure to actually + * prompt the user to save and then exit afterward, otherwise the user will be left in a confusing state. */ + virtual void AcknowledgeQuit_UserPrompt() = 0; + +}; + +static const char * const IVRSystem_Version = "IVRSystem_012"; + +} + + +// ivrapplications.h +namespace vr +{ + + /** Used for all errors reported by the IVRApplications interface */ + enum EVRApplicationError + { + VRApplicationError_None = 0, + + VRApplicationError_AppKeyAlreadyExists = 100, // Only one application can use any given key + VRApplicationError_NoManifest = 101, // the running application does not have a manifest + VRApplicationError_NoApplication = 102, // No application is running + VRApplicationError_InvalidIndex = 103, + VRApplicationError_UnknownApplication = 104, // the application could not be found + VRApplicationError_IPCFailed = 105, // An IPC failure caused the request to fail + VRApplicationError_ApplicationAlreadyRunning = 106, + VRApplicationError_InvalidManifest = 107, + VRApplicationError_InvalidApplication = 108, + VRApplicationError_LaunchFailed = 109, // the process didn't start + VRApplicationError_ApplicationAlreadyStarting = 110, // the system was already starting the same application + VRApplicationError_LaunchInProgress = 111, // The system was already starting a different application + VRApplicationError_OldApplicationQuitting = 112, + VRApplicationError_TransitionAborted = 113, + VRApplicationError_IsTemplate = 114, // error when you try to call LaunchApplication() on a template type app (use LaunchTemplateApplication) + + VRApplicationError_BufferTooSmall = 200, // The provided buffer was too small to fit the requested data + VRApplicationError_PropertyNotSet = 201, // The requested property was not set + VRApplicationError_UnknownProperty = 202, + VRApplicationError_InvalidParameter = 203, + }; + + /** The maximum length of an application key */ + static const uint32_t k_unMaxApplicationKeyLength = 128; + + /** these are the properties available on applications. */ + enum EVRApplicationProperty + { + VRApplicationProperty_Name_String = 0, + + VRApplicationProperty_LaunchType_String = 11, + VRApplicationProperty_WorkingDirectory_String = 12, + VRApplicationProperty_BinaryPath_String = 13, + VRApplicationProperty_Arguments_String = 14, + VRApplicationProperty_URL_String = 15, + + VRApplicationProperty_Description_String = 50, + VRApplicationProperty_NewsURL_String = 51, + VRApplicationProperty_ImagePath_String = 52, + VRApplicationProperty_Source_String = 53, + + VRApplicationProperty_IsDashboardOverlay_Bool = 60, + VRApplicationProperty_IsTemplate_Bool = 61, + VRApplicationProperty_IsInstanced_Bool = 62, + + VRApplicationProperty_LastLaunchTime_Uint64 = 70, + }; + + /** These are states the scene application startup process will go through. */ + enum EVRApplicationTransitionState + { + VRApplicationTransition_None = 0, + + VRApplicationTransition_OldAppQuitSent = 10, + VRApplicationTransition_WaitingForExternalLaunch = 11, + + VRApplicationTransition_NewAppLaunched = 20, + }; + + struct AppOverrideKeys_t + { + const char *pchKey; + const char *pchValue; + }; + + class IVRApplications + { + public: + + // --------------- Application management --------------- // + + /** Adds an application manifest to the list to load when building the list of installed applications. + * Temporary manifests are not automatically loaded */ + virtual EVRApplicationError AddApplicationManifest( const char *pchApplicationManifestFullPath, bool bTemporary = false ) = 0; + + /** Removes an application manifest from the list to load when building the list of installed applications. */ + virtual EVRApplicationError RemoveApplicationManifest( const char *pchApplicationManifestFullPath ) = 0; + + /** Returns true if an application is installed */ + virtual bool IsApplicationInstalled( const char *pchAppKey ) = 0; + + /** Returns the number of applications available in the list */ + virtual uint32_t GetApplicationCount() = 0; + + /** Returns the key of the specified application. The index is at least 0 and is less than the return + * value of GetApplicationCount(). The buffer should be at least k_unMaxApplicationKeyLength in order to + * fit the key. */ + virtual EVRApplicationError GetApplicationKeyByIndex( uint32_t unApplicationIndex, char *pchAppKeyBuffer, uint32_t unAppKeyBufferLen ) = 0; + + /** Returns the key of the application for the specified Process Id. The buffer should be at least + * k_unMaxApplicationKeyLength in order to fit the key. */ + virtual EVRApplicationError GetApplicationKeyByProcessId( uint32_t unProcessId, char *pchAppKeyBuffer, uint32_t unAppKeyBufferLen ) = 0; + + /** Launches the application. The existing scene application will exit and then the new application will start. + * This call is not valid for dashboard overlay applications. */ + virtual EVRApplicationError LaunchApplication( const char *pchAppKey ) = 0; + + /** Launches an instance of an application of type template, with its app key being pchNewAppKey (which must be unique) and optionally override sections + * from the manifest file via AppOverrideKeys_t + */ + virtual EVRApplicationError LaunchTemplateApplication( const char *pchTemplateAppKey, const char *pchNewAppKey, VR_ARRAY_COUNT( unKeys ) const AppOverrideKeys_t *pKeys, uint32_t unKeys ) = 0; + + /** Launches the dashboard overlay application if it is not already running. This call is only valid for + * dashboard overlay applications. */ + virtual EVRApplicationError LaunchDashboardOverlay( const char *pchAppKey ) = 0; + + /** Cancel a pending launch for an application */ + virtual bool CancelApplicationLaunch( const char *pchAppKey ) = 0; + + /** Identifies a running application. OpenVR can't always tell which process started in response + * to a URL. This function allows a URL handler (or the process itself) to identify the app key + * for the now running application. Passing a process ID of 0 identifies the calling process. + * The application must be one that's known to the system via a call to AddApplicationManifest. */ + virtual EVRApplicationError IdentifyApplication( uint32_t unProcessId, const char *pchAppKey ) = 0; + + /** Returns the process ID for an application. Return 0 if the application was not found or is not running. */ + virtual uint32_t GetApplicationProcessId( const char *pchAppKey ) = 0; + + /** Returns a string for an applications error */ + virtual const char *GetApplicationsErrorNameFromEnum( EVRApplicationError error ) = 0; + + // --------------- Application properties --------------- // + + /** Returns a value for an application property. The required buffer size to fit this value will be returned. */ + virtual uint32_t GetApplicationPropertyString( const char *pchAppKey, EVRApplicationProperty eProperty, char *pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError *peError = nullptr ) = 0; + + /** Returns a bool value for an application property. Returns false in all error cases. */ + virtual bool GetApplicationPropertyBool( const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = nullptr ) = 0; + + /** Returns a uint64 value for an application property. Returns 0 in all error cases. */ + virtual uint64_t GetApplicationPropertyUint64( const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = nullptr ) = 0; + + /** Sets the application auto-launch flag. This is only valid for applications which return true for VRApplicationProperty_IsDashboardOverlay_Bool. */ + virtual EVRApplicationError SetApplicationAutoLaunch( const char *pchAppKey, bool bAutoLaunch ) = 0; + + /** Gets the application auto-launch flag. This is only valid for applications which return true for VRApplicationProperty_IsDashboardOverlay_Bool. */ + virtual bool GetApplicationAutoLaunch( const char *pchAppKey ) = 0; + + // --------------- Transition methods --------------- // + + /** Returns the app key for the application that is starting up */ + virtual EVRApplicationError GetStartingApplication( char *pchAppKeyBuffer, uint32_t unAppKeyBufferLen ) = 0; + + /** Returns the application transition state */ + virtual EVRApplicationTransitionState GetTransitionState() = 0; + + /** Returns errors that would prevent the specified application from launching immediately. Calling this function will + * cause the current scene application to quit, so only call it when you are actually about to launch something else. + * What the caller should do about these failures depends on the failure: + * VRApplicationError_OldApplicationQuitting - An existing application has been told to quit. Wait for a VREvent_ProcessQuit + * and try again. + * VRApplicationError_ApplicationAlreadyStarting - This application is already starting. This is a permanent failure. + * VRApplicationError_LaunchInProgress - A different application is already starting. This is a permanent failure. + * VRApplicationError_None - Go ahead and launch. Everything is clear. + */ + virtual EVRApplicationError PerformApplicationPrelaunchCheck( const char *pchAppKey ) = 0; + + /** Returns a string for an application transition state */ + virtual const char *GetApplicationsTransitionStateNameFromEnum( EVRApplicationTransitionState state ) = 0; + + /** Returns true if the outgoing scene app has requested a save prompt before exiting */ + virtual bool IsQuitUserPromptRequested() = 0; + + /** Starts a subprocess within the calling application. This + * suppresses all application transition UI and automatically identifies the new executable + * as part of the same application. On success the calling process should exit immediately. + * If working directory is NULL or "" the directory portion of the binary path will be + * the working directory. */ + virtual EVRApplicationError LaunchInternalProcess( const char *pchBinaryPath, const char *pchArguments, const char *pchWorkingDirectory ) = 0; + }; + + static const char * const IVRApplications_Version = "IVRApplications_005"; + +} // namespace vr + +// ivrsettings.h +namespace vr +{ + enum EVRSettingsError + { + VRSettingsError_None = 0, + VRSettingsError_IPCFailed = 1, + VRSettingsError_WriteFailed = 2, + VRSettingsError_ReadFailed = 3, + }; + + // The maximum length of a settings key + static const uint32_t k_unMaxSettingsKeyLength = 128; + + class IVRSettings + { + public: + virtual const char *GetSettingsErrorNameFromEnum( EVRSettingsError eError ) = 0; + + // Returns true if file sync occurred (force or settings dirty) + virtual bool Sync( bool bForce = false, EVRSettingsError *peError = nullptr ) = 0; + + virtual bool GetBool( const char *pchSection, const char *pchSettingsKey, bool bDefaultValue, EVRSettingsError *peError = nullptr ) = 0; + virtual void SetBool( const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr ) = 0; + virtual int32_t GetInt32( const char *pchSection, const char *pchSettingsKey, int32_t nDefaultValue, EVRSettingsError *peError = nullptr ) = 0; + virtual void SetInt32( const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr ) = 0; + virtual float GetFloat( const char *pchSection, const char *pchSettingsKey, float flDefaultValue, EVRSettingsError *peError = nullptr ) = 0; + virtual void SetFloat( const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr ) = 0; + virtual void GetString( const char *pchSection, const char *pchSettingsKey, char *pchValue, uint32_t unValueLen, const char *pchDefaultValue, EVRSettingsError *peError = nullptr ) = 0; + virtual void SetString( const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr ) = 0; + + virtual void RemoveSection( const char *pchSection, EVRSettingsError *peError = nullptr ) = 0; + virtual void RemoveKeyInSection( const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr ) = 0; + }; + + //----------------------------------------------------------------------------- + static const char * const IVRSettings_Version = "IVRSettings_001"; + + //----------------------------------------------------------------------------- + // steamvr keys + + static const char * const k_pch_SteamVR_Section = "steamvr"; + static const char * const k_pch_SteamVR_RequireHmd_String = "requireHmd"; + static const char * const k_pch_SteamVR_ForcedDriverKey_String = "forcedDriver"; + static const char * const k_pch_SteamVR_ForcedHmdKey_String = "forcedHmd"; + static const char * const k_pch_SteamVR_DisplayDebug_Bool = "displayDebug"; + static const char * const k_pch_SteamVR_DebugProcessPipe_String = "debugProcessPipe"; + static const char * const k_pch_SteamVR_EnableDistortion_Bool = "enableDistortion"; + static const char * const k_pch_SteamVR_DisplayDebugX_Int32 = "displayDebugX"; + static const char * const k_pch_SteamVR_DisplayDebugY_Int32 = "displayDebugY"; + static const char * const k_pch_SteamVR_SendSystemButtonToAllApps_Bool= "sendSystemButtonToAllApps"; + static const char * const k_pch_SteamVR_LogLevel_Int32 = "loglevel"; + static const char * const k_pch_SteamVR_IPD_Float = "ipd"; + static const char * const k_pch_SteamVR_Background_String = "background"; + static const char * const k_pch_SteamVR_BackgroundCameraHeight_Float = "backgroundCameraHeight"; + static const char * const k_pch_SteamVR_BackgroundDomeRadius_Float = "backgroundDomeRadius"; + static const char * const k_pch_SteamVR_Environment_String = "environment"; + static const char * const k_pch_SteamVR_GridColor_String = "gridColor"; + static const char * const k_pch_SteamVR_PlayAreaColor_String = "playAreaColor"; + static const char * const k_pch_SteamVR_ShowStage_Bool = "showStage"; + static const char * const k_pch_SteamVR_ActivateMultipleDrivers_Bool = "activateMultipleDrivers"; + static const char * const k_pch_SteamVR_PowerOffOnExit_Bool = "powerOffOnExit"; + static const char * const k_pch_SteamVR_StandbyAppRunningTimeout_Float = "standbyAppRunningTimeout"; + static const char * const k_pch_SteamVR_StandbyNoAppTimeout_Float = "standbyNoAppTimeout"; + static const char * const k_pch_SteamVR_DirectMode_Bool = "directMode"; + static const char * const k_pch_SteamVR_DirectModeEdidVid_Int32 = "directModeEdidVid"; + static const char * const k_pch_SteamVR_DirectModeEdidPid_Int32 = "directModeEdidPid"; + static const char * const k_pch_SteamVR_UsingSpeakers_Bool = "usingSpeakers"; + static const char * const k_pch_SteamVR_SpeakersForwardYawOffsetDegrees_Float = "speakersForwardYawOffsetDegrees"; + static const char * const k_pch_SteamVR_BaseStationPowerManagement_Bool = "basestationPowerManagement"; + static const char * const k_pch_SteamVR_NeverKillProcesses_Bool = "neverKillProcesses"; + static const char * const k_pch_SteamVR_RenderTargetMultiplier_Float = "renderTargetMultiplier"; + static const char * const k_pch_SteamVR_AllowReprojection_Bool = "allowReprojection"; + static const char * const k_pch_SteamVR_ForceReprojection_Bool = "forceReprojection"; + static const char * const k_pch_SteamVR_ForceFadeOnBadTracking_Bool = "forceFadeOnBadTracking"; + static const char * const k_pch_SteamVR_DefaultMirrorView_Int32 = "defaultMirrorView"; + static const char * const k_pch_SteamVR_ShowMirrorView_Bool = "showMirrorView"; + + //----------------------------------------------------------------------------- + // lighthouse keys + + static const char * const k_pch_Lighthouse_Section = "driver_lighthouse"; + static const char * const k_pch_Lighthouse_DisableIMU_Bool = "disableimu"; + static const char * const k_pch_Lighthouse_UseDisambiguation_String = "usedisambiguation"; + static const char * const k_pch_Lighthouse_DisambiguationDebug_Int32 = "disambiguationdebug"; + + static const char * const k_pch_Lighthouse_PrimaryBasestation_Int32 = "primarybasestation"; + static const char * const k_pch_Lighthouse_LighthouseName_String = "lighthousename"; + static const char * const k_pch_Lighthouse_MaxIncidenceAngleDegrees_Float = "maxincidenceangledegrees"; + static const char * const k_pch_Lighthouse_UseLighthouseDirect_Bool = "uselighthousedirect"; + static const char * const k_pch_Lighthouse_DBHistory_Bool = "dbhistory"; + + //----------------------------------------------------------------------------- + // null keys + + static const char * const k_pch_Null_Section = "driver_null"; + static const char * const k_pch_Null_EnableNullDriver_Bool = "enable"; + static const char * const k_pch_Null_SerialNumber_String = "serialNumber"; + static const char * const k_pch_Null_ModelNumber_String = "modelNumber"; + static const char * const k_pch_Null_WindowX_Int32 = "windowX"; + static const char * const k_pch_Null_WindowY_Int32 = "windowY"; + static const char * const k_pch_Null_WindowWidth_Int32 = "windowWidth"; + static const char * const k_pch_Null_WindowHeight_Int32 = "windowHeight"; + static const char * const k_pch_Null_RenderWidth_Int32 = "renderWidth"; + static const char * const k_pch_Null_RenderHeight_Int32 = "renderHeight"; + static const char * const k_pch_Null_SecondsFromVsyncToPhotons_Float = "secondsFromVsyncToPhotons"; + static const char * const k_pch_Null_DisplayFrequency_Float = "displayFrequency"; + + //----------------------------------------------------------------------------- + // user interface keys + static const char * const k_pch_UserInterface_Section = "userinterface"; + static const char * const k_pch_UserInterface_StatusAlwaysOnTop_Bool = "StatusAlwaysOnTop"; + static const char * const k_pch_UserInterface_EnableScreenshots_Bool = "EnableScreenshots"; + + //----------------------------------------------------------------------------- + // notification keys + static const char * const k_pch_Notifications_Section = "notifications"; + static const char * const k_pch_Notifications_DoNotDisturb_Bool = "DoNotDisturb"; + + //----------------------------------------------------------------------------- + // keyboard keys + static const char * const k_pch_Keyboard_Section = "keyboard"; + static const char * const k_pch_Keyboard_TutorialCompletions = "TutorialCompletions"; + static const char * const k_pch_Keyboard_ScaleX = "ScaleX"; + static const char * const k_pch_Keyboard_ScaleY = "ScaleY"; + static const char * const k_pch_Keyboard_OffsetLeftX = "OffsetLeftX"; + static const char * const k_pch_Keyboard_OffsetRightX = "OffsetRightX"; + static const char * const k_pch_Keyboard_OffsetY = "OffsetY"; + static const char * const k_pch_Keyboard_Smoothing = "Smoothing"; + + //----------------------------------------------------------------------------- + // perf keys + static const char * const k_pch_Perf_Section = "perfcheck"; + static const char * const k_pch_Perf_HeuristicActive_Bool = "heuristicActive"; + static const char * const k_pch_Perf_NotifyInHMD_Bool = "warnInHMD"; + static const char * const k_pch_Perf_NotifyOnlyOnce_Bool = "warnOnlyOnce"; + static const char * const k_pch_Perf_AllowTimingStore_Bool = "allowTimingStore"; + static const char * const k_pch_Perf_SaveTimingsOnExit_Bool = "saveTimingsOnExit"; + static const char * const k_pch_Perf_TestData_Float = "perfTestData"; + + //----------------------------------------------------------------------------- + // collision bounds keys + static const char * const k_pch_CollisionBounds_Section = "collisionBounds"; + static const char * const k_pch_CollisionBounds_Style_Int32 = "CollisionBoundsStyle"; + static const char * const k_pch_CollisionBounds_GroundPerimeterOn_Bool = "CollisionBoundsGroundPerimeterOn"; + static const char * const k_pch_CollisionBounds_CenterMarkerOn_Bool = "CollisionBoundsCenterMarkerOn"; + static const char * const k_pch_CollisionBounds_PlaySpaceOn_Bool = "CollisionBoundsPlaySpaceOn"; + static const char * const k_pch_CollisionBounds_FadeDistance_Float = "CollisionBoundsFadeDistance"; + static const char * const k_pch_CollisionBounds_ColorGammaR_Int32 = "CollisionBoundsColorGammaR"; + static const char * const k_pch_CollisionBounds_ColorGammaG_Int32 = "CollisionBoundsColorGammaG"; + static const char * const k_pch_CollisionBounds_ColorGammaB_Int32 = "CollisionBoundsColorGammaB"; + static const char * const k_pch_CollisionBounds_ColorGammaA_Int32 = "CollisionBoundsColorGammaA"; + + //----------------------------------------------------------------------------- + // camera keys + static const char * const k_pch_Camera_Section = "camera"; + static const char * const k_pch_Camera_EnableCamera_Bool = "enableCamera"; + static const char * const k_pch_Camera_EnableCameraInDashboard_Bool = "enableCameraInDashboard"; + static const char * const k_pch_Camera_EnableCameraForCollisionBounds_Bool = "enableCameraForCollisionBounds"; + static const char * const k_pch_Camera_EnableCameraForRoomView_Bool = "enableCameraForRoomView"; + static const char * const k_pch_Camera_BoundsColorGammaR_Int32 = "cameraBoundsColorGammaR"; + static const char * const k_pch_Camera_BoundsColorGammaG_Int32 = "cameraBoundsColorGammaG"; + static const char * const k_pch_Camera_BoundsColorGammaB_Int32 = "cameraBoundsColorGammaB"; + static const char * const k_pch_Camera_BoundsColorGammaA_Int32 = "cameraBoundsColorGammaA"; + + //----------------------------------------------------------------------------- + // audio keys + static const char * const k_pch_audio_Section = "audio"; + static const char * const k_pch_audio_OnPlaybackDevice_String = "onPlaybackDevice"; + static const char * const k_pch_audio_OnRecordDevice_String = "onRecordDevice"; + static const char * const k_pch_audio_OnPlaybackMirrorDevice_String = "onPlaybackMirrorDevice"; + static const char * const k_pch_audio_OffPlaybackDevice_String = "offPlaybackDevice"; + static const char * const k_pch_audio_OffRecordDevice_String = "offRecordDevice"; + static const char * const k_pch_audio_VIVEHDMIGain = "viveHDMIGain"; + + //----------------------------------------------------------------------------- + // model skin keys + static const char * const k_pch_modelskin_Section = "modelskins"; + +} // namespace vr + +// ivrchaperone.h +namespace vr +{ + +#if defined(__linux__) || defined(__APPLE__) + // The 32-bit version of gcc has the alignment requirement for uint64 and double set to + // 4 meaning that even with #pragma pack(8) these types will only be four-byte aligned. + // The 64-bit version of gcc has the alignment requirement for these types set to + // 8 meaning that unless we use #pragma pack(4) our structures will get bigger. + // The 64-bit structure packing has to match the 32-bit structure packing for each platform. + #pragma pack( push, 4 ) +#else + #pragma pack( push, 8 ) +#endif + +enum ChaperoneCalibrationState +{ + // OK! + ChaperoneCalibrationState_OK = 1, // Chaperone is fully calibrated and working correctly + + // Warnings + ChaperoneCalibrationState_Warning = 100, + ChaperoneCalibrationState_Warning_BaseStationMayHaveMoved = 101, // A base station thinks that it might have moved + ChaperoneCalibrationState_Warning_BaseStationRemoved = 102, // There are less base stations than when calibrated + ChaperoneCalibrationState_Warning_SeatedBoundsInvalid = 103, // Seated bounds haven't been calibrated for the current tracking center + + // Errors + ChaperoneCalibrationState_Error = 200, // The UniverseID is invalid + ChaperoneCalibrationState_Error_BaseStationUninitalized = 201, // Tracking center hasn't be calibrated for at least one of the base stations + ChaperoneCalibrationState_Error_BaseStationConflict = 202, // Tracking center is calibrated, but base stations disagree on the tracking space + ChaperoneCalibrationState_Error_PlayAreaInvalid = 203, // Play Area hasn't been calibrated for the current tracking center + ChaperoneCalibrationState_Error_CollisionBoundsInvalid = 204, // Collision Bounds haven't been calibrated for the current tracking center +}; + + +/** HIGH LEVEL TRACKING SPACE ASSUMPTIONS: +* 0,0,0 is the preferred standing area center. +* 0Y is the floor height. +* -Z is the preferred forward facing direction. */ +class IVRChaperone +{ +public: + + /** Get the current state of Chaperone calibration. This state can change at any time during a session due to physical base station changes. **/ + virtual ChaperoneCalibrationState GetCalibrationState() = 0; + + /** Returns the width and depth of the Play Area (formerly named Soft Bounds) in X and Z. + * Tracking space center (0,0,0) is the center of the Play Area. **/ + virtual bool GetPlayAreaSize( float *pSizeX, float *pSizeZ ) = 0; + + /** Returns the 4 corner positions of the Play Area (formerly named Soft Bounds). + * Corners are in counter-clockwise order. + * Standing center (0,0,0) is the center of the Play Area. + * It's a rectangle. + * 2 sides are parallel to the X axis and 2 sides are parallel to the Z axis. + * Height of every corner is 0Y (on the floor). **/ + virtual bool GetPlayAreaRect( HmdQuad_t *rect ) = 0; + + /** Reload Chaperone data from the .vrchap file on disk. */ + virtual void ReloadInfo( void ) = 0; + + /** Optionally give the chaperone system a hit about the color and brightness in the scene **/ + virtual void SetSceneColor( HmdColor_t color ) = 0; + + /** Get the current chaperone bounds draw color and brightness **/ + virtual void GetBoundsColor( HmdColor_t *pOutputColorArray, int nNumOutputColors, float flCollisionBoundsFadeDistance, HmdColor_t *pOutputCameraColor ) = 0; + + /** Determine whether the bounds are showing right now **/ + virtual bool AreBoundsVisible() = 0; + + /** Force the bounds to show, mostly for utilities **/ + virtual void ForceBoundsVisible( bool bForce ) = 0; +}; + +static const char * const IVRChaperone_Version = "IVRChaperone_003"; + +#pragma pack( pop ) + +} + +// ivrchaperonesetup.h +namespace vr +{ + +enum EChaperoneConfigFile +{ + EChaperoneConfigFile_Live = 1, // The live chaperone config, used by most applications and games + EChaperoneConfigFile_Temp = 2, // The temporary chaperone config, used to live-preview collision bounds in room setup +}; + +enum EChaperoneImportFlags +{ + EChaperoneImport_BoundsOnly = 0x0001, +}; + +/** Manages the working copy of the chaperone info. By default this will be the same as the +* live copy. Any changes made with this interface will stay in the working copy until +* CommitWorkingCopy() is called, at which point the working copy and the live copy will be +* the same again. */ +class IVRChaperoneSetup +{ +public: + + /** Saves the current working copy to disk */ + virtual bool CommitWorkingCopy( EChaperoneConfigFile configFile ) = 0; + + /** Reverts the working copy to match the live chaperone calibration. + * To modify existing data this MUST be do WHILE getting a non-error ChaperoneCalibrationStatus. + * Only after this should you do gets and sets on the existing data. */ + virtual void RevertWorkingCopy() = 0; + + /** Returns the width and depth of the Play Area (formerly named Soft Bounds) in X and Z from the working copy. + * Tracking space center (0,0,0) is the center of the Play Area. */ + virtual bool GetWorkingPlayAreaSize( float *pSizeX, float *pSizeZ ) = 0; + + /** Returns the 4 corner positions of the Play Area (formerly named Soft Bounds) from the working copy. + * Corners are in clockwise order. + * Tracking space center (0,0,0) is the center of the Play Area. + * It's a rectangle. + * 2 sides are parallel to the X axis and 2 sides are parallel to the Z axis. + * Height of every corner is 0Y (on the floor). **/ + virtual bool GetWorkingPlayAreaRect( HmdQuad_t *rect ) = 0; + + /** Returns the number of Quads if the buffer points to null. Otherwise it returns Quads + * into the buffer up to the max specified from the working copy. */ + virtual bool GetWorkingCollisionBoundsInfo( VR_OUT_ARRAY_COUNT(punQuadsCount) HmdQuad_t *pQuadsBuffer, uint32_t* punQuadsCount ) = 0; + + /** Returns the number of Quads if the buffer points to null. Otherwise it returns Quads + * into the buffer up to the max specified. */ + virtual bool GetLiveCollisionBoundsInfo( VR_OUT_ARRAY_COUNT(punQuadsCount) HmdQuad_t *pQuadsBuffer, uint32_t* punQuadsCount ) = 0; + + /** Returns the preferred seated position from the working copy. */ + virtual bool GetWorkingSeatedZeroPoseToRawTrackingPose( HmdMatrix34_t *pmatSeatedZeroPoseToRawTrackingPose ) = 0; + + /** Returns the standing origin from the working copy. */ + virtual bool GetWorkingStandingZeroPoseToRawTrackingPose( HmdMatrix34_t *pmatStandingZeroPoseToRawTrackingPose ) = 0; + + /** Sets the Play Area in the working copy. */ + virtual void SetWorkingPlayAreaSize( float sizeX, float sizeZ ) = 0; + + /** Sets the Collision Bounds in the working copy. */ + virtual void SetWorkingCollisionBoundsInfo( VR_ARRAY_COUNT(unQuadsCount) HmdQuad_t *pQuadsBuffer, uint32_t unQuadsCount ) = 0; + + /** Sets the preferred seated position in the working copy. */ + virtual void SetWorkingSeatedZeroPoseToRawTrackingPose( const HmdMatrix34_t *pMatSeatedZeroPoseToRawTrackingPose ) = 0; + + /** Sets the preferred standing position in the working copy. */ + virtual void SetWorkingStandingZeroPoseToRawTrackingPose( const HmdMatrix34_t *pMatStandingZeroPoseToRawTrackingPose ) = 0; + + /** Tear everything down and reload it from the file on disk */ + virtual void ReloadFromDisk( EChaperoneConfigFile configFile ) = 0; + + /** Returns the preferred seated position. */ + virtual bool GetLiveSeatedZeroPoseToRawTrackingPose( HmdMatrix34_t *pmatSeatedZeroPoseToRawTrackingPose ) = 0; + + virtual void SetWorkingCollisionBoundsTagsInfo( VR_ARRAY_COUNT(unTagCount) uint8_t *pTagsBuffer, uint32_t unTagCount ) = 0; + virtual bool GetLiveCollisionBoundsTagsInfo( VR_OUT_ARRAY_COUNT(punTagCount) uint8_t *pTagsBuffer, uint32_t *punTagCount ) = 0; + + virtual bool SetWorkingPhysicalBoundsInfo( VR_ARRAY_COUNT(unQuadsCount) HmdQuad_t *pQuadsBuffer, uint32_t unQuadsCount ) = 0; + virtual bool GetLivePhysicalBoundsInfo( VR_OUT_ARRAY_COUNT(punQuadsCount) HmdQuad_t *pQuadsBuffer, uint32_t* punQuadsCount ) = 0; + + virtual bool ExportLiveToBuffer( VR_OUT_STRING() char *pBuffer, uint32_t *pnBufferLength ) = 0; + virtual bool ImportFromBufferToWorking( const char *pBuffer, uint32_t nImportFlags ) = 0; +}; + +static const char * const IVRChaperoneSetup_Version = "IVRChaperoneSetup_005"; + + +} + +// ivrcompositor.h +namespace vr +{ + +#if defined(__linux__) || defined(__APPLE__) + // The 32-bit version of gcc has the alignment requirement for uint64 and double set to + // 4 meaning that even with #pragma pack(8) these types will only be four-byte aligned. + // The 64-bit version of gcc has the alignment requirement for these types set to + // 8 meaning that unless we use #pragma pack(4) our structures will get bigger. + // The 64-bit structure packing has to match the 32-bit structure packing for each platform. + #pragma pack( push, 4 ) +#else + #pragma pack( push, 8 ) +#endif + +/** Errors that can occur with the VR compositor */ +enum EVRCompositorError +{ + VRCompositorError_None = 0, + VRCompositorError_RequestFailed = 1, + VRCompositorError_IncompatibleVersion = 100, + VRCompositorError_DoNotHaveFocus = 101, + VRCompositorError_InvalidTexture = 102, + VRCompositorError_IsNotSceneApplication = 103, + VRCompositorError_TextureIsOnWrongDevice = 104, + VRCompositorError_TextureUsesUnsupportedFormat = 105, + VRCompositorError_SharedTexturesNotSupported = 106, + VRCompositorError_IndexOutOfRange = 107, +}; + +const uint32_t VRCompositor_ReprojectionReason_Cpu = 0x01; +const uint32_t VRCompositor_ReprojectionReason_Gpu = 0x02; + +/** Provides a single frame's timing information to the app */ +struct Compositor_FrameTiming +{ + uint32_t m_nSize; // Set to sizeof( Compositor_FrameTiming ) + uint32_t m_nFrameIndex; + uint32_t m_nNumFramePresents; // number of times this frame was presented + uint32_t m_nNumDroppedFrames; // number of additional times previous frame was scanned out + + /** Absolute time reference for comparing frames. This aligns with the vsync that running start is relative to. */ + double m_flSystemTimeInSeconds; + + /** These times may include work from other processes due to OS scheduling. + * The fewer packets of work these are broken up into, the less likely this will happen. + * GPU work can be broken up by calling Flush. This can sometimes be useful to get the GPU started + * processing that work earlier in the frame. */ + float m_flSceneRenderGpuMs; // time spent rendering the scene + float m_flTotalRenderGpuMs; // time between work submitted immediately after present (ideally vsync) until the end of compositor submitted work + float m_flCompositorRenderGpuMs; // time spend performing distortion correction, rendering chaperone, overlays, etc. + float m_flCompositorRenderCpuMs; // time spent on cpu submitting the above work for this frame + float m_flCompositorIdleCpuMs; // time spent waiting for running start (application could have used this much more time) + + /** Miscellaneous measured intervals. */ + float m_flClientFrameIntervalMs; // time between calls to WaitGetPoses + float m_flPresentCallCpuMs; // time blocked on call to present (usually 0.0, but can go long) + float m_flWaitForPresentCpuMs; // time spent spin-waiting for frame index to change (not near-zero indicates wait object failure) + float m_flSubmitFrameMs; // time spent in IVRCompositor::Submit (not near-zero indicates driver issue) + + /** The following are all relative to this frame's SystemTimeInSeconds */ + float m_flWaitGetPosesCalledMs; + float m_flNewPosesReadyMs; + float m_flNewFrameReadyMs; // second call to IVRCompositor::Submit + float m_flCompositorUpdateStartMs; + float m_flCompositorUpdateEndMs; + float m_flCompositorRenderStartMs; + + vr::TrackedDevicePose_t m_HmdPose; // pose used by app to render this frame + int32_t m_nFidelityLevel; // app reported value + + uint32_t m_nReprojectionFlags; +}; + +/** Cumulative stats for current application. These are not cleared until a new app connects, +* but they do stop accumulating once the associated app disconnects. */ +struct Compositor_CumulativeStats +{ + uint32_t m_nPid; // Process id associated with these stats (may no longer be running). + uint32_t m_nNumFramePresents; // total number of times we called present (includes reprojected frames) + uint32_t m_nNumDroppedFrames; // total number of times an old frame was re-scanned out (without reprojection) + uint32_t m_nNumReprojectedFrames; // total number of times a frame was scanned out a second time with reprojection + + /** Values recorded at startup before application has fully faded in the first time. */ + uint32_t m_nNumFramePresentsOnStartup; + uint32_t m_nNumDroppedFramesOnStartup; + uint32_t m_nNumReprojectedFramesOnStartup; + + /** Applications may explicitly fade to the compositor. This is usually to handle level transitions, and loading often causes + * system wide hitches. The following stats are collected during this period. Does not include values recorded during startup. */ + uint32_t m_nNumLoading; + uint32_t m_nNumFramePresentsLoading; + uint32_t m_nNumDroppedFramesLoading; + uint32_t m_nNumReprojectedFramesLoading; + + /** If we don't get a new frame from the app in less than 2.5 frames, then we assume the app has hung and start + * fading back to the compositor. The following stats are a result of this, and are a subset of those recorded above. + * Does not include values recorded during start up or loading. */ + uint32_t m_nNumTimedOut; + uint32_t m_nNumFramePresentsTimedOut; + uint32_t m_nNumDroppedFramesTimedOut; + uint32_t m_nNumReprojectedFramesTimedOut; +}; + +#pragma pack( pop ) + +/** Allows the application to interact with the compositor */ +class IVRCompositor +{ +public: + /** Sets tracking space returned by WaitGetPoses */ + virtual void SetTrackingSpace( ETrackingUniverseOrigin eOrigin ) = 0; + + /** Gets current tracking space returned by WaitGetPoses */ + virtual ETrackingUniverseOrigin GetTrackingSpace() = 0; + + /** Returns pose(s) to use to render scene (and optionally poses predicted two frames out for gameplay). */ + virtual EVRCompositorError WaitGetPoses( VR_ARRAY_COUNT(unRenderPoseArrayCount) TrackedDevicePose_t* pRenderPoseArray, uint32_t unRenderPoseArrayCount, + VR_ARRAY_COUNT(unGamePoseArrayCount) TrackedDevicePose_t* pGamePoseArray, uint32_t unGamePoseArrayCount ) = 0; + + /** Get the last set of poses returned by WaitGetPoses. */ + virtual EVRCompositorError GetLastPoses( VR_ARRAY_COUNT( unRenderPoseArrayCount ) TrackedDevicePose_t* pRenderPoseArray, uint32_t unRenderPoseArrayCount, + VR_ARRAY_COUNT( unGamePoseArrayCount ) TrackedDevicePose_t* pGamePoseArray, uint32_t unGamePoseArrayCount ) = 0; + + /** Interface for accessing last set of poses returned by WaitGetPoses one at a time. + * Returns VRCompositorError_IndexOutOfRange if unDeviceIndex not less than k_unMaxTrackedDeviceCount otherwise VRCompositorError_None. + * It is okay to pass NULL for either pose if you only want one of the values. */ + virtual EVRCompositorError GetLastPoseForTrackedDeviceIndex( TrackedDeviceIndex_t unDeviceIndex, TrackedDevicePose_t *pOutputPose, TrackedDevicePose_t *pOutputGamePose ) = 0; + + /** Updated scene texture to display. If pBounds is NULL the entire texture will be used. If called from an OpenGL app, consider adding a glFlush after + * Submitting both frames to signal the driver to start processing, otherwise it may wait until the command buffer fills up, causing the app to miss frames. + * + * OpenGL dirty state: + * glBindTexture + */ + virtual EVRCompositorError Submit( EVREye eEye, const Texture_t *pTexture, const VRTextureBounds_t* pBounds = 0, EVRSubmitFlags nSubmitFlags = Submit_Default ) = 0; + + /** Clears the frame that was sent with the last call to Submit. This will cause the + * compositor to show the grid until Submit is called again. */ + virtual void ClearLastSubmittedFrame() = 0; + + /** Call immediately after presenting your app's window (i.e. companion window) to unblock the compositor. + * This is an optional call, which only needs to be used if you can't instead call WaitGetPoses immediately after Present. + * For example, if your engine's render and game loop are not on separate threads, or blocking the render thread until 3ms before the next vsync would + * introduce a deadlock of some sort. This function tells the compositor that you have finished all rendering after having Submitted buffers for both + * eyes, and it is free to start its rendering work. This should only be called from the same thread you are rendering on. */ + virtual void PostPresentHandoff() = 0; + + /** Returns true if timing data is filled it. Sets oldest timing info if nFramesAgo is larger than the stored history. + * Be sure to set timing.size = sizeof(Compositor_FrameTiming) on struct passed in before calling this function. */ + virtual bool GetFrameTiming( Compositor_FrameTiming *pTiming, uint32_t unFramesAgo = 0 ) = 0; + + /** Returns the time in seconds left in the current (as identified by FrameTiming's frameIndex) frame. + * Due to "running start", this value may roll over to the next frame before ever reaching 0.0. */ + virtual float GetFrameTimeRemaining() = 0; + + /** Fills out stats accumulated for the last connected application. Pass in sizeof( Compositor_CumulativeStats ) as second parameter. */ + virtual void GetCumulativeStats( Compositor_CumulativeStats *pStats, uint32_t nStatsSizeInBytes ) = 0; + + /** Fades the view on the HMD to the specified color. The fade will take fSeconds, and the color values are between + * 0.0 and 1.0. This color is faded on top of the scene based on the alpha parameter. Removing the fade color instantly + * would be FadeToColor( 0.0, 0.0, 0.0, 0.0, 0.0 ). Values are in un-premultiplied alpha space. */ + virtual void FadeToColor( float fSeconds, float fRed, float fGreen, float fBlue, float fAlpha, bool bBackground = false ) = 0; + + /** Fading the Grid in or out in fSeconds */ + virtual void FadeGrid( float fSeconds, bool bFadeIn ) = 0; + + /** Override the skybox used in the compositor (e.g. for during level loads when the app can't feed scene images fast enough) + * Order is Front, Back, Left, Right, Top, Bottom. If only a single texture is passed, it is assumed in lat-long format. + * If two are passed, it is assumed a lat-long stereo pair. */ + virtual EVRCompositorError SetSkyboxOverride( VR_ARRAY_COUNT( unTextureCount ) const Texture_t *pTextures, uint32_t unTextureCount ) = 0; + + /** Resets compositor skybox back to defaults. */ + virtual void ClearSkyboxOverride() = 0; + + /** Brings the compositor window to the front. This is useful for covering any other window that may be on the HMD + * and is obscuring the compositor window. */ + virtual void CompositorBringToFront() = 0; + + /** Pushes the compositor window to the back. This is useful for allowing other applications to draw directly to the HMD. */ + virtual void CompositorGoToBack() = 0; + + /** Tells the compositor process to clean up and exit. You do not need to call this function at shutdown. Under normal + * circumstances the compositor will manage its own life cycle based on what applications are running. */ + virtual void CompositorQuit() = 0; + + /** Return whether the compositor is fullscreen */ + virtual bool IsFullscreen() = 0; + + /** Returns the process ID of the process that is currently rendering the scene */ + virtual uint32_t GetCurrentSceneFocusProcess() = 0; + + /** Returns the process ID of the process that rendered the last frame (or 0 if the compositor itself rendered the frame.) + * Returns 0 when fading out from an app and the app's process Id when fading into an app. */ + virtual uint32_t GetLastFrameRenderer() = 0; + + /** Returns true if the current process has the scene focus */ + virtual bool CanRenderScene() = 0; + + /** Creates a window on the primary monitor to display what is being shown in the headset. */ + virtual void ShowMirrorWindow() = 0; + + /** Closes the mirror window. */ + virtual void HideMirrorWindow() = 0; + + /** Returns true if the mirror window is shown. */ + virtual bool IsMirrorWindowVisible() = 0; + + /** Writes all images that the compositor knows about (including overlays) to a 'screenshots' folder in the SteamVR runtime root. */ + virtual void CompositorDumpImages() = 0; + + /** Let an app know it should be rendering with low resources. */ + virtual bool ShouldAppRenderWithLowResources() = 0; + + /** Override interleaved reprojection logic to force on. */ + virtual void ForceInterleavedReprojectionOn( bool bOverride ) = 0; + + /** Force reconnecting to the compositor process. */ + virtual void ForceReconnectProcess() = 0; + + /** Temporarily suspends rendering (useful for finer control over scene transitions). */ + virtual void SuspendRendering( bool bSuspend ) = 0; + + /** Screenshot support */ + + /** These functions are no longer used and will be removed in + * a future update. Use the functions via the + * IVRScreenshots interface */ + virtual vr::EVRCompositorError RequestScreenshot( vr::EVRScreenshotType type, const char *pchDestinationFileName, const char *pchVRDestinationFileName ) = 0; + virtual vr::EVRScreenshotType GetCurrentScreenshotType() = 0; + + /** Opens a shared D3D11 texture with the undistorted composited image for each eye. */ + virtual vr::EVRCompositorError GetMirrorTextureD3D11( vr::EVREye eEye, void *pD3D11DeviceOrResource, void **ppD3D11ShaderResourceView ) = 0; + + /** Access to mirror textures from OpenGL. */ + virtual vr::EVRCompositorError GetMirrorTextureGL( vr::EVREye eEye, vr::glUInt_t *pglTextureId, vr::glSharedTextureHandle_t *pglSharedTextureHandle ) = 0; + virtual bool ReleaseSharedGLTexture( vr::glUInt_t glTextureId, vr::glSharedTextureHandle_t glSharedTextureHandle ) = 0; + virtual void LockGLSharedTextureForAccess( vr::glSharedTextureHandle_t glSharedTextureHandle ) = 0; + virtual void UnlockGLSharedTextureForAccess( vr::glSharedTextureHandle_t glSharedTextureHandle ) = 0; +}; + +static const char * const IVRCompositor_Version = "IVRCompositor_015"; + +} // namespace vr + + + +// ivrnotifications.h +namespace vr +{ + +#if defined(__linux__) || defined(__APPLE__) + // The 32-bit version of gcc has the alignment requirement for uint64 and double set to + // 4 meaning that even with #pragma pack(8) these types will only be four-byte aligned. + // The 64-bit version of gcc has the alignment requirement for these types set to + // 8 meaning that unless we use #pragma pack(4) our structures will get bigger. + // The 64-bit structure packing has to match the 32-bit structure packing for each platform. + #pragma pack( push, 4 ) +#else + #pragma pack( push, 8 ) +#endif + +// Used for passing graphic data +struct NotificationBitmap_t +{ + NotificationBitmap_t() + : m_pImageData( nullptr ) + , m_nWidth( 0 ) + , m_nHeight( 0 ) + , m_nBytesPerPixel( 0 ) + { + }; + + void *m_pImageData; + int32_t m_nWidth; + int32_t m_nHeight; + int32_t m_nBytesPerPixel; +}; + + +/** Be aware that the notification type is used as 'priority' to pick the next notification */ +enum EVRNotificationType +{ + /** Transient notifications are automatically hidden after a period of time set by the user. + * They are used for things like information and chat messages that do not require user interaction. */ + EVRNotificationType_Transient = 0, + + /** Persistent notifications are shown to the user until they are hidden by calling RemoveNotification(). + * They are used for things like phone calls and alarms that require user interaction. */ + EVRNotificationType_Persistent = 1, + + /** System notifications are shown no matter what. It is expected, that the ulUserValue is used as ID. + * If there is already a system notification in the queue with that ID it is not accepted into the queue + * to prevent spamming with system notification */ + EVRNotificationType_Transient_SystemWithUserValue = 2, +}; + +enum EVRNotificationStyle +{ + /** Creates a notification with minimal external styling. */ + EVRNotificationStyle_None = 0, + + /** Used for notifications about overlay-level status. In Steam this is used for events like downloads completing. */ + EVRNotificationStyle_Application = 100, + + /** Used for notifications about contacts that are unknown or not available. In Steam this is used for friend invitations and offline friends. */ + EVRNotificationStyle_Contact_Disabled = 200, + + /** Used for notifications about contacts that are available but inactive. In Steam this is used for friends that are online but not playing a game. */ + EVRNotificationStyle_Contact_Enabled = 201, + + /** Used for notifications about contacts that are available and active. In Steam this is used for friends that are online and currently running a game. */ + EVRNotificationStyle_Contact_Active = 202, +}; + +static const uint32_t k_unNotificationTextMaxSize = 256; + +typedef uint32_t VRNotificationId; + + + +#pragma pack( pop ) + +/** Allows notification sources to interact with the VR system + This current interface is not yet implemented. Do not use yet. */ +class IVRNotifications +{ +public: + /** Create a notification and enqueue it to be shown to the user. + * An overlay handle is required to create a notification, as otherwise it would be impossible for a user to act on it. + * To create a two-line notification, use a line break ('\n') to split the text into two lines. + * The pImage argument may be NULL, in which case the specified overlay's icon will be used instead. */ + virtual EVRNotificationError CreateNotification( VROverlayHandle_t ulOverlayHandle, uint64_t ulUserValue, EVRNotificationType type, const char *pchText, EVRNotificationStyle style, const NotificationBitmap_t *pImage, /* out */ VRNotificationId *pNotificationId ) = 0; + + /** Destroy a notification, hiding it first if it currently shown to the user. */ + virtual EVRNotificationError RemoveNotification( VRNotificationId notificationId ) = 0; + +}; + +static const char * const IVRNotifications_Version = "IVRNotifications_002"; + +} // namespace vr + + + +// ivroverlay.h +namespace vr +{ + + /** The maximum length of an overlay key in bytes, counting the terminating null character. */ + static const uint32_t k_unVROverlayMaxKeyLength = 128; + + /** The maximum length of an overlay name in bytes, counting the terminating null character. */ + static const uint32_t k_unVROverlayMaxNameLength = 128; + + /** The maximum number of overlays that can exist in the system at one time. */ + static const uint32_t k_unMaxOverlayCount = 32; + + /** Types of input supported by VR Overlays */ + enum VROverlayInputMethod + { + VROverlayInputMethod_None = 0, // No input events will be generated automatically for this overlay + VROverlayInputMethod_Mouse = 1, // Tracked controllers will get mouse events automatically + }; + + /** Allows the caller to figure out which overlay transform getter to call. */ + enum VROverlayTransformType + { + VROverlayTransform_Absolute = 0, + VROverlayTransform_TrackedDeviceRelative = 1, + VROverlayTransform_SystemOverlay = 2, + VROverlayTransform_TrackedComponent = 3, + }; + + /** Overlay control settings */ + enum VROverlayFlags + { + VROverlayFlags_None = 0, + + // The following only take effect when rendered using the high quality render path (see SetHighQualityOverlay). + VROverlayFlags_Curved = 1, + VROverlayFlags_RGSS4X = 2, + + // Set this flag on a dashboard overlay to prevent a tab from showing up for that overlay + VROverlayFlags_NoDashboardTab = 3, + + // Set this flag on a dashboard that is able to deal with gamepad focus events + VROverlayFlags_AcceptsGamepadEvents = 4, + + // Indicates that the overlay should dim/brighten to show gamepad focus + VROverlayFlags_ShowGamepadFocus = 5, + + // When in VROverlayInputMethod_Mouse you can optionally enable sending VRScroll_t + VROverlayFlags_SendVRScrollEvents = 6, + VROverlayFlags_SendVRTouchpadEvents = 7, + + // If set this will render a vertical scroll wheel on the primary controller, + // only needed if not using VROverlayFlags_SendVRScrollEvents but you still want to represent a scroll wheel + VROverlayFlags_ShowTouchPadScrollWheel = 8, + + // If this is set ownership and render access to the overlay are transferred + // to the new scene process on a call to IVRApplications::LaunchInternalProcess + VROverlayFlags_TransferOwnershipToInternalProcess = 9, + + // If set, renders 50% of the texture in each eye, side by side + VROverlayFlags_SideBySide_Parallel = 10, // Texture is left/right + VROverlayFlags_SideBySide_Crossed = 11, // Texture is crossed and right/left + + VROverlayFlags_Panorama = 12, // Texture is a panorama + VROverlayFlags_StereoPanorama = 13, // Texture is a stereo panorama + }; + + struct VROverlayIntersectionParams_t + { + HmdVector3_t vSource; + HmdVector3_t vDirection; + ETrackingUniverseOrigin eOrigin; + }; + + struct VROverlayIntersectionResults_t + { + HmdVector3_t vPoint; + HmdVector3_t vNormal; + HmdVector2_t vUVs; + float fDistance; + }; + + // Input modes for the Big Picture gamepad text entry + enum EGamepadTextInputMode + { + k_EGamepadTextInputModeNormal = 0, + k_EGamepadTextInputModePassword = 1, + k_EGamepadTextInputModeSubmit = 2, + }; + + // Controls number of allowed lines for the Big Picture gamepad text entry + enum EGamepadTextInputLineMode + { + k_EGamepadTextInputLineModeSingleLine = 0, + k_EGamepadTextInputLineModeMultipleLines = 1 + }; + + /** Directions for changing focus between overlays with the gamepad */ + enum EOverlayDirection + { + OverlayDirection_Up = 0, + OverlayDirection_Down = 1, + OverlayDirection_Left = 2, + OverlayDirection_Right = 3, + + OverlayDirection_Count = 4, + }; + + class IVROverlay + { + public: + + // --------------------------------------------- + // Overlay management methods + // --------------------------------------------- + + /** Finds an existing overlay with the specified key. */ + virtual EVROverlayError FindOverlay( const char *pchOverlayKey, VROverlayHandle_t * pOverlayHandle ) = 0; + + /** Creates a new named overlay. All overlays start hidden and with default settings. */ + virtual EVROverlayError CreateOverlay( const char *pchOverlayKey, const char *pchOverlayFriendlyName, VROverlayHandle_t * pOverlayHandle ) = 0; + + /** Destroys the specified overlay. When an application calls VR_Shutdown all overlays created by that app are + * automatically destroyed. */ + virtual EVROverlayError DestroyOverlay( VROverlayHandle_t ulOverlayHandle ) = 0; + + /** Specify which overlay to use the high quality render path. This overlay will be composited in during the distortion pass which + * results in it drawing on top of everything else, but also at a higher quality as it samples the source texture directly rather than + * rasterizing into each eye's render texture first. Because if this, only one of these is supported at any given time. It is most useful + * for overlays that are expected to take up most of the user's view (e.g. streaming video). + * This mode does not support mouse input to your overlay. */ + virtual EVROverlayError SetHighQualityOverlay( VROverlayHandle_t ulOverlayHandle ) = 0; + + /** Returns the overlay handle of the current overlay being rendered using the single high quality overlay render path. + * Otherwise it will return k_ulOverlayHandleInvalid. */ + virtual vr::VROverlayHandle_t GetHighQualityOverlay() = 0; + + /** Fills the provided buffer with the string key of the overlay. Returns the size of buffer required to store the key, including + * the terminating null character. k_unVROverlayMaxKeyLength will be enough bytes to fit the string. */ + virtual uint32_t GetOverlayKey( VROverlayHandle_t ulOverlayHandle, VR_OUT_STRING() char *pchValue, uint32_t unBufferSize, EVROverlayError *pError = 0L ) = 0; + + /** Fills the provided buffer with the friendly name of the overlay. Returns the size of buffer required to store the key, including + * the terminating null character. k_unVROverlayMaxNameLength will be enough bytes to fit the string. */ + virtual uint32_t GetOverlayName( VROverlayHandle_t ulOverlayHandle, VR_OUT_STRING() char *pchValue, uint32_t unBufferSize, EVROverlayError *pError = 0L ) = 0; + + /** Gets the raw image data from an overlay. Overlay image data is always returned as RGBA data, 4 bytes per pixel. If the buffer is not large enough, width and height + * will be set and VROverlayError_ArrayTooSmall is returned. */ + virtual EVROverlayError GetOverlayImageData( VROverlayHandle_t ulOverlayHandle, void *pvBuffer, uint32_t unBufferSize, uint32_t *punWidth, uint32_t *punHeight ) = 0; + + /** returns a string that corresponds with the specified overlay error. The string will be the name + * of the error enum value for all valid error codes */ + virtual const char *GetOverlayErrorNameFromEnum( EVROverlayError error ) = 0; + + + // --------------------------------------------- + // Overlay rendering methods + // --------------------------------------------- + + /** Sets the pid that is allowed to render to this overlay (the creator pid is always allow to render), + * by default this is the pid of the process that made the overlay */ + virtual EVROverlayError SetOverlayRenderingPid( VROverlayHandle_t ulOverlayHandle, uint32_t unPID ) = 0; + + /** Gets the pid that is allowed to render to this overlay */ + virtual uint32_t GetOverlayRenderingPid( VROverlayHandle_t ulOverlayHandle ) = 0; + + /** Specify flag setting for a given overlay */ + virtual EVROverlayError SetOverlayFlag( VROverlayHandle_t ulOverlayHandle, VROverlayFlags eOverlayFlag, bool bEnabled ) = 0; + + /** Sets flag setting for a given overlay */ + virtual EVROverlayError GetOverlayFlag( VROverlayHandle_t ulOverlayHandle, VROverlayFlags eOverlayFlag, bool *pbEnabled ) = 0; + + /** Sets the color tint of the overlay quad. Use 0.0 to 1.0 per channel. */ + virtual EVROverlayError SetOverlayColor( VROverlayHandle_t ulOverlayHandle, float fRed, float fGreen, float fBlue ) = 0; + + /** Gets the color tint of the overlay quad. */ + virtual EVROverlayError GetOverlayColor( VROverlayHandle_t ulOverlayHandle, float *pfRed, float *pfGreen, float *pfBlue ) = 0; + + /** Sets the alpha of the overlay quad. Use 1.0 for 100 percent opacity to 0.0 for 0 percent opacity. */ + virtual EVROverlayError SetOverlayAlpha( VROverlayHandle_t ulOverlayHandle, float fAlpha ) = 0; + + /** Gets the alpha of the overlay quad. By default overlays are rendering at 100 percent alpha (1.0). */ + virtual EVROverlayError GetOverlayAlpha( VROverlayHandle_t ulOverlayHandle, float *pfAlpha ) = 0; + + /** Sets the width of the overlay quad in meters. By default overlays are rendered on a quad that is 1 meter across */ + virtual EVROverlayError SetOverlayWidthInMeters( VROverlayHandle_t ulOverlayHandle, float fWidthInMeters ) = 0; + + /** Returns the width of the overlay quad in meters. By default overlays are rendered on a quad that is 1 meter across */ + virtual EVROverlayError GetOverlayWidthInMeters( VROverlayHandle_t ulOverlayHandle, float *pfWidthInMeters ) = 0; + + /** For high-quality curved overlays only, sets the distance range in meters from the overlay used to automatically curve + * the surface around the viewer. Min is distance is when the surface will be most curved. Max is when least curved. */ + virtual EVROverlayError SetOverlayAutoCurveDistanceRangeInMeters( VROverlayHandle_t ulOverlayHandle, float fMinDistanceInMeters, float fMaxDistanceInMeters ) = 0; + + /** For high-quality curved overlays only, gets the distance range in meters from the overlay used to automatically curve + * the surface around the viewer. Min is distance is when the surface will be most curved. Max is when least curved. */ + virtual EVROverlayError GetOverlayAutoCurveDistanceRangeInMeters( VROverlayHandle_t ulOverlayHandle, float *pfMinDistanceInMeters, float *pfMaxDistanceInMeters ) = 0; + + /** Sets the colorspace the overlay texture's data is in. Defaults to 'auto'. + * If the texture needs to be resolved, you should call SetOverlayTexture with the appropriate colorspace instead. */ + virtual EVROverlayError SetOverlayTextureColorSpace( VROverlayHandle_t ulOverlayHandle, EColorSpace eTextureColorSpace ) = 0; + + /** Gets the overlay's current colorspace setting. */ + virtual EVROverlayError GetOverlayTextureColorSpace( VROverlayHandle_t ulOverlayHandle, EColorSpace *peTextureColorSpace ) = 0; + + /** Sets the part of the texture to use for the overlay. UV Min is the upper left corner and UV Max is the lower right corner. */ + virtual EVROverlayError SetOverlayTextureBounds( VROverlayHandle_t ulOverlayHandle, const VRTextureBounds_t *pOverlayTextureBounds ) = 0; + + /** Gets the part of the texture to use for the overlay. UV Min is the upper left corner and UV Max is the lower right corner. */ + virtual EVROverlayError GetOverlayTextureBounds( VROverlayHandle_t ulOverlayHandle, VRTextureBounds_t *pOverlayTextureBounds ) = 0; + + /** Returns the transform type of this overlay. */ + virtual EVROverlayError GetOverlayTransformType( VROverlayHandle_t ulOverlayHandle, VROverlayTransformType *peTransformType ) = 0; + + /** Sets the transform to absolute tracking origin. */ + virtual EVROverlayError SetOverlayTransformAbsolute( VROverlayHandle_t ulOverlayHandle, ETrackingUniverseOrigin eTrackingOrigin, const HmdMatrix34_t *pmatTrackingOriginToOverlayTransform ) = 0; + + /** Gets the transform if it is absolute. Returns an error if the transform is some other type. */ + virtual EVROverlayError GetOverlayTransformAbsolute( VROverlayHandle_t ulOverlayHandle, ETrackingUniverseOrigin *peTrackingOrigin, HmdMatrix34_t *pmatTrackingOriginToOverlayTransform ) = 0; + + /** Sets the transform to relative to the transform of the specified tracked device. */ + virtual EVROverlayError SetOverlayTransformTrackedDeviceRelative( VROverlayHandle_t ulOverlayHandle, TrackedDeviceIndex_t unTrackedDevice, const HmdMatrix34_t *pmatTrackedDeviceToOverlayTransform ) = 0; + + /** Gets the transform if it is relative to a tracked device. Returns an error if the transform is some other type. */ + virtual EVROverlayError GetOverlayTransformTrackedDeviceRelative( VROverlayHandle_t ulOverlayHandle, TrackedDeviceIndex_t *punTrackedDevice, HmdMatrix34_t *pmatTrackedDeviceToOverlayTransform ) = 0; + + /** Sets the transform to draw the overlay on a rendermodel component mesh instead of a quad. This will only draw when the system is + * drawing the device. Overlays with this transform type cannot receive mouse events. */ + virtual EVROverlayError SetOverlayTransformTrackedDeviceComponent( VROverlayHandle_t ulOverlayHandle, TrackedDeviceIndex_t unDeviceIndex, const char *pchComponentName ) = 0; + + /** Gets the transform information when the overlay is rendering on a component. */ + virtual EVROverlayError GetOverlayTransformTrackedDeviceComponent( VROverlayHandle_t ulOverlayHandle, TrackedDeviceIndex_t *punDeviceIndex, char *pchComponentName, uint32_t unComponentNameSize ) = 0; + + /** Shows the VR overlay. For dashboard overlays, only the Dashboard Manager is allowed to call this. */ + virtual EVROverlayError ShowOverlay( VROverlayHandle_t ulOverlayHandle ) = 0; + + /** Hides the VR overlay. For dashboard overlays, only the Dashboard Manager is allowed to call this. */ + virtual EVROverlayError HideOverlay( VROverlayHandle_t ulOverlayHandle ) = 0; + + /** Returns true if the overlay is visible. */ + virtual bool IsOverlayVisible( VROverlayHandle_t ulOverlayHandle ) = 0; + + /** Get the transform in 3d space associated with a specific 2d point in the overlay's coordinate space (where 0,0 is the lower left). -Z points out of the overlay */ + virtual EVROverlayError GetTransformForOverlayCoordinates( VROverlayHandle_t ulOverlayHandle, ETrackingUniverseOrigin eTrackingOrigin, HmdVector2_t coordinatesInOverlay, HmdMatrix34_t *pmatTransform ) = 0; + + // --------------------------------------------- + // Overlay input methods + // --------------------------------------------- + + /** Returns true and fills the event with the next event on the overlay's event queue, if there is one. + * If there are no events this method returns false. uncbVREvent should be the size in bytes of the VREvent_t struct */ + virtual bool PollNextOverlayEvent( VROverlayHandle_t ulOverlayHandle, VREvent_t *pEvent, uint32_t uncbVREvent ) = 0; + + /** Returns the current input settings for the specified overlay. */ + virtual EVROverlayError GetOverlayInputMethod( VROverlayHandle_t ulOverlayHandle, VROverlayInputMethod *peInputMethod ) = 0; + + /** Sets the input settings for the specified overlay. */ + virtual EVROverlayError SetOverlayInputMethod( VROverlayHandle_t ulOverlayHandle, VROverlayInputMethod eInputMethod ) = 0; + + /** Gets the mouse scaling factor that is used for mouse events. The actual texture may be a different size, but this is + * typically the size of the underlying UI in pixels. */ + virtual EVROverlayError GetOverlayMouseScale( VROverlayHandle_t ulOverlayHandle, HmdVector2_t *pvecMouseScale ) = 0; + + /** Sets the mouse scaling factor that is used for mouse events. The actual texture may be a different size, but this is + * typically the size of the underlying UI in pixels (not in world space). */ + virtual EVROverlayError SetOverlayMouseScale( VROverlayHandle_t ulOverlayHandle, const HmdVector2_t *pvecMouseScale ) = 0; + + /** Computes the overlay-space pixel coordinates of where the ray intersects the overlay with the + * specified settings. Returns false if there is no intersection. */ + virtual bool ComputeOverlayIntersection( VROverlayHandle_t ulOverlayHandle, const VROverlayIntersectionParams_t *pParams, VROverlayIntersectionResults_t *pResults ) = 0; + + /** Processes mouse input from the specified controller as though it were a mouse pointed at a compositor overlay with the + * specified settings. The controller is treated like a laser pointer on the -z axis. The point where the laser pointer would + * intersect with the overlay is the mouse position, the trigger is left mouse, and the track pad is right mouse. + * + * Return true if the controller is pointed at the overlay and an event was generated. */ + virtual bool HandleControllerOverlayInteractionAsMouse( VROverlayHandle_t ulOverlayHandle, TrackedDeviceIndex_t unControllerDeviceIndex ) = 0; + + /** Returns true if the specified overlay is the hover target. An overlay is the hover target when it is the last overlay "moused over" + * by the virtual mouse pointer */ + virtual bool IsHoverTargetOverlay( VROverlayHandle_t ulOverlayHandle ) = 0; + + /** Returns the current Gamepad focus overlay */ + virtual vr::VROverlayHandle_t GetGamepadFocusOverlay() = 0; + + /** Sets the current Gamepad focus overlay */ + virtual EVROverlayError SetGamepadFocusOverlay( VROverlayHandle_t ulNewFocusOverlay ) = 0; + + /** Sets an overlay's neighbor. This will also set the neighbor of the "to" overlay + * to point back to the "from" overlay. If an overlay's neighbor is set to invalid both + * ends will be cleared */ + virtual EVROverlayError SetOverlayNeighbor( EOverlayDirection eDirection, VROverlayHandle_t ulFrom, VROverlayHandle_t ulTo ) = 0; + + /** Changes the Gamepad focus from one overlay to one of its neighbors. Returns VROverlayError_NoNeighbor if there is no + * neighbor in that direction */ + virtual EVROverlayError MoveGamepadFocusToNeighbor( EOverlayDirection eDirection, VROverlayHandle_t ulFrom ) = 0; + + // --------------------------------------------- + // Overlay texture methods + // --------------------------------------------- + + /** Texture to draw for the overlay. This function can only be called by the overlay's creator or renderer process (see SetOverlayRenderingPid) . + * + * OpenGL dirty state: + * glBindTexture + */ + virtual EVROverlayError SetOverlayTexture( VROverlayHandle_t ulOverlayHandle, const Texture_t *pTexture ) = 0; + + /** Use this to tell the overlay system to release the texture set for this overlay. */ + virtual EVROverlayError ClearOverlayTexture( VROverlayHandle_t ulOverlayHandle ) = 0; + + /** Separate interface for providing the data as a stream of bytes, but there is an upper bound on data + * that can be sent. This function can only be called by the overlay's renderer process. */ + virtual EVROverlayError SetOverlayRaw( VROverlayHandle_t ulOverlayHandle, void *pvBuffer, uint32_t unWidth, uint32_t unHeight, uint32_t unDepth ) = 0; + + /** Separate interface for providing the image through a filename: can be png or jpg, and should not be bigger than 1920x1080. + * This function can only be called by the overlay's renderer process */ + virtual EVROverlayError SetOverlayFromFile( VROverlayHandle_t ulOverlayHandle, const char *pchFilePath ) = 0; + + /** Get the native texture handle/device for an overlay you have created. + * On windows this handle will be a ID3D11ShaderResourceView with a ID3D11Texture2D bound. + * + * The texture will always be sized to match the backing texture you supplied in SetOverlayTexture above. + * + * You MUST call ReleaseNativeOverlayHandle() with pNativeTextureHandle once you are done with this texture. + * + * pNativeTextureHandle is an OUTPUT, it will be a pointer to a ID3D11ShaderResourceView *. + * pNativeTextureRef is an INPUT and should be a ID3D11Resource *. The device used by pNativeTextureRef will be used to bind pNativeTextureHandle. + */ + virtual EVROverlayError GetOverlayTexture( VROverlayHandle_t ulOverlayHandle, void **pNativeTextureHandle, void *pNativeTextureRef, uint32_t *pWidth, uint32_t *pHeight, uint32_t *pNativeFormat, EGraphicsAPIConvention *pAPI, EColorSpace *pColorSpace ) = 0; + + /** Release the pNativeTextureHandle provided from the GetOverlayTexture call, this allows the system to free the underlying GPU resources for this object, + * so only do it once you stop rendering this texture. + */ + virtual EVROverlayError ReleaseNativeOverlayHandle( VROverlayHandle_t ulOverlayHandle, void *pNativeTextureHandle ) = 0; + + /** Get the size of the overlay texture */ + virtual EVROverlayError GetOverlayTextureSize( VROverlayHandle_t ulOverlayHandle, uint32_t *pWidth, uint32_t *pHeight ) = 0; + + // ---------------------------------------------- + // Dashboard Overlay Methods + // ---------------------------------------------- + + /** Creates a dashboard overlay and returns its handle */ + virtual EVROverlayError CreateDashboardOverlay( const char *pchOverlayKey, const char *pchOverlayFriendlyName, VROverlayHandle_t * pMainHandle, VROverlayHandle_t *pThumbnailHandle ) = 0; + + /** Returns true if the dashboard is visible */ + virtual bool IsDashboardVisible() = 0; + + /** returns true if the dashboard is visible and the specified overlay is the active system Overlay */ + virtual bool IsActiveDashboardOverlay( VROverlayHandle_t ulOverlayHandle ) = 0; + + /** Sets the dashboard overlay to only appear when the specified process ID has scene focus */ + virtual EVROverlayError SetDashboardOverlaySceneProcess( VROverlayHandle_t ulOverlayHandle, uint32_t unProcessId ) = 0; + + /** Gets the process ID that this dashboard overlay requires to have scene focus */ + virtual EVROverlayError GetDashboardOverlaySceneProcess( VROverlayHandle_t ulOverlayHandle, uint32_t *punProcessId ) = 0; + + /** Shows the dashboard. */ + virtual void ShowDashboard( const char *pchOverlayToShow ) = 0; + + /** Returns the tracked device that has the laser pointer in the dashboard */ + virtual vr::TrackedDeviceIndex_t GetPrimaryDashboardDevice() = 0; + + // --------------------------------------------- + // Keyboard methods + // --------------------------------------------- + + /** Show the virtual keyboard to accept input **/ + virtual EVROverlayError ShowKeyboard( EGamepadTextInputMode eInputMode, EGamepadTextInputLineMode eLineInputMode, const char *pchDescription, uint32_t unCharMax, const char *pchExistingText, bool bUseMinimalMode, uint64_t uUserValue ) = 0; + + virtual EVROverlayError ShowKeyboardForOverlay( VROverlayHandle_t ulOverlayHandle, EGamepadTextInputMode eInputMode, EGamepadTextInputLineMode eLineInputMode, const char *pchDescription, uint32_t unCharMax, const char *pchExistingText, bool bUseMinimalMode, uint64_t uUserValue ) = 0; + + /** Get the text that was entered into the text input **/ + virtual uint32_t GetKeyboardText( VR_OUT_STRING() char *pchText, uint32_t cchText ) = 0; + + /** Hide the virtual keyboard **/ + virtual void HideKeyboard() = 0; + + /** Set the position of the keyboard in world space **/ + virtual void SetKeyboardTransformAbsolute( ETrackingUniverseOrigin eTrackingOrigin, const HmdMatrix34_t *pmatTrackingOriginToKeyboardTransform ) = 0; + + /** Set the position of the keyboard in overlay space by telling it to avoid a rectangle in the overlay. Rectangle coords have (0,0) in the bottom left **/ + virtual void SetKeyboardPositionForOverlay( VROverlayHandle_t ulOverlayHandle, HmdRect2_t avoidRect ) = 0; + + }; + + static const char * const IVROverlay_Version = "IVROverlay_012"; + +} // namespace vr + +// ivrrendermodels.h +namespace vr +{ + +static const char * const k_pch_Controller_Component_GDC2015 = "gdc2015"; // Canonical coordinate system of the gdc 2015 wired controller, provided for backwards compatibility +static const char * const k_pch_Controller_Component_Base = "base"; // For controllers with an unambiguous 'base'. +static const char * const k_pch_Controller_Component_Tip = "tip"; // For controllers with an unambiguous 'tip' (used for 'laser-pointing') +static const char * const k_pch_Controller_Component_HandGrip = "handgrip"; // Neutral, ambidextrous hand-pose when holding controller. On plane between neutrally posed index finger and thumb +static const char * const k_pch_Controller_Component_Status = "status"; // 1:1 aspect ratio status area, with canonical [0,1] uv mapping + +#if defined(__linux__) || defined(__APPLE__) +// The 32-bit version of gcc has the alignment requirement for uint64 and double set to +// 4 meaning that even with #pragma pack(8) these types will only be four-byte aligned. +// The 64-bit version of gcc has the alignment requirement for these types set to +// 8 meaning that unless we use #pragma pack(4) our structures will get bigger. +// The 64-bit structure packing has to match the 32-bit structure packing for each platform. +#pragma pack( push, 4 ) +#else +#pragma pack( push, 8 ) +#endif + +/** Errors that can occur with the VR compositor */ +enum EVRRenderModelError +{ + VRRenderModelError_None = 0, + VRRenderModelError_Loading = 100, + VRRenderModelError_NotSupported = 200, + VRRenderModelError_InvalidArg = 300, + VRRenderModelError_InvalidModel = 301, + VRRenderModelError_NoShapes = 302, + VRRenderModelError_MultipleShapes = 303, + VRRenderModelError_TooManyVertices = 304, + VRRenderModelError_MultipleTextures = 305, + VRRenderModelError_BufferTooSmall = 306, + VRRenderModelError_NotEnoughNormals = 307, + VRRenderModelError_NotEnoughTexCoords = 308, + + VRRenderModelError_InvalidTexture = 400, +}; + +typedef uint32_t VRComponentProperties; + +enum EVRComponentProperty +{ + VRComponentProperty_IsStatic = (1 << 0), + VRComponentProperty_IsVisible = (1 << 1), + VRComponentProperty_IsTouched = (1 << 2), + VRComponentProperty_IsPressed = (1 << 3), + VRComponentProperty_IsScrolled = (1 << 4), +}; + +/** Describes state information about a render-model component, including transforms and other dynamic properties */ +struct RenderModel_ComponentState_t +{ + HmdMatrix34_t mTrackingToComponentRenderModel; // Transform required when drawing the component render model + HmdMatrix34_t mTrackingToComponentLocal; // Transform available for attaching to a local component coordinate system (-Z out from surface ) + VRComponentProperties uProperties; +}; + +/** A single vertex in a render model */ +struct RenderModel_Vertex_t +{ + HmdVector3_t vPosition; // position in meters in device space + HmdVector3_t vNormal; + float rfTextureCoord[2]; +}; + +/** A texture map for use on a render model */ +struct RenderModel_TextureMap_t +{ + uint16_t unWidth, unHeight; // width and height of the texture map in pixels + const uint8_t *rubTextureMapData; // Map texture data. All textures are RGBA with 8 bits per channel per pixel. Data size is width * height * 4ub +}; + +/** Session unique texture identifier. Rendermodels which share the same texture will have the same id. +IDs <0 denote the texture is not present */ + +typedef int32_t TextureID_t; + +const TextureID_t INVALID_TEXTURE_ID = -1; + +struct RenderModel_t +{ + const RenderModel_Vertex_t *rVertexData; // Vertex data for the mesh + uint32_t unVertexCount; // Number of vertices in the vertex data + const uint16_t *rIndexData; // Indices into the vertex data for each triangle + uint32_t unTriangleCount; // Number of triangles in the mesh. Index count is 3 * TriangleCount + TextureID_t diffuseTextureId; // Session unique texture identifier. Rendermodels which share the same texture will have the same id. <0 == texture not present +}; + +struct RenderModel_ControllerMode_State_t +{ + bool bScrollWheelVisible; // is this controller currently set to be in a scroll wheel mode +}; + +#pragma pack( pop ) + +class IVRRenderModels +{ +public: + + /** Loads and returns a render model for use in the application. pchRenderModelName should be a render model name + * from the Prop_RenderModelName_String property or an absolute path name to a render model on disk. + * + * The resulting render model is valid until VR_Shutdown() is called or until FreeRenderModel() is called. When the + * application is finished with the render model it should call FreeRenderModel() to free the memory associated + * with the model. + * + * The method returns VRRenderModelError_Loading while the render model is still being loaded. + * The method returns VRRenderModelError_None once loaded successfully, otherwise will return an error. */ + virtual EVRRenderModelError LoadRenderModel_Async( const char *pchRenderModelName, RenderModel_t **ppRenderModel ) = 0; + + /** Frees a previously returned render model + * It is safe to call this on a null ptr. */ + virtual void FreeRenderModel( RenderModel_t *pRenderModel ) = 0; + + /** Loads and returns a texture for use in the application. */ + virtual EVRRenderModelError LoadTexture_Async( TextureID_t textureId, RenderModel_TextureMap_t **ppTexture ) = 0; + + /** Frees a previously returned texture + * It is safe to call this on a null ptr. */ + virtual void FreeTexture( RenderModel_TextureMap_t *pTexture ) = 0; + + /** Creates a D3D11 texture and loads data into it. */ + virtual EVRRenderModelError LoadTextureD3D11_Async( TextureID_t textureId, void *pD3D11Device, void **ppD3D11Texture2D ) = 0; + + /** Helper function to copy the bits into an existing texture. */ + virtual EVRRenderModelError LoadIntoTextureD3D11_Async( TextureID_t textureId, void *pDstTexture ) = 0; + + /** Use this to free textures created with LoadTextureD3D11_Async instead of calling Release on them. */ + virtual void FreeTextureD3D11( void *pD3D11Texture2D ) = 0; + + /** Use this to get the names of available render models. Index does not correlate to a tracked device index, but + * is only used for iterating over all available render models. If the index is out of range, this function will return 0. + * Otherwise, it will return the size of the buffer required for the name. */ + virtual uint32_t GetRenderModelName( uint32_t unRenderModelIndex, VR_OUT_STRING() char *pchRenderModelName, uint32_t unRenderModelNameLen ) = 0; + + /** Returns the number of available render models. */ + virtual uint32_t GetRenderModelCount() = 0; + + + /** Returns the number of components of the specified render model. + * Components are useful when client application wish to draw, label, or otherwise interact with components of tracked objects. + * Examples controller components: + * renderable things such as triggers, buttons + * non-renderable things which include coordinate systems such as 'tip', 'base', a neutral controller agnostic hand-pose + * If all controller components are enumerated and rendered, it will be equivalent to drawing the traditional render model + * Returns 0 if components not supported, >0 otherwise */ + virtual uint32_t GetComponentCount( const char *pchRenderModelName ) = 0; + + /** Use this to get the names of available components. Index does not correlate to a tracked device index, but + * is only used for iterating over all available components. If the index is out of range, this function will return 0. + * Otherwise, it will return the size of the buffer required for the name. */ + virtual uint32_t GetComponentName( const char *pchRenderModelName, uint32_t unComponentIndex, VR_OUT_STRING( ) char *pchComponentName, uint32_t unComponentNameLen ) = 0; + + /** Get the button mask for all buttons associated with this component + * If no buttons (or axes) are associated with this component, return 0 + * Note: multiple components may be associated with the same button. Ex: two grip buttons on a single controller. + * Note: A single component may be associated with multiple buttons. Ex: A trackpad which also provides "D-pad" functionality */ + virtual uint64_t GetComponentButtonMask( const char *pchRenderModelName, const char *pchComponentName ) = 0; + + /** Use this to get the render model name for the specified rendermode/component combination, to be passed to LoadRenderModel. + * If the component name is out of range, this function will return 0. + * Otherwise, it will return the size of the buffer required for the name. */ + virtual uint32_t GetComponentRenderModelName( const char *pchRenderModelName, const char *pchComponentName, VR_OUT_STRING( ) char *pchComponentRenderModelName, uint32_t unComponentRenderModelNameLen ) = 0; + + /** Use this to query information about the component, as a function of the controller state. + * + * For dynamic controller components (ex: trigger) values will reflect component motions + * For static components this will return a consistent value independent of the VRControllerState_t + * + * If the pchRenderModelName or pchComponentName is invalid, this will return false (and transforms will be set to identity). + * Otherwise, return true + * Note: For dynamic objects, visibility may be dynamic. (I.e., true/false will be returned based on controller state and controller mode state ) */ + virtual bool GetComponentState( const char *pchRenderModelName, const char *pchComponentName, const vr::VRControllerState_t *pControllerState, const RenderModel_ControllerMode_State_t *pState, RenderModel_ComponentState_t *pComponentState ) = 0; + + /** Returns true if the render model has a component with the specified name */ + virtual bool RenderModelHasComponent( const char *pchRenderModelName, const char *pchComponentName ) = 0; + + /** Returns the URL of the thumbnail image for this rendermodel */ + virtual uint32_t GetRenderModelThumbnailURL( const char *pchRenderModelName, VR_OUT_STRING() char *pchThumbnailURL, uint32_t unThumbnailURLLen, vr::EVRRenderModelError *peError ) = 0; + + /** Provides a render model path that will load the unskinned model if the model name provided has been replace by the user. If the model + * hasn't been replaced the path value will still be a valid path to load the model. Pass this to LoadRenderModel_Async, etc. to load the + * model. */ + virtual uint32_t GetRenderModelOriginalPath( const char *pchRenderModelName, VR_OUT_STRING() char *pchOriginalPath, uint32_t unOriginalPathLen, vr::EVRRenderModelError *peError ) = 0; + + /** Returns a string for a render model error */ + virtual const char *GetRenderModelErrorNameFromEnum( vr::EVRRenderModelError error ) = 0; +}; + +static const char * const IVRRenderModels_Version = "IVRRenderModels_005"; + +} + + +// ivrextendeddisplay.h +namespace vr +{ + + /** NOTE: Use of this interface is not recommended in production applications. It will not work for displays which use + * direct-to-display mode. It is also incompatible with the VR compositor and is not available when the compositor is running. */ + class IVRExtendedDisplay + { + public: + + /** Size and position that the window needs to be on the VR display. */ + virtual void GetWindowBounds( int32_t *pnX, int32_t *pnY, uint32_t *pnWidth, uint32_t *pnHeight ) = 0; + + /** Gets the viewport in the frame buffer to draw the output of the distortion into */ + virtual void GetEyeOutputViewport( EVREye eEye, uint32_t *pnX, uint32_t *pnY, uint32_t *pnWidth, uint32_t *pnHeight ) = 0; + + /** [D3D10/11 Only] + * Returns the adapter index and output index that the user should pass into EnumAdapters and EnumOutputs + * to create the device and swap chain in DX10 and DX11. If an error occurs both indices will be set to -1. + */ + virtual void GetDXGIOutputInfo( int32_t *pnAdapterIndex, int32_t *pnAdapterOutputIndex ) = 0; + + }; + + static const char * const IVRExtendedDisplay_Version = "IVRExtendedDisplay_001"; + +} + + +// ivrtrackedcamera.h +namespace vr +{ + +class IVRTrackedCamera +{ +public: + /** Returns a string for an error */ + virtual const char *GetCameraErrorNameFromEnum( vr::EVRTrackedCameraError eCameraError ) = 0; + + /** For convenience, same as tracked property request Prop_HasCamera_Bool */ + virtual vr::EVRTrackedCameraError HasCamera( vr::TrackedDeviceIndex_t nDeviceIndex, bool *pHasCamera ) = 0; + + /** Gets size of the image frame. */ + virtual vr::EVRTrackedCameraError GetCameraFrameSize( vr::TrackedDeviceIndex_t nDeviceIndex, vr::EVRTrackedCameraFrameType eFrameType, uint32_t *pnWidth, uint32_t *pnHeight, uint32_t *pnFrameBufferSize ) = 0; + + virtual vr::EVRTrackedCameraError GetCameraIntrinisics( vr::TrackedDeviceIndex_t nDeviceIndex, vr::EVRTrackedCameraFrameType eFrameType, vr::HmdVector2_t *pFocalLength, vr::HmdVector2_t *pCenter ) = 0; + + virtual vr::EVRTrackedCameraError GetCameraProjection( vr::TrackedDeviceIndex_t nDeviceIndex, vr::EVRTrackedCameraFrameType eFrameType, float flZNear, float flZFar, vr::HmdMatrix44_t *pProjection ) = 0; + + /** Acquiring streaming service permits video streaming for the caller. Releasing hints the system that video services do not need to be maintained for this client. + * If the camera has not already been activated, a one time spin up may incur some auto exposure as well as initial streaming frame delays. + * The camera should be considered a global resource accessible for shared consumption but not exclusive to any caller. + * The camera may go inactive due to lack of active consumers or headset idleness. */ + virtual vr::EVRTrackedCameraError AcquireVideoStreamingService( vr::TrackedDeviceIndex_t nDeviceIndex, vr::TrackedCameraHandle_t *pHandle ) = 0; + virtual vr::EVRTrackedCameraError ReleaseVideoStreamingService( vr::TrackedCameraHandle_t hTrackedCamera ) = 0; + + /** Copies the image frame into a caller's provided buffer. The image data is currently provided as RGBA data, 4 bytes per pixel. + * A caller can provide null for the framebuffer or frameheader if not desired. Requesting the frame header first, followed by the frame buffer allows + * the caller to determine if the frame as advanced per the frame header sequence. + * If there is no frame available yet, due to initial camera spinup or re-activation, the error will be VRTrackedCameraError_NoFrameAvailable. + * Ideally a caller should be polling at ~16ms intervals */ + virtual vr::EVRTrackedCameraError GetVideoStreamFrameBuffer( vr::TrackedCameraHandle_t hTrackedCamera, vr::EVRTrackedCameraFrameType eFrameType, void *pFrameBuffer, uint32_t nFrameBufferSize, vr::CameraVideoStreamFrameHeader_t *pFrameHeader, uint32_t nFrameHeaderSize ) = 0; +}; + +static const char * const IVRTrackedCamera_Version = "IVRTrackedCamera_003"; + +} // namespace vr + + +// ivrscreenshots.h +namespace vr +{ + +/** Errors that can occur with the VR compositor */ +enum EVRScreenshotError +{ + VRScreenshotError_None = 0, + VRScreenshotError_RequestFailed = 1, + VRScreenshotError_IncompatibleVersion = 100, + VRScreenshotError_NotFound = 101, + VRScreenshotError_BufferTooSmall = 102, + VRScreenshotError_ScreenshotAlreadyInProgress = 108, +}; + +/** Allows the application to generate screenshots */ +class IVRScreenshots +{ +public: + /** Request a screenshot of the requested type. + * A request of the VRScreenshotType_Stereo type will always + * work. Other types will depend on the underlying application + * support. + * The first file name is for the preview image and should be a + * regular screenshot (ideally from the left eye). The second + * is the VR screenshot in the correct format. They should be + * in the same aspect ratio. Formats per type: + * VRScreenshotType_Mono: the VR filename is ignored (can be + * nullptr), this is a normal flat single shot. + * VRScreenshotType_Stereo: The VR image should be a + * side-by-side with the left eye image on the left. + * VRScreenshotType_Cubemap: The VR image should be six square + * images composited horizontally. + * VRScreenshotType_StereoPanorama: above/below with left eye + * panorama being the above image. Image is typically square + * with the panorama being 2x horizontal. + * + * Note that the VR dashboard will call this function when + * the user presses the screenshot binding (currently System + * Button + Trigger). If Steam is running, the destination + * file names will be in %TEMP% and will be copied into + * Steam's screenshot library for the running application + * once SubmitScreenshot() is called. + * If Steam is not running, the paths will be in the user's + * documents folder under Documents\SteamVR\Screenshots. + * Other VR applications can call this to initate a + * screenshot outside of user control. + * The destination file names do not need an extension, + * will be replaced with the correct one for the format + * which is currently .png. */ + virtual vr::EVRScreenshotError RequestScreenshot( vr::ScreenshotHandle_t *pOutScreenshotHandle, vr::EVRScreenshotType type, const char *pchPreviewFilename, const char *pchVRFilename ) = 0; + + /** Called by the running VR application to indicate that it + * wishes to be in charge of screenshots. If the + * application does not call this, the Compositor will only + * support VRScreenshotType_Stereo screenshots that will be + * captured without notification to the running app. + * Once hooked your application will receive a + * VREvent_RequestScreenshot event when the user presses the + * buttons to take a screenshot. */ + virtual vr::EVRScreenshotError HookScreenshot( VR_ARRAY_COUNT( numTypes ) const vr::EVRScreenshotType *pSupportedTypes, int numTypes ) = 0; + + /** When your application receives a + * VREvent_RequestScreenshot event, call these functions to get + * the details of the screenshot request. */ + virtual vr::EVRScreenshotType GetScreenshotPropertyType( vr::ScreenshotHandle_t screenshotHandle, vr::EVRScreenshotError *pError ) = 0; + + /** Get the filename for the preview or vr image (see + * vr::EScreenshotPropertyFilenames). The return value is + * the size of the string. */ + virtual uint32_t GetScreenshotPropertyFilename( vr::ScreenshotHandle_t screenshotHandle, vr::EVRScreenshotPropertyFilenames filenameType, VR_OUT_STRING() char *pchFilename, uint32_t cchFilename, vr::EVRScreenshotError *pError ) = 0; + + /** Call this if the application is taking the screen shot + * will take more than a few ms processing. This will result + * in an overlay being presented that shows a completion + * bar. */ + virtual vr::EVRScreenshotError UpdateScreenshotProgress( vr::ScreenshotHandle_t screenshotHandle, float flProgress ) = 0; + + /** Tells the compositor to take an internal screenshot of + * type VRScreenshotType_Stereo. It will take the current + * submitted scene textures of the running application and + * write them into the preview image and a side-by-side file + * for the VR image. + * This is similiar to request screenshot, but doesn't ever + * talk to the application, just takes the shot and submits. */ + virtual vr::EVRScreenshotError TakeStereoScreenshot( vr::ScreenshotHandle_t *pOutScreenshotHandle, const char *pchPreviewFilename, const char *pchVRFilename ) = 0; + + /** Submit the completed screenshot. If Steam is running + * this will call into the Steam client and upload the + * screenshot to the screenshots section of the library for + * the running application. If Steam is not running, this + * function will display a notification to the user that the + * screenshot was taken. The paths should be full paths with + * extensions. + * File paths should be absolute including + * exntensions. + * screenshotHandle can be k_unScreenshotHandleInvalid if this + * was a new shot taking by the app to be saved and not + * initiated by a user (achievement earned or something) */ + virtual vr::EVRScreenshotError SubmitScreenshot( vr::ScreenshotHandle_t screenshotHandle, vr::EVRScreenshotType type, const char *pchSourcePreviewFilename, const char *pchSourceVRFilename ) = 0; +}; + +static const char * const IVRScreenshots_Version = "IVRScreenshots_001"; + +} // namespace vr + + +// End + +#endif // _OPENVR_API + + +namespace vr +{ + /** Finds the active installation of the VR API and initializes it. The provided path must be absolute + * or relative to the current working directory. These are the local install versions of the equivalent + * functions in steamvr.h and will work without a local Steam install. + * + * This path is to the "root" of the VR API install. That's the directory with + * the "drivers" directory and a platform (i.e. "win32") directory in it, not the directory with the DLL itself. + */ + inline IVRSystem *VR_Init( EVRInitError *peError, EVRApplicationType eApplicationType ); + + /** unloads vrclient.dll. Any interface pointers from the interface are + * invalid after this point */ + inline void VR_Shutdown(); + + /** Returns true if there is an HMD attached. This check is as lightweight as possible and + * can be called outside of VR_Init/VR_Shutdown. It should be used when an application wants + * to know if initializing VR is a possibility but isn't ready to take that step yet. + */ + VR_INTERFACE bool VR_CALLTYPE VR_IsHmdPresent(); + + /** Returns true if the OpenVR runtime is installed. */ + VR_INTERFACE bool VR_CALLTYPE VR_IsRuntimeInstalled(); + + /** Returns where the OpenVR runtime is installed. */ + VR_INTERFACE const char *VR_CALLTYPE VR_RuntimePath(); + + /** Returns the name of the enum value for an EVRInitError. This function may be called outside of VR_Init()/VR_Shutdown(). */ + VR_INTERFACE const char *VR_CALLTYPE VR_GetVRInitErrorAsSymbol( EVRInitError error ); + + /** Returns an english string for an EVRInitError. Applications should call VR_GetVRInitErrorAsSymbol instead and + * use that as a key to look up their own localized error message. This function may be called outside of VR_Init()/VR_Shutdown(). */ + VR_INTERFACE const char *VR_CALLTYPE VR_GetVRInitErrorAsEnglishDescription( EVRInitError error ); + + /** Returns the interface of the specified version. This method must be called after VR_Init. The + * pointer returned is valid until VR_Shutdown is called. + */ + VR_INTERFACE void *VR_CALLTYPE VR_GetGenericInterface( const char *pchInterfaceVersion, EVRInitError *peError ); + + /** Returns whether the interface of the specified version exists. + */ + VR_INTERFACE bool VR_CALLTYPE VR_IsInterfaceVersionValid( const char *pchInterfaceVersion ); + + /** Returns a token that represents whether the VR interface handles need to be reloaded */ + VR_INTERFACE uint32_t VR_CALLTYPE VR_GetInitToken(); + + // These typedefs allow old enum names from SDK 0.9.11 to be used in applications. + // They will go away in the future. + typedef EVRInitError HmdError; + typedef EVREye Hmd_Eye; + typedef EGraphicsAPIConvention GraphicsAPIConvention; + typedef EColorSpace ColorSpace; + typedef ETrackingResult HmdTrackingResult; + typedef ETrackedDeviceClass TrackedDeviceClass; + typedef ETrackingUniverseOrigin TrackingUniverseOrigin; + typedef ETrackedDeviceProperty TrackedDeviceProperty; + typedef ETrackedPropertyError TrackedPropertyError; + typedef EVRSubmitFlags VRSubmitFlags_t; + typedef EVRState VRState_t; + typedef ECollisionBoundsStyle CollisionBoundsStyle_t; + typedef EVROverlayError VROverlayError; + typedef EVRFirmwareError VRFirmwareError; + typedef EVRCompositorError VRCompositorError; + typedef EVRScreenshotError VRScreenshotsError; + + inline uint32_t &VRToken() + { + static uint32_t token; + return token; + } + + class COpenVRContext + { + public: + COpenVRContext() { Clear(); } + void Clear(); + + inline void CheckClear() + { + if ( VRToken() != VR_GetInitToken() ) + { + Clear(); + VRToken() = VR_GetInitToken(); + } + } + + IVRSystem *VRSystem() + { + CheckClear(); + if ( m_pVRSystem == nullptr ) + { + EVRInitError eError; + m_pVRSystem = ( IVRSystem * )VR_GetGenericInterface( IVRSystem_Version, &eError ); + } + return m_pVRSystem; + } + IVRChaperone *VRChaperone() + { + CheckClear(); + if ( m_pVRChaperone == nullptr ) + { + EVRInitError eError; + m_pVRChaperone = ( IVRChaperone * )VR_GetGenericInterface( IVRChaperone_Version, &eError ); + } + return m_pVRChaperone; + } + + IVRChaperoneSetup *VRChaperoneSetup() + { + CheckClear(); + if ( m_pVRChaperoneSetup == nullptr ) + { + EVRInitError eError; + m_pVRChaperoneSetup = ( IVRChaperoneSetup * )VR_GetGenericInterface( IVRChaperoneSetup_Version, &eError ); + } + return m_pVRChaperoneSetup; + } + + IVRCompositor *VRCompositor() + { + CheckClear(); + if ( m_pVRCompositor == nullptr ) + { + EVRInitError eError; + m_pVRCompositor = ( IVRCompositor * )VR_GetGenericInterface( IVRCompositor_Version, &eError ); + } + return m_pVRCompositor; + } + + IVROverlay *VROverlay() + { + CheckClear(); + if ( m_pVROverlay == nullptr ) + { + EVRInitError eError; + m_pVROverlay = ( IVROverlay * )VR_GetGenericInterface( IVROverlay_Version, &eError ); + } + return m_pVROverlay; + } + + IVRScreenshots *VRScreenshots() + { + CheckClear(); + if ( m_pVRScreenshots == nullptr ) + { + EVRInitError eError; + m_pVRScreenshots = ( IVRScreenshots * )VR_GetGenericInterface( IVRScreenshots_Version, &eError ); + } + return m_pVRScreenshots; + } + + IVRRenderModels *VRRenderModels() + { + CheckClear(); + if ( m_pVRRenderModels == nullptr ) + { + EVRInitError eError; + m_pVRRenderModels = ( IVRRenderModels * )VR_GetGenericInterface( IVRRenderModels_Version, &eError ); + } + return m_pVRRenderModels; + } + + IVRExtendedDisplay *VRExtendedDisplay() + { + CheckClear(); + if ( m_pVRExtendedDisplay == nullptr ) + { + EVRInitError eError; + m_pVRExtendedDisplay = ( IVRExtendedDisplay * )VR_GetGenericInterface( IVRExtendedDisplay_Version, &eError ); + } + return m_pVRExtendedDisplay; + } + + IVRSettings *VRSettings() + { + CheckClear(); + if ( m_pVRSettings == nullptr ) + { + EVRInitError eError; + m_pVRSettings = ( IVRSettings * )VR_GetGenericInterface( IVRSettings_Version, &eError ); + } + return m_pVRSettings; + } + + IVRApplications *VRApplications() + { + CheckClear(); + if ( m_pVRApplications == nullptr ) + { + EVRInitError eError; + m_pVRApplications = ( IVRApplications * )VR_GetGenericInterface( IVRApplications_Version, &eError ); + } + return m_pVRApplications; + } + + IVRTrackedCamera *VRTrackedCamera() + { + CheckClear(); + if ( m_pVRTrackedCamera == nullptr ) + { + EVRInitError eError; + m_pVRTrackedCamera = ( IVRTrackedCamera * )VR_GetGenericInterface( IVRTrackedCamera_Version, &eError ); + } + return m_pVRTrackedCamera; + } + + private: + IVRSystem *m_pVRSystem; + IVRChaperone *m_pVRChaperone; + IVRChaperoneSetup *m_pVRChaperoneSetup; + IVRCompositor *m_pVRCompositor; + IVROverlay *m_pVROverlay; + IVRRenderModels *m_pVRRenderModels; + IVRExtendedDisplay *m_pVRExtendedDisplay; + IVRSettings *m_pVRSettings; + IVRApplications *m_pVRApplications; + IVRTrackedCamera *m_pVRTrackedCamera; + IVRScreenshots *m_pVRScreenshots; + }; + + inline COpenVRContext &OpenVRInternal_ModuleContext() + { + static void *ctx[ sizeof( COpenVRContext ) / sizeof( void * ) ]; + return *( COpenVRContext * )ctx; // bypass zero-init constructor + } + + inline IVRSystem *VR_CALLTYPE VRSystem() { return OpenVRInternal_ModuleContext().VRSystem(); } + inline IVRChaperone *VR_CALLTYPE VRChaperone() { return OpenVRInternal_ModuleContext().VRChaperone(); } + inline IVRChaperoneSetup *VR_CALLTYPE VRChaperoneSetup() { return OpenVRInternal_ModuleContext().VRChaperoneSetup(); } + inline IVRCompositor *VR_CALLTYPE VRCompositor() { return OpenVRInternal_ModuleContext().VRCompositor(); } + inline IVROverlay *VR_CALLTYPE VROverlay() { return OpenVRInternal_ModuleContext().VROverlay(); } + inline IVRScreenshots *VR_CALLTYPE VRScreenshots() { return OpenVRInternal_ModuleContext().VRScreenshots(); } + inline IVRRenderModels *VR_CALLTYPE VRRenderModels() { return OpenVRInternal_ModuleContext().VRRenderModels(); } + inline IVRApplications *VR_CALLTYPE VRApplications() { return OpenVRInternal_ModuleContext().VRApplications(); } + inline IVRSettings *VR_CALLTYPE VRSettings() { return OpenVRInternal_ModuleContext().VRSettings(); } + inline IVRExtendedDisplay *VR_CALLTYPE VRExtendedDisplay() { return OpenVRInternal_ModuleContext().VRExtendedDisplay(); } + inline IVRTrackedCamera *VR_CALLTYPE VRTrackedCamera() { return OpenVRInternal_ModuleContext().VRTrackedCamera(); } + + inline void COpenVRContext::Clear() + { + m_pVRSystem = nullptr; + m_pVRChaperone = nullptr; + m_pVRChaperoneSetup = nullptr; + m_pVRCompositor = nullptr; + m_pVROverlay = nullptr; + m_pVRRenderModels = nullptr; + m_pVRExtendedDisplay = nullptr; + m_pVRSettings = nullptr; + m_pVRApplications = nullptr; + m_pVRTrackedCamera = nullptr; + m_pVRScreenshots = nullptr; + } + + VR_INTERFACE uint32_t VR_CALLTYPE VR_InitInternal( EVRInitError *peError, EVRApplicationType eApplicationType ); + VR_INTERFACE void VR_CALLTYPE VR_ShutdownInternal(); + + /** Finds the active installation of vrclient.dll and initializes it */ + inline IVRSystem *VR_Init( EVRInitError *peError, EVRApplicationType eApplicationType ) + { + IVRSystem *pVRSystem = nullptr; + + EVRInitError eError; + VRToken() = VR_InitInternal( &eError, eApplicationType ); + COpenVRContext &ctx = OpenVRInternal_ModuleContext(); + ctx.Clear(); + + if ( eError == VRInitError_None ) + { + if ( VR_IsInterfaceVersionValid( IVRSystem_Version ) ) + { + pVRSystem = VRSystem(); + } + else + { + VR_ShutdownInternal(); + eError = VRInitError_Init_InterfaceNotFound; + } + } + + if ( peError ) + *peError = eError; + return pVRSystem; + } + + /** unloads vrclient.dll. Any interface pointers from the interface are + * invalid after this point */ + inline void VR_Shutdown() + { + VR_ShutdownInternal(); + } +} diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr_api.cs b/examples/ThirdPartyLibs/openvr/headers/openvr_api.cs new file mode 100644 index 000000000..a4d71f826 --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/headers/openvr_api.cs @@ -0,0 +1,4187 @@ +//======= Copyright (c) Valve Corporation, All rights reserved. =============== +// +// Purpose: This file contains C#/managed code bindings for the OpenVR interfaces +// This file is auto-generated, do not edit it. +// +//============================================================================= + +using System; +using System.Runtime.InteropServices; +using Valve.VR; + +namespace Valve.VR +{ + +[StructLayout(LayoutKind.Sequential)] +public struct IVRSystem +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _GetRecommendedRenderTargetSize(ref uint pnWidth, ref uint pnHeight); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetRecommendedRenderTargetSize GetRecommendedRenderTargetSize; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate HmdMatrix44_t _GetProjectionMatrix(EVREye eEye, float fNearZ, float fFarZ, EGraphicsAPIConvention eProjType); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetProjectionMatrix GetProjectionMatrix; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _GetProjectionRaw(EVREye eEye, ref float pfLeft, ref float pfRight, ref float pfTop, ref float pfBottom); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetProjectionRaw GetProjectionRaw; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate DistortionCoordinates_t _ComputeDistortion(EVREye eEye, float fU, float fV); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ComputeDistortion ComputeDistortion; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate HmdMatrix34_t _GetEyeToHeadTransform(EVREye eEye); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetEyeToHeadTransform GetEyeToHeadTransform; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetTimeSinceLastVsync(ref float pfSecondsSinceLastVsync, ref ulong pulFrameCounter); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetTimeSinceLastVsync GetTimeSinceLastVsync; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate int _GetD3D9AdapterIndex(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetD3D9AdapterIndex GetD3D9AdapterIndex; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _GetDXGIOutputInfo(ref int pnAdapterIndex); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetDXGIOutputInfo GetDXGIOutputInfo; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _IsDisplayOnDesktop(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IsDisplayOnDesktop IsDisplayOnDesktop; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _SetDisplayVisibility(bool bIsVisibleOnDesktop); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetDisplayVisibility SetDisplayVisibility; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _GetDeviceToAbsoluteTrackingPose(ETrackingUniverseOrigin eOrigin, float fPredictedSecondsToPhotonsFromNow, [In, Out] TrackedDevicePose_t[] pTrackedDevicePoseArray, uint unTrackedDevicePoseArrayCount); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetDeviceToAbsoluteTrackingPose GetDeviceToAbsoluteTrackingPose; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ResetSeatedZeroPose(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ResetSeatedZeroPose ResetSeatedZeroPose; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate HmdMatrix34_t _GetSeatedZeroPoseToStandingAbsoluteTrackingPose(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetSeatedZeroPoseToStandingAbsoluteTrackingPose GetSeatedZeroPoseToStandingAbsoluteTrackingPose; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate HmdMatrix34_t _GetRawZeroPoseToStandingAbsoluteTrackingPose(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetRawZeroPoseToStandingAbsoluteTrackingPose GetRawZeroPoseToStandingAbsoluteTrackingPose; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetSortedTrackedDeviceIndicesOfClass(ETrackedDeviceClass eTrackedDeviceClass, [In, Out] uint[] punTrackedDeviceIndexArray, uint unTrackedDeviceIndexArrayCount, uint unRelativeToTrackedDeviceIndex); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetSortedTrackedDeviceIndicesOfClass GetSortedTrackedDeviceIndicesOfClass; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EDeviceActivityLevel _GetTrackedDeviceActivityLevel(uint unDeviceId); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetTrackedDeviceActivityLevel GetTrackedDeviceActivityLevel; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ApplyTransform(ref TrackedDevicePose_t pOutputPose, ref TrackedDevicePose_t pTrackedDevicePose, ref HmdMatrix34_t pTransform); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ApplyTransform ApplyTransform; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetTrackedDeviceIndexForControllerRole(ETrackedControllerRole unDeviceType); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetTrackedDeviceIndexForControllerRole GetTrackedDeviceIndexForControllerRole; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate ETrackedControllerRole _GetControllerRoleForTrackedDeviceIndex(uint unDeviceIndex); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetControllerRoleForTrackedDeviceIndex GetControllerRoleForTrackedDeviceIndex; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate ETrackedDeviceClass _GetTrackedDeviceClass(uint unDeviceIndex); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetTrackedDeviceClass GetTrackedDeviceClass; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _IsTrackedDeviceConnected(uint unDeviceIndex); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IsTrackedDeviceConnected IsTrackedDeviceConnected; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetBoolTrackedDeviceProperty(uint unDeviceIndex, ETrackedDeviceProperty prop, ref ETrackedPropertyError pError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetBoolTrackedDeviceProperty GetBoolTrackedDeviceProperty; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate float _GetFloatTrackedDeviceProperty(uint unDeviceIndex, ETrackedDeviceProperty prop, ref ETrackedPropertyError pError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetFloatTrackedDeviceProperty GetFloatTrackedDeviceProperty; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate int _GetInt32TrackedDeviceProperty(uint unDeviceIndex, ETrackedDeviceProperty prop, ref ETrackedPropertyError pError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetInt32TrackedDeviceProperty GetInt32TrackedDeviceProperty; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate ulong _GetUint64TrackedDeviceProperty(uint unDeviceIndex, ETrackedDeviceProperty prop, ref ETrackedPropertyError pError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetUint64TrackedDeviceProperty GetUint64TrackedDeviceProperty; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate HmdMatrix34_t _GetMatrix34TrackedDeviceProperty(uint unDeviceIndex, ETrackedDeviceProperty prop, ref ETrackedPropertyError pError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetMatrix34TrackedDeviceProperty GetMatrix34TrackedDeviceProperty; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetStringTrackedDeviceProperty(uint unDeviceIndex, ETrackedDeviceProperty prop, System.Text.StringBuilder pchValue, uint unBufferSize, ref ETrackedPropertyError pError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetStringTrackedDeviceProperty GetStringTrackedDeviceProperty; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate IntPtr _GetPropErrorNameFromEnum(ETrackedPropertyError error); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetPropErrorNameFromEnum GetPropErrorNameFromEnum; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _PollNextEvent(ref VREvent_t pEvent, uint uncbVREvent); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _PollNextEvent PollNextEvent; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _PollNextEventWithPose(ETrackingUniverseOrigin eOrigin, ref VREvent_t pEvent, uint uncbVREvent, ref TrackedDevicePose_t pTrackedDevicePose); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _PollNextEventWithPose PollNextEventWithPose; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate IntPtr _GetEventTypeNameFromEnum(EVREventType eType); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetEventTypeNameFromEnum GetEventTypeNameFromEnum; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate HiddenAreaMesh_t _GetHiddenAreaMesh(EVREye eEye); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetHiddenAreaMesh GetHiddenAreaMesh; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetControllerState(uint unControllerDeviceIndex, ref VRControllerState_t pControllerState); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetControllerState GetControllerState; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetControllerStateWithPose(ETrackingUniverseOrigin eOrigin, uint unControllerDeviceIndex, ref VRControllerState_t pControllerState, ref TrackedDevicePose_t pTrackedDevicePose); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetControllerStateWithPose GetControllerStateWithPose; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _TriggerHapticPulse(uint unControllerDeviceIndex, uint unAxisId, char usDurationMicroSec); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _TriggerHapticPulse TriggerHapticPulse; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate IntPtr _GetButtonIdNameFromEnum(EVRButtonId eButtonId); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetButtonIdNameFromEnum GetButtonIdNameFromEnum; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate IntPtr _GetControllerAxisTypeNameFromEnum(EVRControllerAxisType eAxisType); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetControllerAxisTypeNameFromEnum GetControllerAxisTypeNameFromEnum; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _CaptureInputFocus(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _CaptureInputFocus CaptureInputFocus; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ReleaseInputFocus(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ReleaseInputFocus ReleaseInputFocus; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _IsInputFocusCapturedByAnotherProcess(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IsInputFocusCapturedByAnotherProcess IsInputFocusCapturedByAnotherProcess; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _DriverDebugRequest(uint unDeviceIndex, string pchRequest, string pchResponseBuffer, uint unResponseBufferSize); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _DriverDebugRequest DriverDebugRequest; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRFirmwareError _PerformFirmwareUpdate(uint unDeviceIndex); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _PerformFirmwareUpdate PerformFirmwareUpdate; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _AcknowledgeQuit_Exiting(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _AcknowledgeQuit_Exiting AcknowledgeQuit_Exiting; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _AcknowledgeQuit_UserPrompt(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _AcknowledgeQuit_UserPrompt AcknowledgeQuit_UserPrompt; + +} + +[StructLayout(LayoutKind.Sequential)] +public struct IVRExtendedDisplay +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _GetWindowBounds(ref int pnX, ref int pnY, ref uint pnWidth, ref uint pnHeight); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetWindowBounds GetWindowBounds; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _GetEyeOutputViewport(EVREye eEye, ref uint pnX, ref uint pnY, ref uint pnWidth, ref uint pnHeight); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetEyeOutputViewport GetEyeOutputViewport; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _GetDXGIOutputInfo(ref int pnAdapterIndex, ref int pnAdapterOutputIndex); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetDXGIOutputInfo GetDXGIOutputInfo; + +} + +[StructLayout(LayoutKind.Sequential)] +public struct IVRTrackedCamera +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate IntPtr _GetCameraErrorNameFromEnum(EVRTrackedCameraError eCameraError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetCameraErrorNameFromEnum GetCameraErrorNameFromEnum; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRTrackedCameraError _HasCamera(uint nDeviceIndex, ref bool pHasCamera); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _HasCamera HasCamera; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRTrackedCameraError _GetCameraFrameSize(uint nDeviceIndex, EVRTrackedCameraFrameType eFrameType, ref uint pnWidth, ref uint pnHeight, ref uint pnFrameBufferSize); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetCameraFrameSize GetCameraFrameSize; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRTrackedCameraError _GetCameraIntrinisics(uint nDeviceIndex, EVRTrackedCameraFrameType eFrameType, ref HmdVector2_t pFocalLength, ref HmdVector2_t pCenter); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetCameraIntrinisics GetCameraIntrinisics; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRTrackedCameraError _GetCameraProjection(uint nDeviceIndex, EVRTrackedCameraFrameType eFrameType, float flZNear, float flZFar, ref HmdMatrix44_t pProjection); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetCameraProjection GetCameraProjection; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRTrackedCameraError _AcquireVideoStreamingService(uint nDeviceIndex, ref ulong pHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _AcquireVideoStreamingService AcquireVideoStreamingService; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRTrackedCameraError _ReleaseVideoStreamingService(ulong hTrackedCamera); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ReleaseVideoStreamingService ReleaseVideoStreamingService; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRTrackedCameraError _GetVideoStreamFrameBuffer(ulong hTrackedCamera, EVRTrackedCameraFrameType eFrameType, IntPtr pFrameBuffer, uint nFrameBufferSize, ref CameraVideoStreamFrameHeader_t pFrameHeader, uint nFrameHeaderSize); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetVideoStreamFrameBuffer GetVideoStreamFrameBuffer; + +} + +[StructLayout(LayoutKind.Sequential)] +public struct IVRApplications +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _AddApplicationManifest(string pchApplicationManifestFullPath, bool bTemporary); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _AddApplicationManifest AddApplicationManifest; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _RemoveApplicationManifest(string pchApplicationManifestFullPath); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _RemoveApplicationManifest RemoveApplicationManifest; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _IsApplicationInstalled(string pchAppKey); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IsApplicationInstalled IsApplicationInstalled; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetApplicationCount(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetApplicationCount GetApplicationCount; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _GetApplicationKeyByIndex(uint unApplicationIndex, string pchAppKeyBuffer, uint unAppKeyBufferLen); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetApplicationKeyByIndex GetApplicationKeyByIndex; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _GetApplicationKeyByProcessId(uint unProcessId, string pchAppKeyBuffer, uint unAppKeyBufferLen); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetApplicationKeyByProcessId GetApplicationKeyByProcessId; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _LaunchApplication(string pchAppKey); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _LaunchApplication LaunchApplication; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _LaunchTemplateApplication(string pchTemplateAppKey, string pchNewAppKey, [In, Out] AppOverrideKeys_t[] pKeys, uint unKeys); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _LaunchTemplateApplication LaunchTemplateApplication; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _LaunchDashboardOverlay(string pchAppKey); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _LaunchDashboardOverlay LaunchDashboardOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _CancelApplicationLaunch(string pchAppKey); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _CancelApplicationLaunch CancelApplicationLaunch; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _IdentifyApplication(uint unProcessId, string pchAppKey); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IdentifyApplication IdentifyApplication; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetApplicationProcessId(string pchAppKey); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetApplicationProcessId GetApplicationProcessId; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate IntPtr _GetApplicationsErrorNameFromEnum(EVRApplicationError error); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetApplicationsErrorNameFromEnum GetApplicationsErrorNameFromEnum; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetApplicationPropertyString(string pchAppKey, EVRApplicationProperty eProperty, string pchPropertyValueBuffer, uint unPropertyValueBufferLen, ref EVRApplicationError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetApplicationPropertyString GetApplicationPropertyString; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetApplicationPropertyBool(string pchAppKey, EVRApplicationProperty eProperty, ref EVRApplicationError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetApplicationPropertyBool GetApplicationPropertyBool; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate ulong _GetApplicationPropertyUint64(string pchAppKey, EVRApplicationProperty eProperty, ref EVRApplicationError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetApplicationPropertyUint64 GetApplicationPropertyUint64; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _SetApplicationAutoLaunch(string pchAppKey, bool bAutoLaunch); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetApplicationAutoLaunch SetApplicationAutoLaunch; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetApplicationAutoLaunch(string pchAppKey); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetApplicationAutoLaunch GetApplicationAutoLaunch; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _GetStartingApplication(string pchAppKeyBuffer, uint unAppKeyBufferLen); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetStartingApplication GetStartingApplication; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationTransitionState _GetTransitionState(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetTransitionState GetTransitionState; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _PerformApplicationPrelaunchCheck(string pchAppKey); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _PerformApplicationPrelaunchCheck PerformApplicationPrelaunchCheck; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate IntPtr _GetApplicationsTransitionStateNameFromEnum(EVRApplicationTransitionState state); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetApplicationsTransitionStateNameFromEnum GetApplicationsTransitionStateNameFromEnum; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _IsQuitUserPromptRequested(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IsQuitUserPromptRequested IsQuitUserPromptRequested; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRApplicationError _LaunchInternalProcess(string pchBinaryPath, string pchArguments, string pchWorkingDirectory); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _LaunchInternalProcess LaunchInternalProcess; + +} + +[StructLayout(LayoutKind.Sequential)] +public struct IVRChaperone +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate ChaperoneCalibrationState _GetCalibrationState(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetCalibrationState GetCalibrationState; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetPlayAreaSize(ref float pSizeX, ref float pSizeZ); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetPlayAreaSize GetPlayAreaSize; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetPlayAreaRect(ref HmdQuad_t rect); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetPlayAreaRect GetPlayAreaRect; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ReloadInfo(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ReloadInfo ReloadInfo; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetSceneColor(HmdColor_t color); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetSceneColor SetSceneColor; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _GetBoundsColor(ref HmdColor_t pOutputColorArray, int nNumOutputColors, float flCollisionBoundsFadeDistance, ref HmdColor_t pOutputCameraColor); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetBoundsColor GetBoundsColor; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _AreBoundsVisible(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _AreBoundsVisible AreBoundsVisible; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ForceBoundsVisible(bool bForce); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ForceBoundsVisible ForceBoundsVisible; + +} + +[StructLayout(LayoutKind.Sequential)] +public struct IVRChaperoneSetup +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _CommitWorkingCopy(EChaperoneConfigFile configFile); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _CommitWorkingCopy CommitWorkingCopy; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _RevertWorkingCopy(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _RevertWorkingCopy RevertWorkingCopy; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetWorkingPlayAreaSize(ref float pSizeX, ref float pSizeZ); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetWorkingPlayAreaSize GetWorkingPlayAreaSize; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetWorkingPlayAreaRect(ref HmdQuad_t rect); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetWorkingPlayAreaRect GetWorkingPlayAreaRect; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetWorkingCollisionBoundsInfo([In, Out] HmdQuad_t[] pQuadsBuffer, ref uint punQuadsCount); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetWorkingCollisionBoundsInfo GetWorkingCollisionBoundsInfo; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetLiveCollisionBoundsInfo([In, Out] HmdQuad_t[] pQuadsBuffer, ref uint punQuadsCount); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetLiveCollisionBoundsInfo GetLiveCollisionBoundsInfo; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetWorkingSeatedZeroPoseToRawTrackingPose(ref HmdMatrix34_t pmatSeatedZeroPoseToRawTrackingPose); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetWorkingSeatedZeroPoseToRawTrackingPose GetWorkingSeatedZeroPoseToRawTrackingPose; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetWorkingStandingZeroPoseToRawTrackingPose(ref HmdMatrix34_t pmatStandingZeroPoseToRawTrackingPose); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetWorkingStandingZeroPoseToRawTrackingPose GetWorkingStandingZeroPoseToRawTrackingPose; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetWorkingPlayAreaSize(float sizeX, float sizeZ); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetWorkingPlayAreaSize SetWorkingPlayAreaSize; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetWorkingCollisionBoundsInfo([In, Out] HmdQuad_t[] pQuadsBuffer, uint unQuadsCount); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetWorkingCollisionBoundsInfo SetWorkingCollisionBoundsInfo; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetWorkingSeatedZeroPoseToRawTrackingPose(ref HmdMatrix34_t pMatSeatedZeroPoseToRawTrackingPose); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetWorkingSeatedZeroPoseToRawTrackingPose SetWorkingSeatedZeroPoseToRawTrackingPose; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetWorkingStandingZeroPoseToRawTrackingPose(ref HmdMatrix34_t pMatStandingZeroPoseToRawTrackingPose); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetWorkingStandingZeroPoseToRawTrackingPose SetWorkingStandingZeroPoseToRawTrackingPose; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ReloadFromDisk(EChaperoneConfigFile configFile); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ReloadFromDisk ReloadFromDisk; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetLiveSeatedZeroPoseToRawTrackingPose(ref HmdMatrix34_t pmatSeatedZeroPoseToRawTrackingPose); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetLiveSeatedZeroPoseToRawTrackingPose GetLiveSeatedZeroPoseToRawTrackingPose; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetWorkingCollisionBoundsTagsInfo([In, Out] byte[] pTagsBuffer, uint unTagCount); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetWorkingCollisionBoundsTagsInfo SetWorkingCollisionBoundsTagsInfo; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetLiveCollisionBoundsTagsInfo([In, Out] byte[] pTagsBuffer, ref uint punTagCount); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetLiveCollisionBoundsTagsInfo GetLiveCollisionBoundsTagsInfo; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _SetWorkingPhysicalBoundsInfo([In, Out] HmdQuad_t[] pQuadsBuffer, uint unQuadsCount); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetWorkingPhysicalBoundsInfo SetWorkingPhysicalBoundsInfo; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetLivePhysicalBoundsInfo([In, Out] HmdQuad_t[] pQuadsBuffer, ref uint punQuadsCount); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetLivePhysicalBoundsInfo GetLivePhysicalBoundsInfo; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _ExportLiveToBuffer(System.Text.StringBuilder pBuffer, ref uint pnBufferLength); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ExportLiveToBuffer ExportLiveToBuffer; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _ImportFromBufferToWorking(string pBuffer, uint nImportFlags); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ImportFromBufferToWorking ImportFromBufferToWorking; + +} + +[StructLayout(LayoutKind.Sequential)] +public struct IVRCompositor +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetTrackingSpace(ETrackingUniverseOrigin eOrigin); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetTrackingSpace SetTrackingSpace; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate ETrackingUniverseOrigin _GetTrackingSpace(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetTrackingSpace GetTrackingSpace; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRCompositorError _WaitGetPoses([In, Out] TrackedDevicePose_t[] pRenderPoseArray, uint unRenderPoseArrayCount, [In, Out] TrackedDevicePose_t[] pGamePoseArray, uint unGamePoseArrayCount); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _WaitGetPoses WaitGetPoses; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRCompositorError _GetLastPoses([In, Out] TrackedDevicePose_t[] pRenderPoseArray, uint unRenderPoseArrayCount, [In, Out] TrackedDevicePose_t[] pGamePoseArray, uint unGamePoseArrayCount); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetLastPoses GetLastPoses; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRCompositorError _GetLastPoseForTrackedDeviceIndex(uint unDeviceIndex, ref TrackedDevicePose_t pOutputPose, ref TrackedDevicePose_t pOutputGamePose); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetLastPoseForTrackedDeviceIndex GetLastPoseForTrackedDeviceIndex; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRCompositorError _Submit(EVREye eEye, ref Texture_t pTexture, ref VRTextureBounds_t pBounds, EVRSubmitFlags nSubmitFlags); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _Submit Submit; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ClearLastSubmittedFrame(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ClearLastSubmittedFrame ClearLastSubmittedFrame; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _PostPresentHandoff(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _PostPresentHandoff PostPresentHandoff; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetFrameTiming(ref Compositor_FrameTiming pTiming, uint unFramesAgo); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetFrameTiming GetFrameTiming; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate float _GetFrameTimeRemaining(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetFrameTimeRemaining GetFrameTimeRemaining; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _GetCumulativeStats(ref Compositor_CumulativeStats pStats, uint nStatsSizeInBytes); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetCumulativeStats GetCumulativeStats; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _FadeToColor(float fSeconds, float fRed, float fGreen, float fBlue, float fAlpha, bool bBackground); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _FadeToColor FadeToColor; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _FadeGrid(float fSeconds, bool bFadeIn); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _FadeGrid FadeGrid; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRCompositorError _SetSkyboxOverride([In, Out] Texture_t[] pTextures, uint unTextureCount); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetSkyboxOverride SetSkyboxOverride; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ClearSkyboxOverride(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ClearSkyboxOverride ClearSkyboxOverride; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _CompositorBringToFront(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _CompositorBringToFront CompositorBringToFront; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _CompositorGoToBack(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _CompositorGoToBack CompositorGoToBack; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _CompositorQuit(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _CompositorQuit CompositorQuit; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _IsFullscreen(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IsFullscreen IsFullscreen; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetCurrentSceneFocusProcess(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetCurrentSceneFocusProcess GetCurrentSceneFocusProcess; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetLastFrameRenderer(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetLastFrameRenderer GetLastFrameRenderer; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _CanRenderScene(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _CanRenderScene CanRenderScene; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ShowMirrorWindow(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ShowMirrorWindow ShowMirrorWindow; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _HideMirrorWindow(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _HideMirrorWindow HideMirrorWindow; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _IsMirrorWindowVisible(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IsMirrorWindowVisible IsMirrorWindowVisible; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _CompositorDumpImages(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _CompositorDumpImages CompositorDumpImages; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _ShouldAppRenderWithLowResources(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ShouldAppRenderWithLowResources ShouldAppRenderWithLowResources; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ForceInterleavedReprojectionOn(bool bOverride); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ForceInterleavedReprojectionOn ForceInterleavedReprojectionOn; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ForceReconnectProcess(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ForceReconnectProcess ForceReconnectProcess; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SuspendRendering(bool bSuspend); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SuspendRendering SuspendRendering; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRCompositorError _RequestScreenshot(EVRScreenshotType type, string pchDestinationFileName, string pchVRDestinationFileName); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _RequestScreenshot RequestScreenshot; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRScreenshotType _GetCurrentScreenshotType(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetCurrentScreenshotType GetCurrentScreenshotType; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRCompositorError _GetMirrorTextureD3D11(EVREye eEye, IntPtr pD3D11DeviceOrResource, ref IntPtr ppD3D11ShaderResourceView); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetMirrorTextureD3D11 GetMirrorTextureD3D11; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRCompositorError _GetMirrorTextureGL(EVREye eEye, ref uint pglTextureId, IntPtr pglSharedTextureHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetMirrorTextureGL GetMirrorTextureGL; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _ReleaseSharedGLTexture(uint glTextureId, IntPtr glSharedTextureHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ReleaseSharedGLTexture ReleaseSharedGLTexture; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _LockGLSharedTextureForAccess(IntPtr glSharedTextureHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _LockGLSharedTextureForAccess LockGLSharedTextureForAccess; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _UnlockGLSharedTextureForAccess(IntPtr glSharedTextureHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _UnlockGLSharedTextureForAccess UnlockGLSharedTextureForAccess; + +} + +[StructLayout(LayoutKind.Sequential)] +public struct IVROverlay +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _FindOverlay(string pchOverlayKey, ref ulong pOverlayHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _FindOverlay FindOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _CreateOverlay(string pchOverlayKey, string pchOverlayFriendlyName, ref ulong pOverlayHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _CreateOverlay CreateOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _DestroyOverlay(ulong ulOverlayHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _DestroyOverlay DestroyOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetHighQualityOverlay(ulong ulOverlayHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetHighQualityOverlay SetHighQualityOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate ulong _GetHighQualityOverlay(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetHighQualityOverlay GetHighQualityOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetOverlayKey(ulong ulOverlayHandle, System.Text.StringBuilder pchValue, uint unBufferSize, ref EVROverlayError pError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayKey GetOverlayKey; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetOverlayName(ulong ulOverlayHandle, System.Text.StringBuilder pchValue, uint unBufferSize, ref EVROverlayError pError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayName GetOverlayName; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayImageData(ulong ulOverlayHandle, IntPtr pvBuffer, uint unBufferSize, ref uint punWidth, ref uint punHeight); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayImageData GetOverlayImageData; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate IntPtr _GetOverlayErrorNameFromEnum(EVROverlayError error); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayErrorNameFromEnum GetOverlayErrorNameFromEnum; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayRenderingPid(ulong ulOverlayHandle, uint unPID); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayRenderingPid SetOverlayRenderingPid; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetOverlayRenderingPid(ulong ulOverlayHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayRenderingPid GetOverlayRenderingPid; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayFlag(ulong ulOverlayHandle, VROverlayFlags eOverlayFlag, bool bEnabled); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayFlag SetOverlayFlag; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayFlag(ulong ulOverlayHandle, VROverlayFlags eOverlayFlag, ref bool pbEnabled); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayFlag GetOverlayFlag; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayColor(ulong ulOverlayHandle, float fRed, float fGreen, float fBlue); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayColor SetOverlayColor; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayColor(ulong ulOverlayHandle, ref float pfRed, ref float pfGreen, ref float pfBlue); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayColor GetOverlayColor; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayAlpha(ulong ulOverlayHandle, float fAlpha); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayAlpha SetOverlayAlpha; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayAlpha(ulong ulOverlayHandle, ref float pfAlpha); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayAlpha GetOverlayAlpha; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayWidthInMeters(ulong ulOverlayHandle, float fWidthInMeters); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayWidthInMeters SetOverlayWidthInMeters; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayWidthInMeters(ulong ulOverlayHandle, ref float pfWidthInMeters); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayWidthInMeters GetOverlayWidthInMeters; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayAutoCurveDistanceRangeInMeters(ulong ulOverlayHandle, float fMinDistanceInMeters, float fMaxDistanceInMeters); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayAutoCurveDistanceRangeInMeters SetOverlayAutoCurveDistanceRangeInMeters; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayAutoCurveDistanceRangeInMeters(ulong ulOverlayHandle, ref float pfMinDistanceInMeters, ref float pfMaxDistanceInMeters); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayAutoCurveDistanceRangeInMeters GetOverlayAutoCurveDistanceRangeInMeters; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayTextureColorSpace(ulong ulOverlayHandle, EColorSpace eTextureColorSpace); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayTextureColorSpace SetOverlayTextureColorSpace; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayTextureColorSpace(ulong ulOverlayHandle, ref EColorSpace peTextureColorSpace); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayTextureColorSpace GetOverlayTextureColorSpace; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayTextureBounds(ulong ulOverlayHandle, ref VRTextureBounds_t pOverlayTextureBounds); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayTextureBounds SetOverlayTextureBounds; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayTextureBounds(ulong ulOverlayHandle, ref VRTextureBounds_t pOverlayTextureBounds); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayTextureBounds GetOverlayTextureBounds; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayTransformType(ulong ulOverlayHandle, ref VROverlayTransformType peTransformType); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayTransformType GetOverlayTransformType; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayTransformAbsolute(ulong ulOverlayHandle, ETrackingUniverseOrigin eTrackingOrigin, ref HmdMatrix34_t pmatTrackingOriginToOverlayTransform); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayTransformAbsolute SetOverlayTransformAbsolute; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayTransformAbsolute(ulong ulOverlayHandle, ref ETrackingUniverseOrigin peTrackingOrigin, ref HmdMatrix34_t pmatTrackingOriginToOverlayTransform); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayTransformAbsolute GetOverlayTransformAbsolute; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayTransformTrackedDeviceRelative(ulong ulOverlayHandle, uint unTrackedDevice, ref HmdMatrix34_t pmatTrackedDeviceToOverlayTransform); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayTransformTrackedDeviceRelative SetOverlayTransformTrackedDeviceRelative; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayTransformTrackedDeviceRelative(ulong ulOverlayHandle, ref uint punTrackedDevice, ref HmdMatrix34_t pmatTrackedDeviceToOverlayTransform); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayTransformTrackedDeviceRelative GetOverlayTransformTrackedDeviceRelative; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayTransformTrackedDeviceComponent(ulong ulOverlayHandle, uint unDeviceIndex, string pchComponentName); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayTransformTrackedDeviceComponent SetOverlayTransformTrackedDeviceComponent; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayTransformTrackedDeviceComponent(ulong ulOverlayHandle, ref uint punDeviceIndex, string pchComponentName, uint unComponentNameSize); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayTransformTrackedDeviceComponent GetOverlayTransformTrackedDeviceComponent; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _ShowOverlay(ulong ulOverlayHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ShowOverlay ShowOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _HideOverlay(ulong ulOverlayHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _HideOverlay HideOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _IsOverlayVisible(ulong ulOverlayHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IsOverlayVisible IsOverlayVisible; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetTransformForOverlayCoordinates(ulong ulOverlayHandle, ETrackingUniverseOrigin eTrackingOrigin, HmdVector2_t coordinatesInOverlay, ref HmdMatrix34_t pmatTransform); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetTransformForOverlayCoordinates GetTransformForOverlayCoordinates; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _PollNextOverlayEvent(ulong ulOverlayHandle, ref VREvent_t pEvent, uint uncbVREvent); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _PollNextOverlayEvent PollNextOverlayEvent; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayInputMethod(ulong ulOverlayHandle, ref VROverlayInputMethod peInputMethod); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayInputMethod GetOverlayInputMethod; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayInputMethod(ulong ulOverlayHandle, VROverlayInputMethod eInputMethod); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayInputMethod SetOverlayInputMethod; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayMouseScale(ulong ulOverlayHandle, ref HmdVector2_t pvecMouseScale); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayMouseScale GetOverlayMouseScale; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayMouseScale(ulong ulOverlayHandle, ref HmdVector2_t pvecMouseScale); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayMouseScale SetOverlayMouseScale; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _ComputeOverlayIntersection(ulong ulOverlayHandle, ref VROverlayIntersectionParams_t pParams, ref VROverlayIntersectionResults_t pResults); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ComputeOverlayIntersection ComputeOverlayIntersection; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _HandleControllerOverlayInteractionAsMouse(ulong ulOverlayHandle, uint unControllerDeviceIndex); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _HandleControllerOverlayInteractionAsMouse HandleControllerOverlayInteractionAsMouse; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _IsHoverTargetOverlay(ulong ulOverlayHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IsHoverTargetOverlay IsHoverTargetOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate ulong _GetGamepadFocusOverlay(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetGamepadFocusOverlay GetGamepadFocusOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetGamepadFocusOverlay(ulong ulNewFocusOverlay); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetGamepadFocusOverlay SetGamepadFocusOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayNeighbor(EOverlayDirection eDirection, ulong ulFrom, ulong ulTo); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayNeighbor SetOverlayNeighbor; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _MoveGamepadFocusToNeighbor(EOverlayDirection eDirection, ulong ulFrom); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _MoveGamepadFocusToNeighbor MoveGamepadFocusToNeighbor; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayTexture(ulong ulOverlayHandle, ref Texture_t pTexture); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayTexture SetOverlayTexture; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _ClearOverlayTexture(ulong ulOverlayHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ClearOverlayTexture ClearOverlayTexture; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayRaw(ulong ulOverlayHandle, IntPtr pvBuffer, uint unWidth, uint unHeight, uint unDepth); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayRaw SetOverlayRaw; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetOverlayFromFile(ulong ulOverlayHandle, string pchFilePath); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetOverlayFromFile SetOverlayFromFile; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayTexture(ulong ulOverlayHandle, ref IntPtr pNativeTextureHandle, IntPtr pNativeTextureRef, ref uint pWidth, ref uint pHeight, ref uint pNativeFormat, ref EGraphicsAPIConvention pAPI, ref EColorSpace pColorSpace); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayTexture GetOverlayTexture; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _ReleaseNativeOverlayHandle(ulong ulOverlayHandle, IntPtr pNativeTextureHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ReleaseNativeOverlayHandle ReleaseNativeOverlayHandle; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetOverlayTextureSize(ulong ulOverlayHandle, ref uint pWidth, ref uint pHeight); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetOverlayTextureSize GetOverlayTextureSize; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _CreateDashboardOverlay(string pchOverlayKey, string pchOverlayFriendlyName, ref ulong pMainHandle, ref ulong pThumbnailHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _CreateDashboardOverlay CreateDashboardOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _IsDashboardVisible(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IsDashboardVisible IsDashboardVisible; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _IsActiveDashboardOverlay(ulong ulOverlayHandle); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _IsActiveDashboardOverlay IsActiveDashboardOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _SetDashboardOverlaySceneProcess(ulong ulOverlayHandle, uint unProcessId); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetDashboardOverlaySceneProcess SetDashboardOverlaySceneProcess; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _GetDashboardOverlaySceneProcess(ulong ulOverlayHandle, ref uint punProcessId); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetDashboardOverlaySceneProcess GetDashboardOverlaySceneProcess; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _ShowDashboard(string pchOverlayToShow); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ShowDashboard ShowDashboard; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetPrimaryDashboardDevice(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetPrimaryDashboardDevice GetPrimaryDashboardDevice; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _ShowKeyboard(int eInputMode, int eLineInputMode, string pchDescription, uint unCharMax, string pchExistingText, bool bUseMinimalMode, ulong uUserValue); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ShowKeyboard ShowKeyboard; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVROverlayError _ShowKeyboardForOverlay(ulong ulOverlayHandle, int eInputMode, int eLineInputMode, string pchDescription, uint unCharMax, string pchExistingText, bool bUseMinimalMode, ulong uUserValue); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _ShowKeyboardForOverlay ShowKeyboardForOverlay; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetKeyboardText(System.Text.StringBuilder pchText, uint cchText); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetKeyboardText GetKeyboardText; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _HideKeyboard(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _HideKeyboard HideKeyboard; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetKeyboardTransformAbsolute(ETrackingUniverseOrigin eTrackingOrigin, ref HmdMatrix34_t pmatTrackingOriginToKeyboardTransform); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetKeyboardTransformAbsolute SetKeyboardTransformAbsolute; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetKeyboardPositionForOverlay(ulong ulOverlayHandle, HmdRect2_t avoidRect); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetKeyboardPositionForOverlay SetKeyboardPositionForOverlay; + +} + +[StructLayout(LayoutKind.Sequential)] +public struct IVRRenderModels +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRRenderModelError _LoadRenderModel_Async(string pchRenderModelName, ref IntPtr ppRenderModel); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _LoadRenderModel_Async LoadRenderModel_Async; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _FreeRenderModel(IntPtr pRenderModel); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _FreeRenderModel FreeRenderModel; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRRenderModelError _LoadTexture_Async(int textureId, ref IntPtr ppTexture); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _LoadTexture_Async LoadTexture_Async; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _FreeTexture(IntPtr pTexture); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _FreeTexture FreeTexture; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRRenderModelError _LoadTextureD3D11_Async(int textureId, IntPtr pD3D11Device, ref IntPtr ppD3D11Texture2D); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _LoadTextureD3D11_Async LoadTextureD3D11_Async; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRRenderModelError _LoadIntoTextureD3D11_Async(int textureId, IntPtr pDstTexture); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _LoadIntoTextureD3D11_Async LoadIntoTextureD3D11_Async; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _FreeTextureD3D11(IntPtr pD3D11Texture2D); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _FreeTextureD3D11 FreeTextureD3D11; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetRenderModelName(uint unRenderModelIndex, System.Text.StringBuilder pchRenderModelName, uint unRenderModelNameLen); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetRenderModelName GetRenderModelName; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetRenderModelCount(); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetRenderModelCount GetRenderModelCount; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetComponentCount(string pchRenderModelName); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetComponentCount GetComponentCount; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetComponentName(string pchRenderModelName, uint unComponentIndex, System.Text.StringBuilder pchComponentName, uint unComponentNameLen); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetComponentName GetComponentName; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate ulong _GetComponentButtonMask(string pchRenderModelName, string pchComponentName); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetComponentButtonMask GetComponentButtonMask; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetComponentRenderModelName(string pchRenderModelName, string pchComponentName, System.Text.StringBuilder pchComponentRenderModelName, uint unComponentRenderModelNameLen); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetComponentRenderModelName GetComponentRenderModelName; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetComponentState(string pchRenderModelName, string pchComponentName, ref VRControllerState_t pControllerState, ref RenderModel_ControllerMode_State_t pState, ref RenderModel_ComponentState_t pComponentState); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetComponentState GetComponentState; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _RenderModelHasComponent(string pchRenderModelName, string pchComponentName); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _RenderModelHasComponent RenderModelHasComponent; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetRenderModelThumbnailURL(string pchRenderModelName, System.Text.StringBuilder pchThumbnailURL, uint unThumbnailURLLen, ref EVRRenderModelError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetRenderModelThumbnailURL GetRenderModelThumbnailURL; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetRenderModelOriginalPath(string pchRenderModelName, System.Text.StringBuilder pchOriginalPath, uint unOriginalPathLen, ref EVRRenderModelError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetRenderModelOriginalPath GetRenderModelOriginalPath; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate IntPtr _GetRenderModelErrorNameFromEnum(EVRRenderModelError error); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetRenderModelErrorNameFromEnum GetRenderModelErrorNameFromEnum; + +} + +[StructLayout(LayoutKind.Sequential)] +public struct IVRNotifications +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRNotificationError _CreateNotification(ulong ulOverlayHandle, ulong ulUserValue, EVRNotificationType type, string pchText, EVRNotificationStyle style, ref NotificationBitmap_t pImage, ref uint pNotificationId); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _CreateNotification CreateNotification; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRNotificationError _RemoveNotification(uint notificationId); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _RemoveNotification RemoveNotification; + +} + +[StructLayout(LayoutKind.Sequential)] +public struct IVRSettings +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate IntPtr _GetSettingsErrorNameFromEnum(EVRSettingsError eError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetSettingsErrorNameFromEnum GetSettingsErrorNameFromEnum; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _Sync(bool bForce, ref EVRSettingsError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _Sync Sync; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate bool _GetBool(string pchSection, string pchSettingsKey, bool bDefaultValue, ref EVRSettingsError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetBool GetBool; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetBool(string pchSection, string pchSettingsKey, bool bValue, ref EVRSettingsError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetBool SetBool; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate int _GetInt32(string pchSection, string pchSettingsKey, int nDefaultValue, ref EVRSettingsError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetInt32 GetInt32; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetInt32(string pchSection, string pchSettingsKey, int nValue, ref EVRSettingsError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetInt32 SetInt32; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate float _GetFloat(string pchSection, string pchSettingsKey, float flDefaultValue, ref EVRSettingsError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetFloat GetFloat; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetFloat(string pchSection, string pchSettingsKey, float flValue, ref EVRSettingsError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetFloat SetFloat; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _GetString(string pchSection, string pchSettingsKey, string pchValue, uint unValueLen, string pchDefaultValue, ref EVRSettingsError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetString GetString; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _SetString(string pchSection, string pchSettingsKey, string pchValue, ref EVRSettingsError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SetString SetString; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _RemoveSection(string pchSection, ref EVRSettingsError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _RemoveSection RemoveSection; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate void _RemoveKeyInSection(string pchSection, string pchSettingsKey, ref EVRSettingsError peError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _RemoveKeyInSection RemoveKeyInSection; + +} + +[StructLayout(LayoutKind.Sequential)] +public struct IVRScreenshots +{ + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRScreenshotError _RequestScreenshot(ref uint pOutScreenshotHandle, EVRScreenshotType type, string pchPreviewFilename, string pchVRFilename); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _RequestScreenshot RequestScreenshot; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRScreenshotError _HookScreenshot([In, Out] EVRScreenshotType[] pSupportedTypes, int numTypes); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _HookScreenshot HookScreenshot; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRScreenshotType _GetScreenshotPropertyType(uint screenshotHandle, ref EVRScreenshotError pError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetScreenshotPropertyType GetScreenshotPropertyType; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate uint _GetScreenshotPropertyFilename(uint screenshotHandle, EVRScreenshotPropertyFilenames filenameType, System.Text.StringBuilder pchFilename, uint cchFilename, ref EVRScreenshotError pError); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _GetScreenshotPropertyFilename GetScreenshotPropertyFilename; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRScreenshotError _UpdateScreenshotProgress(uint screenshotHandle, float flProgress); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _UpdateScreenshotProgress UpdateScreenshotProgress; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRScreenshotError _TakeStereoScreenshot(ref uint pOutScreenshotHandle, string pchPreviewFilename, string pchVRFilename); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _TakeStereoScreenshot TakeStereoScreenshot; + + [UnmanagedFunctionPointer(CallingConvention.StdCall)] + internal delegate EVRScreenshotError _SubmitScreenshot(uint screenshotHandle, EVRScreenshotType type, string pchSourcePreviewFilename, string pchSourceVRFilename); + [MarshalAs(UnmanagedType.FunctionPtr)] + internal _SubmitScreenshot SubmitScreenshot; + +} + + +public class CVRSystem +{ + IVRSystem FnTable; + internal CVRSystem(IntPtr pInterface) + { + FnTable = (IVRSystem)Marshal.PtrToStructure(pInterface, typeof(IVRSystem)); + } + public void GetRecommendedRenderTargetSize(ref uint pnWidth,ref uint pnHeight) + { + pnWidth = 0; + pnHeight = 0; + FnTable.GetRecommendedRenderTargetSize(ref pnWidth,ref pnHeight); + } + public HmdMatrix44_t GetProjectionMatrix(EVREye eEye,float fNearZ,float fFarZ,EGraphicsAPIConvention eProjType) + { + HmdMatrix44_t result = FnTable.GetProjectionMatrix(eEye,fNearZ,fFarZ,eProjType); + return result; + } + public void GetProjectionRaw(EVREye eEye,ref float pfLeft,ref float pfRight,ref float pfTop,ref float pfBottom) + { + pfLeft = 0; + pfRight = 0; + pfTop = 0; + pfBottom = 0; + FnTable.GetProjectionRaw(eEye,ref pfLeft,ref pfRight,ref pfTop,ref pfBottom); + } + public DistortionCoordinates_t ComputeDistortion(EVREye eEye,float fU,float fV) + { + DistortionCoordinates_t result = FnTable.ComputeDistortion(eEye,fU,fV); + return result; + } + public HmdMatrix34_t GetEyeToHeadTransform(EVREye eEye) + { + HmdMatrix34_t result = FnTable.GetEyeToHeadTransform(eEye); + return result; + } + public bool GetTimeSinceLastVsync(ref float pfSecondsSinceLastVsync,ref ulong pulFrameCounter) + { + pfSecondsSinceLastVsync = 0; + pulFrameCounter = 0; + bool result = FnTable.GetTimeSinceLastVsync(ref pfSecondsSinceLastVsync,ref pulFrameCounter); + return result; + } + public int GetD3D9AdapterIndex() + { + int result = FnTable.GetD3D9AdapterIndex(); + return result; + } + public void GetDXGIOutputInfo(ref int pnAdapterIndex) + { + pnAdapterIndex = 0; + FnTable.GetDXGIOutputInfo(ref pnAdapterIndex); + } + public bool IsDisplayOnDesktop() + { + bool result = FnTable.IsDisplayOnDesktop(); + return result; + } + public bool SetDisplayVisibility(bool bIsVisibleOnDesktop) + { + bool result = FnTable.SetDisplayVisibility(bIsVisibleOnDesktop); + return result; + } + public void GetDeviceToAbsoluteTrackingPose(ETrackingUniverseOrigin eOrigin,float fPredictedSecondsToPhotonsFromNow,TrackedDevicePose_t [] pTrackedDevicePoseArray) + { + FnTable.GetDeviceToAbsoluteTrackingPose(eOrigin,fPredictedSecondsToPhotonsFromNow,pTrackedDevicePoseArray,(uint) pTrackedDevicePoseArray.Length); + } + public void ResetSeatedZeroPose() + { + FnTable.ResetSeatedZeroPose(); + } + public HmdMatrix34_t GetSeatedZeroPoseToStandingAbsoluteTrackingPose() + { + HmdMatrix34_t result = FnTable.GetSeatedZeroPoseToStandingAbsoluteTrackingPose(); + return result; + } + public HmdMatrix34_t GetRawZeroPoseToStandingAbsoluteTrackingPose() + { + HmdMatrix34_t result = FnTable.GetRawZeroPoseToStandingAbsoluteTrackingPose(); + return result; + } + public uint GetSortedTrackedDeviceIndicesOfClass(ETrackedDeviceClass eTrackedDeviceClass,uint [] punTrackedDeviceIndexArray,uint unRelativeToTrackedDeviceIndex) + { + uint result = FnTable.GetSortedTrackedDeviceIndicesOfClass(eTrackedDeviceClass,punTrackedDeviceIndexArray,(uint) punTrackedDeviceIndexArray.Length,unRelativeToTrackedDeviceIndex); + return result; + } + public EDeviceActivityLevel GetTrackedDeviceActivityLevel(uint unDeviceId) + { + EDeviceActivityLevel result = FnTable.GetTrackedDeviceActivityLevel(unDeviceId); + return result; + } + public void ApplyTransform(ref TrackedDevicePose_t pOutputPose,ref TrackedDevicePose_t pTrackedDevicePose,ref HmdMatrix34_t pTransform) + { + FnTable.ApplyTransform(ref pOutputPose,ref pTrackedDevicePose,ref pTransform); + } + public uint GetTrackedDeviceIndexForControllerRole(ETrackedControllerRole unDeviceType) + { + uint result = FnTable.GetTrackedDeviceIndexForControllerRole(unDeviceType); + return result; + } + public ETrackedControllerRole GetControllerRoleForTrackedDeviceIndex(uint unDeviceIndex) + { + ETrackedControllerRole result = FnTable.GetControllerRoleForTrackedDeviceIndex(unDeviceIndex); + return result; + } + public ETrackedDeviceClass GetTrackedDeviceClass(uint unDeviceIndex) + { + ETrackedDeviceClass result = FnTable.GetTrackedDeviceClass(unDeviceIndex); + return result; + } + public bool IsTrackedDeviceConnected(uint unDeviceIndex) + { + bool result = FnTable.IsTrackedDeviceConnected(unDeviceIndex); + return result; + } + public bool GetBoolTrackedDeviceProperty(uint unDeviceIndex,ETrackedDeviceProperty prop,ref ETrackedPropertyError pError) + { + bool result = FnTable.GetBoolTrackedDeviceProperty(unDeviceIndex,prop,ref pError); + return result; + } + public float GetFloatTrackedDeviceProperty(uint unDeviceIndex,ETrackedDeviceProperty prop,ref ETrackedPropertyError pError) + { + float result = FnTable.GetFloatTrackedDeviceProperty(unDeviceIndex,prop,ref pError); + return result; + } + public int GetInt32TrackedDeviceProperty(uint unDeviceIndex,ETrackedDeviceProperty prop,ref ETrackedPropertyError pError) + { + int result = FnTable.GetInt32TrackedDeviceProperty(unDeviceIndex,prop,ref pError); + return result; + } + public ulong GetUint64TrackedDeviceProperty(uint unDeviceIndex,ETrackedDeviceProperty prop,ref ETrackedPropertyError pError) + { + ulong result = FnTable.GetUint64TrackedDeviceProperty(unDeviceIndex,prop,ref pError); + return result; + } + public HmdMatrix34_t GetMatrix34TrackedDeviceProperty(uint unDeviceIndex,ETrackedDeviceProperty prop,ref ETrackedPropertyError pError) + { + HmdMatrix34_t result = FnTable.GetMatrix34TrackedDeviceProperty(unDeviceIndex,prop,ref pError); + return result; + } + public uint GetStringTrackedDeviceProperty(uint unDeviceIndex,ETrackedDeviceProperty prop,System.Text.StringBuilder pchValue,uint unBufferSize,ref ETrackedPropertyError pError) + { + uint result = FnTable.GetStringTrackedDeviceProperty(unDeviceIndex,prop,pchValue,unBufferSize,ref pError); + return result; + } + public string GetPropErrorNameFromEnum(ETrackedPropertyError error) + { + IntPtr result = FnTable.GetPropErrorNameFromEnum(error); + return Marshal.PtrToStringAnsi(result); + } + public bool PollNextEvent(ref VREvent_t pEvent,uint uncbVREvent) + { + bool result = FnTable.PollNextEvent(ref pEvent,uncbVREvent); + return result; + } + public bool PollNextEventWithPose(ETrackingUniverseOrigin eOrigin,ref VREvent_t pEvent,uint uncbVREvent,ref TrackedDevicePose_t pTrackedDevicePose) + { + bool result = FnTable.PollNextEventWithPose(eOrigin,ref pEvent,uncbVREvent,ref pTrackedDevicePose); + return result; + } + public string GetEventTypeNameFromEnum(EVREventType eType) + { + IntPtr result = FnTable.GetEventTypeNameFromEnum(eType); + return Marshal.PtrToStringAnsi(result); + } + public HiddenAreaMesh_t GetHiddenAreaMesh(EVREye eEye) + { + HiddenAreaMesh_t result = FnTable.GetHiddenAreaMesh(eEye); + return result; + } + public bool GetControllerState(uint unControllerDeviceIndex,ref VRControllerState_t pControllerState) + { + bool result = FnTable.GetControllerState(unControllerDeviceIndex,ref pControllerState); + return result; + } + public bool GetControllerStateWithPose(ETrackingUniverseOrigin eOrigin,uint unControllerDeviceIndex,ref VRControllerState_t pControllerState,ref TrackedDevicePose_t pTrackedDevicePose) + { + bool result = FnTable.GetControllerStateWithPose(eOrigin,unControllerDeviceIndex,ref pControllerState,ref pTrackedDevicePose); + return result; + } + public void TriggerHapticPulse(uint unControllerDeviceIndex,uint unAxisId,char usDurationMicroSec) + { + FnTable.TriggerHapticPulse(unControllerDeviceIndex,unAxisId,usDurationMicroSec); + } + public string GetButtonIdNameFromEnum(EVRButtonId eButtonId) + { + IntPtr result = FnTable.GetButtonIdNameFromEnum(eButtonId); + return Marshal.PtrToStringAnsi(result); + } + public string GetControllerAxisTypeNameFromEnum(EVRControllerAxisType eAxisType) + { + IntPtr result = FnTable.GetControllerAxisTypeNameFromEnum(eAxisType); + return Marshal.PtrToStringAnsi(result); + } + public bool CaptureInputFocus() + { + bool result = FnTable.CaptureInputFocus(); + return result; + } + public void ReleaseInputFocus() + { + FnTable.ReleaseInputFocus(); + } + public bool IsInputFocusCapturedByAnotherProcess() + { + bool result = FnTable.IsInputFocusCapturedByAnotherProcess(); + return result; + } + public uint DriverDebugRequest(uint unDeviceIndex,string pchRequest,string pchResponseBuffer,uint unResponseBufferSize) + { + uint result = FnTable.DriverDebugRequest(unDeviceIndex,pchRequest,pchResponseBuffer,unResponseBufferSize); + return result; + } + public EVRFirmwareError PerformFirmwareUpdate(uint unDeviceIndex) + { + EVRFirmwareError result = FnTable.PerformFirmwareUpdate(unDeviceIndex); + return result; + } + public void AcknowledgeQuit_Exiting() + { + FnTable.AcknowledgeQuit_Exiting(); + } + public void AcknowledgeQuit_UserPrompt() + { + FnTable.AcknowledgeQuit_UserPrompt(); + } +} + + +public class CVRExtendedDisplay +{ + IVRExtendedDisplay FnTable; + internal CVRExtendedDisplay(IntPtr pInterface) + { + FnTable = (IVRExtendedDisplay)Marshal.PtrToStructure(pInterface, typeof(IVRExtendedDisplay)); + } + public void GetWindowBounds(ref int pnX,ref int pnY,ref uint pnWidth,ref uint pnHeight) + { + pnX = 0; + pnY = 0; + pnWidth = 0; + pnHeight = 0; + FnTable.GetWindowBounds(ref pnX,ref pnY,ref pnWidth,ref pnHeight); + } + public void GetEyeOutputViewport(EVREye eEye,ref uint pnX,ref uint pnY,ref uint pnWidth,ref uint pnHeight) + { + pnX = 0; + pnY = 0; + pnWidth = 0; + pnHeight = 0; + FnTable.GetEyeOutputViewport(eEye,ref pnX,ref pnY,ref pnWidth,ref pnHeight); + } + public void GetDXGIOutputInfo(ref int pnAdapterIndex,ref int pnAdapterOutputIndex) + { + pnAdapterIndex = 0; + pnAdapterOutputIndex = 0; + FnTable.GetDXGIOutputInfo(ref pnAdapterIndex,ref pnAdapterOutputIndex); + } +} + + +public class CVRTrackedCamera +{ + IVRTrackedCamera FnTable; + internal CVRTrackedCamera(IntPtr pInterface) + { + FnTable = (IVRTrackedCamera)Marshal.PtrToStructure(pInterface, typeof(IVRTrackedCamera)); + } + public string GetCameraErrorNameFromEnum(EVRTrackedCameraError eCameraError) + { + IntPtr result = FnTable.GetCameraErrorNameFromEnum(eCameraError); + return Marshal.PtrToStringAnsi(result); + } + public EVRTrackedCameraError HasCamera(uint nDeviceIndex,ref bool pHasCamera) + { + pHasCamera = false; + EVRTrackedCameraError result = FnTable.HasCamera(nDeviceIndex,ref pHasCamera); + return result; + } + public EVRTrackedCameraError GetCameraFrameSize(uint nDeviceIndex,EVRTrackedCameraFrameType eFrameType,ref uint pnWidth,ref uint pnHeight,ref uint pnFrameBufferSize) + { + pnWidth = 0; + pnHeight = 0; + pnFrameBufferSize = 0; + EVRTrackedCameraError result = FnTable.GetCameraFrameSize(nDeviceIndex,eFrameType,ref pnWidth,ref pnHeight,ref pnFrameBufferSize); + return result; + } + public EVRTrackedCameraError GetCameraIntrinisics(uint nDeviceIndex,EVRTrackedCameraFrameType eFrameType,ref HmdVector2_t pFocalLength,ref HmdVector2_t pCenter) + { + EVRTrackedCameraError result = FnTable.GetCameraIntrinisics(nDeviceIndex,eFrameType,ref pFocalLength,ref pCenter); + return result; + } + public EVRTrackedCameraError GetCameraProjection(uint nDeviceIndex,EVRTrackedCameraFrameType eFrameType,float flZNear,float flZFar,ref HmdMatrix44_t pProjection) + { + EVRTrackedCameraError result = FnTable.GetCameraProjection(nDeviceIndex,eFrameType,flZNear,flZFar,ref pProjection); + return result; + } + public EVRTrackedCameraError AcquireVideoStreamingService(uint nDeviceIndex,ref ulong pHandle) + { + pHandle = 0; + EVRTrackedCameraError result = FnTable.AcquireVideoStreamingService(nDeviceIndex,ref pHandle); + return result; + } + public EVRTrackedCameraError ReleaseVideoStreamingService(ulong hTrackedCamera) + { + EVRTrackedCameraError result = FnTable.ReleaseVideoStreamingService(hTrackedCamera); + return result; + } + public EVRTrackedCameraError GetVideoStreamFrameBuffer(ulong hTrackedCamera,EVRTrackedCameraFrameType eFrameType,IntPtr pFrameBuffer,uint nFrameBufferSize,ref CameraVideoStreamFrameHeader_t pFrameHeader,uint nFrameHeaderSize) + { + EVRTrackedCameraError result = FnTable.GetVideoStreamFrameBuffer(hTrackedCamera,eFrameType,pFrameBuffer,nFrameBufferSize,ref pFrameHeader,nFrameHeaderSize); + return result; + } +} + + +public class CVRApplications +{ + IVRApplications FnTable; + internal CVRApplications(IntPtr pInterface) + { + FnTable = (IVRApplications)Marshal.PtrToStructure(pInterface, typeof(IVRApplications)); + } + public EVRApplicationError AddApplicationManifest(string pchApplicationManifestFullPath,bool bTemporary) + { + EVRApplicationError result = FnTable.AddApplicationManifest(pchApplicationManifestFullPath,bTemporary); + return result; + } + public EVRApplicationError RemoveApplicationManifest(string pchApplicationManifestFullPath) + { + EVRApplicationError result = FnTable.RemoveApplicationManifest(pchApplicationManifestFullPath); + return result; + } + public bool IsApplicationInstalled(string pchAppKey) + { + bool result = FnTable.IsApplicationInstalled(pchAppKey); + return result; + } + public uint GetApplicationCount() + { + uint result = FnTable.GetApplicationCount(); + return result; + } + public EVRApplicationError GetApplicationKeyByIndex(uint unApplicationIndex,string pchAppKeyBuffer,uint unAppKeyBufferLen) + { + EVRApplicationError result = FnTable.GetApplicationKeyByIndex(unApplicationIndex,pchAppKeyBuffer,unAppKeyBufferLen); + return result; + } + public EVRApplicationError GetApplicationKeyByProcessId(uint unProcessId,string pchAppKeyBuffer,uint unAppKeyBufferLen) + { + EVRApplicationError result = FnTable.GetApplicationKeyByProcessId(unProcessId,pchAppKeyBuffer,unAppKeyBufferLen); + return result; + } + public EVRApplicationError LaunchApplication(string pchAppKey) + { + EVRApplicationError result = FnTable.LaunchApplication(pchAppKey); + return result; + } + public EVRApplicationError LaunchTemplateApplication(string pchTemplateAppKey,string pchNewAppKey,AppOverrideKeys_t [] pKeys) + { + EVRApplicationError result = FnTable.LaunchTemplateApplication(pchTemplateAppKey,pchNewAppKey,pKeys,(uint) pKeys.Length); + return result; + } + public EVRApplicationError LaunchDashboardOverlay(string pchAppKey) + { + EVRApplicationError result = FnTable.LaunchDashboardOverlay(pchAppKey); + return result; + } + public bool CancelApplicationLaunch(string pchAppKey) + { + bool result = FnTable.CancelApplicationLaunch(pchAppKey); + return result; + } + public EVRApplicationError IdentifyApplication(uint unProcessId,string pchAppKey) + { + EVRApplicationError result = FnTable.IdentifyApplication(unProcessId,pchAppKey); + return result; + } + public uint GetApplicationProcessId(string pchAppKey) + { + uint result = FnTable.GetApplicationProcessId(pchAppKey); + return result; + } + public string GetApplicationsErrorNameFromEnum(EVRApplicationError error) + { + IntPtr result = FnTable.GetApplicationsErrorNameFromEnum(error); + return Marshal.PtrToStringAnsi(result); + } + public uint GetApplicationPropertyString(string pchAppKey,EVRApplicationProperty eProperty,string pchPropertyValueBuffer,uint unPropertyValueBufferLen,ref EVRApplicationError peError) + { + uint result = FnTable.GetApplicationPropertyString(pchAppKey,eProperty,pchPropertyValueBuffer,unPropertyValueBufferLen,ref peError); + return result; + } + public bool GetApplicationPropertyBool(string pchAppKey,EVRApplicationProperty eProperty,ref EVRApplicationError peError) + { + bool result = FnTable.GetApplicationPropertyBool(pchAppKey,eProperty,ref peError); + return result; + } + public ulong GetApplicationPropertyUint64(string pchAppKey,EVRApplicationProperty eProperty,ref EVRApplicationError peError) + { + ulong result = FnTable.GetApplicationPropertyUint64(pchAppKey,eProperty,ref peError); + return result; + } + public EVRApplicationError SetApplicationAutoLaunch(string pchAppKey,bool bAutoLaunch) + { + EVRApplicationError result = FnTable.SetApplicationAutoLaunch(pchAppKey,bAutoLaunch); + return result; + } + public bool GetApplicationAutoLaunch(string pchAppKey) + { + bool result = FnTable.GetApplicationAutoLaunch(pchAppKey); + return result; + } + public EVRApplicationError GetStartingApplication(string pchAppKeyBuffer,uint unAppKeyBufferLen) + { + EVRApplicationError result = FnTable.GetStartingApplication(pchAppKeyBuffer,unAppKeyBufferLen); + return result; + } + public EVRApplicationTransitionState GetTransitionState() + { + EVRApplicationTransitionState result = FnTable.GetTransitionState(); + return result; + } + public EVRApplicationError PerformApplicationPrelaunchCheck(string pchAppKey) + { + EVRApplicationError result = FnTable.PerformApplicationPrelaunchCheck(pchAppKey); + return result; + } + public string GetApplicationsTransitionStateNameFromEnum(EVRApplicationTransitionState state) + { + IntPtr result = FnTable.GetApplicationsTransitionStateNameFromEnum(state); + return Marshal.PtrToStringAnsi(result); + } + public bool IsQuitUserPromptRequested() + { + bool result = FnTable.IsQuitUserPromptRequested(); + return result; + } + public EVRApplicationError LaunchInternalProcess(string pchBinaryPath,string pchArguments,string pchWorkingDirectory) + { + EVRApplicationError result = FnTable.LaunchInternalProcess(pchBinaryPath,pchArguments,pchWorkingDirectory); + return result; + } +} + + +public class CVRChaperone +{ + IVRChaperone FnTable; + internal CVRChaperone(IntPtr pInterface) + { + FnTable = (IVRChaperone)Marshal.PtrToStructure(pInterface, typeof(IVRChaperone)); + } + public ChaperoneCalibrationState GetCalibrationState() + { + ChaperoneCalibrationState result = FnTable.GetCalibrationState(); + return result; + } + public bool GetPlayAreaSize(ref float pSizeX,ref float pSizeZ) + { + pSizeX = 0; + pSizeZ = 0; + bool result = FnTable.GetPlayAreaSize(ref pSizeX,ref pSizeZ); + return result; + } + public bool GetPlayAreaRect(ref HmdQuad_t rect) + { + bool result = FnTable.GetPlayAreaRect(ref rect); + return result; + } + public void ReloadInfo() + { + FnTable.ReloadInfo(); + } + public void SetSceneColor(HmdColor_t color) + { + FnTable.SetSceneColor(color); + } + public void GetBoundsColor(ref HmdColor_t pOutputColorArray,int nNumOutputColors,float flCollisionBoundsFadeDistance,ref HmdColor_t pOutputCameraColor) + { + FnTable.GetBoundsColor(ref pOutputColorArray,nNumOutputColors,flCollisionBoundsFadeDistance,ref pOutputCameraColor); + } + public bool AreBoundsVisible() + { + bool result = FnTable.AreBoundsVisible(); + return result; + } + public void ForceBoundsVisible(bool bForce) + { + FnTable.ForceBoundsVisible(bForce); + } +} + + +public class CVRChaperoneSetup +{ + IVRChaperoneSetup FnTable; + internal CVRChaperoneSetup(IntPtr pInterface) + { + FnTable = (IVRChaperoneSetup)Marshal.PtrToStructure(pInterface, typeof(IVRChaperoneSetup)); + } + public bool CommitWorkingCopy(EChaperoneConfigFile configFile) + { + bool result = FnTable.CommitWorkingCopy(configFile); + return result; + } + public void RevertWorkingCopy() + { + FnTable.RevertWorkingCopy(); + } + public bool GetWorkingPlayAreaSize(ref float pSizeX,ref float pSizeZ) + { + pSizeX = 0; + pSizeZ = 0; + bool result = FnTable.GetWorkingPlayAreaSize(ref pSizeX,ref pSizeZ); + return result; + } + public bool GetWorkingPlayAreaRect(ref HmdQuad_t rect) + { + bool result = FnTable.GetWorkingPlayAreaRect(ref rect); + return result; + } + public bool GetWorkingCollisionBoundsInfo(out HmdQuad_t [] pQuadsBuffer) + { + uint punQuadsCount = 0; + bool result = FnTable.GetWorkingCollisionBoundsInfo(null,ref punQuadsCount); + pQuadsBuffer= new HmdQuad_t[punQuadsCount]; + result = FnTable.GetWorkingCollisionBoundsInfo(pQuadsBuffer,ref punQuadsCount); + return result; + } + public bool GetLiveCollisionBoundsInfo(out HmdQuad_t [] pQuadsBuffer) + { + uint punQuadsCount = 0; + bool result = FnTable.GetLiveCollisionBoundsInfo(null,ref punQuadsCount); + pQuadsBuffer= new HmdQuad_t[punQuadsCount]; + result = FnTable.GetLiveCollisionBoundsInfo(pQuadsBuffer,ref punQuadsCount); + return result; + } + public bool GetWorkingSeatedZeroPoseToRawTrackingPose(ref HmdMatrix34_t pmatSeatedZeroPoseToRawTrackingPose) + { + bool result = FnTable.GetWorkingSeatedZeroPoseToRawTrackingPose(ref pmatSeatedZeroPoseToRawTrackingPose); + return result; + } + public bool GetWorkingStandingZeroPoseToRawTrackingPose(ref HmdMatrix34_t pmatStandingZeroPoseToRawTrackingPose) + { + bool result = FnTable.GetWorkingStandingZeroPoseToRawTrackingPose(ref pmatStandingZeroPoseToRawTrackingPose); + return result; + } + public void SetWorkingPlayAreaSize(float sizeX,float sizeZ) + { + FnTable.SetWorkingPlayAreaSize(sizeX,sizeZ); + } + public void SetWorkingCollisionBoundsInfo(HmdQuad_t [] pQuadsBuffer) + { + FnTable.SetWorkingCollisionBoundsInfo(pQuadsBuffer,(uint) pQuadsBuffer.Length); + } + public void SetWorkingSeatedZeroPoseToRawTrackingPose(ref HmdMatrix34_t pMatSeatedZeroPoseToRawTrackingPose) + { + FnTable.SetWorkingSeatedZeroPoseToRawTrackingPose(ref pMatSeatedZeroPoseToRawTrackingPose); + } + public void SetWorkingStandingZeroPoseToRawTrackingPose(ref HmdMatrix34_t pMatStandingZeroPoseToRawTrackingPose) + { + FnTable.SetWorkingStandingZeroPoseToRawTrackingPose(ref pMatStandingZeroPoseToRawTrackingPose); + } + public void ReloadFromDisk(EChaperoneConfigFile configFile) + { + FnTable.ReloadFromDisk(configFile); + } + public bool GetLiveSeatedZeroPoseToRawTrackingPose(ref HmdMatrix34_t pmatSeatedZeroPoseToRawTrackingPose) + { + bool result = FnTable.GetLiveSeatedZeroPoseToRawTrackingPose(ref pmatSeatedZeroPoseToRawTrackingPose); + return result; + } + public void SetWorkingCollisionBoundsTagsInfo(byte [] pTagsBuffer) + { + FnTable.SetWorkingCollisionBoundsTagsInfo(pTagsBuffer,(uint) pTagsBuffer.Length); + } + public bool GetLiveCollisionBoundsTagsInfo(out byte [] pTagsBuffer) + { + uint punTagCount = 0; + bool result = FnTable.GetLiveCollisionBoundsTagsInfo(null,ref punTagCount); + pTagsBuffer= new byte[punTagCount]; + result = FnTable.GetLiveCollisionBoundsTagsInfo(pTagsBuffer,ref punTagCount); + return result; + } + public bool SetWorkingPhysicalBoundsInfo(HmdQuad_t [] pQuadsBuffer) + { + bool result = FnTable.SetWorkingPhysicalBoundsInfo(pQuadsBuffer,(uint) pQuadsBuffer.Length); + return result; + } + public bool GetLivePhysicalBoundsInfo(out HmdQuad_t [] pQuadsBuffer) + { + uint punQuadsCount = 0; + bool result = FnTable.GetLivePhysicalBoundsInfo(null,ref punQuadsCount); + pQuadsBuffer= new HmdQuad_t[punQuadsCount]; + result = FnTable.GetLivePhysicalBoundsInfo(pQuadsBuffer,ref punQuadsCount); + return result; + } + public bool ExportLiveToBuffer(System.Text.StringBuilder pBuffer,ref uint pnBufferLength) + { + pnBufferLength = 0; + bool result = FnTable.ExportLiveToBuffer(pBuffer,ref pnBufferLength); + return result; + } + public bool ImportFromBufferToWorking(string pBuffer,uint nImportFlags) + { + bool result = FnTable.ImportFromBufferToWorking(pBuffer,nImportFlags); + return result; + } +} + + +public class CVRCompositor +{ + IVRCompositor FnTable; + internal CVRCompositor(IntPtr pInterface) + { + FnTable = (IVRCompositor)Marshal.PtrToStructure(pInterface, typeof(IVRCompositor)); + } + public void SetTrackingSpace(ETrackingUniverseOrigin eOrigin) + { + FnTable.SetTrackingSpace(eOrigin); + } + public ETrackingUniverseOrigin GetTrackingSpace() + { + ETrackingUniverseOrigin result = FnTable.GetTrackingSpace(); + return result; + } + public EVRCompositorError WaitGetPoses(TrackedDevicePose_t [] pRenderPoseArray,TrackedDevicePose_t [] pGamePoseArray) + { + EVRCompositorError result = FnTable.WaitGetPoses(pRenderPoseArray,(uint) pRenderPoseArray.Length,pGamePoseArray,(uint) pGamePoseArray.Length); + return result; + } + public EVRCompositorError GetLastPoses(TrackedDevicePose_t [] pRenderPoseArray,TrackedDevicePose_t [] pGamePoseArray) + { + EVRCompositorError result = FnTable.GetLastPoses(pRenderPoseArray,(uint) pRenderPoseArray.Length,pGamePoseArray,(uint) pGamePoseArray.Length); + return result; + } + public EVRCompositorError GetLastPoseForTrackedDeviceIndex(uint unDeviceIndex,ref TrackedDevicePose_t pOutputPose,ref TrackedDevicePose_t pOutputGamePose) + { + EVRCompositorError result = FnTable.GetLastPoseForTrackedDeviceIndex(unDeviceIndex,ref pOutputPose,ref pOutputGamePose); + return result; + } + public EVRCompositorError Submit(EVREye eEye,ref Texture_t pTexture,ref VRTextureBounds_t pBounds,EVRSubmitFlags nSubmitFlags) + { + EVRCompositorError result = FnTable.Submit(eEye,ref pTexture,ref pBounds,nSubmitFlags); + return result; + } + public void ClearLastSubmittedFrame() + { + FnTable.ClearLastSubmittedFrame(); + } + public void PostPresentHandoff() + { + FnTable.PostPresentHandoff(); + } + public bool GetFrameTiming(ref Compositor_FrameTiming pTiming,uint unFramesAgo) + { + bool result = FnTable.GetFrameTiming(ref pTiming,unFramesAgo); + return result; + } + public float GetFrameTimeRemaining() + { + float result = FnTable.GetFrameTimeRemaining(); + return result; + } + public void GetCumulativeStats(ref Compositor_CumulativeStats pStats,uint nStatsSizeInBytes) + { + FnTable.GetCumulativeStats(ref pStats,nStatsSizeInBytes); + } + public void FadeToColor(float fSeconds,float fRed,float fGreen,float fBlue,float fAlpha,bool bBackground) + { + FnTable.FadeToColor(fSeconds,fRed,fGreen,fBlue,fAlpha,bBackground); + } + public void FadeGrid(float fSeconds,bool bFadeIn) + { + FnTable.FadeGrid(fSeconds,bFadeIn); + } + public EVRCompositorError SetSkyboxOverride(Texture_t [] pTextures) + { + EVRCompositorError result = FnTable.SetSkyboxOverride(pTextures,(uint) pTextures.Length); + return result; + } + public void ClearSkyboxOverride() + { + FnTable.ClearSkyboxOverride(); + } + public void CompositorBringToFront() + { + FnTable.CompositorBringToFront(); + } + public void CompositorGoToBack() + { + FnTable.CompositorGoToBack(); + } + public void CompositorQuit() + { + FnTable.CompositorQuit(); + } + public bool IsFullscreen() + { + bool result = FnTable.IsFullscreen(); + return result; + } + public uint GetCurrentSceneFocusProcess() + { + uint result = FnTable.GetCurrentSceneFocusProcess(); + return result; + } + public uint GetLastFrameRenderer() + { + uint result = FnTable.GetLastFrameRenderer(); + return result; + } + public bool CanRenderScene() + { + bool result = FnTable.CanRenderScene(); + return result; + } + public void ShowMirrorWindow() + { + FnTable.ShowMirrorWindow(); + } + public void HideMirrorWindow() + { + FnTable.HideMirrorWindow(); + } + public bool IsMirrorWindowVisible() + { + bool result = FnTable.IsMirrorWindowVisible(); + return result; + } + public void CompositorDumpImages() + { + FnTable.CompositorDumpImages(); + } + public bool ShouldAppRenderWithLowResources() + { + bool result = FnTable.ShouldAppRenderWithLowResources(); + return result; + } + public void ForceInterleavedReprojectionOn(bool bOverride) + { + FnTable.ForceInterleavedReprojectionOn(bOverride); + } + public void ForceReconnectProcess() + { + FnTable.ForceReconnectProcess(); + } + public void SuspendRendering(bool bSuspend) + { + FnTable.SuspendRendering(bSuspend); + } + public EVRCompositorError RequestScreenshot(EVRScreenshotType type,string pchDestinationFileName,string pchVRDestinationFileName) + { + EVRCompositorError result = FnTable.RequestScreenshot(type,pchDestinationFileName,pchVRDestinationFileName); + return result; + } + public EVRScreenshotType GetCurrentScreenshotType() + { + EVRScreenshotType result = FnTable.GetCurrentScreenshotType(); + return result; + } + public EVRCompositorError GetMirrorTextureD3D11(EVREye eEye,IntPtr pD3D11DeviceOrResource,ref IntPtr ppD3D11ShaderResourceView) + { + EVRCompositorError result = FnTable.GetMirrorTextureD3D11(eEye,pD3D11DeviceOrResource,ref ppD3D11ShaderResourceView); + return result; + } + public EVRCompositorError GetMirrorTextureGL(EVREye eEye,ref uint pglTextureId,IntPtr pglSharedTextureHandle) + { + pglTextureId = 0; + EVRCompositorError result = FnTable.GetMirrorTextureGL(eEye,ref pglTextureId,pglSharedTextureHandle); + return result; + } + public bool ReleaseSharedGLTexture(uint glTextureId,IntPtr glSharedTextureHandle) + { + bool result = FnTable.ReleaseSharedGLTexture(glTextureId,glSharedTextureHandle); + return result; + } + public void LockGLSharedTextureForAccess(IntPtr glSharedTextureHandle) + { + FnTable.LockGLSharedTextureForAccess(glSharedTextureHandle); + } + public void UnlockGLSharedTextureForAccess(IntPtr glSharedTextureHandle) + { + FnTable.UnlockGLSharedTextureForAccess(glSharedTextureHandle); + } +} + + +public class CVROverlay +{ + IVROverlay FnTable; + internal CVROverlay(IntPtr pInterface) + { + FnTable = (IVROverlay)Marshal.PtrToStructure(pInterface, typeof(IVROverlay)); + } + public EVROverlayError FindOverlay(string pchOverlayKey,ref ulong pOverlayHandle) + { + pOverlayHandle = 0; + EVROverlayError result = FnTable.FindOverlay(pchOverlayKey,ref pOverlayHandle); + return result; + } + public EVROverlayError CreateOverlay(string pchOverlayKey,string pchOverlayFriendlyName,ref ulong pOverlayHandle) + { + pOverlayHandle = 0; + EVROverlayError result = FnTable.CreateOverlay(pchOverlayKey,pchOverlayFriendlyName,ref pOverlayHandle); + return result; + } + public EVROverlayError DestroyOverlay(ulong ulOverlayHandle) + { + EVROverlayError result = FnTable.DestroyOverlay(ulOverlayHandle); + return result; + } + public EVROverlayError SetHighQualityOverlay(ulong ulOverlayHandle) + { + EVROverlayError result = FnTable.SetHighQualityOverlay(ulOverlayHandle); + return result; + } + public ulong GetHighQualityOverlay() + { + ulong result = FnTable.GetHighQualityOverlay(); + return result; + } + public uint GetOverlayKey(ulong ulOverlayHandle,System.Text.StringBuilder pchValue,uint unBufferSize,ref EVROverlayError pError) + { + uint result = FnTable.GetOverlayKey(ulOverlayHandle,pchValue,unBufferSize,ref pError); + return result; + } + public uint GetOverlayName(ulong ulOverlayHandle,System.Text.StringBuilder pchValue,uint unBufferSize,ref EVROverlayError pError) + { + uint result = FnTable.GetOverlayName(ulOverlayHandle,pchValue,unBufferSize,ref pError); + return result; + } + public EVROverlayError GetOverlayImageData(ulong ulOverlayHandle,IntPtr pvBuffer,uint unBufferSize,ref uint punWidth,ref uint punHeight) + { + punWidth = 0; + punHeight = 0; + EVROverlayError result = FnTable.GetOverlayImageData(ulOverlayHandle,pvBuffer,unBufferSize,ref punWidth,ref punHeight); + return result; + } + public string GetOverlayErrorNameFromEnum(EVROverlayError error) + { + IntPtr result = FnTable.GetOverlayErrorNameFromEnum(error); + return Marshal.PtrToStringAnsi(result); + } + public EVROverlayError SetOverlayRenderingPid(ulong ulOverlayHandle,uint unPID) + { + EVROverlayError result = FnTable.SetOverlayRenderingPid(ulOverlayHandle,unPID); + return result; + } + public uint GetOverlayRenderingPid(ulong ulOverlayHandle) + { + uint result = FnTable.GetOverlayRenderingPid(ulOverlayHandle); + return result; + } + public EVROverlayError SetOverlayFlag(ulong ulOverlayHandle,VROverlayFlags eOverlayFlag,bool bEnabled) + { + EVROverlayError result = FnTable.SetOverlayFlag(ulOverlayHandle,eOverlayFlag,bEnabled); + return result; + } + public EVROverlayError GetOverlayFlag(ulong ulOverlayHandle,VROverlayFlags eOverlayFlag,ref bool pbEnabled) + { + pbEnabled = false; + EVROverlayError result = FnTable.GetOverlayFlag(ulOverlayHandle,eOverlayFlag,ref pbEnabled); + return result; + } + public EVROverlayError SetOverlayColor(ulong ulOverlayHandle,float fRed,float fGreen,float fBlue) + { + EVROverlayError result = FnTable.SetOverlayColor(ulOverlayHandle,fRed,fGreen,fBlue); + return result; + } + public EVROverlayError GetOverlayColor(ulong ulOverlayHandle,ref float pfRed,ref float pfGreen,ref float pfBlue) + { + pfRed = 0; + pfGreen = 0; + pfBlue = 0; + EVROverlayError result = FnTable.GetOverlayColor(ulOverlayHandle,ref pfRed,ref pfGreen,ref pfBlue); + return result; + } + public EVROverlayError SetOverlayAlpha(ulong ulOverlayHandle,float fAlpha) + { + EVROverlayError result = FnTable.SetOverlayAlpha(ulOverlayHandle,fAlpha); + return result; + } + public EVROverlayError GetOverlayAlpha(ulong ulOverlayHandle,ref float pfAlpha) + { + pfAlpha = 0; + EVROverlayError result = FnTable.GetOverlayAlpha(ulOverlayHandle,ref pfAlpha); + return result; + } + public EVROverlayError SetOverlayWidthInMeters(ulong ulOverlayHandle,float fWidthInMeters) + { + EVROverlayError result = FnTable.SetOverlayWidthInMeters(ulOverlayHandle,fWidthInMeters); + return result; + } + public EVROverlayError GetOverlayWidthInMeters(ulong ulOverlayHandle,ref float pfWidthInMeters) + { + pfWidthInMeters = 0; + EVROverlayError result = FnTable.GetOverlayWidthInMeters(ulOverlayHandle,ref pfWidthInMeters); + return result; + } + public EVROverlayError SetOverlayAutoCurveDistanceRangeInMeters(ulong ulOverlayHandle,float fMinDistanceInMeters,float fMaxDistanceInMeters) + { + EVROverlayError result = FnTable.SetOverlayAutoCurveDistanceRangeInMeters(ulOverlayHandle,fMinDistanceInMeters,fMaxDistanceInMeters); + return result; + } + public EVROverlayError GetOverlayAutoCurveDistanceRangeInMeters(ulong ulOverlayHandle,ref float pfMinDistanceInMeters,ref float pfMaxDistanceInMeters) + { + pfMinDistanceInMeters = 0; + pfMaxDistanceInMeters = 0; + EVROverlayError result = FnTable.GetOverlayAutoCurveDistanceRangeInMeters(ulOverlayHandle,ref pfMinDistanceInMeters,ref pfMaxDistanceInMeters); + return result; + } + public EVROverlayError SetOverlayTextureColorSpace(ulong ulOverlayHandle,EColorSpace eTextureColorSpace) + { + EVROverlayError result = FnTable.SetOverlayTextureColorSpace(ulOverlayHandle,eTextureColorSpace); + return result; + } + public EVROverlayError GetOverlayTextureColorSpace(ulong ulOverlayHandle,ref EColorSpace peTextureColorSpace) + { + EVROverlayError result = FnTable.GetOverlayTextureColorSpace(ulOverlayHandle,ref peTextureColorSpace); + return result; + } + public EVROverlayError SetOverlayTextureBounds(ulong ulOverlayHandle,ref VRTextureBounds_t pOverlayTextureBounds) + { + EVROverlayError result = FnTable.SetOverlayTextureBounds(ulOverlayHandle,ref pOverlayTextureBounds); + return result; + } + public EVROverlayError GetOverlayTextureBounds(ulong ulOverlayHandle,ref VRTextureBounds_t pOverlayTextureBounds) + { + EVROverlayError result = FnTable.GetOverlayTextureBounds(ulOverlayHandle,ref pOverlayTextureBounds); + return result; + } + public EVROverlayError GetOverlayTransformType(ulong ulOverlayHandle,ref VROverlayTransformType peTransformType) + { + EVROverlayError result = FnTable.GetOverlayTransformType(ulOverlayHandle,ref peTransformType); + return result; + } + public EVROverlayError SetOverlayTransformAbsolute(ulong ulOverlayHandle,ETrackingUniverseOrigin eTrackingOrigin,ref HmdMatrix34_t pmatTrackingOriginToOverlayTransform) + { + EVROverlayError result = FnTable.SetOverlayTransformAbsolute(ulOverlayHandle,eTrackingOrigin,ref pmatTrackingOriginToOverlayTransform); + return result; + } + public EVROverlayError GetOverlayTransformAbsolute(ulong ulOverlayHandle,ref ETrackingUniverseOrigin peTrackingOrigin,ref HmdMatrix34_t pmatTrackingOriginToOverlayTransform) + { + EVROverlayError result = FnTable.GetOverlayTransformAbsolute(ulOverlayHandle,ref peTrackingOrigin,ref pmatTrackingOriginToOverlayTransform); + return result; + } + public EVROverlayError SetOverlayTransformTrackedDeviceRelative(ulong ulOverlayHandle,uint unTrackedDevice,ref HmdMatrix34_t pmatTrackedDeviceToOverlayTransform) + { + EVROverlayError result = FnTable.SetOverlayTransformTrackedDeviceRelative(ulOverlayHandle,unTrackedDevice,ref pmatTrackedDeviceToOverlayTransform); + return result; + } + public EVROverlayError GetOverlayTransformTrackedDeviceRelative(ulong ulOverlayHandle,ref uint punTrackedDevice,ref HmdMatrix34_t pmatTrackedDeviceToOverlayTransform) + { + punTrackedDevice = 0; + EVROverlayError result = FnTable.GetOverlayTransformTrackedDeviceRelative(ulOverlayHandle,ref punTrackedDevice,ref pmatTrackedDeviceToOverlayTransform); + return result; + } + public EVROverlayError SetOverlayTransformTrackedDeviceComponent(ulong ulOverlayHandle,uint unDeviceIndex,string pchComponentName) + { + EVROverlayError result = FnTable.SetOverlayTransformTrackedDeviceComponent(ulOverlayHandle,unDeviceIndex,pchComponentName); + return result; + } + public EVROverlayError GetOverlayTransformTrackedDeviceComponent(ulong ulOverlayHandle,ref uint punDeviceIndex,string pchComponentName,uint unComponentNameSize) + { + punDeviceIndex = 0; + EVROverlayError result = FnTable.GetOverlayTransformTrackedDeviceComponent(ulOverlayHandle,ref punDeviceIndex,pchComponentName,unComponentNameSize); + return result; + } + public EVROverlayError ShowOverlay(ulong ulOverlayHandle) + { + EVROverlayError result = FnTable.ShowOverlay(ulOverlayHandle); + return result; + } + public EVROverlayError HideOverlay(ulong ulOverlayHandle) + { + EVROverlayError result = FnTable.HideOverlay(ulOverlayHandle); + return result; + } + public bool IsOverlayVisible(ulong ulOverlayHandle) + { + bool result = FnTable.IsOverlayVisible(ulOverlayHandle); + return result; + } + public EVROverlayError GetTransformForOverlayCoordinates(ulong ulOverlayHandle,ETrackingUniverseOrigin eTrackingOrigin,HmdVector2_t coordinatesInOverlay,ref HmdMatrix34_t pmatTransform) + { + EVROverlayError result = FnTable.GetTransformForOverlayCoordinates(ulOverlayHandle,eTrackingOrigin,coordinatesInOverlay,ref pmatTransform); + return result; + } + public bool PollNextOverlayEvent(ulong ulOverlayHandle,ref VREvent_t pEvent,uint uncbVREvent) + { + bool result = FnTable.PollNextOverlayEvent(ulOverlayHandle,ref pEvent,uncbVREvent); + return result; + } + public EVROverlayError GetOverlayInputMethod(ulong ulOverlayHandle,ref VROverlayInputMethod peInputMethod) + { + EVROverlayError result = FnTable.GetOverlayInputMethod(ulOverlayHandle,ref peInputMethod); + return result; + } + public EVROverlayError SetOverlayInputMethod(ulong ulOverlayHandle,VROverlayInputMethod eInputMethod) + { + EVROverlayError result = FnTable.SetOverlayInputMethod(ulOverlayHandle,eInputMethod); + return result; + } + public EVROverlayError GetOverlayMouseScale(ulong ulOverlayHandle,ref HmdVector2_t pvecMouseScale) + { + EVROverlayError result = FnTable.GetOverlayMouseScale(ulOverlayHandle,ref pvecMouseScale); + return result; + } + public EVROverlayError SetOverlayMouseScale(ulong ulOverlayHandle,ref HmdVector2_t pvecMouseScale) + { + EVROverlayError result = FnTable.SetOverlayMouseScale(ulOverlayHandle,ref pvecMouseScale); + return result; + } + public bool ComputeOverlayIntersection(ulong ulOverlayHandle,ref VROverlayIntersectionParams_t pParams,ref VROverlayIntersectionResults_t pResults) + { + bool result = FnTable.ComputeOverlayIntersection(ulOverlayHandle,ref pParams,ref pResults); + return result; + } + public bool HandleControllerOverlayInteractionAsMouse(ulong ulOverlayHandle,uint unControllerDeviceIndex) + { + bool result = FnTable.HandleControllerOverlayInteractionAsMouse(ulOverlayHandle,unControllerDeviceIndex); + return result; + } + public bool IsHoverTargetOverlay(ulong ulOverlayHandle) + { + bool result = FnTable.IsHoverTargetOverlay(ulOverlayHandle); + return result; + } + public ulong GetGamepadFocusOverlay() + { + ulong result = FnTable.GetGamepadFocusOverlay(); + return result; + } + public EVROverlayError SetGamepadFocusOverlay(ulong ulNewFocusOverlay) + { + EVROverlayError result = FnTable.SetGamepadFocusOverlay(ulNewFocusOverlay); + return result; + } + public EVROverlayError SetOverlayNeighbor(EOverlayDirection eDirection,ulong ulFrom,ulong ulTo) + { + EVROverlayError result = FnTable.SetOverlayNeighbor(eDirection,ulFrom,ulTo); + return result; + } + public EVROverlayError MoveGamepadFocusToNeighbor(EOverlayDirection eDirection,ulong ulFrom) + { + EVROverlayError result = FnTable.MoveGamepadFocusToNeighbor(eDirection,ulFrom); + return result; + } + public EVROverlayError SetOverlayTexture(ulong ulOverlayHandle,ref Texture_t pTexture) + { + EVROverlayError result = FnTable.SetOverlayTexture(ulOverlayHandle,ref pTexture); + return result; + } + public EVROverlayError ClearOverlayTexture(ulong ulOverlayHandle) + { + EVROverlayError result = FnTable.ClearOverlayTexture(ulOverlayHandle); + return result; + } + public EVROverlayError SetOverlayRaw(ulong ulOverlayHandle,IntPtr pvBuffer,uint unWidth,uint unHeight,uint unDepth) + { + EVROverlayError result = FnTable.SetOverlayRaw(ulOverlayHandle,pvBuffer,unWidth,unHeight,unDepth); + return result; + } + public EVROverlayError SetOverlayFromFile(ulong ulOverlayHandle,string pchFilePath) + { + EVROverlayError result = FnTable.SetOverlayFromFile(ulOverlayHandle,pchFilePath); + return result; + } + public EVROverlayError GetOverlayTexture(ulong ulOverlayHandle,ref IntPtr pNativeTextureHandle,IntPtr pNativeTextureRef,ref uint pWidth,ref uint pHeight,ref uint pNativeFormat,ref EGraphicsAPIConvention pAPI,ref EColorSpace pColorSpace) + { + pWidth = 0; + pHeight = 0; + pNativeFormat = 0; + EVROverlayError result = FnTable.GetOverlayTexture(ulOverlayHandle,ref pNativeTextureHandle,pNativeTextureRef,ref pWidth,ref pHeight,ref pNativeFormat,ref pAPI,ref pColorSpace); + return result; + } + public EVROverlayError ReleaseNativeOverlayHandle(ulong ulOverlayHandle,IntPtr pNativeTextureHandle) + { + EVROverlayError result = FnTable.ReleaseNativeOverlayHandle(ulOverlayHandle,pNativeTextureHandle); + return result; + } + public EVROverlayError GetOverlayTextureSize(ulong ulOverlayHandle,ref uint pWidth,ref uint pHeight) + { + pWidth = 0; + pHeight = 0; + EVROverlayError result = FnTable.GetOverlayTextureSize(ulOverlayHandle,ref pWidth,ref pHeight); + return result; + } + public EVROverlayError CreateDashboardOverlay(string pchOverlayKey,string pchOverlayFriendlyName,ref ulong pMainHandle,ref ulong pThumbnailHandle) + { + pMainHandle = 0; + pThumbnailHandle = 0; + EVROverlayError result = FnTable.CreateDashboardOverlay(pchOverlayKey,pchOverlayFriendlyName,ref pMainHandle,ref pThumbnailHandle); + return result; + } + public bool IsDashboardVisible() + { + bool result = FnTable.IsDashboardVisible(); + return result; + } + public bool IsActiveDashboardOverlay(ulong ulOverlayHandle) + { + bool result = FnTable.IsActiveDashboardOverlay(ulOverlayHandle); + return result; + } + public EVROverlayError SetDashboardOverlaySceneProcess(ulong ulOverlayHandle,uint unProcessId) + { + EVROverlayError result = FnTable.SetDashboardOverlaySceneProcess(ulOverlayHandle,unProcessId); + return result; + } + public EVROverlayError GetDashboardOverlaySceneProcess(ulong ulOverlayHandle,ref uint punProcessId) + { + punProcessId = 0; + EVROverlayError result = FnTable.GetDashboardOverlaySceneProcess(ulOverlayHandle,ref punProcessId); + return result; + } + public void ShowDashboard(string pchOverlayToShow) + { + FnTable.ShowDashboard(pchOverlayToShow); + } + public uint GetPrimaryDashboardDevice() + { + uint result = FnTable.GetPrimaryDashboardDevice(); + return result; + } + public EVROverlayError ShowKeyboard(int eInputMode,int eLineInputMode,string pchDescription,uint unCharMax,string pchExistingText,bool bUseMinimalMode,ulong uUserValue) + { + EVROverlayError result = FnTable.ShowKeyboard(eInputMode,eLineInputMode,pchDescription,unCharMax,pchExistingText,bUseMinimalMode,uUserValue); + return result; + } + public EVROverlayError ShowKeyboardForOverlay(ulong ulOverlayHandle,int eInputMode,int eLineInputMode,string pchDescription,uint unCharMax,string pchExistingText,bool bUseMinimalMode,ulong uUserValue) + { + EVROverlayError result = FnTable.ShowKeyboardForOverlay(ulOverlayHandle,eInputMode,eLineInputMode,pchDescription,unCharMax,pchExistingText,bUseMinimalMode,uUserValue); + return result; + } + public uint GetKeyboardText(System.Text.StringBuilder pchText,uint cchText) + { + uint result = FnTable.GetKeyboardText(pchText,cchText); + return result; + } + public void HideKeyboard() + { + FnTable.HideKeyboard(); + } + public void SetKeyboardTransformAbsolute(ETrackingUniverseOrigin eTrackingOrigin,ref HmdMatrix34_t pmatTrackingOriginToKeyboardTransform) + { + FnTable.SetKeyboardTransformAbsolute(eTrackingOrigin,ref pmatTrackingOriginToKeyboardTransform); + } + public void SetKeyboardPositionForOverlay(ulong ulOverlayHandle,HmdRect2_t avoidRect) + { + FnTable.SetKeyboardPositionForOverlay(ulOverlayHandle,avoidRect); + } +} + + +public class CVRRenderModels +{ + IVRRenderModels FnTable; + internal CVRRenderModels(IntPtr pInterface) + { + FnTable = (IVRRenderModels)Marshal.PtrToStructure(pInterface, typeof(IVRRenderModels)); + } + public EVRRenderModelError LoadRenderModel_Async(string pchRenderModelName,ref IntPtr ppRenderModel) + { + EVRRenderModelError result = FnTable.LoadRenderModel_Async(pchRenderModelName,ref ppRenderModel); + return result; + } + public void FreeRenderModel(IntPtr pRenderModel) + { + FnTable.FreeRenderModel(pRenderModel); + } + public EVRRenderModelError LoadTexture_Async(int textureId,ref IntPtr ppTexture) + { + EVRRenderModelError result = FnTable.LoadTexture_Async(textureId,ref ppTexture); + return result; + } + public void FreeTexture(IntPtr pTexture) + { + FnTable.FreeTexture(pTexture); + } + public EVRRenderModelError LoadTextureD3D11_Async(int textureId,IntPtr pD3D11Device,ref IntPtr ppD3D11Texture2D) + { + EVRRenderModelError result = FnTable.LoadTextureD3D11_Async(textureId,pD3D11Device,ref ppD3D11Texture2D); + return result; + } + public EVRRenderModelError LoadIntoTextureD3D11_Async(int textureId,IntPtr pDstTexture) + { + EVRRenderModelError result = FnTable.LoadIntoTextureD3D11_Async(textureId,pDstTexture); + return result; + } + public void FreeTextureD3D11(IntPtr pD3D11Texture2D) + { + FnTable.FreeTextureD3D11(pD3D11Texture2D); + } + public uint GetRenderModelName(uint unRenderModelIndex,System.Text.StringBuilder pchRenderModelName,uint unRenderModelNameLen) + { + uint result = FnTable.GetRenderModelName(unRenderModelIndex,pchRenderModelName,unRenderModelNameLen); + return result; + } + public uint GetRenderModelCount() + { + uint result = FnTable.GetRenderModelCount(); + return result; + } + public uint GetComponentCount(string pchRenderModelName) + { + uint result = FnTable.GetComponentCount(pchRenderModelName); + return result; + } + public uint GetComponentName(string pchRenderModelName,uint unComponentIndex,System.Text.StringBuilder pchComponentName,uint unComponentNameLen) + { + uint result = FnTable.GetComponentName(pchRenderModelName,unComponentIndex,pchComponentName,unComponentNameLen); + return result; + } + public ulong GetComponentButtonMask(string pchRenderModelName,string pchComponentName) + { + ulong result = FnTable.GetComponentButtonMask(pchRenderModelName,pchComponentName); + return result; + } + public uint GetComponentRenderModelName(string pchRenderModelName,string pchComponentName,System.Text.StringBuilder pchComponentRenderModelName,uint unComponentRenderModelNameLen) + { + uint result = FnTable.GetComponentRenderModelName(pchRenderModelName,pchComponentName,pchComponentRenderModelName,unComponentRenderModelNameLen); + return result; + } + public bool GetComponentState(string pchRenderModelName,string pchComponentName,ref VRControllerState_t pControllerState,ref RenderModel_ControllerMode_State_t pState,ref RenderModel_ComponentState_t pComponentState) + { + bool result = FnTable.GetComponentState(pchRenderModelName,pchComponentName,ref pControllerState,ref pState,ref pComponentState); + return result; + } + public bool RenderModelHasComponent(string pchRenderModelName,string pchComponentName) + { + bool result = FnTable.RenderModelHasComponent(pchRenderModelName,pchComponentName); + return result; + } + public uint GetRenderModelThumbnailURL(string pchRenderModelName,System.Text.StringBuilder pchThumbnailURL,uint unThumbnailURLLen,ref EVRRenderModelError peError) + { + uint result = FnTable.GetRenderModelThumbnailURL(pchRenderModelName,pchThumbnailURL,unThumbnailURLLen,ref peError); + return result; + } + public uint GetRenderModelOriginalPath(string pchRenderModelName,System.Text.StringBuilder pchOriginalPath,uint unOriginalPathLen,ref EVRRenderModelError peError) + { + uint result = FnTable.GetRenderModelOriginalPath(pchRenderModelName,pchOriginalPath,unOriginalPathLen,ref peError); + return result; + } + public string GetRenderModelErrorNameFromEnum(EVRRenderModelError error) + { + IntPtr result = FnTable.GetRenderModelErrorNameFromEnum(error); + return Marshal.PtrToStringAnsi(result); + } +} + + +public class CVRNotifications +{ + IVRNotifications FnTable; + internal CVRNotifications(IntPtr pInterface) + { + FnTable = (IVRNotifications)Marshal.PtrToStructure(pInterface, typeof(IVRNotifications)); + } + public EVRNotificationError CreateNotification(ulong ulOverlayHandle,ulong ulUserValue,EVRNotificationType type,string pchText,EVRNotificationStyle style,ref NotificationBitmap_t pImage,ref uint pNotificationId) + { + pNotificationId = 0; + EVRNotificationError result = FnTable.CreateNotification(ulOverlayHandle,ulUserValue,type,pchText,style,ref pImage,ref pNotificationId); + return result; + } + public EVRNotificationError RemoveNotification(uint notificationId) + { + EVRNotificationError result = FnTable.RemoveNotification(notificationId); + return result; + } +} + + +public class CVRSettings +{ + IVRSettings FnTable; + internal CVRSettings(IntPtr pInterface) + { + FnTable = (IVRSettings)Marshal.PtrToStructure(pInterface, typeof(IVRSettings)); + } + public string GetSettingsErrorNameFromEnum(EVRSettingsError eError) + { + IntPtr result = FnTable.GetSettingsErrorNameFromEnum(eError); + return Marshal.PtrToStringAnsi(result); + } + public bool Sync(bool bForce,ref EVRSettingsError peError) + { + bool result = FnTable.Sync(bForce,ref peError); + return result; + } + public bool GetBool(string pchSection,string pchSettingsKey,bool bDefaultValue,ref EVRSettingsError peError) + { + bool result = FnTable.GetBool(pchSection,pchSettingsKey,bDefaultValue,ref peError); + return result; + } + public void SetBool(string pchSection,string pchSettingsKey,bool bValue,ref EVRSettingsError peError) + { + FnTable.SetBool(pchSection,pchSettingsKey,bValue,ref peError); + } + public int GetInt32(string pchSection,string pchSettingsKey,int nDefaultValue,ref EVRSettingsError peError) + { + int result = FnTable.GetInt32(pchSection,pchSettingsKey,nDefaultValue,ref peError); + return result; + } + public void SetInt32(string pchSection,string pchSettingsKey,int nValue,ref EVRSettingsError peError) + { + FnTable.SetInt32(pchSection,pchSettingsKey,nValue,ref peError); + } + public float GetFloat(string pchSection,string pchSettingsKey,float flDefaultValue,ref EVRSettingsError peError) + { + float result = FnTable.GetFloat(pchSection,pchSettingsKey,flDefaultValue,ref peError); + return result; + } + public void SetFloat(string pchSection,string pchSettingsKey,float flValue,ref EVRSettingsError peError) + { + FnTable.SetFloat(pchSection,pchSettingsKey,flValue,ref peError); + } + public void GetString(string pchSection,string pchSettingsKey,string pchValue,uint unValueLen,string pchDefaultValue,ref EVRSettingsError peError) + { + FnTable.GetString(pchSection,pchSettingsKey,pchValue,unValueLen,pchDefaultValue,ref peError); + } + public void SetString(string pchSection,string pchSettingsKey,string pchValue,ref EVRSettingsError peError) + { + FnTable.SetString(pchSection,pchSettingsKey,pchValue,ref peError); + } + public void RemoveSection(string pchSection,ref EVRSettingsError peError) + { + FnTable.RemoveSection(pchSection,ref peError); + } + public void RemoveKeyInSection(string pchSection,string pchSettingsKey,ref EVRSettingsError peError) + { + FnTable.RemoveKeyInSection(pchSection,pchSettingsKey,ref peError); + } +} + + +public class CVRScreenshots +{ + IVRScreenshots FnTable; + internal CVRScreenshots(IntPtr pInterface) + { + FnTable = (IVRScreenshots)Marshal.PtrToStructure(pInterface, typeof(IVRScreenshots)); + } + public EVRScreenshotError RequestScreenshot(ref uint pOutScreenshotHandle,EVRScreenshotType type,string pchPreviewFilename,string pchVRFilename) + { + pOutScreenshotHandle = 0; + EVRScreenshotError result = FnTable.RequestScreenshot(ref pOutScreenshotHandle,type,pchPreviewFilename,pchVRFilename); + return result; + } + public EVRScreenshotError HookScreenshot(EVRScreenshotType [] pSupportedTypes) + { + EVRScreenshotError result = FnTable.HookScreenshot(pSupportedTypes,(int) pSupportedTypes.Length); + return result; + } + public EVRScreenshotType GetScreenshotPropertyType(uint screenshotHandle,ref EVRScreenshotError pError) + { + EVRScreenshotType result = FnTable.GetScreenshotPropertyType(screenshotHandle,ref pError); + return result; + } + public uint GetScreenshotPropertyFilename(uint screenshotHandle,EVRScreenshotPropertyFilenames filenameType,System.Text.StringBuilder pchFilename,uint cchFilename,ref EVRScreenshotError pError) + { + uint result = FnTable.GetScreenshotPropertyFilename(screenshotHandle,filenameType,pchFilename,cchFilename,ref pError); + return result; + } + public EVRScreenshotError UpdateScreenshotProgress(uint screenshotHandle,float flProgress) + { + EVRScreenshotError result = FnTable.UpdateScreenshotProgress(screenshotHandle,flProgress); + return result; + } + public EVRScreenshotError TakeStereoScreenshot(ref uint pOutScreenshotHandle,string pchPreviewFilename,string pchVRFilename) + { + pOutScreenshotHandle = 0; + EVRScreenshotError result = FnTable.TakeStereoScreenshot(ref pOutScreenshotHandle,pchPreviewFilename,pchVRFilename); + return result; + } + public EVRScreenshotError SubmitScreenshot(uint screenshotHandle,EVRScreenshotType type,string pchSourcePreviewFilename,string pchSourceVRFilename) + { + EVRScreenshotError result = FnTable.SubmitScreenshot(screenshotHandle,type,pchSourcePreviewFilename,pchSourceVRFilename); + return result; + } +} + + +public class OpenVRInterop +{ + [DllImportAttribute("openvr_api", EntryPoint = "VR_InitInternal")] + internal static extern uint InitInternal(ref EVRInitError peError, EVRApplicationType eApplicationType); + [DllImportAttribute("openvr_api", EntryPoint = "VR_ShutdownInternal")] + internal static extern void ShutdownInternal(); + [DllImportAttribute("openvr_api", EntryPoint = "VR_IsHmdPresent")] + internal static extern bool IsHmdPresent(); + [DllImportAttribute("openvr_api", EntryPoint = "VR_IsRuntimeInstalled")] + internal static extern bool IsRuntimeInstalled(); + [DllImportAttribute("openvr_api", EntryPoint = "VR_GetStringForHmdError")] + internal static extern IntPtr GetStringForHmdError(EVRInitError error); + [DllImportAttribute("openvr_api", EntryPoint = "VR_GetGenericInterface")] + internal static extern IntPtr GetGenericInterface([In, MarshalAs(UnmanagedType.LPStr)] string pchInterfaceVersion, ref EVRInitError peError); + [DllImportAttribute("openvr_api", EntryPoint = "VR_IsInterfaceVersionValid")] + internal static extern bool IsInterfaceVersionValid([In, MarshalAs(UnmanagedType.LPStr)] string pchInterfaceVersion); + [DllImportAttribute("openvr_api", EntryPoint = "VR_GetInitToken")] + internal static extern uint GetInitToken(); +} + + +public enum EVREye +{ + Eye_Left = 0, + Eye_Right = 1, +} +public enum EGraphicsAPIConvention +{ + API_DirectX = 0, + API_OpenGL = 1, +} +public enum EColorSpace +{ + Auto = 0, + Gamma = 1, + Linear = 2, +} +public enum ETrackingResult +{ + Uninitialized = 1, + Calibrating_InProgress = 100, + Calibrating_OutOfRange = 101, + Running_OK = 200, + Running_OutOfRange = 201, +} +public enum ETrackedDeviceClass +{ + Invalid = 0, + HMD = 1, + Controller = 2, + TrackingReference = 4, + Other = 1000, +} +public enum ETrackedControllerRole +{ + Invalid = 0, + LeftHand = 1, + RightHand = 2, +} +public enum ETrackingUniverseOrigin +{ + TrackingUniverseSeated = 0, + TrackingUniverseStanding = 1, + TrackingUniverseRawAndUncalibrated = 2, +} +public enum ETrackedDeviceProperty +{ + Prop_TrackingSystemName_String = 1000, + Prop_ModelNumber_String = 1001, + Prop_SerialNumber_String = 1002, + Prop_RenderModelName_String = 1003, + Prop_WillDriftInYaw_Bool = 1004, + Prop_ManufacturerName_String = 1005, + Prop_TrackingFirmwareVersion_String = 1006, + Prop_HardwareRevision_String = 1007, + Prop_AllWirelessDongleDescriptions_String = 1008, + Prop_ConnectedWirelessDongle_String = 1009, + Prop_DeviceIsWireless_Bool = 1010, + Prop_DeviceIsCharging_Bool = 1011, + Prop_DeviceBatteryPercentage_Float = 1012, + Prop_StatusDisplayTransform_Matrix34 = 1013, + Prop_Firmware_UpdateAvailable_Bool = 1014, + Prop_Firmware_ManualUpdate_Bool = 1015, + Prop_Firmware_ManualUpdateURL_String = 1016, + Prop_HardwareRevision_Uint64 = 1017, + Prop_FirmwareVersion_Uint64 = 1018, + Prop_FPGAVersion_Uint64 = 1019, + Prop_VRCVersion_Uint64 = 1020, + Prop_RadioVersion_Uint64 = 1021, + Prop_DongleVersion_Uint64 = 1022, + Prop_BlockServerShutdown_Bool = 1023, + Prop_CanUnifyCoordinateSystemWithHmd_Bool = 1024, + Prop_ContainsProximitySensor_Bool = 1025, + Prop_DeviceProvidesBatteryStatus_Bool = 1026, + Prop_DeviceCanPowerOff_Bool = 1027, + Prop_Firmware_ProgrammingTarget_String = 1028, + Prop_DeviceClass_Int32 = 1029, + Prop_HasCamera_Bool = 1030, + Prop_DriverVersion_String = 1031, + Prop_Firmware_ForceUpdateRequired_Bool = 1032, + Prop_ReportsTimeSinceVSync_Bool = 2000, + Prop_SecondsFromVsyncToPhotons_Float = 2001, + Prop_DisplayFrequency_Float = 2002, + Prop_UserIpdMeters_Float = 2003, + Prop_CurrentUniverseId_Uint64 = 2004, + Prop_PreviousUniverseId_Uint64 = 2005, + Prop_DisplayFirmwareVersion_Uint64 = 2006, + Prop_IsOnDesktop_Bool = 2007, + Prop_DisplayMCType_Int32 = 2008, + Prop_DisplayMCOffset_Float = 2009, + Prop_DisplayMCScale_Float = 2010, + Prop_EdidVendorID_Int32 = 2011, + Prop_DisplayMCImageLeft_String = 2012, + Prop_DisplayMCImageRight_String = 2013, + Prop_DisplayGCBlackClamp_Float = 2014, + Prop_EdidProductID_Int32 = 2015, + Prop_CameraToHeadTransform_Matrix34 = 2016, + Prop_DisplayGCType_Int32 = 2017, + Prop_DisplayGCOffset_Float = 2018, + Prop_DisplayGCScale_Float = 2019, + Prop_DisplayGCPrescale_Float = 2020, + Prop_DisplayGCImage_String = 2021, + Prop_LensCenterLeftU_Float = 2022, + Prop_LensCenterLeftV_Float = 2023, + Prop_LensCenterRightU_Float = 2024, + Prop_LensCenterRightV_Float = 2025, + Prop_UserHeadToEyeDepthMeters_Float = 2026, + Prop_CameraFirmwareVersion_Uint64 = 2027, + Prop_CameraFirmwareDescription_String = 2028, + Prop_DisplayFPGAVersion_Uint64 = 2029, + Prop_DisplayBootloaderVersion_Uint64 = 2030, + Prop_DisplayHardwareVersion_Uint64 = 2031, + Prop_AudioFirmwareVersion_Uint64 = 2032, + Prop_CameraCompatibilityMode_Int32 = 2033, + Prop_ScreenshotHorizontalFieldOfViewDegrees_Float = 2034, + Prop_ScreenshotVerticalFieldOfViewDegrees_Float = 2035, + Prop_DisplaySuppressed_Bool = 2036, + Prop_AttachedDeviceId_String = 3000, + Prop_SupportedButtons_Uint64 = 3001, + Prop_Axis0Type_Int32 = 3002, + Prop_Axis1Type_Int32 = 3003, + Prop_Axis2Type_Int32 = 3004, + Prop_Axis3Type_Int32 = 3005, + Prop_Axis4Type_Int32 = 3006, + Prop_FieldOfViewLeftDegrees_Float = 4000, + Prop_FieldOfViewRightDegrees_Float = 4001, + Prop_FieldOfViewTopDegrees_Float = 4002, + Prop_FieldOfViewBottomDegrees_Float = 4003, + Prop_TrackingRangeMinimumMeters_Float = 4004, + Prop_TrackingRangeMaximumMeters_Float = 4005, + Prop_ModeLabel_String = 4006, + Prop_VendorSpecific_Reserved_Start = 10000, + Prop_VendorSpecific_Reserved_End = 10999, +} +public enum ETrackedPropertyError +{ + TrackedProp_Success = 0, + TrackedProp_WrongDataType = 1, + TrackedProp_WrongDeviceClass = 2, + TrackedProp_BufferTooSmall = 3, + TrackedProp_UnknownProperty = 4, + TrackedProp_InvalidDevice = 5, + TrackedProp_CouldNotContactServer = 6, + TrackedProp_ValueNotProvidedByDevice = 7, + TrackedProp_StringExceedsMaximumLength = 8, + TrackedProp_NotYetAvailable = 9, +} +public enum EVRSubmitFlags +{ + Submit_Default = 0, + Submit_LensDistortionAlreadyApplied = 1, + Submit_GlRenderBuffer = 2, +} +public enum EVRState +{ + Undefined = -1, + Off = 0, + Searching = 1, + Searching_Alert = 2, + Ready = 3, + Ready_Alert = 4, + NotReady = 5, + Standby = 6, +} +public enum EVREventType +{ + VREvent_None = 0, + VREvent_TrackedDeviceActivated = 100, + VREvent_TrackedDeviceDeactivated = 101, + VREvent_TrackedDeviceUpdated = 102, + VREvent_TrackedDeviceUserInteractionStarted = 103, + VREvent_TrackedDeviceUserInteractionEnded = 104, + VREvent_IpdChanged = 105, + VREvent_EnterStandbyMode = 106, + VREvent_LeaveStandbyMode = 107, + VREvent_TrackedDeviceRoleChanged = 108, + VREvent_ButtonPress = 200, + VREvent_ButtonUnpress = 201, + VREvent_ButtonTouch = 202, + VREvent_ButtonUntouch = 203, + VREvent_MouseMove = 300, + VREvent_MouseButtonDown = 301, + VREvent_MouseButtonUp = 302, + VREvent_FocusEnter = 303, + VREvent_FocusLeave = 304, + VREvent_Scroll = 305, + VREvent_TouchPadMove = 306, + VREvent_InputFocusCaptured = 400, + VREvent_InputFocusReleased = 401, + VREvent_SceneFocusLost = 402, + VREvent_SceneFocusGained = 403, + VREvent_SceneApplicationChanged = 404, + VREvent_SceneFocusChanged = 405, + VREvent_InputFocusChanged = 406, + VREvent_SceneApplicationSecondaryRenderingStarted = 407, + VREvent_HideRenderModels = 410, + VREvent_ShowRenderModels = 411, + VREvent_OverlayShown = 500, + VREvent_OverlayHidden = 501, + VREvent_DashboardActivated = 502, + VREvent_DashboardDeactivated = 503, + VREvent_DashboardThumbSelected = 504, + VREvent_DashboardRequested = 505, + VREvent_ResetDashboard = 506, + VREvent_RenderToast = 507, + VREvent_ImageLoaded = 508, + VREvent_ShowKeyboard = 509, + VREvent_HideKeyboard = 510, + VREvent_OverlayGamepadFocusGained = 511, + VREvent_OverlayGamepadFocusLost = 512, + VREvent_OverlaySharedTextureChanged = 513, + VREvent_DashboardGuideButtonDown = 514, + VREvent_DashboardGuideButtonUp = 515, + VREvent_ScreenshotTriggered = 516, + VREvent_ImageFailed = 517, + VREvent_RequestScreenshot = 520, + VREvent_ScreenshotTaken = 521, + VREvent_ScreenshotFailed = 522, + VREvent_SubmitScreenshotToDashboard = 523, + VREvent_Notification_Shown = 600, + VREvent_Notification_Hidden = 601, + VREvent_Notification_BeginInteraction = 602, + VREvent_Notification_Destroyed = 603, + VREvent_Quit = 700, + VREvent_ProcessQuit = 701, + VREvent_QuitAborted_UserPrompt = 702, + VREvent_QuitAcknowledged = 703, + VREvent_DriverRequestedQuit = 704, + VREvent_ChaperoneDataHasChanged = 800, + VREvent_ChaperoneUniverseHasChanged = 801, + VREvent_ChaperoneTempDataHasChanged = 802, + VREvent_ChaperoneSettingsHaveChanged = 803, + VREvent_SeatedZeroPoseReset = 804, + VREvent_AudioSettingsHaveChanged = 820, + VREvent_BackgroundSettingHasChanged = 850, + VREvent_CameraSettingsHaveChanged = 851, + VREvent_ReprojectionSettingHasChanged = 852, + VREvent_ModelSkinSettingsHaveChanged = 853, + VREvent_EnvironmentSettingsHaveChanged = 854, + VREvent_StatusUpdate = 900, + VREvent_MCImageUpdated = 1000, + VREvent_FirmwareUpdateStarted = 1100, + VREvent_FirmwareUpdateFinished = 1101, + VREvent_KeyboardClosed = 1200, + VREvent_KeyboardCharInput = 1201, + VREvent_KeyboardDone = 1202, + VREvent_ApplicationTransitionStarted = 1300, + VREvent_ApplicationTransitionAborted = 1301, + VREvent_ApplicationTransitionNewAppStarted = 1302, + VREvent_ApplicationListUpdated = 1303, + VREvent_Compositor_MirrorWindowShown = 1400, + VREvent_Compositor_MirrorWindowHidden = 1401, + VREvent_Compositor_ChaperoneBoundsShown = 1410, + VREvent_Compositor_ChaperoneBoundsHidden = 1411, + VREvent_TrackedCamera_StartVideoStream = 1500, + VREvent_TrackedCamera_StopVideoStream = 1501, + VREvent_TrackedCamera_PauseVideoStream = 1502, + VREvent_TrackedCamera_ResumeVideoStream = 1503, + VREvent_PerformanceTest_EnableCapture = 1600, + VREvent_PerformanceTest_DisableCapture = 1601, + VREvent_PerformanceTest_FidelityLevel = 1602, + VREvent_VendorSpecific_Reserved_Start = 10000, + VREvent_VendorSpecific_Reserved_End = 19999, +} +public enum EDeviceActivityLevel +{ + k_EDeviceActivityLevel_Unknown = -1, + k_EDeviceActivityLevel_Idle = 0, + k_EDeviceActivityLevel_UserInteraction = 1, + k_EDeviceActivityLevel_UserInteraction_Timeout = 2, + k_EDeviceActivityLevel_Standby = 3, +} +public enum EVRButtonId +{ + k_EButton_System = 0, + k_EButton_ApplicationMenu = 1, + k_EButton_Grip = 2, + k_EButton_DPad_Left = 3, + k_EButton_DPad_Up = 4, + k_EButton_DPad_Right = 5, + k_EButton_DPad_Down = 6, + k_EButton_A = 7, + k_EButton_Axis0 = 32, + k_EButton_Axis1 = 33, + k_EButton_Axis2 = 34, + k_EButton_Axis3 = 35, + k_EButton_Axis4 = 36, + k_EButton_SteamVR_Touchpad = 32, + k_EButton_SteamVR_Trigger = 33, + k_EButton_Dashboard_Back = 2, + k_EButton_Max = 64, +} +public enum EVRMouseButton +{ + Left = 1, + Right = 2, + Middle = 4, +} +public enum EVRControllerAxisType +{ + k_eControllerAxis_None = 0, + k_eControllerAxis_TrackPad = 1, + k_eControllerAxis_Joystick = 2, + k_eControllerAxis_Trigger = 3, +} +public enum EVRControllerEventOutputType +{ + ControllerEventOutput_OSEvents = 0, + ControllerEventOutput_VREvents = 1, +} +public enum ECollisionBoundsStyle +{ + COLLISION_BOUNDS_STYLE_BEGINNER = 0, + COLLISION_BOUNDS_STYLE_INTERMEDIATE = 1, + COLLISION_BOUNDS_STYLE_SQUARES = 2, + COLLISION_BOUNDS_STYLE_ADVANCED = 3, + COLLISION_BOUNDS_STYLE_NONE = 4, + COLLISION_BOUNDS_STYLE_COUNT = 5, +} +public enum EVROverlayError +{ + None = 0, + UnknownOverlay = 10, + InvalidHandle = 11, + PermissionDenied = 12, + OverlayLimitExceeded = 13, + WrongVisibilityType = 14, + KeyTooLong = 15, + NameTooLong = 16, + KeyInUse = 17, + WrongTransformType = 18, + InvalidTrackedDevice = 19, + InvalidParameter = 20, + ThumbnailCantBeDestroyed = 21, + ArrayTooSmall = 22, + RequestFailed = 23, + InvalidTexture = 24, + UnableToLoadFile = 25, + VROVerlayError_KeyboardAlreadyInUse = 26, + NoNeighbor = 27, +} +public enum EVRApplicationType +{ + VRApplication_Other = 0, + VRApplication_Scene = 1, + VRApplication_Overlay = 2, + VRApplication_Background = 3, + VRApplication_Utility = 4, + VRApplication_VRMonitor = 5, +} +public enum EVRFirmwareError +{ + None = 0, + Success = 1, + Fail = 2, +} +public enum EVRNotificationError +{ + OK = 0, + InvalidNotificationId = 100, + NotificationQueueFull = 101, + InvalidOverlayHandle = 102, + SystemWithUserValueAlreadyExists = 103, +} +public enum EVRInitError +{ + None = 0, + Unknown = 1, + Init_InstallationNotFound = 100, + Init_InstallationCorrupt = 101, + Init_VRClientDLLNotFound = 102, + Init_FileNotFound = 103, + Init_FactoryNotFound = 104, + Init_InterfaceNotFound = 105, + Init_InvalidInterface = 106, + Init_UserConfigDirectoryInvalid = 107, + Init_HmdNotFound = 108, + Init_NotInitialized = 109, + Init_PathRegistryNotFound = 110, + Init_NoConfigPath = 111, + Init_NoLogPath = 112, + Init_PathRegistryNotWritable = 113, + Init_AppInfoInitFailed = 114, + Init_Retry = 115, + Init_InitCanceledByUser = 116, + Init_AnotherAppLaunching = 117, + Init_SettingsInitFailed = 118, + Init_ShuttingDown = 119, + Init_TooManyObjects = 120, + Init_NoServerForBackgroundApp = 121, + Init_NotSupportedWithCompositor = 122, + Init_NotAvailableToUtilityApps = 123, + Init_Internal = 124, + Driver_Failed = 200, + Driver_Unknown = 201, + Driver_HmdUnknown = 202, + Driver_NotLoaded = 203, + Driver_RuntimeOutOfDate = 204, + Driver_HmdInUse = 205, + Driver_NotCalibrated = 206, + Driver_CalibrationInvalid = 207, + Driver_HmdDisplayNotFound = 208, + IPC_ServerInitFailed = 300, + IPC_ConnectFailed = 301, + IPC_SharedStateInitFailed = 302, + IPC_CompositorInitFailed = 303, + IPC_MutexInitFailed = 304, + IPC_Failed = 305, + Compositor_Failed = 400, + Compositor_D3D11HardwareRequired = 401, + Compositor_FirmwareRequiresUpdate = 402, + Compositor_OverlayInitFailed = 403, + Compositor_ScreenshotsInitFailed = 404, + VendorSpecific_UnableToConnectToOculusRuntime = 1000, + VendorSpecific_HmdFound_CantOpenDevice = 1101, + VendorSpecific_HmdFound_UnableToRequestConfigStart = 1102, + VendorSpecific_HmdFound_NoStoredConfig = 1103, + VendorSpecific_HmdFound_ConfigTooBig = 1104, + VendorSpecific_HmdFound_ConfigTooSmall = 1105, + VendorSpecific_HmdFound_UnableToInitZLib = 1106, + VendorSpecific_HmdFound_CantReadFirmwareVersion = 1107, + VendorSpecific_HmdFound_UnableToSendUserDataStart = 1108, + VendorSpecific_HmdFound_UnableToGetUserDataStart = 1109, + VendorSpecific_HmdFound_UnableToGetUserDataNext = 1110, + VendorSpecific_HmdFound_UserDataAddressRange = 1111, + VendorSpecific_HmdFound_UserDataError = 1112, + VendorSpecific_HmdFound_ConfigFailedSanityCheck = 1113, + Steam_SteamInstallationNotFound = 2000, +} +public enum EVRScreenshotType +{ + None = 0, + Mono = 1, + Stereo = 2, + Cubemap = 3, + MonoPanorama = 4, + StereoPanorama = 5, +} +public enum EVRScreenshotPropertyFilenames +{ + Preview = 0, + VR = 1, +} +public enum EVRTrackedCameraError +{ + None = 0, + OperationFailed = 100, + InvalidHandle = 101, + InvalidFrameHeaderVersion = 102, + OutOfHandles = 103, + IPCFailure = 104, + NotSupportedForThisDevice = 105, + SharedMemoryFailure = 106, + FrameBufferingFailure = 107, + StreamSetupFailure = 108, + InvalidGLTextureId = 109, + InvalidSharedTextureHandle = 110, + FailedToGetGLTextureId = 111, + SharedTextureFailure = 112, + NoFrameAvailable = 113, + InvalidArgument = 114, + InvalidFrameBufferSize = 115, +} +public enum EVRTrackedCameraFrameType +{ + Distorted = 0, + Undistorted = 1, + MaximumUndistorted = 2, + MAX_CAMERA_FRAME_TYPES = 3, +} +public enum EVRApplicationError +{ + None = 0, + AppKeyAlreadyExists = 100, + NoManifest = 101, + NoApplication = 102, + InvalidIndex = 103, + UnknownApplication = 104, + IPCFailed = 105, + ApplicationAlreadyRunning = 106, + InvalidManifest = 107, + InvalidApplication = 108, + LaunchFailed = 109, + ApplicationAlreadyStarting = 110, + LaunchInProgress = 111, + OldApplicationQuitting = 112, + TransitionAborted = 113, + IsTemplate = 114, + BufferTooSmall = 200, + PropertyNotSet = 201, + UnknownProperty = 202, + InvalidParameter = 203, +} +public enum EVRApplicationProperty +{ + Name_String = 0, + LaunchType_String = 11, + WorkingDirectory_String = 12, + BinaryPath_String = 13, + Arguments_String = 14, + URL_String = 15, + Description_String = 50, + NewsURL_String = 51, + ImagePath_String = 52, + Source_String = 53, + IsDashboardOverlay_Bool = 60, + IsTemplate_Bool = 61, + IsInstanced_Bool = 62, + LastLaunchTime_Uint64 = 70, +} +public enum EVRApplicationTransitionState +{ + VRApplicationTransition_None = 0, + VRApplicationTransition_OldAppQuitSent = 10, + VRApplicationTransition_WaitingForExternalLaunch = 11, + VRApplicationTransition_NewAppLaunched = 20, +} +public enum ChaperoneCalibrationState +{ + OK = 1, + Warning = 100, + Warning_BaseStationMayHaveMoved = 101, + Warning_BaseStationRemoved = 102, + Warning_SeatedBoundsInvalid = 103, + Error = 200, + Error_BaseStationUninitalized = 201, + Error_BaseStationConflict = 202, + Error_PlayAreaInvalid = 203, + Error_CollisionBoundsInvalid = 204, +} +public enum EChaperoneConfigFile +{ + Live = 1, + Temp = 2, +} +public enum EChaperoneImportFlags +{ + EChaperoneImport_BoundsOnly = 1, +} +public enum EVRCompositorError +{ + None = 0, + RequestFailed = 1, + IncompatibleVersion = 100, + DoNotHaveFocus = 101, + InvalidTexture = 102, + IsNotSceneApplication = 103, + TextureIsOnWrongDevice = 104, + TextureUsesUnsupportedFormat = 105, + SharedTexturesNotSupported = 106, + IndexOutOfRange = 107, +} +public enum VROverlayInputMethod +{ + None = 0, + Mouse = 1, +} +public enum VROverlayTransformType +{ + VROverlayTransform_Absolute = 0, + VROverlayTransform_TrackedDeviceRelative = 1, + VROverlayTransform_SystemOverlay = 2, + VROverlayTransform_TrackedComponent = 3, +} +public enum VROverlayFlags +{ + None = 0, + Curved = 1, + RGSS4X = 2, + NoDashboardTab = 3, + AcceptsGamepadEvents = 4, + ShowGamepadFocus = 5, + SendVRScrollEvents = 6, + SendVRTouchpadEvents = 7, + ShowTouchPadScrollWheel = 8, + TransferOwnershipToInternalProcess = 9, + SideBySide_Parallel = 10, + SideBySide_Crossed = 11, + Panorama = 12, + StereoPanorama = 13, +} +public enum EGamepadTextInputMode +{ + k_EGamepadTextInputModeNormal = 0, + k_EGamepadTextInputModePassword = 1, + k_EGamepadTextInputModeSubmit = 2, +} +public enum EGamepadTextInputLineMode +{ + k_EGamepadTextInputLineModeSingleLine = 0, + k_EGamepadTextInputLineModeMultipleLines = 1, +} +public enum EOverlayDirection +{ + Up = 0, + Down = 1, + Left = 2, + Right = 3, + Count = 4, +} +public enum EVRRenderModelError +{ + None = 0, + Loading = 100, + NotSupported = 200, + InvalidArg = 300, + InvalidModel = 301, + NoShapes = 302, + MultipleShapes = 303, + TooManyVertices = 304, + MultipleTextures = 305, + BufferTooSmall = 306, + NotEnoughNormals = 307, + NotEnoughTexCoords = 308, + InvalidTexture = 400, +} +public enum EVRComponentProperty +{ + IsStatic = 1, + IsVisible = 2, + IsTouched = 4, + IsPressed = 8, + IsScrolled = 16, +} +public enum EVRNotificationType +{ + Transient = 0, + Persistent = 1, + Transient_SystemWithUserValue = 2, +} +public enum EVRNotificationStyle +{ + None = 0, + Application = 100, + Contact_Disabled = 200, + Contact_Enabled = 201, + Contact_Active = 202, +} +public enum EVRSettingsError +{ + None = 0, + IPCFailed = 1, + WriteFailed = 2, + ReadFailed = 3, +} +public enum EVRScreenshotError +{ + None = 0, + RequestFailed = 1, + IncompatibleVersion = 100, + NotFound = 101, + BufferTooSmall = 102, + ScreenshotAlreadyInProgress = 108, +} + +[StructLayout(LayoutKind.Explicit)] public struct VREvent_Data_t +{ + [FieldOffset(0)] public VREvent_Reserved_t reserved; + [FieldOffset(0)] public VREvent_Controller_t controller; + [FieldOffset(0)] public VREvent_Mouse_t mouse; + [FieldOffset(0)] public VREvent_Scroll_t scroll; + [FieldOffset(0)] public VREvent_Process_t process; + [FieldOffset(0)] public VREvent_Notification_t notification; + [FieldOffset(0)] public VREvent_Overlay_t overlay; + [FieldOffset(0)] public VREvent_Status_t status; + [FieldOffset(0)] public VREvent_Ipd_t ipd; + [FieldOffset(0)] public VREvent_Chaperone_t chaperone; + [FieldOffset(0)] public VREvent_PerformanceTest_t performanceTest; + [FieldOffset(0)] public VREvent_TouchPadMove_t touchPadMove; + [FieldOffset(0)] public VREvent_SeatedZeroPoseReset_t seatedZeroPoseReset; + [FieldOffset(0)] public VREvent_Screenshot_t screenshot; + [FieldOffset(0)] public VREvent_Keyboard_t keyboard; // This has to be at the end due to a mono bug +} + +[StructLayout(LayoutKind.Sequential)] public struct HmdMatrix34_t +{ + public float m0; //float[3][4] + public float m1; + public float m2; + public float m3; + public float m4; + public float m5; + public float m6; + public float m7; + public float m8; + public float m9; + public float m10; + public float m11; +} +[StructLayout(LayoutKind.Sequential)] public struct HmdMatrix44_t +{ + public float m0; //float[4][4] + public float m1; + public float m2; + public float m3; + public float m4; + public float m5; + public float m6; + public float m7; + public float m8; + public float m9; + public float m10; + public float m11; + public float m12; + public float m13; + public float m14; + public float m15; +} +[StructLayout(LayoutKind.Sequential)] public struct HmdVector3_t +{ + public float v0; //float[3] + public float v1; + public float v2; +} +[StructLayout(LayoutKind.Sequential)] public struct HmdVector4_t +{ + public float v0; //float[4] + public float v1; + public float v2; + public float v3; +} +[StructLayout(LayoutKind.Sequential)] public struct HmdVector3d_t +{ + public double v0; //double[3] + public double v1; + public double v2; +} +[StructLayout(LayoutKind.Sequential)] public struct HmdVector2_t +{ + public float v0; //float[2] + public float v1; +} +[StructLayout(LayoutKind.Sequential)] public struct HmdQuaternion_t +{ + public double w; + public double x; + public double y; + public double z; +} +[StructLayout(LayoutKind.Sequential)] public struct HmdColor_t +{ + public float r; + public float g; + public float b; + public float a; +} +[StructLayout(LayoutKind.Sequential)] public struct HmdQuad_t +{ + public HmdVector3_t vCorners0; //HmdVector3_t[4] + public HmdVector3_t vCorners1; + public HmdVector3_t vCorners2; + public HmdVector3_t vCorners3; +} +[StructLayout(LayoutKind.Sequential)] public struct HmdRect2_t +{ + public HmdVector2_t vTopLeft; + public HmdVector2_t vBottomRight; +} +[StructLayout(LayoutKind.Sequential)] public struct DistortionCoordinates_t +{ + public float rfRed0; //float[2] + public float rfRed1; + public float rfGreen0; //float[2] + public float rfGreen1; + public float rfBlue0; //float[2] + public float rfBlue1; +} +[StructLayout(LayoutKind.Sequential)] public struct Texture_t +{ + public IntPtr handle; // void * + public EGraphicsAPIConvention eType; + public EColorSpace eColorSpace; +} +[StructLayout(LayoutKind.Sequential)] public struct TrackedDevicePose_t +{ + public HmdMatrix34_t mDeviceToAbsoluteTracking; + public HmdVector3_t vVelocity; + public HmdVector3_t vAngularVelocity; + public ETrackingResult eTrackingResult; + [MarshalAs(UnmanagedType.I1)] + public bool bPoseIsValid; + [MarshalAs(UnmanagedType.I1)] + public bool bDeviceIsConnected; +} +[StructLayout(LayoutKind.Sequential)] public struct VRTextureBounds_t +{ + public float uMin; + public float vMin; + public float uMax; + public float vMax; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Controller_t +{ + public uint button; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Mouse_t +{ + public float x; + public float y; + public uint button; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Scroll_t +{ + public float xdelta; + public float ydelta; + public uint repeatCount; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_TouchPadMove_t +{ + [MarshalAs(UnmanagedType.I1)] + public bool bFingerDown; + public float flSecondsFingerDown; + public float fValueXFirst; + public float fValueYFirst; + public float fValueXRaw; + public float fValueYRaw; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Notification_t +{ + public ulong ulUserValue; + public uint notificationId; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Process_t +{ + public uint pid; + public uint oldPid; + [MarshalAs(UnmanagedType.I1)] + public bool bForced; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Overlay_t +{ + public ulong overlayHandle; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Status_t +{ + public uint statusState; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Keyboard_t +{ + public byte cNewInput0,cNewInput1,cNewInput2,cNewInput3,cNewInput4,cNewInput5,cNewInput6,cNewInput7; + public ulong uUserValue; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Ipd_t +{ + public float ipdMeters; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Chaperone_t +{ + public ulong m_nPreviousUniverse; + public ulong m_nCurrentUniverse; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Reserved_t +{ + public ulong reserved0; + public ulong reserved1; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_PerformanceTest_t +{ + public uint m_nFidelityLevel; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_SeatedZeroPoseReset_t +{ + [MarshalAs(UnmanagedType.I1)] + public bool bResetBySystemMenu; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_Screenshot_t +{ + public uint handle; + public uint type; +} +[StructLayout(LayoutKind.Sequential)] public struct VREvent_t +{ + public uint eventType; + public uint trackedDeviceIndex; + public float eventAgeSeconds; + public VREvent_Data_t data; +} +[StructLayout(LayoutKind.Sequential)] public struct HiddenAreaMesh_t +{ + public IntPtr pVertexData; // const struct vr::HmdVector2_t * + public uint unTriangleCount; +} +[StructLayout(LayoutKind.Sequential)] public struct VRControllerAxis_t +{ + public float x; + public float y; +} +[StructLayout(LayoutKind.Sequential)] public struct VRControllerState_t +{ + public uint unPacketNum; + public ulong ulButtonPressed; + public ulong ulButtonTouched; + public VRControllerAxis_t rAxis0; //VRControllerAxis_t[5] + public VRControllerAxis_t rAxis1; + public VRControllerAxis_t rAxis2; + public VRControllerAxis_t rAxis3; + public VRControllerAxis_t rAxis4; +} +[StructLayout(LayoutKind.Sequential)] public struct Compositor_OverlaySettings +{ + public uint size; + [MarshalAs(UnmanagedType.I1)] + public bool curved; + [MarshalAs(UnmanagedType.I1)] + public bool antialias; + public float scale; + public float distance; + public float alpha; + public float uOffset; + public float vOffset; + public float uScale; + public float vScale; + public float gridDivs; + public float gridWidth; + public float gridScale; + public HmdMatrix44_t transform; +} +[StructLayout(LayoutKind.Sequential)] public struct CameraVideoStreamFrameHeader_t +{ + public EVRTrackedCameraFrameType eFrameType; + public uint nWidth; + public uint nHeight; + public uint nBytesPerPixel; + public uint nFrameSequence; + public TrackedDevicePose_t standingTrackedDevicePose; +} +[StructLayout(LayoutKind.Sequential)] public struct AppOverrideKeys_t +{ + public IntPtr pchKey; // const char * + public IntPtr pchValue; // const char * +} +[StructLayout(LayoutKind.Sequential)] public struct Compositor_FrameTiming +{ + public uint m_nSize; + public uint m_nFrameIndex; + public uint m_nNumFramePresents; + public uint m_nNumDroppedFrames; + public double m_flSystemTimeInSeconds; + public float m_flSceneRenderGpuMs; + public float m_flTotalRenderGpuMs; + public float m_flCompositorRenderGpuMs; + public float m_flCompositorRenderCpuMs; + public float m_flCompositorIdleCpuMs; + public float m_flClientFrameIntervalMs; + public float m_flPresentCallCpuMs; + public float m_flWaitForPresentCpuMs; + public float m_flSubmitFrameMs; + public float m_flWaitGetPosesCalledMs; + public float m_flNewPosesReadyMs; + public float m_flNewFrameReadyMs; + public float m_flCompositorUpdateStartMs; + public float m_flCompositorUpdateEndMs; + public float m_flCompositorRenderStartMs; + public TrackedDevicePose_t m_HmdPose; + public int m_nFidelityLevel; + public uint m_nReprojectionFlags; +} +[StructLayout(LayoutKind.Sequential)] public struct Compositor_CumulativeStats +{ + public uint m_nPid; + public uint m_nNumFramePresents; + public uint m_nNumDroppedFrames; + public uint m_nNumReprojectedFrames; + public uint m_nNumFramePresentsOnStartup; + public uint m_nNumDroppedFramesOnStartup; + public uint m_nNumReprojectedFramesOnStartup; + public uint m_nNumLoading; + public uint m_nNumFramePresentsLoading; + public uint m_nNumDroppedFramesLoading; + public uint m_nNumReprojectedFramesLoading; + public uint m_nNumTimedOut; + public uint m_nNumFramePresentsTimedOut; + public uint m_nNumDroppedFramesTimedOut; + public uint m_nNumReprojectedFramesTimedOut; +} +[StructLayout(LayoutKind.Sequential)] public struct VROverlayIntersectionParams_t +{ + public HmdVector3_t vSource; + public HmdVector3_t vDirection; + public ETrackingUniverseOrigin eOrigin; +} +[StructLayout(LayoutKind.Sequential)] public struct VROverlayIntersectionResults_t +{ + public HmdVector3_t vPoint; + public HmdVector3_t vNormal; + public HmdVector2_t vUVs; + public float fDistance; +} +[StructLayout(LayoutKind.Sequential)] public struct RenderModel_ComponentState_t +{ + public HmdMatrix34_t mTrackingToComponentRenderModel; + public HmdMatrix34_t mTrackingToComponentLocal; + public uint uProperties; +} +[StructLayout(LayoutKind.Sequential)] public struct RenderModel_Vertex_t +{ + public HmdVector3_t vPosition; + public HmdVector3_t vNormal; + public float rfTextureCoord0; //float[2] + public float rfTextureCoord1; +} +[StructLayout(LayoutKind.Sequential)] public struct RenderModel_TextureMap_t +{ + public char unWidth; + public char unHeight; + public IntPtr rubTextureMapData; // const uint8_t * +} +[StructLayout(LayoutKind.Sequential)] public struct RenderModel_t +{ + public IntPtr rVertexData; // const struct vr::RenderModel_Vertex_t * + public uint unVertexCount; + public IntPtr rIndexData; // const uint16_t * + public uint unTriangleCount; + public int diffuseTextureId; +} +[StructLayout(LayoutKind.Sequential)] public struct RenderModel_ControllerMode_State_t +{ + [MarshalAs(UnmanagedType.I1)] + public bool bScrollWheelVisible; +} +[StructLayout(LayoutKind.Sequential)] public struct NotificationBitmap_t +{ + public IntPtr m_pImageData; // void * + public int m_nWidth; + public int m_nHeight; + public int m_nBytesPerPixel; +} +[StructLayout(LayoutKind.Sequential)] public struct COpenVRContext +{ + public IntPtr m_pVRSystem; // class vr::IVRSystem * + public IntPtr m_pVRChaperone; // class vr::IVRChaperone * + public IntPtr m_pVRChaperoneSetup; // class vr::IVRChaperoneSetup * + public IntPtr m_pVRCompositor; // class vr::IVRCompositor * + public IntPtr m_pVROverlay; // class vr::IVROverlay * + public IntPtr m_pVRRenderModels; // class vr::IVRRenderModels * + public IntPtr m_pVRExtendedDisplay; // class vr::IVRExtendedDisplay * + public IntPtr m_pVRSettings; // class vr::IVRSettings * + public IntPtr m_pVRApplications; // class vr::IVRApplications * + public IntPtr m_pVRTrackedCamera; // class vr::IVRTrackedCamera * + public IntPtr m_pVRScreenshots; // class vr::IVRScreenshots * +} + +public class OpenVR +{ + + public static uint InitInternal(ref EVRInitError peError, EVRApplicationType eApplicationType) + { + return OpenVRInterop.InitInternal(ref peError, eApplicationType); + } + + public static void ShutdownInternal() + { + OpenVRInterop.ShutdownInternal(); + } + + public static bool IsHmdPresent() + { + return OpenVRInterop.IsHmdPresent(); + } + + public static bool IsRuntimeInstalled() + { + return OpenVRInterop.IsRuntimeInstalled(); + } + + public static string GetStringForHmdError(EVRInitError error) + { + return Marshal.PtrToStringAnsi(OpenVRInterop.GetStringForHmdError(error)); + } + + public static IntPtr GetGenericInterface(string pchInterfaceVersion, ref EVRInitError peError) + { + return OpenVRInterop.GetGenericInterface(pchInterfaceVersion, ref peError); + } + + public static bool IsInterfaceVersionValid(string pchInterfaceVersion) + { + return OpenVRInterop.IsInterfaceVersionValid(pchInterfaceVersion); + } + + public static uint GetInitToken() + { + return OpenVRInterop.GetInitToken(); + } + + public const uint k_unTrackingStringSize = 32; + public const uint k_unMaxDriverDebugResponseSize = 32768; + public const uint k_unTrackedDeviceIndex_Hmd = 0; + public const uint k_unMaxTrackedDeviceCount = 16; + public const uint k_unTrackedDeviceIndexOther = 4294967294; + public const uint k_unTrackedDeviceIndexInvalid = 4294967295; + public const uint k_unMaxPropertyStringSize = 32768; + public const uint k_unControllerStateAxisCount = 5; + public const ulong k_ulOverlayHandleInvalid = 0; + public const uint k_unScreenshotHandleInvalid = 0; + public const string IVRSystem_Version = "IVRSystem_012"; + public const string IVRExtendedDisplay_Version = "IVRExtendedDisplay_001"; + public const string IVRTrackedCamera_Version = "IVRTrackedCamera_003"; + public const uint k_unMaxApplicationKeyLength = 128; + public const string IVRApplications_Version = "IVRApplications_005"; + public const string IVRChaperone_Version = "IVRChaperone_003"; + public const string IVRChaperoneSetup_Version = "IVRChaperoneSetup_005"; + public const string IVRCompositor_Version = "IVRCompositor_015"; + public const uint k_unVROverlayMaxKeyLength = 128; + public const uint k_unVROverlayMaxNameLength = 128; + public const uint k_unMaxOverlayCount = 32; + public const string IVROverlay_Version = "IVROverlay_012"; + public const string k_pch_Controller_Component_GDC2015 = "gdc2015"; + public const string k_pch_Controller_Component_Base = "base"; + public const string k_pch_Controller_Component_Tip = "tip"; + public const string k_pch_Controller_Component_HandGrip = "handgrip"; + public const string k_pch_Controller_Component_Status = "status"; + public const string IVRRenderModels_Version = "IVRRenderModels_005"; + public const uint k_unNotificationTextMaxSize = 256; + public const string IVRNotifications_Version = "IVRNotifications_002"; + public const uint k_unMaxSettingsKeyLength = 128; + public const string IVRSettings_Version = "IVRSettings_001"; + public const string k_pch_SteamVR_Section = "steamvr"; + public const string k_pch_SteamVR_RequireHmd_String = "requireHmd"; + public const string k_pch_SteamVR_ForcedDriverKey_String = "forcedDriver"; + public const string k_pch_SteamVR_ForcedHmdKey_String = "forcedHmd"; + public const string k_pch_SteamVR_DisplayDebug_Bool = "displayDebug"; + public const string k_pch_SteamVR_DebugProcessPipe_String = "debugProcessPipe"; + public const string k_pch_SteamVR_EnableDistortion_Bool = "enableDistortion"; + public const string k_pch_SteamVR_DisplayDebugX_Int32 = "displayDebugX"; + public const string k_pch_SteamVR_DisplayDebugY_Int32 = "displayDebugY"; + public const string k_pch_SteamVR_SendSystemButtonToAllApps_Bool = "sendSystemButtonToAllApps"; + public const string k_pch_SteamVR_LogLevel_Int32 = "loglevel"; + public const string k_pch_SteamVR_IPD_Float = "ipd"; + public const string k_pch_SteamVR_Background_String = "background"; + public const string k_pch_SteamVR_BackgroundCameraHeight_Float = "backgroundCameraHeight"; + public const string k_pch_SteamVR_BackgroundDomeRadius_Float = "backgroundDomeRadius"; + public const string k_pch_SteamVR_Environment_String = "environment"; + public const string k_pch_SteamVR_GridColor_String = "gridColor"; + public const string k_pch_SteamVR_PlayAreaColor_String = "playAreaColor"; + public const string k_pch_SteamVR_ShowStage_Bool = "showStage"; + public const string k_pch_SteamVR_ActivateMultipleDrivers_Bool = "activateMultipleDrivers"; + public const string k_pch_SteamVR_PowerOffOnExit_Bool = "powerOffOnExit"; + public const string k_pch_SteamVR_StandbyAppRunningTimeout_Float = "standbyAppRunningTimeout"; + public const string k_pch_SteamVR_StandbyNoAppTimeout_Float = "standbyNoAppTimeout"; + public const string k_pch_SteamVR_DirectMode_Bool = "directMode"; + public const string k_pch_SteamVR_DirectModeEdidVid_Int32 = "directModeEdidVid"; + public const string k_pch_SteamVR_DirectModeEdidPid_Int32 = "directModeEdidPid"; + public const string k_pch_SteamVR_UsingSpeakers_Bool = "usingSpeakers"; + public const string k_pch_SteamVR_SpeakersForwardYawOffsetDegrees_Float = "speakersForwardYawOffsetDegrees"; + public const string k_pch_SteamVR_BaseStationPowerManagement_Bool = "basestationPowerManagement"; + public const string k_pch_SteamVR_NeverKillProcesses_Bool = "neverKillProcesses"; + public const string k_pch_SteamVR_RenderTargetMultiplier_Float = "renderTargetMultiplier"; + public const string k_pch_SteamVR_AllowReprojection_Bool = "allowReprojection"; + public const string k_pch_SteamVR_ForceReprojection_Bool = "forceReprojection"; + public const string k_pch_SteamVR_ForceFadeOnBadTracking_Bool = "forceFadeOnBadTracking"; + public const string k_pch_SteamVR_DefaultMirrorView_Int32 = "defaultMirrorView"; + public const string k_pch_SteamVR_ShowMirrorView_Bool = "showMirrorView"; + public const string k_pch_Lighthouse_Section = "driver_lighthouse"; + public const string k_pch_Lighthouse_DisableIMU_Bool = "disableimu"; + public const string k_pch_Lighthouse_UseDisambiguation_String = "usedisambiguation"; + public const string k_pch_Lighthouse_DisambiguationDebug_Int32 = "disambiguationdebug"; + public const string k_pch_Lighthouse_PrimaryBasestation_Int32 = "primarybasestation"; + public const string k_pch_Lighthouse_LighthouseName_String = "lighthousename"; + public const string k_pch_Lighthouse_MaxIncidenceAngleDegrees_Float = "maxincidenceangledegrees"; + public const string k_pch_Lighthouse_UseLighthouseDirect_Bool = "uselighthousedirect"; + public const string k_pch_Lighthouse_DBHistory_Bool = "dbhistory"; + public const string k_pch_Null_Section = "driver_null"; + public const string k_pch_Null_EnableNullDriver_Bool = "enable"; + public const string k_pch_Null_SerialNumber_String = "serialNumber"; + public const string k_pch_Null_ModelNumber_String = "modelNumber"; + public const string k_pch_Null_WindowX_Int32 = "windowX"; + public const string k_pch_Null_WindowY_Int32 = "windowY"; + public const string k_pch_Null_WindowWidth_Int32 = "windowWidth"; + public const string k_pch_Null_WindowHeight_Int32 = "windowHeight"; + public const string k_pch_Null_RenderWidth_Int32 = "renderWidth"; + public const string k_pch_Null_RenderHeight_Int32 = "renderHeight"; + public const string k_pch_Null_SecondsFromVsyncToPhotons_Float = "secondsFromVsyncToPhotons"; + public const string k_pch_Null_DisplayFrequency_Float = "displayFrequency"; + public const string k_pch_UserInterface_Section = "userinterface"; + public const string k_pch_UserInterface_StatusAlwaysOnTop_Bool = "StatusAlwaysOnTop"; + public const string k_pch_UserInterface_EnableScreenshots_Bool = "EnableScreenshots"; + public const string k_pch_Notifications_Section = "notifications"; + public const string k_pch_Notifications_DoNotDisturb_Bool = "DoNotDisturb"; + public const string k_pch_Keyboard_Section = "keyboard"; + public const string k_pch_Keyboard_TutorialCompletions = "TutorialCompletions"; + public const string k_pch_Keyboard_ScaleX = "ScaleX"; + public const string k_pch_Keyboard_ScaleY = "ScaleY"; + public const string k_pch_Keyboard_OffsetLeftX = "OffsetLeftX"; + public const string k_pch_Keyboard_OffsetRightX = "OffsetRightX"; + public const string k_pch_Keyboard_OffsetY = "OffsetY"; + public const string k_pch_Keyboard_Smoothing = "Smoothing"; + public const string k_pch_Perf_Section = "perfcheck"; + public const string k_pch_Perf_HeuristicActive_Bool = "heuristicActive"; + public const string k_pch_Perf_NotifyInHMD_Bool = "warnInHMD"; + public const string k_pch_Perf_NotifyOnlyOnce_Bool = "warnOnlyOnce"; + public const string k_pch_Perf_AllowTimingStore_Bool = "allowTimingStore"; + public const string k_pch_Perf_SaveTimingsOnExit_Bool = "saveTimingsOnExit"; + public const string k_pch_Perf_TestData_Float = "perfTestData"; + public const string k_pch_CollisionBounds_Section = "collisionBounds"; + public const string k_pch_CollisionBounds_Style_Int32 = "CollisionBoundsStyle"; + public const string k_pch_CollisionBounds_GroundPerimeterOn_Bool = "CollisionBoundsGroundPerimeterOn"; + public const string k_pch_CollisionBounds_CenterMarkerOn_Bool = "CollisionBoundsCenterMarkerOn"; + public const string k_pch_CollisionBounds_PlaySpaceOn_Bool = "CollisionBoundsPlaySpaceOn"; + public const string k_pch_CollisionBounds_FadeDistance_Float = "CollisionBoundsFadeDistance"; + public const string k_pch_CollisionBounds_ColorGammaR_Int32 = "CollisionBoundsColorGammaR"; + public const string k_pch_CollisionBounds_ColorGammaG_Int32 = "CollisionBoundsColorGammaG"; + public const string k_pch_CollisionBounds_ColorGammaB_Int32 = "CollisionBoundsColorGammaB"; + public const string k_pch_CollisionBounds_ColorGammaA_Int32 = "CollisionBoundsColorGammaA"; + public const string k_pch_Camera_Section = "camera"; + public const string k_pch_Camera_EnableCamera_Bool = "enableCamera"; + public const string k_pch_Camera_EnableCameraInDashboard_Bool = "enableCameraInDashboard"; + public const string k_pch_Camera_EnableCameraForCollisionBounds_Bool = "enableCameraForCollisionBounds"; + public const string k_pch_Camera_EnableCameraForRoomView_Bool = "enableCameraForRoomView"; + public const string k_pch_Camera_BoundsColorGammaR_Int32 = "cameraBoundsColorGammaR"; + public const string k_pch_Camera_BoundsColorGammaG_Int32 = "cameraBoundsColorGammaG"; + public const string k_pch_Camera_BoundsColorGammaB_Int32 = "cameraBoundsColorGammaB"; + public const string k_pch_Camera_BoundsColorGammaA_Int32 = "cameraBoundsColorGammaA"; + public const string k_pch_audio_Section = "audio"; + public const string k_pch_audio_OnPlaybackDevice_String = "onPlaybackDevice"; + public const string k_pch_audio_OnRecordDevice_String = "onRecordDevice"; + public const string k_pch_audio_OnPlaybackMirrorDevice_String = "onPlaybackMirrorDevice"; + public const string k_pch_audio_OffPlaybackDevice_String = "offPlaybackDevice"; + public const string k_pch_audio_OffRecordDevice_String = "offRecordDevice"; + public const string k_pch_audio_VIVEHDMIGain = "viveHDMIGain"; + public const string k_pch_modelskin_Section = "modelskins"; + public const string IVRScreenshots_Version = "IVRScreenshots_001"; + + static uint VRToken { get; set; } + + const string FnTable_Prefix = "FnTable:"; + + class COpenVRContext + { + public COpenVRContext() { Clear(); } + + public void Clear() + { + m_pVRSystem = null; + m_pVRChaperone = null; + m_pVRChaperoneSetup = null; + m_pVRCompositor = null; + m_pVROverlay = null; + m_pVRRenderModels = null; + m_pVRExtendedDisplay = null; + m_pVRSettings = null; + m_pVRApplications = null; + m_pVRScreenshots = null; + } + + void CheckClear() + { + if (VRToken != GetInitToken()) + { + Clear(); + VRToken = GetInitToken(); + } + } + + public CVRSystem VRSystem() + { + CheckClear(); + if (m_pVRSystem == null) + { + var eError = EVRInitError.None; + var pInterface = OpenVRInterop.GetGenericInterface(FnTable_Prefix+IVRSystem_Version, ref eError); + if (pInterface != IntPtr.Zero && eError == EVRInitError.None) + m_pVRSystem = new CVRSystem(pInterface); + } + return m_pVRSystem; + } + + public CVRChaperone VRChaperone() + { + CheckClear(); + if (m_pVRChaperone == null) + { + var eError = EVRInitError.None; + var pInterface = OpenVRInterop.GetGenericInterface(FnTable_Prefix+IVRChaperone_Version, ref eError); + if (pInterface != IntPtr.Zero && eError == EVRInitError.None) + m_pVRChaperone = new CVRChaperone(pInterface); + } + return m_pVRChaperone; + } + + public CVRChaperoneSetup VRChaperoneSetup() + { + CheckClear(); + if (m_pVRChaperoneSetup == null) + { + var eError = EVRInitError.None; + var pInterface = OpenVRInterop.GetGenericInterface(FnTable_Prefix+IVRChaperoneSetup_Version, ref eError); + if (pInterface != IntPtr.Zero && eError == EVRInitError.None) + m_pVRChaperoneSetup = new CVRChaperoneSetup(pInterface); + } + return m_pVRChaperoneSetup; + } + + public CVRCompositor VRCompositor() + { + CheckClear(); + if (m_pVRCompositor == null) + { + var eError = EVRInitError.None; + var pInterface = OpenVRInterop.GetGenericInterface(FnTable_Prefix+IVRCompositor_Version, ref eError); + if (pInterface != IntPtr.Zero && eError == EVRInitError.None) + m_pVRCompositor = new CVRCompositor(pInterface); + } + return m_pVRCompositor; + } + + public CVROverlay VROverlay() + { + CheckClear(); + if (m_pVROverlay == null) + { + var eError = EVRInitError.None; + var pInterface = OpenVRInterop.GetGenericInterface(FnTable_Prefix+IVROverlay_Version, ref eError); + if (pInterface != IntPtr.Zero && eError == EVRInitError.None) + m_pVROverlay = new CVROverlay(pInterface); + } + return m_pVROverlay; + } + + public CVRRenderModels VRRenderModels() + { + CheckClear(); + if (m_pVRRenderModels == null) + { + var eError = EVRInitError.None; + var pInterface = OpenVRInterop.GetGenericInterface(FnTable_Prefix+IVRRenderModels_Version, ref eError); + if (pInterface != IntPtr.Zero && eError == EVRInitError.None) + m_pVRRenderModels = new CVRRenderModels(pInterface); + } + return m_pVRRenderModels; + } + + public CVRExtendedDisplay VRExtendedDisplay() + { + CheckClear(); + if (m_pVRExtendedDisplay == null) + { + var eError = EVRInitError.None; + var pInterface = OpenVRInterop.GetGenericInterface(FnTable_Prefix+IVRExtendedDisplay_Version, ref eError); + if (pInterface != IntPtr.Zero && eError == EVRInitError.None) + m_pVRExtendedDisplay = new CVRExtendedDisplay(pInterface); + } + return m_pVRExtendedDisplay; + } + + public CVRSettings VRSettings() + { + CheckClear(); + if (m_pVRSettings == null) + { + var eError = EVRInitError.None; + var pInterface = OpenVRInterop.GetGenericInterface(FnTable_Prefix+IVRSettings_Version, ref eError); + if (pInterface != IntPtr.Zero && eError == EVRInitError.None) + m_pVRSettings = new CVRSettings(pInterface); + } + return m_pVRSettings; + } + + public CVRApplications VRApplications() + { + CheckClear(); + if (m_pVRApplications == null) + { + var eError = EVRInitError.None; + var pInterface = OpenVRInterop.GetGenericInterface(FnTable_Prefix+IVRApplications_Version, ref eError); + if (pInterface != IntPtr.Zero && eError == EVRInitError.None) + m_pVRApplications = new CVRApplications(pInterface); + } + return m_pVRApplications; + } + + public CVRScreenshots VRScreenshots() + { + CheckClear(); + if (m_pVRScreenshots == null) + { + var eError = EVRInitError.None; + var pInterface = OpenVRInterop.GetGenericInterface(FnTable_Prefix+IVRScreenshots_Version, ref eError); + if (pInterface != IntPtr.Zero && eError == EVRInitError.None) + m_pVRScreenshots = new CVRScreenshots(pInterface); + } + return m_pVRScreenshots; + } + + private CVRSystem m_pVRSystem; + private CVRChaperone m_pVRChaperone; + private CVRChaperoneSetup m_pVRChaperoneSetup; + private CVRCompositor m_pVRCompositor; + private CVROverlay m_pVROverlay; + private CVRRenderModels m_pVRRenderModels; + private CVRExtendedDisplay m_pVRExtendedDisplay; + private CVRSettings m_pVRSettings; + private CVRApplications m_pVRApplications; + private CVRScreenshots m_pVRScreenshots; + }; + + private static COpenVRContext _OpenVRInternal_ModuleContext = null; + static COpenVRContext OpenVRInternal_ModuleContext + { + get + { + if (_OpenVRInternal_ModuleContext == null) + _OpenVRInternal_ModuleContext = new COpenVRContext(); + return _OpenVRInternal_ModuleContext; + } + } + + public static CVRSystem System { get { return OpenVRInternal_ModuleContext.VRSystem(); } } + public static CVRChaperone Chaperone { get { return OpenVRInternal_ModuleContext.VRChaperone(); } } + public static CVRChaperoneSetup ChaperoneSetup { get { return OpenVRInternal_ModuleContext.VRChaperoneSetup(); } } + public static CVRCompositor Compositor { get { return OpenVRInternal_ModuleContext.VRCompositor(); } } + public static CVROverlay Overlay { get { return OpenVRInternal_ModuleContext.VROverlay(); } } + public static CVRRenderModels RenderModels { get { return OpenVRInternal_ModuleContext.VRRenderModels(); } } + public static CVRApplications Applications { get { return OpenVRInternal_ModuleContext.VRApplications(); } } + public static CVRSettings Settings { get { return OpenVRInternal_ModuleContext.VRSettings(); } } + public static CVRExtendedDisplay ExtendedDisplay { get { return OpenVRInternal_ModuleContext.VRExtendedDisplay(); } } + public static CVRScreenshots Screenshots { get { return OpenVRInternal_ModuleContext.VRScreenshots(); } } + + /** Finds the active installation of vrclient.dll and initializes it */ + public static CVRSystem Init(ref EVRInitError peError, EVRApplicationType eApplicationType = EVRApplicationType.VRApplication_Scene) + { + VRToken = InitInternal(ref peError, eApplicationType); + OpenVRInternal_ModuleContext.Clear(); + + if (peError != EVRInitError.None) + return null; + + bool bInterfaceValid = IsInterfaceVersionValid(IVRSystem_Version); + if (!bInterfaceValid) + { + ShutdownInternal(); + peError = EVRInitError.Init_InterfaceNotFound; + return null; + } + + return OpenVR.System; + } + + /** unloads vrclient.dll. Any interface pointers from the interface are + * invalid after this point */ + public static void Shutdown() + { + ShutdownInternal(); + } + +} + + + +} + diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr_api.json b/examples/ThirdPartyLibs/openvr/headers/openvr_api.json new file mode 100644 index 000000000..c72b2c415 --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/headers/openvr_api.json @@ -0,0 +1,3347 @@ +{"typedefs":[{"typedef": "vr::glSharedTextureHandle_t","type": "void *"} +,{"typedef": "vr::glInt_t","type": "int32_t"} +,{"typedef": "vr::glUInt_t","type": "uint32_t"} +,{"typedef": "vr::TrackedDeviceIndex_t","type": "uint32_t"} +,{"typedef": "vr::VREvent_Data_t","type": "union VREvent_Data_t"} +,{"typedef": "vr::VRControllerState_t","type": "struct vr::VRControllerState001_t"} +,{"typedef": "vr::VROverlayHandle_t","type": "uint64_t"} +,{"typedef": "vr::TrackedCameraHandle_t","type": "uint64_t"} +,{"typedef": "vr::ScreenshotHandle_t","type": "uint32_t"} +,{"typedef": "vr::VRComponentProperties","type": "uint32_t"} +,{"typedef": "vr::TextureID_t","type": "int32_t"} +,{"typedef": "vr::VRNotificationId","type": "uint32_t"} +,{"typedef": "vr::HmdError","type": "enum vr::EVRInitError"} +,{"typedef": "vr::Hmd_Eye","type": "enum vr::EVREye"} +,{"typedef": "vr::GraphicsAPIConvention","type": "enum vr::EGraphicsAPIConvention"} +,{"typedef": "vr::ColorSpace","type": "enum vr::EColorSpace"} +,{"typedef": "vr::HmdTrackingResult","type": "enum vr::ETrackingResult"} +,{"typedef": "vr::TrackedDeviceClass","type": "enum vr::ETrackedDeviceClass"} +,{"typedef": "vr::TrackingUniverseOrigin","type": "enum vr::ETrackingUniverseOrigin"} +,{"typedef": "vr::TrackedDeviceProperty","type": "enum vr::ETrackedDeviceProperty"} +,{"typedef": "vr::TrackedPropertyError","type": "enum vr::ETrackedPropertyError"} +,{"typedef": "vr::VRSubmitFlags_t","type": "enum vr::EVRSubmitFlags"} +,{"typedef": "vr::VRState_t","type": "enum vr::EVRState"} +,{"typedef": "vr::CollisionBoundsStyle_t","type": "enum vr::ECollisionBoundsStyle"} +,{"typedef": "vr::VROverlayError","type": "enum vr::EVROverlayError"} +,{"typedef": "vr::VRFirmwareError","type": "enum vr::EVRFirmwareError"} +,{"typedef": "vr::VRCompositorError","type": "enum vr::EVRCompositorError"} +,{"typedef": "vr::VRScreenshotsError","type": "enum vr::EVRScreenshotError"} +], +"enums":[ + {"enumname": "vr::EVREye","values": [ + {"name": "Eye_Left","value": "0"} + ,{"name": "Eye_Right","value": "1"} +]} +, {"enumname": "vr::EGraphicsAPIConvention","values": [ + {"name": "API_DirectX","value": "0"} + ,{"name": "API_OpenGL","value": "1"} +]} +, {"enumname": "vr::EColorSpace","values": [ + {"name": "ColorSpace_Auto","value": "0"} + ,{"name": "ColorSpace_Gamma","value": "1"} + ,{"name": "ColorSpace_Linear","value": "2"} +]} +, {"enumname": "vr::ETrackingResult","values": [ + {"name": "TrackingResult_Uninitialized","value": "1"} + ,{"name": "TrackingResult_Calibrating_InProgress","value": "100"} + ,{"name": "TrackingResult_Calibrating_OutOfRange","value": "101"} + ,{"name": "TrackingResult_Running_OK","value": "200"} + ,{"name": "TrackingResult_Running_OutOfRange","value": "201"} +]} +, {"enumname": "vr::ETrackedDeviceClass","values": [ + {"name": "TrackedDeviceClass_Invalid","value": "0"} + ,{"name": "TrackedDeviceClass_HMD","value": "1"} + ,{"name": "TrackedDeviceClass_Controller","value": "2"} + ,{"name": "TrackedDeviceClass_TrackingReference","value": "4"} + ,{"name": "TrackedDeviceClass_Other","value": "1000"} +]} +, {"enumname": "vr::ETrackedControllerRole","values": [ + {"name": "TrackedControllerRole_Invalid","value": "0"} + ,{"name": "TrackedControllerRole_LeftHand","value": "1"} + ,{"name": "TrackedControllerRole_RightHand","value": "2"} +]} +, {"enumname": "vr::ETrackingUniverseOrigin","values": [ + {"name": "TrackingUniverseSeated","value": "0"} + ,{"name": "TrackingUniverseStanding","value": "1"} + ,{"name": "TrackingUniverseRawAndUncalibrated","value": "2"} +]} +, {"enumname": "vr::ETrackedDeviceProperty","values": [ + {"name": "Prop_TrackingSystemName_String","value": "1000"} + ,{"name": "Prop_ModelNumber_String","value": "1001"} + ,{"name": "Prop_SerialNumber_String","value": "1002"} + ,{"name": "Prop_RenderModelName_String","value": "1003"} + ,{"name": "Prop_WillDriftInYaw_Bool","value": "1004"} + ,{"name": "Prop_ManufacturerName_String","value": "1005"} + ,{"name": "Prop_TrackingFirmwareVersion_String","value": "1006"} + ,{"name": "Prop_HardwareRevision_String","value": "1007"} + ,{"name": "Prop_AllWirelessDongleDescriptions_String","value": "1008"} + ,{"name": "Prop_ConnectedWirelessDongle_String","value": "1009"} + ,{"name": "Prop_DeviceIsWireless_Bool","value": "1010"} + ,{"name": "Prop_DeviceIsCharging_Bool","value": "1011"} + ,{"name": "Prop_DeviceBatteryPercentage_Float","value": "1012"} + ,{"name": "Prop_StatusDisplayTransform_Matrix34","value": "1013"} + ,{"name": "Prop_Firmware_UpdateAvailable_Bool","value": "1014"} + ,{"name": "Prop_Firmware_ManualUpdate_Bool","value": "1015"} + ,{"name": "Prop_Firmware_ManualUpdateURL_String","value": "1016"} + ,{"name": "Prop_HardwareRevision_Uint64","value": "1017"} + ,{"name": "Prop_FirmwareVersion_Uint64","value": "1018"} + ,{"name": "Prop_FPGAVersion_Uint64","value": "1019"} + ,{"name": "Prop_VRCVersion_Uint64","value": "1020"} + ,{"name": "Prop_RadioVersion_Uint64","value": "1021"} + ,{"name": "Prop_DongleVersion_Uint64","value": "1022"} + ,{"name": "Prop_BlockServerShutdown_Bool","value": "1023"} + ,{"name": "Prop_CanUnifyCoordinateSystemWithHmd_Bool","value": "1024"} + ,{"name": "Prop_ContainsProximitySensor_Bool","value": "1025"} + ,{"name": "Prop_DeviceProvidesBatteryStatus_Bool","value": "1026"} + ,{"name": "Prop_DeviceCanPowerOff_Bool","value": "1027"} + ,{"name": "Prop_Firmware_ProgrammingTarget_String","value": "1028"} + ,{"name": "Prop_DeviceClass_Int32","value": "1029"} + ,{"name": "Prop_HasCamera_Bool","value": "1030"} + ,{"name": "Prop_DriverVersion_String","value": "1031"} + ,{"name": "Prop_Firmware_ForceUpdateRequired_Bool","value": "1032"} + ,{"name": "Prop_ReportsTimeSinceVSync_Bool","value": "2000"} + ,{"name": "Prop_SecondsFromVsyncToPhotons_Float","value": "2001"} + ,{"name": "Prop_DisplayFrequency_Float","value": "2002"} + ,{"name": "Prop_UserIpdMeters_Float","value": "2003"} + ,{"name": "Prop_CurrentUniverseId_Uint64","value": "2004"} + ,{"name": "Prop_PreviousUniverseId_Uint64","value": "2005"} + ,{"name": "Prop_DisplayFirmwareVersion_Uint64","value": "2006"} + ,{"name": "Prop_IsOnDesktop_Bool","value": "2007"} + ,{"name": "Prop_DisplayMCType_Int32","value": "2008"} + ,{"name": "Prop_DisplayMCOffset_Float","value": "2009"} + ,{"name": "Prop_DisplayMCScale_Float","value": "2010"} + ,{"name": "Prop_EdidVendorID_Int32","value": "2011"} + ,{"name": "Prop_DisplayMCImageLeft_String","value": "2012"} + ,{"name": "Prop_DisplayMCImageRight_String","value": "2013"} + ,{"name": "Prop_DisplayGCBlackClamp_Float","value": "2014"} + ,{"name": "Prop_EdidProductID_Int32","value": "2015"} + ,{"name": "Prop_CameraToHeadTransform_Matrix34","value": "2016"} + ,{"name": "Prop_DisplayGCType_Int32","value": "2017"} + ,{"name": "Prop_DisplayGCOffset_Float","value": "2018"} + ,{"name": "Prop_DisplayGCScale_Float","value": "2019"} + ,{"name": "Prop_DisplayGCPrescale_Float","value": "2020"} + ,{"name": "Prop_DisplayGCImage_String","value": "2021"} + ,{"name": "Prop_LensCenterLeftU_Float","value": "2022"} + ,{"name": "Prop_LensCenterLeftV_Float","value": "2023"} + ,{"name": "Prop_LensCenterRightU_Float","value": "2024"} + ,{"name": "Prop_LensCenterRightV_Float","value": "2025"} + ,{"name": "Prop_UserHeadToEyeDepthMeters_Float","value": "2026"} + ,{"name": "Prop_CameraFirmwareVersion_Uint64","value": "2027"} + ,{"name": "Prop_CameraFirmwareDescription_String","value": "2028"} + ,{"name": "Prop_DisplayFPGAVersion_Uint64","value": "2029"} + ,{"name": "Prop_DisplayBootloaderVersion_Uint64","value": "2030"} + ,{"name": "Prop_DisplayHardwareVersion_Uint64","value": "2031"} + ,{"name": "Prop_AudioFirmwareVersion_Uint64","value": "2032"} + ,{"name": "Prop_CameraCompatibilityMode_Int32","value": "2033"} + ,{"name": "Prop_ScreenshotHorizontalFieldOfViewDegrees_Float","value": "2034"} + ,{"name": "Prop_ScreenshotVerticalFieldOfViewDegrees_Float","value": "2035"} + ,{"name": "Prop_DisplaySuppressed_Bool","value": "2036"} + ,{"name": "Prop_AttachedDeviceId_String","value": "3000"} + ,{"name": "Prop_SupportedButtons_Uint64","value": "3001"} + ,{"name": "Prop_Axis0Type_Int32","value": "3002"} + ,{"name": "Prop_Axis1Type_Int32","value": "3003"} + ,{"name": "Prop_Axis2Type_Int32","value": "3004"} + ,{"name": "Prop_Axis3Type_Int32","value": "3005"} + ,{"name": "Prop_Axis4Type_Int32","value": "3006"} + ,{"name": "Prop_FieldOfViewLeftDegrees_Float","value": "4000"} + ,{"name": "Prop_FieldOfViewRightDegrees_Float","value": "4001"} + ,{"name": "Prop_FieldOfViewTopDegrees_Float","value": "4002"} + ,{"name": "Prop_FieldOfViewBottomDegrees_Float","value": "4003"} + ,{"name": "Prop_TrackingRangeMinimumMeters_Float","value": "4004"} + ,{"name": "Prop_TrackingRangeMaximumMeters_Float","value": "4005"} + ,{"name": "Prop_ModeLabel_String","value": "4006"} + ,{"name": "Prop_VendorSpecific_Reserved_Start","value": "10000"} + ,{"name": "Prop_VendorSpecific_Reserved_End","value": "10999"} +]} +, {"enumname": "vr::ETrackedPropertyError","values": [ + {"name": "TrackedProp_Success","value": "0"} + ,{"name": "TrackedProp_WrongDataType","value": "1"} + ,{"name": "TrackedProp_WrongDeviceClass","value": "2"} + ,{"name": "TrackedProp_BufferTooSmall","value": "3"} + ,{"name": "TrackedProp_UnknownProperty","value": "4"} + ,{"name": "TrackedProp_InvalidDevice","value": "5"} + ,{"name": "TrackedProp_CouldNotContactServer","value": "6"} + ,{"name": "TrackedProp_ValueNotProvidedByDevice","value": "7"} + ,{"name": "TrackedProp_StringExceedsMaximumLength","value": "8"} + ,{"name": "TrackedProp_NotYetAvailable","value": "9"} +]} +, {"enumname": "vr::EVRSubmitFlags","values": [ + {"name": "Submit_Default","value": "0"} + ,{"name": "Submit_LensDistortionAlreadyApplied","value": "1"} + ,{"name": "Submit_GlRenderBuffer","value": "2"} +]} +, {"enumname": "vr::EVRState","values": [ + {"name": "VRState_Undefined","value": "-1"} + ,{"name": "VRState_Off","value": "0"} + ,{"name": "VRState_Searching","value": "1"} + ,{"name": "VRState_Searching_Alert","value": "2"} + ,{"name": "VRState_Ready","value": "3"} + ,{"name": "VRState_Ready_Alert","value": "4"} + ,{"name": "VRState_NotReady","value": "5"} + ,{"name": "VRState_Standby","value": "6"} +]} +, {"enumname": "vr::EVREventType","values": [ + {"name": "VREvent_None","value": "0"} + ,{"name": "VREvent_TrackedDeviceActivated","value": "100"} + ,{"name": "VREvent_TrackedDeviceDeactivated","value": "101"} + ,{"name": "VREvent_TrackedDeviceUpdated","value": "102"} + ,{"name": "VREvent_TrackedDeviceUserInteractionStarted","value": "103"} + ,{"name": "VREvent_TrackedDeviceUserInteractionEnded","value": "104"} + ,{"name": "VREvent_IpdChanged","value": "105"} + ,{"name": "VREvent_EnterStandbyMode","value": "106"} + ,{"name": "VREvent_LeaveStandbyMode","value": "107"} + ,{"name": "VREvent_TrackedDeviceRoleChanged","value": "108"} + ,{"name": "VREvent_ButtonPress","value": "200"} + ,{"name": "VREvent_ButtonUnpress","value": "201"} + ,{"name": "VREvent_ButtonTouch","value": "202"} + ,{"name": "VREvent_ButtonUntouch","value": "203"} + ,{"name": "VREvent_MouseMove","value": "300"} + ,{"name": "VREvent_MouseButtonDown","value": "301"} + ,{"name": "VREvent_MouseButtonUp","value": "302"} + ,{"name": "VREvent_FocusEnter","value": "303"} + ,{"name": "VREvent_FocusLeave","value": "304"} + ,{"name": "VREvent_Scroll","value": "305"} + ,{"name": "VREvent_TouchPadMove","value": "306"} + ,{"name": "VREvent_InputFocusCaptured","value": "400"} + ,{"name": "VREvent_InputFocusReleased","value": "401"} + ,{"name": "VREvent_SceneFocusLost","value": "402"} + ,{"name": "VREvent_SceneFocusGained","value": "403"} + ,{"name": "VREvent_SceneApplicationChanged","value": "404"} + ,{"name": "VREvent_SceneFocusChanged","value": "405"} + ,{"name": "VREvent_InputFocusChanged","value": "406"} + ,{"name": "VREvent_SceneApplicationSecondaryRenderingStarted","value": "407"} + ,{"name": "VREvent_HideRenderModels","value": "410"} + ,{"name": "VREvent_ShowRenderModels","value": "411"} + ,{"name": "VREvent_OverlayShown","value": "500"} + ,{"name": "VREvent_OverlayHidden","value": "501"} + ,{"name": "VREvent_DashboardActivated","value": "502"} + ,{"name": "VREvent_DashboardDeactivated","value": "503"} + ,{"name": "VREvent_DashboardThumbSelected","value": "504"} + ,{"name": "VREvent_DashboardRequested","value": "505"} + ,{"name": "VREvent_ResetDashboard","value": "506"} + ,{"name": "VREvent_RenderToast","value": "507"} + ,{"name": "VREvent_ImageLoaded","value": "508"} + ,{"name": "VREvent_ShowKeyboard","value": "509"} + ,{"name": "VREvent_HideKeyboard","value": "510"} + ,{"name": "VREvent_OverlayGamepadFocusGained","value": "511"} + ,{"name": "VREvent_OverlayGamepadFocusLost","value": "512"} + ,{"name": "VREvent_OverlaySharedTextureChanged","value": "513"} + ,{"name": "VREvent_DashboardGuideButtonDown","value": "514"} + ,{"name": "VREvent_DashboardGuideButtonUp","value": "515"} + ,{"name": "VREvent_ScreenshotTriggered","value": "516"} + ,{"name": "VREvent_ImageFailed","value": "517"} + ,{"name": "VREvent_RequestScreenshot","value": "520"} + ,{"name": "VREvent_ScreenshotTaken","value": "521"} + ,{"name": "VREvent_ScreenshotFailed","value": "522"} + ,{"name": "VREvent_SubmitScreenshotToDashboard","value": "523"} + ,{"name": "VREvent_Notification_Shown","value": "600"} + ,{"name": "VREvent_Notification_Hidden","value": "601"} + ,{"name": "VREvent_Notification_BeginInteraction","value": "602"} + ,{"name": "VREvent_Notification_Destroyed","value": "603"} + ,{"name": "VREvent_Quit","value": "700"} + ,{"name": "VREvent_ProcessQuit","value": "701"} + ,{"name": "VREvent_QuitAborted_UserPrompt","value": "702"} + ,{"name": "VREvent_QuitAcknowledged","value": "703"} + ,{"name": "VREvent_DriverRequestedQuit","value": "704"} + ,{"name": "VREvent_ChaperoneDataHasChanged","value": "800"} + ,{"name": "VREvent_ChaperoneUniverseHasChanged","value": "801"} + ,{"name": "VREvent_ChaperoneTempDataHasChanged","value": "802"} + ,{"name": "VREvent_ChaperoneSettingsHaveChanged","value": "803"} + ,{"name": "VREvent_SeatedZeroPoseReset","value": "804"} + ,{"name": "VREvent_AudioSettingsHaveChanged","value": "820"} + ,{"name": "VREvent_BackgroundSettingHasChanged","value": "850"} + ,{"name": "VREvent_CameraSettingsHaveChanged","value": "851"} + ,{"name": "VREvent_ReprojectionSettingHasChanged","value": "852"} + ,{"name": "VREvent_ModelSkinSettingsHaveChanged","value": "853"} + ,{"name": "VREvent_EnvironmentSettingsHaveChanged","value": "854"} + ,{"name": "VREvent_StatusUpdate","value": "900"} + ,{"name": "VREvent_MCImageUpdated","value": "1000"} + ,{"name": "VREvent_FirmwareUpdateStarted","value": "1100"} + ,{"name": "VREvent_FirmwareUpdateFinished","value": "1101"} + ,{"name": "VREvent_KeyboardClosed","value": "1200"} + ,{"name": "VREvent_KeyboardCharInput","value": "1201"} + ,{"name": "VREvent_KeyboardDone","value": "1202"} + ,{"name": "VREvent_ApplicationTransitionStarted","value": "1300"} + ,{"name": "VREvent_ApplicationTransitionAborted","value": "1301"} + ,{"name": "VREvent_ApplicationTransitionNewAppStarted","value": "1302"} + ,{"name": "VREvent_ApplicationListUpdated","value": "1303"} + ,{"name": "VREvent_Compositor_MirrorWindowShown","value": "1400"} + ,{"name": "VREvent_Compositor_MirrorWindowHidden","value": "1401"} + ,{"name": "VREvent_Compositor_ChaperoneBoundsShown","value": "1410"} + ,{"name": "VREvent_Compositor_ChaperoneBoundsHidden","value": "1411"} + ,{"name": "VREvent_TrackedCamera_StartVideoStream","value": "1500"} + ,{"name": "VREvent_TrackedCamera_StopVideoStream","value": "1501"} + ,{"name": "VREvent_TrackedCamera_PauseVideoStream","value": "1502"} + ,{"name": "VREvent_TrackedCamera_ResumeVideoStream","value": "1503"} + ,{"name": "VREvent_PerformanceTest_EnableCapture","value": "1600"} + ,{"name": "VREvent_PerformanceTest_DisableCapture","value": "1601"} + ,{"name": "VREvent_PerformanceTest_FidelityLevel","value": "1602"} + ,{"name": "VREvent_VendorSpecific_Reserved_Start","value": "10000"} + ,{"name": "VREvent_VendorSpecific_Reserved_End","value": "19999"} +]} +, {"enumname": "vr::EDeviceActivityLevel","values": [ + {"name": "k_EDeviceActivityLevel_Unknown","value": "-1"} + ,{"name": "k_EDeviceActivityLevel_Idle","value": "0"} + ,{"name": "k_EDeviceActivityLevel_UserInteraction","value": "1"} + ,{"name": "k_EDeviceActivityLevel_UserInteraction_Timeout","value": "2"} + ,{"name": "k_EDeviceActivityLevel_Standby","value": "3"} +]} +, {"enumname": "vr::EVRButtonId","values": [ + {"name": "k_EButton_System","value": "0"} + ,{"name": "k_EButton_ApplicationMenu","value": "1"} + ,{"name": "k_EButton_Grip","value": "2"} + ,{"name": "k_EButton_DPad_Left","value": "3"} + ,{"name": "k_EButton_DPad_Up","value": "4"} + ,{"name": "k_EButton_DPad_Right","value": "5"} + ,{"name": "k_EButton_DPad_Down","value": "6"} + ,{"name": "k_EButton_A","value": "7"} + ,{"name": "k_EButton_Axis0","value": "32"} + ,{"name": "k_EButton_Axis1","value": "33"} + ,{"name": "k_EButton_Axis2","value": "34"} + ,{"name": "k_EButton_Axis3","value": "35"} + ,{"name": "k_EButton_Axis4","value": "36"} + ,{"name": "k_EButton_SteamVR_Touchpad","value": "32"} + ,{"name": "k_EButton_SteamVR_Trigger","value": "33"} + ,{"name": "k_EButton_Dashboard_Back","value": "2"} + ,{"name": "k_EButton_Max","value": "64"} +]} +, {"enumname": "vr::EVRMouseButton","values": [ + {"name": "VRMouseButton_Left","value": "1"} + ,{"name": "VRMouseButton_Right","value": "2"} + ,{"name": "VRMouseButton_Middle","value": "4"} +]} +, {"enumname": "vr::EVRControllerAxisType","values": [ + {"name": "k_eControllerAxis_None","value": "0"} + ,{"name": "k_eControllerAxis_TrackPad","value": "1"} + ,{"name": "k_eControllerAxis_Joystick","value": "2"} + ,{"name": "k_eControllerAxis_Trigger","value": "3"} +]} +, {"enumname": "vr::EVRControllerEventOutputType","values": [ + {"name": "ControllerEventOutput_OSEvents","value": "0"} + ,{"name": "ControllerEventOutput_VREvents","value": "1"} +]} +, {"enumname": "vr::ECollisionBoundsStyle","values": [ + {"name": "COLLISION_BOUNDS_STYLE_BEGINNER","value": "0"} + ,{"name": "COLLISION_BOUNDS_STYLE_INTERMEDIATE","value": "1"} + ,{"name": "COLLISION_BOUNDS_STYLE_SQUARES","value": "2"} + ,{"name": "COLLISION_BOUNDS_STYLE_ADVANCED","value": "3"} + ,{"name": "COLLISION_BOUNDS_STYLE_NONE","value": "4"} + ,{"name": "COLLISION_BOUNDS_STYLE_COUNT","value": "5"} +]} +, {"enumname": "vr::EVROverlayError","values": [ + {"name": "VROverlayError_None","value": "0"} + ,{"name": "VROverlayError_UnknownOverlay","value": "10"} + ,{"name": "VROverlayError_InvalidHandle","value": "11"} + ,{"name": "VROverlayError_PermissionDenied","value": "12"} + ,{"name": "VROverlayError_OverlayLimitExceeded","value": "13"} + ,{"name": "VROverlayError_WrongVisibilityType","value": "14"} + ,{"name": "VROverlayError_KeyTooLong","value": "15"} + ,{"name": "VROverlayError_NameTooLong","value": "16"} + ,{"name": "VROverlayError_KeyInUse","value": "17"} + ,{"name": "VROverlayError_WrongTransformType","value": "18"} + ,{"name": "VROverlayError_InvalidTrackedDevice","value": "19"} + ,{"name": "VROverlayError_InvalidParameter","value": "20"} + ,{"name": "VROverlayError_ThumbnailCantBeDestroyed","value": "21"} + ,{"name": "VROverlayError_ArrayTooSmall","value": "22"} + ,{"name": "VROverlayError_RequestFailed","value": "23"} + ,{"name": "VROverlayError_InvalidTexture","value": "24"} + ,{"name": "VROverlayError_UnableToLoadFile","value": "25"} + ,{"name": "VROVerlayError_KeyboardAlreadyInUse","value": "26"} + ,{"name": "VROverlayError_NoNeighbor","value": "27"} +]} +, {"enumname": "vr::EVRApplicationType","values": [ + {"name": "VRApplication_Other","value": "0"} + ,{"name": "VRApplication_Scene","value": "1"} + ,{"name": "VRApplication_Overlay","value": "2"} + ,{"name": "VRApplication_Background","value": "3"} + ,{"name": "VRApplication_Utility","value": "4"} + ,{"name": "VRApplication_VRMonitor","value": "5"} +]} +, {"enumname": "vr::EVRFirmwareError","values": [ + {"name": "VRFirmwareError_None","value": "0"} + ,{"name": "VRFirmwareError_Success","value": "1"} + ,{"name": "VRFirmwareError_Fail","value": "2"} +]} +, {"enumname": "vr::EVRNotificationError","values": [ + {"name": "VRNotificationError_OK","value": "0"} + ,{"name": "VRNotificationError_InvalidNotificationId","value": "100"} + ,{"name": "VRNotificationError_NotificationQueueFull","value": "101"} + ,{"name": "VRNotificationError_InvalidOverlayHandle","value": "102"} + ,{"name": "VRNotificationError_SystemWithUserValueAlreadyExists","value": "103"} +]} +, {"enumname": "vr::EVRInitError","values": [ + {"name": "VRInitError_None","value": "0"} + ,{"name": "VRInitError_Unknown","value": "1"} + ,{"name": "VRInitError_Init_InstallationNotFound","value": "100"} + ,{"name": "VRInitError_Init_InstallationCorrupt","value": "101"} + ,{"name": "VRInitError_Init_VRClientDLLNotFound","value": "102"} + ,{"name": "VRInitError_Init_FileNotFound","value": "103"} + ,{"name": "VRInitError_Init_FactoryNotFound","value": "104"} + ,{"name": "VRInitError_Init_InterfaceNotFound","value": "105"} + ,{"name": "VRInitError_Init_InvalidInterface","value": "106"} + ,{"name": "VRInitError_Init_UserConfigDirectoryInvalid","value": "107"} + ,{"name": "VRInitError_Init_HmdNotFound","value": "108"} + ,{"name": "VRInitError_Init_NotInitialized","value": "109"} + ,{"name": "VRInitError_Init_PathRegistryNotFound","value": "110"} + ,{"name": "VRInitError_Init_NoConfigPath","value": "111"} + ,{"name": "VRInitError_Init_NoLogPath","value": "112"} + ,{"name": "VRInitError_Init_PathRegistryNotWritable","value": "113"} + ,{"name": "VRInitError_Init_AppInfoInitFailed","value": "114"} + ,{"name": "VRInitError_Init_Retry","value": "115"} + ,{"name": "VRInitError_Init_InitCanceledByUser","value": "116"} + ,{"name": "VRInitError_Init_AnotherAppLaunching","value": "117"} + ,{"name": "VRInitError_Init_SettingsInitFailed","value": "118"} + ,{"name": "VRInitError_Init_ShuttingDown","value": "119"} + ,{"name": "VRInitError_Init_TooManyObjects","value": "120"} + ,{"name": "VRInitError_Init_NoServerForBackgroundApp","value": "121"} + ,{"name": "VRInitError_Init_NotSupportedWithCompositor","value": "122"} + ,{"name": "VRInitError_Init_NotAvailableToUtilityApps","value": "123"} + ,{"name": "VRInitError_Init_Internal","value": "124"} + ,{"name": "VRInitError_Driver_Failed","value": "200"} + ,{"name": "VRInitError_Driver_Unknown","value": "201"} + ,{"name": "VRInitError_Driver_HmdUnknown","value": "202"} + ,{"name": "VRInitError_Driver_NotLoaded","value": "203"} + ,{"name": "VRInitError_Driver_RuntimeOutOfDate","value": "204"} + ,{"name": "VRInitError_Driver_HmdInUse","value": "205"} + ,{"name": "VRInitError_Driver_NotCalibrated","value": "206"} + ,{"name": "VRInitError_Driver_CalibrationInvalid","value": "207"} + ,{"name": "VRInitError_Driver_HmdDisplayNotFound","value": "208"} + ,{"name": "VRInitError_IPC_ServerInitFailed","value": "300"} + ,{"name": "VRInitError_IPC_ConnectFailed","value": "301"} + ,{"name": "VRInitError_IPC_SharedStateInitFailed","value": "302"} + ,{"name": "VRInitError_IPC_CompositorInitFailed","value": "303"} + ,{"name": "VRInitError_IPC_MutexInitFailed","value": "304"} + ,{"name": "VRInitError_IPC_Failed","value": "305"} + ,{"name": "VRInitError_Compositor_Failed","value": "400"} + ,{"name": "VRInitError_Compositor_D3D11HardwareRequired","value": "401"} + ,{"name": "VRInitError_Compositor_FirmwareRequiresUpdate","value": "402"} + ,{"name": "VRInitError_Compositor_OverlayInitFailed","value": "403"} + ,{"name": "VRInitError_Compositor_ScreenshotsInitFailed","value": "404"} + ,{"name": "VRInitError_VendorSpecific_UnableToConnectToOculusRuntime","value": "1000"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_CantOpenDevice","value": "1101"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_UnableToRequestConfigStart","value": "1102"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_NoStoredConfig","value": "1103"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_ConfigTooBig","value": "1104"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_ConfigTooSmall","value": "1105"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_UnableToInitZLib","value": "1106"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_CantReadFirmwareVersion","value": "1107"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_UnableToSendUserDataStart","value": "1108"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_UnableToGetUserDataStart","value": "1109"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_UnableToGetUserDataNext","value": "1110"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_UserDataAddressRange","value": "1111"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_UserDataError","value": "1112"} + ,{"name": "VRInitError_VendorSpecific_HmdFound_ConfigFailedSanityCheck","value": "1113"} + ,{"name": "VRInitError_Steam_SteamInstallationNotFound","value": "2000"} +]} +, {"enumname": "vr::EVRScreenshotType","values": [ + {"name": "VRScreenshotType_None","value": "0"} + ,{"name": "VRScreenshotType_Mono","value": "1"} + ,{"name": "VRScreenshotType_Stereo","value": "2"} + ,{"name": "VRScreenshotType_Cubemap","value": "3"} + ,{"name": "VRScreenshotType_MonoPanorama","value": "4"} + ,{"name": "VRScreenshotType_StereoPanorama","value": "5"} +]} +, {"enumname": "vr::EVRScreenshotPropertyFilenames","values": [ + {"name": "VRScreenshotPropertyFilenames_Preview","value": "0"} + ,{"name": "VRScreenshotPropertyFilenames_VR","value": "1"} +]} +, {"enumname": "vr::EVRTrackedCameraError","values": [ + {"name": "VRTrackedCameraError_None","value": "0"} + ,{"name": "VRTrackedCameraError_OperationFailed","value": "100"} + ,{"name": "VRTrackedCameraError_InvalidHandle","value": "101"} + ,{"name": "VRTrackedCameraError_InvalidFrameHeaderVersion","value": "102"} + ,{"name": "VRTrackedCameraError_OutOfHandles","value": "103"} + ,{"name": "VRTrackedCameraError_IPCFailure","value": "104"} + ,{"name": "VRTrackedCameraError_NotSupportedForThisDevice","value": "105"} + ,{"name": "VRTrackedCameraError_SharedMemoryFailure","value": "106"} + ,{"name": "VRTrackedCameraError_FrameBufferingFailure","value": "107"} + ,{"name": "VRTrackedCameraError_StreamSetupFailure","value": "108"} + ,{"name": "VRTrackedCameraError_InvalidGLTextureId","value": "109"} + ,{"name": "VRTrackedCameraError_InvalidSharedTextureHandle","value": "110"} + ,{"name": "VRTrackedCameraError_FailedToGetGLTextureId","value": "111"} + ,{"name": "VRTrackedCameraError_SharedTextureFailure","value": "112"} + ,{"name": "VRTrackedCameraError_NoFrameAvailable","value": "113"} + ,{"name": "VRTrackedCameraError_InvalidArgument","value": "114"} + ,{"name": "VRTrackedCameraError_InvalidFrameBufferSize","value": "115"} +]} +, {"enumname": "vr::EVRTrackedCameraFrameType","values": [ + {"name": "VRTrackedCameraFrameType_Distorted","value": "0"} + ,{"name": "VRTrackedCameraFrameType_Undistorted","value": "1"} + ,{"name": "VRTrackedCameraFrameType_MaximumUndistorted","value": "2"} + ,{"name": "MAX_CAMERA_FRAME_TYPES","value": "3"} +]} +, {"enumname": "vr::EVRApplicationError","values": [ + {"name": "VRApplicationError_None","value": "0"} + ,{"name": "VRApplicationError_AppKeyAlreadyExists","value": "100"} + ,{"name": "VRApplicationError_NoManifest","value": "101"} + ,{"name": "VRApplicationError_NoApplication","value": "102"} + ,{"name": "VRApplicationError_InvalidIndex","value": "103"} + ,{"name": "VRApplicationError_UnknownApplication","value": "104"} + ,{"name": "VRApplicationError_IPCFailed","value": "105"} + ,{"name": "VRApplicationError_ApplicationAlreadyRunning","value": "106"} + ,{"name": "VRApplicationError_InvalidManifest","value": "107"} + ,{"name": "VRApplicationError_InvalidApplication","value": "108"} + ,{"name": "VRApplicationError_LaunchFailed","value": "109"} + ,{"name": "VRApplicationError_ApplicationAlreadyStarting","value": "110"} + ,{"name": "VRApplicationError_LaunchInProgress","value": "111"} + ,{"name": "VRApplicationError_OldApplicationQuitting","value": "112"} + ,{"name": "VRApplicationError_TransitionAborted","value": "113"} + ,{"name": "VRApplicationError_IsTemplate","value": "114"} + ,{"name": "VRApplicationError_BufferTooSmall","value": "200"} + ,{"name": "VRApplicationError_PropertyNotSet","value": "201"} + ,{"name": "VRApplicationError_UnknownProperty","value": "202"} + ,{"name": "VRApplicationError_InvalidParameter","value": "203"} +]} +, {"enumname": "vr::EVRApplicationProperty","values": [ + {"name": "VRApplicationProperty_Name_String","value": "0"} + ,{"name": "VRApplicationProperty_LaunchType_String","value": "11"} + ,{"name": "VRApplicationProperty_WorkingDirectory_String","value": "12"} + ,{"name": "VRApplicationProperty_BinaryPath_String","value": "13"} + ,{"name": "VRApplicationProperty_Arguments_String","value": "14"} + ,{"name": "VRApplicationProperty_URL_String","value": "15"} + ,{"name": "VRApplicationProperty_Description_String","value": "50"} + ,{"name": "VRApplicationProperty_NewsURL_String","value": "51"} + ,{"name": "VRApplicationProperty_ImagePath_String","value": "52"} + ,{"name": "VRApplicationProperty_Source_String","value": "53"} + ,{"name": "VRApplicationProperty_IsDashboardOverlay_Bool","value": "60"} + ,{"name": "VRApplicationProperty_IsTemplate_Bool","value": "61"} + ,{"name": "VRApplicationProperty_IsInstanced_Bool","value": "62"} + ,{"name": "VRApplicationProperty_LastLaunchTime_Uint64","value": "70"} +]} +, {"enumname": "vr::EVRApplicationTransitionState","values": [ + {"name": "VRApplicationTransition_None","value": "0"} + ,{"name": "VRApplicationTransition_OldAppQuitSent","value": "10"} + ,{"name": "VRApplicationTransition_WaitingForExternalLaunch","value": "11"} + ,{"name": "VRApplicationTransition_NewAppLaunched","value": "20"} +]} +, {"enumname": "vr::ChaperoneCalibrationState","values": [ + {"name": "ChaperoneCalibrationState_OK","value": "1"} + ,{"name": "ChaperoneCalibrationState_Warning","value": "100"} + ,{"name": "ChaperoneCalibrationState_Warning_BaseStationMayHaveMoved","value": "101"} + ,{"name": "ChaperoneCalibrationState_Warning_BaseStationRemoved","value": "102"} + ,{"name": "ChaperoneCalibrationState_Warning_SeatedBoundsInvalid","value": "103"} + ,{"name": "ChaperoneCalibrationState_Error","value": "200"} + ,{"name": "ChaperoneCalibrationState_Error_BaseStationUninitalized","value": "201"} + ,{"name": "ChaperoneCalibrationState_Error_BaseStationConflict","value": "202"} + ,{"name": "ChaperoneCalibrationState_Error_PlayAreaInvalid","value": "203"} + ,{"name": "ChaperoneCalibrationState_Error_CollisionBoundsInvalid","value": "204"} +]} +, {"enumname": "vr::EChaperoneConfigFile","values": [ + {"name": "EChaperoneConfigFile_Live","value": "1"} + ,{"name": "EChaperoneConfigFile_Temp","value": "2"} +]} +, {"enumname": "vr::EChaperoneImportFlags","values": [ + {"name": "EChaperoneImport_BoundsOnly","value": "1"} +]} +, {"enumname": "vr::EVRCompositorError","values": [ + {"name": "VRCompositorError_None","value": "0"} + ,{"name": "VRCompositorError_RequestFailed","value": "1"} + ,{"name": "VRCompositorError_IncompatibleVersion","value": "100"} + ,{"name": "VRCompositorError_DoNotHaveFocus","value": "101"} + ,{"name": "VRCompositorError_InvalidTexture","value": "102"} + ,{"name": "VRCompositorError_IsNotSceneApplication","value": "103"} + ,{"name": "VRCompositorError_TextureIsOnWrongDevice","value": "104"} + ,{"name": "VRCompositorError_TextureUsesUnsupportedFormat","value": "105"} + ,{"name": "VRCompositorError_SharedTexturesNotSupported","value": "106"} + ,{"name": "VRCompositorError_IndexOutOfRange","value": "107"} +]} +, {"enumname": "vr::VROverlayInputMethod","values": [ + {"name": "VROverlayInputMethod_None","value": "0"} + ,{"name": "VROverlayInputMethod_Mouse","value": "1"} +]} +, {"enumname": "vr::VROverlayTransformType","values": [ + {"name": "VROverlayTransform_Absolute","value": "0"} + ,{"name": "VROverlayTransform_TrackedDeviceRelative","value": "1"} + ,{"name": "VROverlayTransform_SystemOverlay","value": "2"} + ,{"name": "VROverlayTransform_TrackedComponent","value": "3"} +]} +, {"enumname": "vr::VROverlayFlags","values": [ + {"name": "VROverlayFlags_None","value": "0"} + ,{"name": "VROverlayFlags_Curved","value": "1"} + ,{"name": "VROverlayFlags_RGSS4X","value": "2"} + ,{"name": "VROverlayFlags_NoDashboardTab","value": "3"} + ,{"name": "VROverlayFlags_AcceptsGamepadEvents","value": "4"} + ,{"name": "VROverlayFlags_ShowGamepadFocus","value": "5"} + ,{"name": "VROverlayFlags_SendVRScrollEvents","value": "6"} + ,{"name": "VROverlayFlags_SendVRTouchpadEvents","value": "7"} + ,{"name": "VROverlayFlags_ShowTouchPadScrollWheel","value": "8"} + ,{"name": "VROverlayFlags_TransferOwnershipToInternalProcess","value": "9"} + ,{"name": "VROverlayFlags_SideBySide_Parallel","value": "10"} + ,{"name": "VROverlayFlags_SideBySide_Crossed","value": "11"} + ,{"name": "VROverlayFlags_Panorama","value": "12"} + ,{"name": "VROverlayFlags_StereoPanorama","value": "13"} +]} +, {"enumname": "vr::EGamepadTextInputMode","values": [ + {"name": "k_EGamepadTextInputModeNormal","value": "0"} + ,{"name": "k_EGamepadTextInputModePassword","value": "1"} + ,{"name": "k_EGamepadTextInputModeSubmit","value": "2"} +]} +, {"enumname": "vr::EGamepadTextInputLineMode","values": [ + {"name": "k_EGamepadTextInputLineModeSingleLine","value": "0"} + ,{"name": "k_EGamepadTextInputLineModeMultipleLines","value": "1"} +]} +, {"enumname": "vr::EOverlayDirection","values": [ + {"name": "OverlayDirection_Up","value": "0"} + ,{"name": "OverlayDirection_Down","value": "1"} + ,{"name": "OverlayDirection_Left","value": "2"} + ,{"name": "OverlayDirection_Right","value": "3"} + ,{"name": "OverlayDirection_Count","value": "4"} +]} +, {"enumname": "vr::EVRRenderModelError","values": [ + {"name": "VRRenderModelError_None","value": "0"} + ,{"name": "VRRenderModelError_Loading","value": "100"} + ,{"name": "VRRenderModelError_NotSupported","value": "200"} + ,{"name": "VRRenderModelError_InvalidArg","value": "300"} + ,{"name": "VRRenderModelError_InvalidModel","value": "301"} + ,{"name": "VRRenderModelError_NoShapes","value": "302"} + ,{"name": "VRRenderModelError_MultipleShapes","value": "303"} + ,{"name": "VRRenderModelError_TooManyVertices","value": "304"} + ,{"name": "VRRenderModelError_MultipleTextures","value": "305"} + ,{"name": "VRRenderModelError_BufferTooSmall","value": "306"} + ,{"name": "VRRenderModelError_NotEnoughNormals","value": "307"} + ,{"name": "VRRenderModelError_NotEnoughTexCoords","value": "308"} + ,{"name": "VRRenderModelError_InvalidTexture","value": "400"} +]} +, {"enumname": "vr::EVRComponentProperty","values": [ + {"name": "VRComponentProperty_IsStatic","value": "1"} + ,{"name": "VRComponentProperty_IsVisible","value": "2"} + ,{"name": "VRComponentProperty_IsTouched","value": "4"} + ,{"name": "VRComponentProperty_IsPressed","value": "8"} + ,{"name": "VRComponentProperty_IsScrolled","value": "16"} +]} +, {"enumname": "vr::EVRNotificationType","values": [ + {"name": "EVRNotificationType_Transient","value": "0"} + ,{"name": "EVRNotificationType_Persistent","value": "1"} + ,{"name": "EVRNotificationType_Transient_SystemWithUserValue","value": "2"} +]} +, {"enumname": "vr::EVRNotificationStyle","values": [ + {"name": "EVRNotificationStyle_None","value": "0"} + ,{"name": "EVRNotificationStyle_Application","value": "100"} + ,{"name": "EVRNotificationStyle_Contact_Disabled","value": "200"} + ,{"name": "EVRNotificationStyle_Contact_Enabled","value": "201"} + ,{"name": "EVRNotificationStyle_Contact_Active","value": "202"} +]} +, {"enumname": "vr::EVRSettingsError","values": [ + {"name": "VRSettingsError_None","value": "0"} + ,{"name": "VRSettingsError_IPCFailed","value": "1"} + ,{"name": "VRSettingsError_WriteFailed","value": "2"} + ,{"name": "VRSettingsError_ReadFailed","value": "3"} +]} +, {"enumname": "vr::EVRScreenshotError","values": [ + {"name": "VRScreenshotError_None","value": "0"} + ,{"name": "VRScreenshotError_RequestFailed","value": "1"} + ,{"name": "VRScreenshotError_IncompatibleVersion","value": "100"} + ,{"name": "VRScreenshotError_NotFound","value": "101"} + ,{"name": "VRScreenshotError_BufferTooSmall","value": "102"} + ,{"name": "VRScreenshotError_ScreenshotAlreadyInProgress","value": "108"} +]} +], +"consts":[{ + "constname": "k_unTrackingStringSize","consttype": "const uint32_t", "constval": "32"} +,{ + "constname": "k_unMaxDriverDebugResponseSize","consttype": "const uint32_t", "constval": "32768"} +,{ + "constname": "k_unTrackedDeviceIndex_Hmd","consttype": "const uint32_t", "constval": "0"} +,{ + "constname": "k_unMaxTrackedDeviceCount","consttype": "const uint32_t", "constval": "16"} +,{ + "constname": "k_unTrackedDeviceIndexOther","consttype": "const uint32_t", "constval": "4294967294"} +,{ + "constname": "k_unTrackedDeviceIndexInvalid","consttype": "const uint32_t", "constval": "4294967295"} +,{ + "constname": "k_unMaxPropertyStringSize","consttype": "const uint32_t", "constval": "32768"} +,{ + "constname": "k_unControllerStateAxisCount","consttype": "const uint32_t", "constval": "5"} +,{ + "constname": "k_ulOverlayHandleInvalid","consttype": "const VROverlayHandle_t", "constval": "0"} +,{ + "constname": "k_unScreenshotHandleInvalid","consttype": "const uint32_t", "constval": "0"} +,{ + "constname": "IVRSystem_Version","consttype": "const char *const", "constval": "IVRSystem_012"} +,{ + "constname": "IVRExtendedDisplay_Version","consttype": "const char *const", "constval": "IVRExtendedDisplay_001"} +,{ + "constname": "IVRTrackedCamera_Version","consttype": "const char *const", "constval": "IVRTrackedCamera_003"} +,{ + "constname": "k_unMaxApplicationKeyLength","consttype": "const uint32_t", "constval": "128"} +,{ + "constname": "IVRApplications_Version","consttype": "const char *const", "constval": "IVRApplications_005"} +,{ + "constname": "IVRChaperone_Version","consttype": "const char *const", "constval": "IVRChaperone_003"} +,{ + "constname": "IVRChaperoneSetup_Version","consttype": "const char *const", "constval": "IVRChaperoneSetup_005"} +,{ + "constname": "IVRCompositor_Version","consttype": "const char *const", "constval": "IVRCompositor_015"} +,{ + "constname": "k_unVROverlayMaxKeyLength","consttype": "const uint32_t", "constval": "128"} +,{ + "constname": "k_unVROverlayMaxNameLength","consttype": "const uint32_t", "constval": "128"} +,{ + "constname": "k_unMaxOverlayCount","consttype": "const uint32_t", "constval": "32"} +,{ + "constname": "IVROverlay_Version","consttype": "const char *const", "constval": "IVROverlay_012"} +,{ + "constname": "k_pch_Controller_Component_GDC2015","consttype": "const char *const", "constval": "gdc2015"} +,{ + "constname": "k_pch_Controller_Component_Base","consttype": "const char *const", "constval": "base"} +,{ + "constname": "k_pch_Controller_Component_Tip","consttype": "const char *const", "constval": "tip"} +,{ + "constname": "k_pch_Controller_Component_HandGrip","consttype": "const char *const", "constval": "handgrip"} +,{ + "constname": "k_pch_Controller_Component_Status","consttype": "const char *const", "constval": "status"} +,{ + "constname": "IVRRenderModels_Version","consttype": "const char *const", "constval": "IVRRenderModels_005"} +,{ + "constname": "k_unNotificationTextMaxSize","consttype": "const uint32_t", "constval": "256"} +,{ + "constname": "IVRNotifications_Version","consttype": "const char *const", "constval": "IVRNotifications_002"} +,{ + "constname": "k_unMaxSettingsKeyLength","consttype": "const uint32_t", "constval": "128"} +,{ + "constname": "IVRSettings_Version","consttype": "const char *const", "constval": "IVRSettings_001"} +,{ + "constname": "k_pch_SteamVR_Section","consttype": "const char *const", "constval": "steamvr"} +,{ + "constname": "k_pch_SteamVR_RequireHmd_String","consttype": "const char *const", "constval": "requireHmd"} +,{ + "constname": "k_pch_SteamVR_ForcedDriverKey_String","consttype": "const char *const", "constval": "forcedDriver"} +,{ + "constname": "k_pch_SteamVR_ForcedHmdKey_String","consttype": "const char *const", "constval": "forcedHmd"} +,{ + "constname": "k_pch_SteamVR_DisplayDebug_Bool","consttype": "const char *const", "constval": "displayDebug"} +,{ + "constname": "k_pch_SteamVR_DebugProcessPipe_String","consttype": "const char *const", "constval": "debugProcessPipe"} +,{ + "constname": "k_pch_SteamVR_EnableDistortion_Bool","consttype": "const char *const", "constval": "enableDistortion"} +,{ + "constname": "k_pch_SteamVR_DisplayDebugX_Int32","consttype": "const char *const", "constval": "displayDebugX"} +,{ + "constname": "k_pch_SteamVR_DisplayDebugY_Int32","consttype": "const char *const", "constval": "displayDebugY"} +,{ + "constname": "k_pch_SteamVR_SendSystemButtonToAllApps_Bool","consttype": "const char *const", "constval": "sendSystemButtonToAllApps"} +,{ + "constname": "k_pch_SteamVR_LogLevel_Int32","consttype": "const char *const", "constval": "loglevel"} +,{ + "constname": "k_pch_SteamVR_IPD_Float","consttype": "const char *const", "constval": "ipd"} +,{ + "constname": "k_pch_SteamVR_Background_String","consttype": "const char *const", "constval": "background"} +,{ + "constname": "k_pch_SteamVR_BackgroundCameraHeight_Float","consttype": "const char *const", "constval": "backgroundCameraHeight"} +,{ + "constname": "k_pch_SteamVR_BackgroundDomeRadius_Float","consttype": "const char *const", "constval": "backgroundDomeRadius"} +,{ + "constname": "k_pch_SteamVR_Environment_String","consttype": "const char *const", "constval": "environment"} +,{ + "constname": "k_pch_SteamVR_GridColor_String","consttype": "const char *const", "constval": "gridColor"} +,{ + "constname": "k_pch_SteamVR_PlayAreaColor_String","consttype": "const char *const", "constval": "playAreaColor"} +,{ + "constname": "k_pch_SteamVR_ShowStage_Bool","consttype": "const char *const", "constval": "showStage"} +,{ + "constname": "k_pch_SteamVR_ActivateMultipleDrivers_Bool","consttype": "const char *const", "constval": "activateMultipleDrivers"} +,{ + "constname": "k_pch_SteamVR_PowerOffOnExit_Bool","consttype": "const char *const", "constval": "powerOffOnExit"} +,{ + "constname": "k_pch_SteamVR_StandbyAppRunningTimeout_Float","consttype": "const char *const", "constval": "standbyAppRunningTimeout"} +,{ + "constname": "k_pch_SteamVR_StandbyNoAppTimeout_Float","consttype": "const char *const", "constval": "standbyNoAppTimeout"} +,{ + "constname": "k_pch_SteamVR_DirectMode_Bool","consttype": "const char *const", "constval": "directMode"} +,{ + "constname": "k_pch_SteamVR_DirectModeEdidVid_Int32","consttype": "const char *const", "constval": "directModeEdidVid"} +,{ + "constname": "k_pch_SteamVR_DirectModeEdidPid_Int32","consttype": "const char *const", "constval": "directModeEdidPid"} +,{ + "constname": "k_pch_SteamVR_UsingSpeakers_Bool","consttype": "const char *const", "constval": "usingSpeakers"} +,{ + "constname": "k_pch_SteamVR_SpeakersForwardYawOffsetDegrees_Float","consttype": "const char *const", "constval": "speakersForwardYawOffsetDegrees"} +,{ + "constname": "k_pch_SteamVR_BaseStationPowerManagement_Bool","consttype": "const char *const", "constval": "basestationPowerManagement"} +,{ + "constname": "k_pch_SteamVR_NeverKillProcesses_Bool","consttype": "const char *const", "constval": "neverKillProcesses"} +,{ + "constname": "k_pch_SteamVR_RenderTargetMultiplier_Float","consttype": "const char *const", "constval": "renderTargetMultiplier"} +,{ + "constname": "k_pch_SteamVR_AllowReprojection_Bool","consttype": "const char *const", "constval": "allowReprojection"} +,{ + "constname": "k_pch_SteamVR_ForceReprojection_Bool","consttype": "const char *const", "constval": "forceReprojection"} +,{ + "constname": "k_pch_SteamVR_ForceFadeOnBadTracking_Bool","consttype": "const char *const", "constval": "forceFadeOnBadTracking"} +,{ + "constname": "k_pch_SteamVR_DefaultMirrorView_Int32","consttype": "const char *const", "constval": "defaultMirrorView"} +,{ + "constname": "k_pch_SteamVR_ShowMirrorView_Bool","consttype": "const char *const", "constval": "showMirrorView"} +,{ + "constname": "k_pch_Lighthouse_Section","consttype": "const char *const", "constval": "driver_lighthouse"} +,{ + "constname": "k_pch_Lighthouse_DisableIMU_Bool","consttype": "const char *const", "constval": "disableimu"} +,{ + "constname": "k_pch_Lighthouse_UseDisambiguation_String","consttype": "const char *const", "constval": "usedisambiguation"} +,{ + "constname": "k_pch_Lighthouse_DisambiguationDebug_Int32","consttype": "const char *const", "constval": "disambiguationdebug"} +,{ + "constname": "k_pch_Lighthouse_PrimaryBasestation_Int32","consttype": "const char *const", "constval": "primarybasestation"} +,{ + "constname": "k_pch_Lighthouse_LighthouseName_String","consttype": "const char *const", "constval": "lighthousename"} +,{ + "constname": "k_pch_Lighthouse_MaxIncidenceAngleDegrees_Float","consttype": "const char *const", "constval": "maxincidenceangledegrees"} +,{ + "constname": "k_pch_Lighthouse_UseLighthouseDirect_Bool","consttype": "const char *const", "constval": "uselighthousedirect"} +,{ + "constname": "k_pch_Lighthouse_DBHistory_Bool","consttype": "const char *const", "constval": "dbhistory"} +,{ + "constname": "k_pch_Null_Section","consttype": "const char *const", "constval": "driver_null"} +,{ + "constname": "k_pch_Null_EnableNullDriver_Bool","consttype": "const char *const", "constval": "enable"} +,{ + "constname": "k_pch_Null_SerialNumber_String","consttype": "const char *const", "constval": "serialNumber"} +,{ + "constname": "k_pch_Null_ModelNumber_String","consttype": "const char *const", "constval": "modelNumber"} +,{ + "constname": "k_pch_Null_WindowX_Int32","consttype": "const char *const", "constval": "windowX"} +,{ + "constname": "k_pch_Null_WindowY_Int32","consttype": "const char *const", "constval": "windowY"} +,{ + "constname": "k_pch_Null_WindowWidth_Int32","consttype": "const char *const", "constval": "windowWidth"} +,{ + "constname": "k_pch_Null_WindowHeight_Int32","consttype": "const char *const", "constval": "windowHeight"} +,{ + "constname": "k_pch_Null_RenderWidth_Int32","consttype": "const char *const", "constval": "renderWidth"} +,{ + "constname": "k_pch_Null_RenderHeight_Int32","consttype": "const char *const", "constval": "renderHeight"} +,{ + "constname": "k_pch_Null_SecondsFromVsyncToPhotons_Float","consttype": "const char *const", "constval": "secondsFromVsyncToPhotons"} +,{ + "constname": "k_pch_Null_DisplayFrequency_Float","consttype": "const char *const", "constval": "displayFrequency"} +,{ + "constname": "k_pch_UserInterface_Section","consttype": "const char *const", "constval": "userinterface"} +,{ + "constname": "k_pch_UserInterface_StatusAlwaysOnTop_Bool","consttype": "const char *const", "constval": "StatusAlwaysOnTop"} +,{ + "constname": "k_pch_UserInterface_EnableScreenshots_Bool","consttype": "const char *const", "constval": "EnableScreenshots"} +,{ + "constname": "k_pch_Notifications_Section","consttype": "const char *const", "constval": "notifications"} +,{ + "constname": "k_pch_Notifications_DoNotDisturb_Bool","consttype": "const char *const", "constval": "DoNotDisturb"} +,{ + "constname": "k_pch_Keyboard_Section","consttype": "const char *const", "constval": "keyboard"} +,{ + "constname": "k_pch_Keyboard_TutorialCompletions","consttype": "const char *const", "constval": "TutorialCompletions"} +,{ + "constname": "k_pch_Keyboard_ScaleX","consttype": "const char *const", "constval": "ScaleX"} +,{ + "constname": "k_pch_Keyboard_ScaleY","consttype": "const char *const", "constval": "ScaleY"} +,{ + "constname": "k_pch_Keyboard_OffsetLeftX","consttype": "const char *const", "constval": "OffsetLeftX"} +,{ + "constname": "k_pch_Keyboard_OffsetRightX","consttype": "const char *const", "constval": "OffsetRightX"} +,{ + "constname": "k_pch_Keyboard_OffsetY","consttype": "const char *const", "constval": "OffsetY"} +,{ + "constname": "k_pch_Keyboard_Smoothing","consttype": "const char *const", "constval": "Smoothing"} +,{ + "constname": "k_pch_Perf_Section","consttype": "const char *const", "constval": "perfcheck"} +,{ + "constname": "k_pch_Perf_HeuristicActive_Bool","consttype": "const char *const", "constval": "heuristicActive"} +,{ + "constname": "k_pch_Perf_NotifyInHMD_Bool","consttype": "const char *const", "constval": "warnInHMD"} +,{ + "constname": "k_pch_Perf_NotifyOnlyOnce_Bool","consttype": "const char *const", "constval": "warnOnlyOnce"} +,{ + "constname": "k_pch_Perf_AllowTimingStore_Bool","consttype": "const char *const", "constval": "allowTimingStore"} +,{ + "constname": "k_pch_Perf_SaveTimingsOnExit_Bool","consttype": "const char *const", "constval": "saveTimingsOnExit"} +,{ + "constname": "k_pch_Perf_TestData_Float","consttype": "const char *const", "constval": "perfTestData"} +,{ + "constname": "k_pch_CollisionBounds_Section","consttype": "const char *const", "constval": "collisionBounds"} +,{ + "constname": "k_pch_CollisionBounds_Style_Int32","consttype": "const char *const", "constval": "CollisionBoundsStyle"} +,{ + "constname": "k_pch_CollisionBounds_GroundPerimeterOn_Bool","consttype": "const char *const", "constval": "CollisionBoundsGroundPerimeterOn"} +,{ + "constname": "k_pch_CollisionBounds_CenterMarkerOn_Bool","consttype": "const char *const", "constval": "CollisionBoundsCenterMarkerOn"} +,{ + "constname": "k_pch_CollisionBounds_PlaySpaceOn_Bool","consttype": "const char *const", "constval": "CollisionBoundsPlaySpaceOn"} +,{ + "constname": "k_pch_CollisionBounds_FadeDistance_Float","consttype": "const char *const", "constval": "CollisionBoundsFadeDistance"} +,{ + "constname": "k_pch_CollisionBounds_ColorGammaR_Int32","consttype": "const char *const", "constval": "CollisionBoundsColorGammaR"} +,{ + "constname": "k_pch_CollisionBounds_ColorGammaG_Int32","consttype": "const char *const", "constval": "CollisionBoundsColorGammaG"} +,{ + "constname": "k_pch_CollisionBounds_ColorGammaB_Int32","consttype": "const char *const", "constval": "CollisionBoundsColorGammaB"} +,{ + "constname": "k_pch_CollisionBounds_ColorGammaA_Int32","consttype": "const char *const", "constval": "CollisionBoundsColorGammaA"} +,{ + "constname": "k_pch_Camera_Section","consttype": "const char *const", "constval": "camera"} +,{ + "constname": "k_pch_Camera_EnableCamera_Bool","consttype": "const char *const", "constval": "enableCamera"} +,{ + "constname": "k_pch_Camera_EnableCameraInDashboard_Bool","consttype": "const char *const", "constval": "enableCameraInDashboard"} +,{ + "constname": "k_pch_Camera_EnableCameraForCollisionBounds_Bool","consttype": "const char *const", "constval": "enableCameraForCollisionBounds"} +,{ + "constname": "k_pch_Camera_EnableCameraForRoomView_Bool","consttype": "const char *const", "constval": "enableCameraForRoomView"} +,{ + "constname": "k_pch_Camera_BoundsColorGammaR_Int32","consttype": "const char *const", "constval": "cameraBoundsColorGammaR"} +,{ + "constname": "k_pch_Camera_BoundsColorGammaG_Int32","consttype": "const char *const", "constval": "cameraBoundsColorGammaG"} +,{ + "constname": "k_pch_Camera_BoundsColorGammaB_Int32","consttype": "const char *const", "constval": "cameraBoundsColorGammaB"} +,{ + "constname": "k_pch_Camera_BoundsColorGammaA_Int32","consttype": "const char *const", "constval": "cameraBoundsColorGammaA"} +,{ + "constname": "k_pch_audio_Section","consttype": "const char *const", "constval": "audio"} +,{ + "constname": "k_pch_audio_OnPlaybackDevice_String","consttype": "const char *const", "constval": "onPlaybackDevice"} +,{ + "constname": "k_pch_audio_OnRecordDevice_String","consttype": "const char *const", "constval": "onRecordDevice"} +,{ + "constname": "k_pch_audio_OnPlaybackMirrorDevice_String","consttype": "const char *const", "constval": "onPlaybackMirrorDevice"} +,{ + "constname": "k_pch_audio_OffPlaybackDevice_String","consttype": "const char *const", "constval": "offPlaybackDevice"} +,{ + "constname": "k_pch_audio_OffRecordDevice_String","consttype": "const char *const", "constval": "offRecordDevice"} +,{ + "constname": "k_pch_audio_VIVEHDMIGain","consttype": "const char *const", "constval": "viveHDMIGain"} +,{ + "constname": "k_pch_modelskin_Section","consttype": "const char *const", "constval": "modelskins"} +,{ + "constname": "IVRScreenshots_Version","consttype": "const char *const", "constval": "IVRScreenshots_001"} +], +"structs":[{"struct": "vr::HmdMatrix34_t","fields": [ +{ "fieldname": "m", "fieldtype": "float [3][4]"}]} +,{"struct": "vr::HmdMatrix44_t","fields": [ +{ "fieldname": "m", "fieldtype": "float [4][4]"}]} +,{"struct": "vr::HmdVector3_t","fields": [ +{ "fieldname": "v", "fieldtype": "float [3]"}]} +,{"struct": "vr::HmdVector4_t","fields": [ +{ "fieldname": "v", "fieldtype": "float [4]"}]} +,{"struct": "vr::HmdVector3d_t","fields": [ +{ "fieldname": "v", "fieldtype": "double [3]"}]} +,{"struct": "vr::HmdVector2_t","fields": [ +{ "fieldname": "v", "fieldtype": "float [2]"}]} +,{"struct": "vr::HmdQuaternion_t","fields": [ +{ "fieldname": "w", "fieldtype": "double"}, +{ "fieldname": "x", "fieldtype": "double"}, +{ "fieldname": "y", "fieldtype": "double"}, +{ "fieldname": "z", "fieldtype": "double"}]} +,{"struct": "vr::HmdColor_t","fields": [ +{ "fieldname": "r", "fieldtype": "float"}, +{ "fieldname": "g", "fieldtype": "float"}, +{ "fieldname": "b", "fieldtype": "float"}, +{ "fieldname": "a", "fieldtype": "float"}]} +,{"struct": "vr::HmdQuad_t","fields": [ +{ "fieldname": "vCorners", "fieldtype": "struct vr::HmdVector3_t [4]"}]} +,{"struct": "vr::HmdRect2_t","fields": [ +{ "fieldname": "vTopLeft", "fieldtype": "struct vr::HmdVector2_t"}, +{ "fieldname": "vBottomRight", "fieldtype": "struct vr::HmdVector2_t"}]} +,{"struct": "vr::DistortionCoordinates_t","fields": [ +{ "fieldname": "rfRed", "fieldtype": "float [2]"}, +{ "fieldname": "rfGreen", "fieldtype": "float [2]"}, +{ "fieldname": "rfBlue", "fieldtype": "float [2]"}]} +,{"struct": "vr::Texture_t","fields": [ +{ "fieldname": "handle", "fieldtype": "void *"}, +{ "fieldname": "eType", "fieldtype": "enum vr::EGraphicsAPIConvention"}, +{ "fieldname": "eColorSpace", "fieldtype": "enum vr::EColorSpace"}]} +,{"struct": "vr::TrackedDevicePose_t","fields": [ +{ "fieldname": "mDeviceToAbsoluteTracking", "fieldtype": "struct vr::HmdMatrix34_t"}, +{ "fieldname": "vVelocity", "fieldtype": "struct vr::HmdVector3_t"}, +{ "fieldname": "vAngularVelocity", "fieldtype": "struct vr::HmdVector3_t"}, +{ "fieldname": "eTrackingResult", "fieldtype": "enum vr::ETrackingResult"}, +{ "fieldname": "bPoseIsValid", "fieldtype": "_Bool"}, +{ "fieldname": "bDeviceIsConnected", "fieldtype": "_Bool"}]} +,{"struct": "vr::VRTextureBounds_t","fields": [ +{ "fieldname": "uMin", "fieldtype": "float"}, +{ "fieldname": "vMin", "fieldtype": "float"}, +{ "fieldname": "uMax", "fieldtype": "float"}, +{ "fieldname": "vMax", "fieldtype": "float"}]} +,{"struct": "vr::VREvent_Controller_t","fields": [ +{ "fieldname": "button", "fieldtype": "uint32_t"}]} +,{"struct": "vr::VREvent_Mouse_t","fields": [ +{ "fieldname": "x", "fieldtype": "float"}, +{ "fieldname": "y", "fieldtype": "float"}, +{ "fieldname": "button", "fieldtype": "uint32_t"}]} +,{"struct": "vr::VREvent_Scroll_t","fields": [ +{ "fieldname": "xdelta", "fieldtype": "float"}, +{ "fieldname": "ydelta", "fieldtype": "float"}, +{ "fieldname": "repeatCount", "fieldtype": "uint32_t"}]} +,{"struct": "vr::VREvent_TouchPadMove_t","fields": [ +{ "fieldname": "bFingerDown", "fieldtype": "_Bool"}, +{ "fieldname": "flSecondsFingerDown", "fieldtype": "float"}, +{ "fieldname": "fValueXFirst", "fieldtype": "float"}, +{ "fieldname": "fValueYFirst", "fieldtype": "float"}, +{ "fieldname": "fValueXRaw", "fieldtype": "float"}, +{ "fieldname": "fValueYRaw", "fieldtype": "float"}]} +,{"struct": "vr::VREvent_Notification_t","fields": [ +{ "fieldname": "ulUserValue", "fieldtype": "uint64_t"}, +{ "fieldname": "notificationId", "fieldtype": "uint32_t"}]} +,{"struct": "vr::VREvent_Process_t","fields": [ +{ "fieldname": "pid", "fieldtype": "uint32_t"}, +{ "fieldname": "oldPid", "fieldtype": "uint32_t"}, +{ "fieldname": "bForced", "fieldtype": "_Bool"}]} +,{"struct": "vr::VREvent_Overlay_t","fields": [ +{ "fieldname": "overlayHandle", "fieldtype": "uint64_t"}]} +,{"struct": "vr::VREvent_Status_t","fields": [ +{ "fieldname": "statusState", "fieldtype": "uint32_t"}]} +,{"struct": "vr::VREvent_Keyboard_t","fields": [ +{ "fieldname": "cNewInput", "fieldtype": "char [8]"}, +{ "fieldname": "uUserValue", "fieldtype": "uint64_t"}]} +,{"struct": "vr::VREvent_Ipd_t","fields": [ +{ "fieldname": "ipdMeters", "fieldtype": "float"}]} +,{"struct": "vr::VREvent_Chaperone_t","fields": [ +{ "fieldname": "m_nPreviousUniverse", "fieldtype": "uint64_t"}, +{ "fieldname": "m_nCurrentUniverse", "fieldtype": "uint64_t"}]} +,{"struct": "vr::VREvent_Reserved_t","fields": [ +{ "fieldname": "reserved0", "fieldtype": "uint64_t"}, +{ "fieldname": "reserved1", "fieldtype": "uint64_t"}]} +,{"struct": "vr::VREvent_PerformanceTest_t","fields": [ +{ "fieldname": "m_nFidelityLevel", "fieldtype": "uint32_t"}]} +,{"struct": "vr::VREvent_SeatedZeroPoseReset_t","fields": [ +{ "fieldname": "bResetBySystemMenu", "fieldtype": "_Bool"}]} +,{"struct": "vr::VREvent_Screenshot_t","fields": [ +{ "fieldname": "handle", "fieldtype": "uint32_t"}, +{ "fieldname": "type", "fieldtype": "uint32_t"}]} +,{"struct": "vr::(anonymous)","fields": [ +{ "fieldname": "reserved", "fieldtype": "struct vr::VREvent_Reserved_t"}, +{ "fieldname": "controller", "fieldtype": "struct vr::VREvent_Controller_t"}, +{ "fieldname": "mouse", "fieldtype": "struct vr::VREvent_Mouse_t"}, +{ "fieldname": "scroll", "fieldtype": "struct vr::VREvent_Scroll_t"}, +{ "fieldname": "process", "fieldtype": "struct vr::VREvent_Process_t"}, +{ "fieldname": "notification", "fieldtype": "struct vr::VREvent_Notification_t"}, +{ "fieldname": "overlay", "fieldtype": "struct vr::VREvent_Overlay_t"}, +{ "fieldname": "status", "fieldtype": "struct vr::VREvent_Status_t"}, +{ "fieldname": "keyboard", "fieldtype": "struct vr::VREvent_Keyboard_t"}, +{ "fieldname": "ipd", "fieldtype": "struct vr::VREvent_Ipd_t"}, +{ "fieldname": "chaperone", "fieldtype": "struct vr::VREvent_Chaperone_t"}, +{ "fieldname": "performanceTest", "fieldtype": "struct vr::VREvent_PerformanceTest_t"}, +{ "fieldname": "touchPadMove", "fieldtype": "struct vr::VREvent_TouchPadMove_t"}, +{ "fieldname": "seatedZeroPoseReset", "fieldtype": "struct vr::VREvent_SeatedZeroPoseReset_t"}, +{ "fieldname": "screenshot", "fieldtype": "struct vr::VREvent_Screenshot_t"}]} +,{"struct": "vr::VREvent_t","fields": [ +{ "fieldname": "eventType", "fieldtype": "uint32_t"}, +{ "fieldname": "trackedDeviceIndex", "fieldtype": "TrackedDeviceIndex_t"}, +{ "fieldname": "eventAgeSeconds", "fieldtype": "float"}, +{ "fieldname": "data", "fieldtype": "VREvent_Data_t"}]} +,{"struct": "vr::HiddenAreaMesh_t","fields": [ +{ "fieldname": "pVertexData", "fieldtype": "const struct vr::HmdVector2_t *"}, +{ "fieldname": "unTriangleCount", "fieldtype": "uint32_t"}]} +,{"struct": "vr::VRControllerAxis_t","fields": [ +{ "fieldname": "x", "fieldtype": "float"}, +{ "fieldname": "y", "fieldtype": "float"}]} +,{"struct": "vr::VRControllerState001_t","fields": [ +{ "fieldname": "unPacketNum", "fieldtype": "uint32_t"}, +{ "fieldname": "ulButtonPressed", "fieldtype": "uint64_t"}, +{ "fieldname": "ulButtonTouched", "fieldtype": "uint64_t"}, +{ "fieldname": "rAxis", "fieldtype": "struct vr::VRControllerAxis_t [5]"}]} +,{"struct": "vr::Compositor_OverlaySettings","fields": [ +{ "fieldname": "size", "fieldtype": "uint32_t"}, +{ "fieldname": "curved", "fieldtype": "_Bool"}, +{ "fieldname": "antialias", "fieldtype": "_Bool"}, +{ "fieldname": "scale", "fieldtype": "float"}, +{ "fieldname": "distance", "fieldtype": "float"}, +{ "fieldname": "alpha", "fieldtype": "float"}, +{ "fieldname": "uOffset", "fieldtype": "float"}, +{ "fieldname": "vOffset", "fieldtype": "float"}, +{ "fieldname": "uScale", "fieldtype": "float"}, +{ "fieldname": "vScale", "fieldtype": "float"}, +{ "fieldname": "gridDivs", "fieldtype": "float"}, +{ "fieldname": "gridWidth", "fieldtype": "float"}, +{ "fieldname": "gridScale", "fieldtype": "float"}, +{ "fieldname": "transform", "fieldtype": "struct vr::HmdMatrix44_t"}]} +,{"struct": "vr::CameraVideoStreamFrameHeader_t","fields": [ +{ "fieldname": "eFrameType", "fieldtype": "enum vr::EVRTrackedCameraFrameType"}, +{ "fieldname": "nWidth", "fieldtype": "uint32_t"}, +{ "fieldname": "nHeight", "fieldtype": "uint32_t"}, +{ "fieldname": "nBytesPerPixel", "fieldtype": "uint32_t"}, +{ "fieldname": "nFrameSequence", "fieldtype": "uint32_t"}, +{ "fieldname": "standingTrackedDevicePose", "fieldtype": "struct vr::TrackedDevicePose_t"}]} +,{"struct": "vr::AppOverrideKeys_t","fields": [ +{ "fieldname": "pchKey", "fieldtype": "const char *"}, +{ "fieldname": "pchValue", "fieldtype": "const char *"}]} +,{"struct": "vr::Compositor_FrameTiming","fields": [ +{ "fieldname": "m_nSize", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nFrameIndex", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumFramePresents", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumDroppedFrames", "fieldtype": "uint32_t"}, +{ "fieldname": "m_flSystemTimeInSeconds", "fieldtype": "double"}, +{ "fieldname": "m_flSceneRenderGpuMs", "fieldtype": "float"}, +{ "fieldname": "m_flTotalRenderGpuMs", "fieldtype": "float"}, +{ "fieldname": "m_flCompositorRenderGpuMs", "fieldtype": "float"}, +{ "fieldname": "m_flCompositorRenderCpuMs", "fieldtype": "float"}, +{ "fieldname": "m_flCompositorIdleCpuMs", "fieldtype": "float"}, +{ "fieldname": "m_flClientFrameIntervalMs", "fieldtype": "float"}, +{ "fieldname": "m_flPresentCallCpuMs", "fieldtype": "float"}, +{ "fieldname": "m_flWaitForPresentCpuMs", "fieldtype": "float"}, +{ "fieldname": "m_flSubmitFrameMs", "fieldtype": "float"}, +{ "fieldname": "m_flWaitGetPosesCalledMs", "fieldtype": "float"}, +{ "fieldname": "m_flNewPosesReadyMs", "fieldtype": "float"}, +{ "fieldname": "m_flNewFrameReadyMs", "fieldtype": "float"}, +{ "fieldname": "m_flCompositorUpdateStartMs", "fieldtype": "float"}, +{ "fieldname": "m_flCompositorUpdateEndMs", "fieldtype": "float"}, +{ "fieldname": "m_flCompositorRenderStartMs", "fieldtype": "float"}, +{ "fieldname": "m_HmdPose", "fieldtype": "vr::TrackedDevicePose_t"}, +{ "fieldname": "m_nFidelityLevel", "fieldtype": "int32_t"}, +{ "fieldname": "m_nReprojectionFlags", "fieldtype": "uint32_t"}]} +,{"struct": "vr::Compositor_CumulativeStats","fields": [ +{ "fieldname": "m_nPid", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumFramePresents", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumDroppedFrames", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumReprojectedFrames", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumFramePresentsOnStartup", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumDroppedFramesOnStartup", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumReprojectedFramesOnStartup", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumLoading", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumFramePresentsLoading", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumDroppedFramesLoading", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumReprojectedFramesLoading", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumTimedOut", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumFramePresentsTimedOut", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumDroppedFramesTimedOut", "fieldtype": "uint32_t"}, +{ "fieldname": "m_nNumReprojectedFramesTimedOut", "fieldtype": "uint32_t"}]} +,{"struct": "vr::VROverlayIntersectionParams_t","fields": [ +{ "fieldname": "vSource", "fieldtype": "struct vr::HmdVector3_t"}, +{ "fieldname": "vDirection", "fieldtype": "struct vr::HmdVector3_t"}, +{ "fieldname": "eOrigin", "fieldtype": "enum vr::ETrackingUniverseOrigin"}]} +,{"struct": "vr::VROverlayIntersectionResults_t","fields": [ +{ "fieldname": "vPoint", "fieldtype": "struct vr::HmdVector3_t"}, +{ "fieldname": "vNormal", "fieldtype": "struct vr::HmdVector3_t"}, +{ "fieldname": "vUVs", "fieldtype": "struct vr::HmdVector2_t"}, +{ "fieldname": "fDistance", "fieldtype": "float"}]} +,{"struct": "vr::RenderModel_ComponentState_t","fields": [ +{ "fieldname": "mTrackingToComponentRenderModel", "fieldtype": "struct vr::HmdMatrix34_t"}, +{ "fieldname": "mTrackingToComponentLocal", "fieldtype": "struct vr::HmdMatrix34_t"}, +{ "fieldname": "uProperties", "fieldtype": "VRComponentProperties"}]} +,{"struct": "vr::RenderModel_Vertex_t","fields": [ +{ "fieldname": "vPosition", "fieldtype": "struct vr::HmdVector3_t"}, +{ "fieldname": "vNormal", "fieldtype": "struct vr::HmdVector3_t"}, +{ "fieldname": "rfTextureCoord", "fieldtype": "float [2]"}]} +,{"struct": "vr::RenderModel_TextureMap_t","fields": [ +{ "fieldname": "unWidth", "fieldtype": "uint16_t"}, +{ "fieldname": "unHeight", "fieldtype": "uint16_t"}, +{ "fieldname": "rubTextureMapData", "fieldtype": "const uint8_t *"}]} +,{"struct": "vr::RenderModel_t","fields": [ +{ "fieldname": "rVertexData", "fieldtype": "const struct vr::RenderModel_Vertex_t *"}, +{ "fieldname": "unVertexCount", "fieldtype": "uint32_t"}, +{ "fieldname": "rIndexData", "fieldtype": "const uint16_t *"}, +{ "fieldname": "unTriangleCount", "fieldtype": "uint32_t"}, +{ "fieldname": "diffuseTextureId", "fieldtype": "TextureID_t"}]} +,{"struct": "vr::RenderModel_ControllerMode_State_t","fields": [ +{ "fieldname": "bScrollWheelVisible", "fieldtype": "_Bool"}]} +,{"struct": "vr::NotificationBitmap_t","fields": [ +{ "fieldname": "m_pImageData", "fieldtype": "void *"}, +{ "fieldname": "m_nWidth", "fieldtype": "int32_t"}, +{ "fieldname": "m_nHeight", "fieldtype": "int32_t"}, +{ "fieldname": "m_nBytesPerPixel", "fieldtype": "int32_t"}]} +,{"struct": "vr::COpenVRContext","fields": [ +{ "fieldname": "m_pVRSystem", "fieldtype": "class vr::IVRSystem *"}, +{ "fieldname": "m_pVRChaperone", "fieldtype": "class vr::IVRChaperone *"}, +{ "fieldname": "m_pVRChaperoneSetup", "fieldtype": "class vr::IVRChaperoneSetup *"}, +{ "fieldname": "m_pVRCompositor", "fieldtype": "class vr::IVRCompositor *"}, +{ "fieldname": "m_pVROverlay", "fieldtype": "class vr::IVROverlay *"}, +{ "fieldname": "m_pVRRenderModels", "fieldtype": "class vr::IVRRenderModels *"}, +{ "fieldname": "m_pVRExtendedDisplay", "fieldtype": "class vr::IVRExtendedDisplay *"}, +{ "fieldname": "m_pVRSettings", "fieldtype": "class vr::IVRSettings *"}, +{ "fieldname": "m_pVRApplications", "fieldtype": "class vr::IVRApplications *"}, +{ "fieldname": "m_pVRTrackedCamera", "fieldtype": "class vr::IVRTrackedCamera *"}, +{ "fieldname": "m_pVRScreenshots", "fieldtype": "class vr::IVRScreenshots *"}]} +], +"methods":[{ + "classname": "vr::IVRSystem", + "methodname": "GetRecommendedRenderTargetSize", + "returntype": "void", + "params": [ +{ "paramname": "pnWidth" ,"paramtype": "uint32_t *"}, +{ "paramname": "pnHeight" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetProjectionMatrix", + "returntype": "struct vr::HmdMatrix44_t", + "params": [ +{ "paramname": "eEye" ,"paramtype": "vr::EVREye"}, +{ "paramname": "fNearZ" ,"paramtype": "float"}, +{ "paramname": "fFarZ" ,"paramtype": "float"}, +{ "paramname": "eProjType" ,"paramtype": "vr::EGraphicsAPIConvention"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetProjectionRaw", + "returntype": "void", + "params": [ +{ "paramname": "eEye" ,"paramtype": "vr::EVREye"}, +{ "paramname": "pfLeft" ,"paramtype": "float *"}, +{ "paramname": "pfRight" ,"paramtype": "float *"}, +{ "paramname": "pfTop" ,"paramtype": "float *"}, +{ "paramname": "pfBottom" ,"paramtype": "float *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "ComputeDistortion", + "returntype": "struct vr::DistortionCoordinates_t", + "params": [ +{ "paramname": "eEye" ,"paramtype": "vr::EVREye"}, +{ "paramname": "fU" ,"paramtype": "float"}, +{ "paramname": "fV" ,"paramtype": "float"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetEyeToHeadTransform", + "returntype": "struct vr::HmdMatrix34_t", + "params": [ +{ "paramname": "eEye" ,"paramtype": "vr::EVREye"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetTimeSinceLastVsync", + "returntype": "bool", + "params": [ +{ "paramname": "pfSecondsSinceLastVsync" ,"paramtype": "float *"}, +{ "paramname": "pulFrameCounter" ,"paramtype": "uint64_t *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetD3D9AdapterIndex", + "returntype": "int32_t" +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetDXGIOutputInfo", + "returntype": "void", + "params": [ +{ "paramname": "pnAdapterIndex" ,"paramtype": "int32_t *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "IsDisplayOnDesktop", + "returntype": "bool" +} +,{ + "classname": "vr::IVRSystem", + "methodname": "SetDisplayVisibility", + "returntype": "bool", + "params": [ +{ "paramname": "bIsVisibleOnDesktop" ,"paramtype": "bool"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetDeviceToAbsoluteTrackingPose", + "returntype": "void", + "params": [ +{ "paramname": "eOrigin" ,"paramtype": "vr::ETrackingUniverseOrigin"}, +{ "paramname": "fPredictedSecondsToPhotonsFromNow" ,"paramtype": "float"}, +{ "paramname": "pTrackedDevicePoseArray" ,"array_count": "unTrackedDevicePoseArrayCount" ,"paramtype": "struct vr::TrackedDevicePose_t *"}, +{ "paramname": "unTrackedDevicePoseArrayCount" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "ResetSeatedZeroPose", + "returntype": "void" +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetSeatedZeroPoseToStandingAbsoluteTrackingPose", + "returntype": "struct vr::HmdMatrix34_t" +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetRawZeroPoseToStandingAbsoluteTrackingPose", + "returntype": "struct vr::HmdMatrix34_t" +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetSortedTrackedDeviceIndicesOfClass", + "returntype": "uint32_t", + "params": [ +{ "paramname": "eTrackedDeviceClass" ,"paramtype": "vr::ETrackedDeviceClass"}, +{ "paramname": "punTrackedDeviceIndexArray" ,"array_count": "unTrackedDeviceIndexArrayCount" ,"paramtype": "vr::TrackedDeviceIndex_t *"}, +{ "paramname": "unTrackedDeviceIndexArrayCount" ,"paramtype": "uint32_t"}, +{ "paramname": "unRelativeToTrackedDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetTrackedDeviceActivityLevel", + "returntype": "vr::EDeviceActivityLevel", + "params": [ +{ "paramname": "unDeviceId" ,"paramtype": "vr::TrackedDeviceIndex_t"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "ApplyTransform", + "returntype": "void", + "params": [ +{ "paramname": "pOutputPose" ,"paramtype": "struct vr::TrackedDevicePose_t *"}, +{ "paramname": "pTrackedDevicePose" ,"paramtype": "const struct vr::TrackedDevicePose_t *"}, +{ "paramname": "pTransform" ,"paramtype": "const struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetTrackedDeviceIndexForControllerRole", + "returntype": "vr::TrackedDeviceIndex_t", + "params": [ +{ "paramname": "unDeviceType" ,"paramtype": "vr::ETrackedControllerRole"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetControllerRoleForTrackedDeviceIndex", + "returntype": "vr::ETrackedControllerRole", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetTrackedDeviceClass", + "returntype": "vr::ETrackedDeviceClass", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "IsTrackedDeviceConnected", + "returntype": "bool", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetBoolTrackedDeviceProperty", + "returntype": "bool", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "prop" ,"paramtype": "vr::ETrackedDeviceProperty"}, +{ "paramname": "pError" ,"paramtype": "vr::ETrackedPropertyError *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetFloatTrackedDeviceProperty", + "returntype": "float", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "prop" ,"paramtype": "vr::ETrackedDeviceProperty"}, +{ "paramname": "pError" ,"paramtype": "vr::ETrackedPropertyError *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetInt32TrackedDeviceProperty", + "returntype": "int32_t", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "prop" ,"paramtype": "vr::ETrackedDeviceProperty"}, +{ "paramname": "pError" ,"paramtype": "vr::ETrackedPropertyError *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetUint64TrackedDeviceProperty", + "returntype": "uint64_t", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "prop" ,"paramtype": "vr::ETrackedDeviceProperty"}, +{ "paramname": "pError" ,"paramtype": "vr::ETrackedPropertyError *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetMatrix34TrackedDeviceProperty", + "returntype": "struct vr::HmdMatrix34_t", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "prop" ,"paramtype": "vr::ETrackedDeviceProperty"}, +{ "paramname": "pError" ,"paramtype": "vr::ETrackedPropertyError *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetStringTrackedDeviceProperty", + "returntype": "uint32_t", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "prop" ,"paramtype": "vr::ETrackedDeviceProperty"}, +{ "paramname": "pchValue" ,"out_string": " " ,"paramtype": "char *"}, +{ "paramname": "unBufferSize" ,"paramtype": "uint32_t"}, +{ "paramname": "pError" ,"paramtype": "vr::ETrackedPropertyError *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetPropErrorNameFromEnum", + "returntype": "const char *", + "params": [ +{ "paramname": "error" ,"paramtype": "vr::ETrackedPropertyError"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "PollNextEvent", + "returntype": "bool", + "params": [ +{ "paramname": "pEvent" ,"paramtype": "struct vr::VREvent_t *"}, +{ "paramname": "uncbVREvent" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "PollNextEventWithPose", + "returntype": "bool", + "params": [ +{ "paramname": "eOrigin" ,"paramtype": "vr::ETrackingUniverseOrigin"}, +{ "paramname": "pEvent" ,"paramtype": "struct vr::VREvent_t *"}, +{ "paramname": "uncbVREvent" ,"paramtype": "uint32_t"}, +{ "paramname": "pTrackedDevicePose" ,"paramtype": "vr::TrackedDevicePose_t *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetEventTypeNameFromEnum", + "returntype": "const char *", + "params": [ +{ "paramname": "eType" ,"paramtype": "vr::EVREventType"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetHiddenAreaMesh", + "returntype": "struct vr::HiddenAreaMesh_t", + "params": [ +{ "paramname": "eEye" ,"paramtype": "vr::EVREye"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetControllerState", + "returntype": "bool", + "params": [ +{ "paramname": "unControllerDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "pControllerState" ,"paramtype": "vr::VRControllerState_t *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetControllerStateWithPose", + "returntype": "bool", + "params": [ +{ "paramname": "eOrigin" ,"paramtype": "vr::ETrackingUniverseOrigin"}, +{ "paramname": "unControllerDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "pControllerState" ,"paramtype": "vr::VRControllerState_t *"}, +{ "paramname": "pTrackedDevicePose" ,"paramtype": "struct vr::TrackedDevicePose_t *"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "TriggerHapticPulse", + "returntype": "void", + "params": [ +{ "paramname": "unControllerDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "unAxisId" ,"paramtype": "uint32_t"}, +{ "paramname": "usDurationMicroSec" ,"paramtype": "unsigned short"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetButtonIdNameFromEnum", + "returntype": "const char *", + "params": [ +{ "paramname": "eButtonId" ,"paramtype": "vr::EVRButtonId"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "GetControllerAxisTypeNameFromEnum", + "returntype": "const char *", + "params": [ +{ "paramname": "eAxisType" ,"paramtype": "vr::EVRControllerAxisType"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "CaptureInputFocus", + "returntype": "bool" +} +,{ + "classname": "vr::IVRSystem", + "methodname": "ReleaseInputFocus", + "returntype": "void" +} +,{ + "classname": "vr::IVRSystem", + "methodname": "IsInputFocusCapturedByAnotherProcess", + "returntype": "bool" +} +,{ + "classname": "vr::IVRSystem", + "methodname": "DriverDebugRequest", + "returntype": "uint32_t", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "pchRequest" ,"paramtype": "const char *"}, +{ "paramname": "pchResponseBuffer" ,"paramtype": "char *"}, +{ "paramname": "unResponseBufferSize" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "PerformFirmwareUpdate", + "returntype": "vr::EVRFirmwareError", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"} + ] +} +,{ + "classname": "vr::IVRSystem", + "methodname": "AcknowledgeQuit_Exiting", + "returntype": "void" +} +,{ + "classname": "vr::IVRSystem", + "methodname": "AcknowledgeQuit_UserPrompt", + "returntype": "void" +} +,{ + "classname": "vr::IVRExtendedDisplay", + "methodname": "GetWindowBounds", + "returntype": "void", + "params": [ +{ "paramname": "pnX" ,"paramtype": "int32_t *"}, +{ "paramname": "pnY" ,"paramtype": "int32_t *"}, +{ "paramname": "pnWidth" ,"paramtype": "uint32_t *"}, +{ "paramname": "pnHeight" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVRExtendedDisplay", + "methodname": "GetEyeOutputViewport", + "returntype": "void", + "params": [ +{ "paramname": "eEye" ,"paramtype": "vr::EVREye"}, +{ "paramname": "pnX" ,"paramtype": "uint32_t *"}, +{ "paramname": "pnY" ,"paramtype": "uint32_t *"}, +{ "paramname": "pnWidth" ,"paramtype": "uint32_t *"}, +{ "paramname": "pnHeight" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVRExtendedDisplay", + "methodname": "GetDXGIOutputInfo", + "returntype": "void", + "params": [ +{ "paramname": "pnAdapterIndex" ,"paramtype": "int32_t *"}, +{ "paramname": "pnAdapterOutputIndex" ,"paramtype": "int32_t *"} + ] +} +,{ + "classname": "vr::IVRTrackedCamera", + "methodname": "GetCameraErrorNameFromEnum", + "returntype": "const char *", + "params": [ +{ "paramname": "eCameraError" ,"paramtype": "vr::EVRTrackedCameraError"} + ] +} +,{ + "classname": "vr::IVRTrackedCamera", + "methodname": "HasCamera", + "returntype": "vr::EVRTrackedCameraError", + "params": [ +{ "paramname": "nDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "pHasCamera" ,"paramtype": "bool *"} + ] +} +,{ + "classname": "vr::IVRTrackedCamera", + "methodname": "GetCameraFrameSize", + "returntype": "vr::EVRTrackedCameraError", + "params": [ +{ "paramname": "nDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "eFrameType" ,"paramtype": "vr::EVRTrackedCameraFrameType"}, +{ "paramname": "pnWidth" ,"paramtype": "uint32_t *"}, +{ "paramname": "pnHeight" ,"paramtype": "uint32_t *"}, +{ "paramname": "pnFrameBufferSize" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVRTrackedCamera", + "methodname": "GetCameraIntrinisics", + "returntype": "vr::EVRTrackedCameraError", + "params": [ +{ "paramname": "nDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "eFrameType" ,"paramtype": "vr::EVRTrackedCameraFrameType"}, +{ "paramname": "pFocalLength" ,"paramtype": "vr::HmdVector2_t *"}, +{ "paramname": "pCenter" ,"paramtype": "vr::HmdVector2_t *"} + ] +} +,{ + "classname": "vr::IVRTrackedCamera", + "methodname": "GetCameraProjection", + "returntype": "vr::EVRTrackedCameraError", + "params": [ +{ "paramname": "nDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "eFrameType" ,"paramtype": "vr::EVRTrackedCameraFrameType"}, +{ "paramname": "flZNear" ,"paramtype": "float"}, +{ "paramname": "flZFar" ,"paramtype": "float"}, +{ "paramname": "pProjection" ,"paramtype": "vr::HmdMatrix44_t *"} + ] +} +,{ + "classname": "vr::IVRTrackedCamera", + "methodname": "AcquireVideoStreamingService", + "returntype": "vr::EVRTrackedCameraError", + "params": [ +{ "paramname": "nDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "pHandle" ,"paramtype": "vr::TrackedCameraHandle_t *"} + ] +} +,{ + "classname": "vr::IVRTrackedCamera", + "methodname": "ReleaseVideoStreamingService", + "returntype": "vr::EVRTrackedCameraError", + "params": [ +{ "paramname": "hTrackedCamera" ,"paramtype": "vr::TrackedCameraHandle_t"} + ] +} +,{ + "classname": "vr::IVRTrackedCamera", + "methodname": "GetVideoStreamFrameBuffer", + "returntype": "vr::EVRTrackedCameraError", + "params": [ +{ "paramname": "hTrackedCamera" ,"paramtype": "vr::TrackedCameraHandle_t"}, +{ "paramname": "eFrameType" ,"paramtype": "vr::EVRTrackedCameraFrameType"}, +{ "paramname": "pFrameBuffer" ,"paramtype": "void *"}, +{ "paramname": "nFrameBufferSize" ,"paramtype": "uint32_t"}, +{ "paramname": "pFrameHeader" ,"paramtype": "vr::CameraVideoStreamFrameHeader_t *"}, +{ "paramname": "nFrameHeaderSize" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "AddApplicationManifest", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "pchApplicationManifestFullPath" ,"paramtype": "const char *"}, +{ "paramname": "bTemporary" ,"paramtype": "bool"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "RemoveApplicationManifest", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "pchApplicationManifestFullPath" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "IsApplicationInstalled", + "returntype": "bool", + "params": [ +{ "paramname": "pchAppKey" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetApplicationCount", + "returntype": "uint32_t" +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetApplicationKeyByIndex", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "unApplicationIndex" ,"paramtype": "uint32_t"}, +{ "paramname": "pchAppKeyBuffer" ,"paramtype": "char *"}, +{ "paramname": "unAppKeyBufferLen" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetApplicationKeyByProcessId", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "unProcessId" ,"paramtype": "uint32_t"}, +{ "paramname": "pchAppKeyBuffer" ,"paramtype": "char *"}, +{ "paramname": "unAppKeyBufferLen" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "LaunchApplication", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "pchAppKey" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "LaunchTemplateApplication", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "pchTemplateAppKey" ,"paramtype": "const char *"}, +{ "paramname": "pchNewAppKey" ,"paramtype": "const char *"}, +{ "paramname": "pKeys" ,"array_count": "unKeys" ,"paramtype": "const struct vr::AppOverrideKeys_t *"}, +{ "paramname": "unKeys" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "LaunchDashboardOverlay", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "pchAppKey" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "CancelApplicationLaunch", + "returntype": "bool", + "params": [ +{ "paramname": "pchAppKey" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "IdentifyApplication", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "unProcessId" ,"paramtype": "uint32_t"}, +{ "paramname": "pchAppKey" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetApplicationProcessId", + "returntype": "uint32_t", + "params": [ +{ "paramname": "pchAppKey" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetApplicationsErrorNameFromEnum", + "returntype": "const char *", + "params": [ +{ "paramname": "error" ,"paramtype": "vr::EVRApplicationError"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetApplicationPropertyString", + "returntype": "uint32_t", + "params": [ +{ "paramname": "pchAppKey" ,"paramtype": "const char *"}, +{ "paramname": "eProperty" ,"paramtype": "vr::EVRApplicationProperty"}, +{ "paramname": "pchPropertyValueBuffer" ,"paramtype": "char *"}, +{ "paramname": "unPropertyValueBufferLen" ,"paramtype": "uint32_t"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRApplicationError *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetApplicationPropertyBool", + "returntype": "bool", + "params": [ +{ "paramname": "pchAppKey" ,"paramtype": "const char *"}, +{ "paramname": "eProperty" ,"paramtype": "vr::EVRApplicationProperty"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRApplicationError *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetApplicationPropertyUint64", + "returntype": "uint64_t", + "params": [ +{ "paramname": "pchAppKey" ,"paramtype": "const char *"}, +{ "paramname": "eProperty" ,"paramtype": "vr::EVRApplicationProperty"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRApplicationError *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "SetApplicationAutoLaunch", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "pchAppKey" ,"paramtype": "const char *"}, +{ "paramname": "bAutoLaunch" ,"paramtype": "bool"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetApplicationAutoLaunch", + "returntype": "bool", + "params": [ +{ "paramname": "pchAppKey" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetStartingApplication", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "pchAppKeyBuffer" ,"paramtype": "char *"}, +{ "paramname": "unAppKeyBufferLen" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetTransitionState", + "returntype": "vr::EVRApplicationTransitionState" +} +,{ + "classname": "vr::IVRApplications", + "methodname": "PerformApplicationPrelaunchCheck", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "pchAppKey" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "GetApplicationsTransitionStateNameFromEnum", + "returntype": "const char *", + "params": [ +{ "paramname": "state" ,"paramtype": "vr::EVRApplicationTransitionState"} + ] +} +,{ + "classname": "vr::IVRApplications", + "methodname": "IsQuitUserPromptRequested", + "returntype": "bool" +} +,{ + "classname": "vr::IVRApplications", + "methodname": "LaunchInternalProcess", + "returntype": "vr::EVRApplicationError", + "params": [ +{ "paramname": "pchBinaryPath" ,"paramtype": "const char *"}, +{ "paramname": "pchArguments" ,"paramtype": "const char *"}, +{ "paramname": "pchWorkingDirectory" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRChaperone", + "methodname": "GetCalibrationState", + "returntype": "vr::ChaperoneCalibrationState" +} +,{ + "classname": "vr::IVRChaperone", + "methodname": "GetPlayAreaSize", + "returntype": "bool", + "params": [ +{ "paramname": "pSizeX" ,"paramtype": "float *"}, +{ "paramname": "pSizeZ" ,"paramtype": "float *"} + ] +} +,{ + "classname": "vr::IVRChaperone", + "methodname": "GetPlayAreaRect", + "returntype": "bool", + "params": [ +{ "paramname": "rect" ,"paramtype": "struct vr::HmdQuad_t *"} + ] +} +,{ + "classname": "vr::IVRChaperone", + "methodname": "ReloadInfo", + "returntype": "void" +} +,{ + "classname": "vr::IVRChaperone", + "methodname": "SetSceneColor", + "returntype": "void", + "params": [ +{ "paramname": "color" ,"paramtype": "struct vr::HmdColor_t"} + ] +} +,{ + "classname": "vr::IVRChaperone", + "methodname": "GetBoundsColor", + "returntype": "void", + "params": [ +{ "paramname": "pOutputColorArray" ,"paramtype": "struct vr::HmdColor_t *"}, +{ "paramname": "nNumOutputColors" ,"paramtype": "int"}, +{ "paramname": "flCollisionBoundsFadeDistance" ,"paramtype": "float"}, +{ "paramname": "pOutputCameraColor" ,"paramtype": "struct vr::HmdColor_t *"} + ] +} +,{ + "classname": "vr::IVRChaperone", + "methodname": "AreBoundsVisible", + "returntype": "bool" +} +,{ + "classname": "vr::IVRChaperone", + "methodname": "ForceBoundsVisible", + "returntype": "void", + "params": [ +{ "paramname": "bForce" ,"paramtype": "bool"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "CommitWorkingCopy", + "returntype": "bool", + "params": [ +{ "paramname": "configFile" ,"paramtype": "vr::EChaperoneConfigFile"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "RevertWorkingCopy", + "returntype": "void" +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "GetWorkingPlayAreaSize", + "returntype": "bool", + "params": [ +{ "paramname": "pSizeX" ,"paramtype": "float *"}, +{ "paramname": "pSizeZ" ,"paramtype": "float *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "GetWorkingPlayAreaRect", + "returntype": "bool", + "params": [ +{ "paramname": "rect" ,"paramtype": "struct vr::HmdQuad_t *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "GetWorkingCollisionBoundsInfo", + "returntype": "bool", + "params": [ +{ "paramname": "pQuadsBuffer" ,"out_array_count": "punQuadsCount" ,"paramtype": "struct vr::HmdQuad_t *"}, +{ "paramname": "punQuadsCount" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "GetLiveCollisionBoundsInfo", + "returntype": "bool", + "params": [ +{ "paramname": "pQuadsBuffer" ,"out_array_count": "punQuadsCount" ,"paramtype": "struct vr::HmdQuad_t *"}, +{ "paramname": "punQuadsCount" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "GetWorkingSeatedZeroPoseToRawTrackingPose", + "returntype": "bool", + "params": [ +{ "paramname": "pmatSeatedZeroPoseToRawTrackingPose" ,"paramtype": "struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "GetWorkingStandingZeroPoseToRawTrackingPose", + "returntype": "bool", + "params": [ +{ "paramname": "pmatStandingZeroPoseToRawTrackingPose" ,"paramtype": "struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "SetWorkingPlayAreaSize", + "returntype": "void", + "params": [ +{ "paramname": "sizeX" ,"paramtype": "float"}, +{ "paramname": "sizeZ" ,"paramtype": "float"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "SetWorkingCollisionBoundsInfo", + "returntype": "void", + "params": [ +{ "paramname": "pQuadsBuffer" ,"array_count": "unQuadsCount" ,"paramtype": "struct vr::HmdQuad_t *"}, +{ "paramname": "unQuadsCount" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "SetWorkingSeatedZeroPoseToRawTrackingPose", + "returntype": "void", + "params": [ +{ "paramname": "pMatSeatedZeroPoseToRawTrackingPose" ,"paramtype": "const struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "SetWorkingStandingZeroPoseToRawTrackingPose", + "returntype": "void", + "params": [ +{ "paramname": "pMatStandingZeroPoseToRawTrackingPose" ,"paramtype": "const struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "ReloadFromDisk", + "returntype": "void", + "params": [ +{ "paramname": "configFile" ,"paramtype": "vr::EChaperoneConfigFile"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "GetLiveSeatedZeroPoseToRawTrackingPose", + "returntype": "bool", + "params": [ +{ "paramname": "pmatSeatedZeroPoseToRawTrackingPose" ,"paramtype": "struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "SetWorkingCollisionBoundsTagsInfo", + "returntype": "void", + "params": [ +{ "paramname": "pTagsBuffer" ,"array_count": "unTagCount" ,"paramtype": "uint8_t *"}, +{ "paramname": "unTagCount" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "GetLiveCollisionBoundsTagsInfo", + "returntype": "bool", + "params": [ +{ "paramname": "pTagsBuffer" ,"out_array_count": "punTagCount" ,"paramtype": "uint8_t *"}, +{ "paramname": "punTagCount" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "SetWorkingPhysicalBoundsInfo", + "returntype": "bool", + "params": [ +{ "paramname": "pQuadsBuffer" ,"array_count": "unQuadsCount" ,"paramtype": "struct vr::HmdQuad_t *"}, +{ "paramname": "unQuadsCount" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "GetLivePhysicalBoundsInfo", + "returntype": "bool", + "params": [ +{ "paramname": "pQuadsBuffer" ,"out_array_count": "punQuadsCount" ,"paramtype": "struct vr::HmdQuad_t *"}, +{ "paramname": "punQuadsCount" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "ExportLiveToBuffer", + "returntype": "bool", + "params": [ +{ "paramname": "pBuffer" ,"out_string": " " ,"paramtype": "char *"}, +{ "paramname": "pnBufferLength" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVRChaperoneSetup", + "methodname": "ImportFromBufferToWorking", + "returntype": "bool", + "params": [ +{ "paramname": "pBuffer" ,"paramtype": "const char *"}, +{ "paramname": "nImportFlags" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "SetTrackingSpace", + "returntype": "void", + "params": [ +{ "paramname": "eOrigin" ,"paramtype": "vr::ETrackingUniverseOrigin"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "GetTrackingSpace", + "returntype": "vr::ETrackingUniverseOrigin" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "WaitGetPoses", + "returntype": "vr::EVRCompositorError", + "params": [ +{ "paramname": "pRenderPoseArray" ,"array_count": "unRenderPoseArrayCount" ,"paramtype": "struct vr::TrackedDevicePose_t *"}, +{ "paramname": "unRenderPoseArrayCount" ,"paramtype": "uint32_t"}, +{ "paramname": "pGamePoseArray" ,"array_count": "unGamePoseArrayCount" ,"paramtype": "struct vr::TrackedDevicePose_t *"}, +{ "paramname": "unGamePoseArrayCount" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "GetLastPoses", + "returntype": "vr::EVRCompositorError", + "params": [ +{ "paramname": "pRenderPoseArray" ,"array_count": "unRenderPoseArrayCount" ,"paramtype": "struct vr::TrackedDevicePose_t *"}, +{ "paramname": "unRenderPoseArrayCount" ,"paramtype": "uint32_t"}, +{ "paramname": "pGamePoseArray" ,"array_count": "unGamePoseArrayCount" ,"paramtype": "struct vr::TrackedDevicePose_t *"}, +{ "paramname": "unGamePoseArrayCount" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "GetLastPoseForTrackedDeviceIndex", + "returntype": "vr::EVRCompositorError", + "params": [ +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "pOutputPose" ,"paramtype": "struct vr::TrackedDevicePose_t *"}, +{ "paramname": "pOutputGamePose" ,"paramtype": "struct vr::TrackedDevicePose_t *"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "Submit", + "returntype": "vr::EVRCompositorError", + "params": [ +{ "paramname": "eEye" ,"paramtype": "vr::EVREye"}, +{ "paramname": "pTexture" ,"paramtype": "const struct vr::Texture_t *"}, +{ "paramname": "pBounds" ,"paramtype": "const struct vr::VRTextureBounds_t *"}, +{ "paramname": "nSubmitFlags" ,"paramtype": "vr::EVRSubmitFlags"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "ClearLastSubmittedFrame", + "returntype": "void" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "PostPresentHandoff", + "returntype": "void" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "GetFrameTiming", + "returntype": "bool", + "params": [ +{ "paramname": "pTiming" ,"paramtype": "struct vr::Compositor_FrameTiming *"}, +{ "paramname": "unFramesAgo" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "GetFrameTimeRemaining", + "returntype": "float" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "GetCumulativeStats", + "returntype": "void", + "params": [ +{ "paramname": "pStats" ,"paramtype": "struct vr::Compositor_CumulativeStats *"}, +{ "paramname": "nStatsSizeInBytes" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "FadeToColor", + "returntype": "void", + "params": [ +{ "paramname": "fSeconds" ,"paramtype": "float"}, +{ "paramname": "fRed" ,"paramtype": "float"}, +{ "paramname": "fGreen" ,"paramtype": "float"}, +{ "paramname": "fBlue" ,"paramtype": "float"}, +{ "paramname": "fAlpha" ,"paramtype": "float"}, +{ "paramname": "bBackground" ,"paramtype": "bool"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "FadeGrid", + "returntype": "void", + "params": [ +{ "paramname": "fSeconds" ,"paramtype": "float"}, +{ "paramname": "bFadeIn" ,"paramtype": "bool"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "SetSkyboxOverride", + "returntype": "vr::EVRCompositorError", + "params": [ +{ "paramname": "pTextures" ,"array_count": "unTextureCount" ,"paramtype": "const struct vr::Texture_t *"}, +{ "paramname": "unTextureCount" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "ClearSkyboxOverride", + "returntype": "void" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "CompositorBringToFront", + "returntype": "void" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "CompositorGoToBack", + "returntype": "void" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "CompositorQuit", + "returntype": "void" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "IsFullscreen", + "returntype": "bool" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "GetCurrentSceneFocusProcess", + "returntype": "uint32_t" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "GetLastFrameRenderer", + "returntype": "uint32_t" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "CanRenderScene", + "returntype": "bool" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "ShowMirrorWindow", + "returntype": "void" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "HideMirrorWindow", + "returntype": "void" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "IsMirrorWindowVisible", + "returntype": "bool" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "CompositorDumpImages", + "returntype": "void" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "ShouldAppRenderWithLowResources", + "returntype": "bool" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "ForceInterleavedReprojectionOn", + "returntype": "void", + "params": [ +{ "paramname": "bOverride" ,"paramtype": "bool"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "ForceReconnectProcess", + "returntype": "void" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "SuspendRendering", + "returntype": "void", + "params": [ +{ "paramname": "bSuspend" ,"paramtype": "bool"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "RequestScreenshot", + "returntype": "vr::EVRCompositorError", + "params": [ +{ "paramname": "type" ,"paramtype": "vr::EVRScreenshotType"}, +{ "paramname": "pchDestinationFileName" ,"paramtype": "const char *"}, +{ "paramname": "pchVRDestinationFileName" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "GetCurrentScreenshotType", + "returntype": "vr::EVRScreenshotType" +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "GetMirrorTextureD3D11", + "returntype": "vr::EVRCompositorError", + "params": [ +{ "paramname": "eEye" ,"paramtype": "vr::EVREye"}, +{ "paramname": "pD3D11DeviceOrResource" ,"paramtype": "void *"}, +{ "paramname": "ppD3D11ShaderResourceView" ,"paramtype": "void **"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "GetMirrorTextureGL", + "returntype": "vr::EVRCompositorError", + "params": [ +{ "paramname": "eEye" ,"paramtype": "vr::EVREye"}, +{ "paramname": "pglTextureId" ,"paramtype": "vr::glUInt_t *"}, +{ "paramname": "pglSharedTextureHandle" ,"paramtype": "vr::glSharedTextureHandle_t *"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "ReleaseSharedGLTexture", + "returntype": "bool", + "params": [ +{ "paramname": "glTextureId" ,"paramtype": "vr::glUInt_t"}, +{ "paramname": "glSharedTextureHandle" ,"paramtype": "vr::glSharedTextureHandle_t"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "LockGLSharedTextureForAccess", + "returntype": "void", + "params": [ +{ "paramname": "glSharedTextureHandle" ,"paramtype": "vr::glSharedTextureHandle_t"} + ] +} +,{ + "classname": "vr::IVRCompositor", + "methodname": "UnlockGLSharedTextureForAccess", + "returntype": "void", + "params": [ +{ "paramname": "glSharedTextureHandle" ,"paramtype": "vr::glSharedTextureHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "FindOverlay", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "pchOverlayKey" ,"paramtype": "const char *"}, +{ "paramname": "pOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "CreateOverlay", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "pchOverlayKey" ,"paramtype": "const char *"}, +{ "paramname": "pchOverlayFriendlyName" ,"paramtype": "const char *"}, +{ "paramname": "pOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "DestroyOverlay", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetHighQualityOverlay", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetHighQualityOverlay", + "returntype": "vr::VROverlayHandle_t" +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayKey", + "returntype": "uint32_t", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pchValue" ,"out_string": " " ,"paramtype": "char *"}, +{ "paramname": "unBufferSize" ,"paramtype": "uint32_t"}, +{ "paramname": "pError" ,"paramtype": "vr::EVROverlayError *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayName", + "returntype": "uint32_t", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pchValue" ,"out_string": " " ,"paramtype": "char *"}, +{ "paramname": "unBufferSize" ,"paramtype": "uint32_t"}, +{ "paramname": "pError" ,"paramtype": "vr::EVROverlayError *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayImageData", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pvBuffer" ,"paramtype": "void *"}, +{ "paramname": "unBufferSize" ,"paramtype": "uint32_t"}, +{ "paramname": "punWidth" ,"paramtype": "uint32_t *"}, +{ "paramname": "punHeight" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayErrorNameFromEnum", + "returntype": "const char *", + "params": [ +{ "paramname": "error" ,"paramtype": "vr::EVROverlayError"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayRenderingPid", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "unPID" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayRenderingPid", + "returntype": "uint32_t", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayFlag", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "eOverlayFlag" ,"paramtype": "vr::VROverlayFlags"}, +{ "paramname": "bEnabled" ,"paramtype": "bool"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayFlag", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "eOverlayFlag" ,"paramtype": "vr::VROverlayFlags"}, +{ "paramname": "pbEnabled" ,"paramtype": "bool *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayColor", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "fRed" ,"paramtype": "float"}, +{ "paramname": "fGreen" ,"paramtype": "float"}, +{ "paramname": "fBlue" ,"paramtype": "float"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayColor", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pfRed" ,"paramtype": "float *"}, +{ "paramname": "pfGreen" ,"paramtype": "float *"}, +{ "paramname": "pfBlue" ,"paramtype": "float *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayAlpha", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "fAlpha" ,"paramtype": "float"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayAlpha", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pfAlpha" ,"paramtype": "float *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayWidthInMeters", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "fWidthInMeters" ,"paramtype": "float"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayWidthInMeters", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pfWidthInMeters" ,"paramtype": "float *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayAutoCurveDistanceRangeInMeters", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "fMinDistanceInMeters" ,"paramtype": "float"}, +{ "paramname": "fMaxDistanceInMeters" ,"paramtype": "float"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayAutoCurveDistanceRangeInMeters", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pfMinDistanceInMeters" ,"paramtype": "float *"}, +{ "paramname": "pfMaxDistanceInMeters" ,"paramtype": "float *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayTextureColorSpace", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "eTextureColorSpace" ,"paramtype": "vr::EColorSpace"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayTextureColorSpace", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "peTextureColorSpace" ,"paramtype": "vr::EColorSpace *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayTextureBounds", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pOverlayTextureBounds" ,"paramtype": "const struct vr::VRTextureBounds_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayTextureBounds", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pOverlayTextureBounds" ,"paramtype": "struct vr::VRTextureBounds_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayTransformType", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "peTransformType" ,"paramtype": "vr::VROverlayTransformType *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayTransformAbsolute", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "eTrackingOrigin" ,"paramtype": "vr::ETrackingUniverseOrigin"}, +{ "paramname": "pmatTrackingOriginToOverlayTransform" ,"paramtype": "const struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayTransformAbsolute", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "peTrackingOrigin" ,"paramtype": "vr::ETrackingUniverseOrigin *"}, +{ "paramname": "pmatTrackingOriginToOverlayTransform" ,"paramtype": "struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayTransformTrackedDeviceRelative", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "unTrackedDevice" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "pmatTrackedDeviceToOverlayTransform" ,"paramtype": "const struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayTransformTrackedDeviceRelative", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "punTrackedDevice" ,"paramtype": "vr::TrackedDeviceIndex_t *"}, +{ "paramname": "pmatTrackedDeviceToOverlayTransform" ,"paramtype": "struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayTransformTrackedDeviceComponent", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "unDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"}, +{ "paramname": "pchComponentName" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayTransformTrackedDeviceComponent", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "punDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t *"}, +{ "paramname": "pchComponentName" ,"paramtype": "char *"}, +{ "paramname": "unComponentNameSize" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "ShowOverlay", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "HideOverlay", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "IsOverlayVisible", + "returntype": "bool", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetTransformForOverlayCoordinates", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "eTrackingOrigin" ,"paramtype": "vr::ETrackingUniverseOrigin"}, +{ "paramname": "coordinatesInOverlay" ,"paramtype": "struct vr::HmdVector2_t"}, +{ "paramname": "pmatTransform" ,"paramtype": "struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "PollNextOverlayEvent", + "returntype": "bool", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pEvent" ,"paramtype": "struct vr::VREvent_t *"}, +{ "paramname": "uncbVREvent" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayInputMethod", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "peInputMethod" ,"paramtype": "vr::VROverlayInputMethod *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayInputMethod", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "eInputMethod" ,"paramtype": "vr::VROverlayInputMethod"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayMouseScale", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pvecMouseScale" ,"paramtype": "struct vr::HmdVector2_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayMouseScale", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pvecMouseScale" ,"paramtype": "const struct vr::HmdVector2_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "ComputeOverlayIntersection", + "returntype": "bool", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pParams" ,"paramtype": "const struct vr::VROverlayIntersectionParams_t *"}, +{ "paramname": "pResults" ,"paramtype": "struct vr::VROverlayIntersectionResults_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "HandleControllerOverlayInteractionAsMouse", + "returntype": "bool", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "unControllerDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "IsHoverTargetOverlay", + "returntype": "bool", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetGamepadFocusOverlay", + "returntype": "vr::VROverlayHandle_t" +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetGamepadFocusOverlay", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulNewFocusOverlay" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayNeighbor", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "eDirection" ,"paramtype": "vr::EOverlayDirection"}, +{ "paramname": "ulFrom" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "ulTo" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "MoveGamepadFocusToNeighbor", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "eDirection" ,"paramtype": "vr::EOverlayDirection"}, +{ "paramname": "ulFrom" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayTexture", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pTexture" ,"paramtype": "const struct vr::Texture_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "ClearOverlayTexture", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayRaw", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pvBuffer" ,"paramtype": "void *"}, +{ "paramname": "unWidth" ,"paramtype": "uint32_t"}, +{ "paramname": "unHeight" ,"paramtype": "uint32_t"}, +{ "paramname": "unDepth" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetOverlayFromFile", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pchFilePath" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayTexture", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pNativeTextureHandle" ,"paramtype": "void **"}, +{ "paramname": "pNativeTextureRef" ,"paramtype": "void *"}, +{ "paramname": "pWidth" ,"paramtype": "uint32_t *"}, +{ "paramname": "pHeight" ,"paramtype": "uint32_t *"}, +{ "paramname": "pNativeFormat" ,"paramtype": "uint32_t *"}, +{ "paramname": "pAPI" ,"paramtype": "vr::EGraphicsAPIConvention *"}, +{ "paramname": "pColorSpace" ,"paramtype": "vr::EColorSpace *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "ReleaseNativeOverlayHandle", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pNativeTextureHandle" ,"paramtype": "void *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetOverlayTextureSize", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "pWidth" ,"paramtype": "uint32_t *"}, +{ "paramname": "pHeight" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "CreateDashboardOverlay", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "pchOverlayKey" ,"paramtype": "const char *"}, +{ "paramname": "pchOverlayFriendlyName" ,"paramtype": "const char *"}, +{ "paramname": "pMainHandle" ,"paramtype": "vr::VROverlayHandle_t *"}, +{ "paramname": "pThumbnailHandle" ,"paramtype": "vr::VROverlayHandle_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "IsDashboardVisible", + "returntype": "bool" +} +,{ + "classname": "vr::IVROverlay", + "methodname": "IsActiveDashboardOverlay", + "returntype": "bool", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetDashboardOverlaySceneProcess", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "unProcessId" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetDashboardOverlaySceneProcess", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "punProcessId" ,"paramtype": "uint32_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "ShowDashboard", + "returntype": "void", + "params": [ +{ "paramname": "pchOverlayToShow" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetPrimaryDashboardDevice", + "returntype": "vr::TrackedDeviceIndex_t" +} +,{ + "classname": "vr::IVROverlay", + "methodname": "ShowKeyboard", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "eInputMode" ,"paramtype": "vr::EGamepadTextInputMode"}, +{ "paramname": "eLineInputMode" ,"paramtype": "vr::EGamepadTextInputLineMode"}, +{ "paramname": "pchDescription" ,"paramtype": "const char *"}, +{ "paramname": "unCharMax" ,"paramtype": "uint32_t"}, +{ "paramname": "pchExistingText" ,"paramtype": "const char *"}, +{ "paramname": "bUseMinimalMode" ,"paramtype": "bool"}, +{ "paramname": "uUserValue" ,"paramtype": "uint64_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "ShowKeyboardForOverlay", + "returntype": "vr::EVROverlayError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "eInputMode" ,"paramtype": "vr::EGamepadTextInputMode"}, +{ "paramname": "eLineInputMode" ,"paramtype": "vr::EGamepadTextInputLineMode"}, +{ "paramname": "pchDescription" ,"paramtype": "const char *"}, +{ "paramname": "unCharMax" ,"paramtype": "uint32_t"}, +{ "paramname": "pchExistingText" ,"paramtype": "const char *"}, +{ "paramname": "bUseMinimalMode" ,"paramtype": "bool"}, +{ "paramname": "uUserValue" ,"paramtype": "uint64_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "GetKeyboardText", + "returntype": "uint32_t", + "params": [ +{ "paramname": "pchText" ,"out_string": " " ,"paramtype": "char *"}, +{ "paramname": "cchText" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "HideKeyboard", + "returntype": "void" +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetKeyboardTransformAbsolute", + "returntype": "void", + "params": [ +{ "paramname": "eTrackingOrigin" ,"paramtype": "vr::ETrackingUniverseOrigin"}, +{ "paramname": "pmatTrackingOriginToKeyboardTransform" ,"paramtype": "const struct vr::HmdMatrix34_t *"} + ] +} +,{ + "classname": "vr::IVROverlay", + "methodname": "SetKeyboardPositionForOverlay", + "returntype": "void", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "avoidRect" ,"paramtype": "struct vr::HmdRect2_t"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "LoadRenderModel_Async", + "returntype": "vr::EVRRenderModelError", + "params": [ +{ "paramname": "pchRenderModelName" ,"paramtype": "const char *"}, +{ "paramname": "ppRenderModel" ,"paramtype": "struct vr::RenderModel_t **"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "FreeRenderModel", + "returntype": "void", + "params": [ +{ "paramname": "pRenderModel" ,"paramtype": "struct vr::RenderModel_t *"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "LoadTexture_Async", + "returntype": "vr::EVRRenderModelError", + "params": [ +{ "paramname": "textureId" ,"paramtype": "vr::TextureID_t"}, +{ "paramname": "ppTexture" ,"paramtype": "struct vr::RenderModel_TextureMap_t **"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "FreeTexture", + "returntype": "void", + "params": [ +{ "paramname": "pTexture" ,"paramtype": "struct vr::RenderModel_TextureMap_t *"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "LoadTextureD3D11_Async", + "returntype": "vr::EVRRenderModelError", + "params": [ +{ "paramname": "textureId" ,"paramtype": "vr::TextureID_t"}, +{ "paramname": "pD3D11Device" ,"paramtype": "void *"}, +{ "paramname": "ppD3D11Texture2D" ,"paramtype": "void **"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "LoadIntoTextureD3D11_Async", + "returntype": "vr::EVRRenderModelError", + "params": [ +{ "paramname": "textureId" ,"paramtype": "vr::TextureID_t"}, +{ "paramname": "pDstTexture" ,"paramtype": "void *"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "FreeTextureD3D11", + "returntype": "void", + "params": [ +{ "paramname": "pD3D11Texture2D" ,"paramtype": "void *"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "GetRenderModelName", + "returntype": "uint32_t", + "params": [ +{ "paramname": "unRenderModelIndex" ,"paramtype": "uint32_t"}, +{ "paramname": "pchRenderModelName" ,"out_string": " " ,"paramtype": "char *"}, +{ "paramname": "unRenderModelNameLen" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "GetRenderModelCount", + "returntype": "uint32_t" +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "GetComponentCount", + "returntype": "uint32_t", + "params": [ +{ "paramname": "pchRenderModelName" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "GetComponentName", + "returntype": "uint32_t", + "params": [ +{ "paramname": "pchRenderModelName" ,"paramtype": "const char *"}, +{ "paramname": "unComponentIndex" ,"paramtype": "uint32_t"}, +{ "paramname": "pchComponentName" ,"out_string": " " ,"paramtype": "char *"}, +{ "paramname": "unComponentNameLen" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "GetComponentButtonMask", + "returntype": "uint64_t", + "params": [ +{ "paramname": "pchRenderModelName" ,"paramtype": "const char *"}, +{ "paramname": "pchComponentName" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "GetComponentRenderModelName", + "returntype": "uint32_t", + "params": [ +{ "paramname": "pchRenderModelName" ,"paramtype": "const char *"}, +{ "paramname": "pchComponentName" ,"paramtype": "const char *"}, +{ "paramname": "pchComponentRenderModelName" ,"out_string": " " ,"paramtype": "char *"}, +{ "paramname": "unComponentRenderModelNameLen" ,"paramtype": "uint32_t"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "GetComponentState", + "returntype": "bool", + "params": [ +{ "paramname": "pchRenderModelName" ,"paramtype": "const char *"}, +{ "paramname": "pchComponentName" ,"paramtype": "const char *"}, +{ "paramname": "pControllerState" ,"paramtype": "const vr::VRControllerState_t *"}, +{ "paramname": "pState" ,"paramtype": "const struct vr::RenderModel_ControllerMode_State_t *"}, +{ "paramname": "pComponentState" ,"paramtype": "struct vr::RenderModel_ComponentState_t *"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "RenderModelHasComponent", + "returntype": "bool", + "params": [ +{ "paramname": "pchRenderModelName" ,"paramtype": "const char *"}, +{ "paramname": "pchComponentName" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "GetRenderModelThumbnailURL", + "returntype": "uint32_t", + "params": [ +{ "paramname": "pchRenderModelName" ,"paramtype": "const char *"}, +{ "paramname": "pchThumbnailURL" ,"out_string": " " ,"paramtype": "char *"}, +{ "paramname": "unThumbnailURLLen" ,"paramtype": "uint32_t"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRRenderModelError *"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "GetRenderModelOriginalPath", + "returntype": "uint32_t", + "params": [ +{ "paramname": "pchRenderModelName" ,"paramtype": "const char *"}, +{ "paramname": "pchOriginalPath" ,"out_string": " " ,"paramtype": "char *"}, +{ "paramname": "unOriginalPathLen" ,"paramtype": "uint32_t"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRRenderModelError *"} + ] +} +,{ + "classname": "vr::IVRRenderModels", + "methodname": "GetRenderModelErrorNameFromEnum", + "returntype": "const char *", + "params": [ +{ "paramname": "error" ,"paramtype": "vr::EVRRenderModelError"} + ] +} +,{ + "classname": "vr::IVRNotifications", + "methodname": "CreateNotification", + "returntype": "vr::EVRNotificationError", + "params": [ +{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"}, +{ "paramname": "ulUserValue" ,"paramtype": "uint64_t"}, +{ "paramname": "type" ,"paramtype": "vr::EVRNotificationType"}, +{ "paramname": "pchText" ,"paramtype": "const char *"}, +{ "paramname": "style" ,"paramtype": "vr::EVRNotificationStyle"}, +{ "paramname": "pImage" ,"paramtype": "const struct vr::NotificationBitmap_t *"}, +{ "paramname": "pNotificationId" ,"paramtype": "vr::VRNotificationId *"} + ] +} +,{ + "classname": "vr::IVRNotifications", + "methodname": "RemoveNotification", + "returntype": "vr::EVRNotificationError", + "params": [ +{ "paramname": "notificationId" ,"paramtype": "vr::VRNotificationId"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "GetSettingsErrorNameFromEnum", + "returntype": "const char *", + "params": [ +{ "paramname": "eError" ,"paramtype": "vr::EVRSettingsError"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "Sync", + "returntype": "bool", + "params": [ +{ "paramname": "bForce" ,"paramtype": "bool"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "GetBool", + "returntype": "bool", + "params": [ +{ "paramname": "pchSection" ,"paramtype": "const char *"}, +{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"}, +{ "paramname": "bDefaultValue" ,"paramtype": "bool"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "SetBool", + "returntype": "void", + "params": [ +{ "paramname": "pchSection" ,"paramtype": "const char *"}, +{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"}, +{ "paramname": "bValue" ,"paramtype": "bool"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "GetInt32", + "returntype": "int32_t", + "params": [ +{ "paramname": "pchSection" ,"paramtype": "const char *"}, +{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"}, +{ "paramname": "nDefaultValue" ,"paramtype": "int32_t"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "SetInt32", + "returntype": "void", + "params": [ +{ "paramname": "pchSection" ,"paramtype": "const char *"}, +{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"}, +{ "paramname": "nValue" ,"paramtype": "int32_t"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "GetFloat", + "returntype": "float", + "params": [ +{ "paramname": "pchSection" ,"paramtype": "const char *"}, +{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"}, +{ "paramname": "flDefaultValue" ,"paramtype": "float"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "SetFloat", + "returntype": "void", + "params": [ +{ "paramname": "pchSection" ,"paramtype": "const char *"}, +{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"}, +{ "paramname": "flValue" ,"paramtype": "float"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "GetString", + "returntype": "void", + "params": [ +{ "paramname": "pchSection" ,"paramtype": "const char *"}, +{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"}, +{ "paramname": "pchValue" ,"paramtype": "char *"}, +{ "paramname": "unValueLen" ,"paramtype": "uint32_t"}, +{ "paramname": "pchDefaultValue" ,"paramtype": "const char *"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "SetString", + "returntype": "void", + "params": [ +{ "paramname": "pchSection" ,"paramtype": "const char *"}, +{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"}, +{ "paramname": "pchValue" ,"paramtype": "const char *"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "RemoveSection", + "returntype": "void", + "params": [ +{ "paramname": "pchSection" ,"paramtype": "const char *"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"} + ] +} +,{ + "classname": "vr::IVRSettings", + "methodname": "RemoveKeyInSection", + "returntype": "void", + "params": [ +{ "paramname": "pchSection" ,"paramtype": "const char *"}, +{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"}, +{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"} + ] +} +,{ + "classname": "vr::IVRScreenshots", + "methodname": "RequestScreenshot", + "returntype": "vr::EVRScreenshotError", + "params": [ +{ "paramname": "pOutScreenshotHandle" ,"paramtype": "vr::ScreenshotHandle_t *"}, +{ "paramname": "type" ,"paramtype": "vr::EVRScreenshotType"}, +{ "paramname": "pchPreviewFilename" ,"paramtype": "const char *"}, +{ "paramname": "pchVRFilename" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRScreenshots", + "methodname": "HookScreenshot", + "returntype": "vr::EVRScreenshotError", + "params": [ +{ "paramname": "pSupportedTypes" ,"array_count": "numTypes" ,"paramtype": "const vr::EVRScreenshotType *"}, +{ "paramname": "numTypes" ,"paramtype": "int"} + ] +} +,{ + "classname": "vr::IVRScreenshots", + "methodname": "GetScreenshotPropertyType", + "returntype": "vr::EVRScreenshotType", + "params": [ +{ "paramname": "screenshotHandle" ,"paramtype": "vr::ScreenshotHandle_t"}, +{ "paramname": "pError" ,"paramtype": "vr::EVRScreenshotError *"} + ] +} +,{ + "classname": "vr::IVRScreenshots", + "methodname": "GetScreenshotPropertyFilename", + "returntype": "uint32_t", + "params": [ +{ "paramname": "screenshotHandle" ,"paramtype": "vr::ScreenshotHandle_t"}, +{ "paramname": "filenameType" ,"paramtype": "vr::EVRScreenshotPropertyFilenames"}, +{ "paramname": "pchFilename" ,"out_string": " " ,"paramtype": "char *"}, +{ "paramname": "cchFilename" ,"paramtype": "uint32_t"}, +{ "paramname": "pError" ,"paramtype": "vr::EVRScreenshotError *"} + ] +} +,{ + "classname": "vr::IVRScreenshots", + "methodname": "UpdateScreenshotProgress", + "returntype": "vr::EVRScreenshotError", + "params": [ +{ "paramname": "screenshotHandle" ,"paramtype": "vr::ScreenshotHandle_t"}, +{ "paramname": "flProgress" ,"paramtype": "float"} + ] +} +,{ + "classname": "vr::IVRScreenshots", + "methodname": "TakeStereoScreenshot", + "returntype": "vr::EVRScreenshotError", + "params": [ +{ "paramname": "pOutScreenshotHandle" ,"paramtype": "vr::ScreenshotHandle_t *"}, +{ "paramname": "pchPreviewFilename" ,"paramtype": "const char *"}, +{ "paramname": "pchVRFilename" ,"paramtype": "const char *"} + ] +} +,{ + "classname": "vr::IVRScreenshots", + "methodname": "SubmitScreenshot", + "returntype": "vr::EVRScreenshotError", + "params": [ +{ "paramname": "screenshotHandle" ,"paramtype": "vr::ScreenshotHandle_t"}, +{ "paramname": "type" ,"paramtype": "vr::EVRScreenshotType"}, +{ "paramname": "pchSourcePreviewFilename" ,"paramtype": "const char *"}, +{ "paramname": "pchSourceVRFilename" ,"paramtype": "const char *"} + ] +} +] +} \ No newline at end of file diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr_capi.h b/examples/ThirdPartyLibs/openvr/headers/openvr_capi.h new file mode 100644 index 000000000..76eafd4d6 --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/headers/openvr_capi.h @@ -0,0 +1,1626 @@ +//======= Copyright (c) Valve Corporation, All rights reserved. =============== +// +// Purpose: Header for flatted SteamAPI. Use this for binding to other languages. +// This file is auto-generated, do not edit it. +// +//============================================================================= + +#ifndef __OPENVR_API_FLAT_H__ +#define __OPENVR_API_FLAT_H__ +#if defined( _WIN32 ) || defined( __clang__ ) +#pragma once +#endif + +#ifdef __cplusplus +#define EXTERN_C extern "C" +#else +#define EXTERN_C +#endif + +#define OPENVR_FNTABLE_CALLTYPE __stdcall + +// OPENVR API export macro +#if defined( _WIN32 ) && !defined( _X360 ) + #if defined( OPENVR_API_EXPORTS ) + #define S_API EXTERN_C __declspec( dllexport ) + #elif defined( OPENVR_API_NODLL ) + #define S_API EXTERN_C + #else + #define S_API extern "C" __declspec( dllimport ) + #endif // OPENVR_API_EXPORTS +#elif defined( GNUC ) + #if defined( OPENVR_API_EXPORTS ) + #define S_API EXTERN_C __attribute__ ((visibility("default"))) + #else + #define S_API EXTERN_C + #endif // OPENVR_API_EXPORTS +#else // !WIN32 + #if defined( OPENVR_API_EXPORTS ) + #define S_API EXTERN_C + #else + #define S_API EXTERN_C + #endif // OPENVR_API_EXPORTS +#endif + +#include + +#if defined( __WIN32 ) +typedef char bool; +#endif + + +// OpenVR Constants + +static const unsigned int k_unTrackingStringSize = 32; +static const unsigned int k_unMaxDriverDebugResponseSize = 32768; +static const unsigned int k_unTrackedDeviceIndex_Hmd = 0; +static const unsigned int k_unMaxTrackedDeviceCount = 16; +static const unsigned int k_unTrackedDeviceIndexOther = 4294967294; +static const unsigned int k_unTrackedDeviceIndexInvalid = 4294967295; +static const unsigned int k_unMaxPropertyStringSize = 32768; +static const unsigned int k_unControllerStateAxisCount = 5; +static const unsigned long k_ulOverlayHandleInvalid = 0; +static const unsigned int k_unScreenshotHandleInvalid = 0; +static const char * IVRSystem_Version = "IVRSystem_012"; +static const char * IVRExtendedDisplay_Version = "IVRExtendedDisplay_001"; +static const char * IVRTrackedCamera_Version = "IVRTrackedCamera_003"; +static const unsigned int k_unMaxApplicationKeyLength = 128; +static const char * IVRApplications_Version = "IVRApplications_005"; +static const char * IVRChaperone_Version = "IVRChaperone_003"; +static const char * IVRChaperoneSetup_Version = "IVRChaperoneSetup_005"; +static const char * IVRCompositor_Version = "IVRCompositor_015"; +static const unsigned int k_unVROverlayMaxKeyLength = 128; +static const unsigned int k_unVROverlayMaxNameLength = 128; +static const unsigned int k_unMaxOverlayCount = 32; +static const char * IVROverlay_Version = "IVROverlay_012"; +static const char * k_pch_Controller_Component_GDC2015 = "gdc2015"; +static const char * k_pch_Controller_Component_Base = "base"; +static const char * k_pch_Controller_Component_Tip = "tip"; +static const char * k_pch_Controller_Component_HandGrip = "handgrip"; +static const char * k_pch_Controller_Component_Status = "status"; +static const char * IVRRenderModels_Version = "IVRRenderModels_005"; +static const unsigned int k_unNotificationTextMaxSize = 256; +static const char * IVRNotifications_Version = "IVRNotifications_002"; +static const unsigned int k_unMaxSettingsKeyLength = 128; +static const char * IVRSettings_Version = "IVRSettings_001"; +static const char * k_pch_SteamVR_Section = "steamvr"; +static const char * k_pch_SteamVR_RequireHmd_String = "requireHmd"; +static const char * k_pch_SteamVR_ForcedDriverKey_String = "forcedDriver"; +static const char * k_pch_SteamVR_ForcedHmdKey_String = "forcedHmd"; +static const char * k_pch_SteamVR_DisplayDebug_Bool = "displayDebug"; +static const char * k_pch_SteamVR_DebugProcessPipe_String = "debugProcessPipe"; +static const char * k_pch_SteamVR_EnableDistortion_Bool = "enableDistortion"; +static const char * k_pch_SteamVR_DisplayDebugX_Int32 = "displayDebugX"; +static const char * k_pch_SteamVR_DisplayDebugY_Int32 = "displayDebugY"; +static const char * k_pch_SteamVR_SendSystemButtonToAllApps_Bool = "sendSystemButtonToAllApps"; +static const char * k_pch_SteamVR_LogLevel_Int32 = "loglevel"; +static const char * k_pch_SteamVR_IPD_Float = "ipd"; +static const char * k_pch_SteamVR_Background_String = "background"; +static const char * k_pch_SteamVR_BackgroundCameraHeight_Float = "backgroundCameraHeight"; +static const char * k_pch_SteamVR_BackgroundDomeRadius_Float = "backgroundDomeRadius"; +static const char * k_pch_SteamVR_Environment_String = "environment"; +static const char * k_pch_SteamVR_GridColor_String = "gridColor"; +static const char * k_pch_SteamVR_PlayAreaColor_String = "playAreaColor"; +static const char * k_pch_SteamVR_ShowStage_Bool = "showStage"; +static const char * k_pch_SteamVR_ActivateMultipleDrivers_Bool = "activateMultipleDrivers"; +static const char * k_pch_SteamVR_PowerOffOnExit_Bool = "powerOffOnExit"; +static const char * k_pch_SteamVR_StandbyAppRunningTimeout_Float = "standbyAppRunningTimeout"; +static const char * k_pch_SteamVR_StandbyNoAppTimeout_Float = "standbyNoAppTimeout"; +static const char * k_pch_SteamVR_DirectMode_Bool = "directMode"; +static const char * k_pch_SteamVR_DirectModeEdidVid_Int32 = "directModeEdidVid"; +static const char * k_pch_SteamVR_DirectModeEdidPid_Int32 = "directModeEdidPid"; +static const char * k_pch_SteamVR_UsingSpeakers_Bool = "usingSpeakers"; +static const char * k_pch_SteamVR_SpeakersForwardYawOffsetDegrees_Float = "speakersForwardYawOffsetDegrees"; +static const char * k_pch_SteamVR_BaseStationPowerManagement_Bool = "basestationPowerManagement"; +static const char * k_pch_SteamVR_NeverKillProcesses_Bool = "neverKillProcesses"; +static const char * k_pch_SteamVR_RenderTargetMultiplier_Float = "renderTargetMultiplier"; +static const char * k_pch_SteamVR_AllowReprojection_Bool = "allowReprojection"; +static const char * k_pch_SteamVR_ForceReprojection_Bool = "forceReprojection"; +static const char * k_pch_SteamVR_ForceFadeOnBadTracking_Bool = "forceFadeOnBadTracking"; +static const char * k_pch_SteamVR_DefaultMirrorView_Int32 = "defaultMirrorView"; +static const char * k_pch_SteamVR_ShowMirrorView_Bool = "showMirrorView"; +static const char * k_pch_Lighthouse_Section = "driver_lighthouse"; +static const char * k_pch_Lighthouse_DisableIMU_Bool = "disableimu"; +static const char * k_pch_Lighthouse_UseDisambiguation_String = "usedisambiguation"; +static const char * k_pch_Lighthouse_DisambiguationDebug_Int32 = "disambiguationdebug"; +static const char * k_pch_Lighthouse_PrimaryBasestation_Int32 = "primarybasestation"; +static const char * k_pch_Lighthouse_LighthouseName_String = "lighthousename"; +static const char * k_pch_Lighthouse_MaxIncidenceAngleDegrees_Float = "maxincidenceangledegrees"; +static const char * k_pch_Lighthouse_UseLighthouseDirect_Bool = "uselighthousedirect"; +static const char * k_pch_Lighthouse_DBHistory_Bool = "dbhistory"; +static const char * k_pch_Null_Section = "driver_null"; +static const char * k_pch_Null_EnableNullDriver_Bool = "enable"; +static const char * k_pch_Null_SerialNumber_String = "serialNumber"; +static const char * k_pch_Null_ModelNumber_String = "modelNumber"; +static const char * k_pch_Null_WindowX_Int32 = "windowX"; +static const char * k_pch_Null_WindowY_Int32 = "windowY"; +static const char * k_pch_Null_WindowWidth_Int32 = "windowWidth"; +static const char * k_pch_Null_WindowHeight_Int32 = "windowHeight"; +static const char * k_pch_Null_RenderWidth_Int32 = "renderWidth"; +static const char * k_pch_Null_RenderHeight_Int32 = "renderHeight"; +static const char * k_pch_Null_SecondsFromVsyncToPhotons_Float = "secondsFromVsyncToPhotons"; +static const char * k_pch_Null_DisplayFrequency_Float = "displayFrequency"; +static const char * k_pch_UserInterface_Section = "userinterface"; +static const char * k_pch_UserInterface_StatusAlwaysOnTop_Bool = "StatusAlwaysOnTop"; +static const char * k_pch_UserInterface_EnableScreenshots_Bool = "EnableScreenshots"; +static const char * k_pch_Notifications_Section = "notifications"; +static const char * k_pch_Notifications_DoNotDisturb_Bool = "DoNotDisturb"; +static const char * k_pch_Keyboard_Section = "keyboard"; +static const char * k_pch_Keyboard_TutorialCompletions = "TutorialCompletions"; +static const char * k_pch_Keyboard_ScaleX = "ScaleX"; +static const char * k_pch_Keyboard_ScaleY = "ScaleY"; +static const char * k_pch_Keyboard_OffsetLeftX = "OffsetLeftX"; +static const char * k_pch_Keyboard_OffsetRightX = "OffsetRightX"; +static const char * k_pch_Keyboard_OffsetY = "OffsetY"; +static const char * k_pch_Keyboard_Smoothing = "Smoothing"; +static const char * k_pch_Perf_Section = "perfcheck"; +static const char * k_pch_Perf_HeuristicActive_Bool = "heuristicActive"; +static const char * k_pch_Perf_NotifyInHMD_Bool = "warnInHMD"; +static const char * k_pch_Perf_NotifyOnlyOnce_Bool = "warnOnlyOnce"; +static const char * k_pch_Perf_AllowTimingStore_Bool = "allowTimingStore"; +static const char * k_pch_Perf_SaveTimingsOnExit_Bool = "saveTimingsOnExit"; +static const char * k_pch_Perf_TestData_Float = "perfTestData"; +static const char * k_pch_CollisionBounds_Section = "collisionBounds"; +static const char * k_pch_CollisionBounds_Style_Int32 = "CollisionBoundsStyle"; +static const char * k_pch_CollisionBounds_GroundPerimeterOn_Bool = "CollisionBoundsGroundPerimeterOn"; +static const char * k_pch_CollisionBounds_CenterMarkerOn_Bool = "CollisionBoundsCenterMarkerOn"; +static const char * k_pch_CollisionBounds_PlaySpaceOn_Bool = "CollisionBoundsPlaySpaceOn"; +static const char * k_pch_CollisionBounds_FadeDistance_Float = "CollisionBoundsFadeDistance"; +static const char * k_pch_CollisionBounds_ColorGammaR_Int32 = "CollisionBoundsColorGammaR"; +static const char * k_pch_CollisionBounds_ColorGammaG_Int32 = "CollisionBoundsColorGammaG"; +static const char * k_pch_CollisionBounds_ColorGammaB_Int32 = "CollisionBoundsColorGammaB"; +static const char * k_pch_CollisionBounds_ColorGammaA_Int32 = "CollisionBoundsColorGammaA"; +static const char * k_pch_Camera_Section = "camera"; +static const char * k_pch_Camera_EnableCamera_Bool = "enableCamera"; +static const char * k_pch_Camera_EnableCameraInDashboard_Bool = "enableCameraInDashboard"; +static const char * k_pch_Camera_EnableCameraForCollisionBounds_Bool = "enableCameraForCollisionBounds"; +static const char * k_pch_Camera_EnableCameraForRoomView_Bool = "enableCameraForRoomView"; +static const char * k_pch_Camera_BoundsColorGammaR_Int32 = "cameraBoundsColorGammaR"; +static const char * k_pch_Camera_BoundsColorGammaG_Int32 = "cameraBoundsColorGammaG"; +static const char * k_pch_Camera_BoundsColorGammaB_Int32 = "cameraBoundsColorGammaB"; +static const char * k_pch_Camera_BoundsColorGammaA_Int32 = "cameraBoundsColorGammaA"; +static const char * k_pch_audio_Section = "audio"; +static const char * k_pch_audio_OnPlaybackDevice_String = "onPlaybackDevice"; +static const char * k_pch_audio_OnRecordDevice_String = "onRecordDevice"; +static const char * k_pch_audio_OnPlaybackMirrorDevice_String = "onPlaybackMirrorDevice"; +static const char * k_pch_audio_OffPlaybackDevice_String = "offPlaybackDevice"; +static const char * k_pch_audio_OffRecordDevice_String = "offRecordDevice"; +static const char * k_pch_audio_VIVEHDMIGain = "viveHDMIGain"; +static const char * k_pch_modelskin_Section = "modelskins"; +static const char * IVRScreenshots_Version = "IVRScreenshots_001"; + +// OpenVR Enums + +typedef enum EVREye +{ + EVREye_Eye_Left = 0, + EVREye_Eye_Right = 1, +} EVREye; + +typedef enum EGraphicsAPIConvention +{ + EGraphicsAPIConvention_API_DirectX = 0, + EGraphicsAPIConvention_API_OpenGL = 1, +} EGraphicsAPIConvention; + +typedef enum EColorSpace +{ + EColorSpace_ColorSpace_Auto = 0, + EColorSpace_ColorSpace_Gamma = 1, + EColorSpace_ColorSpace_Linear = 2, +} EColorSpace; + +typedef enum ETrackingResult +{ + ETrackingResult_TrackingResult_Uninitialized = 1, + ETrackingResult_TrackingResult_Calibrating_InProgress = 100, + ETrackingResult_TrackingResult_Calibrating_OutOfRange = 101, + ETrackingResult_TrackingResult_Running_OK = 200, + ETrackingResult_TrackingResult_Running_OutOfRange = 201, +} ETrackingResult; + +typedef enum ETrackedDeviceClass +{ + ETrackedDeviceClass_TrackedDeviceClass_Invalid = 0, + ETrackedDeviceClass_TrackedDeviceClass_HMD = 1, + ETrackedDeviceClass_TrackedDeviceClass_Controller = 2, + ETrackedDeviceClass_TrackedDeviceClass_TrackingReference = 4, + ETrackedDeviceClass_TrackedDeviceClass_Other = 1000, +} ETrackedDeviceClass; + +typedef enum ETrackedControllerRole +{ + ETrackedControllerRole_TrackedControllerRole_Invalid = 0, + ETrackedControllerRole_TrackedControllerRole_LeftHand = 1, + ETrackedControllerRole_TrackedControllerRole_RightHand = 2, +} ETrackedControllerRole; + +typedef enum ETrackingUniverseOrigin +{ + ETrackingUniverseOrigin_TrackingUniverseSeated = 0, + ETrackingUniverseOrigin_TrackingUniverseStanding = 1, + ETrackingUniverseOrigin_TrackingUniverseRawAndUncalibrated = 2, +} ETrackingUniverseOrigin; + +typedef enum ETrackedDeviceProperty +{ + ETrackedDeviceProperty_Prop_TrackingSystemName_String = 1000, + ETrackedDeviceProperty_Prop_ModelNumber_String = 1001, + ETrackedDeviceProperty_Prop_SerialNumber_String = 1002, + ETrackedDeviceProperty_Prop_RenderModelName_String = 1003, + ETrackedDeviceProperty_Prop_WillDriftInYaw_Bool = 1004, + ETrackedDeviceProperty_Prop_ManufacturerName_String = 1005, + ETrackedDeviceProperty_Prop_TrackingFirmwareVersion_String = 1006, + ETrackedDeviceProperty_Prop_HardwareRevision_String = 1007, + ETrackedDeviceProperty_Prop_AllWirelessDongleDescriptions_String = 1008, + ETrackedDeviceProperty_Prop_ConnectedWirelessDongle_String = 1009, + ETrackedDeviceProperty_Prop_DeviceIsWireless_Bool = 1010, + ETrackedDeviceProperty_Prop_DeviceIsCharging_Bool = 1011, + ETrackedDeviceProperty_Prop_DeviceBatteryPercentage_Float = 1012, + ETrackedDeviceProperty_Prop_StatusDisplayTransform_Matrix34 = 1013, + ETrackedDeviceProperty_Prop_Firmware_UpdateAvailable_Bool = 1014, + ETrackedDeviceProperty_Prop_Firmware_ManualUpdate_Bool = 1015, + ETrackedDeviceProperty_Prop_Firmware_ManualUpdateURL_String = 1016, + ETrackedDeviceProperty_Prop_HardwareRevision_Uint64 = 1017, + ETrackedDeviceProperty_Prop_FirmwareVersion_Uint64 = 1018, + ETrackedDeviceProperty_Prop_FPGAVersion_Uint64 = 1019, + ETrackedDeviceProperty_Prop_VRCVersion_Uint64 = 1020, + ETrackedDeviceProperty_Prop_RadioVersion_Uint64 = 1021, + ETrackedDeviceProperty_Prop_DongleVersion_Uint64 = 1022, + ETrackedDeviceProperty_Prop_BlockServerShutdown_Bool = 1023, + ETrackedDeviceProperty_Prop_CanUnifyCoordinateSystemWithHmd_Bool = 1024, + ETrackedDeviceProperty_Prop_ContainsProximitySensor_Bool = 1025, + ETrackedDeviceProperty_Prop_DeviceProvidesBatteryStatus_Bool = 1026, + ETrackedDeviceProperty_Prop_DeviceCanPowerOff_Bool = 1027, + ETrackedDeviceProperty_Prop_Firmware_ProgrammingTarget_String = 1028, + ETrackedDeviceProperty_Prop_DeviceClass_Int32 = 1029, + ETrackedDeviceProperty_Prop_HasCamera_Bool = 1030, + ETrackedDeviceProperty_Prop_DriverVersion_String = 1031, + ETrackedDeviceProperty_Prop_Firmware_ForceUpdateRequired_Bool = 1032, + ETrackedDeviceProperty_Prop_ReportsTimeSinceVSync_Bool = 2000, + ETrackedDeviceProperty_Prop_SecondsFromVsyncToPhotons_Float = 2001, + ETrackedDeviceProperty_Prop_DisplayFrequency_Float = 2002, + ETrackedDeviceProperty_Prop_UserIpdMeters_Float = 2003, + ETrackedDeviceProperty_Prop_CurrentUniverseId_Uint64 = 2004, + ETrackedDeviceProperty_Prop_PreviousUniverseId_Uint64 = 2005, + ETrackedDeviceProperty_Prop_DisplayFirmwareVersion_Uint64 = 2006, + ETrackedDeviceProperty_Prop_IsOnDesktop_Bool = 2007, + ETrackedDeviceProperty_Prop_DisplayMCType_Int32 = 2008, + ETrackedDeviceProperty_Prop_DisplayMCOffset_Float = 2009, + ETrackedDeviceProperty_Prop_DisplayMCScale_Float = 2010, + ETrackedDeviceProperty_Prop_EdidVendorID_Int32 = 2011, + ETrackedDeviceProperty_Prop_DisplayMCImageLeft_String = 2012, + ETrackedDeviceProperty_Prop_DisplayMCImageRight_String = 2013, + ETrackedDeviceProperty_Prop_DisplayGCBlackClamp_Float = 2014, + ETrackedDeviceProperty_Prop_EdidProductID_Int32 = 2015, + ETrackedDeviceProperty_Prop_CameraToHeadTransform_Matrix34 = 2016, + ETrackedDeviceProperty_Prop_DisplayGCType_Int32 = 2017, + ETrackedDeviceProperty_Prop_DisplayGCOffset_Float = 2018, + ETrackedDeviceProperty_Prop_DisplayGCScale_Float = 2019, + ETrackedDeviceProperty_Prop_DisplayGCPrescale_Float = 2020, + ETrackedDeviceProperty_Prop_DisplayGCImage_String = 2021, + ETrackedDeviceProperty_Prop_LensCenterLeftU_Float = 2022, + ETrackedDeviceProperty_Prop_LensCenterLeftV_Float = 2023, + ETrackedDeviceProperty_Prop_LensCenterRightU_Float = 2024, + ETrackedDeviceProperty_Prop_LensCenterRightV_Float = 2025, + ETrackedDeviceProperty_Prop_UserHeadToEyeDepthMeters_Float = 2026, + ETrackedDeviceProperty_Prop_CameraFirmwareVersion_Uint64 = 2027, + ETrackedDeviceProperty_Prop_CameraFirmwareDescription_String = 2028, + ETrackedDeviceProperty_Prop_DisplayFPGAVersion_Uint64 = 2029, + ETrackedDeviceProperty_Prop_DisplayBootloaderVersion_Uint64 = 2030, + ETrackedDeviceProperty_Prop_DisplayHardwareVersion_Uint64 = 2031, + ETrackedDeviceProperty_Prop_AudioFirmwareVersion_Uint64 = 2032, + ETrackedDeviceProperty_Prop_CameraCompatibilityMode_Int32 = 2033, + ETrackedDeviceProperty_Prop_ScreenshotHorizontalFieldOfViewDegrees_Float = 2034, + ETrackedDeviceProperty_Prop_ScreenshotVerticalFieldOfViewDegrees_Float = 2035, + ETrackedDeviceProperty_Prop_DisplaySuppressed_Bool = 2036, + ETrackedDeviceProperty_Prop_AttachedDeviceId_String = 3000, + ETrackedDeviceProperty_Prop_SupportedButtons_Uint64 = 3001, + ETrackedDeviceProperty_Prop_Axis0Type_Int32 = 3002, + ETrackedDeviceProperty_Prop_Axis1Type_Int32 = 3003, + ETrackedDeviceProperty_Prop_Axis2Type_Int32 = 3004, + ETrackedDeviceProperty_Prop_Axis3Type_Int32 = 3005, + ETrackedDeviceProperty_Prop_Axis4Type_Int32 = 3006, + ETrackedDeviceProperty_Prop_FieldOfViewLeftDegrees_Float = 4000, + ETrackedDeviceProperty_Prop_FieldOfViewRightDegrees_Float = 4001, + ETrackedDeviceProperty_Prop_FieldOfViewTopDegrees_Float = 4002, + ETrackedDeviceProperty_Prop_FieldOfViewBottomDegrees_Float = 4003, + ETrackedDeviceProperty_Prop_TrackingRangeMinimumMeters_Float = 4004, + ETrackedDeviceProperty_Prop_TrackingRangeMaximumMeters_Float = 4005, + ETrackedDeviceProperty_Prop_ModeLabel_String = 4006, + ETrackedDeviceProperty_Prop_VendorSpecific_Reserved_Start = 10000, + ETrackedDeviceProperty_Prop_VendorSpecific_Reserved_End = 10999, +} ETrackedDeviceProperty; + +typedef enum ETrackedPropertyError +{ + ETrackedPropertyError_TrackedProp_Success = 0, + ETrackedPropertyError_TrackedProp_WrongDataType = 1, + ETrackedPropertyError_TrackedProp_WrongDeviceClass = 2, + ETrackedPropertyError_TrackedProp_BufferTooSmall = 3, + ETrackedPropertyError_TrackedProp_UnknownProperty = 4, + ETrackedPropertyError_TrackedProp_InvalidDevice = 5, + ETrackedPropertyError_TrackedProp_CouldNotContactServer = 6, + ETrackedPropertyError_TrackedProp_ValueNotProvidedByDevice = 7, + ETrackedPropertyError_TrackedProp_StringExceedsMaximumLength = 8, + ETrackedPropertyError_TrackedProp_NotYetAvailable = 9, +} ETrackedPropertyError; + +typedef enum EVRSubmitFlags +{ + EVRSubmitFlags_Submit_Default = 0, + EVRSubmitFlags_Submit_LensDistortionAlreadyApplied = 1, + EVRSubmitFlags_Submit_GlRenderBuffer = 2, +} EVRSubmitFlags; + +typedef enum EVRState +{ + EVRState_VRState_Undefined = -1, + EVRState_VRState_Off = 0, + EVRState_VRState_Searching = 1, + EVRState_VRState_Searching_Alert = 2, + EVRState_VRState_Ready = 3, + EVRState_VRState_Ready_Alert = 4, + EVRState_VRState_NotReady = 5, + EVRState_VRState_Standby = 6, +} EVRState; + +typedef enum EVREventType +{ + EVREventType_VREvent_None = 0, + EVREventType_VREvent_TrackedDeviceActivated = 100, + EVREventType_VREvent_TrackedDeviceDeactivated = 101, + EVREventType_VREvent_TrackedDeviceUpdated = 102, + EVREventType_VREvent_TrackedDeviceUserInteractionStarted = 103, + EVREventType_VREvent_TrackedDeviceUserInteractionEnded = 104, + EVREventType_VREvent_IpdChanged = 105, + EVREventType_VREvent_EnterStandbyMode = 106, + EVREventType_VREvent_LeaveStandbyMode = 107, + EVREventType_VREvent_TrackedDeviceRoleChanged = 108, + EVREventType_VREvent_ButtonPress = 200, + EVREventType_VREvent_ButtonUnpress = 201, + EVREventType_VREvent_ButtonTouch = 202, + EVREventType_VREvent_ButtonUntouch = 203, + EVREventType_VREvent_MouseMove = 300, + EVREventType_VREvent_MouseButtonDown = 301, + EVREventType_VREvent_MouseButtonUp = 302, + EVREventType_VREvent_FocusEnter = 303, + EVREventType_VREvent_FocusLeave = 304, + EVREventType_VREvent_Scroll = 305, + EVREventType_VREvent_TouchPadMove = 306, + EVREventType_VREvent_InputFocusCaptured = 400, + EVREventType_VREvent_InputFocusReleased = 401, + EVREventType_VREvent_SceneFocusLost = 402, + EVREventType_VREvent_SceneFocusGained = 403, + EVREventType_VREvent_SceneApplicationChanged = 404, + EVREventType_VREvent_SceneFocusChanged = 405, + EVREventType_VREvent_InputFocusChanged = 406, + EVREventType_VREvent_SceneApplicationSecondaryRenderingStarted = 407, + EVREventType_VREvent_HideRenderModels = 410, + EVREventType_VREvent_ShowRenderModels = 411, + EVREventType_VREvent_OverlayShown = 500, + EVREventType_VREvent_OverlayHidden = 501, + EVREventType_VREvent_DashboardActivated = 502, + EVREventType_VREvent_DashboardDeactivated = 503, + EVREventType_VREvent_DashboardThumbSelected = 504, + EVREventType_VREvent_DashboardRequested = 505, + EVREventType_VREvent_ResetDashboard = 506, + EVREventType_VREvent_RenderToast = 507, + EVREventType_VREvent_ImageLoaded = 508, + EVREventType_VREvent_ShowKeyboard = 509, + EVREventType_VREvent_HideKeyboard = 510, + EVREventType_VREvent_OverlayGamepadFocusGained = 511, + EVREventType_VREvent_OverlayGamepadFocusLost = 512, + EVREventType_VREvent_OverlaySharedTextureChanged = 513, + EVREventType_VREvent_DashboardGuideButtonDown = 514, + EVREventType_VREvent_DashboardGuideButtonUp = 515, + EVREventType_VREvent_ScreenshotTriggered = 516, + EVREventType_VREvent_ImageFailed = 517, + EVREventType_VREvent_RequestScreenshot = 520, + EVREventType_VREvent_ScreenshotTaken = 521, + EVREventType_VREvent_ScreenshotFailed = 522, + EVREventType_VREvent_SubmitScreenshotToDashboard = 523, + EVREventType_VREvent_Notification_Shown = 600, + EVREventType_VREvent_Notification_Hidden = 601, + EVREventType_VREvent_Notification_BeginInteraction = 602, + EVREventType_VREvent_Notification_Destroyed = 603, + EVREventType_VREvent_Quit = 700, + EVREventType_VREvent_ProcessQuit = 701, + EVREventType_VREvent_QuitAborted_UserPrompt = 702, + EVREventType_VREvent_QuitAcknowledged = 703, + EVREventType_VREvent_DriverRequestedQuit = 704, + EVREventType_VREvent_ChaperoneDataHasChanged = 800, + EVREventType_VREvent_ChaperoneUniverseHasChanged = 801, + EVREventType_VREvent_ChaperoneTempDataHasChanged = 802, + EVREventType_VREvent_ChaperoneSettingsHaveChanged = 803, + EVREventType_VREvent_SeatedZeroPoseReset = 804, + EVREventType_VREvent_AudioSettingsHaveChanged = 820, + EVREventType_VREvent_BackgroundSettingHasChanged = 850, + EVREventType_VREvent_CameraSettingsHaveChanged = 851, + EVREventType_VREvent_ReprojectionSettingHasChanged = 852, + EVREventType_VREvent_ModelSkinSettingsHaveChanged = 853, + EVREventType_VREvent_EnvironmentSettingsHaveChanged = 854, + EVREventType_VREvent_StatusUpdate = 900, + EVREventType_VREvent_MCImageUpdated = 1000, + EVREventType_VREvent_FirmwareUpdateStarted = 1100, + EVREventType_VREvent_FirmwareUpdateFinished = 1101, + EVREventType_VREvent_KeyboardClosed = 1200, + EVREventType_VREvent_KeyboardCharInput = 1201, + EVREventType_VREvent_KeyboardDone = 1202, + EVREventType_VREvent_ApplicationTransitionStarted = 1300, + EVREventType_VREvent_ApplicationTransitionAborted = 1301, + EVREventType_VREvent_ApplicationTransitionNewAppStarted = 1302, + EVREventType_VREvent_ApplicationListUpdated = 1303, + EVREventType_VREvent_Compositor_MirrorWindowShown = 1400, + EVREventType_VREvent_Compositor_MirrorWindowHidden = 1401, + EVREventType_VREvent_Compositor_ChaperoneBoundsShown = 1410, + EVREventType_VREvent_Compositor_ChaperoneBoundsHidden = 1411, + EVREventType_VREvent_TrackedCamera_StartVideoStream = 1500, + EVREventType_VREvent_TrackedCamera_StopVideoStream = 1501, + EVREventType_VREvent_TrackedCamera_PauseVideoStream = 1502, + EVREventType_VREvent_TrackedCamera_ResumeVideoStream = 1503, + EVREventType_VREvent_PerformanceTest_EnableCapture = 1600, + EVREventType_VREvent_PerformanceTest_DisableCapture = 1601, + EVREventType_VREvent_PerformanceTest_FidelityLevel = 1602, + EVREventType_VREvent_VendorSpecific_Reserved_Start = 10000, + EVREventType_VREvent_VendorSpecific_Reserved_End = 19999, +} EVREventType; + +typedef enum EDeviceActivityLevel +{ + EDeviceActivityLevel_k_EDeviceActivityLevel_Unknown = -1, + EDeviceActivityLevel_k_EDeviceActivityLevel_Idle = 0, + EDeviceActivityLevel_k_EDeviceActivityLevel_UserInteraction = 1, + EDeviceActivityLevel_k_EDeviceActivityLevel_UserInteraction_Timeout = 2, + EDeviceActivityLevel_k_EDeviceActivityLevel_Standby = 3, +} EDeviceActivityLevel; + +typedef enum EVRButtonId +{ + EVRButtonId_k_EButton_System = 0, + EVRButtonId_k_EButton_ApplicationMenu = 1, + EVRButtonId_k_EButton_Grip = 2, + EVRButtonId_k_EButton_DPad_Left = 3, + EVRButtonId_k_EButton_DPad_Up = 4, + EVRButtonId_k_EButton_DPad_Right = 5, + EVRButtonId_k_EButton_DPad_Down = 6, + EVRButtonId_k_EButton_A = 7, + EVRButtonId_k_EButton_Axis0 = 32, + EVRButtonId_k_EButton_Axis1 = 33, + EVRButtonId_k_EButton_Axis2 = 34, + EVRButtonId_k_EButton_Axis3 = 35, + EVRButtonId_k_EButton_Axis4 = 36, + EVRButtonId_k_EButton_SteamVR_Touchpad = 32, + EVRButtonId_k_EButton_SteamVR_Trigger = 33, + EVRButtonId_k_EButton_Dashboard_Back = 2, + EVRButtonId_k_EButton_Max = 64, +} EVRButtonId; + +typedef enum EVRMouseButton +{ + EVRMouseButton_VRMouseButton_Left = 1, + EVRMouseButton_VRMouseButton_Right = 2, + EVRMouseButton_VRMouseButton_Middle = 4, +} EVRMouseButton; + +typedef enum EVRControllerAxisType +{ + EVRControllerAxisType_k_eControllerAxis_None = 0, + EVRControllerAxisType_k_eControllerAxis_TrackPad = 1, + EVRControllerAxisType_k_eControllerAxis_Joystick = 2, + EVRControllerAxisType_k_eControllerAxis_Trigger = 3, +} EVRControllerAxisType; + +typedef enum EVRControllerEventOutputType +{ + EVRControllerEventOutputType_ControllerEventOutput_OSEvents = 0, + EVRControllerEventOutputType_ControllerEventOutput_VREvents = 1, +} EVRControllerEventOutputType; + +typedef enum ECollisionBoundsStyle +{ + ECollisionBoundsStyle_COLLISION_BOUNDS_STYLE_BEGINNER = 0, + ECollisionBoundsStyle_COLLISION_BOUNDS_STYLE_INTERMEDIATE = 1, + ECollisionBoundsStyle_COLLISION_BOUNDS_STYLE_SQUARES = 2, + ECollisionBoundsStyle_COLLISION_BOUNDS_STYLE_ADVANCED = 3, + ECollisionBoundsStyle_COLLISION_BOUNDS_STYLE_NONE = 4, + ECollisionBoundsStyle_COLLISION_BOUNDS_STYLE_COUNT = 5, +} ECollisionBoundsStyle; + +typedef enum EVROverlayError +{ + EVROverlayError_VROverlayError_None = 0, + EVROverlayError_VROverlayError_UnknownOverlay = 10, + EVROverlayError_VROverlayError_InvalidHandle = 11, + EVROverlayError_VROverlayError_PermissionDenied = 12, + EVROverlayError_VROverlayError_OverlayLimitExceeded = 13, + EVROverlayError_VROverlayError_WrongVisibilityType = 14, + EVROverlayError_VROverlayError_KeyTooLong = 15, + EVROverlayError_VROverlayError_NameTooLong = 16, + EVROverlayError_VROverlayError_KeyInUse = 17, + EVROverlayError_VROverlayError_WrongTransformType = 18, + EVROverlayError_VROverlayError_InvalidTrackedDevice = 19, + EVROverlayError_VROverlayError_InvalidParameter = 20, + EVROverlayError_VROverlayError_ThumbnailCantBeDestroyed = 21, + EVROverlayError_VROverlayError_ArrayTooSmall = 22, + EVROverlayError_VROverlayError_RequestFailed = 23, + EVROverlayError_VROverlayError_InvalidTexture = 24, + EVROverlayError_VROverlayError_UnableToLoadFile = 25, + EVROverlayError_VROVerlayError_KeyboardAlreadyInUse = 26, + EVROverlayError_VROverlayError_NoNeighbor = 27, +} EVROverlayError; + +typedef enum EVRApplicationType +{ + EVRApplicationType_VRApplication_Other = 0, + EVRApplicationType_VRApplication_Scene = 1, + EVRApplicationType_VRApplication_Overlay = 2, + EVRApplicationType_VRApplication_Background = 3, + EVRApplicationType_VRApplication_Utility = 4, + EVRApplicationType_VRApplication_VRMonitor = 5, +} EVRApplicationType; + +typedef enum EVRFirmwareError +{ + EVRFirmwareError_VRFirmwareError_None = 0, + EVRFirmwareError_VRFirmwareError_Success = 1, + EVRFirmwareError_VRFirmwareError_Fail = 2, +} EVRFirmwareError; + +typedef enum EVRNotificationError +{ + EVRNotificationError_VRNotificationError_OK = 0, + EVRNotificationError_VRNotificationError_InvalidNotificationId = 100, + EVRNotificationError_VRNotificationError_NotificationQueueFull = 101, + EVRNotificationError_VRNotificationError_InvalidOverlayHandle = 102, + EVRNotificationError_VRNotificationError_SystemWithUserValueAlreadyExists = 103, +} EVRNotificationError; + +typedef enum EVRInitError +{ + EVRInitError_VRInitError_None = 0, + EVRInitError_VRInitError_Unknown = 1, + EVRInitError_VRInitError_Init_InstallationNotFound = 100, + EVRInitError_VRInitError_Init_InstallationCorrupt = 101, + EVRInitError_VRInitError_Init_VRClientDLLNotFound = 102, + EVRInitError_VRInitError_Init_FileNotFound = 103, + EVRInitError_VRInitError_Init_FactoryNotFound = 104, + EVRInitError_VRInitError_Init_InterfaceNotFound = 105, + EVRInitError_VRInitError_Init_InvalidInterface = 106, + EVRInitError_VRInitError_Init_UserConfigDirectoryInvalid = 107, + EVRInitError_VRInitError_Init_HmdNotFound = 108, + EVRInitError_VRInitError_Init_NotInitialized = 109, + EVRInitError_VRInitError_Init_PathRegistryNotFound = 110, + EVRInitError_VRInitError_Init_NoConfigPath = 111, + EVRInitError_VRInitError_Init_NoLogPath = 112, + EVRInitError_VRInitError_Init_PathRegistryNotWritable = 113, + EVRInitError_VRInitError_Init_AppInfoInitFailed = 114, + EVRInitError_VRInitError_Init_Retry = 115, + EVRInitError_VRInitError_Init_InitCanceledByUser = 116, + EVRInitError_VRInitError_Init_AnotherAppLaunching = 117, + EVRInitError_VRInitError_Init_SettingsInitFailed = 118, + EVRInitError_VRInitError_Init_ShuttingDown = 119, + EVRInitError_VRInitError_Init_TooManyObjects = 120, + EVRInitError_VRInitError_Init_NoServerForBackgroundApp = 121, + EVRInitError_VRInitError_Init_NotSupportedWithCompositor = 122, + EVRInitError_VRInitError_Init_NotAvailableToUtilityApps = 123, + EVRInitError_VRInitError_Init_Internal = 124, + EVRInitError_VRInitError_Driver_Failed = 200, + EVRInitError_VRInitError_Driver_Unknown = 201, + EVRInitError_VRInitError_Driver_HmdUnknown = 202, + EVRInitError_VRInitError_Driver_NotLoaded = 203, + EVRInitError_VRInitError_Driver_RuntimeOutOfDate = 204, + EVRInitError_VRInitError_Driver_HmdInUse = 205, + EVRInitError_VRInitError_Driver_NotCalibrated = 206, + EVRInitError_VRInitError_Driver_CalibrationInvalid = 207, + EVRInitError_VRInitError_Driver_HmdDisplayNotFound = 208, + EVRInitError_VRInitError_IPC_ServerInitFailed = 300, + EVRInitError_VRInitError_IPC_ConnectFailed = 301, + EVRInitError_VRInitError_IPC_SharedStateInitFailed = 302, + EVRInitError_VRInitError_IPC_CompositorInitFailed = 303, + EVRInitError_VRInitError_IPC_MutexInitFailed = 304, + EVRInitError_VRInitError_IPC_Failed = 305, + EVRInitError_VRInitError_Compositor_Failed = 400, + EVRInitError_VRInitError_Compositor_D3D11HardwareRequired = 401, + EVRInitError_VRInitError_Compositor_FirmwareRequiresUpdate = 402, + EVRInitError_VRInitError_Compositor_OverlayInitFailed = 403, + EVRInitError_VRInitError_Compositor_ScreenshotsInitFailed = 404, + EVRInitError_VRInitError_VendorSpecific_UnableToConnectToOculusRuntime = 1000, + EVRInitError_VRInitError_VendorSpecific_HmdFound_CantOpenDevice = 1101, + EVRInitError_VRInitError_VendorSpecific_HmdFound_UnableToRequestConfigStart = 1102, + EVRInitError_VRInitError_VendorSpecific_HmdFound_NoStoredConfig = 1103, + EVRInitError_VRInitError_VendorSpecific_HmdFound_ConfigTooBig = 1104, + EVRInitError_VRInitError_VendorSpecific_HmdFound_ConfigTooSmall = 1105, + EVRInitError_VRInitError_VendorSpecific_HmdFound_UnableToInitZLib = 1106, + EVRInitError_VRInitError_VendorSpecific_HmdFound_CantReadFirmwareVersion = 1107, + EVRInitError_VRInitError_VendorSpecific_HmdFound_UnableToSendUserDataStart = 1108, + EVRInitError_VRInitError_VendorSpecific_HmdFound_UnableToGetUserDataStart = 1109, + EVRInitError_VRInitError_VendorSpecific_HmdFound_UnableToGetUserDataNext = 1110, + EVRInitError_VRInitError_VendorSpecific_HmdFound_UserDataAddressRange = 1111, + EVRInitError_VRInitError_VendorSpecific_HmdFound_UserDataError = 1112, + EVRInitError_VRInitError_VendorSpecific_HmdFound_ConfigFailedSanityCheck = 1113, + EVRInitError_VRInitError_Steam_SteamInstallationNotFound = 2000, +} EVRInitError; + +typedef enum EVRScreenshotType +{ + EVRScreenshotType_VRScreenshotType_None = 0, + EVRScreenshotType_VRScreenshotType_Mono = 1, + EVRScreenshotType_VRScreenshotType_Stereo = 2, + EVRScreenshotType_VRScreenshotType_Cubemap = 3, + EVRScreenshotType_VRScreenshotType_MonoPanorama = 4, + EVRScreenshotType_VRScreenshotType_StereoPanorama = 5, +} EVRScreenshotType; + +typedef enum EVRScreenshotPropertyFilenames +{ + EVRScreenshotPropertyFilenames_VRScreenshotPropertyFilenames_Preview = 0, + EVRScreenshotPropertyFilenames_VRScreenshotPropertyFilenames_VR = 1, +} EVRScreenshotPropertyFilenames; + +typedef enum EVRTrackedCameraError +{ + EVRTrackedCameraError_VRTrackedCameraError_None = 0, + EVRTrackedCameraError_VRTrackedCameraError_OperationFailed = 100, + EVRTrackedCameraError_VRTrackedCameraError_InvalidHandle = 101, + EVRTrackedCameraError_VRTrackedCameraError_InvalidFrameHeaderVersion = 102, + EVRTrackedCameraError_VRTrackedCameraError_OutOfHandles = 103, + EVRTrackedCameraError_VRTrackedCameraError_IPCFailure = 104, + EVRTrackedCameraError_VRTrackedCameraError_NotSupportedForThisDevice = 105, + EVRTrackedCameraError_VRTrackedCameraError_SharedMemoryFailure = 106, + EVRTrackedCameraError_VRTrackedCameraError_FrameBufferingFailure = 107, + EVRTrackedCameraError_VRTrackedCameraError_StreamSetupFailure = 108, + EVRTrackedCameraError_VRTrackedCameraError_InvalidGLTextureId = 109, + EVRTrackedCameraError_VRTrackedCameraError_InvalidSharedTextureHandle = 110, + EVRTrackedCameraError_VRTrackedCameraError_FailedToGetGLTextureId = 111, + EVRTrackedCameraError_VRTrackedCameraError_SharedTextureFailure = 112, + EVRTrackedCameraError_VRTrackedCameraError_NoFrameAvailable = 113, + EVRTrackedCameraError_VRTrackedCameraError_InvalidArgument = 114, + EVRTrackedCameraError_VRTrackedCameraError_InvalidFrameBufferSize = 115, +} EVRTrackedCameraError; + +typedef enum EVRTrackedCameraFrameType +{ + EVRTrackedCameraFrameType_VRTrackedCameraFrameType_Distorted = 0, + EVRTrackedCameraFrameType_VRTrackedCameraFrameType_Undistorted = 1, + EVRTrackedCameraFrameType_VRTrackedCameraFrameType_MaximumUndistorted = 2, + EVRTrackedCameraFrameType_MAX_CAMERA_FRAME_TYPES = 3, +} EVRTrackedCameraFrameType; + +typedef enum EVRApplicationError +{ + EVRApplicationError_VRApplicationError_None = 0, + EVRApplicationError_VRApplicationError_AppKeyAlreadyExists = 100, + EVRApplicationError_VRApplicationError_NoManifest = 101, + EVRApplicationError_VRApplicationError_NoApplication = 102, + EVRApplicationError_VRApplicationError_InvalidIndex = 103, + EVRApplicationError_VRApplicationError_UnknownApplication = 104, + EVRApplicationError_VRApplicationError_IPCFailed = 105, + EVRApplicationError_VRApplicationError_ApplicationAlreadyRunning = 106, + EVRApplicationError_VRApplicationError_InvalidManifest = 107, + EVRApplicationError_VRApplicationError_InvalidApplication = 108, + EVRApplicationError_VRApplicationError_LaunchFailed = 109, + EVRApplicationError_VRApplicationError_ApplicationAlreadyStarting = 110, + EVRApplicationError_VRApplicationError_LaunchInProgress = 111, + EVRApplicationError_VRApplicationError_OldApplicationQuitting = 112, + EVRApplicationError_VRApplicationError_TransitionAborted = 113, + EVRApplicationError_VRApplicationError_IsTemplate = 114, + EVRApplicationError_VRApplicationError_BufferTooSmall = 200, + EVRApplicationError_VRApplicationError_PropertyNotSet = 201, + EVRApplicationError_VRApplicationError_UnknownProperty = 202, + EVRApplicationError_VRApplicationError_InvalidParameter = 203, +} EVRApplicationError; + +typedef enum EVRApplicationProperty +{ + EVRApplicationProperty_VRApplicationProperty_Name_String = 0, + EVRApplicationProperty_VRApplicationProperty_LaunchType_String = 11, + EVRApplicationProperty_VRApplicationProperty_WorkingDirectory_String = 12, + EVRApplicationProperty_VRApplicationProperty_BinaryPath_String = 13, + EVRApplicationProperty_VRApplicationProperty_Arguments_String = 14, + EVRApplicationProperty_VRApplicationProperty_URL_String = 15, + EVRApplicationProperty_VRApplicationProperty_Description_String = 50, + EVRApplicationProperty_VRApplicationProperty_NewsURL_String = 51, + EVRApplicationProperty_VRApplicationProperty_ImagePath_String = 52, + EVRApplicationProperty_VRApplicationProperty_Source_String = 53, + EVRApplicationProperty_VRApplicationProperty_IsDashboardOverlay_Bool = 60, + EVRApplicationProperty_VRApplicationProperty_IsTemplate_Bool = 61, + EVRApplicationProperty_VRApplicationProperty_IsInstanced_Bool = 62, + EVRApplicationProperty_VRApplicationProperty_LastLaunchTime_Uint64 = 70, +} EVRApplicationProperty; + +typedef enum EVRApplicationTransitionState +{ + EVRApplicationTransitionState_VRApplicationTransition_None = 0, + EVRApplicationTransitionState_VRApplicationTransition_OldAppQuitSent = 10, + EVRApplicationTransitionState_VRApplicationTransition_WaitingForExternalLaunch = 11, + EVRApplicationTransitionState_VRApplicationTransition_NewAppLaunched = 20, +} EVRApplicationTransitionState; + +typedef enum ChaperoneCalibrationState +{ + ChaperoneCalibrationState_OK = 1, + ChaperoneCalibrationState_Warning = 100, + ChaperoneCalibrationState_Warning_BaseStationMayHaveMoved = 101, + ChaperoneCalibrationState_Warning_BaseStationRemoved = 102, + ChaperoneCalibrationState_Warning_SeatedBoundsInvalid = 103, + ChaperoneCalibrationState_Error = 200, + ChaperoneCalibrationState_Error_BaseStationUninitalized = 201, + ChaperoneCalibrationState_Error_BaseStationConflict = 202, + ChaperoneCalibrationState_Error_PlayAreaInvalid = 203, + ChaperoneCalibrationState_Error_CollisionBoundsInvalid = 204, +} ChaperoneCalibrationState; + +typedef enum EChaperoneConfigFile +{ + EChaperoneConfigFile_Live = 1, + EChaperoneConfigFile_Temp = 2, +} EChaperoneConfigFile; + +typedef enum EChaperoneImportFlags +{ + EChaperoneImportFlags_EChaperoneImport_BoundsOnly = 1, +} EChaperoneImportFlags; + +typedef enum EVRCompositorError +{ + EVRCompositorError_VRCompositorError_None = 0, + EVRCompositorError_VRCompositorError_RequestFailed = 1, + EVRCompositorError_VRCompositorError_IncompatibleVersion = 100, + EVRCompositorError_VRCompositorError_DoNotHaveFocus = 101, + EVRCompositorError_VRCompositorError_InvalidTexture = 102, + EVRCompositorError_VRCompositorError_IsNotSceneApplication = 103, + EVRCompositorError_VRCompositorError_TextureIsOnWrongDevice = 104, + EVRCompositorError_VRCompositorError_TextureUsesUnsupportedFormat = 105, + EVRCompositorError_VRCompositorError_SharedTexturesNotSupported = 106, + EVRCompositorError_VRCompositorError_IndexOutOfRange = 107, +} EVRCompositorError; + +typedef enum VROverlayInputMethod +{ + VROverlayInputMethod_None = 0, + VROverlayInputMethod_Mouse = 1, +} VROverlayInputMethod; + +typedef enum VROverlayTransformType +{ + VROverlayTransformType_VROverlayTransform_Absolute = 0, + VROverlayTransformType_VROverlayTransform_TrackedDeviceRelative = 1, + VROverlayTransformType_VROverlayTransform_SystemOverlay = 2, + VROverlayTransformType_VROverlayTransform_TrackedComponent = 3, +} VROverlayTransformType; + +typedef enum VROverlayFlags +{ + VROverlayFlags_None = 0, + VROverlayFlags_Curved = 1, + VROverlayFlags_RGSS4X = 2, + VROverlayFlags_NoDashboardTab = 3, + VROverlayFlags_AcceptsGamepadEvents = 4, + VROverlayFlags_ShowGamepadFocus = 5, + VROverlayFlags_SendVRScrollEvents = 6, + VROverlayFlags_SendVRTouchpadEvents = 7, + VROverlayFlags_ShowTouchPadScrollWheel = 8, + VROverlayFlags_TransferOwnershipToInternalProcess = 9, + VROverlayFlags_SideBySide_Parallel = 10, + VROverlayFlags_SideBySide_Crossed = 11, + VROverlayFlags_Panorama = 12, + VROverlayFlags_StereoPanorama = 13, +} VROverlayFlags; + +typedef enum EGamepadTextInputMode +{ + EGamepadTextInputMode_k_EGamepadTextInputModeNormal = 0, + EGamepadTextInputMode_k_EGamepadTextInputModePassword = 1, + EGamepadTextInputMode_k_EGamepadTextInputModeSubmit = 2, +} EGamepadTextInputMode; + +typedef enum EGamepadTextInputLineMode +{ + EGamepadTextInputLineMode_k_EGamepadTextInputLineModeSingleLine = 0, + EGamepadTextInputLineMode_k_EGamepadTextInputLineModeMultipleLines = 1, +} EGamepadTextInputLineMode; + +typedef enum EOverlayDirection +{ + EOverlayDirection_OverlayDirection_Up = 0, + EOverlayDirection_OverlayDirection_Down = 1, + EOverlayDirection_OverlayDirection_Left = 2, + EOverlayDirection_OverlayDirection_Right = 3, + EOverlayDirection_OverlayDirection_Count = 4, +} EOverlayDirection; + +typedef enum EVRRenderModelError +{ + EVRRenderModelError_VRRenderModelError_None = 0, + EVRRenderModelError_VRRenderModelError_Loading = 100, + EVRRenderModelError_VRRenderModelError_NotSupported = 200, + EVRRenderModelError_VRRenderModelError_InvalidArg = 300, + EVRRenderModelError_VRRenderModelError_InvalidModel = 301, + EVRRenderModelError_VRRenderModelError_NoShapes = 302, + EVRRenderModelError_VRRenderModelError_MultipleShapes = 303, + EVRRenderModelError_VRRenderModelError_TooManyVertices = 304, + EVRRenderModelError_VRRenderModelError_MultipleTextures = 305, + EVRRenderModelError_VRRenderModelError_BufferTooSmall = 306, + EVRRenderModelError_VRRenderModelError_NotEnoughNormals = 307, + EVRRenderModelError_VRRenderModelError_NotEnoughTexCoords = 308, + EVRRenderModelError_VRRenderModelError_InvalidTexture = 400, +} EVRRenderModelError; + +typedef enum EVRComponentProperty +{ + EVRComponentProperty_VRComponentProperty_IsStatic = 1, + EVRComponentProperty_VRComponentProperty_IsVisible = 2, + EVRComponentProperty_VRComponentProperty_IsTouched = 4, + EVRComponentProperty_VRComponentProperty_IsPressed = 8, + EVRComponentProperty_VRComponentProperty_IsScrolled = 16, +} EVRComponentProperty; + +typedef enum EVRNotificationType +{ + EVRNotificationType_Transient = 0, + EVRNotificationType_Persistent = 1, + EVRNotificationType_Transient_SystemWithUserValue = 2, +} EVRNotificationType; + +typedef enum EVRNotificationStyle +{ + EVRNotificationStyle_None = 0, + EVRNotificationStyle_Application = 100, + EVRNotificationStyle_Contact_Disabled = 200, + EVRNotificationStyle_Contact_Enabled = 201, + EVRNotificationStyle_Contact_Active = 202, +} EVRNotificationStyle; + +typedef enum EVRSettingsError +{ + EVRSettingsError_VRSettingsError_None = 0, + EVRSettingsError_VRSettingsError_IPCFailed = 1, + EVRSettingsError_VRSettingsError_WriteFailed = 2, + EVRSettingsError_VRSettingsError_ReadFailed = 3, +} EVRSettingsError; + +typedef enum EVRScreenshotError +{ + EVRScreenshotError_VRScreenshotError_None = 0, + EVRScreenshotError_VRScreenshotError_RequestFailed = 1, + EVRScreenshotError_VRScreenshotError_IncompatibleVersion = 100, + EVRScreenshotError_VRScreenshotError_NotFound = 101, + EVRScreenshotError_VRScreenshotError_BufferTooSmall = 102, + EVRScreenshotError_VRScreenshotError_ScreenshotAlreadyInProgress = 108, +} EVRScreenshotError; + + +// OpenVR typedefs + +typedef uint32_t TrackedDeviceIndex_t; +typedef uint32_t VRNotificationId; +typedef uint64_t VROverlayHandle_t; +typedef void * glSharedTextureHandle_t; +typedef int32_t glInt_t; +typedef uint32_t glUInt_t; +typedef uint32_t TrackedDeviceIndex_t; +typedef uint64_t VROverlayHandle_t; +typedef uint64_t TrackedCameraHandle_t; +typedef uint32_t ScreenshotHandle_t; +typedef uint32_t VRComponentProperties; +typedef int32_t TextureID_t; +typedef uint32_t VRNotificationId; +typedef EVRInitError HmdError; +typedef EVREye Hmd_Eye; +typedef EGraphicsAPIConvention GraphicsAPIConvention; +typedef EColorSpace ColorSpace; +typedef ETrackingResult HmdTrackingResult; +typedef ETrackedDeviceClass TrackedDeviceClass; +typedef ETrackingUniverseOrigin TrackingUniverseOrigin; +typedef ETrackedDeviceProperty TrackedDeviceProperty; +typedef ETrackedPropertyError TrackedPropertyError; +typedef EVRSubmitFlags VRSubmitFlags_t; +typedef EVRState VRState_t; +typedef ECollisionBoundsStyle CollisionBoundsStyle_t; +typedef EVROverlayError VROverlayError; +typedef EVRFirmwareError VRFirmwareError; +typedef EVRCompositorError VRCompositorError; +typedef EVRScreenshotError VRScreenshotsError; + +// OpenVR Structs + +typedef struct HmdMatrix34_t +{ + float m[3][4]; //float[3][4] +} HmdMatrix34_t; + +typedef struct HmdMatrix44_t +{ + float m[4][4]; //float[4][4] +} HmdMatrix44_t; + +typedef struct HmdVector3_t +{ + float v[3]; //float[3] +} HmdVector3_t; + +typedef struct HmdVector4_t +{ + float v[4]; //float[4] +} HmdVector4_t; + +typedef struct HmdVector3d_t +{ + double v[3]; //double[3] +} HmdVector3d_t; + +typedef struct HmdVector2_t +{ + float v[2]; //float[2] +} HmdVector2_t; + +typedef struct HmdQuaternion_t +{ + double w; + double x; + double y; + double z; +} HmdQuaternion_t; + +typedef struct HmdColor_t +{ + float r; + float g; + float b; + float a; +} HmdColor_t; + +typedef struct HmdQuad_t +{ + struct HmdVector3_t vCorners[4]; //struct vr::HmdVector3_t[4] +} HmdQuad_t; + +typedef struct HmdRect2_t +{ + struct HmdVector2_t vTopLeft; + struct HmdVector2_t vBottomRight; +} HmdRect2_t; + +typedef struct DistortionCoordinates_t +{ + float rfRed[2]; //float[2] + float rfGreen[2]; //float[2] + float rfBlue[2]; //float[2] +} DistortionCoordinates_t; + +typedef struct Texture_t +{ + void * handle; // void * + enum EGraphicsAPIConvention eType; + enum EColorSpace eColorSpace; +} Texture_t; + +typedef struct TrackedDevicePose_t +{ + struct HmdMatrix34_t mDeviceToAbsoluteTracking; + struct HmdVector3_t vVelocity; + struct HmdVector3_t vAngularVelocity; + enum ETrackingResult eTrackingResult; + bool bPoseIsValid; + bool bDeviceIsConnected; +} TrackedDevicePose_t; + +typedef struct VRTextureBounds_t +{ + float uMin; + float vMin; + float uMax; + float vMax; +} VRTextureBounds_t; + +typedef struct VREvent_Controller_t +{ + uint32_t button; +} VREvent_Controller_t; + +typedef struct VREvent_Mouse_t +{ + float x; + float y; + uint32_t button; +} VREvent_Mouse_t; + +typedef struct VREvent_Scroll_t +{ + float xdelta; + float ydelta; + uint32_t repeatCount; +} VREvent_Scroll_t; + +typedef struct VREvent_TouchPadMove_t +{ + bool bFingerDown; + float flSecondsFingerDown; + float fValueXFirst; + float fValueYFirst; + float fValueXRaw; + float fValueYRaw; +} VREvent_TouchPadMove_t; + +typedef struct VREvent_Notification_t +{ + uint64_t ulUserValue; + uint32_t notificationId; +} VREvent_Notification_t; + +typedef struct VREvent_Process_t +{ + uint32_t pid; + uint32_t oldPid; + bool bForced; +} VREvent_Process_t; + +typedef struct VREvent_Overlay_t +{ + uint64_t overlayHandle; +} VREvent_Overlay_t; + +typedef struct VREvent_Status_t +{ + uint32_t statusState; +} VREvent_Status_t; + +typedef struct VREvent_Keyboard_t +{ + char * cNewInput[8]; //char[8] + uint64_t uUserValue; +} VREvent_Keyboard_t; + +typedef struct VREvent_Ipd_t +{ + float ipdMeters; +} VREvent_Ipd_t; + +typedef struct VREvent_Chaperone_t +{ + uint64_t m_nPreviousUniverse; + uint64_t m_nCurrentUniverse; +} VREvent_Chaperone_t; + +typedef struct VREvent_Reserved_t +{ + uint64_t reserved0; + uint64_t reserved1; +} VREvent_Reserved_t; + +typedef struct VREvent_PerformanceTest_t +{ + uint32_t m_nFidelityLevel; +} VREvent_PerformanceTest_t; + +typedef struct VREvent_SeatedZeroPoseReset_t +{ + bool bResetBySystemMenu; +} VREvent_SeatedZeroPoseReset_t; + +typedef struct VREvent_Screenshot_t +{ + uint32_t handle; + uint32_t type; +} VREvent_Screenshot_t; + +typedef struct HiddenAreaMesh_t +{ + struct HmdVector2_t * pVertexData; // const struct vr::HmdVector2_t * + uint32_t unTriangleCount; +} HiddenAreaMesh_t; + +typedef struct VRControllerAxis_t +{ + float x; + float y; +} VRControllerAxis_t; + +typedef struct VRControllerState_t +{ + uint32_t unPacketNum; + uint64_t ulButtonPressed; + uint64_t ulButtonTouched; + struct VRControllerAxis_t rAxis[5]; //struct vr::VRControllerAxis_t[5] +} VRControllerState_t; + +typedef struct Compositor_OverlaySettings +{ + uint32_t size; + bool curved; + bool antialias; + float scale; + float distance; + float alpha; + float uOffset; + float vOffset; + float uScale; + float vScale; + float gridDivs; + float gridWidth; + float gridScale; + struct HmdMatrix44_t transform; +} Compositor_OverlaySettings; + +typedef struct CameraVideoStreamFrameHeader_t +{ + enum EVRTrackedCameraFrameType eFrameType; + uint32_t nWidth; + uint32_t nHeight; + uint32_t nBytesPerPixel; + uint32_t nFrameSequence; + struct TrackedDevicePose_t standingTrackedDevicePose; +} CameraVideoStreamFrameHeader_t; + +typedef struct AppOverrideKeys_t +{ + char * pchKey; // const char * + char * pchValue; // const char * +} AppOverrideKeys_t; + +typedef struct Compositor_FrameTiming +{ + uint32_t m_nSize; + uint32_t m_nFrameIndex; + uint32_t m_nNumFramePresents; + uint32_t m_nNumDroppedFrames; + double m_flSystemTimeInSeconds; + float m_flSceneRenderGpuMs; + float m_flTotalRenderGpuMs; + float m_flCompositorRenderGpuMs; + float m_flCompositorRenderCpuMs; + float m_flCompositorIdleCpuMs; + float m_flClientFrameIntervalMs; + float m_flPresentCallCpuMs; + float m_flWaitForPresentCpuMs; + float m_flSubmitFrameMs; + float m_flWaitGetPosesCalledMs; + float m_flNewPosesReadyMs; + float m_flNewFrameReadyMs; + float m_flCompositorUpdateStartMs; + float m_flCompositorUpdateEndMs; + float m_flCompositorRenderStartMs; + TrackedDevicePose_t m_HmdPose; + int32_t m_nFidelityLevel; + uint32_t m_nReprojectionFlags; +} Compositor_FrameTiming; + +typedef struct Compositor_CumulativeStats +{ + uint32_t m_nPid; + uint32_t m_nNumFramePresents; + uint32_t m_nNumDroppedFrames; + uint32_t m_nNumReprojectedFrames; + uint32_t m_nNumFramePresentsOnStartup; + uint32_t m_nNumDroppedFramesOnStartup; + uint32_t m_nNumReprojectedFramesOnStartup; + uint32_t m_nNumLoading; + uint32_t m_nNumFramePresentsLoading; + uint32_t m_nNumDroppedFramesLoading; + uint32_t m_nNumReprojectedFramesLoading; + uint32_t m_nNumTimedOut; + uint32_t m_nNumFramePresentsTimedOut; + uint32_t m_nNumDroppedFramesTimedOut; + uint32_t m_nNumReprojectedFramesTimedOut; +} Compositor_CumulativeStats; + +typedef struct VROverlayIntersectionParams_t +{ + struct HmdVector3_t vSource; + struct HmdVector3_t vDirection; + enum ETrackingUniverseOrigin eOrigin; +} VROverlayIntersectionParams_t; + +typedef struct VROverlayIntersectionResults_t +{ + struct HmdVector3_t vPoint; + struct HmdVector3_t vNormal; + struct HmdVector2_t vUVs; + float fDistance; +} VROverlayIntersectionResults_t; + +typedef struct RenderModel_ComponentState_t +{ + struct HmdMatrix34_t mTrackingToComponentRenderModel; + struct HmdMatrix34_t mTrackingToComponentLocal; + VRComponentProperties uProperties; +} RenderModel_ComponentState_t; + +typedef struct RenderModel_Vertex_t +{ + struct HmdVector3_t vPosition; + struct HmdVector3_t vNormal; + float rfTextureCoord[2]; //float[2] +} RenderModel_Vertex_t; + +typedef struct RenderModel_TextureMap_t +{ + uint16_t unWidth; + uint16_t unHeight; + uint8_t * rubTextureMapData; // const uint8_t * +} RenderModel_TextureMap_t; + +typedef struct RenderModel_t +{ + struct RenderModel_Vertex_t * rVertexData; // const struct vr::RenderModel_Vertex_t * + uint32_t unVertexCount; + uint16_t * rIndexData; // const uint16_t * + uint32_t unTriangleCount; + TextureID_t diffuseTextureId; +} RenderModel_t; + +typedef struct RenderModel_ControllerMode_State_t +{ + bool bScrollWheelVisible; +} RenderModel_ControllerMode_State_t; + +typedef struct NotificationBitmap_t +{ + void * m_pImageData; // void * + int32_t m_nWidth; + int32_t m_nHeight; + int32_t m_nBytesPerPixel; +} NotificationBitmap_t; + +typedef struct COpenVRContext +{ + intptr_t m_pVRSystem; // class vr::IVRSystem * + intptr_t m_pVRChaperone; // class vr::IVRChaperone * + intptr_t m_pVRChaperoneSetup; // class vr::IVRChaperoneSetup * + intptr_t m_pVRCompositor; // class vr::IVRCompositor * + intptr_t m_pVROverlay; // class vr::IVROverlay * + intptr_t m_pVRRenderModels; // class vr::IVRRenderModels * + intptr_t m_pVRExtendedDisplay; // class vr::IVRExtendedDisplay * + intptr_t m_pVRSettings; // class vr::IVRSettings * + intptr_t m_pVRApplications; // class vr::IVRApplications * + intptr_t m_pVRTrackedCamera; // class vr::IVRTrackedCamera * + intptr_t m_pVRScreenshots; // class vr::IVRScreenshots * +} COpenVRContext; + + +typedef union +{ + VREvent_Reserved_t reserved; + VREvent_Controller_t controller; + VREvent_Mouse_t mouse; + VREvent_Scroll_t scroll; + VREvent_Process_t process; + VREvent_Notification_t notification; + VREvent_Overlay_t overlay; + VREvent_Status_t status; + VREvent_Keyboard_t keyboard; + VREvent_Ipd_t ipd; + VREvent_Chaperone_t chaperone; + VREvent_PerformanceTest_t performanceTest; + VREvent_TouchPadMove_t touchPadMove; + VREvent_SeatedZeroPoseReset_t seatedZeroPoseReset; +} VREvent_Data_t; + +/** An event posted by the server to all running applications */ +struct VREvent_t +{ + uint32_t eventType; // EVREventType enum + TrackedDeviceIndex_t trackedDeviceIndex; + float eventAgeSeconds; + // event data must be the end of the struct as its size is variable + VREvent_Data_t data; +}; + + +// OpenVR Function Pointer Tables + +struct VR_IVRSystem_FnTable +{ + void (OPENVR_FNTABLE_CALLTYPE *GetRecommendedRenderTargetSize)(uint32_t * pnWidth, uint32_t * pnHeight); + struct HmdMatrix44_t (OPENVR_FNTABLE_CALLTYPE *GetProjectionMatrix)(EVREye eEye, float fNearZ, float fFarZ, EGraphicsAPIConvention eProjType); + void (OPENVR_FNTABLE_CALLTYPE *GetProjectionRaw)(EVREye eEye, float * pfLeft, float * pfRight, float * pfTop, float * pfBottom); + struct DistortionCoordinates_t (OPENVR_FNTABLE_CALLTYPE *ComputeDistortion)(EVREye eEye, float fU, float fV); + struct HmdMatrix34_t (OPENVR_FNTABLE_CALLTYPE *GetEyeToHeadTransform)(EVREye eEye); + bool (OPENVR_FNTABLE_CALLTYPE *GetTimeSinceLastVsync)(float * pfSecondsSinceLastVsync, uint64_t * pulFrameCounter); + int32_t (OPENVR_FNTABLE_CALLTYPE *GetD3D9AdapterIndex)(); + void (OPENVR_FNTABLE_CALLTYPE *GetDXGIOutputInfo)(int32_t * pnAdapterIndex); + bool (OPENVR_FNTABLE_CALLTYPE *IsDisplayOnDesktop)(); + bool (OPENVR_FNTABLE_CALLTYPE *SetDisplayVisibility)(bool bIsVisibleOnDesktop); + void (OPENVR_FNTABLE_CALLTYPE *GetDeviceToAbsoluteTrackingPose)(ETrackingUniverseOrigin eOrigin, float fPredictedSecondsToPhotonsFromNow, struct TrackedDevicePose_t * pTrackedDevicePoseArray, uint32_t unTrackedDevicePoseArrayCount); + void (OPENVR_FNTABLE_CALLTYPE *ResetSeatedZeroPose)(); + struct HmdMatrix34_t (OPENVR_FNTABLE_CALLTYPE *GetSeatedZeroPoseToStandingAbsoluteTrackingPose)(); + struct HmdMatrix34_t (OPENVR_FNTABLE_CALLTYPE *GetRawZeroPoseToStandingAbsoluteTrackingPose)(); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetSortedTrackedDeviceIndicesOfClass)(ETrackedDeviceClass eTrackedDeviceClass, TrackedDeviceIndex_t * punTrackedDeviceIndexArray, uint32_t unTrackedDeviceIndexArrayCount, TrackedDeviceIndex_t unRelativeToTrackedDeviceIndex); + EDeviceActivityLevel (OPENVR_FNTABLE_CALLTYPE *GetTrackedDeviceActivityLevel)(TrackedDeviceIndex_t unDeviceId); + void (OPENVR_FNTABLE_CALLTYPE *ApplyTransform)(struct TrackedDevicePose_t * pOutputPose, struct TrackedDevicePose_t * pTrackedDevicePose, struct HmdMatrix34_t * pTransform); + TrackedDeviceIndex_t (OPENVR_FNTABLE_CALLTYPE *GetTrackedDeviceIndexForControllerRole)(ETrackedControllerRole unDeviceType); + ETrackedControllerRole (OPENVR_FNTABLE_CALLTYPE *GetControllerRoleForTrackedDeviceIndex)(TrackedDeviceIndex_t unDeviceIndex); + ETrackedDeviceClass (OPENVR_FNTABLE_CALLTYPE *GetTrackedDeviceClass)(TrackedDeviceIndex_t unDeviceIndex); + bool (OPENVR_FNTABLE_CALLTYPE *IsTrackedDeviceConnected)(TrackedDeviceIndex_t unDeviceIndex); + bool (OPENVR_FNTABLE_CALLTYPE *GetBoolTrackedDeviceProperty)(TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError * pError); + float (OPENVR_FNTABLE_CALLTYPE *GetFloatTrackedDeviceProperty)(TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError * pError); + int32_t (OPENVR_FNTABLE_CALLTYPE *GetInt32TrackedDeviceProperty)(TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError * pError); + uint64_t (OPENVR_FNTABLE_CALLTYPE *GetUint64TrackedDeviceProperty)(TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError * pError); + struct HmdMatrix34_t (OPENVR_FNTABLE_CALLTYPE *GetMatrix34TrackedDeviceProperty)(TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError * pError); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetStringTrackedDeviceProperty)(TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, char * pchValue, uint32_t unBufferSize, ETrackedPropertyError * pError); + char * (OPENVR_FNTABLE_CALLTYPE *GetPropErrorNameFromEnum)(ETrackedPropertyError error); + bool (OPENVR_FNTABLE_CALLTYPE *PollNextEvent)(struct VREvent_t * pEvent, uint32_t uncbVREvent); + bool (OPENVR_FNTABLE_CALLTYPE *PollNextEventWithPose)(ETrackingUniverseOrigin eOrigin, struct VREvent_t * pEvent, uint32_t uncbVREvent, TrackedDevicePose_t * pTrackedDevicePose); + char * (OPENVR_FNTABLE_CALLTYPE *GetEventTypeNameFromEnum)(EVREventType eType); + struct HiddenAreaMesh_t (OPENVR_FNTABLE_CALLTYPE *GetHiddenAreaMesh)(EVREye eEye); + bool (OPENVR_FNTABLE_CALLTYPE *GetControllerState)(TrackedDeviceIndex_t unControllerDeviceIndex, VRControllerState_t * pControllerState); + bool (OPENVR_FNTABLE_CALLTYPE *GetControllerStateWithPose)(ETrackingUniverseOrigin eOrigin, TrackedDeviceIndex_t unControllerDeviceIndex, VRControllerState_t * pControllerState, struct TrackedDevicePose_t * pTrackedDevicePose); + void (OPENVR_FNTABLE_CALLTYPE *TriggerHapticPulse)(TrackedDeviceIndex_t unControllerDeviceIndex, uint32_t unAxisId, unsigned short usDurationMicroSec); + char * (OPENVR_FNTABLE_CALLTYPE *GetButtonIdNameFromEnum)(EVRButtonId eButtonId); + char * (OPENVR_FNTABLE_CALLTYPE *GetControllerAxisTypeNameFromEnum)(EVRControllerAxisType eAxisType); + bool (OPENVR_FNTABLE_CALLTYPE *CaptureInputFocus)(); + void (OPENVR_FNTABLE_CALLTYPE *ReleaseInputFocus)(); + bool (OPENVR_FNTABLE_CALLTYPE *IsInputFocusCapturedByAnotherProcess)(); + uint32_t (OPENVR_FNTABLE_CALLTYPE *DriverDebugRequest)(TrackedDeviceIndex_t unDeviceIndex, char * pchRequest, char * pchResponseBuffer, uint32_t unResponseBufferSize); + EVRFirmwareError (OPENVR_FNTABLE_CALLTYPE *PerformFirmwareUpdate)(TrackedDeviceIndex_t unDeviceIndex); + void (OPENVR_FNTABLE_CALLTYPE *AcknowledgeQuit_Exiting)(); + void (OPENVR_FNTABLE_CALLTYPE *AcknowledgeQuit_UserPrompt)(); +}; + +struct VR_IVRExtendedDisplay_FnTable +{ + void (OPENVR_FNTABLE_CALLTYPE *GetWindowBounds)(int32_t * pnX, int32_t * pnY, uint32_t * pnWidth, uint32_t * pnHeight); + void (OPENVR_FNTABLE_CALLTYPE *GetEyeOutputViewport)(EVREye eEye, uint32_t * pnX, uint32_t * pnY, uint32_t * pnWidth, uint32_t * pnHeight); + void (OPENVR_FNTABLE_CALLTYPE *GetDXGIOutputInfo)(int32_t * pnAdapterIndex, int32_t * pnAdapterOutputIndex); +}; + +struct VR_IVRTrackedCamera_FnTable +{ + char * (OPENVR_FNTABLE_CALLTYPE *GetCameraErrorNameFromEnum)(EVRTrackedCameraError eCameraError); + EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *HasCamera)(TrackedDeviceIndex_t nDeviceIndex, bool * pHasCamera); + EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *GetCameraFrameSize)(TrackedDeviceIndex_t nDeviceIndex, EVRTrackedCameraFrameType eFrameType, uint32_t * pnWidth, uint32_t * pnHeight, uint32_t * pnFrameBufferSize); + EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *GetCameraIntrinisics)(TrackedDeviceIndex_t nDeviceIndex, EVRTrackedCameraFrameType eFrameType, HmdVector2_t * pFocalLength, HmdVector2_t * pCenter); + EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *GetCameraProjection)(TrackedDeviceIndex_t nDeviceIndex, EVRTrackedCameraFrameType eFrameType, float flZNear, float flZFar, HmdMatrix44_t * pProjection); + EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *AcquireVideoStreamingService)(TrackedDeviceIndex_t nDeviceIndex, TrackedCameraHandle_t * pHandle); + EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *ReleaseVideoStreamingService)(TrackedCameraHandle_t hTrackedCamera); + EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *GetVideoStreamFrameBuffer)(TrackedCameraHandle_t hTrackedCamera, EVRTrackedCameraFrameType eFrameType, void * pFrameBuffer, uint32_t nFrameBufferSize, CameraVideoStreamFrameHeader_t * pFrameHeader, uint32_t nFrameHeaderSize); +}; + +struct VR_IVRApplications_FnTable +{ + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *AddApplicationManifest)(char * pchApplicationManifestFullPath, bool bTemporary); + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *RemoveApplicationManifest)(char * pchApplicationManifestFullPath); + bool (OPENVR_FNTABLE_CALLTYPE *IsApplicationInstalled)(char * pchAppKey); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetApplicationCount)(); + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *GetApplicationKeyByIndex)(uint32_t unApplicationIndex, char * pchAppKeyBuffer, uint32_t unAppKeyBufferLen); + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *GetApplicationKeyByProcessId)(uint32_t unProcessId, char * pchAppKeyBuffer, uint32_t unAppKeyBufferLen); + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *LaunchApplication)(char * pchAppKey); + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *LaunchTemplateApplication)(char * pchTemplateAppKey, char * pchNewAppKey, struct AppOverrideKeys_t * pKeys, uint32_t unKeys); + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *LaunchDashboardOverlay)(char * pchAppKey); + bool (OPENVR_FNTABLE_CALLTYPE *CancelApplicationLaunch)(char * pchAppKey); + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *IdentifyApplication)(uint32_t unProcessId, char * pchAppKey); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetApplicationProcessId)(char * pchAppKey); + char * (OPENVR_FNTABLE_CALLTYPE *GetApplicationsErrorNameFromEnum)(EVRApplicationError error); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetApplicationPropertyString)(char * pchAppKey, EVRApplicationProperty eProperty, char * pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError * peError); + bool (OPENVR_FNTABLE_CALLTYPE *GetApplicationPropertyBool)(char * pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError * peError); + uint64_t (OPENVR_FNTABLE_CALLTYPE *GetApplicationPropertyUint64)(char * pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError * peError); + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *SetApplicationAutoLaunch)(char * pchAppKey, bool bAutoLaunch); + bool (OPENVR_FNTABLE_CALLTYPE *GetApplicationAutoLaunch)(char * pchAppKey); + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *GetStartingApplication)(char * pchAppKeyBuffer, uint32_t unAppKeyBufferLen); + EVRApplicationTransitionState (OPENVR_FNTABLE_CALLTYPE *GetTransitionState)(); + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *PerformApplicationPrelaunchCheck)(char * pchAppKey); + char * (OPENVR_FNTABLE_CALLTYPE *GetApplicationsTransitionStateNameFromEnum)(EVRApplicationTransitionState state); + bool (OPENVR_FNTABLE_CALLTYPE *IsQuitUserPromptRequested)(); + EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *LaunchInternalProcess)(char * pchBinaryPath, char * pchArguments, char * pchWorkingDirectory); +}; + +struct VR_IVRChaperone_FnTable +{ + ChaperoneCalibrationState (OPENVR_FNTABLE_CALLTYPE *GetCalibrationState)(); + bool (OPENVR_FNTABLE_CALLTYPE *GetPlayAreaSize)(float * pSizeX, float * pSizeZ); + bool (OPENVR_FNTABLE_CALLTYPE *GetPlayAreaRect)(struct HmdQuad_t * rect); + void (OPENVR_FNTABLE_CALLTYPE *ReloadInfo)(); + void (OPENVR_FNTABLE_CALLTYPE *SetSceneColor)(struct HmdColor_t color); + void (OPENVR_FNTABLE_CALLTYPE *GetBoundsColor)(struct HmdColor_t * pOutputColorArray, int nNumOutputColors, float flCollisionBoundsFadeDistance, struct HmdColor_t * pOutputCameraColor); + bool (OPENVR_FNTABLE_CALLTYPE *AreBoundsVisible)(); + void (OPENVR_FNTABLE_CALLTYPE *ForceBoundsVisible)(bool bForce); +}; + +struct VR_IVRChaperoneSetup_FnTable +{ + bool (OPENVR_FNTABLE_CALLTYPE *CommitWorkingCopy)(EChaperoneConfigFile configFile); + void (OPENVR_FNTABLE_CALLTYPE *RevertWorkingCopy)(); + bool (OPENVR_FNTABLE_CALLTYPE *GetWorkingPlayAreaSize)(float * pSizeX, float * pSizeZ); + bool (OPENVR_FNTABLE_CALLTYPE *GetWorkingPlayAreaRect)(struct HmdQuad_t * rect); + bool (OPENVR_FNTABLE_CALLTYPE *GetWorkingCollisionBoundsInfo)(struct HmdQuad_t * pQuadsBuffer, uint32_t * punQuadsCount); + bool (OPENVR_FNTABLE_CALLTYPE *GetLiveCollisionBoundsInfo)(struct HmdQuad_t * pQuadsBuffer, uint32_t * punQuadsCount); + bool (OPENVR_FNTABLE_CALLTYPE *GetWorkingSeatedZeroPoseToRawTrackingPose)(struct HmdMatrix34_t * pmatSeatedZeroPoseToRawTrackingPose); + bool (OPENVR_FNTABLE_CALLTYPE *GetWorkingStandingZeroPoseToRawTrackingPose)(struct HmdMatrix34_t * pmatStandingZeroPoseToRawTrackingPose); + void (OPENVR_FNTABLE_CALLTYPE *SetWorkingPlayAreaSize)(float sizeX, float sizeZ); + void (OPENVR_FNTABLE_CALLTYPE *SetWorkingCollisionBoundsInfo)(struct HmdQuad_t * pQuadsBuffer, uint32_t unQuadsCount); + void (OPENVR_FNTABLE_CALLTYPE *SetWorkingSeatedZeroPoseToRawTrackingPose)(struct HmdMatrix34_t * pMatSeatedZeroPoseToRawTrackingPose); + void (OPENVR_FNTABLE_CALLTYPE *SetWorkingStandingZeroPoseToRawTrackingPose)(struct HmdMatrix34_t * pMatStandingZeroPoseToRawTrackingPose); + void (OPENVR_FNTABLE_CALLTYPE *ReloadFromDisk)(EChaperoneConfigFile configFile); + bool (OPENVR_FNTABLE_CALLTYPE *GetLiveSeatedZeroPoseToRawTrackingPose)(struct HmdMatrix34_t * pmatSeatedZeroPoseToRawTrackingPose); + void (OPENVR_FNTABLE_CALLTYPE *SetWorkingCollisionBoundsTagsInfo)(uint8_t * pTagsBuffer, uint32_t unTagCount); + bool (OPENVR_FNTABLE_CALLTYPE *GetLiveCollisionBoundsTagsInfo)(uint8_t * pTagsBuffer, uint32_t * punTagCount); + bool (OPENVR_FNTABLE_CALLTYPE *SetWorkingPhysicalBoundsInfo)(struct HmdQuad_t * pQuadsBuffer, uint32_t unQuadsCount); + bool (OPENVR_FNTABLE_CALLTYPE *GetLivePhysicalBoundsInfo)(struct HmdQuad_t * pQuadsBuffer, uint32_t * punQuadsCount); + bool (OPENVR_FNTABLE_CALLTYPE *ExportLiveToBuffer)(char * pBuffer, uint32_t * pnBufferLength); + bool (OPENVR_FNTABLE_CALLTYPE *ImportFromBufferToWorking)(char * pBuffer, uint32_t nImportFlags); +}; + +struct VR_IVRCompositor_FnTable +{ + void (OPENVR_FNTABLE_CALLTYPE *SetTrackingSpace)(ETrackingUniverseOrigin eOrigin); + ETrackingUniverseOrigin (OPENVR_FNTABLE_CALLTYPE *GetTrackingSpace)(); + EVRCompositorError (OPENVR_FNTABLE_CALLTYPE *WaitGetPoses)(struct TrackedDevicePose_t * pRenderPoseArray, uint32_t unRenderPoseArrayCount, struct TrackedDevicePose_t * pGamePoseArray, uint32_t unGamePoseArrayCount); + EVRCompositorError (OPENVR_FNTABLE_CALLTYPE *GetLastPoses)(struct TrackedDevicePose_t * pRenderPoseArray, uint32_t unRenderPoseArrayCount, struct TrackedDevicePose_t * pGamePoseArray, uint32_t unGamePoseArrayCount); + EVRCompositorError (OPENVR_FNTABLE_CALLTYPE *GetLastPoseForTrackedDeviceIndex)(TrackedDeviceIndex_t unDeviceIndex, struct TrackedDevicePose_t * pOutputPose, struct TrackedDevicePose_t * pOutputGamePose); + EVRCompositorError (OPENVR_FNTABLE_CALLTYPE *Submit)(EVREye eEye, struct Texture_t * pTexture, struct VRTextureBounds_t * pBounds, EVRSubmitFlags nSubmitFlags); + void (OPENVR_FNTABLE_CALLTYPE *ClearLastSubmittedFrame)(); + void (OPENVR_FNTABLE_CALLTYPE *PostPresentHandoff)(); + bool (OPENVR_FNTABLE_CALLTYPE *GetFrameTiming)(struct Compositor_FrameTiming * pTiming, uint32_t unFramesAgo); + float (OPENVR_FNTABLE_CALLTYPE *GetFrameTimeRemaining)(); + void (OPENVR_FNTABLE_CALLTYPE *GetCumulativeStats)(struct Compositor_CumulativeStats * pStats, uint32_t nStatsSizeInBytes); + void (OPENVR_FNTABLE_CALLTYPE *FadeToColor)(float fSeconds, float fRed, float fGreen, float fBlue, float fAlpha, bool bBackground); + void (OPENVR_FNTABLE_CALLTYPE *FadeGrid)(float fSeconds, bool bFadeIn); + EVRCompositorError (OPENVR_FNTABLE_CALLTYPE *SetSkyboxOverride)(struct Texture_t * pTextures, uint32_t unTextureCount); + void (OPENVR_FNTABLE_CALLTYPE *ClearSkyboxOverride)(); + void (OPENVR_FNTABLE_CALLTYPE *CompositorBringToFront)(); + void (OPENVR_FNTABLE_CALLTYPE *CompositorGoToBack)(); + void (OPENVR_FNTABLE_CALLTYPE *CompositorQuit)(); + bool (OPENVR_FNTABLE_CALLTYPE *IsFullscreen)(); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetCurrentSceneFocusProcess)(); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetLastFrameRenderer)(); + bool (OPENVR_FNTABLE_CALLTYPE *CanRenderScene)(); + void (OPENVR_FNTABLE_CALLTYPE *ShowMirrorWindow)(); + void (OPENVR_FNTABLE_CALLTYPE *HideMirrorWindow)(); + bool (OPENVR_FNTABLE_CALLTYPE *IsMirrorWindowVisible)(); + void (OPENVR_FNTABLE_CALLTYPE *CompositorDumpImages)(); + bool (OPENVR_FNTABLE_CALLTYPE *ShouldAppRenderWithLowResources)(); + void (OPENVR_FNTABLE_CALLTYPE *ForceInterleavedReprojectionOn)(bool bOverride); + void (OPENVR_FNTABLE_CALLTYPE *ForceReconnectProcess)(); + void (OPENVR_FNTABLE_CALLTYPE *SuspendRendering)(bool bSuspend); + EVRCompositorError (OPENVR_FNTABLE_CALLTYPE *RequestScreenshot)(EVRScreenshotType type, char * pchDestinationFileName, char * pchVRDestinationFileName); + EVRScreenshotType (OPENVR_FNTABLE_CALLTYPE *GetCurrentScreenshotType)(); + EVRCompositorError (OPENVR_FNTABLE_CALLTYPE *GetMirrorTextureD3D11)(EVREye eEye, void * pD3D11DeviceOrResource, void ** ppD3D11ShaderResourceView); + EVRCompositorError (OPENVR_FNTABLE_CALLTYPE *GetMirrorTextureGL)(EVREye eEye, glUInt_t * pglTextureId, glSharedTextureHandle_t * pglSharedTextureHandle); + bool (OPENVR_FNTABLE_CALLTYPE *ReleaseSharedGLTexture)(glUInt_t glTextureId, glSharedTextureHandle_t glSharedTextureHandle); + void (OPENVR_FNTABLE_CALLTYPE *LockGLSharedTextureForAccess)(glSharedTextureHandle_t glSharedTextureHandle); + void (OPENVR_FNTABLE_CALLTYPE *UnlockGLSharedTextureForAccess)(glSharedTextureHandle_t glSharedTextureHandle); +}; + +struct VR_IVROverlay_FnTable +{ + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *FindOverlay)(char * pchOverlayKey, VROverlayHandle_t * pOverlayHandle); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *CreateOverlay)(char * pchOverlayKey, char * pchOverlayFriendlyName, VROverlayHandle_t * pOverlayHandle); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *DestroyOverlay)(VROverlayHandle_t ulOverlayHandle); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetHighQualityOverlay)(VROverlayHandle_t ulOverlayHandle); + VROverlayHandle_t (OPENVR_FNTABLE_CALLTYPE *GetHighQualityOverlay)(); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetOverlayKey)(VROverlayHandle_t ulOverlayHandle, char * pchValue, uint32_t unBufferSize, EVROverlayError * pError); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetOverlayName)(VROverlayHandle_t ulOverlayHandle, char * pchValue, uint32_t unBufferSize, EVROverlayError * pError); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayImageData)(VROverlayHandle_t ulOverlayHandle, void * pvBuffer, uint32_t unBufferSize, uint32_t * punWidth, uint32_t * punHeight); + char * (OPENVR_FNTABLE_CALLTYPE *GetOverlayErrorNameFromEnum)(EVROverlayError error); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayRenderingPid)(VROverlayHandle_t ulOverlayHandle, uint32_t unPID); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetOverlayRenderingPid)(VROverlayHandle_t ulOverlayHandle); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayFlag)(VROverlayHandle_t ulOverlayHandle, VROverlayFlags eOverlayFlag, bool bEnabled); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayFlag)(VROverlayHandle_t ulOverlayHandle, VROverlayFlags eOverlayFlag, bool * pbEnabled); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayColor)(VROverlayHandle_t ulOverlayHandle, float fRed, float fGreen, float fBlue); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayColor)(VROverlayHandle_t ulOverlayHandle, float * pfRed, float * pfGreen, float * pfBlue); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayAlpha)(VROverlayHandle_t ulOverlayHandle, float fAlpha); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayAlpha)(VROverlayHandle_t ulOverlayHandle, float * pfAlpha); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayWidthInMeters)(VROverlayHandle_t ulOverlayHandle, float fWidthInMeters); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayWidthInMeters)(VROverlayHandle_t ulOverlayHandle, float * pfWidthInMeters); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayAutoCurveDistanceRangeInMeters)(VROverlayHandle_t ulOverlayHandle, float fMinDistanceInMeters, float fMaxDistanceInMeters); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayAutoCurveDistanceRangeInMeters)(VROverlayHandle_t ulOverlayHandle, float * pfMinDistanceInMeters, float * pfMaxDistanceInMeters); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayTextureColorSpace)(VROverlayHandle_t ulOverlayHandle, EColorSpace eTextureColorSpace); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayTextureColorSpace)(VROverlayHandle_t ulOverlayHandle, EColorSpace * peTextureColorSpace); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayTextureBounds)(VROverlayHandle_t ulOverlayHandle, struct VRTextureBounds_t * pOverlayTextureBounds); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayTextureBounds)(VROverlayHandle_t ulOverlayHandle, struct VRTextureBounds_t * pOverlayTextureBounds); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayTransformType)(VROverlayHandle_t ulOverlayHandle, VROverlayTransformType * peTransformType); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayTransformAbsolute)(VROverlayHandle_t ulOverlayHandle, ETrackingUniverseOrigin eTrackingOrigin, struct HmdMatrix34_t * pmatTrackingOriginToOverlayTransform); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayTransformAbsolute)(VROverlayHandle_t ulOverlayHandle, ETrackingUniverseOrigin * peTrackingOrigin, struct HmdMatrix34_t * pmatTrackingOriginToOverlayTransform); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayTransformTrackedDeviceRelative)(VROverlayHandle_t ulOverlayHandle, TrackedDeviceIndex_t unTrackedDevice, struct HmdMatrix34_t * pmatTrackedDeviceToOverlayTransform); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayTransformTrackedDeviceRelative)(VROverlayHandle_t ulOverlayHandle, TrackedDeviceIndex_t * punTrackedDevice, struct HmdMatrix34_t * pmatTrackedDeviceToOverlayTransform); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayTransformTrackedDeviceComponent)(VROverlayHandle_t ulOverlayHandle, TrackedDeviceIndex_t unDeviceIndex, char * pchComponentName); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayTransformTrackedDeviceComponent)(VROverlayHandle_t ulOverlayHandle, TrackedDeviceIndex_t * punDeviceIndex, char * pchComponentName, uint32_t unComponentNameSize); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *ShowOverlay)(VROverlayHandle_t ulOverlayHandle); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *HideOverlay)(VROverlayHandle_t ulOverlayHandle); + bool (OPENVR_FNTABLE_CALLTYPE *IsOverlayVisible)(VROverlayHandle_t ulOverlayHandle); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetTransformForOverlayCoordinates)(VROverlayHandle_t ulOverlayHandle, ETrackingUniverseOrigin eTrackingOrigin, struct HmdVector2_t coordinatesInOverlay, struct HmdMatrix34_t * pmatTransform); + bool (OPENVR_FNTABLE_CALLTYPE *PollNextOverlayEvent)(VROverlayHandle_t ulOverlayHandle, struct VREvent_t * pEvent, uint32_t uncbVREvent); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayInputMethod)(VROverlayHandle_t ulOverlayHandle, VROverlayInputMethod * peInputMethod); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayInputMethod)(VROverlayHandle_t ulOverlayHandle, VROverlayInputMethod eInputMethod); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayMouseScale)(VROverlayHandle_t ulOverlayHandle, struct HmdVector2_t * pvecMouseScale); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayMouseScale)(VROverlayHandle_t ulOverlayHandle, struct HmdVector2_t * pvecMouseScale); + bool (OPENVR_FNTABLE_CALLTYPE *ComputeOverlayIntersection)(VROverlayHandle_t ulOverlayHandle, struct VROverlayIntersectionParams_t * pParams, struct VROverlayIntersectionResults_t * pResults); + bool (OPENVR_FNTABLE_CALLTYPE *HandleControllerOverlayInteractionAsMouse)(VROverlayHandle_t ulOverlayHandle, TrackedDeviceIndex_t unControllerDeviceIndex); + bool (OPENVR_FNTABLE_CALLTYPE *IsHoverTargetOverlay)(VROverlayHandle_t ulOverlayHandle); + VROverlayHandle_t (OPENVR_FNTABLE_CALLTYPE *GetGamepadFocusOverlay)(); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetGamepadFocusOverlay)(VROverlayHandle_t ulNewFocusOverlay); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayNeighbor)(EOverlayDirection eDirection, VROverlayHandle_t ulFrom, VROverlayHandle_t ulTo); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *MoveGamepadFocusToNeighbor)(EOverlayDirection eDirection, VROverlayHandle_t ulFrom); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayTexture)(VROverlayHandle_t ulOverlayHandle, struct Texture_t * pTexture); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *ClearOverlayTexture)(VROverlayHandle_t ulOverlayHandle); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayRaw)(VROverlayHandle_t ulOverlayHandle, void * pvBuffer, uint32_t unWidth, uint32_t unHeight, uint32_t unDepth); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayFromFile)(VROverlayHandle_t ulOverlayHandle, char * pchFilePath); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayTexture)(VROverlayHandle_t ulOverlayHandle, void ** pNativeTextureHandle, void * pNativeTextureRef, uint32_t * pWidth, uint32_t * pHeight, uint32_t * pNativeFormat, EGraphicsAPIConvention * pAPI, EColorSpace * pColorSpace); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *ReleaseNativeOverlayHandle)(VROverlayHandle_t ulOverlayHandle, void * pNativeTextureHandle); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayTextureSize)(VROverlayHandle_t ulOverlayHandle, uint32_t * pWidth, uint32_t * pHeight); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *CreateDashboardOverlay)(char * pchOverlayKey, char * pchOverlayFriendlyName, VROverlayHandle_t * pMainHandle, VROverlayHandle_t * pThumbnailHandle); + bool (OPENVR_FNTABLE_CALLTYPE *IsDashboardVisible)(); + bool (OPENVR_FNTABLE_CALLTYPE *IsActiveDashboardOverlay)(VROverlayHandle_t ulOverlayHandle); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetDashboardOverlaySceneProcess)(VROverlayHandle_t ulOverlayHandle, uint32_t unProcessId); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetDashboardOverlaySceneProcess)(VROverlayHandle_t ulOverlayHandle, uint32_t * punProcessId); + void (OPENVR_FNTABLE_CALLTYPE *ShowDashboard)(char * pchOverlayToShow); + TrackedDeviceIndex_t (OPENVR_FNTABLE_CALLTYPE *GetPrimaryDashboardDevice)(); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *ShowKeyboard)(EGamepadTextInputMode eInputMode, EGamepadTextInputLineMode eLineInputMode, char * pchDescription, uint32_t unCharMax, char * pchExistingText, bool bUseMinimalMode, uint64_t uUserValue); + EVROverlayError (OPENVR_FNTABLE_CALLTYPE *ShowKeyboardForOverlay)(VROverlayHandle_t ulOverlayHandle, EGamepadTextInputMode eInputMode, EGamepadTextInputLineMode eLineInputMode, char * pchDescription, uint32_t unCharMax, char * pchExistingText, bool bUseMinimalMode, uint64_t uUserValue); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetKeyboardText)(char * pchText, uint32_t cchText); + void (OPENVR_FNTABLE_CALLTYPE *HideKeyboard)(); + void (OPENVR_FNTABLE_CALLTYPE *SetKeyboardTransformAbsolute)(ETrackingUniverseOrigin eTrackingOrigin, struct HmdMatrix34_t * pmatTrackingOriginToKeyboardTransform); + void (OPENVR_FNTABLE_CALLTYPE *SetKeyboardPositionForOverlay)(VROverlayHandle_t ulOverlayHandle, struct HmdRect2_t avoidRect); +}; + +struct VR_IVRRenderModels_FnTable +{ + EVRRenderModelError (OPENVR_FNTABLE_CALLTYPE *LoadRenderModel_Async)(char * pchRenderModelName, struct RenderModel_t ** ppRenderModel); + void (OPENVR_FNTABLE_CALLTYPE *FreeRenderModel)(struct RenderModel_t * pRenderModel); + EVRRenderModelError (OPENVR_FNTABLE_CALLTYPE *LoadTexture_Async)(TextureID_t textureId, struct RenderModel_TextureMap_t ** ppTexture); + void (OPENVR_FNTABLE_CALLTYPE *FreeTexture)(struct RenderModel_TextureMap_t * pTexture); + EVRRenderModelError (OPENVR_FNTABLE_CALLTYPE *LoadTextureD3D11_Async)(TextureID_t textureId, void * pD3D11Device, void ** ppD3D11Texture2D); + EVRRenderModelError (OPENVR_FNTABLE_CALLTYPE *LoadIntoTextureD3D11_Async)(TextureID_t textureId, void * pDstTexture); + void (OPENVR_FNTABLE_CALLTYPE *FreeTextureD3D11)(void * pD3D11Texture2D); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetRenderModelName)(uint32_t unRenderModelIndex, char * pchRenderModelName, uint32_t unRenderModelNameLen); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetRenderModelCount)(); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetComponentCount)(char * pchRenderModelName); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetComponentName)(char * pchRenderModelName, uint32_t unComponentIndex, char * pchComponentName, uint32_t unComponentNameLen); + uint64_t (OPENVR_FNTABLE_CALLTYPE *GetComponentButtonMask)(char * pchRenderModelName, char * pchComponentName); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetComponentRenderModelName)(char * pchRenderModelName, char * pchComponentName, char * pchComponentRenderModelName, uint32_t unComponentRenderModelNameLen); + bool (OPENVR_FNTABLE_CALLTYPE *GetComponentState)(char * pchRenderModelName, char * pchComponentName, VRControllerState_t * pControllerState, struct RenderModel_ControllerMode_State_t * pState, struct RenderModel_ComponentState_t * pComponentState); + bool (OPENVR_FNTABLE_CALLTYPE *RenderModelHasComponent)(char * pchRenderModelName, char * pchComponentName); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetRenderModelThumbnailURL)(char * pchRenderModelName, char * pchThumbnailURL, uint32_t unThumbnailURLLen, EVRRenderModelError * peError); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetRenderModelOriginalPath)(char * pchRenderModelName, char * pchOriginalPath, uint32_t unOriginalPathLen, EVRRenderModelError * peError); + char * (OPENVR_FNTABLE_CALLTYPE *GetRenderModelErrorNameFromEnum)(EVRRenderModelError error); +}; + +struct VR_IVRNotifications_FnTable +{ + EVRNotificationError (OPENVR_FNTABLE_CALLTYPE *CreateNotification)(VROverlayHandle_t ulOverlayHandle, uint64_t ulUserValue, EVRNotificationType type, char * pchText, EVRNotificationStyle style, struct NotificationBitmap_t * pImage, VRNotificationId * pNotificationId); + EVRNotificationError (OPENVR_FNTABLE_CALLTYPE *RemoveNotification)(VRNotificationId notificationId); +}; + +struct VR_IVRSettings_FnTable +{ + char * (OPENVR_FNTABLE_CALLTYPE *GetSettingsErrorNameFromEnum)(EVRSettingsError eError); + bool (OPENVR_FNTABLE_CALLTYPE *Sync)(bool bForce, EVRSettingsError * peError); + bool (OPENVR_FNTABLE_CALLTYPE *GetBool)(char * pchSection, char * pchSettingsKey, bool bDefaultValue, EVRSettingsError * peError); + void (OPENVR_FNTABLE_CALLTYPE *SetBool)(char * pchSection, char * pchSettingsKey, bool bValue, EVRSettingsError * peError); + int32_t (OPENVR_FNTABLE_CALLTYPE *GetInt32)(char * pchSection, char * pchSettingsKey, int32_t nDefaultValue, EVRSettingsError * peError); + void (OPENVR_FNTABLE_CALLTYPE *SetInt32)(char * pchSection, char * pchSettingsKey, int32_t nValue, EVRSettingsError * peError); + float (OPENVR_FNTABLE_CALLTYPE *GetFloat)(char * pchSection, char * pchSettingsKey, float flDefaultValue, EVRSettingsError * peError); + void (OPENVR_FNTABLE_CALLTYPE *SetFloat)(char * pchSection, char * pchSettingsKey, float flValue, EVRSettingsError * peError); + void (OPENVR_FNTABLE_CALLTYPE *GetString)(char * pchSection, char * pchSettingsKey, char * pchValue, uint32_t unValueLen, char * pchDefaultValue, EVRSettingsError * peError); + void (OPENVR_FNTABLE_CALLTYPE *SetString)(char * pchSection, char * pchSettingsKey, char * pchValue, EVRSettingsError * peError); + void (OPENVR_FNTABLE_CALLTYPE *RemoveSection)(char * pchSection, EVRSettingsError * peError); + void (OPENVR_FNTABLE_CALLTYPE *RemoveKeyInSection)(char * pchSection, char * pchSettingsKey, EVRSettingsError * peError); +}; + +struct VR_IVRScreenshots_FnTable +{ + EVRScreenshotError (OPENVR_FNTABLE_CALLTYPE *RequestScreenshot)(ScreenshotHandle_t * pOutScreenshotHandle, EVRScreenshotType type, char * pchPreviewFilename, char * pchVRFilename); + EVRScreenshotError (OPENVR_FNTABLE_CALLTYPE *HookScreenshot)(EVRScreenshotType * pSupportedTypes, int numTypes); + EVRScreenshotType (OPENVR_FNTABLE_CALLTYPE *GetScreenshotPropertyType)(ScreenshotHandle_t screenshotHandle, EVRScreenshotError * pError); + uint32_t (OPENVR_FNTABLE_CALLTYPE *GetScreenshotPropertyFilename)(ScreenshotHandle_t screenshotHandle, EVRScreenshotPropertyFilenames filenameType, char * pchFilename, uint32_t cchFilename, EVRScreenshotError * pError); + EVRScreenshotError (OPENVR_FNTABLE_CALLTYPE *UpdateScreenshotProgress)(ScreenshotHandle_t screenshotHandle, float flProgress); + EVRScreenshotError (OPENVR_FNTABLE_CALLTYPE *TakeStereoScreenshot)(ScreenshotHandle_t * pOutScreenshotHandle, char * pchPreviewFilename, char * pchVRFilename); + EVRScreenshotError (OPENVR_FNTABLE_CALLTYPE *SubmitScreenshot)(ScreenshotHandle_t screenshotHandle, EVRScreenshotType type, char * pchSourcePreviewFilename, char * pchSourceVRFilename); +}; + + +#if 0 +// Global entry points +S_API intptr_t VR_InitInternal( EVRInitError *peError, EVRApplicationType eType ); +S_API void VR_ShutdownInternal(); +S_API bool VR_IsHmdPresent(); +S_API intptr_t VR_GetGenericInterface( const char *pchInterfaceVersion, EVRInitError *peError ); +S_API bool VR_IsRuntimeInstalled(); +S_API const char * VR_GetVRInitErrorAsSymbol( EVRInitError error ); +S_API const char * VR_GetVRInitErrorAsEnglishDescription( EVRInitError error ); +#endif + +#endif // __OPENVR_API_FLAT_H__ + + diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr_driver.h b/examples/ThirdPartyLibs/openvr/headers/openvr_driver.h new file mode 100644 index 000000000..3f2a21df4 --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/headers/openvr_driver.h @@ -0,0 +1,1829 @@ +#pragma once + +// openvr_driver.h +//========= Copyright Valve Corporation ============// +// Dynamically generated file. Do not modify this file directly. + +#ifndef _OPENVR_DRIVER_API +#define _OPENVR_DRIVER_API + +#include + + + +// vrtypes.h +#ifndef _INCLUDE_VRTYPES_H +#define _INCLUDE_VRTYPES_H + +namespace vr +{ + +#if defined(__linux__) || defined(__APPLE__) + // The 32-bit version of gcc has the alignment requirement for uint64 and double set to + // 4 meaning that even with #pragma pack(8) these types will only be four-byte aligned. + // The 64-bit version of gcc has the alignment requirement for these types set to + // 8 meaning that unless we use #pragma pack(4) our structures will get bigger. + // The 64-bit structure packing has to match the 32-bit structure packing for each platform. + #pragma pack( push, 4 ) +#else + #pragma pack( push, 8 ) +#endif + +typedef void* glSharedTextureHandle_t; +typedef int32_t glInt_t; +typedef uint32_t glUInt_t; + +// right-handed system +// +y is up +// +x is to the right +// -z is going away from you +// Distance unit is meters +struct HmdMatrix34_t +{ + float m[3][4]; +}; + +struct HmdMatrix44_t +{ + float m[4][4]; +}; + +struct HmdVector3_t +{ + float v[3]; +}; + +struct HmdVector4_t +{ + float v[4]; +}; + +struct HmdVector3d_t +{ + double v[3]; +}; + +struct HmdVector2_t +{ + float v[2]; +}; + +struct HmdQuaternion_t +{ + double w, x, y, z; +}; + +struct HmdColor_t +{ + float r, g, b, a; +}; + +struct HmdQuad_t +{ + HmdVector3_t vCorners[ 4 ]; +}; + +struct HmdRect2_t +{ + HmdVector2_t vTopLeft; + HmdVector2_t vBottomRight; +}; + +/** Used to return the post-distortion UVs for each color channel. +* UVs range from 0 to 1 with 0,0 in the upper left corner of the +* source render target. The 0,0 to 1,1 range covers a single eye. */ +struct DistortionCoordinates_t +{ + float rfRed[2]; + float rfGreen[2]; + float rfBlue[2]; +}; + +enum EVREye +{ + Eye_Left = 0, + Eye_Right = 1 +}; + +enum EGraphicsAPIConvention +{ + API_DirectX = 0, // Normalized Z goes from 0 at the viewer to 1 at the far clip plane + API_OpenGL = 1, // Normalized Z goes from 1 at the viewer to -1 at the far clip plane +}; + +enum EColorSpace +{ + ColorSpace_Auto = 0, // Assumes 'gamma' for 8-bit per component formats, otherwise 'linear'. This mirrors the DXGI formats which have _SRGB variants. + ColorSpace_Gamma = 1, // Texture data can be displayed directly on the display without any conversion (a.k.a. display native format). + ColorSpace_Linear = 2, // Same as gamma but has been converted to a linear representation using DXGI's sRGB conversion algorithm. +}; + +struct Texture_t +{ + void* handle; // Native d3d texture pointer or GL texture id. + EGraphicsAPIConvention eType; + EColorSpace eColorSpace; +}; + +enum ETrackingResult +{ + TrackingResult_Uninitialized = 1, + + TrackingResult_Calibrating_InProgress = 100, + TrackingResult_Calibrating_OutOfRange = 101, + + TrackingResult_Running_OK = 200, + TrackingResult_Running_OutOfRange = 201, +}; + +static const uint32_t k_unTrackingStringSize = 32; +static const uint32_t k_unMaxDriverDebugResponseSize = 32768; + +/** Used to pass device IDs to API calls */ +typedef uint32_t TrackedDeviceIndex_t; +static const uint32_t k_unTrackedDeviceIndex_Hmd = 0; +static const uint32_t k_unMaxTrackedDeviceCount = 16; +static const uint32_t k_unTrackedDeviceIndexOther = 0xFFFFFFFE; +static const uint32_t k_unTrackedDeviceIndexInvalid = 0xFFFFFFFF; + +/** Describes what kind of object is being tracked at a given ID */ +enum ETrackedDeviceClass +{ + TrackedDeviceClass_Invalid = 0, // the ID was not valid. + TrackedDeviceClass_HMD = 1, // Head-Mounted Displays + TrackedDeviceClass_Controller = 2, // Tracked controllers + TrackedDeviceClass_TrackingReference = 4, // Camera and base stations that serve as tracking reference points + + TrackedDeviceClass_Other = 1000, +}; + + +/** Describes what specific role associated with a tracked device */ +enum ETrackedControllerRole +{ + TrackedControllerRole_Invalid = 0, // Invalid value for controller type + TrackedControllerRole_LeftHand = 1, // Tracked device associated with the left hand + TrackedControllerRole_RightHand = 2, // Tracked device associated with the right hand +}; + + +/** describes a single pose for a tracked object */ +struct TrackedDevicePose_t +{ + HmdMatrix34_t mDeviceToAbsoluteTracking; + HmdVector3_t vVelocity; // velocity in tracker space in m/s + HmdVector3_t vAngularVelocity; // angular velocity in radians/s (?) + ETrackingResult eTrackingResult; + bool bPoseIsValid; + + // This indicates that there is a device connected for this spot in the pose array. + // It could go from true to false if the user unplugs the device. + bool bDeviceIsConnected; +}; + +/** Identifies which style of tracking origin the application wants to use +* for the poses it is requesting */ +enum ETrackingUniverseOrigin +{ + TrackingUniverseSeated = 0, // Poses are provided relative to the seated zero pose + TrackingUniverseStanding = 1, // Poses are provided relative to the safe bounds configured by the user + TrackingUniverseRawAndUncalibrated = 2, // Poses are provided in the coordinate system defined by the driver. You probably don't want this one. +}; + + +/** Each entry in this enum represents a property that can be retrieved about a +* tracked device. Many fields are only valid for one ETrackedDeviceClass. */ +enum ETrackedDeviceProperty +{ + // general properties that apply to all device classes + Prop_TrackingSystemName_String = 1000, + Prop_ModelNumber_String = 1001, + Prop_SerialNumber_String = 1002, + Prop_RenderModelName_String = 1003, + Prop_WillDriftInYaw_Bool = 1004, + Prop_ManufacturerName_String = 1005, + Prop_TrackingFirmwareVersion_String = 1006, + Prop_HardwareRevision_String = 1007, + Prop_AllWirelessDongleDescriptions_String = 1008, + Prop_ConnectedWirelessDongle_String = 1009, + Prop_DeviceIsWireless_Bool = 1010, + Prop_DeviceIsCharging_Bool = 1011, + Prop_DeviceBatteryPercentage_Float = 1012, // 0 is empty, 1 is full + Prop_StatusDisplayTransform_Matrix34 = 1013, + Prop_Firmware_UpdateAvailable_Bool = 1014, + Prop_Firmware_ManualUpdate_Bool = 1015, + Prop_Firmware_ManualUpdateURL_String = 1016, + Prop_HardwareRevision_Uint64 = 1017, + Prop_FirmwareVersion_Uint64 = 1018, + Prop_FPGAVersion_Uint64 = 1019, + Prop_VRCVersion_Uint64 = 1020, + Prop_RadioVersion_Uint64 = 1021, + Prop_DongleVersion_Uint64 = 1022, + Prop_BlockServerShutdown_Bool = 1023, + Prop_CanUnifyCoordinateSystemWithHmd_Bool = 1024, + Prop_ContainsProximitySensor_Bool = 1025, + Prop_DeviceProvidesBatteryStatus_Bool = 1026, + Prop_DeviceCanPowerOff_Bool = 1027, + Prop_Firmware_ProgrammingTarget_String = 1028, + Prop_DeviceClass_Int32 = 1029, + Prop_HasCamera_Bool = 1030, + Prop_DriverVersion_String = 1031, + Prop_Firmware_ForceUpdateRequired_Bool = 1032, + + // Properties that are unique to TrackedDeviceClass_HMD + Prop_ReportsTimeSinceVSync_Bool = 2000, + Prop_SecondsFromVsyncToPhotons_Float = 2001, + Prop_DisplayFrequency_Float = 2002, + Prop_UserIpdMeters_Float = 2003, + Prop_CurrentUniverseId_Uint64 = 2004, + Prop_PreviousUniverseId_Uint64 = 2005, + Prop_DisplayFirmwareVersion_Uint64 = 2006, + Prop_IsOnDesktop_Bool = 2007, + Prop_DisplayMCType_Int32 = 2008, + Prop_DisplayMCOffset_Float = 2009, + Prop_DisplayMCScale_Float = 2010, + Prop_EdidVendorID_Int32 = 2011, + Prop_DisplayMCImageLeft_String = 2012, + Prop_DisplayMCImageRight_String = 2013, + Prop_DisplayGCBlackClamp_Float = 2014, + Prop_EdidProductID_Int32 = 2015, + Prop_CameraToHeadTransform_Matrix34 = 2016, + Prop_DisplayGCType_Int32 = 2017, + Prop_DisplayGCOffset_Float = 2018, + Prop_DisplayGCScale_Float = 2019, + Prop_DisplayGCPrescale_Float = 2020, + Prop_DisplayGCImage_String = 2021, + Prop_LensCenterLeftU_Float = 2022, + Prop_LensCenterLeftV_Float = 2023, + Prop_LensCenterRightU_Float = 2024, + Prop_LensCenterRightV_Float = 2025, + Prop_UserHeadToEyeDepthMeters_Float = 2026, + Prop_CameraFirmwareVersion_Uint64 = 2027, + Prop_CameraFirmwareDescription_String = 2028, + Prop_DisplayFPGAVersion_Uint64 = 2029, + Prop_DisplayBootloaderVersion_Uint64 = 2030, + Prop_DisplayHardwareVersion_Uint64 = 2031, + Prop_AudioFirmwareVersion_Uint64 = 2032, + Prop_CameraCompatibilityMode_Int32 = 2033, + Prop_ScreenshotHorizontalFieldOfViewDegrees_Float = 2034, + Prop_ScreenshotVerticalFieldOfViewDegrees_Float = 2035, + Prop_DisplaySuppressed_Bool = 2036, + + // Properties that are unique to TrackedDeviceClass_Controller + Prop_AttachedDeviceId_String = 3000, + Prop_SupportedButtons_Uint64 = 3001, + Prop_Axis0Type_Int32 = 3002, // Return value is of type EVRControllerAxisType + Prop_Axis1Type_Int32 = 3003, // Return value is of type EVRControllerAxisType + Prop_Axis2Type_Int32 = 3004, // Return value is of type EVRControllerAxisType + Prop_Axis3Type_Int32 = 3005, // Return value is of type EVRControllerAxisType + Prop_Axis4Type_Int32 = 3006, // Return value is of type EVRControllerAxisType + + // Properties that are unique to TrackedDeviceClass_TrackingReference + Prop_FieldOfViewLeftDegrees_Float = 4000, + Prop_FieldOfViewRightDegrees_Float = 4001, + Prop_FieldOfViewTopDegrees_Float = 4002, + Prop_FieldOfViewBottomDegrees_Float = 4003, + Prop_TrackingRangeMinimumMeters_Float = 4004, + Prop_TrackingRangeMaximumMeters_Float = 4005, + Prop_ModeLabel_String = 4006, + + // Vendors are free to expose private debug data in this reserved region + Prop_VendorSpecific_Reserved_Start = 10000, + Prop_VendorSpecific_Reserved_End = 10999, +}; + +/** No string property will ever be longer than this length */ +static const uint32_t k_unMaxPropertyStringSize = 32 * 1024; + +/** Used to return errors that occur when reading properties. */ +enum ETrackedPropertyError +{ + TrackedProp_Success = 0, + TrackedProp_WrongDataType = 1, + TrackedProp_WrongDeviceClass = 2, + TrackedProp_BufferTooSmall = 3, + TrackedProp_UnknownProperty = 4, + TrackedProp_InvalidDevice = 5, + TrackedProp_CouldNotContactServer = 6, + TrackedProp_ValueNotProvidedByDevice = 7, + TrackedProp_StringExceedsMaximumLength = 8, + TrackedProp_NotYetAvailable = 9, // The property value isn't known yet, but is expected soon. Call again later. +}; + +/** Allows the application to control what part of the provided texture will be used in the +* frame buffer. */ +struct VRTextureBounds_t +{ + float uMin, vMin; + float uMax, vMax; +}; + + +/** Allows the application to control how scene textures are used by the compositor when calling Submit. */ +enum EVRSubmitFlags +{ + // Simple render path. App submits rendered left and right eye images with no lens distortion correction applied. + Submit_Default = 0x00, + + // App submits final left and right eye images with lens distortion already applied (lens distortion makes the images appear + // barrel distorted with chromatic aberration correction applied). The app would have used the data returned by + // vr::IVRSystem::ComputeDistortion() to apply the correct distortion to the rendered images before calling Submit(). + Submit_LensDistortionAlreadyApplied = 0x01, + + // If the texture pointer passed in is actually a renderbuffer (e.g. for MSAA in OpenGL) then set this flag. + Submit_GlRenderBuffer = 0x02, +}; + + +/** Status of the overall system or tracked objects */ +enum EVRState +{ + VRState_Undefined = -1, + VRState_Off = 0, + VRState_Searching = 1, + VRState_Searching_Alert = 2, + VRState_Ready = 3, + VRState_Ready_Alert = 4, + VRState_NotReady = 5, + VRState_Standby = 6, +}; + +/** The types of events that could be posted (and what the parameters mean for each event type) */ +enum EVREventType +{ + VREvent_None = 0, + + VREvent_TrackedDeviceActivated = 100, + VREvent_TrackedDeviceDeactivated = 101, + VREvent_TrackedDeviceUpdated = 102, + VREvent_TrackedDeviceUserInteractionStarted = 103, + VREvent_TrackedDeviceUserInteractionEnded = 104, + VREvent_IpdChanged = 105, + VREvent_EnterStandbyMode = 106, + VREvent_LeaveStandbyMode = 107, + VREvent_TrackedDeviceRoleChanged = 108, + + VREvent_ButtonPress = 200, // data is controller + VREvent_ButtonUnpress = 201, // data is controller + VREvent_ButtonTouch = 202, // data is controller + VREvent_ButtonUntouch = 203, // data is controller + + VREvent_MouseMove = 300, // data is mouse + VREvent_MouseButtonDown = 301, // data is mouse + VREvent_MouseButtonUp = 302, // data is mouse + VREvent_FocusEnter = 303, // data is overlay + VREvent_FocusLeave = 304, // data is overlay + VREvent_Scroll = 305, // data is mouse + VREvent_TouchPadMove = 306, // data is mouse + + VREvent_InputFocusCaptured = 400, // data is process DEPRECATED + VREvent_InputFocusReleased = 401, // data is process DEPRECATED + VREvent_SceneFocusLost = 402, // data is process + VREvent_SceneFocusGained = 403, // data is process + VREvent_SceneApplicationChanged = 404, // data is process - The App actually drawing the scene changed (usually to or from the compositor) + VREvent_SceneFocusChanged = 405, // data is process - New app got access to draw the scene + VREvent_InputFocusChanged = 406, // data is process + VREvent_SceneApplicationSecondaryRenderingStarted = 407, // data is process + + VREvent_HideRenderModels = 410, // Sent to the scene application to request hiding render models temporarily + VREvent_ShowRenderModels = 411, // Sent to the scene application to request restoring render model visibility + + VREvent_OverlayShown = 500, + VREvent_OverlayHidden = 501, + VREvent_DashboardActivated = 502, + VREvent_DashboardDeactivated = 503, + VREvent_DashboardThumbSelected = 504, // Sent to the overlay manager - data is overlay + VREvent_DashboardRequested = 505, // Sent to the overlay manager - data is overlay + VREvent_ResetDashboard = 506, // Send to the overlay manager + VREvent_RenderToast = 507, // Send to the dashboard to render a toast - data is the notification ID + VREvent_ImageLoaded = 508, // Sent to overlays when a SetOverlayRaw or SetOverlayFromFile call finishes loading + VREvent_ShowKeyboard = 509, // Sent to keyboard renderer in the dashboard to invoke it + VREvent_HideKeyboard = 510, // Sent to keyboard renderer in the dashboard to hide it + VREvent_OverlayGamepadFocusGained = 511, // Sent to an overlay when IVROverlay::SetFocusOverlay is called on it + VREvent_OverlayGamepadFocusLost = 512, // Send to an overlay when it previously had focus and IVROverlay::SetFocusOverlay is called on something else + VREvent_OverlaySharedTextureChanged = 513, + VREvent_DashboardGuideButtonDown = 514, + VREvent_DashboardGuideButtonUp = 515, + VREvent_ScreenshotTriggered = 516, // Screenshot button combo was pressed, Dashboard should request a screenshot + VREvent_ImageFailed = 517, // Sent to overlays when a SetOverlayRaw or SetOverlayfromFail fails to load + + // Screenshot API + VREvent_RequestScreenshot = 520, // Sent by vrclient application to compositor to take a screenshot + VREvent_ScreenshotTaken = 521, // Sent by compositor to the application that the screenshot has been taken + VREvent_ScreenshotFailed = 522, // Sent by compositor to the application that the screenshot failed to be taken + VREvent_SubmitScreenshotToDashboard = 523, // Sent by compositor to the dashboard that a completed screenshot was submitted + + VREvent_Notification_Shown = 600, + VREvent_Notification_Hidden = 601, + VREvent_Notification_BeginInteraction = 602, + VREvent_Notification_Destroyed = 603, + + VREvent_Quit = 700, // data is process + VREvent_ProcessQuit = 701, // data is process + VREvent_QuitAborted_UserPrompt = 702, // data is process + VREvent_QuitAcknowledged = 703, // data is process + VREvent_DriverRequestedQuit = 704, // The driver has requested that SteamVR shut down + + VREvent_ChaperoneDataHasChanged = 800, + VREvent_ChaperoneUniverseHasChanged = 801, + VREvent_ChaperoneTempDataHasChanged = 802, + VREvent_ChaperoneSettingsHaveChanged = 803, + VREvent_SeatedZeroPoseReset = 804, + + VREvent_AudioSettingsHaveChanged = 820, + + VREvent_BackgroundSettingHasChanged = 850, + VREvent_CameraSettingsHaveChanged = 851, + VREvent_ReprojectionSettingHasChanged = 852, + VREvent_ModelSkinSettingsHaveChanged = 853, + VREvent_EnvironmentSettingsHaveChanged = 854, + + VREvent_StatusUpdate = 900, + + VREvent_MCImageUpdated = 1000, + + VREvent_FirmwareUpdateStarted = 1100, + VREvent_FirmwareUpdateFinished = 1101, + + VREvent_KeyboardClosed = 1200, + VREvent_KeyboardCharInput = 1201, + VREvent_KeyboardDone = 1202, // Sent when DONE button clicked on keyboard + + VREvent_ApplicationTransitionStarted = 1300, + VREvent_ApplicationTransitionAborted = 1301, + VREvent_ApplicationTransitionNewAppStarted = 1302, + VREvent_ApplicationListUpdated = 1303, + + VREvent_Compositor_MirrorWindowShown = 1400, + VREvent_Compositor_MirrorWindowHidden = 1401, + VREvent_Compositor_ChaperoneBoundsShown = 1410, + VREvent_Compositor_ChaperoneBoundsHidden = 1411, + + VREvent_TrackedCamera_StartVideoStream = 1500, + VREvent_TrackedCamera_StopVideoStream = 1501, + VREvent_TrackedCamera_PauseVideoStream = 1502, + VREvent_TrackedCamera_ResumeVideoStream = 1503, + + VREvent_PerformanceTest_EnableCapture = 1600, + VREvent_PerformanceTest_DisableCapture = 1601, + VREvent_PerformanceTest_FidelityLevel = 1602, + + // Vendors are free to expose private events in this reserved region + VREvent_VendorSpecific_Reserved_Start = 10000, + VREvent_VendorSpecific_Reserved_End = 19999, +}; + + +/** Level of Hmd activity */ +enum EDeviceActivityLevel +{ + k_EDeviceActivityLevel_Unknown = -1, + k_EDeviceActivityLevel_Idle = 0, + k_EDeviceActivityLevel_UserInteraction = 1, + k_EDeviceActivityLevel_UserInteraction_Timeout = 2, + k_EDeviceActivityLevel_Standby = 3, +}; + + +/** VR controller button and axis IDs */ +enum EVRButtonId +{ + k_EButton_System = 0, + k_EButton_ApplicationMenu = 1, + k_EButton_Grip = 2, + k_EButton_DPad_Left = 3, + k_EButton_DPad_Up = 4, + k_EButton_DPad_Right = 5, + k_EButton_DPad_Down = 6, + k_EButton_A = 7, + + k_EButton_Axis0 = 32, + k_EButton_Axis1 = 33, + k_EButton_Axis2 = 34, + k_EButton_Axis3 = 35, + k_EButton_Axis4 = 36, + + // aliases for well known controllers + k_EButton_SteamVR_Touchpad = k_EButton_Axis0, + k_EButton_SteamVR_Trigger = k_EButton_Axis1, + + k_EButton_Dashboard_Back = k_EButton_Grip, + + k_EButton_Max = 64 +}; + +inline uint64_t ButtonMaskFromId( EVRButtonId id ) { return 1ull << id; } + +/** used for controller button events */ +struct VREvent_Controller_t +{ + uint32_t button; // EVRButtonId enum +}; + + +/** used for simulated mouse events in overlay space */ +enum EVRMouseButton +{ + VRMouseButton_Left = 0x0001, + VRMouseButton_Right = 0x0002, + VRMouseButton_Middle = 0x0004, +}; + + +/** used for simulated mouse events in overlay space */ +struct VREvent_Mouse_t +{ + float x, y; // co-ords are in GL space, bottom left of the texture is 0,0 + uint32_t button; // EVRMouseButton enum +}; + +/** used for simulated mouse wheel scroll in overlay space */ +struct VREvent_Scroll_t +{ + float xdelta, ydelta; // movement in fraction of the pad traversed since last delta, 1.0 for a full swipe + uint32_t repeatCount; +}; + +/** when in mouse input mode you can receive data from the touchpad, these events are only sent if the users finger + is on the touchpad (or just released from it) +**/ +struct VREvent_TouchPadMove_t +{ + // true if the users finger is detected on the touch pad + bool bFingerDown; + + // How long the finger has been down in seconds + float flSecondsFingerDown; + + // These values indicate the starting finger position (so you can do some basic swipe stuff) + float fValueXFirst; + float fValueYFirst; + + // This is the raw sampled coordinate without deadzoning + float fValueXRaw; + float fValueYRaw; +}; + +/** notification related events. Details will still change at this point */ +struct VREvent_Notification_t +{ + uint64_t ulUserValue; + uint32_t notificationId; +}; + +/** Used for events about processes */ +struct VREvent_Process_t +{ + uint32_t pid; + uint32_t oldPid; + bool bForced; +}; + + +/** Used for a few events about overlays */ +struct VREvent_Overlay_t +{ + uint64_t overlayHandle; +}; + + +/** Used for a few events about overlays */ +struct VREvent_Status_t +{ + uint32_t statusState; // EVRState enum +}; + +/** Used for keyboard events **/ +struct VREvent_Keyboard_t +{ + char cNewInput[8]; // Up to 11 bytes of new input + uint64_t uUserValue; // Possible flags about the new input +}; + +struct VREvent_Ipd_t +{ + float ipdMeters; +}; + +struct VREvent_Chaperone_t +{ + uint64_t m_nPreviousUniverse; + uint64_t m_nCurrentUniverse; +}; + +/** Not actually used for any events */ +struct VREvent_Reserved_t +{ + uint64_t reserved0; + uint64_t reserved1; +}; + +struct VREvent_PerformanceTest_t +{ + uint32_t m_nFidelityLevel; +}; + +struct VREvent_SeatedZeroPoseReset_t +{ + bool bResetBySystemMenu; +}; + +struct VREvent_Screenshot_t +{ + uint32_t handle; + uint32_t type; +}; + +/** If you change this you must manually update openvr_interop.cs.py */ +typedef union +{ + VREvent_Reserved_t reserved; + VREvent_Controller_t controller; + VREvent_Mouse_t mouse; + VREvent_Scroll_t scroll; + VREvent_Process_t process; + VREvent_Notification_t notification; + VREvent_Overlay_t overlay; + VREvent_Status_t status; + VREvent_Keyboard_t keyboard; + VREvent_Ipd_t ipd; + VREvent_Chaperone_t chaperone; + VREvent_PerformanceTest_t performanceTest; + VREvent_TouchPadMove_t touchPadMove; + VREvent_SeatedZeroPoseReset_t seatedZeroPoseReset; + VREvent_Screenshot_t screenshot; +} VREvent_Data_t; + +/** An event posted by the server to all running applications */ +struct VREvent_t +{ + uint32_t eventType; // EVREventType enum + TrackedDeviceIndex_t trackedDeviceIndex; + float eventAgeSeconds; + // event data must be the end of the struct as its size is variable + VREvent_Data_t data; +}; + + +/** The mesh to draw into the stencil (or depth) buffer to perform +* early stencil (or depth) kills of pixels that will never appear on the HMD. +* This mesh draws on all the pixels that will be hidden after distortion. +* +* If the HMD does not provide a visible area mesh pVertexData will be +* NULL and unTriangleCount will be 0. */ +struct HiddenAreaMesh_t +{ + const HmdVector2_t *pVertexData; + uint32_t unTriangleCount; +}; + + +/** Identifies what kind of axis is on the controller at index n. Read this type +* with pVRSystem->Get( nControllerDeviceIndex, Prop_Axis0Type_Int32 + n ); +*/ +enum EVRControllerAxisType +{ + k_eControllerAxis_None = 0, + k_eControllerAxis_TrackPad = 1, + k_eControllerAxis_Joystick = 2, + k_eControllerAxis_Trigger = 3, // Analog trigger data is in the X axis +}; + + +/** contains information about one axis on the controller */ +struct VRControllerAxis_t +{ + float x; // Ranges from -1.0 to 1.0 for joysticks and track pads. Ranges from 0.0 to 1.0 for triggers were 0 is fully released. + float y; // Ranges from -1.0 to 1.0 for joysticks and track pads. Is always 0.0 for triggers. +}; + + +/** the number of axes in the controller state */ +static const uint32_t k_unControllerStateAxisCount = 5; + + +/** Holds all the state of a controller at one moment in time. */ +struct VRControllerState001_t +{ + // If packet num matches that on your prior call, then the controller state hasn't been changed since + // your last call and there is no need to process it + uint32_t unPacketNum; + + // bit flags for each of the buttons. Use ButtonMaskFromId to turn an ID into a mask + uint64_t ulButtonPressed; + uint64_t ulButtonTouched; + + // Axis data for the controller's analog inputs + VRControllerAxis_t rAxis[ k_unControllerStateAxisCount ]; +}; + + +typedef VRControllerState001_t VRControllerState_t; + + +/** determines how to provide output to the application of various event processing functions. */ +enum EVRControllerEventOutputType +{ + ControllerEventOutput_OSEvents = 0, + ControllerEventOutput_VREvents = 1, +}; + + + +/** Collision Bounds Style */ +enum ECollisionBoundsStyle +{ + COLLISION_BOUNDS_STYLE_BEGINNER = 0, + COLLISION_BOUNDS_STYLE_INTERMEDIATE, + COLLISION_BOUNDS_STYLE_SQUARES, + COLLISION_BOUNDS_STYLE_ADVANCED, + COLLISION_BOUNDS_STYLE_NONE, + + COLLISION_BOUNDS_STYLE_COUNT +}; + +/** Allows the application to customize how the overlay appears in the compositor */ +struct Compositor_OverlaySettings +{ + uint32_t size; // sizeof(Compositor_OverlaySettings) + bool curved, antialias; + float scale, distance, alpha; + float uOffset, vOffset, uScale, vScale; + float gridDivs, gridWidth, gridScale; + HmdMatrix44_t transform; +}; + +/** used to refer to a single VR overlay */ +typedef uint64_t VROverlayHandle_t; + +static const VROverlayHandle_t k_ulOverlayHandleInvalid = 0; + +/** Errors that can occur around VR overlays */ +enum EVROverlayError +{ + VROverlayError_None = 0, + + VROverlayError_UnknownOverlay = 10, + VROverlayError_InvalidHandle = 11, + VROverlayError_PermissionDenied = 12, + VROverlayError_OverlayLimitExceeded = 13, // No more overlays could be created because the maximum number already exist + VROverlayError_WrongVisibilityType = 14, + VROverlayError_KeyTooLong = 15, + VROverlayError_NameTooLong = 16, + VROverlayError_KeyInUse = 17, + VROverlayError_WrongTransformType = 18, + VROverlayError_InvalidTrackedDevice = 19, + VROverlayError_InvalidParameter = 20, + VROverlayError_ThumbnailCantBeDestroyed = 21, + VROverlayError_ArrayTooSmall = 22, + VROverlayError_RequestFailed = 23, + VROverlayError_InvalidTexture = 24, + VROverlayError_UnableToLoadFile = 25, + VROVerlayError_KeyboardAlreadyInUse = 26, + VROverlayError_NoNeighbor = 27, +}; + +/** enum values to pass in to VR_Init to identify whether the application will +* draw a 3D scene. */ +enum EVRApplicationType +{ + VRApplication_Other = 0, // Some other kind of application that isn't covered by the other entries + VRApplication_Scene = 1, // Application will submit 3D frames + VRApplication_Overlay = 2, // Application only interacts with overlays + VRApplication_Background = 3, // Application should not start SteamVR if it's not already running, and should not + // keep it running if everything else quits. + VRApplication_Utility = 4, // Init should not try to load any drivers. The application needs access to utility + // interfaces (like IVRSettings and IVRApplications) but not hardware. + VRApplication_VRMonitor = 5, // Reserved for vrmonitor +}; + + +/** error codes for firmware */ +enum EVRFirmwareError +{ + VRFirmwareError_None = 0, + VRFirmwareError_Success = 1, + VRFirmwareError_Fail = 2, +}; + + +/** error codes for notifications */ +enum EVRNotificationError +{ + VRNotificationError_OK = 0, + VRNotificationError_InvalidNotificationId = 100, + VRNotificationError_NotificationQueueFull = 101, + VRNotificationError_InvalidOverlayHandle = 102, + VRNotificationError_SystemWithUserValueAlreadyExists = 103, +}; + + +/** error codes returned by Vr_Init */ + +// Please add adequate error description to https://developer.valvesoftware.com/w/index.php?title=Category:SteamVRHelp +enum EVRInitError +{ + VRInitError_None = 0, + VRInitError_Unknown = 1, + + VRInitError_Init_InstallationNotFound = 100, + VRInitError_Init_InstallationCorrupt = 101, + VRInitError_Init_VRClientDLLNotFound = 102, + VRInitError_Init_FileNotFound = 103, + VRInitError_Init_FactoryNotFound = 104, + VRInitError_Init_InterfaceNotFound = 105, + VRInitError_Init_InvalidInterface = 106, + VRInitError_Init_UserConfigDirectoryInvalid = 107, + VRInitError_Init_HmdNotFound = 108, + VRInitError_Init_NotInitialized = 109, + VRInitError_Init_PathRegistryNotFound = 110, + VRInitError_Init_NoConfigPath = 111, + VRInitError_Init_NoLogPath = 112, + VRInitError_Init_PathRegistryNotWritable = 113, + VRInitError_Init_AppInfoInitFailed = 114, + VRInitError_Init_Retry = 115, // Used internally to cause retries to vrserver + VRInitError_Init_InitCanceledByUser = 116, // The calling application should silently exit. The user canceled app startup + VRInitError_Init_AnotherAppLaunching = 117, + VRInitError_Init_SettingsInitFailed = 118, + VRInitError_Init_ShuttingDown = 119, + VRInitError_Init_TooManyObjects = 120, + VRInitError_Init_NoServerForBackgroundApp = 121, + VRInitError_Init_NotSupportedWithCompositor = 122, + VRInitError_Init_NotAvailableToUtilityApps = 123, + VRInitError_Init_Internal = 124, + + VRInitError_Driver_Failed = 200, + VRInitError_Driver_Unknown = 201, + VRInitError_Driver_HmdUnknown = 202, + VRInitError_Driver_NotLoaded = 203, + VRInitError_Driver_RuntimeOutOfDate = 204, + VRInitError_Driver_HmdInUse = 205, + VRInitError_Driver_NotCalibrated = 206, + VRInitError_Driver_CalibrationInvalid = 207, + VRInitError_Driver_HmdDisplayNotFound = 208, + + VRInitError_IPC_ServerInitFailed = 300, + VRInitError_IPC_ConnectFailed = 301, + VRInitError_IPC_SharedStateInitFailed = 302, + VRInitError_IPC_CompositorInitFailed = 303, + VRInitError_IPC_MutexInitFailed = 304, + VRInitError_IPC_Failed = 305, + + VRInitError_Compositor_Failed = 400, + VRInitError_Compositor_D3D11HardwareRequired = 401, + VRInitError_Compositor_FirmwareRequiresUpdate = 402, + VRInitError_Compositor_OverlayInitFailed = 403, + VRInitError_Compositor_ScreenshotsInitFailed = 404, + + VRInitError_VendorSpecific_UnableToConnectToOculusRuntime = 1000, + + VRInitError_VendorSpecific_HmdFound_CantOpenDevice = 1101, + VRInitError_VendorSpecific_HmdFound_UnableToRequestConfigStart = 1102, + VRInitError_VendorSpecific_HmdFound_NoStoredConfig = 1103, + VRInitError_VendorSpecific_HmdFound_ConfigTooBig = 1104, + VRInitError_VendorSpecific_HmdFound_ConfigTooSmall = 1105, + VRInitError_VendorSpecific_HmdFound_UnableToInitZLib = 1106, + VRInitError_VendorSpecific_HmdFound_CantReadFirmwareVersion = 1107, + VRInitError_VendorSpecific_HmdFound_UnableToSendUserDataStart = 1108, + VRInitError_VendorSpecific_HmdFound_UnableToGetUserDataStart = 1109, + VRInitError_VendorSpecific_HmdFound_UnableToGetUserDataNext = 1110, + VRInitError_VendorSpecific_HmdFound_UserDataAddressRange = 1111, + VRInitError_VendorSpecific_HmdFound_UserDataError = 1112, + VRInitError_VendorSpecific_HmdFound_ConfigFailedSanityCheck = 1113, + + VRInitError_Steam_SteamInstallationNotFound = 2000, +}; + +enum EVRScreenshotType +{ + VRScreenshotType_None = 0, + VRScreenshotType_Mono = 1, // left eye only + VRScreenshotType_Stereo = 2, + VRScreenshotType_Cubemap = 3, + VRScreenshotType_MonoPanorama = 4, + VRScreenshotType_StereoPanorama = 5 +}; + +enum EVRScreenshotPropertyFilenames +{ + VRScreenshotPropertyFilenames_Preview = 0, + VRScreenshotPropertyFilenames_VR = 1, +}; + +enum EVRTrackedCameraError +{ + VRTrackedCameraError_None = 0, + VRTrackedCameraError_OperationFailed = 100, + VRTrackedCameraError_InvalidHandle = 101, + VRTrackedCameraError_InvalidFrameHeaderVersion = 102, + VRTrackedCameraError_OutOfHandles = 103, + VRTrackedCameraError_IPCFailure = 104, + VRTrackedCameraError_NotSupportedForThisDevice = 105, + VRTrackedCameraError_SharedMemoryFailure = 106, + VRTrackedCameraError_FrameBufferingFailure = 107, + VRTrackedCameraError_StreamSetupFailure = 108, + VRTrackedCameraError_InvalidGLTextureId = 109, + VRTrackedCameraError_InvalidSharedTextureHandle = 110, + VRTrackedCameraError_FailedToGetGLTextureId = 111, + VRTrackedCameraError_SharedTextureFailure = 112, + VRTrackedCameraError_NoFrameAvailable = 113, + VRTrackedCameraError_InvalidArgument = 114, + VRTrackedCameraError_InvalidFrameBufferSize = 115, +}; + +enum EVRTrackedCameraFrameType +{ + VRTrackedCameraFrameType_Distorted = 0, // This is the camera video frame size in pixels, still distorted. + VRTrackedCameraFrameType_Undistorted, // In pixels, an undistorted inscribed rectangle region without invalid regions. This size is subject to changes shortly. + VRTrackedCameraFrameType_MaximumUndistorted, // In pixels, maximum undistorted with invalid regions. Non zero alpha component identifies valid regions. + MAX_CAMERA_FRAME_TYPES +}; + +typedef uint64_t TrackedCameraHandle_t; +#define INVALID_TRACKED_CAMERA_HANDLE ((vr::TrackedCameraHandle_t)0) + +struct CameraVideoStreamFrameHeader_t +{ + EVRTrackedCameraFrameType eFrameType; + + uint32_t nWidth; + uint32_t nHeight; + uint32_t nBytesPerPixel; + + uint32_t nFrameSequence; + + TrackedDevicePose_t standingTrackedDevicePose; +}; + +// Screenshot types +typedef uint32_t ScreenshotHandle_t; + +static const uint32_t k_unScreenshotHandleInvalid = 0; + +#pragma pack( pop ) + +// figure out how to import from the VR API dll +#if defined(_WIN32) + +#ifdef VR_API_EXPORT +#define VR_INTERFACE extern "C" __declspec( dllexport ) +#else +#define VR_INTERFACE extern "C" __declspec( dllimport ) +#endif + +#elif defined(GNUC) || defined(COMPILER_GCC) || defined(__APPLE__) + +#ifdef VR_API_EXPORT +#define VR_INTERFACE extern "C" __attribute__((visibility("default"))) +#else +#define VR_INTERFACE extern "C" +#endif + +#else +#error "Unsupported Platform." +#endif + + +#if defined( _WIN32 ) +#define VR_CALLTYPE __cdecl +#else +#define VR_CALLTYPE +#endif + +} // namespace vr + +#endif // _INCLUDE_VRTYPES_H + + +// vrtrackedcameratypes.h +#ifndef _VRTRACKEDCAMERATYPES_H +#define _VRTRACKEDCAMERATYPES_H + +namespace vr +{ + +#if defined(__linux__) || defined(__APPLE__) + // The 32-bit version of gcc has the alignment requirement for uint64 and double set to + // 4 meaning that even with #pragma pack(8) these types will only be four-byte aligned. + // The 64-bit version of gcc has the alignment requirement for these types set to + // 8 meaning that unless we use #pragma pack(4) our structures will get bigger. + // The 64-bit structure packing has to match the 32-bit structure packing for each platform. + #pragma pack( push, 4 ) +#else + #pragma pack( push, 8 ) +#endif + +enum ECameraVideoStreamFormat +{ + CVS_FORMAT_UNKNOWN = 0, + CVS_FORMAT_RAW10 = 1, // 10 bits per pixel + CVS_FORMAT_NV12 = 2, // 12 bits per pixel + CVS_FORMAT_RGB24 = 3, // 24 bits per pixel + CVS_MAX_FORMATS +}; + +enum ECameraCompatibilityMode +{ + CAMERA_COMPAT_MODE_BULK_DEFAULT = 0, + CAMERA_COMPAT_MODE_BULK_64K_DMA, + CAMERA_COMPAT_MODE_BULK_16K_DMA, + CAMERA_COMPAT_MODE_BULK_8K_DMA, + CAMERA_COMPAT_MODE_ISO_52FPS, + CAMERA_COMPAT_MODE_ISO_50FPS, + CAMERA_COMPAT_MODE_ISO_48FPS, + CAMERA_COMPAT_MODE_ISO_46FPS, + CAMERA_COMPAT_MODE_ISO_44FPS, + CAMERA_COMPAT_MODE_ISO_42FPS, + CAMERA_COMPAT_MODE_ISO_40FPS, + CAMERA_COMPAT_MODE_ISO_35FPS, + CAMERA_COMPAT_MODE_ISO_30FPS, + MAX_CAMERA_COMPAT_MODES +}; + +#ifdef _MSC_VER +#define VR_CAMERA_DECL_ALIGN( x ) __declspec( align( x ) ) +#else +#define VR_CAMERA_DECL_ALIGN( x ) // +#endif + +#define MAX_CAMERA_FRAME_SHARED_HANDLES 4 + +VR_CAMERA_DECL_ALIGN( 8 ) struct CameraVideoStreamFrame_t +{ + ECameraVideoStreamFormat m_nStreamFormat; + + uint32_t m_nWidth; + uint32_t m_nHeight; + + uint32_t m_nImageDataSize; // Based on stream format, width, height + + uint32_t m_nFrameSequence; // Starts from 0 when stream starts. + + uint32_t m_nBufferIndex; // Identifies which buffer the image data is hosted + uint32_t m_nBufferCount; // Total number of configured buffers + + uint32_t m_nExposureTime; + + uint32_t m_nISPFrameTimeStamp; // Driver provided time stamp per driver centric time base + uint32_t m_nISPReferenceTimeStamp; + uint32_t m_nSyncCounter; + + uint32_t m_nCamSyncEvents; + uint32_t m_nISPSyncEvents; + + double m_flReferenceCamSyncTime; + + double m_flFrameElapsedTime; // Starts from 0 when stream starts. In seconds. + double m_flFrameDeliveryRate; + + double m_flFrameCaptureTime_DriverAbsolute; // In USB time, via AuxEvent + double m_flFrameCaptureTime_ServerRelative; // In System time within the server + uint64_t m_nFrameCaptureTicks_ServerAbsolute; // In system ticks within the server + double m_flFrameCaptureTime_ClientRelative; // At the client, relative to when the frame was exposed/captured. + + double m_flSyncMarkerError; + + TrackedDevicePose_t m_StandingTrackedDevicePose; // Supplied by HMD layer when used as a tracked camera + + uint64_t m_pImageData; +}; + +#pragma pack( pop ) + +} + +#endif // _VRTRACKEDCAMERATYPES_H +// ivrsettings.h +namespace vr +{ + enum EVRSettingsError + { + VRSettingsError_None = 0, + VRSettingsError_IPCFailed = 1, + VRSettingsError_WriteFailed = 2, + VRSettingsError_ReadFailed = 3, + }; + + // The maximum length of a settings key + static const uint32_t k_unMaxSettingsKeyLength = 128; + + class IVRSettings + { + public: + virtual const char *GetSettingsErrorNameFromEnum( EVRSettingsError eError ) = 0; + + // Returns true if file sync occurred (force or settings dirty) + virtual bool Sync( bool bForce = false, EVRSettingsError *peError = nullptr ) = 0; + + virtual bool GetBool( const char *pchSection, const char *pchSettingsKey, bool bDefaultValue, EVRSettingsError *peError = nullptr ) = 0; + virtual void SetBool( const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr ) = 0; + virtual int32_t GetInt32( const char *pchSection, const char *pchSettingsKey, int32_t nDefaultValue, EVRSettingsError *peError = nullptr ) = 0; + virtual void SetInt32( const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr ) = 0; + virtual float GetFloat( const char *pchSection, const char *pchSettingsKey, float flDefaultValue, EVRSettingsError *peError = nullptr ) = 0; + virtual void SetFloat( const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr ) = 0; + virtual void GetString( const char *pchSection, const char *pchSettingsKey, char *pchValue, uint32_t unValueLen, const char *pchDefaultValue, EVRSettingsError *peError = nullptr ) = 0; + virtual void SetString( const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr ) = 0; + + virtual void RemoveSection( const char *pchSection, EVRSettingsError *peError = nullptr ) = 0; + virtual void RemoveKeyInSection( const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr ) = 0; + }; + + //----------------------------------------------------------------------------- + static const char * const IVRSettings_Version = "IVRSettings_001"; + + //----------------------------------------------------------------------------- + // steamvr keys + + static const char * const k_pch_SteamVR_Section = "steamvr"; + static const char * const k_pch_SteamVR_RequireHmd_String = "requireHmd"; + static const char * const k_pch_SteamVR_ForcedDriverKey_String = "forcedDriver"; + static const char * const k_pch_SteamVR_ForcedHmdKey_String = "forcedHmd"; + static const char * const k_pch_SteamVR_DisplayDebug_Bool = "displayDebug"; + static const char * const k_pch_SteamVR_DebugProcessPipe_String = "debugProcessPipe"; + static const char * const k_pch_SteamVR_EnableDistortion_Bool = "enableDistortion"; + static const char * const k_pch_SteamVR_DisplayDebugX_Int32 = "displayDebugX"; + static const char * const k_pch_SteamVR_DisplayDebugY_Int32 = "displayDebugY"; + static const char * const k_pch_SteamVR_SendSystemButtonToAllApps_Bool= "sendSystemButtonToAllApps"; + static const char * const k_pch_SteamVR_LogLevel_Int32 = "loglevel"; + static const char * const k_pch_SteamVR_IPD_Float = "ipd"; + static const char * const k_pch_SteamVR_Background_String = "background"; + static const char * const k_pch_SteamVR_BackgroundCameraHeight_Float = "backgroundCameraHeight"; + static const char * const k_pch_SteamVR_BackgroundDomeRadius_Float = "backgroundDomeRadius"; + static const char * const k_pch_SteamVR_Environment_String = "environment"; + static const char * const k_pch_SteamVR_GridColor_String = "gridColor"; + static const char * const k_pch_SteamVR_PlayAreaColor_String = "playAreaColor"; + static const char * const k_pch_SteamVR_ShowStage_Bool = "showStage"; + static const char * const k_pch_SteamVR_ActivateMultipleDrivers_Bool = "activateMultipleDrivers"; + static const char * const k_pch_SteamVR_PowerOffOnExit_Bool = "powerOffOnExit"; + static const char * const k_pch_SteamVR_StandbyAppRunningTimeout_Float = "standbyAppRunningTimeout"; + static const char * const k_pch_SteamVR_StandbyNoAppTimeout_Float = "standbyNoAppTimeout"; + static const char * const k_pch_SteamVR_DirectMode_Bool = "directMode"; + static const char * const k_pch_SteamVR_DirectModeEdidVid_Int32 = "directModeEdidVid"; + static const char * const k_pch_SteamVR_DirectModeEdidPid_Int32 = "directModeEdidPid"; + static const char * const k_pch_SteamVR_UsingSpeakers_Bool = "usingSpeakers"; + static const char * const k_pch_SteamVR_SpeakersForwardYawOffsetDegrees_Float = "speakersForwardYawOffsetDegrees"; + static const char * const k_pch_SteamVR_BaseStationPowerManagement_Bool = "basestationPowerManagement"; + static const char * const k_pch_SteamVR_NeverKillProcesses_Bool = "neverKillProcesses"; + static const char * const k_pch_SteamVR_RenderTargetMultiplier_Float = "renderTargetMultiplier"; + static const char * const k_pch_SteamVR_AllowReprojection_Bool = "allowReprojection"; + static const char * const k_pch_SteamVR_ForceReprojection_Bool = "forceReprojection"; + static const char * const k_pch_SteamVR_ForceFadeOnBadTracking_Bool = "forceFadeOnBadTracking"; + static const char * const k_pch_SteamVR_DefaultMirrorView_Int32 = "defaultMirrorView"; + static const char * const k_pch_SteamVR_ShowMirrorView_Bool = "showMirrorView"; + + //----------------------------------------------------------------------------- + // lighthouse keys + + static const char * const k_pch_Lighthouse_Section = "driver_lighthouse"; + static const char * const k_pch_Lighthouse_DisableIMU_Bool = "disableimu"; + static const char * const k_pch_Lighthouse_UseDisambiguation_String = "usedisambiguation"; + static const char * const k_pch_Lighthouse_DisambiguationDebug_Int32 = "disambiguationdebug"; + + static const char * const k_pch_Lighthouse_PrimaryBasestation_Int32 = "primarybasestation"; + static const char * const k_pch_Lighthouse_LighthouseName_String = "lighthousename"; + static const char * const k_pch_Lighthouse_MaxIncidenceAngleDegrees_Float = "maxincidenceangledegrees"; + static const char * const k_pch_Lighthouse_UseLighthouseDirect_Bool = "uselighthousedirect"; + static const char * const k_pch_Lighthouse_DBHistory_Bool = "dbhistory"; + + //----------------------------------------------------------------------------- + // null keys + + static const char * const k_pch_Null_Section = "driver_null"; + static const char * const k_pch_Null_EnableNullDriver_Bool = "enable"; + static const char * const k_pch_Null_SerialNumber_String = "serialNumber"; + static const char * const k_pch_Null_ModelNumber_String = "modelNumber"; + static const char * const k_pch_Null_WindowX_Int32 = "windowX"; + static const char * const k_pch_Null_WindowY_Int32 = "windowY"; + static const char * const k_pch_Null_WindowWidth_Int32 = "windowWidth"; + static const char * const k_pch_Null_WindowHeight_Int32 = "windowHeight"; + static const char * const k_pch_Null_RenderWidth_Int32 = "renderWidth"; + static const char * const k_pch_Null_RenderHeight_Int32 = "renderHeight"; + static const char * const k_pch_Null_SecondsFromVsyncToPhotons_Float = "secondsFromVsyncToPhotons"; + static const char * const k_pch_Null_DisplayFrequency_Float = "displayFrequency"; + + //----------------------------------------------------------------------------- + // user interface keys + static const char * const k_pch_UserInterface_Section = "userinterface"; + static const char * const k_pch_UserInterface_StatusAlwaysOnTop_Bool = "StatusAlwaysOnTop"; + static const char * const k_pch_UserInterface_EnableScreenshots_Bool = "EnableScreenshots"; + + //----------------------------------------------------------------------------- + // notification keys + static const char * const k_pch_Notifications_Section = "notifications"; + static const char * const k_pch_Notifications_DoNotDisturb_Bool = "DoNotDisturb"; + + //----------------------------------------------------------------------------- + // keyboard keys + static const char * const k_pch_Keyboard_Section = "keyboard"; + static const char * const k_pch_Keyboard_TutorialCompletions = "TutorialCompletions"; + static const char * const k_pch_Keyboard_ScaleX = "ScaleX"; + static const char * const k_pch_Keyboard_ScaleY = "ScaleY"; + static const char * const k_pch_Keyboard_OffsetLeftX = "OffsetLeftX"; + static const char * const k_pch_Keyboard_OffsetRightX = "OffsetRightX"; + static const char * const k_pch_Keyboard_OffsetY = "OffsetY"; + static const char * const k_pch_Keyboard_Smoothing = "Smoothing"; + + //----------------------------------------------------------------------------- + // perf keys + static const char * const k_pch_Perf_Section = "perfcheck"; + static const char * const k_pch_Perf_HeuristicActive_Bool = "heuristicActive"; + static const char * const k_pch_Perf_NotifyInHMD_Bool = "warnInHMD"; + static const char * const k_pch_Perf_NotifyOnlyOnce_Bool = "warnOnlyOnce"; + static const char * const k_pch_Perf_AllowTimingStore_Bool = "allowTimingStore"; + static const char * const k_pch_Perf_SaveTimingsOnExit_Bool = "saveTimingsOnExit"; + static const char * const k_pch_Perf_TestData_Float = "perfTestData"; + + //----------------------------------------------------------------------------- + // collision bounds keys + static const char * const k_pch_CollisionBounds_Section = "collisionBounds"; + static const char * const k_pch_CollisionBounds_Style_Int32 = "CollisionBoundsStyle"; + static const char * const k_pch_CollisionBounds_GroundPerimeterOn_Bool = "CollisionBoundsGroundPerimeterOn"; + static const char * const k_pch_CollisionBounds_CenterMarkerOn_Bool = "CollisionBoundsCenterMarkerOn"; + static const char * const k_pch_CollisionBounds_PlaySpaceOn_Bool = "CollisionBoundsPlaySpaceOn"; + static const char * const k_pch_CollisionBounds_FadeDistance_Float = "CollisionBoundsFadeDistance"; + static const char * const k_pch_CollisionBounds_ColorGammaR_Int32 = "CollisionBoundsColorGammaR"; + static const char * const k_pch_CollisionBounds_ColorGammaG_Int32 = "CollisionBoundsColorGammaG"; + static const char * const k_pch_CollisionBounds_ColorGammaB_Int32 = "CollisionBoundsColorGammaB"; + static const char * const k_pch_CollisionBounds_ColorGammaA_Int32 = "CollisionBoundsColorGammaA"; + + //----------------------------------------------------------------------------- + // camera keys + static const char * const k_pch_Camera_Section = "camera"; + static const char * const k_pch_Camera_EnableCamera_Bool = "enableCamera"; + static const char * const k_pch_Camera_EnableCameraInDashboard_Bool = "enableCameraInDashboard"; + static const char * const k_pch_Camera_EnableCameraForCollisionBounds_Bool = "enableCameraForCollisionBounds"; + static const char * const k_pch_Camera_EnableCameraForRoomView_Bool = "enableCameraForRoomView"; + static const char * const k_pch_Camera_BoundsColorGammaR_Int32 = "cameraBoundsColorGammaR"; + static const char * const k_pch_Camera_BoundsColorGammaG_Int32 = "cameraBoundsColorGammaG"; + static const char * const k_pch_Camera_BoundsColorGammaB_Int32 = "cameraBoundsColorGammaB"; + static const char * const k_pch_Camera_BoundsColorGammaA_Int32 = "cameraBoundsColorGammaA"; + + //----------------------------------------------------------------------------- + // audio keys + static const char * const k_pch_audio_Section = "audio"; + static const char * const k_pch_audio_OnPlaybackDevice_String = "onPlaybackDevice"; + static const char * const k_pch_audio_OnRecordDevice_String = "onRecordDevice"; + static const char * const k_pch_audio_OnPlaybackMirrorDevice_String = "onPlaybackMirrorDevice"; + static const char * const k_pch_audio_OffPlaybackDevice_String = "offPlaybackDevice"; + static const char * const k_pch_audio_OffRecordDevice_String = "offRecordDevice"; + static const char * const k_pch_audio_VIVEHDMIGain = "viveHDMIGain"; + + //----------------------------------------------------------------------------- + // model skin keys + static const char * const k_pch_modelskin_Section = "modelskins"; + +} // namespace vr + +// iservertrackeddevicedriver.h +namespace vr +{ + + +struct DriverPoseQuaternion_t +{ + double w, x, y, z; +}; + +struct DriverPose_t +{ + /* Time offset of this pose, in seconds from the actual time of the pose, + * relative to the time of the PoseUpdated() call made by the driver. + */ + double poseTimeOffset; + + /* Generally, the pose maintained by a driver + * is in an inertial coordinate system different + * from the world system of x+ right, y+ up, z+ back. + * Also, the driver is not usually tracking the "head" position, + * but instead an internal IMU or another reference point in the HMD. + * The following two transforms transform positions and orientations + * to app world space from driver world space, + * and to HMD head space from driver local body space. + * + * We maintain the driver pose state in its internal coordinate system, + * so we can do the pose prediction math without having to + * use angular acceleration. A driver's angular acceleration is generally not measured, + * and is instead calculated from successive samples of angular velocity. + * This leads to a noisy angular acceleration values, which are also + * lagged due to the filtering required to reduce noise to an acceptable level. + */ + vr::HmdQuaternion_t qWorldFromDriverRotation; + double vecWorldFromDriverTranslation[ 3 ]; + + vr::HmdQuaternion_t qDriverFromHeadRotation; + double vecDriverFromHeadTranslation[ 3 ]; + + /* State of driver pose, in meters and radians. */ + /* Position of the driver tracking reference in driver world space + * +[0] (x) is right + * +[1] (y) is up + * -[2] (z) is forward + */ + double vecPosition[ 3 ]; + + /* Velocity of the pose in meters/second */ + double vecVelocity[ 3 ]; + + /* Acceleration of the pose in meters/second */ + double vecAcceleration[ 3 ]; + + /* Orientation of the tracker, represented as a quaternion */ + vr::HmdQuaternion_t qRotation; + + /* Angular velocity of the pose in axis-angle + * representation. The direction is the angle of + * rotation and the magnitude is the angle around + * that axis in radians/second. */ + double vecAngularVelocity[ 3 ]; + + /* Angular acceleration of the pose in axis-angle + * representation. The direction is the angle of + * rotation and the magnitude is the angle around + * that axis in radians/second^2. */ + double vecAngularAcceleration[ 3 ]; + + ETrackingResult result; + + bool poseIsValid; + bool willDriftInYaw; + bool shouldApplyHeadModel; + bool deviceIsConnected; +}; + + +// ---------------------------------------------------------------------------------------------- +// Purpose: Represents a single tracked device in a driver +// ---------------------------------------------------------------------------------------------- +class ITrackedDeviceServerDriver +{ +public: + + // ------------------------------------ + // Management Methods + // ------------------------------------ + /** This is called before an HMD is returned to the application. It will always be + * called before any display or tracking methods. Memory and processor use by the + * ITrackedDeviceServerDriver object should be kept to a minimum until it is activated. + * The pose listener is guaranteed to be valid until Deactivate is called, but + * should not be used after that point. */ + virtual EVRInitError Activate( uint32_t unObjectId ) = 0; + + /** This is called when The VR system is switching from this Hmd being the active display + * to another Hmd being the active display. The driver should clean whatever memory + * and thread use it can when it is deactivated */ + virtual void Deactivate() = 0; + + /** Handles a request from the system to power off this device */ + virtual void PowerOff() = 0; + + /** Requests a component interface of the driver for device-specific functionality. The driver should return NULL + * if the requested interface or version is not supported. */ + virtual void *GetComponent( const char *pchComponentNameAndVersion ) = 0; + + /** A VR Client has made this debug request of the driver. The set of valid requests is entirely + * up to the driver and the client to figure out, as is the format of the response. Responses that + * exceed the length of the supplied buffer should be truncated and null terminated */ + virtual void DebugRequest( const char *pchRequest, char *pchResponseBuffer, uint32_t unResponseBufferSize ) = 0; + + // ------------------------------------ + // Tracking Methods + // ------------------------------------ + virtual DriverPose_t GetPose() = 0; + + // ------------------------------------ + // Property Methods + // ------------------------------------ + + /** Returns a bool property. If the property is not available this function will return false. */ + virtual bool GetBoolTrackedDeviceProperty( ETrackedDeviceProperty prop, ETrackedPropertyError *pError ) = 0; + + /** Returns a float property. If the property is not available this function will return 0. */ + virtual float GetFloatTrackedDeviceProperty( ETrackedDeviceProperty prop, ETrackedPropertyError *pError ) = 0; + + /** Returns an int property. If the property is not available this function will return 0. */ + virtual int32_t GetInt32TrackedDeviceProperty( ETrackedDeviceProperty prop, ETrackedPropertyError *pError ) = 0; + + /** Returns a uint64 property. If the property is not available this function will return 0. */ + virtual uint64_t GetUint64TrackedDeviceProperty( ETrackedDeviceProperty prop, ETrackedPropertyError *pError ) = 0; + + /** Returns a matrix property. If the device index is not valid or the property is not a matrix type, this function will return identity. */ + virtual HmdMatrix34_t GetMatrix34TrackedDeviceProperty( ETrackedDeviceProperty prop, ETrackedPropertyError *pError ) = 0; + + /** Returns a string property. If the property is not available this function will return 0 and pError will be + * set to an error. Otherwise it returns the length of the number of bytes necessary to hold this string including + * the trailing null. If the buffer is too small the error will be TrackedProp_BufferTooSmall. Strings will + * generally fit in buffers of k_unTrackingStringSize characters. Drivers may not return strings longer than + * k_unMaxPropertyStringSize. */ + virtual uint32_t GetStringTrackedDeviceProperty( ETrackedDeviceProperty prop, char *pchValue, uint32_t unBufferSize, ETrackedPropertyError *pError ) = 0; + +}; + + + +static const char *ITrackedDeviceServerDriver_Version = "ITrackedDeviceServerDriver_004"; + +} +// ivrdisplaycomponent.h +namespace vr +{ + + + // ---------------------------------------------------------------------------------------------- + // Purpose: The display component on a single tracked device + // ---------------------------------------------------------------------------------------------- + class IVRDisplayComponent + { + public: + + // ------------------------------------ + // Display Methods + // ------------------------------------ + + /** Size and position that the window needs to be on the VR display. */ + virtual void GetWindowBounds( int32_t *pnX, int32_t *pnY, uint32_t *pnWidth, uint32_t *pnHeight ) = 0; + + /** Returns true if the display is extending the desktop. */ + virtual bool IsDisplayOnDesktop( ) = 0; + + /** Returns true if the display is real and not a fictional display. */ + virtual bool IsDisplayRealDisplay( ) = 0; + + /** Suggested size for the intermediate render target that the distortion pulls from. */ + virtual void GetRecommendedRenderTargetSize( uint32_t *pnWidth, uint32_t *pnHeight ) = 0; + + /** Gets the viewport in the frame buffer to draw the output of the distortion into */ + virtual void GetEyeOutputViewport( EVREye eEye, uint32_t *pnX, uint32_t *pnY, uint32_t *pnWidth, uint32_t *pnHeight ) = 0; + + /** The components necessary to build your own projection matrix in case your + * application is doing something fancy like infinite Z */ + virtual void GetProjectionRaw( EVREye eEye, float *pfLeft, float *pfRight, float *pfTop, float *pfBottom ) = 0; + + /** Returns the result of the distortion function for the specified eye and input UVs. UVs go from 0,0 in + * the upper left of that eye's viewport and 1,1 in the lower right of that eye's viewport. */ + virtual DistortionCoordinates_t ComputeDistortion( EVREye eEye, float fU, float fV ) = 0; + + }; + + static const char *IVRDisplayComponent_Version = "IVRDisplayComponent_002"; + +} + +// ivrdriverdirectmodecomponent.h +namespace vr +{ + + + // ---------------------------------------------------------------------------------------------- + // Purpose: This component is used for drivers that implement direct mode entirely on their own + // without allowing the VR Compositor to own the window/device. Chances are you don't + // need to implement this component in your driver. + // ---------------------------------------------------------------------------------------------- + class IVRDriverDirectModeComponent + { + public: + + // ----------------------------------- + // Direct mode methods + // ----------------------------------- + + /** Specific to Oculus compositor support, textures supplied must be created using this method. */ + virtual void CreateSwapTextureSet( uint32_t unPid, uint32_t unFormat, uint32_t unWidth, uint32_t unHeight, void *(*pSharedTextureHandles)[3] ) {} + + /** Used to textures created using CreateSwapTextureSet. Only one of the set's handles needs to be used to destroy the entire set. */ + virtual void DestroySwapTextureSet( void *pSharedTextureHandle ) {} + + /** Used to purge all texture sets for a given process. */ + virtual void DestroyAllSwapTextureSets( uint32_t unPid ) {} + + /** After Present returns, calls this to get the next index to use for rendering. */ + virtual void GetNextSwapTextureSetIndex( void *pSharedTextureHandles[ 2 ], uint32_t( *pIndices )[ 2 ] ) {} + + /** Call once per layer to draw for this frame. One shared texture handle per eye. Textures must be created + * using CreateSwapTextureSet and should be alternated per frame. Call Present once all layers have been submitted. */ + virtual void SubmitLayer( void *pSharedTextureHandles[ 2 ], const vr::VRTextureBounds_t( &bounds )[ 2 ], const vr::HmdMatrix34_t *pPose ) {} + + /** Submits queued layers for display. */ + virtual void Present( void *hSyncTexture ) {} + + }; + + static const char *IVRDriverDirectModeComponent_Version = "IVRDriverDirectModeComponent_001"; + +} + +// ivrcontrollercomponent.h +namespace vr +{ + + + // ---------------------------------------------------------------------------------------------- + // Purpose: Controller access on a single tracked device. + // ---------------------------------------------------------------------------------------------- + class IVRControllerComponent + { + public: + + // ------------------------------------ + // Controller Methods + // ------------------------------------ + + /** Gets the current state of a controller. */ + virtual VRControllerState_t GetControllerState( ) = 0; + + /** Returns a uint64 property. If the property is not available this function will return 0. */ + virtual bool TriggerHapticPulse( uint32_t unAxisId, uint16_t usPulseDurationMicroseconds ) = 0; + + }; + + + + static const char *IVRControllerComponent_Version = "IVRControllerComponent_001"; + +} +// ivrcameracomponent.h +namespace vr +{ + + //----------------------------------------------------------------------------- + //----------------------------------------------------------------------------- + class ICameraVideoSinkCallback + { + public: + virtual void OnCameraVideoSinkCallback() = 0; + }; + + // ---------------------------------------------------------------------------------------------- + // Purpose: The camera on a single tracked device + // ---------------------------------------------------------------------------------------------- + class IVRCameraComponent + { + public: + // ------------------------------------ + // Camera Methods + // ------------------------------------ + virtual bool HasCamera() = 0; + virtual bool GetCameraFirmwareDescription( char *pBuffer, uint32_t nBufferLen ) = 0; + virtual bool GetCameraFrameDimensions( vr::ECameraVideoStreamFormat nVideoStreamFormat, uint32_t *pWidth, uint32_t *pHeight ) = 0; + virtual bool GetCameraFrameBufferingRequirements( int *pDefaultFrameQueueSize, uint32_t *pFrameBufferDataSize ) = 0; + virtual bool SetCameraFrameBuffering( int nFrameBufferCount, void **ppFrameBuffers, uint32_t nFrameBufferDataSize ) = 0; + virtual bool SetCameraVideoStreamFormat( vr::ECameraVideoStreamFormat nVideoStreamFormat ) = 0; + virtual vr::ECameraVideoStreamFormat GetCameraVideoStreamFormat() = 0; + virtual bool StartVideoStream() = 0; + virtual void StopVideoStream() = 0; + virtual bool IsVideoStreamActive() = 0; + virtual float GetVideoStreamElapsedTime() = 0; + virtual const vr::CameraVideoStreamFrame_t *GetVideoStreamFrame() = 0; + virtual void ReleaseVideoStreamFrame( const vr::CameraVideoStreamFrame_t *pFrameImage ) = 0; + virtual bool SetAutoExposure( bool bEnable ) = 0; + virtual bool PauseVideoStream() = 0; + virtual bool ResumeVideoStream() = 0; + virtual bool IsVideoStreamPaused() = 0; + virtual bool GetCameraDistortion( float flInputU, float flInputV, float *pflOutputU, float *pflOutputV ) = 0; + virtual bool GetCameraProjection( float flWidthPixels, float flHeightPixels, float flZNear, float flZFar, vr::HmdMatrix44_t *pProjection ) = 0; + virtual bool GetRecommendedCameraUndistortion( uint32_t *pUndistortionWidthPixels, uint32_t *pUndistortionHeightPixels ) = 0; + virtual bool SetCameraUndistortion( uint32_t nUndistortionWidthPixels, uint32_t nUndistortionHeightPixels ) = 0; + virtual bool GetCameraFirmwareVersion( uint64_t *pFirmwareVersion ) = 0; + virtual bool SetFrameRate( int nISPFrameRate, int nSensorFrameRate ) = 0; + virtual bool SetCameraVideoSinkCallback( vr::ICameraVideoSinkCallback *pCameraVideoSinkCallback ) = 0; + virtual bool GetCameraCompatibilityMode( vr::ECameraCompatibilityMode *pCameraCompatibilityMode ) = 0; + virtual bool SetCameraCompatibilityMode( vr::ECameraCompatibilityMode nCameraCompatibilityMode ) = 0; + virtual bool GetCameraFrameBounds( vr::EVRTrackedCameraFrameType eFrameType, uint32_t *pLeft, uint32_t *pTop, uint32_t *pWidth, uint32_t *pHeight ) = 0; + virtual bool GetCameraIntrinsics( vr::EVRTrackedCameraFrameType eFrameType, HmdVector2_t *pFocalLength, HmdVector2_t *pCenter ) = 0; + }; + + static const char *IVRCameraComponent_Version = "IVRCameraComponent_001"; +} +// itrackeddevicedriverprovider.h +namespace vr +{ + +class ITrackedDeviceServerDriver; +struct TrackedDeviceDriverInfo_t; +struct DriverPose_t; + +class IDriverLog +{ +public: + /** Writes a log message to the log file prefixed with the driver name */ + virtual void Log( const char *pchLogMessage ) = 0; +}; + +/** This interface is provided by vrserver to allow the driver to notify +* the system when something changes about a device. These changes must +* not change the serial number or class of the device because those values +* are permanently associated with the device's index. */ +class IServerDriverHost +{ +public: + /** Notifies the server that a tracked device has been added. If this function returns true + * the server will call Activate on the device. If it returns false some kind of error + * has occurred and the device will not be activated. */ + virtual bool TrackedDeviceAdded( const char *pchDeviceSerialNumber ) = 0; + + /** Notifies the server that a tracked device's pose has been updated */ + virtual void TrackedDevicePoseUpdated( uint32_t unWhichDevice, const DriverPose_t & newPose ) = 0; + + /** Notifies the server that the property cache for the specified device should be invalidated */ + virtual void TrackedDevicePropertiesChanged( uint32_t unWhichDevice ) = 0; + + /** Notifies the server that vsync has occurred on the the display attached to the device. This is + * only permitted on devices of the HMD class. */ + virtual void VsyncEvent( double vsyncTimeOffsetSeconds ) = 0; + + /** notifies the server that the button was pressed */ + virtual void TrackedDeviceButtonPressed( uint32_t unWhichDevice, EVRButtonId eButtonId, double eventTimeOffset ) = 0; + + /** notifies the server that the button was unpressed */ + virtual void TrackedDeviceButtonUnpressed( uint32_t unWhichDevice, EVRButtonId eButtonId, double eventTimeOffset ) = 0; + + /** notifies the server that the button was pressed */ + virtual void TrackedDeviceButtonTouched( uint32_t unWhichDevice, EVRButtonId eButtonId, double eventTimeOffset ) = 0; + + /** notifies the server that the button was unpressed */ + virtual void TrackedDeviceButtonUntouched( uint32_t unWhichDevice, EVRButtonId eButtonId, double eventTimeOffset ) = 0; + + /** notifies the server than a controller axis changed */ + virtual void TrackedDeviceAxisUpdated( uint32_t unWhichDevice, uint32_t unWhichAxis, const VRControllerAxis_t & axisState ) = 0; + + /** Notifies the server that the MC image has been updated for the display attached to the device. This is + * only permitted on devices of the HMD class. */ + virtual void MCImageUpdated() = 0; + + /** always returns a pointer to a valid interface pointer of IVRSettings */ + virtual IVRSettings *GetSettings( const char *pchInterfaceVersion ) = 0; + + /** Notifies the server that the physical IPD adjustment has been moved on the HMD */ + virtual void PhysicalIpdSet( uint32_t unWhichDevice, float fPhysicalIpdMeters ) = 0; + + /** Notifies the server that the proximity sensor on the specified device */ + virtual void ProximitySensorState( uint32_t unWhichDevice, bool bProximitySensorTriggered ) = 0; + + /** Sends a vendor specific event (VREvent_VendorSpecific_Reserved_Start..VREvent_VendorSpecific_Reserved_End */ + virtual void VendorSpecificEvent( uint32_t unWhichDevice, vr::EVREventType eventType, const VREvent_Data_t & eventData, double eventTimeOffset ) = 0; + + /** Returns true if SteamVR is exiting */ + virtual bool IsExiting() = 0; +}; + + +/** This interface must be implemented in each driver. It will be loaded in vrserver.exe */ +class IServerTrackedDeviceProvider +{ +public: + /** initializes the driver. This will be called before any other methods are called. + * If Init returns anything other than VRInitError_None the driver DLL will be unloaded. + * + * pDriverHost will never be NULL, and will always be a pointer to a IServerDriverHost interface + * + * pchUserDriverConfigDir - The absolute path of the directory where the driver should store user + * config files. + * pchDriverInstallDir - The absolute path of the root directory for the driver. + */ + virtual EVRInitError Init( IDriverLog *pDriverLog, vr::IServerDriverHost *pDriverHost, const char *pchUserDriverConfigDir, const char *pchDriverInstallDir ) = 0; + + /** cleans up the driver right before it is unloaded */ + virtual void Cleanup() = 0; + + /** Returns the version of the ITrackedDeviceServerDriver interface used by this driver */ + virtual const char * const *GetInterfaceVersions() = 0; + + /** returns the number of HMDs that this driver manages that are physically connected. */ + virtual uint32_t GetTrackedDeviceCount() = 0; + + /** returns a single HMD */ + virtual ITrackedDeviceServerDriver *GetTrackedDeviceDriver( uint32_t unWhich ) = 0; + + /** returns a single HMD by ID */ + virtual ITrackedDeviceServerDriver* FindTrackedDeviceDriver( const char *pchId ) = 0; + + /** Allows the driver do to some work in the main loop of the server. */ + virtual void RunFrame() = 0; + + + // ------------ Power State Functions ----------------------- // + + /** Returns true if the driver wants to block Standby mode. */ + virtual bool ShouldBlockStandbyMode() = 0; + + /** Called when the system is entering Standby mode. The driver should switch itself into whatever sort of low-power + * state it has. */ + virtual void EnterStandby() = 0; + + /** Called when the system is leaving Standby mode. The driver should switch itself back to + full operation. */ + virtual void LeaveStandby() = 0; + +}; + + +static const char *IServerTrackedDeviceProvider_Version = "IServerTrackedDeviceProvider_003"; + + +/** This interface is provided by vrclient to allow the driver call back and query various information */ +class IClientDriverHost +{ +public: + /** Returns the device class of a tracked device. If there has not been a device connected in this slot + * since the application started this function will return TrackedDevice_Invalid. For previous detected + * devices the function will return the previously observed device class. + * + * To determine which devices exist on the system, just loop from 0 to k_unMaxTrackedDeviceCount and check + * the device class. Every device with something other than TrackedDevice_Invalid is associated with an + * actual tracked device. */ + virtual ETrackedDeviceClass GetTrackedDeviceClass( vr::TrackedDeviceIndex_t unDeviceIndex ) = 0; + + /** Returns true if there is a device connected in this slot. */ + virtual bool IsTrackedDeviceConnected( vr::TrackedDeviceIndex_t unDeviceIndex ) = 0; + + /** Returns a bool property. If the device index is not valid or the property is not a bool type this function will return false. */ + virtual bool GetBoolTrackedDeviceProperty( vr::TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError *pError = 0L ) = 0; + + /** Returns a float property. If the device index is not valid or the property is not a float type this function will return 0. */ + virtual float GetFloatTrackedDeviceProperty( vr::TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError *pError = 0L ) = 0; + + /** Returns an int property. If the device index is not valid or the property is not a int type this function will return 0. */ + virtual int32_t GetInt32TrackedDeviceProperty( vr::TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError *pError = 0L ) = 0; + + /** Returns a uint64 property. If the device index is not valid or the property is not a uint64 type this function will return 0. */ + virtual uint64_t GetUint64TrackedDeviceProperty( vr::TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, ETrackedPropertyError *pError = 0L ) = 0; + + /** Returns a string property. If the device index is not valid or the property is not a float type this function will + * return 0. Otherwise it returns the length of the number of bytes necessary to hold this string including the trailing + * null. Strings will generally fit in buffers of k_unTrackingStringSize characters. */ + virtual uint32_t GetStringTrackedDeviceProperty( vr::TrackedDeviceIndex_t unDeviceIndex, ETrackedDeviceProperty prop, char *pchValue, uint32_t unBufferSize, ETrackedPropertyError *pError = 0L ) = 0; + + /** always returns a pointer to a valid interface pointer of IVRSettings */ + virtual IVRSettings *GetSettings( const char *pchInterfaceVersion ) = 0; +}; + + + +/** This interface must be implemented in each driver. It will be loaded in vrclient.dll */ +class IClientTrackedDeviceProvider +{ +public: + /** initializes the driver. This will be called before any other methods are called, + * except BIsHmdPresent(). BIsHmdPresent is called outside of the Init/Cleanup pair. + * If Init returns anything other than VRInitError_None the driver DLL will be unloaded. + * + * pDriverHost will never be NULL, and will always be a pointer to a IClientDriverHost interface + * + * pchUserDriverConfigDir - The absolute path of the directory where the driver should store user + * config files. + * pchDriverInstallDir - The absolute path of the root directory for the driver. + */ + virtual EVRInitError Init( IDriverLog *pDriverLog, vr::IClientDriverHost *pDriverHost, const char *pchUserDriverConfigDir, const char *pchDriverInstallDir ) = 0; + + /** cleans up the driver right before it is unloaded */ + virtual void Cleanup() = 0; + + /** Called when the client needs to inform an application if an HMD is attached that uses + * this driver. This method should be as lightweight as possible and should have no side effects + * such as hooking process functions or leaving resources loaded. Init will not be called before + * this method and Cleanup will not be called after it. + */ + virtual bool BIsHmdPresent( const char *pchUserConfigDir ) = 0; + + /** called when the client inits an HMD to let the client driver know which one is in use */ + virtual EVRInitError SetDisplayId( const char *pchDisplayId ) = 0; + + /** Returns the stencil mesh information for the current HMD. If this HMD does not have a stencil mesh the vertex data and count will be + * NULL and 0 respectively. This mesh is meant to be rendered into the stencil buffer (or into the depth buffer setting nearz) before rendering + * each eye's view. The pixels covered by this mesh will never be seen by the user after the lens distortion is applied and based on visibility to the panels. + * This will improve perf by letting the GPU early-reject pixels the user will never see before running the pixel shader. + * NOTE: Render this mesh with backface culling disabled since the winding order of the vertices can be different per-HMD or per-eye. + */ + virtual HiddenAreaMesh_t GetHiddenAreaMesh( EVREye eEye ) = 0; + + /** Get the MC image for the current HMD. + * Returns the size in bytes of the buffer required to hold the specified resource. */ + virtual uint32_t GetMCImage( uint32_t *pImgWidth, uint32_t *pImgHeight, uint32_t *pChannels, void *pDataBuffer, uint32_t unBufferLen ) = 0; +}; + +static const char *IClientTrackedDeviceProvider_Version = "IClientTrackedDeviceProvider_003"; + +} + + + + +namespace vr +{ + static const char * const k_InterfaceVersions[] = + { + IVRSettings_Version, + ITrackedDeviceServerDriver_Version, + IVRDisplayComponent_Version, + IVRDriverDirectModeComponent_Version, + IVRControllerComponent_Version, + IVRCameraComponent_Version, + IServerTrackedDeviceProvider_Version, + IClientTrackedDeviceProvider_Version, + nullptr + }; +} +// End + +#endif // _OPENVR_DRIVER_API + + diff --git a/examples/ThirdPartyLibs/openvr/lib/linux32/libopenvr_api.so b/examples/ThirdPartyLibs/openvr/lib/linux32/libopenvr_api.so new file mode 100644 index 0000000000000000000000000000000000000000..27da01cbe12da068abb542b1641702ce6eca95e6 GIT binary patch literal 2315918 zcmce94|r6?)&5#q^>`ZR46;NHP!N!2JVRU4oU)6UV(l6sS# zaO)=tl8z#htVz9;eT{OYJp(jtd8&r?Mtwhkv~Yr!w%NVWY*<; zqL(HoCTM0_f10K-nf2GB9^^3}JO32a_D8zv+5+wPs#AYIx#qS{zZ+8b*MI+MRnqy{ z-ib3>lFMA-~&h-Q9q4@_?!fMG19e2n}MH) z^djj6nV}Aiq%smjITd>`q1VF7Q{79s{1K zXjUQr2og#DjC3wC_aNPjG#=@Hke)($4d76uPUI&8J_GmyQVR0?Tnbo?v>JII;1;AO zknEpZ6oIW~5V)8j=17WhWzDi2O{XSCMxCu0}cy=_w?x-v^QS zc?mc_^8q&_U4b+aX${g(kQN{{AmxIl0Pt&}*0i4?&(8|LsYw4tz6z-X`K79k^)1N% z0;wGNWLx=io`5$Jz2nnoT@RgLG9-pZkCLoS_{NLb-)``{$~oBU=T9JCUOXPI_iFfbd;j`WgOaClqDghAsrK^o<*0c^7(+bA#Fms z8)*fS{j%v%mp=4*UzGzaYJXv>xd_B=fTdnLi-Cf#gFv3+YRw>yh~REz%UE ze<0n0G!JPB(wj&}!B5-=H~?@r;HgOF=OUH)HDIdB{~hpsm0zad5VYNod=JuyG}Xxa&Y|3;dObPCc{sCyZ(8p-_JuQC;Y zC!qdQg-=3011SJ}F47d_`DsBq9r-rFtbeDX>_eb8BVD12&#|htQq=o_AFKF0hx`vn z?TTiSf-eI0Lz;!uAGBdrJ`(vqA>V;C9cc{kWA zwhmdpj}BaYh&PTfF(c;mkBr6#USi>AA$x*@UvMDoWQ7r%4Tgt%#S|E{gfL#Onwm--WX|rjP{eW!5>D)zDXZ&!{)J|Pf_?LEWV6i8#c%KE)XVz z{!CSWQ93f}!~Xx5dc4bs&q=@QG}sX)=Oh#puXl{^J%@bHU#yr3J#5IKujLN<9T2n* z4lP6RXZ)AiVD(?+n6FhQ<67roW3Qt;`-g%a#yU>5PjbxPKZm12eK@}3PRDf|#&a$5 zZ2!)AW-YFTknM2Dztz@1>qGs~K4AC`wx8)}|7Q@@Jz&I%tp7X4)6!^-=h766^%qwA z$8G#6-y_gR2J~T$rvw{z#zWTpy$GVFwbuOo2L0urKXX1WhCSsxYt8>iROCEm>8lY= zu;rIl|AQR;pK>(j8;gr-qx>gQo=1=r-v4}L)Q9q334Js}AKW)ce<=#PArI9^{3gfx z8|ARKkB$XzY+xpR84RuHLF0OW?V-NNClxu{a?yy-gg%RG`kXrgh3Z53mN@#Gp9p)w z_)L5L9{qdKKlcLmmw<}ab(a2m9P+0)`0aA6htC}Ko;2wD8H@j8BTebpAC?;WYq5>@ zykzL(ep~FR|_7gJvEcNrcZ30C8vmt+r<&P#g`2W?RkKZ`zH=&1&2m8Z(n(N{FGjO)B(by9y{{s&B7bl^k)zBkmp;6{e0twjxoQce7Zv)SHnKJxxwv9f1d%S z*BRH3?0=hM{HHqbV;y)I^wDm!?-OkE&H38^{kB5Crv0}%EogtTlILb-;D62e zxg7KFZL#ccgJb;L;lEnpzs9Kczj5gQpALEVQV`pEz7OlC{Tbs-h2ww9A)kH`=+%eg z={M5Es6WKJ;8$lG-$z(a8CXx|c;AJ6@G!@mk9k;6$xRmi0OmIx^J}g@%^~l{oOty) z9`G74s(Z@PmyW_zn}05M$amdQ&|lE9pV1g^6UJ-G_cw>W4m$7w)bFn>{br!QZkv6r z#&|Mp?93dUobkFm#~{$5KT3mp2$#QM#_{z5mz z`Ralz$+*Yx+r;~ii0=QF4*X>3FB$r~Lbd+|@OI!Pzte5{=KL1H{+e1WdElxdAJ#8+ z*vlhWzs-*s=YEuj=P(&q?~_4G{LTc75AvGp`F7OT`7M2vL!M^HW7hv=AnI3G{^EsH zjQ_Wmyp<7Y41M3>81I{yZ(a<6t@Qt;!(XH@ervYo=Szpazi^Cix`Y3J9rPnFv;?Al z4q!g(R$2aaj-&st9sF+`8Qs1O`bloI^t1jX)Z6Uwq0`|%p0MWU7_7I{CoOy#+PB;E zd!#hB%*unoS`0v(VTkGpzkhc}%Gxc|40>%gXH~n4d z1=0PFci2-=f3y!+_Wlt3MYGLc3~BqsJV86pOi+){j z#2tvYuT=OSlhNP(mVVAT3%2sKwSICP{J(&I)|xGOUxR*HZTfl0p^wiU^R)=}*$n%< zO!YtCQ9s})*h0{f=LP699qYlIzdB}Y_Hegj{kNWndi9~c?{(PIszmr7=$p%$_I80| zeHPo+8{1!o`O3h2r7HTd=)dj}%N}_K-UNSpwyOV!V?0IhcdgBqeQtK>=U4~6awHh3 z5BvWZ>&J`u@fzeQ?@Y*31bIw-T;D)m#G+>`d9DWkj7Kf~haCD^&yLgw zqH5RM40`{BKo4%p+>s=f^CyU4b_-*M2VB7SJWd|#{R=VK5# z@DJwr2iw*I_5Vxwht{X9`8*%%sda@V&x-@mA8>PhU6Ts_m@kIel=pszKPf z&ict{-wk`CSqttM|D6teCgjg}%<8|$WM4Zy7dw z3#MXyK;Kj&_49Z##(Tfj|DPTDy$t(LU9)Act8M;~>v<5?N2+aod;|TaKW*`Q={VHG zf137{0{d%ever|`F`jdv4=?Q1)YnbtqZ9R^{ayc46Ep1R8pr%T0YmdXZpCje^@CpE zpG|wc+6{ZP$#Wi5mt)iaJE<7&Z>|1+cVTpY<1AFpN7p#!vtR(mx7-@<6E^v%uMQi| z@wCAocH8td1Bz;W#M(c1QgGCp^8X6@>4ttxeSQLa?S{Qx3o_2zC-8TGl$xTj0{aSncq9Qqh`BIf^>*7|tY zh5i~X|5kAfbOL`gM)mj1NMzK9@}|JP%@6T!p~Pmyr>4AB*w2a{wbt8k(A)RJPaN{k za@h9{=&uF(W49a+SVun6pTj@*U8BvrYdgBO>g;-*_%1-EWQm z4d}ZA`lem6e=JQceTi{@i1_&wOnun?1EiLvcvb?C^~Yg8y6=XL6+YUrUhcvA)qZWo z6USjbG|Y!d&v`aK7@GEmLtoFGW7e`iJkta`{aMTYet~$t?jdXb+8y)XMgL*z|8obw zVh6ql{=06awOQd`VyaYgxU9=IQZjYgywPAe?+)acb!i?X7sGe=}Cpj5TBgF`N%S*B=A>i!d5|5D9OqpMrQ|+noR7#WVnp|I{UOwNGU5UX~RCr2N z;~R3xHLJS1s(M0A-lF-lsw(2uWL3_oD6c8Y^wgA8mwWZ{Dzo!Ey}G<|&g80U^e0@< zI&TqlH6NKtWyKgpRV77=kom4#E zQ(X)^t5zqc(#-N2FFW(dLE5} zvtg&rsjiyqDWMG0ilLF(LlEQ^FO06GB7C|BQb8A{YNNPkE%M}7O@XKwQDx2Ss%k1X zT7Z1aZC*LXF}1ixzoBMPWl0Q4<|UcqCX^O?VJ6v7L#&LM)33_D&Zk3|?8@0y(e1Nq zl-91Rgb~cst2l)=5ukQOa6@@b`K)r9Z8QZmn(0|kUV@=am{n6%fg#HTVX|_nY8)!f zh2`pbo?_iodNV92mH^zMtMjY!^y11=a63GAPHyo+lkpL@%)=ykI1{ujV?O;J@@3DY+`N|f17tg5PrBE>3!KZs)(lPju<^}dn9&0R9GZ=?m~mHL=b zeWNv&?InGrHoRWnICIeA8Lx#Onp|BqKdaK`Sid<{6&2TdYW1uIrn`>#mZ+*5%k{Fj zOFhd}8+Ed_W%1d&5 z70!hXF(&$Sy{a<1^pLVz!c3?wuQ~M4CZRK5HMTZ*uE|v;KKg!}Ys&Rhc#3O!t4>T+yXnVwm`Ik}!&eb~pNJIuj83?DtYyn6n^;%ZNU zw=_nb6H4Y)RxQLfJjZjruUs$8sx9ZP70t&{J&uuWIaG3VZ~VRBQvvAhzY$HXdMWvQu^I8@lMjE&@ma?e8cp~Q$o z8h6vN@9BjTN=t1x!h-VImdb54HHgRNS1s_^iVj7bU1KAR3X9;xY*jTJwhf32vduFl_h017D}PElA1z;C=x(fF%=g>6lFI2fL=a( zk*zQu!{~t@Qov}^n%*3qtwX26=qI^37{0Yn;s`x=nZ8pSdqO;VL@+k#CiwI!L!a?z zqepvKTKG!@c8E-@P_-AX*itGH6C;ka`(RtUnnJbOZDok_E5tq~m3d0$^}^Xk&;8rp zOB_dRr!LH{p^vh>k8*mE9X}GnrEX*SYi zDt5jjp;w|iLv=*o5;h`mn?Aa$QrXVLa~cvh4D)9`G~|8K)H z76KzmTzQ$xK30dEvL7j+LnZmea}YB{t`OsQc|>h2UF4K4s=?KKMIUXkck;;TLLr!& z#+K(b&qwU%4|H3Hp}4WQ9Oo=Ljnxc$tn&-D=Vf;Mn^#ih7D$J|-| z(^4cWuc|IL0~A{`s5o!lqFGh7j5$CNXAm;l!xBY0o5*9O{3=*?B-pa`XJxOd%CDM; zOYvBZSTx+dV(YVOCi^NXaGvGy$YB=uib(gelliKv5hlrwB9|4>7X#76oJW}ev*vg>_vs2QIIcG?#j)fhpx(vm9R zys0dsnqDhq$eG1Dj|DkRvCVsnU`s|VIwN~33%S-jL?8<2#90fY(-4gv!R2DA=zmt5`3*`Kgm!P@4fIKYoBWh;#mXA{s zTfkf&&Oz4F&4o}(1 z%#%sP2nfX&I7NxmL0_63t~YUsmDU+noLMnP9@SlM?dTB|4~K^63FFsf*QoMn=Vuco zqEiI)s(4aWRW*)|;ntkX!90Icg!U6U8%vdygCwk~vMO_rG-)i&^-g0=%Cst9jVBLL zkaONFHocNimpEFFNW>*>+?jBy5TOK)i6ZC6_7=r*D`P^9^x|ljT{EQ$yS#BTL^X1d zU?f+;`+AE@W#5cXgt7FANVUG!gRNs$BrH*-h104QcrKNoD>psL7?R#Hcgb2M_FKTdi$HN7OXu!+lOx*CsA*ONDKbAX&Zg9T=-T=3Tam_Lx>vw*!=`DH@rf=lt zEfx+ATn+Zt1$8uUSZ1|uuE3#- zJViAIPgIr9spNxFbG4GP((-DSUxUZ1@B~(A77B$7k5b`5DfQ&lh>>`H3bs415K1WJ z6H|O13nX)+AGT7B<|-azioITJ1~x`x$}4eCRnM9$y$hF1@fcSHP6@N-+6qTwo!5A> zt{sO*vnqXfKCE`crGmsIfim)Q%e!O0kkJS8>`PnO|y3Ku1i#e7O^ zzGr?3?kLPgj4#T7PDWQpX=+r>!eVb$E_4Momq6^2`Cd$fNK#r+vuHjLqet{#f&MWm zo=WPlav>F!r{kHnLOdE(wGcY4oTHZ&;!Llq8Y)tc#?8XhaFuv!N-rr>CDpj*0lmVY zW3yIf^3oDqlfYUz$C_T{!z@%&1s-kwJehBHP+3(7OOpFW8nlYM$d9pN7?m6|V0B4Z zwN}iNj~d=ouECRAWZ=Ur${5Tiy5{2wsFwWZX$xv9l`+nqUE#xH579I}v0o+l93RZ7 zu(;$_UpZVH`qQ!38jk}SRn>;aG$zS3C(CwBTQ)3J9wSsNap9sXPMA;J>^E4z*kFGP zFu|hu5wI_%_^LVOB{sdozV)%?RW*gPFrkx1ipl5Skf)CW4novqm*nXqMwDPd6zbJD ztwuo>pE=CWN4X-yIWmt`@gKWkyaw{1qVc5S;aHEt39_D*1LmU*84Rwoe6zuLM4@yI z0gt?E4l5qdxTAww#?WkVAuCT#-t1_N(HauPw6+bks-mX1fy6XZ%2Ayfk84IvPNp$A z5bQ8>V-X&qj-=BX9gjp}6)D@6Wjn4gcNQk!<0&-US|L^ko=TlnT)}g>S)8k}5t2$g zPAS%umtL5gSE$jkz)_HqjjGfG4}?HV@1-%D@tF&w9eko;zO(RDrL1A)n#aJ-@z^B% zv%?~>0r$}&WnxX0_PLd@EpUaJ4wO#bZeNG9kV~=E@NvqloD#Kwo3(F9 z+-vLv_KB+Mn=Qe;P?3e%@WIz%Q^zn2qpzsRMupSy+O*CN#NFmY#iI*l8|AimBu01% zc!i43JaCc%8|sgE?9lUu*@MU!y1D@=3P>VC+QhXSaL;N zQQ_>WYHV)U%6f4tbVwL7cY9bQ6l~dw*bY55*;9?9OK6tZ?Jzsj3K!yXuM%QoZ=&yk zj2MmOln@W;3&`3#t9l;7O-v)A2Z>FqJ(Y-!5vwjl+^NmR!jcH8(hQ+c;KjYqnnhTB z2;`!}h*IOem$nc)FR9GhdF3`zBbd{CH5DF@7r{%Jr?hZUxu?P+uklpOj#3NGEVh2{LP7XveT?WZN8%q%%t@s@;IZ~sI`QPA9>{#?+axH(E2k^H^SvZ@doHCadq2lG}H-`edm;PRp^?|30QZ$yVP_ zdt24>tBA)-`{T8n(Vl%8{074I~NLa^U=Myqz|FM*qh~`d@V~-@t+QJgD~7Czs=m1V?F)DBO^*zfHcQ zv@}&m{`x7TKS6t1l^Oh#Bm4);coRjR9B<7Tq#vNY6ve+^gnui3TL1&lwkx8ahbTBy!Bho@DL6{Ou?mh?aH@hi3g#3Z^SKO2P38W+<4cV7`LW6`Y}9k%AQpdKJ_atW~fQNbhylNB7I;7|oqP57PB?m`8}E10QZ zj)G+hX5gJH>}QRF378kxFqft)xJ<$A3hq%*gPf#GQ7~1(3l&TwU8|5HEX3AjAfeNO(Qo8Bdst{f6)cyf=YxI_8h?Cd?n<&DaA8 ze};J^EW|t#&cge02+J^^gyon|!g-ia!b-fGoUjV>O6bM+*9ogJzl1vGm#`M^(jdGI z--#!@9d<`}2i}WKi1!v05!T`TafEl__eluv(X_`VEzgJjQJ;gAM;Q67tBB5Uorpx1^f{6PxvwBpD>L1C+x!f6Yj}K`t$W@Hnhb zLcDN(3L#zuKa~(aPLo539|*}OOvO4U#0%1A5T1i|PKX!LmlCGCv@*gGF0F#_5|`#B z91TB7cqP_9A%5g!F(F1Z7U&O+TKct7qD+9#1EG2 zB3$Is-XyGZY3+pdF6}+S2A8&*@Gh73A>rLFt%DFRk>5jzA0`PCHo3IDg!j6%Zo)M# zZ6D!Um$sj9ol84N_z)Z+{Nh0P$ppejTv{UGdY6_&_?SyeCdA9(QwZ?`FGC17y0oE$ zPr0;ILipD-!slJuFv1sITAqJzBFqRch^=pPuT0Q_{w+N{J&mpUQQ<$L*KiO%GyE^S z-P*rB@s>6cTA!Zh;E1)JM-o+0&m&35!I|LaXga{9=MhGRWvuRO7aT7Q()eaEt+Q2d zI9#oa|2kU)$4gPPvQ*;Df-_q-jChmaaJX7oI`KNeSyeWcxL5ECiDwWm5}c%EQ;6pX zK8kn_@eIM)v}`)@biv0HFCv~Qcn0w@;>m(%6893<1SjjVTH@V5px}|I#OsK62+pp` zmJx3kJfCJbRI^ysi7{B1n#1R!?{DQA1o=&_@@D0Sr688$e zk$492BEegTPa&Qo_$J~x#4`lnLVP;$biub0FCv~Qcq{QT;>m(;8bq3cibPg7cTG%2J6p3!X}R81W{- z(}<@NuM>P2@v+3cf?r5HgLskP>BOfH&k=kS@f_kAf{!IWop`$7U7;^~5KC0;~4 zRq$5gWyF&O-%i|1ToZg3@mk{D`(^zTuOr?ecsucB#M=dbk9ZUDR>5}@UrW42@DGVM z6K@v0gZKvGO@i+s-a@=i@G$W$#Jz&=CEiNBNbqjryNKrqzK?i2@eIND6W>idUGRg% zJBX(Wu3>7+!o-sWPaxh+ToXKz_F-GEO;vMVZ@sRPa~dAyiV|8#K#i%3VtE+4B|zCrxTw-JV)?R#B+#e2tJnh zbmHlPk0)M4JXP=v;$_5>1Z`%hrc=M0-wy>S)YcHWno-w!>Zmlm@&Aq~epK(A2a9|DNuiTMw>VH$AXzw5FwMIS;Oz{@{pqk@@=iy+ffw zT+XLz`r;9-cYox5`0kHzk>aHT*9`RAZOHc1XS$zya1VmBU?cwrcGSP6)nU9JqtX>< z>_C}*QRu!f;E2}12QQ#b`_Gf^ry5xjl=@>cQ20$_0wUZDcUE`cc`|Z8bss_fb_#M6 zgbo!Sq8wJzd9546GiDmOX2vJSfPxud2g4{AB0~dG>Sm(Oq76xb#+p-g5je z>ENR2CkOpo(H&IcMt`BzEY0m{M{mKI2VZXs4o!owXk5RSA!}gfzR-QOpb!5G|LWUL z1gn5=e_+YM(92~g*_oLJ%hEK!B*H*G=4^ag@VULH3{6f7G?FUNNEU&tWudHPG}rLf z0M2JxU#vt6-=rYQr|cW|rMvMhj6Eo{s=y}&WT6Uv%7U5u0_{QH{@{{>fxR#Z{ai7{ zu_eN@6g>5fp{#$%>hb5dz?iUTLRlMVOOL=AhYB{B;)b%;LgI*}-G^hbVAclz-UQX% z6;LQ?(DE;{guMss-3>`FrchRgbWyM?qu7nVR1G00rKCE|pxWkc_+N+<%G$j%i`NI54Afss z`h>KecfrV?09Ru)bT^PD;7>uxhY%i zjb9=hl@`9|M4Zx_rk%4NZbj41X)G()71%+hl_=?I z4D9Ht4@Me)?h51_?0U)Moz)BPhcLcS);~?&rQ{t%83!c`b}$9)4(#Z>h+}uK-_rGI z*B;tm*PRZvbWVVP&a#QHIcM2C(9Nd5^Y0xCXBR$*y|un=_+oK$L0=*~UHA)>VJ+>{ zGlH^u;5%j8+5!KyQ&t!(OdHYK_{~nKC#LrcTnR^IxhZ3v80&FbQZN~F6ToKHGnkxx zKMP7t=%stGcu{F=eLcB}jjcvaFj>DEO?q+@3>mC`ImzQ8iKG8JcMg!Hun>A{GTL-r z#XR)|=afh(BmE@NSL}ng(@(|{X_yGYodZY_l+w--)c$I5CW8W4wkc^n*Czy5)0fyJ zfh{~c9}euBVAdW>74C-rK=C^VRDfM)7+KMGUie;I7}dA6-Nsla#TX?tJ6KeMaaw#M zS|7}@=AZ|Q`A(6KlJ4~Hf&4~pdnC6hl3NqWHAHgjBf0!YPLJeDBe_hK^KVbNWoDa_ z{~h?v`nLW`{(_{)5Y7xHa#sl!&`Rj_d#+D1S~i6?ol6ND-_^g^*$)H3VJSJvW?e7* zo?AqHq(zveD19XRx2J(Jw3+S0w}3XV4O9NE?=#at#5|Inld>#pAJ^z9(7t#f zT~As5wLqdHE`nMvf^V^f)wi7oNsPVTn0W~OlPHt6+N=G333ok-2PD#4vL&(!j!$DS z06&$rE0DDtI~KRa@bmRBL5!l|UEj=L!S2x2hyr}Gg4j`+b2o-C)L_9D!SsfRPyU2@ z6Ng?c4t)-cGgR=|vaC(A#bSFJ`USSn%~_i|r?P5+#0Nue;Rf!$ueEDUgcIUK<=t;P z7+BKcU(%v2tqT==Vq^8r|0-4-zPJ~DzZQOf zT42bRB`!1%aiZcNhOPGda3dC6{cDeb7DJmEtltN`%^~0Q!q2bx$?C^o)k-tgNyxtz z{uEXSMZnac^smriKxpmVivC=}?-G;Wd+0Kj-{TH`4+}ri#_)Rv(M)~YzkJ4c{oCX6 zd)2`&SNM@OhF`JpTW#{&6qnyS4u1WFA8BLw9WVSQnf%tr<=5fh_iPvSN7@*EuOV!y zZ~Kp~#=9mizx@t=vxFaMWBA=F{2np+HN@qY^i1^p4i2dj`I{0n- zoZ}^J3_nIz@c$;i(zyIaIrvozKhnnVs~3LH)hPYt$K{vl;CGhrBW(=75yG#;L8cm>d0$%u`* z9*ndvfIF;zZDF}cX^$C(08mLc{OlqJ$ zNiu1H`eexrn~CEQg}O??ogA=syEuFniXn)i`2U}M=?lyy-n7O z)EoL8V(Qm1K@r6cLz@UcA@0e&Ft$JF+tima`J*tdbf=;$`Qp-#>Yd)dw~z9UjgmKN z_~T8nt?^7V;$NF(Mh2ciWf}3bjox-?m75udpS^y{Vd|$IramW5eed$-$CbBt`sqhV zKjR4Li=ycJz8*`Xj6jx!&0hQJ56YlBd;DtpFZ=vd#L;i8f6Mj8U%!2{M;&VD#eQmS z{oB?a4z1Pko`(q7*bTQB}?)f%(HDUacgR;@iuJx|4B?4fV-x2oA_8($xA7N-A9=vlSi z?8cgJL;ekBMKAJi?5#f9f3Ip0I(438?8o;0H<@gXV7>>xZk#um{xs<{34>9_Xn7~nQ?3YPq!X^>y!8wX^*%pw<`Wv~o!*)c+hvBWe|tUD<(%($ z@*UFO#E}nfr*HB_`=6NkvMxJ%kslrx-f{9w_s{ZT*g zC#hzDHw0%JaAAizhk&u$;p_rUXj8)WgCL zSr3aoWIZhSko8jzQ$O`E^*M*B&p%B4^uyH8=(Rr1dc`ud`KR9FnFMZ5h8aZY)%`GE zQgDef1U`YanCE4QwtKyOp~umc`3OtQ{)sggJ0G-n^iL~aaxiEULD{^LguA%f(|dAL ztWFfe=6+Wv^yd|H$?; zdToD1^H&tb=E&!-^hdTY`;qM{eq?*^A=)3oexcjgIQ>(MJu^0wCy-_TtF@Y1`&pFz zM$<1oGWu0@I6SkO#EH+8y>Kr;Q0N;HToO4O!Tys1Nt3Z_VzW-c=FJ-l5!vNT)#Cks z*dOF<)#4!b7o)Fu{#VXit%iq;H{!PEne2~g&!gKP)1F7W@!KEC`d!5nV2jNW=&w1d z;UV=GWq)!QZ1ot&o;ZK%{JPik;oj|g70-+h$=_zLhOwGwi(;sJ1`vkId$I}YY51fb zIbgP!2EOTSzeq;Q$k~SREWL3vcool}Ee?m&S6qAB()ae!`sQP}F&*3GkJ!r*$B(O8 zqj=k{@1o`>?s&FGHMQ%5^5FKkd3k9D)sbT}rO;hqfVi}m>qY9IXVseq&0*rJXnnQE z6U?r!zWJB;;;}h`^~HzAW2PYf^ z+z-&H$Pjau(6cIR>n+~?81H;z)m~%tap?{HbjRw)ynhjU-mq$4e14JjlM-_|goi1H z*hU9aRwpG?@Q|KW`@zwgWZU|QH=gM0XWRK!-1|MT^8dK=*xs+#c~E6vzn1^z8FlRS zwA7nEm-cHt<{|dmxAiY)*p|J=IdACg{!btINivoTHWtQCY7NQJ2T)l()~e|ltX5>~d_?IRCoHz>`Iz~LcV2pk z_D+4mv)G?#f~$h0m}MN8#+~2Z=y6~gmp*diL>`!mu%{Uw2|aA{i0E-|<%sBUx@xCC z!sAjNx!BG-4!JDY^aqlPht{+UzVb&L>BBsAM;=^O~rjPjJg#+o+c+=zbZ`bdr zsCr|5BiC$>LqbQ`CHIi+`@Q*m#1YyzPtK#Bcj;Z<8FBU9JAGz6dfD%Dr! zM*Y-Y>&+O}dQuZpq#RogS~{-)pm&{Kb4S^~anl;d9UuGH?^!Lodo zjd!p3NWS*iu#;ssvTT@pB=8yE3N@lF|BP)v z^!N{W^-tU@c+!eS5X66Aq5htGC0=HQf^(&yM#oEyzLt*bq{*%NvmyU_$yV!+nda{Q z9@PADPw2T(=vSVi#aB1B{tiz~cX!p9>oMei9dz{vE(Ak&!)!d9>|T*0%!kP6FP8Fa zS-z5QrU?1lx0C)NDIde{cKG*6$#9hTmUW)ZBAC1X4Lq;yKTz&&I36W;EDZS%NRUuK^M6jzX#g6R?2=MJ$T#=0iaFpmATT;i_*q--3_|XED@SgcO%B!Bkviq^fN_f zJO?^-H%vygd*xc;uvPSPt&|TJE_XE5X+_J-+Cw*P@EhZbY`lbk=YEZUzWy~VO71G2@e==U`ZjI|tHem#&KdE@m=})F^viyVHpNx{xr;9z>{mCBa zr~UxFhr7Y>CrLs{&tvx|qeVE_m-v&Va74Q}9=Hy}pL`DbkbjvJmYM!!qoC#S{7EbL z)gLhI{1vP+_sZ$QAp!FE4=ivuJkHhY-z|!O!5`pC%;IT zsUkwU=-==&hCi7qlyAveiS;Lsi;y*@KUps0)!mJQD6`F<6Bh)tAR{H|_yx=TbZUSfRK3lPOrwraxIMYrBvBPp-LA z{E7d-oRELW+i)h6?zleWuRsplt3D>=&p>wZ@Q{C<6wTGo#vq|owfW=CFXm!>^=U3v z(O+!*(GJP{2R!;G*wB$(`uC8(9$fHU+CPQ-8>F(-_h{D+Q!$4Bg#SY%ReykXpJLzVcK}jTda}9Sj%YRBld%Q- z&_G=usd(+^t<=ZmS15h-3;Dy4P`~_+?2!LW8GM2cJq&oBD@-Ix4f)RiW~gG5O%`ZDa)4k$!)P?+eq)g(>boa_xs0;aT-omyGq#GLYR|z(inmR7z zZx#BpQ0Mc;%D-PmPixjccCXkYz23Q*+?rVSmV4ze@e^aEj9ylM(Y-QFBpD=SjP3N_ zg#2d-M$fFTHRmUEXZP-&o-5pV*@gSAbr3;R>kmOd1e*9FzG-WDzomjZXD}S(cIkf- zdZ|Caw{ankVg$IN40*Wmc9!=@`EZF0`Hi-a|5c&?Udm4*7yo-w@&ij6b(D1Wz(twn z=r6>$CEo0$Q(Y01fv*>37)~BqgNOKobXqOM*gLk8g+C}L!p_skb_2>HSlp^2^@lybc06y*zq%N8kFCGx$8lFmXFn|>q( zl(rIA-oj$WWn*Rh*uS%da3V$?T3w1lI{(oqQ+~ZpdOslYoGzpul!R74fd3>Nq!^m< z+go5{T)Vj&_!5$ke+x?7%RiR<$5JcNbtB)8+4%<+Q=SXoWxEsM6Wk4(g*IPGPLh)K zQj#DgDJ*I1$JQYfD>=h5()&ct1w!4#!7QIE`F=7AzMIb7xCytNT7TV|J*>293PcK<># z)?#AFUxz_-7P1A_q2a&yyv@x0;TJa3e|24I_|yGq3r0wb=Qd#-hy2T5faAm$74dz= zaO2}#&5+;eZ-Q(5Lppxwas9RDW2KkHXx6pcT0f6L%C21&zJ>S}3xAjR1`Gcuam(NM zzb3xSsvijcoj$Bn)!$I!eC2_{(~0w2whA9lJj=qT5+7~hGl-vK;T6PBH1Q~ZA9$Yn zdTET>e_SE|RuJoB?wAnre}EjeI{mzm|0~J%*G~`mH$wMnAI2qw=^HQIKyBJoNxOIy zt+3g4cD=5ysI2F$cs|JaI$HX_T=l>I)X02+cgTOrOV)h-`LW*TYh(0$X=rAjucQ}& z+vY2kxNW|!ByO9pb_~%zU){uQ^Of=^=+kHFGvvPo?d|jBBVJ(DHxakZ*I2e6ZPm{p zZkw+<;wM`5&BTwg@D1emwfIumhkj4|6AS;C_@6C&7u)0N*tDN8ad;5}kFtkFxcI^T zkMk9rAK};nn;HDRe$5>>;qVA7d7N{ld&LIvvwKirTyN;-yH_N@Glcw!@3ZW6)axg~ zBMHU`**D#^cbk!@>+DhJ!hc{kuj^I{<60>w)8E6}y^vk}X2?GubIRcGwUEDAYUk>k z&Fl0W^rB2M(K5;PkJ4beu-^<7!RPCZa4Kl)UcLyr#C9XaxNM&*Xoa9vzNb5HCJqBO z{c)0Xi0h&WLU$JsPTcF%3%Xn7vy-%brE$F^~O^iqtP z-=9Cj{{Ar1w%)A^#NQXa;aHIyJmHJ+eiEsHrAo!b~ zx5)TM$oNAO*Ils+`_h6@A^%bw>!@K4vW8hCJsSPkv@doWZ14~LC-#ZmJslzcY&7q} z^~Jt_0RB1TpGN$Th=vG%k5$C-mqY&3h(90lA4T|EcvF@?8uI^dE8v46|NDgZVW(nw z2q7bJ*lii`&f926{)bW2StZ#O%<_F`x@y%xscmPbaNQvWr>z4ctb^-;bqTlAXcQ4#|H0DzdPB5R76eE<%w_ zVHP#W?)^Kmn3(mpQPT`c{TWH+&NwPb(6>@vyLGrL5xvze`y?0PnvBiTA;XGk`m z+3O{HA+tP>fN8PW<&sTcX}V<3XX!bTJ)YT9B>VL%$hsxl@gcGaMwX@DN$|Fl*)Jsf z1hfB=>{in5mh4KF{!y~)Sh`KJ3t9R*$$DA3QL+4q^9CE0Dv-YD4&GMg&dCs;Z`vZ*W`BiU6f zy+E>ynB{xaL;gZ$Pn7I5W(P@DW3wI!Nk_AEpJY#Fwo|en!dZ2GB-t&@{zzL(x)Dd?x>p?c^{V3w^ z@jku%c*SG*@h9o;{)X4zN~GpHhb;aKmm;Wyh%fEi_SR4%SZD^fOQ2tZNpRYar6obWMWf%nCO4GxO zb$P9A*}vhvF`y#s`TqSq`XxIWjv_7I&-p3FWV~b)_libO~T=a@s`CMh8m#X`n`O!Fy+e@`EI{}`w7M3(?5Q^_Nm9;niLoiY79dN zd2tTuA>bJdO7P_F&hTikr0^mhM0;NCs8ON?c4BVA_cVhPFDtvLt)C{(2jzv|!PN`i ze}sPJ)gp;O;r<$UHnzIgv_`#;2yf8k8)^{HQ9x{hYozgx^YJ?(Ck1o&;XQW8Sesju z{e3@|AsnLw%YFq3w#hM=|3HuLo#09C&4cR>%+Pn%9k>{6(WScgC-U+A#TQE_#puMp z_d>i64iB#+F3Z~8(7FZhD8uXU3U*^i?#y<)M`juFyd>L(UV;PhqRGa0YmeoC?}fIc z0PnXv!Hgf-?KvRw?{I-`5b4Sl-9Fd0aqsJp?Ieihdmp{-UN#^&uQ26pd5_(7p zUWqr`Wo`@J2t~RZp;YYlu?_ua*~AH}e?V2}HiRvH5WWi7NsUc-lw zBZ;EyT!)cnwT7ngEq(~=&>_DmBCq{S3ZG2HWbMLh`hwnl!K?SVzPxdKWHb}D?=u_?7zvr$G=b?zNA~BEQ_%gu`3i>q!#dJZn;m?uf;65gV zJw1b?kl>Vqp+$UgY}Yd|-uIFI9x3X)0=*KuwI|>`C_jSZygrx`EJzmr2g`>4`)Pva zeg$vM^6d}#cGJf!Nkm7CSAzxAF<$TZ9Guc-ou-t#D2z8H%Y;)6oAC=NU7Y- zmmlZsyL>g>l<)Y!e*1eRu{O;2EM9D>W9eV{&R(U8@fc;->xO6Q{-rVUS6?wkECcF# zD|Ww_!dZsDJXywb&AH+)-LLrg^$4{T;0Tn(;Dyohl1ARwgzUy(xJ)<-*3nsbq;iN^ zsXVE&qA60zk*c?2(#m~9O$+yp1zj)0uCfjLZJPyTVW?fNn98}#M)jOcIcJdSVZ*)r z=@&F18ObhWX&DdT&@(deU2U+6k0MslwIZ^=$ot>1RpI^b=NPUgD;dg4<@lr2B<~)+ z1$&H5O`@YM)RF4^a;YBzHJi$c*5s*DKh&&@*5nTd$lR&PGb5Uu$Cp`)b}xlaL!N!g zM?_X3y@yR%SU!;@`_<2(tmh+?y!N+Iw%F9ViKY4^?z9 zTG!G3ovzT0{R0Kt;rqw=w%1&5Y>>y1b4prxzOgr8Lv0(IG8S7iU$k9&oErFbMs3~V zv995vg)VnP2Y7~V=pXnN+`tnItDpA&(9eDM6dvEK=1(1r=s|_$pT~V$lhW9u=LEhw z?*Q%{ExZl_jr+EGFRrN7M$=E;FS`q7qIL{&Kuch$+{-n3u-aBg3jyR5Gj^U4eqF`pq2B2XftO(i$A68nmLI{IUIv zCutySFlV1J2eRc-*J>k$BTWvUyH@1ryqo*L!hV-~_vyEriZ|BuKKMaMYA8NkpNam1 zOSX36PAcD(jnKrLp+6Xeb&Jz`hPxZCz_39|o!_mq zLpegkN6|u`WbY!qM}OS^g-c)Gg^l17dLb)3Rvvc;S;{XDbnfFeQ+u$nC!&GZ;T26) z<>29gbGex0XEjVQZ8HID;XASsFk?or(XKOA1VxtqpyN}S2a0e;~qqp0CQs_{GU3N6{?e&sbj$|>=}c18~& zMBe<46X;L;nsc;0G);C178<)mI7zk#mPVomccXAc$ny~1>)Oz&*Fdj92`F&UGZE1U zBS|B|a5p|i32<*9>dMCQFZ?9}#4=Gv6LF41*Q-#vDRRB`No>3S zK|9FORTtS+mZ5iZzd%6lU(%|%SIR-I72TDu#K}GuY%p~&6$_=jGy6d zkaA&62ZUA`^Js)*Mi-sdfJ?_@zz_(mp;ljk~exWM+}NN zMR(te+ryissOxScb{&NxM(zFab3>7reRsXa^;f@lE!D&&h+deu)#D>Hp;B*)Aqy*i=(u^~Mm!Ssy z0KpFZ4i3iYeBVYlw2Dh%#pYn~8wAK2{uxypLBgXW7{)uGk{@e0p9Q%5V-t?Y@FfZ1 zWGqkrewTg$3P$vVzr<1^_s7{w)OCo>95u`nv=D`S*@Dl$t~}+=dN?Js9iKzht*dPEPPUuA24&|1CYWYg}Z$mL;9!Z*}>% zxyB(HeCLi-_vWMlb>9v0eO9-4K+mzhjvbjN^$Y?<;2jVw{b!Tw%W-e%b72bSeHobs zoD)oY4-zDXuZ2p3)7}f!CIz8U#~T+im|(iwr*ATExO^b_H$ zq3z?`o3EGZOHl3ml*>?ELK(jehSd=MJ!FVFVtUQorwWWCNVMQ#5BIT7=*CX#yk3^; zKP(ko|2gEn7H2;Y=xoSm%5*VB#$nvW`mrJ{&jJpp2*gC5+;sk5lKc+!o?1k+tcu_`;|A`S+5y7N(digcsG4a z@FzIC3T5_l!QLpH>mB%Mu}>%_{2m`Ch!ZAAR1O1Oe-G^HBb+bB%F~8;s=n>(6Zbw)bqmvi%Z3vGON#;Qk|K7zI zBesvVa0#K8EIoma%Mxy- zge_m<-U-6Mk~Q373f8zA`SX$d5h#TYj=9`2_E9c!{$6H7E57k-V-qY`ixa`%k~KIK zyfGW4;w44F z7GC9IlVryq(C1`rF*rfeaR`7 zr5H25ZyDmq9%w2Os(yk|Tid;RhHIWB2K0}6SKy$v;JZ}Xq%3zC)Wgb&S`@x%l> z@t=h_au2#`(ys(#Zd5n1Z~gD33gS6c%+yFLo+R6l{W=WeWrom});%flZ4 z2|`CZyPogbD?gsH%r8Hz(zylFGi))=K2O9DBSB0j?%vz#7?8u>#DC+^H7_)6ZTK(P zlk3}#8H~F&J}eelVuJ_x3J^ZuOafZErFd;D*{IHI~=10_QU?L`YM&X#{!S(eJOh{ zFxSb%edG4y3q8<7#74@|xiN)T%PF{=r5AjHRY!XaKXezSaFU@o<*)cPG;nm$?h2Yj zK`%%zP56DQtPSplzrlpW>9`xp*iwE!&u~s^JqI8?&bqmLcwvZv4iqo8%eJ14s|>_N zQA39_*b1LxTvgIg*dB#Du_+nnMdnrFuOS6FFHzU6f2S?Piv9x)t3Zj~m<4%xJHr)} zYl_eWTzYQk#20Do_ZQ&Y#N7p4p{t~RJ?bM0O6ZZzN5kHi&vH#Wc@{MGJM>C25V4eF4jqQ;(!oG7VGmQ z=EDH8SOY(VOHqI&!mFK|kfkn%J!W67FY>sV7p*%nxiHa`x&L~jp`g9Ci-IX@3M|l3vql+X4>L(x~sBgAtB>Wrj-PUn z>jkVtIiNZQ^K9I3m3e56lllSiA0_s5biE#NL{{yU6ztgxy>KMt$&_R<#8eHJ0tuX*87*N*OqRuoo43N!4W(V@p+WQLGE5D_eHE*I%lAX+~19~YKqtDf@n|K zi5Zng&mygy_il?Jx9#*}3mZ&BnGva!1O0#Oy$O7jMbbZ>gb^Y}C%UY%$|@=z2nu*I zf(Xb276}F+fQrX@AnUaVGk~sv#F@c7`|v0VQQY-FMa7j>ltUDv35l7gtVTo*&v2+S z3@R#enT7xNTiwqwA%L#>9>4$V=OdY?kLv2`>gww1>T0rQ*T+TPu`fzWQTmG5vJ?6u zA@ycj616Nx_8mh=+f%cdAaBMUf&{MUkeJQzGqnnG@oQ=5i0t8k{V zIpJ#nCexl~QY*aZ*BYsb&9Kc{)1I@_aN0C8@e$Lk2|$cUzxo~k71dh7nIMpUixk`; z%EIHnhu=e(42T{&%eG$O%V=X1ix$`Glg^e0{Gu&@DtJ)loLW3i-OMdTO>8V0#Q74J zQ?jtExS}u_yJt>2!dleO%3+_Oz zz_w6l6Yf4r9Mqz)oMSZilz)!gSK|w83nx^a*jBtB3NcZ0JE-J5%{possFXjG1UvN} z3cp1j8028s4%tC{zA5h>qnAR4h;OrUKALwCPW_}}UuT=(gCN-Azg{uuHE~Kt$a$j47xZO9^t7>DrxujVlQ&k#5||feTW<#F;UTo-2_Y$-++ls`Kgx2wPY$~ z633irh7~RqaY^tjT3UnuKei1+9)G%%X@`Vs)($L9B~={`ph=AGT4rvbz!&OBCq2ws zlh#i%O=1`b?YVD3mnJ(NofX`wN_k9kiIesyKh+jnSZ^hMhqQm2wEwKnX}_R#prB2t z!yX8%Bn90IA3(r{*JS%o?^)a~pVs~kEK=ydr~RBjL2eW658V@>P1Yv+zh`l$efr1o zFuT9cJS^~TsHIUW@4ZJ7na~4a-*NKWm>0KhT)>;3YhIkwL_X;YtEyJp;jp{?o0U7W0;|ThvwSbxBmK|uiqPq&XRyO^iVHV*$N7A4V5)Aa-eJ1; zZS3|RgiZ&z^QC>=eP@0R8*0=HPCN|Vq@?PdOlp(^;I>95s#fi&|0YIJ7cQ*8=KN4w z#5?oJE)zwV4Vcfl8m<|b$>(fi+y$D=&7nRcxGYd-6t3_`dE8-6lQjw6fah_!lD&-) zt~QI788x_{+X8C~RnBKnG!pj(idKYECbILFnE*df_Q$L8MbVbI{_HV$V0w4zOnW_n zF(12q+L7-KL;mFXA{9O(58DgZnuQ~F0iH>SK)4j(0&#!j7)UK9(Flg*W6=*D0Yjny zdCJI6#UKPAZt``@%MRth5IGfxY>&vgiV`dco`b5L2p$XRW>QU#jNk&MK|a?{^k^O* zRGGnLf|sChfTu@mjwV_3!X0Z1q~MC6F#TkJ!Zb_~?_xS0wbL<;P0GwD0II;#AB|!W z#Cx%anZQw7Lc&-!ytGlr(^yaf@8UQld^5NW=wlwGFP^x9?_E4E0)^$qLVBqnOXbV5 z%yDSXQnDz?DU8sFM)hOc;?-?%9UVg84~iA4U&ExyJf6YaAuXYAd2jU z%2JVsffQA*CUy||nPHT-6BbkY6MrLc4EBW3pO|k?F47$aV){=GQDk@un;|HcREpUM zVpU-3Kx=iBVs!4f^T7lQP6iy3XUJ_RP{;zr6)QVoW!qb+6PwEvjjkjZuOhuYk@^9M zIEr*%QKVN%nypCp6-BxVY2MCd+MSy!%Ax99TXfEpCEt_yA&$Y#GO7q>j4BKGjQ^Go zC+cOn{9Se}f5%$!ckC+uwp#Pw@;3ap%!hv?OMT$gSdJucl8hTF^U#tBv(?Om(ZiWV zQFs<&2?kwF-#H#sijf?tX;rd|7k9(!BQo23W*K1w%Gl)i=S+*u1q1YD6 z^}QtD0#XEEmDnacAyFEeBM+kryqn3*)-_?}ug}H$A?)M6g*&He(=fsD% zaH}x>YgLCSZy?2tk&yu5Y_og-ewhopI}nZ%I@51|51?X2(6GI$h6pfK0L}9i9KnKciQdQmrm;V0-Fc@Gw<>h2_@@rsm;~ljpEBe5qz~ zEQ?CGGKeeW)c~ax{9*V>A#vh;l%Yc6H$rEoBQlC}-rXl%OGJin&O5vN@kGe}O1%Z$ zeJ1|D*8w;*9pHg7UTdi^P)Gj_0e(+_dW=I|(#uy10`+$J_28=HTrUEtXWZ7`POm!y zsChOgPqS_mX+}9`HZ*gY;r7hT@=&udZG_%Wz5uM#VNaKSINQ7n3A-3+_NFs*vA4YD zAOAh;cM_#f?e4TJ!X=MH& zo3BaU#9?!{q5gaRMx2X2BhFMXTM(Pc?5A63(p^^3db_~qSS^w?F?b6+Y!z*=3%rg3 zsVUr#(Ef{?MF2K9@dh-HlByrJa>?$FfsIQ#mP7p7gc9l(gp&TX#rd_}`Ne6c%5jj? zFQ4-(TmRx*dv_b~3ul+cs3pZ9vqD^5=Y0S=|jz`=03G7=8h7soJ>Z5qxk)6Np6+Dgubb7(WIfS79WH zCb^!6`B-;iB8Gu5%rN~Z#gy~|7+o!)W;rQnSVSqXBXouqp3-ybH1vsa_5Ug^kyx?H zSseB$sf-i#Y??Ap9L3IZkj!!pno%Y|cVf9x64?RzSGX(4dS&k`f{o#_z76;7>j{^v zVV0AH_73-;#&F|Yg1z{%z72OA;6lkGV>n9Qe08rb)|EqMNo#uJlKnN>mvjsOrWASN z8-MI`P5Mj76TGNMuL;L6sWu;pDVR!X)XA!9)T4g3JMVL0#Nix+G)BCnBMQct-o$v{ z2`=JzPbakeRvd5Dek+dm-7pWU@#YzhjQ2sD%a3pslXcjP$?fN&*_3mX`>759RG91G z+%@Eo;B2Tza?}7i`WKdwRO&{ZFhCaW!j(#5@_E8`&O_|U0frD!$|g#si5yQ8CTdAFu&X?TZ$j#t$~%RP3wxYHCCrdVQ27x)klyR_OXpWikq>H^SM7d3}Dh%v3Xp7aE_^U zh<8Q;t4EpU@2}NgH3MRZGicN1rCY1;1FTqb%weLLN2)x`>~vFna! z-6EoNKtAX+-O*Ii7?P8Hg&PT73e+L^WrV_J{|DGX~x#2Ge4BAU#Jc0Ej z-N}m5UB!yUX|;k<%P|=BVy!N!mSa(hSYc6f3AQZ@VB3Q;QAb{heSf$(isGPLtl+=F zsWJRNHZ>C~c;6gzSZ)oE%CQ!Sr-UW9S;YzBG#sGgLMuEIx!4uf1^VWO4(Cd&%E$&E z4#qI);<}?a+QQP#TN5x-a-}>C18u_X2hQklcy3g25IhppzL}PbX`6s}_~5i_3HHH| z_cH7!o=sz?KSHehOPxZmze*P9#ETI*g;poTskfWzKjbj_pVIwrZ4PU**Z%u;|6AMr zZ?k9r586lnF(PJPK0wk`|9|td`;R_5{l8N8|IYpP|4-8YjjI1G%wfJgx-YUjJJAV? zg1XNf=<9Pku8qxyB2>@b2L3FJjM;+ymi>d~7_2NK4*R*CJ{KLeJN?xas?+5qX`S|X z?8ts?aN-!KK_yj#u$91N0UkFw2j5v{?^X`~`D1TGT+ku6SFR_~U?Q$;OvpAz!^RbA zr*;7_Uk%48sl&V-)mgXP%^c&i&$>Uj45WaU9IVZg{+S8SbMfx4a)o8=4cLWUOUR|@ zQ)+=xv_c)gs_Qy85Of$v6{*J^c{|<&6vMn}(7ESC4|kqx?tLugS;T*?C2@VaXoR&>Wa^G{84P4DNSd6ZPG{bIlLUegr4Wi!wu zy|3}o`=z5R1=o`Q2G?C6FdwMo)1_K^P55g`3P_DcE(_C|VILp`LQ0Wfmr zzcnu7R&tzyslm@LCg>tqW^mua@mQtpR@{+;BAv z-(s(TJrxdn%IK}@pJ~^xWqpwFWK8(e%-aW;W4d$6-!|@d=&x<3{%)AIbCa$o(_XU{ zDWql#nz@ag=A?G!m{zLdG0uL_sXxzCKaeRxAW8#*w>eYq6 zO1k1R zry0~{^EO{RSc^p|BOa{dA7iH!iy_p`ve2QG^;x)H&FR?;oCSx3z^+hRb-0c5a;rbi z>_g4X!;M_y5a3SPxGlVi!t^$u*#-2|_CpGwy8v8!CqUu0{fE^020Hez=}2^KI^I1P z1B=NAfH-%CEY8GbIp0*HFZ>T`Gi!~$cIcjT^U{6?)7h$bqKRz4;kRtJn zqH6ddIK)3#h+iH4DtQ}-=cWJW9{SHAxcB#<|MOSK`u{2E-w`)Q&E62~xja*?3w1VX z+OMqKl@;4M@dP-gr<&7#YHYVAa62LP`jeo`AmTxIBOl%A<-@-gHcEqVINjhZSmDFC zSm8!oF7EQBhdl{-ukEh!^nEwjFjec$jCzOPcSE@;sp=y54j}9H^>ynD*M>3-QkUfz z)K(w>qB#knB1>~%H-O%3_4a}E7H%i)GPZXJ=crD#H@4xN>OduzBMD#RE9qEpiR}F@ zq$2V)Ttk+G*8_dMS)zi~i-U{neAvoSV>ym`Oqy58!C3BWRyB_hHz_buY`CmsIdZpE z2y6K);amj3!T?`7l#B{5g=N;6bHPY{5)Jz^Hu?6&Xafm3bQa04gZos_sMTH%SnSDT zIg!d7%nL;LY;JZoPB*f_)Evj{;A?UsHZ~|#i`4d&Mr~yx%j$C{8Q;7JemS*tyaL?H z&_Ek1JSLz;)B&o4b+Z1eh~yK zV#8EWnj{}ZzS?_U4>EGd&JJf~liH$`Gl;&W>gUk3QNza;eArH$ZguHA2 z1FR%C0jmvn#GI74EiAs6kccC67rqj&b7w)iCLQD|ELI+UG@Br+kVbY$fgR9Yuyj8T zI#L1`;c##T{_)Q72Rw7U79t`w*_}2I88wMB$yKlkUVuX={=JrEUUufw^I%@+|8T|N z{10P1`7Uq!Z!wZPeU;m@U>7OeFlkhh^GmHCEiCxZV4=em5?T&6kTVPGDJW(4g>3N` z)7h`v*`Zrt6hfdix8^^btih3*+{n!vGDD|eD+-P$+$qSVUloLh!ADqK;i1nHg1PNC z1Hs7ltkAiU?ae}Md1F4vnX1kkP!B=fJoQ}IodtGi7RJa;JW3_rla|Ufy8r^`>7qP zpme-G(xpPjpShi^>k22n{e|&IJSCinsEGt!9K)4Z3XXwX!UU(B$X{mpUI0`67Ds!C zi#ShsA6Msc1qH|`++E6F5%?z5H(fv(+x8`&aLpbMz}oUj%aJ}M*=%t!B_c^3}++lH9$}oZE@mr56(LEd>uok`b;j@hm-Kk_5iN zA^|6JMTVr>3)}i@vJaukT{tM5W8h?N=GUcTcap*`^{U99$fkbIWj7otCXR=wDyb@5 z1$!6o%jcTSIY1uY#lZH^a8E3rmqB>mKcSgRA3BbtLXGL*sM}YY%{vsWhNQ)!8yf?x@1sC@K+P4QL&Y@?Ys6(7)}cP^`>hbjo%6x|8Y!yFm=xt|p^php9RO&}lkiQ#fH5ErCe|9XKrpj!fl&-v3#uvWawX-< z%TOY8Jk6Gv&?QyfS1KV5nO1R-5&XznypC>EHQznue_*NqzRE5YUElOac{|z+BXcb> zU&e+$1NqT+@YjmWhavD~4zCfcw-#^EwdHhGfgpfc0s#4+69ADQfV-JmR8JZfZ7_>I z@-G~HkXjEAuXAA*f*W0Dd=tf?@Utk`{glw??&tfXRL>F2lWW(*e?VWq@xS^Fnr5FZ zdGntXhMygOPIo`?F`5GuE4Wn4}Gjn5-a z=7k2_w=f`1@czYnn3<-q51vuBQ3%=kIR(#oC3 zq~B+B@^kl--)f)vTZ^fG_iWrB-cR6-RXxsfUt#~>j(!Sy4o;L{DJ-d)x16JE-*2T? z4F|`B_>>UyYu`cm9^HR>+AyovW~dH-z#;$hS#+6&yv1TJ?qTAaxq zYZ}=YGvjLnLXgKyaGj2iz0F>e!bc=;0eDwFLiOktt_}@1wx8QP{4Hx1epb_5 zJ*)tMh6uON?8pi0(I|9uE=K);vQep25tLAyvOr-)IArXMzEOI3=pSHyJs!AUj6~cl zNS!5e1vyBbGK1LX4FqrH9*v!XH9Uly1?3!l=<7rFon$HeFu9 zTvY;^ehpNAAfHR~mk?{-@CD?%PyvtCE|J%(9Ai(vS9Q%X4ZNQau7(5EJrOiy6@Fgo zF1`JwGS=Qv$ig)VCFHl@aFD}SH3~vr0DzKM9aAr{P* z0_mbB=(v^tnOgT?)O84bJEVao^rtT}Fh~U`trR3|z5{O>g^R-eVgzzCwwE>!J(HYD zv|wGcJ?u9i-T_xAbf2q{2}DwLF265gr`09uzYZkZFL{UVa}R+lc;o8+)|h17?x(c! zTkk>O&;dyvHz|*@p~*_TO-0|iT#+*Zm=lTWCjm9ou9Xh*%o@ndwI=Id@X1JUVd8=g zvYZ93wSuMg8gGXJ`=l3l2ca9{lXHLo|BFwiR8hYuKh!Tu3jU|ib&I#jY?vgf%E0cWbQM?#b~HcrPUvPSnp<3L_TQN{#!&l^+*2+5U_SxeGbj! zSSwwFQ>qU}%8YzOUXq<1#&>@E1{q(hBL|R6ggKU>9Ac-F=@1n3JZx-?TH{`_SGMs z>Rv%DMr%7^cL%M}O#DtJ^S}6=Hd^sJi6;LurFilVbV7Qfq8Exh7Jhh@-jah8=R)x- zsk&*I(&xYnzIM#OPCHQuuEb!@&NSjR#q4fIyx3`{*ls5-+JUqP^{97_KgNCLwm8x7 z#~#DK#y4FmDwA2;YMAuhv!U#faX2bQ;#rZ;Gega4T4b1rKZ(xMgu{kONxp*tH44GP zb{}K(_8q$&YK3uocBmbIP`U%Xr=anoNMv(nY41#10~2{&la*Q1JJU^rl7)VZeD(M& zjaKwepo%*`6h2>N0VN^1&rkVP4wL0aOOXTj;Pz^?j3A@>>yBFd!fM;btS%Z zoB;YIy6zIY$<$DVH4C<-z!M7~4OrXJly+mp7cOcsVuD(kVLye^rb!j=?IX7%)Q0>~ zJdhY7e3m_%)ccV<00wx4{1ZMykviPXcvnV$>(Z>Wp;>321H>^YaZ=zL6^YNR<8UTIVzB^8|0rK4E^k9@cl zIJDjtxQKW>_rL6c3ZvZ$p|qecf0x3JX|95W8Io8nvA5#W*kvIS1ep9`=3wkOWU>RnPbscuyB^$5p=y_pu4_Tb2ctJ$UgvEnVW01iE4I zb7X`7V_NF9^!ugMe}__S4QChk$OxZVJTWsP6fj{p;%vgjNZ9SPDtc1QE1)wA-{f(!w~}P0)ilSp0&%YF^N~Wyaf8HQeoH*V?T|Q$092)tsvF@d zt)JUKw>~_VjfPIL3b%4fli<8SIh{mK+gK<*bsuEW@jFl_as3{JU3{p&S3<`rsrs%) z>+i63W~0e=5D+TFIL%-HK zQlb^tP1rW-9h(PYNMQJ_Ry~Ze6>L?ton^`wNSk9SoFLKB??nXLemhB?=!gC(v{XC3 z#MZN&6repDd~HUy2-=~E1VxeR;0Z`d8Q z@RU>EL03lP7NF7y&^hMQ0Zv|BwDn70yLMOgFb73ri%viat*mIA`iPLY%ED2F*wJ$KEUQ{aZxtP_^&FeSea2@ zV)KD53DcfMV^Tz6IO9N~ydBxP50^>;UHI)zF`--lfGW;ap2Sz+1uOD9jWl}aAibqK za)R%$pU^n0vaZBSkKF`}onbQBIWf?fUnmI#N6cGffmLJjMe(C9TOs{?CtX*I zlb0mhT3mx3$o>)qSDv$bckyCQD;TH@kPMEW;aK zmbzN4F&NMda3x$SC*xV<0sHAnr_I%K5{fs z$JpqYdJDlrScI+MdshBzmY}^H7$hDhbIC|L*cUERQ;#L>E9@AuNEs2G%?`+omKfi! zhH9_BUf`Ev2^9Vus5QkPM`zfKqpP)%YBD1zzEE{BhQyG?&zwdfpG^K6@1bX)qJQ!W z_?cV{v287$k1R_D-%#_M^u%mghOtOyqKH%(_k{CI5(D2R-aZ3$oj6Ms{K_vSBP_sA zV>66+4t1Z9qU0`$t1{+eF}ZfA=%9w77D18UYMIq*^Dq_tfFGP&D`epwug;VBPy+? ztaJV3S`$59?^fLQMrVBfhQraQ^RJQrWs$&Cd4i?NQ3^Ls7UGXh;k3sn+6tS0YSZC) z*2zJdm;Ekf;w(jL&H2?fut9bQNYsaR5NqcK&(*9~iZr{h=hlP&o-3rVbNl8j7VeKU zm$q}bLZhKkANNMqn(nYSwTaOxfx!CD(oT0rCq3^lLZ=p|?n0nK5W=pq9FRQ8gZD%)-fwMXb065vtz(^+kY?kS7OBmW!p;q*1uT4< zr*K-Nwu_|jY8!GX3wJ}BgR7YGoG%rrO$kYu_bt)=D8BuusMScwbaV z|7ud7qSwh}D~LOh&xs&+ij~(dYNn6sE;mZrVU@MdGiATb_pcKnF&J|%N0zNqZI-97>Lm4ZGn?|jS;1;z7Lu0KXi-~{M#Dl2w6>dpv+>9Zr zZiS;Sr#>Y|N!3`XkISEF^$$n2K!hOf00e}V*^-#;K+ygILXQS4#3fay0f;gl;CX0F zV!Wu6C+qaI9*A@iStdyy6UsD6Ih+*fdJ)31y7ZkR@IF~+!y`fOrb3CoHSNI+4#~9T z!QKxJGvY&ym4g#E3V??J06tV0cy-Rj2YyHZmJ&Eihw{A-w%T~l1`fPYum!mp!qCJ+K^>FXZS-~<9cA7b4>B3OV`DA=m0Fe@pilhIpri#5K^I4P=6wj?cOtx24s zsQOZVmS*~zjLe#znHe=Obky{0h5)zj`K+8@H_nI4hPG;9{6Jj0VhsYc^vulUqor>C zP`cmt8e!f#Jg^yWLCimqbnq|CE#7%xsAciawxI)xceV`kS&_hIqt}S=2H3G2dr|Su zgF~OCzI5@S{cITa!GMaJcq7d5!`rXy7S6q+HDflvjZoX6Hi(7CXGyx|WQ8_&sbFj` z*WTT%FjrZ`hK*o`;y=6(yam-0?V%o(R9!Y7#z358sJ9+f;5%64wkM`?nJa1q|F}ra zDA}rjH5WtbDxoqcvS~qmHS?||-@kDng77S}rKV@qn)Eu&AzGS8!1Ag2 zYQWCHZ%%{e13W7|o|IAYU?|T4^G28hhohT;+7RBa&E=U&-iYFzr-Z*M?%FAwMDlM{ znr$i6<8Vcn3R)5!{~L_wFdN{+;i)X64&FY$_b<%03NnqMBkVmWa{w~50;ZTt(5C@tJ(4a+Pp+I9+{Vn0cC>SGB-Bt!hPR&-O{EXKPK0i3rn(hCF?Z?M& zGIk2^R1Ecuon0!#VH|%l0h08G1R84g9$}6dj{7qC*)l7}4ppOS-CoC6dJi1;IUaxs zUx1=U?-5;=2WrM0k@6Ft{A_%29*u3@sK$okoxu>^8on-csLTmDXXvsVsc;;(;cOmr zs;rBVjh!(+$FFoV#%@yZRL;212}Am4O~@?Xd20A5qPoqvZN%7v@IFl@7$Nn_$f?Hm zF3VFd7Vqp3sz;>aXXL(w%-+77x_Hdy7)4*rVZ*>-BSJ?O?>H`W0$8sm`~?^k4LR}v z-iKdU1zE%%eX8L)wkyD`Wx1ymo#QQ-BilV0=XeWZko*l;Pk-ZjZbq`1`%QxusdhS+ z^5o@iI_xKs-XHTN`5vZ(u1`a0vdaC2iAT!uF1?)U=yFKTNbpwhnpnqXzq%za!KY~(H$y?%w1KVs^KIwd0 zFeFY=WZ;pQ!YyOlb}JYjI?BJWrPVtVax&CM%P|Vh!I=EVbST17gKKS>M%PI5%t*CQ z=Ay$-m~VmJ!$WI~r4Ed6Rq^eaE#<7g5>=q=r4~B#K_@(EcU$zS35@g(`}idtIR(sr zVhYf_k0>YLIIfd+G*_$W86@%anF~`}3@%PEpw56ZeP^Ig$b|DYtKo3qTxB!LPMmx) zHv(VC3P@WKm?PW{E7Ts(At`!+RF|6t13DCR$Mqp=$bCOpIro_bJv$Wi!S|n*|7+Q@ zWts1q1zkH7be4oO@L%9f9Q#N-ThTA#Bygj6{Zuj}zSRF7{o)NMUWkA7>|XSX&fhno zUtD(5Pt`B}ge#!?*DsDg*3~aoVdOcAPhIeT`o+XM{$J5Al6PW0H>F<;EiTFt=dqz9 zOsHe6pvvVIpZf=Y^mR-!Ew3QWhK}$@ijV?91czX&S6%l5$0gvc8on9JQ7dLJE!P@2+Q&MCa}Yjz3)IjNJ@>VgQ%aaT{Ho%aMm&-T=(- z9J_o4%3}}K{nYS@fgQ%c5o7)Sh46q`nq{wV#+y*n{sxfHJE5Ar*u6t&rSWE})FU6& z?%~(dKYkSalYX{-bH|AkCeJ;+r+$;5g)L3LSt-Nl>GDD1%iFZ%02;_0rZwRskzX9uyRo2p*Z1w33_{s!y0cvJ)(Hx_>550isWM{q4q;v zhzk%)-wCW)ng&L%o2ISO>2KXpE7HT?wElLCv@-uhqVj+G+m^(G$8n0k z^~5i%zl}P25B+Vyk-wh)HaPJvbd8d#X6T3b>uZlk-i)Q%`3D4!&@WQi@j@lW^5DdS zQtz$D>BU3q88!u8POaZaejiS?R9oOq11Q_2;l-5jvkJkT@ST$B`no{c%#ykzJ$1i5 z!>v2cu1mkOL~VOjmuyK%HA?E<>Z!ZXQ}E)G@S4Bv^)n;EVM}^wF|dnE{pH9N zUdbh|v_oUwwYU0<#&hE^Pu=_Ny4cC>P9*UBf_Gk(N?q^VSlQWa_fosA%#AsX>JE^) z-nsENPu-*Kx-vILH>#T}b-i=r3Qyg2$aUw&nT_hM_`LDlIL=e|DP0$H%x%TxL{uPQwc3@u9Tc(T(FVL48G%W0NrB%Dc$C%u3gEN1djrG~O79|aF zPtksJ6I9h~kr*0!|HE0ufP)e)x%28hT#v+`37tOV2;@2LLS+;=UT>l(k@kk={SGDg z3@N)1X`mp2qNpB;PCWiR3d_R~c*heR0on==JO0^k6&|w{u5kNCU7$naPbQ8|h~a+` z568#pe17%KrAO|wpgh}_bI3*Z$;j`%B>8r0^2u9pcz02ibZCd8@5lTKfm-c3=!20~ z;a^K!#ZwNr9I5eK?b2(tO|MUwr*0I$+3Ez6M?Y!kkF64{`E&>!u?&1g;;p)sUxgv@ z$G(RqYsSbEWSa>L@L|X&n8SKt3kn-$s-(o80N-Go)b#|Iwd~t}{wUtOON*vTxv3oQ zK%aZg$0|ZopFT1wK!=m`$#Lr+(5OB+$c*t{)-RL#8|?bItY4B=pKe<(qcr^>=nazI z{#x|X<400=2^T`fDYv$D5_6pz6&;?AIxUUelr&yXs0nD#G?Df`(%6wwPWUjOxsG+$^UI>#ql?NVYzdk^ zN~b==|DVC5=rH-zcSX9gc;O6E;Z&CWULdD7@qH>4eYjCa_?&@z9;9zu(8vw#xfN@N^#u37F`aS$dn%=RN36_TnNnGx z>$Ew@uL;h`Fz40cS3Jmwx*0XW2N8kiA^x;_XUBsx`O6Sk=0x}oAZZqp;=$RHQ_fwz z5yKTCgb>+cmhp$9kWN2*?SMZhy*vg0_ZY8O5AZ zgvofE9rrDaNh3onF8hUM$cEaN%y&|n}E1|8=CTTs7 zaz>v7VC|*mkJbRb*BQ7`MBMi=izFhhCA}7wKno7^LeASEUVzs(0>~J*o=96!0=&;# z;o?RWUXTio@;;aq9`;t40>1X5{Jv=GPN>`CSfP^Yvdjgjs_s-F>ys$23N!Cz$Zn+= zmN~DcI_A6{GIxwlMZYPk2jF5j6lvw(p1g(NYf{j(Eg5V!^&VzCOCE=k%ImKe8t0u8 z)1hJ~q@+JU}h_F;(t1JPq`5zs^kinvE~9zehHW zqP?XJ=2}VBKvT{at?&}<4+#`UeMO>iieq+Csg{|(nhLgT*5&G$KFy_;{+07l=N$+|5CNIoD*OwZI z4g#>dc4NyAjPnH0e73msIL}C=mTG;!6Q&>HfB%&y6y5226wFa4i}Aj4Fc#+nU_h~; zt2w$eVtFG-7-I3IdLe%IY8Y7xKQan@R$)C~hUY~iwDZKSU04OM@z0THv)+5bGs&1W ztr(HB01X93_Y95lh|GGV!K(<;pgkH{jdg~9KLU7Kp7dVd2f_h7g064TEyXYhb~#)ylLI+C)3)PZ zT(%3ng1>e^wG{}>M#Di5Bzdmxu0mgv@NK~=U5{9Cl+;mnf0)laC-80PNGlHkb7~_s z;$?ILa|&w%-{KK5C*bjCKOhk`LAYa&#Q-r3+X{XE*KF+XJ#=tl66Rh>)eEJ++<1M5 zMek}#fkEq@t#1xDT|O1X@hywUi)DN;Q`9agCO2@jwQNPh&ZpXz9DB~viM2Ovc& z_O5>b&eO?_4un`)~~={KS0m@-^gEQY;DY6$0Frd;jir^(NE^Dn!KAb zYw~Uei`|0%|17MQ&S%Alrc6G2{z#k8Zea@e>|vy+RY&a~gW#_mNO0W$y0dBif-~^X z7Gao5Uq1FLu-FU$)hzZYrk@GfG*HPeSjXmy6q`dShKSyjT#gi*qotUZU&}<6iTuik zOsT_?ZVqj2%d*)`%QDC>inG~#0wsTLV_BvJ*?fe`HL&@C(gvZ{!wk-$P+K|tg`+0-1k4e1OM@z?C=~2K`r7QLE^8%f(x+D{&W_M=iNkk2mL&6G!}m&FJ$)3 zuF1OtB5#7tiqz&M4DGk~DQ-Nrwatz7OaV9gkz)5>>#LKXL_z13sEU_~`u_AJa&&&pdyd@sj+L@nf4;E&Asx$lAnf2OBg_%orX8#XV4}u%4 zh@7@F^GTg~uw8Sl6_FElW|r#A&ER&-@6zBpeQM6k8+GP;$V9-m(u|CZ(%|~UwGdv| zjzt=9W^6P^sKz{;bJFqMN97eA_zrGyyl1C^dm3>ovOyJv06B>#qZp`>hr0unwm!)& zaj>7{7&H4% z33)$^3|4s^p@y)PDl5n(X5ULJF3qgIOtH)V4c3L(eG<<}K{P_w3zo1&o9raf$wcfLWuknXPA^ z1`{QiJ^J$mR z2D24hyl1C+3K#}(@^I2C00WzXWt|M_W4_4AJOjJ{urKlP;S5Z|EYvc~JK{%s#9_p< z0P1SKKl*3P*m!ISDrDflsb)EUn(|t=~x#s9C>?7x`0{<;yax3tO1t|yUw*4C8l2r&*sfQR<|Ss z6^adNi5uc&G-b2L6eYVW!6}xcV81dbBQqn(IRf2^~ z&CU}q883mj7Fa~il{Zbc!So$@hs_o46Ut+!3m8y0^8xMDlEDVbLI?ks(Z&FV{@#G6g zOI0{#nJ(!y>ZQiVl>cPoJl0r-G#FCw^eG-PPCf1Zd|RFC*bn7imJVv2fcnG+^#j-~ z`8Lwj1FW`Ls8RbnrIPb@a1AScjx@K?S?m57tuXj=PW4B6h=Zz-VG*`R&^Yb3X_{hq9}m-gF8CFeEb8dl0i+Fsfh z_n^JdzqNpJg6jN*pnOP6R*0>7I~X2jxkmIqMJhRQe)3r9@V&NgsL3O9Nlk>bM>LESOf!1)K@VAD{+VL#CKT3N~%r>DaXW#!#hkILJR0} zNI_i1j*o2x`?XPL;?8A}MEsC@EKu)CvE_nnd#=}5&_=62lB zVyJikyq8I0c8>>Z>AjX2=i4Z~VQH%73mv%E2{RMrt}>*q#UwEE`o)7{FEc0hj3inG z;-TweyF-`o5Up?p17j=`^K=~^aH6B1HeP@J1**bs-#6FH>lvwNW#sjQb=Fx$!)KvO z5@a8}Lf1U~f(`l|u`35*?>$-88;HJ|zu^wF6DldF;;xNuh;0=h{(C;42t^clP=qTK zgntwaMye!VLl)hL#5Q~yQYlLR-4Zs((GAwn-F%RIQM$kAFxZE$ghGJ#AI5Nh)E$(e zNnbe38kECF+vpZz;&87g_QA{eK9-za*pz!3(+8Jy&G9{HfA8CmgsTaSz-j?|y%4TB z3CA64ospMKv%DtUKR;K5!$RIy2-jB#XD>nFj` z?W2yu>r6ZikQKSPIx}1+m-!I(Um5o7c(m5-kFv%A;}2Igo{<`P-SK-I&A=pK#_z7xMYWPm@JdnA{@&=sEj5ncR)~#(}wXJ(jIJxUJnuK9BeK^ zGj<$61a;z@0)3I6x=Eip1V1x-s1{dacj#&HPPPd5Ubd)XQ1eY1%;*Wy;%fJah$uZ4 z?9n{WZjDWGqsFL%!3yCZFuwU289!K&tR&;dIiOvUL|E?#Q(gJ7c?UzP&9^k+GR4|7Q*>D6RHXuGe3NX-I;e3Z!QJfI~eHorYnHTa_ zpQ(zlNuEig*?yGJg)Y59=R2d5hjv_gO*&C%HQ%Pyl^cXs^HYa7_u+)=(hdyOI3fw5 zoE;hLl=m;}m&te%=tbBcI~Qc6>!l(KXN65H@R%mjE5KHTT@5{eIZ;@90!dV|j{jEH zx3uU)4cGeSf=TjLLX>m14Lp;?F&p2meQ`9q@m= znKp_k9D6KGkP^MKJKzaNJSCCHl3_h0DRaQ=m2D2fLu!0D$Oujk6izn^XZWKZqN2L5 zYvj-9ew;sw1uUcci11$m`P2Q;d$AGYfByn8#!T!nR!bWB;kwEkPH+cLY|zI}Z2$n6ao z6I+)CrvRqdIeJj7IULh(3QCpwT6z>Af2OB{vih>#+zi&3T%Jp~l7{{t9`vyKK66ED@u5+B(;Nlw-AZdrS>*Y4dd zK(5K3so&g)OfCVVfmxBYI~P|Orurv$lD+Lzn_z84Cf2$epy+uhYf5lNJX;psjpFJ0 z)9;b*(Vuo>Ym>yuI4?Hn{VF&fQLt{$>^8v@uS!!dgY7XN5v~sOk}mo>Sk4ZBH38XO zGm(BMnACXo+%=*vnul{IH{Z481&tm->_gBBOr~Ywi z^}h$pil^yRD_<^CV4}$tGO%Zckw2AeeH@qv+7gs&JS1|68JtQ{e>3MW1nkbpy7MD% z7MB)eL4YFi3d{|Mn1xfhUiX)2UTbWxOf-+wpC73$#v2y|#CU5crJ%R70ab3yiM&}~ znwxBfJ|RADIzH54G(Puzs_@ZZ6h0s0dbZ#L087y+{mg_FhPi8nXZv#oics=k1t7Jie=JMclw=;# zIo;CxfvIly;3@KE1v>mLnu7IMosnaKgE$ad z{iyU7RP}kPx;t{sJR_&ZWGai`)Z069GQR!Q$SIQF;Fiis8(+;Rs<}RPbCnwpi@doR z*d7mT5hUwG%6haXD(}(IpCIiLU+%(+E4oq+Q=lt-h!kguOO}Gw`5cw-AQwnhTErrb zPu9N)*WQx1afgdz_2LeUN#PgC0RWSFzyVADD|J3tw0dx26F9P@>gbVjKFD}eR3gsw zL?OghLhUjV4`35diT^YRZehMqwJ1 zRQ>H*sx1RB>%R3L8k~tZQk<>uqrx9Pu|YcMt0fW!1>$wya-_oX!i@=)# z&guonUTLRSTkSb)LDdtFR9HP?JmQJR61sHa5KI-@RTw))1;WC~jdEdSXpv89fTgfwczXx<|~o{RpOW&Cn1uN0Dr(}9Z> zoT&)Jikve4!bucfMZI{-);_td4)8}G#-P&K2Y!&Ge%-|u5&fQPcuLlcFS0lNn(snGXV z+XN7u6%7pgT8Sg^wiVF+*dss&;+e{tPAQNS@jlimSxlM6Q8&%m_*Z<8Wi)%+qe(85 zVG+uEpgk*f6Rag8jzvctURgNt6w$|P$YSaS&nh0F4>IVc7*n|+yNoH7$?u5+F-_HF z9vkyR&{jz`C!qZnqN6{4>(9j)hD$N8F*z}ciJecdtAGQy z`)ah6#Id)%`SC|_{mpUkHRP-#A_hf7CdWhuvpBxKXX87$)LWNf`fRgGqq?P1*SQtB z^L^9}dFy@(g!WSRT&e5aXnd7*PxRJ($y1j>tx*7oI$q2cD{$v;OU^!fX{d|TbFLm1 zvfl5JMpM~rPNQZ>Asv?^4nI~o-A5J0{AIOP)?=peL8e-ke-9t}s!1)=8SLI7Z&5oL zi5Zc4O4WMhbBxBW)H+DyYW)9JYGrDLk`b0j23eV1*7^&8X|MM^`R+8bjxt7D6oxL} zO%ZA6VK>K7`U6b)BEEnl+En}!L9hl%hTuZKc(_QN%gQT&pXH`B1V;6}=1*;VK6 zAgH{;V@jeUQ}x;5cdNnYFvrQ#Y?N`$HUE%}m$K!x4gcf>+GDI|hB5Qs1>usRpq5%A zG!8ac`>7vUvoJMe^_j6I6V;_`JXnm{kVw~}qESZA>v%BABHU|MbVavS|Uk<+;&~Dkzbs-(})#FYeVp_ zS;pU{#ow8Q#fRocyDi{3sXrP=MRbzSxk^7LQ(d9q2B9j&WFn9Ba7I^eO>5h+hnYpi zf%4G=b{9=osu%t{yW{ux9G!FLY53Aj#*V{pa{-B9SVSuxBU->CBd~zK#vJCqi&DFr z+%)#zg~fBXbkJPD;y30;TcVFLd1Gu@#<)d@$m+)sf|*2XFg8G?0vkh48YnfL$NMLPK`lv6ib7$?n>2-2O-E z(5#0a6(c5ZgP@Rk64}7~Y~xM5n;a;Nj&CvM^gw>`xKqt=u~`&lTL|5uM>+BKLunWs z0}LeCFFFG=pu(DSRnQ&8!ue_;#0Y)+I0_G7W04B{tJX}OS;%9*B14WzuTjAoN209e zP|ZTg7eI0)yLZ)t1RzEEH}-x>{KJs)tdsJAF7u$1Qma$$LWc!0Rl7kR5f0Hugtsv1 zCma#JiWL$@eGRZJYG=lAWM~wvc8&{2;<)fqnn=>m3UM9>zU7f2@O$YkfZ4}!;n__c z7b?3v_LUOH99oFyyzu^sIR9E=>p**+7rp|HPCqXkf(?_L7e2}?9Bs-@au*Qel>gUP zSRD3sUf2oR67K&DB{SavQEB!X(4klN%I#TJpW+{^R>fwoo*jDi!S|mkBwp=Ovsc#+ zy*j%IxS{iq9~2!65v_VIuluD*Oljui_ow?qSk|KoZ03-WR5!%k0OMpyCp0Ar4K@9iR@_Yzx!Mw{D%MT zQY09)uN)Ig4cfNRsIA<7Oy$mI?U!0UxJrXvf-^Jm`@Z&-W_YIMGt9FAu%w2Uj?ALz zM9+7Z5yZ`hnUP9g0FQj<&lq>9GPBU#Sl)a!!n2H`YJE%zKjbc3%`9sIj;LmlU|+(L z&vn&z4mUG})&AHGM6sq-$u71M{yY+_fK9Fx12f%ZoTX@E}Bg`T`Pwm{(NY!XR`e5xy|1E_x@lO!$%-P_Y zk^ZZfe&?Ua^vmZkb2?H!KuXm}|4o(O`6u=2>5n~44OX!Tm}cAnb5eKn4?T_W5+;I& zie}-i2>A&}i~|qNG6!`wCv`Q#HV-KVf|GUo%^prLw(rS8I!n&D~0UupoPup2yQh219L@4nb= zmcwqdG`r2P*=>f0-DcVBHgnu%d$8MVu$yf^^77kk^4pVOopgR{OC0ycZ?lBoCJ4W4 zeiJqWzk$h2Jlza&G%<&e9{`*^_-%y(p3ZMli&gGI?vLZQI$$7to6c`D$!{~g{Pq{@ zqj@ig{4}deh0Si{HQ_VOaD_AW;57`q=&9%$riDLx0y$4mMGCPsiLLZrPYvuZ8qcrg zc7K6qa(x4N_o4Q%%*uHlISI?j?Ay^7hs!i8olGT0%b~h$>nb-k+qOJ84oZcM4sP0} zqjNXplNX)FsH{c4O|qoybQ^=8j2@;RkVVlTEREQ5iURh@>)4BqMp}BQw^7gYEb}6k zdWFiKjS2pj|$Vr?LdV+aE-4ZE8}=4wG^Zuqn0HG9P!BG1Nskc0aj zdywr&5+q;DF>Lo~@L;kzfqHPi*D4bKHR3)Q1yaS{+{djV@ylZFDCXX46g|X6%-2QJ z?tHYb*Mu*U!^m0tqjm=e<4bA$_uw+$DiQ}gwzjhhtv%t*t+k58(~r3yG54i(Dz}l| ziV=vteHlfP*?Z9BlO3eVIt5(A511`td) zqZ-sh%0P+s(vm93St*Qfm+W)y8g$^C$s<{lA==NCXJEU5|)Xr!MXht1iK(a&3=oTHyR%J_!IA#Bq9_0}@UR>pII%YOXz zx?nc`hyHqJ!(6^E1^lP_>y4c7Q~mW;0E0dK^(G>f`gi{N{pjD%zritC+h1)af2zOU zHt;k(*nYad-oIZ}g!`HPdS~MpY5)FubK%SA@z?t!K1rO;>p&d){l-+&{(ARdeJZJ{ z`~&Ip|AfC@AK_T#%=2I4ueTiJRtC6V)L-wzayh^B`spg?L zKuOhyeIc3nLd$=nzuuEFFMer%z2{-$m$Tmg)&6=0hWFR;*Sl!3Vw|Ht@i0zuJ`}Y5 z`Rn}|Dp5(*W5NCS>s^7PCCq{U8h^b%VzjX&!WOEH&%eCC-rbZUzkt8qN8A1<`0I_P zgz`qW`lt%T0{U`o<6%;xepZ~;Puh>)nKk?V=>8byp z`0HhO>i;MHdKDBby8r))zh1GY{!jPU8?#8b51P8iUyqmmX#CxWzuw=s;^<20{(1pjDVs%pIe)$Gm@Oq$xAdS&Jp%hoeP*Y2Y~F}wzP`t9!8E8jmy;3;qnTS9FC%skeEGqEVmus$?L_(E!fu#bKq8eQ6CPc&g?g$C@>Xz;l(B~E zrW^Ywjgi|k;d+l|7>tr`V>oeXp@?{nfn8~kKoxNw!*3i&WMm||;G7i) z$I9x2sKdh?Z!tkPD2~$NGzM_9h!1X|t(IbYcNP0+GfXRTwIQ&>9}A*U%vf}RU&Zpp zyCM8qjIWYv5>l+R_O&nRv+yXwa za`n-oKU(OiZ7k?Xz~%fGK4jBS4$j)?fHpnv0vh85)OPQHh6|w2(*Zr<0d$TR&<>2C z-5+*_hHp9_^SXh3BAOq0htA};HyDDfgK{TY9t$@ZX?+i%B~x|Xk9_63v*9^4SLeM8 zq3Xc-I+NbDbK&|Wfmjo-q7);AlK*vuJ5fQ2?#Gz2D}|$0gl!k+>qje;Ah?1+$24eq zewAsAX-GbaZZuB&K&2_C-sJgdUx>D}+kTHj{Hvy59mV?}U6qL_-M?z#ZRA78xrPir zZNL5o?-sja*Y&1O^RM~}X9%`Sf=4oY{i{Ai5y#))5!f7mIe&u!K;s1P<8a45ud?I+ zKztzn&pDKxZ~{s5ulfrp=a1njPn>?xbHw(q+V(-@-3+5}>b5mT{&e`lW1cC0s>12c zl+)f$PtC&s!dWR;Y!psWZdCcD{>e80rt3qsmhHM=*o+IQ)Do8<4e!$V;yuNrcyKD} z!F%csd>DmM9c$U{A3$jTslqAaPxnV=v5}^nr{=*dT~f`yYv(EDr+#D6blZOlOJ+vK zw(F+i{s;Z1=v-!q2azd`W~O+UWfo37G=F-xaH&7~0*a?OPmM;6CY`6wNpD;Hf{LaF zii*b<2MVY7@4OHd#~*}mypMfn4}1`Q>?{EnH6-wLTsf4Z$-sh}kU=-8RxD|eF8;f+ z@vnB1BH}mZPluZnqK&X@rnpH>rJL0B;&KjmhCc?68;p0FbJFy2!!SN@M*>m7N0hVT zXw((fU5}%Y0U=H{Tf2l(n-q1W_Egj34+X_Ce|mB$WXPBU0{K(NKW>Jn@|0hEo)}J8 zo&x?WY@rx2+r6O!T{&h79y1jljoq{^VFlOkX=f46kl9VmDVjmllMw1YED)v6xNVs& zicZuipE)V5bjo{3X>=Z-{WZJK6aDYZrsT;;xQRECClQ<|?c0B;3aAvcM z>_wiKDB{SIfs21hd6EHW9O&2HN|Psz&qt2OQe0A1ct)f1kt`tgW6no58lLkJ<-fGb zP4f6Jy?|5@!|T8F9Fu;+k;$%Sv9vk>q2J!FZN%$!T3M_rT-uMFLikQ{~`aSiI@MM z|B`Z<`5)`Qv={>Nf4Kir*UPwS+g@`2ll_;Dehdc&`}JSiJ`<&WY5%1s2y|cmOLwBc ze*BlNB#i$C|D`X$gZuPfszHIh`!CIA?thv8(z$GHul`GIn7eQPr5%r;xBK;9dXJ@k zzW>q`g4vh<(v2waU+KT}!^3EAul`FPGxtCBU&{CxJJS98FY#{k+`)+{P*P$4IEgCW zO|)10Bw#H3j587oM?r6PZ;msnmW43$t|j`jKcfHwt`BWZV{}iSeRKRyl;plpo0)fE z??rv{soSyh%^T5Wd2!dv!>1*Egs1k`ytaNXnvCr9sdy)`OOc5$cxrP8S~$x>w1$E0 z3^*F+wU&GAA0gd?$|kI5yB%Ev~bW&E4x(PZUIzn zMg>^y1UB=>-b5Mh=RtDT{?|V#%5SnS%;A7T`<{h>f^5@L@0-2!RXJWtgx$0>I5Y9v z2eG3V+Rp0V!0^`>HyA_PSbya``I4m#=nDeQm=S0z~s^R z;H^{K?ghNW5r4;|!*eerl)5kTEgk4 zmv>XQya{&%==drYUPS2X&au!I-isfS--(S^kQF^qX<}O$_y&&vRAk~Q0Gb6*8=(upRMx~%c8G+@s7W&x2F-hO@_INBTanIudq-^bDxW?5 zH%J*NT6C~~GQ9YJ#u7Cn?CEd?;IVZ*9liz}Ggy&c=C8U89#zuCRtPT|!`Lv#@UsS=fzv<&TwOCVSp(*7FT_I}lH(BNjO)o{-IgYhmFuhmJ7u zn8d_(9fl6+HV~m8J_3`=WE<2_DvyZKkbe#kg!S8p5f*wLCDqy)L$9)@TRy4@n_e5a z<)%z88W;}E@|7?yrCxLF_)hvWcn%1+ZIygbks!&X;0m$QoO>fj*NJNJ7b1vxtS`9^ zU~c1K;F~+1VHhRW-A2RkoAfe6P=@oCcA?h)&?c?U^vq!el{WuVWPQqhQ?(-E- z9FyUX^2%@ImJyj&(M+N)>;ynpUXzCUnsn6fy@9zS9PU8;D-m6@(lPr7t!YfzFVl(`yhftfKrc=5X$F5uc9)A6kc9e9lbA2REX< z_>61{pGuZ-h0UF4YY*yJ>1A#qKEG>>&j#XCRO%x0box+rO-E+U^-U0m)768__hJBT zH0A0zqg{m8qD*oM%%Wodw(pDI3|D&IH*xNZKM65~1Ur71lRg~~d2d+UFN z$$)RW{9?`xZ@;cn`A++c$lxiz3!{`){z)Ww;oqvhZTLMJm;VBk^_HKfzU}hGB)k`& zPL0a{klx=~e7c=2PWu|jFB|ZY_^{6z3%v)CS8_}ct5Pj1)S+;&`q6!I9?GR9DK`Zq zGQj<_z$sY43m4E6fHFC%Q!YS?hoXXZ>25ZkBEd-?zUd?a(u*_XA~UTf`j*?aA5@fgjjfl}V+ zqGvTR#4lBlEp?>-=2OB;w#IX*hohxNLq z@tj^Etws`%bAknoHMcXwr1wb;!C4eq*e0{A`032SjrWXBZGZY%A(lSk1s%Zk?&$MgpBaXgA5WZZ_NDv?*7zIQFM0Z&u#2G)wa>&EoiT z8JVXi&$QvMu>f0?I^zQi=Fe%;FT>^xB7!=n68{a2R_WdXV+8=n1-HowKRu+2{}}Yx zilVggd#F)oRsnw@UpK*YP$&6jFY74cnpiJ6Q~FnFZ;ddu`X*$fxwf9+7b9gTd56F= zjV2>qHtd~-SqM< zJ+RLKEqIOK@wMPn1&={h0FR0VTH&*Qv%rM3 z=k+Nw5S0~rXZ4;==w~6B9n#HK-XzVsx*OX^5MOq9HCJI*Y&|i0!_A;;+LVcqz@cC` zMCzov4zF&9p~H#h3N#PN>7O%NVu8v_EE;3#CVf{Qlyyn-ErO4&5H(WXB%HgQtrpH= zo1mHW2Il?+Wvc3;q|+nUm%Zp1f{WIDD0G{f8v^WkhV&gnf>4sZNQ7yPvu}oJwM}KO zw5a{AMtKXzl}H92tzFMJp5k}TFxr*xGGKhe=t~b|Zj$r}@)uha8Dk_`HwTexjKK73 zl(G5Ha+)riAi`L>;C>#lH8D$t7GNAXf;aq~3ke2__&Zd}*}YE+qc(Ew)BKiSSen1l z(AYa79f>Fmim% ztho`)ysLMXPi#ybYc;+XVkcf=Z1Zyf!T)aL6k?6{@qHzj>b}J~W07|U%>?m((UB78 zdnQINae^>Sbz{`Fhs?8H>}@;hxn6RjXwB#J&zUQai>9Er8`ub@j8wUKSHjEOyr)2G zZgiHoT(hikjCF?2FKaWHKhn)EBUQr7{Cs!c5~Wy~r@*&ArI)qX=^4!sKz>95M^jvd z?S!fRFt34ky1DK-wQl+jISEYR^nYmt!5TdkaB_?JlPt{HPgnC0?)fdGuxsVDNr~{! zJJH$>1&;8`*MBLgRKj%0>9L9;S{mwkE8u55L=4@mXKeNPC?JyffP6XhkIh0`Hj`B& zmDBI>PF!e~3tFB+%bDA<3v;F^+iZ0kV~fgh*c=gq>-h}?2mJxjGdG^qCT& zS}$lSN7q4wExwqYMvywBXp{~?oSKTzAUnICjbKzi_vB+-QV~>f`&^Mzc_Z(2sFy?q zqm;wIojTO1y48G|<5u44RL^!toyxg>a!9ZuRLz}uw!hbsd*!O<2Xd(D(I9_B_7weJ z5%aE?>4|P^L<-?sX-Et=IRCiQSrdu+_wRAnp7RQe% ztLT;Zo7n$sT5v0Rdoa!ze8pS5nXie5Vz*X5W4*`RCcB$hE_C|>NqF!B%Ps9K$x zd=g`-E@~QfsR#i%!j9V1^BJg(NtOfG@bwD(w$z?>b)q1?i@lt%Zg<2og{Do$<=5LS zznJ`kb@lOm$o48Kk|6*b17ixg?Ucz zDVfq%60QA+9}+(XTr|p}9Jr~?*KZTh-!BoM&7pO0tU$@?KXVvWPQLWtAc@2#X1X$G z?ZvWNAO>@-x=)u+(m+o4d2Brp;E4SE#81LUaQKm;9 z_4%lvG!x-`nQS5(!=p;iPeO)A4d2xR8X=El$&_mxRnyh^AI z6?i_BLtp^~GV}AH`bb(%Wj0H|Eox)A)@46!!F-b>;!z(aa?}Jc*}M#MICrl*34NhQbmDIEa-Oes}p`~)vfEH z^Z!)*>ZkXjljp^+rk`MY-QoDv*mD3+@vGvmj$iG|oNOb0)$**-uJR<&i?DPkezof@ z5=@=MuU7nEyYZ{4DLbT^#&#fnwevRPSJUPT{`~mWxi?!}?tAaoh+mDJ2HobxuXf_i z_TpD3q9Aeq&Cc@lEYey){3;pQm-|jWW}%%jXj?%nuf__fLxzeTLuPv28Ac;e6N+Q8 zl$hrHXjbYFW_;R|%eNEC`hb43%2Lj+ekVH#I}c?Y1z`}%+BtgtYz?5jxBD^L({hGk zphdm+`6|=Sq5H01CKt-um13QSvTg;T+X!Vjw~3m=p)5s{LWwPnf7ryaF7)GAA^%n` zE~9kx9pYJs3q(vntexp5v!qt{pMVtNS!W_~4N^PCvt+;e@vH|mCxo;#&AB|Ap?FZA zM_5yy2*j50hcFS@_|;??lR4QmPyprT=SE{{whJS6&&T~-6Y*?^`&WT5G(WdeMl0XB zGlJNa^+$)`yy0uzgJ3J4FhgCTT#1A_IVsd^5*T}2do=|lSPzZ>h2#A-^8o2Kv zM?W_)n)K6J(c*{VxB7VjdJ~IwCvm+ShUGzdQ$CbWo~ExI<9g@j1F`(v{9-1q_nrJQ z&r&9Rh}4^`|0powOQe*9{r8nX9`^U2DApG0RrWc6FUDgYd>h-r*Jz)E@-v0_@OTbrS3YC=56Um(G1ociO+rt2 zf^!ay3wQ|P5hsP?5x)@*6pxS`FkWOd{Zl8Kc!XZ1uciRj23)n_YQ#34jOXtRM<1Tb zS;KSb#1?(ah14ke8;aUDFZge!XWu;GznRFJ%w4wBz5crkc$c5gNcXM1jA~TVSQycI zvl@oA$J|V0As1G_2VFNnV?kc8(E^i`IyJDlH_LofaH0ARKeDjvsTAu(FFKF%Vi=XQ z3&6oYpasGTVQ(T|Q-2v{z4R^=<_8nxIh1ZO0hrkbL*G z=nSU$q#_921k@MC)W@X3=)v#Ezna?EJ$ zo$A=s^s45X4p|2JUB^pv+i(EF{!&}Qj=#FO*^0vImyWuUrmhuQp2cPCo{`V~7=h+n zST=wl>>*sJbqCaAYXP<&Ls&>{1EOeU*yExetk|5TRi`+;!FMpD*U`7a47uRJErKl< zJTU%x!D8bFI*m&F0OK?qKPWb^gnhdP5M-jPJp4_ddE7$jQYUJwos`nFc?oL{_H-|>t8Alr^Ed=>lYe!LJ8zIi&}R!z?=^L^xUKSRnw=m|Gl z{Pd)zSd10X2(!KK*QnFK;5GWw^txk!A$7%s9n$el;q)(rqd;~~K(OXy_pLmIJG*}_ z;97n*t{&%l7Qyw5flX>wgq0GX;ib`c;#M;Ey&cKyJ0{|TbNF{=^#fM7PXEdg+fTTN zWiQ$tNA+|s-dT%Pe&7*;R8C)2@jbH7Ws;H`2Aof>gg$IGb$EMi9l%{gNn{}yx;P*q~qJ@&jl6yE56b{FciTd=J#0a}4G3 z1TU0-cVSuOoM`Rg6meto%3_P~@A|1s7b%sg(z1s9bW5`OoBXni0>3QDh%@wUd_?o) zmn8%2eEhpv$hd!&rT)=yOTON$b{-A2QysK3KhM8ASNU7#YTVtEO%W|dPyamR-(BS5 zFOSVL{@pn{>fgPZ7XA(Y?r#X@$|-8>TP8?s>{TyI-Lnn~47+&ypUMk)XfbfEne*}~1gslQyo=qqzRT}jWl?Xdm^0M7HKAROdA3Hf#BmsKx{*8V`; z7N(b1)o;$PyKQ>eOUs+`OEb^Lznd>#PSwJSc=H{qQxLo90lW(ws-&RKTb``X_RoM5 za;gqjEw;(~PSs7!w?u6-c23A!SnqIcG~Plo&_dAGTew8meFNM)yoE=o+fGxcQanid zYIA_jr}!`x54jDW2)RF>0D{aP!e5(1>0E!UukDT?yrB{0lHE?ENcwq=2z|Elj==K^ z|Czn$*~G6Or1#cZ5cccVD>c4Nv|*l;B3-vc7gU>Ij8`!dX;Jg>R>qlH$+mL1!sXqyy-VP)V%^n+ zPKAn4xLE2@YRx7fqSfpTxw-pol52<4ADh)nQ$?o36(O%c8XsfcSUHVlAZR_eE$+T|L2$Xl-xC6Ivfz{Podq zoS2Yh+4{tLTzOws)f^v?TWViZy9s61Hv2TRzAnkHuf4Q}<(pL>3#A{?#UtFwXSx%H zvbdIQocK-rCEdu=uX!2$6V};{lRh)}?WZ?Gcq8RySP}KU?`(Fb9_~))WosUg#Ya$o z&v1Q1>4mmF_ME1&yU6s@@tS;lMY>zvQdZp@t^JW0q8(!H26U^xX4T}A zFUsHuqe1#hN?+(REsIB2OK>xQ&7bW`$wHg4QqiBk*7QKi1zQoKwGYx!e%rU^FIO)^ z%js#n%P%#|K#;wR?S7Ryns@o7eq>606fAv7m8#Uc$;Hm=PW1|{RV&P-nzhP6oUpO5 z=EVEy?@%;YCF7UmH@ymkhr*PHsp%!W%M-fVqY_%Px~kARH5yvfh=padkiXA#5(~>F z?!C>zSOttskXdLfj5eveVColCy{W5j>$hLag*N}HTJ+0R0 z0?^WDv}dCLnB_OC@B1P`zT~fv zKf6+7Tk?mEzuS>NzqgH-B|4Qqe^tBNl|OYs{T-4&uj2R2mp=`>*>U-EOSry~KQ*>~ zAb;A+9b@|b%W_A{cs|pyf`#SIV;4f&=ksnyLRIfAZ+mBR`Y8d2g-c zO)o9ZU07rLyOVpn6H4t0+sm$h+4cFcANu^E!djm1;YD&uFB{^^>U+pD^ksXWfGz?a zw?1`}=_^5Bx}U46v}|eolDZA?1eYPnryE-%XBG>g*_u30D|GdmLT52o62;40TrtG{ zWiZ;)eyM+otEyV>GCPhps)>{#D~+R7MC z;82Ob&I3vSM^mJ?z)2klEKRXB`VBD7;`Gm9Iv{E)w=S42O9?2XC-X8peBn2__AuXG zIQgf-@->-|y`WytGD9eFnk;b1`eLV>+eNp(9@D$9O-4fM5LO8+4$Oz_1(xpvt4wX* zHTxLAu|$VVh{X{yk6!e;-TC+#dc=R*d^`+a zYim>TF!G&5i+6R( zsa%rT-R@)NYU9dfasgliRACjgBtI!mri!`p*oiG;Gk&bO&*$!`#})UD)jOy5BZK!6 z_sru;l4;Is^y6yd7CbcCJ1F9q3m%e}ttd=9ploT~WcdlS)wn?ut;zaqm}KTSriSzG z?11Moxz*0Fh%S$^?ia}LM>ONcT0^GHA5bOQ-9zr~?cYmfhZn8oUQXOm#a?kipOp<; zyIitWAIh4e*FQ#O1sR#5`l_m`y+r9#M2Xl1RZG0cRBzCA+--Ld+W_4{02&ezK+Vaf zBEjSz*LeF}U^+o5yYM2Qpsxg<@eAxp1t+n>X%p@e#opD$zTHx{JiaHlL+-5mOh-iA z;YH4fBIhcaEN0Tm)+OErb;5zFt>A5+Ca0|-#m#Mi{T(kd*c*Bsrt=C^U2vFeDCQb4 zW+;A{?}@=xLq_!kP_o}^8D<)1q7QJ7!gg@_yAvYL6%ps9zKIoXIY>Wti*lU~VtZ&r{w{&kM>a1)|Tm+0|O^J_Os_f=4p6V5#dlxl=ELeZG*t7+-y4aj! zFcX(J-83nY>zsqjzEN`_Gb+sq&|Iw7BJ#3&oaTrKe0NkW3VEf z4FHM9`tAwxb9|`Yq|KW%KPspR5nyMX;M+Kt6ZOfxq zz}tUV9(^hr_&V~a63hMn%kn52n(I^^;m~Rh$)o0wJX+RK9#yVDcn0$5LR9|$v^;ur ztO%+Td4$+O9xanRvM?i$mVJdh8jW!4Adh}`Ci19^q3nn}ItXw=@@V-OE06BJ`ad9# z9;fj@9`zB?Baa5qk>t_Y`lcNRA$jzBc(11Ml~&24K`gN7=O+bm+4%XsgFm(+(}lwf z6~&TzQoNDKizEuU&1p)J^oXhziBffS{pc^Z)@@BJCpWLL55g88F6G>*rCos~^VcBk z!5SQH`}|zn+FHGWmC`obs%9%p=T9=B1o+F8TYEba&@N zDTNQ5r$MiNSA#wrZMz}W-MhRnS>H9;RunB?j9KKAM|8t1TIFelyt)C_<@P$~*E+;#0^-;lz-sD0NG`>&)SfF=&t_-mooB zMQ@jX$-s`9QPInruCK}Wr;@P7i_GNIM{>#G27`j31^HQ)SaW5mTfHV5pWJs8FS%bb z^=E!KOH%_Wq$#*p!j^u!spbYeQcc~om^D=xQ!AyT5|rN6FWqYryQmC3n44!UetwDm zSkt)Zod7?Kf8+ZLg+FeC^d=N07k5o=22(B08IgwfyJ#Ksm`~xYi#saP9!=kLUMHVU zr1yF>jMRk`%;6`--LIT+DHXs4-b|HnAcZj{-dJ-e=5!FHo9Mio%%{_OIb#kqfI_O~ zZc47i^&->yEcGG_Xv2%tv_su2rHwpBBi~pOQ)WS zQsB6AhCSZ}mqPTyCqb}L)U zDpyAU?jC6pFls1n&A$4OQb_Qs@R=eq+@VTGA13P z+U)jlDp$EDuV)p@>~8i&l@~3IwH7k;3XI9gB`j#}r1jbjhG9{bSQZ`j5|F5Ww{n%D z{YMK53RSJ>^Ecoa+E7=2)l+VHF|A+`C!U&C-CE$ZIV&mSEKUrU{aC#kJi&&m6f>}= z%~NYnRWmF4yri+LtJ`qZDJ%?b)#{~S9#fiF-9_sqz~r1*iD!wi44hmXAFqX|{xsFa z-Y&s-b$hrI7>)*2_L9>atyr4533ms3ae^%`N|4UoR^YXSahRZyE`CL_B5`!ko#X38 zOUntZXS<|zZRVj?(1@9pQ+thtjZdsv?J?+xLb^{}f9I zNykuH`YdkP+$FiVuyCapIkBu^;)MvNKAZY)eI?CWF|GP7HuSW4gJv-6T~FZnWZ%k` zhD}|{s#~Hryv+2;#@NVTXG*Et9U-@q6?P@w(A&*wU=IG-cLxT`r=c@U;^Js|gEzFW z%kj|LiGUQn!R&*GwKB*4I#rBt>i+_>DwM`r`?N8NS5gfh`+&Xd4XR-{?rEi6t5*|( z?861)a{cYC>Ov|Ltf{$(<$*?6J!pvq{YE zsI<<#`_}vcwv}`V1$;d*zZ`7mMQ-oYtS&wWa<%&bmS(DsnpU0~QDCm;E0QyD15%@= z@vv3C93aO>Z>ObiH%75>RaY$dw!%sK26HWco{=WVq*7W{*{arH1$rOBqzNsLu#HlV zn>F!%Ffq3|ba8P^@Ol{Qf007#k`68M`T*uY5&W`L&o-bMc*JaC=6~69{E$KV9DEH#?XL()R=k>Cs6Rt?s_k7me zE02$$h$X!5ZVp>?)^L6X0^RsV*V7_p%@cL`t95V6st2k!H*=Y&n)FASGo z-aEkMZE&&^c{bTpSXRB}$`1mi#Y?W=tPj0YdkwdLcV(!_t%Vc!GdnlscrNelMjquZ z1C=`cWGyI(RO%ysfS6xsr2vE}KhG`^K7Kw!G}km9^t$EOn7QwJr4f!r?iB~RC--zd z@AG073+zfPgZ+8}zPcRMi&5*xWTCTaO|~3+Gpbsn(^W3Hxo3373=KCj4Z+7%-7le4 zlr_gs%en+J-Nly;@j>XJ`!@+S1x-WjdNahXH$!ynwZJ(8e^6=J-x9C7r$-Qh-k-$Y zWetfY>Z4Q9c8jhBS104va1A&Y&|mN>_kwdlxV?5BEzs)G#LHu?b@fxO=8w^THh#jd zhRt0Y+79Tm*o(|E{l!+`MTY$gplKssXt}Lx{o9U%JHa!K6{P;Z{`{PdhF;TH!?wQv%jM}J z1mAyyJl)Hz`8j!dQ3b-_Ys=G@C3_H&J0wr<@e3Py`aSyZRG$6;hOB8^#WnE?&amSB z%kuPQgxS9!Pcy>Azamc;YkXOGS{g&1KEgkUjRAa-*ckTHtUP@VNrM0XmH$iRX@%t9 z_T=gFZF#!&BwwE1Hq;>I07?rnM_kfgp8lT25dEj+|Cgu#XUfy9@Gtpa zU;f`9PmR9E)veDo>E%fZ=kt%!OF_hLhamiriE&q545|mZhVJU`Z2vTw=*KvZ|@v2E|x`s9*h&KcJzd>VXde{kwt)5x!A#J5(ew|L28KrKd7MI;+#P3$EJ zT!%pJbd>vrM)`VZlxqNl}yTw7{2Yer4uZl-@Ck=i$qIuGqme>WVj z?zrN7i?bHEZKk^Cq$~oz+5c)Pzw)AyFJ!0bR{XXZOpe!MAv zN4ET0Fx{@a@Oz>ub_K<>-$ovi;%Qe!3gSimH%yxxDM%dP7O?I2xU#nRUjF`vNNH7tz)|-68}R%1+1Y`UM@6QO z%=@0Y565CnLsN6GUwa%5*_)Kw+Z|jYKhfgO@TtR0C2lzd;=8${N*g}uf+@B8xJLZF z#xBw%Sa{U`zd3(n)LWv+EsQQWBNCmnxMxFa&*;3Co(-FOI^Cv^iJbR!#`}LDJZAq; zTdJ6qvZnEbCdm^~XI7Y45$myY00A{`V3@O=nD!8*zAa|sC*M!{VTb$JMDNfu=Nay2 zHK}QQYiZDhM7Qcsf|b3b&c=jEIpDus{Yy;!-*%{ftf_zLHtLUcn&1enWHpUHq%Iu6 z@+ONpbsmgve3nZE`%Kf!tq*=7877(RC9hJOT3{j!(aQW0s-v*hd4&bzwSLif3*xn= zv5RT^z@YI$739=#c1P7Z3|cQaKivLVLHl!5*kV)pl6-9bV;tCQFK_7YeAC~}&ucLK zwnv^`Y$FuvCDz&Dq`sgRAL;iD;y1`Yj!|Q{>*piKspmDq#Wm_VZq^(6TZdSvY5bPy zFFU@2fHQA=*gTA{bNnq)VLQGax$*7Q+4!>jDt-pPqf=Ly?(bcq;p#kwi^n)_!hyR2 zv46V4$}!5IN1FtE59)-~?1c~&G)XTzORngMOu?5a?dCRRf zpo*ZBi)`%{gLp$$`@v4my3`nvfw}wea6l4u{qr2~Z}xjosntuK^<}P7if%Mr+KHcO z)(PS&QSRft`B!?Dyg=qVi1w1bLN%uh;7#>v&!kNaR=YBmkdaPX>J=PsdRJFUJE?mq z>YASxusuaC0CoX@IZc_hIekDAQdMl1NH(%{Snut31vyHh3r0qg?{!VSzoo~EECj|G zAHk2Ce7|dt7foH}Pv?=CCA*n(A{tgrM*h}PCSi{sbghB6*v>5n=OW3c{hGw)=#YgroExxo2`noE2mx?oHMKr(xY z?%loZ>v&o{MrSRKE*KU`wr=UsGJP1A$>OY~?3QF}*B&iwE6bZ}Be(i5S0+>K*XcNa zhiQ(Pzj}_6S>%5ISc}}9e$WZO%MpuTEW7Ea_<So)%OFYG5m%6XNo}iv&=i&x3_rJDSUZ@dME3pV@FaKL;h|o#TzZi ziM1)tQR1TA!gkO^n-skKd>F8h^m2D+x1VzqrpM(GcSOWt^V)DNmBGTC(z;Nt?noxRf;X3*4(B?iG=S&$={x+Qn%r z`;zF6W`ccy(1C_@-%(#~)iDDySQK2_{V9GF#7mh)LT;fGa^S0MBX6TOFAiQiEzq~< z1LeCngrvZAg58 zqz7M4Npi`7CbQtg;>=(2@tGU%B`|bN<8PnynSqUhZEin$IL;jz>0ghx7exqGD0?yS z4dhV~@gB2|MN$j;OJbp?xacgClG;wDMZd z8wSHPQVR_~_ko0`Vgp6yaFZG4X}lWpCnR}?i>m{4g`h4ElFRVch#FljHY zM!B&o7viqk+UhTZOS={1lw;IP7TcZ_P1Qovghtv2U`;#DNVe0KgjI{2ewr65&b6G~ zUok#9wjR?gq>Vcw!sS;Y&ubd*TV$wy+G#xsmsS)-@(Bjs z_i09vgo`&@_Q6ISf z_i0~>lyr{LzSRLrYm}6DDwrH*F!>@F(%Sk}m|U#EeGN=52SxdqY&o(MOuFDmm^^rW z7?b~?Xc&_h0i?8*`6SlLF2n6Gc{czGlVxhjVDb@KQLQP|GMMz&N6wd+lO<_%qMF8i zpR(%>)Ty;{Ro+@TXrtCjZ3($(Lu_@|#EFt|9SJs|)^6%>WT|Dgn7SR)`P(XP*X(@_Qu!mZn@=kDeYX=* zIbW>OHY(MoTNk9*8m4=ZqG3`wPGkUXoRQlmm5Cw@@V1*SlQ5*Bn+8;CG_@?#SuvU? z|5=XgvesVyyL;$By05?Gh0z6<^Z(=`=Wo+FhOlY+ zaC9hla>PljL-(p)j~e70rDYRJ6AyXlvR4BE7OWn%VnR^0!iVv$=Q_uS!8_aPwx^7Y%lWD{4mifHB{%iC{FeWtz+(`bt zkX%>j)2EeRQle27Di94djaSV#B3cU3QgPbONZs*YVfpe?iiYLOn|Ah6eNMH8b31*{ z(&u45_%|T3Y8s#9Y?EO&Y4{pJyd)oD;xJ)rLqrEEb- zDWFu^JN45;81LXxm11X4Ag6S`(7cnym+$|_p9d4-Of9Nio`_0en*{z}F!o8~w9Vb( zYx~#3cJU8i$k`Lqt|}^kLX16;H{WBB-o(HD9L%=`Jz94s6kl8KK3z(3*u);3;|lGh zlzW;L-Jf@pdW_QCOC!z!@R3Cxf|H1mXLU2!;1C4AU7^ZW#s_-kB|c#|vks(AYCJ29 zYkp$f_3|e76uN)34zkGanEf;cqRhMU+MG+(j>PvO^x`FJL&Vp7XeY#%goC69?Mvo; z5oDbKKh_fCj_%tLV)NjwlW@4&1#Ey;R+C{Bf*iG1=AU<9!yg?lGXtgAS4tL7Ef^IKaQa}}dk-e_BPeoz7 z`Og*oB}THI6bARB~*LgRn- zXTcFoCAP?yloWenMCYP}(C6q>jcMvJnlk?0VwcMT){80&Ik&20h-MkUGbpEqZNv&G zUtedwwZaC`VZYzqwQNvfR(%Kh5d6ia(-ZRG-@h~Xe+|Mr8vZ$dmZ7(8z&wt+FSPTQ z0p7T{PuR~&aNAzcuL9T;-crBupx?iaOK)fm`c2)3GnDw>ymsUB+aDK< z!=?R=9A`bi*Mo!huT}fIsr_2N{Yk|_NuY0xOaD@RW#vKYd#1m!?fVJFE^eW z{r)C0oY$1ELHE@nK=y!IO+keYt=)h_keBC;OP@oLeEkP{fIPa! zi^ruO=A*@L&`*B*zxwL-AMC7s(O)E3Uw!(Mif7ha|G9hctn>X=*?I%%QPa4~gTAmV zmCnKmad!2UE0%IJDoQbTj9+`~)}5obF7ETX7n$zx9XBgQ@K+(&jb)Io_$U|`drzE7 z?U|NfPwjRvhdBz!+S2*S3O1CR%_*FqXwBRl_`_|yFg3^k_wxtB^60dK5NzZ$KqOiD zAYo#*S!)T(F?Eh!z^~8GRV5huerh#;f%FAYN`fV4pMfuTBt$45y!_yi>x|H0s;&KF z{JEGSZK+=)S8E#oa=#B^kvmvuI~)kz$V`5H%d6TTu_qBO!~e4b5vMo`{EZcyaUehX zMl0Y6R+KBeqt;RB7 z{|CU6;y`NodsiaMQLDJbOLo1HzeZ3uKf{M4(IxG~(cydU3WzPs?of%=t!IMsZ(AUj zGRM*DIa^+~G5)O}3t0Rd@^@wH>GBqiyCv3A3Q98!R=qEa8~~tHe(N$d8afY>cPMa) zyh5eDh22!!er)%6j60@iJh)OWahw__i(@7;JG&)iXt;^!46$k`v&^4pCOu4a6v`;| zq*raOVdr2>YNq;`n>!2sbT+Td!2E_ypqRV(eE7~%!>b`OZd$T_obO|8NuIoRVtC)t z5^Jy9`NY02N~XI_+r$9{cMoWBFLzY2zeU9mj+Hy1oh`gI>*u!WqwoJ)_5VluPgThP zY?$WWW#bFU$+$rQSeKLjFUWq)sH| zVEgbn@t)*Ca!H9iL)rR9l*(U$7bEjTE}m%Q+mndzn#RnW06)Q=oujQz(h4*gNw zad46Ij2d+6*6^=8Y`r^6KjdFf5$D#O^wq61{|;V{Y7F|mr-`i--qQ1N*CGF`ZXV zs*|~{0g)xJ_AvHYxU)0}PRCq7L32>`p(tI;s#n>}i8lnd+DSeBghVS@WapY@u{{n} zvw1i2RH7GPy6m%>qFH*6F5uv9ZE{)QtHWCnHeY8-YR<*sFUv`p;9Vkn;jF0oKHYpz ztg(aM|;VAzcA9*0DAa0WL2@FLg6%(_WpVm+D_%}f*eMZVSDIhuHS<1`J|KBN*-c=2Ez|tLt z7PoH6&B|?i2}`T;XXT82?5w2U2t)ETMZ=Kv^&y#z5Xr$it6iy`{8DG;mHI`yQt$S( zqdG#R*fRriZG!lwba&?4@*mmavmBSbqV*89WVpUPFC#2gF%T-$;yMWqPj_bzP1nH6kb(Y_7jEzTuLci#IkD4tmoa=Ra*3;ZHMj4C7_E$G$F0n7*H z!+aB>KW{~RwpAYdd;EzdZTk0GI$#2uC1mv>eG9>b&arI*F?95_S#`}d=X zN*Z~1pz4D$u%{0nP$2!5W<9Ym^K|CPfO(G(_xZHG=W<_0)#o31XBT+Jm0Bd;FpHN> zqm|w8U!QqXmde#zb?3$)`p(>DZI9!i5CL#Dka45N$$auj&FC*7Y81qxnX}Y~A>Gi& zfK+#ZH!NFOZW3EPE=35DCU(lW?c)bEYs37HoP+;=vt9l#rvLw~{J+QlH2*Wv|04fW z(@W0r`TyXK{4a@})9yn2uiU&j{$KJ{{Qr=pX8&TNn3~Pw|CrDJ%PE)R|1ItL|BX+x z{BL$5zI#}Q=fM%g)AYXpP~IoI9=@Iba^|!F1#f&BfAH;9Z=^E!Nv+(DJSfQ@L(QHV zL+H-PTCq)59-P8}!n}C^A4BrsN_3m_F5(yy2bJIMa^+ci7+B!Tv*F)ihpoTL=5k z=m)a@Bxh2Ki-7Rol@h-Frv@D(4vqaMan?>tu=)WxSbh6%x9v#?s|hykh@M~~mPTg` zX#_@jKoaM4hEyr^Wv48s9)#>aQ(5+(p{lHU;0HvJ>9y4Nk||$Ke9M;;nxF@msLmxs zPh4pfF*+$pfnOgv%a8_#TD%Gi@wx61r2aTQ&7+dL_D5`Cgh1?Crzx4PgP53T3% zU1RsZ@sK{b*1n&$mfu&-up}0??A9>hY%vH~cJD)f#vLzYff^_e9dk zXY?=j-bDU{MA=+Mk|yV{wfAHbrmDnT#vx+G+w;4?&GcE?H*4=1O3Tf6SBWH)d+a@N zQy6!14ed2Ud(fNFCjZb~xWft$U zkkiA}tBf{N*&1z6Q>H>NkWPYGyjr3x0;$>vY5$%gNgz< zowGBx?5viv-nx)JcXOUTxB4sexyT%5I%m%%)NG!#=A@VGxl5ZVm(%ACmz)mUb6=&; zaWv%J!!W0&f6%!;ha8uT93TBb{ofJaDN%Ex?G5|GZbLM3)arS+7(LJX3O(mC|gSkIFpk(HC|!p_t4#SxxGkISLN&83eeWCa&sXVtulk7iymxzj?~lO0J$>&aHg8p7D)k z{r$_o{30tw{>T0Ov4|vySw2O_|9O9ZZ)QHw_vB>yy8ixKsZWI2mm>#-^u4FF4&)?A z$lpKQ=zChc=zk2 zK6=Y<2LlY19o|rKd54f)o34wmN{=lq$D2He$9`pev(*Gs> zqC-4jx}nvdhVXLz7s5-sc)$=ulxFRXhA<=#QZx+7zCI*B1rnnl8hGp4mHJ14g?DIP zsUNm0^|D`Tf0g=L@qoS5Qch_U@%gbmG|FZM@>TJGS`CAB<=z9V()iyI5BNpCM){{L zOzSy%7mf#2ONl7H$8-G_}L-acNHv_-Gxef9SXqw+P|L%Z4z<2_zSHSx-jZbqvPhTjJ zX4i|aZP$0Oif@+ePd*!xdNZN$4jzS5m`F*z4;EQ8hWwj({(+0&80j!6-FzF2}7BfBT(aQN5eoIg3`^-Ah-p?@D(EORuJXB@;3@2<9M%(!rHqnAG zdehVXI$}ojV~U1H^y+3iqHi%GvyPZj$G0o>kY8%cH`&-_HSErO2;EdIw;XH%CAr|= zlL*nkhoA}Q%!iN=eqohc=||yV4E#ES{PalCq&ysEGD>@=egod@K+>nGA3PjG`5TxU z$82NHN98XLx6(@b1m2}FNUfj1kcf3KykI;Frbj#rhvj;d10i!G(7oHSR{Bmp8h^sZ zO`6%r&rb2;T+wA^36PxYh&w3X11=x4dD6qL+M!AJL&Lx`A7pT^miRwB7MTKuWFRI5Jc zHvNj5UtTZ4>KCy7wy=KRKAt`D<~#&9NCxN0_uuFEJX(7ekOjOh*TQvt3@P=G!9i&) z2v&e!$Ya>Au>v#;#DlpXxYKy{o)Qp8s7=Gi68^LQ&MP_A&3NB4(J=@jb64iKf%M6X zcCV8Z&qccr5=5(cmve5s^f!iRof{@*6$H35^_f5Hm|x>YwXiL}#))voSNS#m=_6vF zQX_fSrq5%(a>1;7vKa8s=h^dt!?g*O?Jhro32GXDeN9N5B{z4E-f$Nh1xHkG^wpr8 zek7c)dfDhhb@JeAf83y*qP0W$-GBL@2>UkpHK<#(_7moJQ1@u<`}}2hT-{N;U&!x* z+U4;f_6F~P=8~=W(OH}Chm;9j-o1~xynBV=E#&xYCWQ2gEBv@cC}uGcIJko(;J8{H zSK;IzhXkCpJzB!&w>m4wNd&*#coW}QwTwAl?8BOvr7F`lca7F5p@`pR;+mj6W7kiVhM2R`<;2fi;L|VdoKIvb)XpZR z*0uxwWx-9`97!CVeqS@5)o0cJVfpnM!u96!P^&->7|TPbzduU#Q~B`MB`(gX+g`lM$|KdkWn#HN9&6i=PFujvKWby3=8%FCa%vk3FN>iOA4fW#tP7__qECtN(iidMPT1m2 z+3HN*lK!pQHE9gGe`m||-tpc6fA7=6&!ihDFS6rpT3BB0+O!lUtL6P_sSDwg` zbxu}%S9|o2nOU|j-qX%k@>8>`#(PZqk}mT5RJR{uT)zdw2iJ}=P03WZL4}i^a*yT2 z!F;zOo7?To-mFF7Zp$ZMY|Z>OH=i4ZaYEN66Aw+DkGmp$Eku&PKRY;&Y4)>Sj~FEW zG08AE%8J%AorxU_7mn7c*ohrajNXBu^OB1~dg^U!rKh$#u6za~Q9LZo=Hl%9BtPlq zAEKPLnd6kDpuJ$?fmzNpdn&}g`6n&iexaeCjWtMiK(@H6vhLBTC<(Gd1RSn*jMm$m z;irZHUigUg6Q2PY#Lz8@OfJKDvG-j9Za)T|xw%vNdybWu{NIT#1vP8ef)&m~vSBg0;53s8CpgDCylC2{ z?z+v2<5arbq0}iaowT1}y;oc39vQ8@O;wErOOE_Pu05LRPATSQgbDruss3A28HkGd z+dn1cu+#5z4rRH=41jJAhfw{4%g1XbXj?2QZKJI#L4Qc~acIOIXeLQOa%*v7v46=) za9(Y0eWLf=l4$Lv%%?I7#L1dh(PM65wC*0kOq07CQzFREw1$qjfVNxHun6A^nuggM z3x*kjv+Alx9yJ@}GGceuZWV&8>V{c&}gJ!+VCEQ&Hxiq&B9w6pnkE6 zo3@>XbX*-8+4l5DR<>>41w|=HAlEK)&Bs)gu$lT067_L8hr{7<2kDrf9p#3U#6fF* zN}_TIM`r7r^XS^_IeL_0V#BF)ZJ1Rd>(p;}8$JxYvu2V~XRDN)n4QVr=a4nf{{+cj z&a)MhC(1o);Dkt`G?OrKtYn*i?qotF{$qp*7pWvN)20@6izjS`=imhTgV>DV)4$?F zin*CTigr)DCMY>DC_Zk)_s(I!f#ygtxf!3-p%yy4*OsS=AP3vo9a==bkwnmMtgk2mFi!K%IqTvfbA0aXP#b2)e(Lu8HtYzq`5esor1hym ztgJPSKfl6P6-y*N$=(9l4A(q^v*1*=f%Nb7W|XJ|LrsS5NUA@*Ez1LnW31IltY#q~8)LG$OP|lDbEj}(H5bCUu~wUqkt6usmBk@Ag1-jEL?=tU zRs2YuE!k!d=a?6EJ31Gud?QK1LrFrIxt2oGf_3!Ay+y~=z1ST8qccmMiqsi!pKE@4 zv3b;y+MC*fE5hyWRn3v%=FXCjL#mEvw@vsn+MTTyUe!F*AlDq3&_0inM?UlD_rAKqm(joL$_XRiFm&|UlCucf_A@vlq5uEv71QmZ2v!@ zsNb6rEGs{@BID5RzQ_PQO&atGpimU~ef>qI>|_cE(?D4R(lhU6mLp`|3dei5cfS51 zbj0@O>;3bN58qfQ=_#wzoaKeZAoM8Cv5^0?s4(jFWm+vA3YZ`Z_v9F?64R0m* zfM)%K5nO#mUL2)7)%8Eyqtr)4VP8e5Z&FBq;}uFum42u92HJP{OzA@hj-{R!9uvqKg5> zko?W>bwaO|T3ykBKfKQnoKLS$P&7=h-xgUwjuY|5m?bWt*I$814fcBdr9hP_;M40X zB%9meh@On_>lUqJzpL!=+Rd6@j#npEH^sCY zhbFg6JQJ9ZuOyzkC?w+XwoN=gg|#~n&tCu70pdCEppL|I?&o3RIe~4ShX1wQGbiS> z9%tp;yOwSeM$UE9xS4?aM0FC?Qbe%X^sbPm({K7x?Zr-|+RvF-FL`N*N-ll36Ds+( z_?5&?&$01`9(*dfiK1aDDg3}v$;dA4sN`Y^LjXG83dPisrhrc+5AGdMi5XYs^-lDs zfA75R{ZQFgp4XkvN}N5fI~?N*(n|F}n%6WAyaW+xl?CqKNVG5%!%zqP-C!g20=y}# zXk9s;z7XZCJWNLFWe&(_;FH$zH$U@{)iBS~2c~SlLX=yh$Fcqg_OEepT@N2)|6Xjg z7NBUCkLa(`-NHs?M{D?(ObhC7XpX19?a%Qsz9uKgPkP_3TyNcNK(Z!C>LH4TEz|vw z3J-Y;erU+i0!)bY+j@ zrNbF@H@_zi2&O-lWow|rUyx|k8hF`(Qao1s_ti!Jz|5N3lU{CTkNJ9l;ScEnY>wTU znkv>cKZE)DuF(wiQLVrHDI7DFhn&AcAYV-Sp`iKXr-iDk**yb&FnGLiEAZD znetOOwk9csn+)-O{q*So@)bt2JfBA;mQnA^*HM+xZ;W`2J z$(L}xc+re(C;Ynp$eMIhN4~${ET4QWRUZx0v;Tj*At~;^z;cN9%=h=_&a+RuXw4Q0 z)~b>|6!C2r*+r>dTOPCwAyjW)v{MZwW< za713PayM4*C7Qt&cYzr0d0Ba$(6%MWC^yqr`UdDdFqRT0-Fya$cJzE>rg~nP2*V?fsBB~gZx%?mTE8a63d)f znikC@AWKei-r8$E z0Xz#qW>$)ht~7Kck7}5X9+tFD_UvkgXizxs4WEvT$?iAvlXom{Z@r6xq8W`Q^$JD9 z8SRI_>!PfgTNomStfjZ7Gp0^zGH)&ZtbJ$gGcaq1YOfvA26-kTu?4Dqff42MPm!H7 zKVM8<>Z&n_O)|zXerr$3n7R>xRMYtEkC~aQe)>D&pEM+F2F6-8W6d74(NRtH<}YVkKSK(rE1v$;GE}`f@W}c5$iF%>)5PhsPB5FuFQx~hlW$?-HJ7PjGffuW>zXnG~1HyABsj} z%Lc|;;(KuiR@JJ+ZQKH8ddl2o>?ZaoDfu&n#Wk~TU<6gG{1P=D$yZDV0P4;%;!@^Z zMQO*LuF3Wkt$iABbrkkqjhqbj|PGGNgZ$ZDenE}T$OI01G9tv!-9j>w6S-egyR+0do;cpyKt z&s5^b$ou5T5a)jWnm8Ayl$bo2w}&8jy8@i_8`h>X{7>dwN2&zyU3%Ar@uvUw|t8?TnVa2Y>Cb=(KK`QM#LVtGV+UN($hf-Qxp(I`bR<>#~T8gAbeHB zj)*KxnDY;gIiBn8?V8E+%GZ~19zqyO47J!(VHmVl7Pm5=v@5)6U$$zUBlF8n!tar#i480DC;FaZy zY%VY^k9cRSFWVfgO9F+W_ruqhZHm^N#FMjeVD+46?JsFDx}f`@bK++XIwV>vWopn7 z(ORT$0pGn_)+l!WWwf?J9ahhFRz{yy(rm-!pS|*hG62?@7IF*8c8bRPj@&dsKdiq`d`-oONddq}NLDNOI7skDB} z&1F+>@JgpK3Y0ov@rI6UiPm00f#`z0&5kf57rENlrhJMu<342#ECFQ&nlM1*qt;?e zMZ7CYz4j5@GEX#A=}(SHrpuOUzqZEb*KSw!H&hj{b)$hHx#U{oX%c!RW=t+G;}y9D z>o(W;p{A>%U_Y+7273MlWzv7+lNC4TFNZ(j{UiTD-^RIpn*U}$-mtmYYAj{E%)IR0 zVpa-bfWHFNr+`H)G;#}3!5NRzq(rhW)rM0ceWxJsSC{yu;quPL=#0B1gz%pGHTG5w zPYY(!^im&>1#)u;>fUTOHe1s398>F~U|DO0ywbx|%Ov#DLHM5oR`w}#i)(5pQ-#iu zEt#kM^_=`@)pv|eEkcylG=6%HSoG2$KTv`kLU%Ggc%h^zHe0{)ZlDN)Xt6coQf4-* zgCXbo?WKAo=)F^Ebz-y2$iXibheS=Pxl(Qtue_5FW(~d5t?F6U0B_p#&t&W+CX@fY zm%cY|`}=|VzAF2DCsW^V9RIdv-M0-d!ZvVYcfcx!ST_7sLDNgE)6&qr7qfX~7?MQx zMZ|q9EavcVPCiKl;bqs*Rqps)xk^w!o_u%B;qUu({Jtvu{fj-J$dS|}dXochEZ~{2 zTI#YHz|HMH7VHywuU@Boj_#MWPsfhwzhQLhzgVDa8V_K%M9tcHARX>tBU!ijZfHyX zRe46AMN6{kQB|@0&)jK`BbsF!hVtqz6eQ53cNRZVEx)GoXY|fBFOZD2$4godEAh-_ zmqzaIOewi&4%U~%bUBFq{XjE65Yn?Q>oe}5aoBBBt6rOV*dMJO>MUcj>dvJf@(dve zl$P0e+mmkj3%Y|Ou<)N3Y znC@KEpht!L=Q_w(MW)K_it$e_Cg>z;ZLg{Xb=qEUfS@a7rO!l%Ub2g~Au?|z887#F3 z&^7v*rA(RY=5DON@>a_0254Dj_tO2SFx>w)MkbC)$FKbjR}*!PE@+W? zqL_S3U;c@$NqpaF8`OPbN&E9W%EKS=&-xgC>w!8pq_l5&X|#47h$lmAo_{F1pm0Dp z@;ztLmY;1teEC#uK78pJ%7-7VeN)rcop3k3D=ofl&!om5NXmWijXwZX`*%sDE@(zr z*j-1-%>~yw3#ng_xQ_Jv(VOejlb9^Q=kFIP1cdaDMG{jYCcf|PUUqdPdYwem#NKS0 z+1oFl|NX{(ypGOLQvQK^N3WB9oBo7{oV?^t0m9hskYcf-^6N-=N~L2~)@eEZ)D{;( zk$1mx8IliIL2OOBCykBgyc7%Hton45iUBY4t8$0<<(8%k1Q>CrZg?uKy()DRsey#4 z!l%7272Eq?hz}b3*q1`=D-7rBH}M-|d8rt1B3avg&yt5CmT}94f2NdK<}qHQfe5^d zmk{c&HUbdpp9lA4K zy%S2@Gj}d^&OD(s@ifVfMV-2C8U)^?$zz|xFu+>v4kNd*j4K{mh1MTS=fG#mCKq1t zHE%1kIXtoCRHHDtd-rK+XzOxGy%|A$w9Xh^)x}RrhwrnpVQZI5w(64?IoYXfCYmVx z*1iD9u@-K?_99cgLD#WKXn*MjzNPe!=f(Hzg^36N^34Ij3EG#zvQWK(I}Lu|8$!`|kr>#&<3$F0 zL$AXrRE$(}VqC_|6*4Qzn&RVw&hX4Ea}z7*Dp)VJ+uu_4M`v_NwR-ip*dZx+sK0A( zz)cg;bOP83-1i(mHqiN_wXaFUo1?0lY$MNzfR0>W_Ib2Unn<##xQrX3GqmlV00xZ; z`kh9h4&V_m%?>-oP|dmt$&u@viX!6|00UlecxuX;Cmy_T3#OtN0oJAQato+85(w??w|qdk4u~b$ z*Np%9OJL2r3h4foblBau4B3<9U-jj5b0!pt9?gceh#l^DnH;K8A&F<@COj)wCUS2ifOuftITsM!^ouPx`sWqo8Q`gA4>g9ZDlsq_-;J<1YqW$+cU-Imm_D8 z8|$QZ;B(v$0p?9HB2D!5IXw_$+uxn2)sTBMi`=Sp_-R-kv|UWMY2v|__gv;uDfw+| zg!}+A*z6o<|2U%Aq~%?_;%zzxI}R)yUWa<#z#;qcthr5fsb0C$@{@;A}}e5vfWq# zw5N=%sfZQ6u9ma|;$fwQPQS1w?Z<1VSr$Xrmeoa7KhULasr*A|cY5sO^htcw^9;#4 z=J(@gAfD@<Y?gsRA5F6i(6p4{uCB{!Z2E)H+RX)oPgFYN4o{ z1vy&#d$a_h^VO$8tH!<9gEEj;8h=nBTDw9*i(SDCK;(A33?d*WpvV6xClYrCXQ!|h z$Z&?eLUDIdgYoN_F2K%(G%bVPxJCp_iGX>DUIfh2=Kuy(B!ETCbW{Kg_m82%`hY0H zBsB6r{9K&ID{br&Ge8b3!0!{xeEMqb+8fNA4-fPQ$|*=H*OVVTeSiU&*|ZbU?tGL+ z+AqDodI`p36260oU{;L@6|^rn#WvZGuQ1P&7k28iubVro@3UnI|G5x&L|?#K2|@*cQ}@TA0n7B#oDPgAMCNIOF4^Bwa@rApMG` zaKinfv@kqxjahZSQKisBZhki_dj*E!KQK5twFTy_X*`0S#ezT+>CHfZU3O+sYV>9w zt!to;GIne)g~(iP{Ht0OFE5L&#y%M)yeu{Ij{q0{5Vz&McJgq2RDQ9jW4<7N03jW>Frwuh6lG|50cGapr4Vo~60DRq# zLDGs2b#c1qAvlm9-6+offlXZ$Qu~8=H_`)lYHW4%`aQ*>ZFq{LA>!_!7m7+|<6mK7 z7lJK?54l!qjk|{zsgcIBCf)^8h$L_PblPk!ZY}=>+OBuz?ntgR{g?XyN9(Q^cUP}* zyA`ek{@t9)6>9hVg|y4h-MUt`I%wpl<*~HA-^0KqB_#`&aa&~lgZ2#>e#X5X<=M#px_tHH|exMXcwB?8!Yqwd5P|2HhbQ#H|#xs$TS;vnLnk z+mk<$_`{xD=-ZPqYfoN_J$Y?6-=6FydlCyRu}Jn51hL9PDt2*+pe0txpu}j?k`4XG zT2p(8`Z`*ZRg0o^8HSu(a<1Ve-8ZKgSCciU8FRW9j~y&b)TgS0Rcd;CTiv%7OSy40{U%wd`nB(99v_oKk<%d;`(A1Z>{ zuHCmoc4kk3b{ZF*V$ZKA+Z50CRxgV-Ff+H?PtLx?0IW3jEcPYFYu3bMAhK#tt)Y`; z9qdcR3vC?TNi0D$BmcAZ<#Yy#L54*t`*KOnzI<`MrV`72nbWN+(GA?in3cyt1W$C$PwHceOJr#j7Es@{SJ;$rx)6!6Z`_B_E1gCQ=GaSyUSTOt>&pwa7P87bW)f zaq?;UV+|%S70ua-uw}W*OBl-%7Dx>Tq)d~Q^Jcxozic$8li`Y*#%l%#l0DF;k-%Yn z`YhyN*f8tVD)TjIe@(rp8sOS%(&wX2Zd;SSS<-e}nshckytto_^B4dvT>%$9;KtBBGV^k0*XD{dxA3uh5^T+5-QY{#8<)($ivq3LM*%nWe-iLB_FFb7w_%(W(WuBxH61$C$aH~qos@6p7PD3mkpITNQ z0~!-gvZ^z28al^vlYSdDJwwoazxVU^lT6p;)TvXaPMve=RF$%uL-oa>LhktVV-og1Xl7q$f$8k?gR{DceI3y>Z}dPqV@dVYRPUaZk&9Qu_xKtX-{9BUA#J|g)iz8+8fU~TRua($={eVY=XM(OpzJ4 zsZ*D(18Pp) zi@muUU@OGdPVIta4!#e2@2lWr-lR~kExxROOZY&~;N{^19fJeRVSBCnvIk6Un$k|6 z`eW9#ZmI$WihT}+m{dZkcy3-tHsHMg+Cz^^ggY3+UPSOd|7Ue=2_r|cjH#&CKP$P# z?FQ)QtS|3i2}k_jdA{`kI)>dHd_jvCGl*(R9Nu!My_L1p$Qf zSQ52MvDp*tn?rl(wS_J)?eAa^@-cY04FUW1m_wb?@OLjzIwy6d)AUb$R$x7*SMoh& z0?x;8g8coz(V%OgCD*6c>y4Ock?J+It( zlZpBZm=ji+Tt(v|2mh6Q2Yt|??bOdp_rjZYR3b_!mwJ4RnJP3$FDK`9GZVEtANWJHTLg|F?+z z?F4gi)Hn>R`TY!0qN8*d;?6*~GcJ4XMYg5?gkWJ1ADN8%W`J^9!0Sp38y@&lVcNKh zaui-;WdJCeq3(f0R-nmoLKEM0>@kFzz(MJIxG=T=DMT)ZjR3i^f?Vjxv?-zJUIFdY z&r(MDLh=(V1P;=B*i8T*u{Q#XlMQ@y8haBU9|J{s8vOk?BXts-ai1l*@WkrBvu6V9R6< zlzkH;7jT78Eknhc+)y#EeV(|=v&!Wa-Zp~B`9LHd*pDSa_Vc_k1IMj_2s5z`4d3fZ z8r%hAzrj>@ZT6NmXFU-3jH3D*xHVF}{j8jkrNwKAVp_Y-dLS{#%PrJ9{zogpF9ceo`pid%P7AnoqnuOjK2F9 zh=A1km( zp{|mYXtR&B8S18(Fm*$wdk++Q$4Dm#2{tK0(ZQ(;aT1|;C|}2<;q6|-!Dl?N_b@mm zC77nq@R9!VXCaihBkW4Bi`{}oS&d#%gR6#1kn0nY$Fl~*pFE-T?`PDI{Asle2`j2Q zXjgiYZh=!|iYnqrFGikw@`CFhcnRwtE}8b$zeD8Jx6}U{d9_ALrOT^@Nc$yuMR_t- zu&C^vlVz6nz;j~Qlj+AT!SekSUYsW$Cy@WSppGrf;DRR1@05UPMIY~`JS1#y7x*Yr z-3{&SEA8vZuSuZHq4G=E?#}=np4j&n8Dux_y@e$;u~(f0LHey&%Z zT?E&NzB!Cl)8*GxjAw@YI#D2u5(s@Dw4idDLwiC4)I1eanI)VH1Wi8gIZa0MlYK+` zLZZR@)0#xf<2l?k4A=XX8rIK=1DfvD97egj-A90SB^b_Y*OH6>@lU*{`tq~uz7JWo0no<=VIkFbnN>#)Oki%(0u40j<=}W8$pT6QTbFsqqgX34PX=oa z7K1dEFuE(HjA_x$Xwg4HYmw<2q0#7FVv)bXYrYCb*+RWyA>`jM8CUNJ+wrVLPp``a zK8fkn$dwwNmYDn#YVctinoFX_{Shhb@}%XC#9Zi?m}|&~lTn1{`7jE9a7tf<(g@y2 zc(n|pk*vOwpH7_1Kmc=;CcEl3;XP{+mm>Sfmss|kc9JFv zewEZ-=c|1X&RDnhLr(2brM>MRVlsPzZOR`AYP+xEzkC%haVtJ+Kb=wWVyW2ZtN4ho zVu4$6iG6cM#kNwhEs=LRI@(up8*;&MxO>L#<5Z-ljZFB|O+>Y;ui|mOichPG_P!Te zS|T+sqmGJqmE+={Ba!0m*|z~oQr>q`W_c;gosM4voXBD)thlzc z0A$0P==rs!;94^TmAnNOpyI8r)uo(^qUMu-*Pz8rtrKntmkTg7f?MnS29R1=Itkn%2qsL*_T_ zo0g|JSVg!o+nK4MJe=^ibeUX^>n{6l3=_K(s3dj|J>$+@*A0N7`2jvkVZb^@b_(CGfi7yR{#a2F#GT|yCI&SPI-67gV8zE&CtLj`8^a}RB? zkOx1z(V;P{beIVnv}3tHqa4mhe~Ltm%K}Tk&NnU#A6JX`WmmGB{>ut@yrWD=@&%YvGoR3NK0pPaB!Q3iJFG#$;5O zAr(A@rw=RKld2HB+K>OQrEtBAf6E*c?(HjFtiP*n9Y_&`_YY_g#8zM@BOb|sYgp|+ z4x5Oau2k!u5B5zNkjoGmt%=b^5;a0YMss0(5|z2Wh; z%(dq6UsGNRhdYe;e*_k)jTIo7u*|uy;aBP*@LIWkM_P&XaLUxm8%a#Fa6&*}S%Z7J zFUzp2werlkDv@WXcST}nAcH+#N)D8lWol!6kVbt1{c{f9sltTY7kSn^g0mzM$jbEU zO`gXQf*d4(c~qCMoHNEAX9C<45acWO*-0{9j=H3p(Y{kadvhKSIOE~TnF+QpFTQXg z$Ty{*Y>8V5!1t1~gd_QCo#SzMYc4Q=+;_JEwb)&R*dBZiE>6b2tfCeFCEjgBAz{95vzsXhg%z0 zF*qzZ&+2RX+XmTed<6TOF!4qV}K*> z_?d6SczX|Pa6BxGN8$m*0JvsS_&^6OIurH?HtXpZ(xO+$N1hfv2|ujTmVqZ|GiUK< zY%c+!oo+M1wIWh$P|yMm>zhP>ZaE0-Lr9NsFfesSpeON0#JLjD@ke`^o~1VLKzv>nJ%D;Gqw zwEY|Kmh+}p5RPAY=!nwSlu?qdOI5t_px$lvNV*6$wZ+F+dZ|wfRlSv=%kNbwownCe z>kukf^Q6P0_Tm_sUbjeJgEuVlEk%Vvdn3d0vr0H^W+mzC(m3T?8FUSuLs*Seg1AyR%ENz7h3-Pn( zMTr)9(L(2NJCZ!h$hF{86gB5Y^$8_fH@*kX6LVQl^9<=3@s25 ziOK$w1;}bG5cpc`R$xoU28qeif06>CQ9A`jp<|}W(N}{(l!Ok}Aa@kGNN^}jH4c!! zPTem7-1o9y+DO}<30skGElYTKa4s(4QLwpSKtFxFEeY;hGg!_peHb%SqJD67*ns6C zB%;Njg|_%YV|VyKz7{n}(OI`ctA)%6jtd_cFY`WlcKARiEhg?xy~M{HB)g;AE}@+J zn-f)}_wyC9%9QDgDKVFYBC{>M$e*7wjqgQ%;u>~MMJMSOwO)?$GjV~h+=ae!KBP`z zxz4_FzxI{$;q@PoCP7E6+wO1u-;W){OQlmol?T`krK0k2G6w+{tOF`Gbho_WI-K*n*DMz9zydWRkn%-MwO3q$T> z+2ghZuc47U6y5cKW|y+yp}5JM#g%l99X1;=cDS^OlaI?DR4nfqJ^en&A4_(5RBn$Wex$M^^1p-71d;86~{6(FAd zQl%Q@c|tlUrTiPI;gYRrGEk5GgGqyD1r*c$Z9}WJrn%YcT$atH7GBGe92QB8?O_TtlBH@vj9Xl(o9( zA+XFrN8n?&o(d4o?EVw8fW<8@V07OEX1LBec$I&9Tzhn{7|1*(%~tHcqe`LTCR7Ev*62zVTnHXY?7=tug6bBq=T(hQnHEocfj=2_5;g3f zxREPiR;sy++juPM28OJS=HR`?BO;Gey33C-;KoD19x2DB`bA$u3+!oX!w!#+2Ofze z(mXm8rI(*8YR-!8s58*7uY^F#-riE@*uyZ~cr!R%P~v5iCGr?Joe;Kj zBMv8k(70j?M;CkZ77@JO+5HD#!le|T!uAEE{T(P8 z+c#~KYE7*jPJC)FQ{C@IK`gfdQpcD9u3=e8Q26!1x2zvTE?DWV8WP8vl?WkG>Fs6E z$tK~8)TVs;_yzEWLlhzdM>LnOOu8`3rAwaEy3pl;*6A{vYStn)G++_6?$CsU4F;KA zENQ{Z{XI2=>h2(%pf1HzSKx^tM~6k9bB7|Wt6FR=^cGzDhRKCH^a5+_4{;P+)uxFB z0YHl7QXv%A?EtxoPm5iFYPkCymJmItZ__*pBA}dZ*Ee{5G=!scnyU@Q_6rIuc(5ET z@21~@9)t}x-HtT@y8)`BTI^VK*XiERQE@ev6IBf1mK7WVuKpZ7Ew-9nT28tt8sb{! z?rJ_l@}epG=n7m9y+5>DWm9`TisA=i*}NYUz8yYP`SA1(&=vLpL*-+~WaA2j(NWG~ zpx=SwaSKau-Nk%eG!+f=;yci7{A2+uT?HlV@$U(XxHI&hq>7kH-Xztcm86GU#R^@1 zE0);QMAaVs0~^93?ko+DJc!1xWZJ^hfDi<9*qGm(dFp6t%8e8K z6F_*qodh=W_qIaXtap3+^aE(~7NmLdN&36Q?eFiUzuMv|(%Y`X9S+h9^ze+PbEIj{5q=7r{+5fN=+mt;s1h{}i=V{y+&MQPjX|R?0FWzU?n1n9->k%A zNW%GYPv7eTe3pWds9Rx|U*@=)+SIKc5;pKQ0%GLaJCJ5dITy4ey-q-eT3U}sIZnBT zr@$(nn(&w`Vva+l`97#B^F+jfe=j>3*F|GmEJFnss)O(Zjzc`TIV1UO^dmVZ1)Pd? zGLrg!9dk?F`|Gve3rVR0w_~-HP}vN?XR>=PC7h6lB!Fk0zi{4bdj#B#_=h(1XQ$$+ zWz)#QWeo#yGDP;q$SGYR4!HT+Pw87jp_PTFb<7GKXX$CN%Z|W0hAIzyQnU%c?)DV< z^lvT0b(p^XgBP&=0~zIQLOdd`x|-y9lH6785nw_yyBO=U3=~GgbrfYON0DrRFm_w4 z2>6QZw}4M8jv~>Vh%(0UCcsVH0I}%EiGgqvT?Z*Pu%i~GG#dy9(ROAl2hr_FN-0_U zgFxc{>>#=u9+V*XS;W+!Jf$3`d_=|~TH1za@;E(UitCL^I?KCuxS0KpQ)m=;Ipqj) z9r0TLL|XX&-yPJKW8paB8_>+px`O8IMF~rs60Y=m7WL^56lIpH2m~xI2(65*WLfbQ ziQsw*qE-376p_$jb5y>*bCLdTo&i6h@)SYK5XVtuxVVN;D10BBLYDX*Pc!cpr_iU-jDfDkLV9F^JlLDg2Dg!?@fQsY)$|>YI z2V(CNUEz;I-GBDGU@LR({|Bc~(bS(>X2TyOJ|KECx{(fz1K|wfy-nIIuImF&4qi5J zeDI8ca01Q7x0U7u@`VY!31&&Y4*!nd|HEN$%*eUSpOfkTN%@EFMZSnxC5J5C@7M9Q zb1BP}Vp_W8{C*u@d#AA63BGb^{-jj9{{a;evQ6#yoznb2sdAfHPEORQ^)$`vLl$=R z+3u!@1fuNdJZpf;VI4mYpsFJ~oFiqTW@jaCKnCwS{~7txX{|Asv_kT>{QswzS zp2M7a8#HnKAH-Xs%Qbo+waC;p`=4X_B+g(O^+fTtqEnOu)ScbVEtAD$K5ux&qXgKE zay=bfQgHth*5dwm0jmuEg|S)*jKuL=>zk5Y9XSt!9R3mPKfqUubye+Ad~MBj{a)gQ zhQ`SG>bhvR->Z~_yZG1V_v%U1#P8*tAljZ4noy8BVV} zP&1_jeVC>M(W7O9#6G9jBX@(Sl=)774{_cc5ki4CM3+;M9Nwz$>?(cDVR1Ad@dDG( zd;zr-$Jt+l+NAnY+-RzlsO?NSXvtc{^?w+a$K*!O)v=V>P07tjiqB3ig_uj$x-1hc zJv_T~5+vmwC`@zv4S-4TIc3l5a-9H{tFXm+LT+;$E=xW4$JHsFQR0#XsHZ1RAkb{2 zxg-u=kY4^pHkdjTbr#FdLt5f|j*F|YC7)0ITx+kn4IPdrsEb+FI{d4gM5_={q!x8G zAF-$#2c3mnu4(gNNRSLQAaU;5Q||=R$WKM@N%*ENbRk?Me3!=S>qY6fzbW(0^P1g_ zY6*m@D^F93Sc$8YBI#VB`maOv$5ebiTod+hAp~&$$$@Mvq&>4j$Ma?jYE|HgZ>bo0 zXOv`KkIfq}Ha~cVydj}UIcQ(;+fi`g2hxmsO)acCp><(DM-Qzr|_Yv|fs~cLS zGB5^g{^aAtfGIH5ie;x=Z8BMbk4YI!A6y%Oj=9SDMLzUDtw!av=&M^Dy*alAIg1EZ zofk+uZ))Wu-CbYcFX5*-kKRmoz;1@hyJL5Ap<>+tUluo@7QPb_A|@V+OMPBjIpqkEE!95! zCKAogh2+kwq}?VF_Sap`SO_qY8emQsJ)H%Qx_G`x{*k6@ZdcU&IH38o%X zA^lgD(66jTzoLY}&FA84#EERzx4iOG;O9t=%~%vn@r3$_@h!0Qh%qDsp^eD&t=yZ) z2+NV?`BkBXU=VIC7b3V$obKs#7|&+Yd{+1S+pNlP;?PIo3$VO~ZC-*jk6*38he8DL z**P8oM^0`8#oXS03Ek-sKV6o;+U)eouaSYNFeMRQE9u>zgbOAcxX(r`wgSlKqmO{pq zAU7(qlZA@jo=7)BzJY1(lT-2EV>NKay4|fn`HW`b=%FYogytwJ|4>W%JXD|*x`{tW1+>!x< zx|#R!sW|P=fzOJYaDX6qlo6je+mXko0txYVm(?M(Nn2d;8D1SQ%j&5j;!1)nZ$20Y zV7bO#6cwYMf*4w|a}Fn4W56b^=gNy!#RvDyw#H=TXtU^S;Q{cxqJ5QtI@zy5JRF4t z=JKZ(gNBYeaKkE^AGj$MdC@AlWJ?>e3i21#SoRHH*>?NUHMmZ(v!44J_I`L0IaD8d z4v5#W%Ls^%59*nvMfuJ)&NZl;Wq5AgXe!!=t+7I1qR2Z$W?kl6q62Jj%h&SKzhKP|6BQ;|d%A7(s#HknK`3AB`}q zo!9;VvZP(a@D*jO^DvldA8H8X7d5L@m>rbncpDn(;1>!yR{Bvs=-=F&f<6ZVz;VJj z8b}u`XMk4JVlQGIj=>^|w|qfyXI~0uEV4aJq~p4S;%~LZ%cF&6+z_ z5?>ZNTDj6Vy2ti$&e19PBT5cn`_+JiYjd{Y5kt?F2da}EAjA)lAjxGq9=)B`owVWZ zW7+e}IRZ-%@h*EFJ8tpZoIboG$K9YsFciBLSm;ve6VQQd3kColtbgf64xttbq4F^> zC~OxlAvwKz|AKxgWD;Wm%?;jb4a*)dyh)pRI|+jmQO>$hzR=QthmL!lpvsDN&O;Ae z&ceJh)xhwPOSD!BwD@-fMuUL@!mHT)yNVR#=+3(_#aG3GTIy`N799@G^wflUj`3P9 zJSt@6EM)q^S6{lGvN%;Cc#pqumK653uBWkZ16Bb~o`EKEeLnuy4kj`176r+km4IdI zZNWI}p^o)N#m@h59q>m7Yjm6`Xz-+T(oBBl%KTn_nZFfn(rk9r`+caMSdBCa`}G~Ia9Pc8A%o^aR~@(l}! z4(S|rr8)Nl$n|Y#?0Spb;q7nyeRtaDRF0x-bf6W_gTrAw8{)yY(a{2Z8lM>(9lvBh zw~>yW|8+L6=*SM8+SHrX4+v2#m<(+g!Mr*k2x8=lQQHJHm*5 zUFo@w{GEK?7{*d!^JzcN>w$@_MW2QpbU6FD`PvlvuZYO^pI$0(?B~7AQTFqB zf~P*-5fTtkvh|HiM7V?Ptnuz^*&OgzK)CTsm z6eyYY@3NF=)S?N{#V;P87V(&}e}PrvVWy?qpJM-Fs9G}Y?`K{~Yrm(opJD$F@V9?; zM*Am7`zibPYP8=my?xsMG;6u$+XA?XZ^ZhVpt|FGVh!+t6iIr)?zL#3cv18;IiPhskEy$C{9!S#| z5;>Uasq&ChuxOQ8IfpfPqS2M-_Gekja2`PzyHd5z1&rkU`Uj;<2F0^;F9!yRV)oEAY7=~T%KJ+GJ23$rbTyv-evM}v3i_5n`WZDrcOcwt@a-;G>LT>rGPe_unAGId23V^-#3XwaCp zcu)_0O?Ks=9;j@M>A=@WX7S<`Pb%ZYVb9V4Qd}S}D z9o#5UDjSU{x4!#n3BTwI!~POuvl3zH+sxB8l#O5F0`819pSD9*$Fqz4ve!$K@BhXIL;uHa-9 z;}QJB!!NNKlbpEuD^`9dyGD8Ss|pb@)NE2`5wKm9P^S>Z&15@sm+pEZ<{+E-c>Q3$cN~XV~*1n=h~(1FN-Wn;saGBJV!|BmEAc72pzYIsGT+mCrW)3o?DSsWuuC%wn3S zPaSGZJLLNU0@8g(#ucbT{ICN8+cRa~yaKR`m?ruP7%NeTAyww-SY)z~r-r~ouIx@O zRhL7mGw5X~?6z~7UvLkQcDz;YQnqtC(y*uN8LQi7yZj*bDen`)_}Il*oFmnL*x{I{ zyiy3)YxAHto<<}ufLu`0-LN|6t&gSUI1E0bM~=(V9YAx3W$CN3*FwwXclwn1EuxU! z8mDt84~fKc2>UPuf^*l3-!OG+w8rqi2%-@E^>IS5o)Me1{1D`3D?Q`?<;`X!gRmVLx{o z_H*r&J<7P^<^9P3g}vR$K&ZS=|*W+-~QNd zMnWPeIqe#rbUr!q^X^vdQO3icLA;!J_G&xII(&6MNx#G3-)MM@Ve$D|JY%wPWs$f^Rg zvjDq4VISiLz%Q}4%hu=;xBex9l;0NBX!(`)N|TYoHU}YE(i_jmLW$_);^jh!SO6VJ zFK`5~BNF$DxcY=lBNw{Jeyl^Hp%@o;aF>b1T9YyWVq?V)C46%c3Dnwt?5QJMdz2-( zAKM*>vE3&x#r*F~ZA;ljrDwSPUInevWrLJF$9OLv1{fse`&Z(xj}PyBHjNL%R8lkd zOaBT{K=+psWu zFLQ}%Ez{Ke z;l6U3iAj20drG=}xqK4);qI?C+1Fx=#2x3~3PvoD8tUjoKSq5rFuFuA^6bldE(1pA zBTeZ+*k`V&r2fzmQUo+{?aO89gjjcoeYppScvRq>J^n?Dbo1Gl2gyvUkmm7=yU)3N zDtn@q28XNf2FcvsmbYeKPW88(XCkfE|K04jA4frG z`0PjQpXQr`@=^w*fB*E$VTam}`Hua#irRa+{rG1j!G7fOBm1Ya*|%yp76)#=4(>}6 za&TXt3Aq~;iuQ@!thuVuY=MQTy z_I2$=XW#T%47pGLl>Kk4fUy5JX4s3fq$wi+bLwi&)@eO+g2(t&mV;nxntU^mdAKdm zuQ9Z)M7U-F=$B^lee0Qg&oQqQx7m9(Uw-J^#C}2!^4wR3B`5m8w~#hIJLg1PzUZ@a z!oZ%3tz+lBjs|>o4ld?%6qq%CSBB1$>4wfm-jay9Ud(!}89D{No<#w}Z|DRkc{2Sc zQqD7SreE$eaLz7;+Ilhjcew58mxrdPH+wJJ@Ex#6Wl_DchB>9ev zpL5%@7QN{oU^X-RLF#ZGOGnGSHkjpS1)Iw1>L@g9wO!Qfh ziJy?~O6oMD@c>o?-~MJ-)J}ZKRpNC|HYc|wpLgr_O7WBSC`=!b@`Xwr|LC`<`xVl> z1ta-k%6?Y%Cig0NXe*BweO6-(o9a*zOzK>9Sw)R-A<72 z59FOI%v@(L5QW~3OJ;u68SUWlPr2L6R6$gtGN}8n47K4SHdc&_ffgvsR~Lb?dac|K z#a{-K2V$Tl*@eCXQQ5S-;2)VMTtNFmUArk)h572wqj{MEA-2Q3nCbXRsf7HU>2l<2@9Cd6gCK~k$XTLFnb0Aj51vbhASw*3=}Zjiu84g zN2jRkOQ+y5lp8}GFfS3zA)WdG_jzF#hUlCW1MnQ?Ce^?df0^ z0*n)t70cqt0Ch|DW~eG$`g^dGe4&=QzO(o0Rn0lL-%2j)(xSIR^43bsGdabzS0p~r zT+|l;t=!7kK6P!H7X27yaOlGl=25}N^XQ1emGDUo@nwq&_%S&Tmskwq+fP&FnTvTp zV!VXg-y4rC#D@amxjY#q;vMF08b;8y zxHHn^6q|>A#x)`Rq>^XLwPhvQA9t})?$mo)cw@-=#7meCUdPJP+wUu&yc?W46@Ye( zOQ(xDl@j+-@-XFt~ z(}NU{$J5z`*UEEs>zsI$^aj=c3p%zm$8m_ynkIf> z<325VIKJH~9OzxN@iuF&_SI~iZ=+Jns5IaX%t&3CMR@?soQRb9`C`S3sOP(CB|LjW862v>B+YaVcZlxFaL)4e2P;bj;RFW z=rH)4>BEO_4`4y5hZG}TPo4K);8o?rt2^;}^$@&#^J%o*MNs=KP{Uz$y&*`&85%1t znTP5sM!&t~+@D%x88lWc0jY4qU8vo@z>DEfXT2sUk5?PrQE( z?FjE*<2e&6@NDbwgMd#pt4e|M{BuITsd#w_nAx`ooF@Utd5{Tsx=6y+W}gEfMVs*6 zPA6gP%Zl{Ey#qX$lJ~8|7l~2PFY<~!{O7gw>ciB#kU4uj&*R1V= zXS}FN*i8J@$j?VjJLt9Ryv6(rZAU2#@K|3>AA#k`pIFPZKPPwj_~B4~8f|Zc(t`JY zmvQ{?KF3)cxm*ZER0F*r|0MqlNF*gs@Xp9Fw^Z2>uI%;!P}v!2oG<6YNeQ^Joc$D` zw-Lwv*8<}ifzih(ud|ko!3^i5yhOTMhq)5hry@;4lkDG~?TlS`nM#a@E&y@JBQ{(P zxP!m`D@we)WzCM^1|`iDm9*vK1w zyl$zT>Xk@U^!SUE-@H`O%MdNePp^pNzbW~JF1#BK4{wx|*HwA@cV`OAftSe%vU~wX zXNsCJ2);NDaC}UC=zH&w{{rtkz_S94ckLGy{%CtQ*1kyf zDNgwgC~ru4hs#y>z4maQm&nT|d#Th*z9s85n7)q{veExMUc>~NN-&3s(ZW-WS@uI< zV_9b~C3bNLQ^!Tp>Fc~NK3;&&QotdCl-#i&z{u!LSr3*53ypU4_j;E%2o#5UZP9?< z)Dp~HFg=(L?f}=f*mX$M7T0i2et@4MPwWTIP^e@%3PfxCvJo5%{s$_Y{~w};fBvJ% z)HClG9|!-Zq|*Aut};Wy_$4@3!V@@&_n{A1P=BWVQ36T_D7OE*wDy&}KSxSjFC}pP zC@;1t)X9-KN{_)3Mb6}evHOFB#%kfk*rxlo+fxy4ruT0H9GoiY;{o{xUPS*L=ujL1 zNmD#-C&Af1J{5WK7b(Aa5%C2-ODGzB(c%7yC~j%n=AZ)ccjm zK4g2Wzhm@+9gnR#b^DH%mbL|_V?zs{n=q*Q&i(r8j=i_qmA`Vd4>k#@HcU{wuf~4# zH0fyQZM~+4bU(GOAjMf`+<*m--=ThO0PjYsbAV2yA&mVDupfJ_4UQIN-%Qm540Jr2BR{w8?eKFE6f|2tC|+r_yW}ebd=0 zxd0pjdG(Nt9C|Mi~W(xQWbl6?<4hTGzbHpK%UXIaApwPR;n zg^y_~st^ZjjTs4i+N+GoHlNVii7pT98PpOVvhQjhq9jTob>F}odg3Wpj4vpmEzZMd z@CQ9HD16}9DR+jaX7>!;A|y)7H{Q3VY~XG99j07r9Ka2~+o<*wf}U%o@F?J)XN}qr zZU#Nsz^M!xw>Wqeo#`_#HtxnzzdUSg=`y6*iHnh^hL-}?^v1F)=xa)uNDbLT=9%3W zBb+Lo+~E7Y$+y0N+iTHNFiwfct9VIXR=i{kKF2XNUNRp4PsmdI4S7NNt1T`Wqc>(( z)8Cq=|F>cv=ndnzp9y`Rnpvd!%-2QV=k8|3k5)y!5da|q`SH>*lpd9VZT9JyqqIAN zeCL&>ru)D;?k_9Nuf)STfpxNR3^rcI83|Sj)YyH=M`bm518@z@=^DHv=!#(S`x_8O zP#i8m_BN|@+{^+oXwA}b@zM!kiogaSkX>0i9_{)46z;r1ivVJw3Bs4N?autf`U8?6 zHUGaMBh?c>T72$oEsQIt9njOczjGZVSfu*ktA1ilH7~ z>gAIaIpTH>`-`=1FSL*p1qHtN$8Qt(PrLB*F&IT+f_5e=V3Kn139=Z|8Q*!b0tM>* zStlT?4MHyh^;7$@$PpP;5B4I>rxp$f6ogJK+JulGeNT1~lC&YsxHO>^I%Ckcc`bn8 zl#kL;?2=X47x#2l&eh2`l{`m(xPCo@)1{D&UYiL7q?f*M)|XD3UUqh>sj)VS^gB{r9JFKu61~ialRIb~NkipYh1ViN%jeC%I5he)s1sD}|!WU(s0)<&Re)ed|l-WUf|^uXiUdd1^6O z=sPkL1uJgCUvO%<6<9zF#C(FjpGqWGZkNx|T+e1v^KCSOCn%!&6eXF+tY)6 z%L?9J@mG87ahL{}`A5tSKA|_|2Imy*!@iH>CK0@W6ma4FE3Gzw$(U;n6{p*u9Jt*o zHbXAk|2Y=T^v?~(lP|F!X2pi^^zm76^ula-63~cXw#Yvw`QTguIC7!NA^ZjIIuUw7 zq((f`1i&+rc6g&m)3H&Auas%JU)N3xg8UbjHyf#Prfp?Lix-feaI3Ci%96T;o zHLWB*c!EL-0K!wpXN8V3_Cz-YJLy&9iZ)@NLCQ`jB~5o|G47Q)MDo4g1TaM{E5c9A&mtf#b`0uD@QlL+ zqEAu(1MZ4C7?7_Zg`m?p`XT&ZP!1y1=lzY`(F+W=hbv+Me(Y1-m+67$L9M_ZHLYcZ z{2ZL>So$fim}(FEH}=cWt+4-vDE)9nf!e^yhvPWIKVv_63@8&+Ml;YPzck@ACI)*; zYYWh2AY=-Ly#G!AioA%*RxglNC$ZIOW3qzh(UBay2v|d)B4QVF9l;d<%zoIHljbZS z&3+CxrIMclPkX4e7g74MD^*(Q_OHNN$!#wGIr3>GbPw3S&(r?B4CI3GKmkroFYTSy zcqwcbv{75CY?o5lE>Q0)#Zs!A$EbL$Fl_Gozg$xh_S@ zKzgcb2;q!A&wLz{QH=q*i;bKTAwLN&%fA40Hj1b&8ag1gy%nT%tUnb$OTya)ICnrN z+;F^h3mkCSIT6moRWj;vI3mHx!gZU3GUaym@Z|B?z=s&KJ!*r%8e=jDoI{%^QbUT1 z=BVPLY%aD~js8AB{Lgr=HnelJ-2+-wqGLEx{CP$ySoR4lxsmEM&%tWKeo|*_!W{2oNCXU}??TVE zlu1ST0h5ZNmHYymiXB|pjgw)oG?+4>4we5_1^X{8k3h>x!T6b;J2B5$s^_6IMFa0g z$xxqKdJr$?&40CtLV5CF=X46#XC9^KbxLq4*2~~R5G}ML`H*k^DEm}aq+_wehM^TM z7z|oS&(?BZWo_c2-Mk+h^9{?{NUTMX>WBWqzTlWf0j67Q?SC`TLYiLFm%cE!eRsA! z4q;~C!1zAeQbEij#|##h1GD8~)|>6(VSYm>$V5_}On1{kz4{DB&$ZhlOj*sMphgaL z+LZO&6F2ujhd2afrzD?ZhT_lnPfYa$^T++sEa>aVb9dp+^AW5F>J_E>!qb4FZ$E(c z=ZTO9SpT0T!3NTsfpfti8njD%6vomKsSNBojGR&`y0)S{=U?`b9RJYmE(u408x6`R zZ=SN$lN|pH!lBJwloR;-6}&X+sGE;|wT&MAPE_<$v0&hX@bv79tf4vDkf!9!bb6kQ z5p0E?s;1{JWRtZ4+I(3~%Yl3+WGB)14aQy~D|teS6YS;-LC8#c`uO!ES6KLl;UDm# zriNi{;@xlIVNLBX3roXE1qG=iWnxn=2AGG4F-4B3m zuwr$#^aEs7PoHqe=+QhlEnFZ)} z3myzztx|I;;f%_yEayvXwvM@l<#|I<71Y-A(W0^12y8(Yuy;Q)ABr|!clAKfQJ_Wu zOmP6~9db(K;B{bweLw?;2R68YUus>^Yk4J{{RxZ-v!Y%?@)T?R8>N}k@qBa-cwCKD zj4J?sHev$Xmy!gv_7+ev`Mxur*F*Y8s^>nX_(6Y=ltKBCUC0X45Y6PKT#OXm&ZZEu zyu?d@uiDeiZgoEg;vq{KI9D1dNP+tfxL9{(JD{kfq19%ruKK}j2jVoy`vTcqaHh%m z#3jXF6b>BO`Z^FI_XGm?BcR5rrhl1HF+H9G^8+^y=D-o1vEM4uNHTvU-_FceQ!9`^ zGY1uAKb})9kk8VXXP967E`#Ay(5SuM5rs16cUnH2lghE2+8tyD=@0Rs0I*3QCtIN0DGR@+#UiD zNrk$KR)@9^e)yUChx(^^--f*o6BqvP`AU&DEhdJ!IVap(_0qX%w=9E{ch>XSQ=sGFWcBiHn~-(gPLDQ+S2$ z$^eOwKjMV|!Y3N}YZI;$Hnx#Ag0VG&eWTFow->!g$Gsnq>jsa~<9)nNpt~lPdj~tN ze2stPjF8#@`G?ah|-ET$L(eSePITAF?6sir{YB>rrbfOarpK zJO4BDv3nxG^O)9Pu2230$;lHu zJiwo-|Ni=!6bo%j+y#=Q^r3RA(?ZMx?xN;%6`27+9jRXOm~R(VRzGv#5$0t_vj-o%I*^?8EvLsXl}FRQwp8R*+>)D+u)^Ll5ayh?!2?nBwk4K!eOiYJsI6 zgFQ+7%CkSsr%UD>UO4aHJN3oiN_$*Cp;Fj}G`4JxZwUqLJb_IWc1i&kkl(ch(4ptR zFPGl^2pCVrx6&emQpcFqP&>E_AWzI3QREBpr5MLuUxi2$%o2KE=T%j^@c=YZnxUFU zs`~&PuC^6<=9P$>3igN8;FeuT`E}c)*DWIpA^H302hUw{F6f|@#vxPT-n9>Y0A32z z_l}3Q6(N$zSyPD*X~q$7oc>?tz*rqBDY2^Bp)y7ijpuk$Jo%DQ@1L#LOV0I;Czt^J z%lG`d_%=(RPUTHVbl&C#2By)&%|H9l{I?|@9PA1unsDr^(8skf*&Xy3Pr?3u7v}Txf%Xq@Xu&_lmO8Ig!Zv# z7nWcX)v<6q`Z@fj^h@w}SE)J-RYm8{$E#0Z8pd(>G)wXiud!3({DnOeQy6Q)M@WP_ zj_F`}TBGjha7o<>OB6DJJ+Sw+hx#=aCQpmepB&AekVWX-{6`*)s>9+pxfAKLV3xvf z8V=@hI^$q@yWk&ip&GnOp&(i*1i+O=Y|7jWmXi$d54duylWX7O&p;$~XeV;}+sgp1 zI35&>7Whfj*naHzI<)u5o|GKY1V)A&$ zFVp0$@nxi8oUADBeFaAe^Z*fsDCKgi#eM)Ot>xo^ZanZ+YFMF^E`wHP&6U_|d5e=f zH{{m0`HI^itsanJ*XB9Ta@oC$;yJm1JPqcVM{?6 z*l%Qm;d5m}$zBZ3bzW9gkoqEko`-q{E3a6~$Zk#(U?zg6bi{#oVX1ukE#Sj=BrW<4 zkb!`zlt(!2&vuFXzY4hd7@WsmJpIGvb6yXlMa8uNF}uMx8I<^}jq$h|pqE&B&5hW6 zkZ3N;i|`8m^ka)9X&%1=NA!>4!(NQO3WBj~0R=ILfS_=6;V`N!qb3E5{UB;$2ZLSU zIQ8TR>7;yiVkXjNn}Irvn3yt-*ZOPdx#0A!-0_C+mhqjpT5XwO+UY~MSYdb`+UyCO zqD>ClC)ke2dEn@jy9(u!Th*-`v%p(ilFG0zsPstitE0a=l*IKHa41syR_9R=f0p=t z1E4zRQ}}&l>f4@26K~a953BPiW~2svGv}7Lafyn@E88uqjk|2;x{7O8CYWIMAVo|M0IueLH1LCFV~6k{0Yg& zx$X)6e}Tx0RBtw9K8KgFjjT|IqN<`z_HBS=bJOxn0oYvtPSozG!vF8aHcixSST#}G z8fg6N_Qt8Fd@{iXrUCr(JHZ7w1?*1(wj&eR-gf=*wyjc+2B#F!_0L`+4r+szauZy(*TWLSnC57V09asuYVSl_N4FWj4om#Ko-duJ=0gXPZqHeUT z1d-|kIJQKU5f^=}*}rqu*X?k%^evmXYW3cD%UVV^7-c)`lWDGKYaqpLbjoULD+8(impq8~!PQIPkMYF%38c^S@6JE!GGSsb0Cm=4{A z|AsmG_OVj$Qq=RNfK{;$Sg5tcz7y97DWx8<b)3Fr2_l!)B&nLjQS`}|EAsmiO0~I(gKkh z_6KnNe{zB|v%8e$@eNb7Fbl62`sv;I;E(>59CAjstG-g>W-soMg;%Z)#RucxWcLtM zMhGgfAoI{zDgMD^wy$LC6E?7U{4>6t%ynde!niVqi)Hybkk$7PQmA7}opZ0ExWIQ6 z#phOFKa?F%D%UoEU2+3^B=;QI#rP)M18iF$%%jS3C33PBOCS%$5Pzj#j zLIY0Z&|XZ93(fMz;;oa9Fq-!7!xLWBU;tc9bA*@-MVpWoH_IB~@LYqRtDHj5qR@aq zqc)QPn%eR;`tB3qBMo&mLwk$X7Ka+{ZCe~@oIFK*fyv1am({Q6iGs%JGeh-oY-0m< z^G;*;=I@Zv0nbS_Zmu(S)8`#%+-xHaLeLB}NDskqP2Kv0A81#5_jd%pn{u!vb~)T3jkYG zWewaJ-V-{#c=wcUuv@%-??z|Q?ftuf?f%`yhN4XgzK>PBe{y?cPvQ;fcdg!dA`l84 zUtG5L-rVAYlk<%|AVKf-$2NnusF-*d zYihlI;6$ujQ}Xp)CBgRk`j*YRI_xoyfy+`LvE9+i_g-1P4H4M(2blDc>h=+aHDN2I zd_!=AzVj}DbH+o~bt%Xt5Zmm+YxGmjt`&%_I3w-%v2w)|@&fnQu-VmuzoN z9gks0Smw5oh)IaI(Rcl5cC|`#leg2GwL!1b^rrkNgK)`oA@nkN^ax5_qns&EcC_So zA%qAtyJS!8t**&7+Dg>VNgk!Zd(jO&kptH1N=b?Tlfbn`YLCX2GXZ=zTp3RV1p>a+CU8kBC9q$n}6_M;$$o{4`){f zsxvX(emC26(VktTn3vQ9-77}-AFtBw6C0ziJ2k-s$FlqCM(z( z(Uj)H97Ch5CfO;{P=%k?m|mK`6T&8cX>aCi`~C%?8jB^0QI(y+T04gcs>oIrsWA|m z`G%A_N-)`OKgl>7^c$05&U}IfIc72qQo4M5?TlxUMq|r(;&J?&*dY|zZp)j$Lb2M2 zS403LaFke}400fc@)L5P54V#upn53vF}nkaPW+f|CX^u^$0B@lio^!*RkXRCaN z%{P0@a&BW_V6<1C;1JagS)WVX5-&;N?e=;UPVdYP`)j7LGdtW`nSEl&8=I(NN%jdP zg$0Z`(r4R2%n^SiIW=`^*x;BHz96E7&y-uJ1Kb~ zVXs6Iv)*DBItD68zqD65;9K^8znxePibwXp+fU}Teb*tbyNAeGL8lw|1$fNYCF%Yy{Mw)}zf;A+kWu$#P7#czVTYZ5wTC6=fYF2D9hh8=@ z(tq5NP*;6w&XiEW#K_ck?}dTj&|!E0HhFHi|B|;!IxW@_a3fQ*`8b9a`w2{jqHW&` zYq8y&6`=FrVQrs9ra2NvX}6@kwkg{XzQ4oG)}RidZsGeoP6{1q4(gz5htuM|{bZ~i#uKlx3WOHV&0_6Ec)lUiFg!gk zn^L-<#CU?3C%drPV7D5R5LaH*5}&aYKU=~V-5)xJC3><%#g3N1y7-K@k&~TWYnH7W zggzw4hMO-7b$qy>@(ET+b_zFN5jujOTr*0N{ld*7L#Ob_>#*#RBVoZ|3E48rzC@bj z8e%-Lfc5gj&7(udIaEYD0RQkPo`iWe))G1@nPcEaoVO`%wCF~bN5Yj?qF?4QV_QO7 ztTD&r+J8hy+ru;1EWi$I!DAJ5?e(Ud;F;4I&Dc44oZi$1$`c|x3zF@Zkb#m%FX7lF zJKNn8Kl0X=wp5A0)s2HCX_OHaeiEx{8;LDw4PER0+1 zAWM|X!dSM&7&Q`?x&>;9!PIZKVE`*s+sDZ{ zXbL80S)Sh9WqPlNqeoG3**ECMlFGn-Gj~p~efYsHw`GO2aK--IP_CH;Wom@2Y;3tV zNNI+4%?|{%Z!(@M8GK_24vRt>1v`cBzbh-)-q@g56(n&b4CWlBbLbe%bf}~lEOXSb zk;WR^K*xx46$xIpCH!Ff+p^5UnP$I8=wt>XtP1wT6qRInG~ekax>cw>HS2Se$J;Bu zf^xSnSQuR!EGXU@1phrEMX(q?UxL$Dp#{(-ski~5se;gIeKipZY%oWnRa^_ueeBp< zb1~31eP5V8z~;=sJQveu@FY*jQNdclnK@d8w;S``k<$5gd@p<76oR@Xrh7t%40^c0 znwlMM?x`()SDU#5)xymuYWiF-Ss2Q3^aDVea(B47qZWlrDr?HG!p-fpXb{;`+J>9k zB#Xk$I7gAAMd`Q4>0>Q+F@PpU%U35Y`XDPE6K+02i;j`Bd@a_4B~BnfXmssj@`MP{cKu`1yH}^Fx`j0jJR^)}7PbZGhQ67}KCu=kA#gBv~RnFFC z9w&u*Yx;O5A1hz8wWtkpP3atNzEhj=0e&V92>BjIS5c7}k7==U*!EF^_!C-`ubqUO zcWbe3_<@u1+19We3WR#d*t_W_ThIv4*ZWP$KUv)a_6qOLV4C}KcV{#g@9Lck;} zApz7V3E2$^gk(*2`J+LD3COxc(~2#%Xj2BcP=<+ElSpO}%OFVrUyJ zRkVTmecqYb-PvU~!9Mps_kMp*c{us(&ikHo-t+&=IcH`U`ltO}t76`La>j9!7~UUgrM-7#;!9clScfP#u8TkXAo{+baD*=;8+!N-kr6@~ zA$X6;NSnjyXNm3LVaaT{*6lAhu5}-lHvrh{58Levd(RMAm;XFXX17xbRZoI{G1EaR z;bDGDU1lWQ7&r2;gX+H+HJ|pe{;f5TdkjBgt-bUFj@@>_3 zPxQ=|AjV z_vJSCC~4-KI0>xuR+At1q{ht};vTnl&!_XO!Lq{Ue8O_4;`!s`{muk6kcXyEZ|WSdo1GkXDK1A(_v$>Uvn7)1>B6?r(8~ zj0s?zcAfR1ZX{Y6^vj2j&uPp(K^ynAX{BuxgPvE3cfW^<{)~0P>D;9KUj698y}e_< z|M`ht$ArG#B5id^Zyq-${<5!k$cVk(r^J%p>*MzJ9%Y57yLTpk{k>Q5_gL>0llS(1 zFujkT*z3IzJk;KM4%pV-`!%qmy>~SDAp;|Lpk0o@Ybo?SB~_#Mvc#8YZv}@MYpwK$ zbn(~81=?aR7vsLH-=me2l9=&j@7L;2T({PyXP37@yPoMiHgl8o(1~~5$_$zXvZ4O_ z|H!JFUdw~s`m;8YEPXpKoZ5Iqn+?5C#4OmWZT5K|$ma9kAN7CqSLx%ET#RrTuco?3 z*KO!j8aK(g7SAxBMuxWYeVQjmH=jLAW+VEGmi<4aL};D92W0fyZDHIi3s)-o3wjs&$8$e`U)_&x&E(H~4@d~U7bM{EdsykU+`^m|7DUwA$@Kp7jYp0Ug;#sKd877AQQT!^a=*6m)pfixeP5i6 z?N(fjbs>K=w%AX8(-ze~oV4Bqi*#e!fms-7Z3oJg$UFF`5M>ecp@ajNzM1FW+8Gyy(m;nU43nmiGH{=$WZ>dKMmGB338vv))>w*FXx=geT-W3lLP zHGiIC%u+Dj+Zi-olD)|Pn%=zVK({p&-PsB10iHD0aY7aA7nKNyBx?r(}!V_4`M>i-#g zc)>U}NN?Jx-F%ozgi_*&RF>=p%JQyN77qKlQQ7$FB+QhvWF9Ni=Q}6dvo&73E1=)n zlJhxTU+s_z#XZzJ^{(DC<-WjYxyxhmrf_R;C9zU`@+btM>JemX9|?_hhuLy_?~S7^ z=n4heqt|xhn`Vza*h-+WQK}so=TbT~s zi~k$+;graVdhLhZhPZF>ZGBCKm%1e*m)U(U-@){oyKlGOg%q-Pvi#laxT(Ig7(<*-Artj%Bm;m)C{O8iFdz;8N z-6YKf?sI)FNTkNOOJ7Fo%O77bp_8D!v#okOtVL3;UHGQ{db0G3joNEd{SVWieV#U% zxpEWU>OUr__(GDEeHuqFujS1ON7(QPZoK+dE8YXI%1w%#lGG3Hye_qXdsN9Zn~`Z+ z=wz99Q;#G-%QOG|vikOvTrjea)<9I6t@4-*7E9{1%<-=vucf_>GQ|^S`hQBJ-q5zt zyLaIdG5uOG{gZ&{wO2(q-7wX^_RrD?f3|{?F4~)8>3BCDkx8Evc>!CxQbPVeGIndW z671g})uYG6`gNlf&v5@nOk_$)<~~Qt#Mq(!2M$V~pj8PyhiB<#diUDxnwj5a>HU<= zBuA65Nut=xuk3LDTgm|di9Lz&!p^ohc@QcGu8H|kGyg1EmNaL+lG)7K|(zBe$WX zj>xR<)LIT=&ipk z=snj?SPR*qUa~;q$npEHqeKXtST?Ea|HzL*^d@sO&X@lpE9KOOBi{5E6Bualu#&cR z)SrmHrhMnYP@IeW?|vlJeS{-UnWZlLO6!1Mqk;z40dHjAPzE^v-CB6hmgwP4s_%By zAG5i?apwpsC-V&klKNvQZjQa$d2}PuH`~JY>Fk8w;r=Hy$Oi?FKPmw8XW0=Qa)}ta?e?^WIR-EwkOD9@!5@b zp0!q(*yYuC-^t;-muaUIa_=x%X||+h_WqiQfHC=OlH#6dV?j_CQTy!>fF3Tx*%Icc$l{do}qh1KG8bKn@-8CNI$} z=-Kizx4&C*I{k0Qy#^gZS}rVy78l9!%H`Q$q302|DMFBUoRau{MgHXj32ST zlyONO7&@!;Wq&*Y%w!rtEW>Fsby-%6oef@YLJN*Eo_96QO^_-4TZ9j$0FuowU9xVy zHnDN^YuKS^FMj&%NAo!dvFR0FBF|k@#-W)*YKC}+a8Fe`+){rXdjkAItlB$#U&bLQ zr&t2nB?T+*BH$4z7NB^PxZ9U%H7p~;{2V*y?JZh9d082ISW+&}GU+QRtZjcb+iG!N zY-H9U_gL)wm6jddc&FO-_~wA_IO=9CyvxUAo8g?|u5C(~?d28cq14_$BEwT?lP$43tlm#cU;bPC#{bfa z@|a(KBFFo(-TMYs^wEus=6nr5yI`lj-i(NS-K95D6x_K`8i8!7e-#LQR1BbR4Gy~ns0_1~;z4ewa#Bb`sk{I8&ovCR9*625=T zcjhhrX=bHHE-n)z!~!kqS5SRPR8Jvt?G8@LH`VI>(p0S1;NMiNvV@{N4wu*<+p(X` zrA#kt%w>OSX3in^h2H)AWQ+eOe!O1>O7$Ny`(jfgCs?pn>6jNYy7aLDSa7s=iIo0A z%6K8QO7fSUo;>dM47mu2+L z%s5(ohHqG-dzhvETU7Cx6gn?k7{FB_Q7wU z%JV;3sL$WbEf=q&$V>2zs6Tc=;`cJ{_ZGBzb9N?fmb-xZJCl^ehD@22Q1vpCX4a?3 zl5;MnY-BTTrf(u&6F0R;)-N8zZ%+E|PZ-P5r^RCvH_3r7=Fu~sv~VSHQ=NRRAI)cu zU414K+>Bkl%YBL7oHk#=^qe+tPD}MQzMQt1S(chBeD(ximUU*vE^on3pPd@rme|lH zR%9i4wJ^N7Nj}dmuPf;=uQgyFsby3aZ_Rl~jLS;e^tyQ95oUh>x{dkIgWiIK!}m)3 z%wnIkVuDvohgUOSjtg)mv&}bqj4yAjw_eO;$wNyB9#(xaCN196wy$A~c$9y9Ofo)t z+r}jGvA%sw{TCxVT|}4i`o8)D0V(fMoSP(GbfbG&TRSar^M~B58+l;7b#h-uvuN$h zXcHtpGkY|r=sa7zISpCfjBSkE4qr~IZ!(Lip6Nc%&UmIriM-iv`X}C;UDavG;%`mz zEN|%O!kZzd1@NGW=K+TS$e zD`ru6UdqbF4SX}_lYBWlyeZx+i|n?4q7~9k&7S!A33b!s5;y&sYxNu26ypgj_k~mz zeo7>slT+6EFXO3iJUBHsp?3tGnY^IJ^Ks(Sx5m+UbGFiXFw>ylIkb@d`>lD63oUd% zT&<7|*qp62J%0E0p0pvecnR4tvb1h}{LI8nf0fLo*ZLC8NAS;GXF)d}xmDsyN^tX* z5X9(I4BQ#d$~)eC*LXdxzLdD%O!u@V-gPmO`M#;0+Slq!dS~$Kq;a3V^|5bOXWX09 zH?&qKHde>^X7y=bY7%?DLCff6aB7qHQSO@QX{-K?|4xP!--ca{mQJ6`B0qDRvo-EF z{D?KTZT(oH^{(}QPV~pIOUe9*4wjPQh(ZFL4c6WzyRx1(Qi`<f%20BPCI4tj9r(1D0qz<%G{guNMEva*wLppo~*6?FQ2de24gH`nUU z^xujp-Y*lM-Y?zfR(}P(o@6)~*OTX466nkK`~S`Y8dgZg&mG-+I%oNMM@;^#cc>OM zi$BKu=V*xDmk)CoR-4ku(l@Wf^A@z=mr2*%=l?ZACNZg=a~tbBsjB-j zwdD{NI!gI?Z1~~3so666W?DCXq^cJv-nYi7yiWDyKaLu)pJTx@*+fpzuJEOPLl<43 zytb4rep!*6wMll@m-r{WWh`DYDM)OXiULyO+0P|@Ye;%1vEeu!lOa0%iF8sVLvB|w zox+rjyKBg3DNG)&_WYTB1V^N@M`dmxmCK>%3?_b%><3I%m zKFhRPJYz~fm((@h|Cb-~+lBRSJjhELGnfq>py;JO-%73ZEwJp%kQGfi&DH2TC=EGh zfA957UM9Tk-T(5jA-?RpSU|c<(x}YL+3&uP;jWY0CHLJ_;N9MwJ&V->4#jiBwA+`n zhi4QzkbCjen0-C=vsuKjezGc!6o?LLm15FTqW3oO2zgWlN|Qo?;me41ruMi(m!Gxt*j zl2f#e1O5`(q%4pPM&E{mzWElaGo9A0@=_0Gp-K12*)tB^cFvO_$9*ra{Mg@nx-b11 zM#K*JmAv%F6QrF2Wzt@f;@Rot z?6JJ9GEQr8s^^gZ0~$EtlUZWn5`TxRE6J~(Sf!R)>vF9;ImJ}BeX=_9ti-!IDV=*V ztL}z+`VPd(EtU z$!-=e#yN+~(EGQ>B~0~RAtU{{Tw}`8$xN&#j|q!i&T9LoNw#Ik`Htxs?bTo7mCZ2m zF6sR!t^-6w<}gc|o^znudsxB9aw6{2=>-J+CsM=h5T{*Up8iJlzQcR;bjsAu`>AIC0jh<6iM9~e zY4lnWO-4uWE!czkBq#1SlJwRDyPeYSkl8oyqoscOSK#kPV!NUKqeO4Pe(B@sGkIyG zKSwJ9>7_^_wYU28_>68z^%IFt-{c&W?+p5#_c=xWbriMENAQ!*{evoN(%k<|y*o|xei6PctfOD$&Rx5$5!W@97A zK$xa-r25F{m1F!9iR;E2?2G-+>-tPvjU{;Pc#d}7k6VEYG`|b+8|;W#h~(Xjk{~^e zUS{1H346(;(v7+FVOj#iOzxyLNz)lHU6;K+aJrV8(#84*UG&CRpXG-&Sr8yOHxmWP zkqmf6S7eDlu#zifwIRX3Nb|D^Kl0m_a-Si0rVWqC2VMGa5?(6r*kIae|`}uk$)05Zx4WgJitok%p zw;Ii5aF%X6W9L$C4`u0a2se2$n9z;U<;d7cr^A7&Pw;Bnkr>+-W=`o zoT_SPW^swTs(QUL&wO!NO3D7rqP(QoU0ziwdYUO%;4ZIRA>XyI@~ewWRyiGWidQ?U zivt%k*107LM|ydUOS1>v+$vi}b#+y>ZG6fEWnN{CySSo43)+@j<+f#3c`6;Y@sm>` zg=Af|$K@8$E{Tv_C6YD873B_FNP}Rmo}gr{c7%sAZ36bW z(JObCU?^+Qp%cbsxT`=^+ zu8I0GDG-d;itl78`5arATSc8KEni_Tc9)&(HMc6eDuzfaiZCB~E-urP9!(O>e!~+s z4j{#RJ+q^Qir0CSRE97adA*E;RXR)DQS1?E@ba8s12$!QplC{hLYt|SjOLc^TvJ}+ zoKsO;Q?tydXdFmK+_#|HK)o`|Lo*FGF;g_^T z1TQTrp;N60e$@=K7dyh@omc7d(1HkVPO;1Fp}_|AL!vzTn&KLhXitpEJqOdFk5Tzm#iq2)Tg@mIY>s;2iq+RU*K5OE&@)y$Pr67`E-y8Pvt{9l z4HHEqd7-B~l)LuosuC(;*fsf*RwDf=-MYD+QR+qa>U(=~^%d(xN?#OFY=TLB( zR$lpvvXj)b)(}!mGkHo|S6-76@qKc{_bCzIuZ;LU)tr1ivGW+*q`z6U%o*yeBrd(@ zIr*~I2a(JuKIT_3B$t=0iXzIdE?>dCh{7?dyQv?JxMq})p%>}H=!3K9(<-Dx2@8&z zm|w+kR=FZllFO_qh6qoAu_Y|9wCd_&32xD9=1-B~8LcZgz=ZiUY|MAAlRhTWYi?Dp zld@l473%t_jOG9WBY>&eg=JTi>&!dLOKI*zc9N8lFleVqNI_OIr)A0+7-Rx7&alYB zFPg&&mn^9+cQf^t85c%`%krGX4nq`Ze-SEyB%AvO-HZj-6I@Qsioj4G{*6A(#hh6( zS#+d_FnSK7grW(;yl5SR;m1%mUy6u;bmh=dI;*4jNb|U>DvCXoC1plo$`C46nffd- za9PGWvR$jABDGhobyhDZEe#vo4WBY^@wlDL?z#7nqB5?}bxJb1b#bph`AUSzM$^k; z#49hcdn$sNWsHHLkxe7MXrq65%0qF~WzD1;#B- zK_&AB$7Ca>XtF6$Wf_&l%eB5i3=GZujH#mGC3Kx4HOlKG(d=r9DZeU{J49(&;o;4# z%CDNuE!jx|W6TQI&g4EKpLuu%%|0?Dkui`+y9xIsW2bq*4wuT<8(W(0S?$t>@jxxq z%P!ry+_NIQZG;KJ+6E

m9i*`>ey_i3^D31o_DSz zji8(tsP?L1mIpF7x$AM=y%+)HA|N9IEPe@%jFOM;hLP)?f!X*V269-g1aS>1zeD96 zT;>hV9896Jgk&|u4S^Y0P++OEuf54Hc^2Y}p#^h;mU)}=*Jf+s5X8fw1q-Zph9W&I zQ~3vC37jv8Ln6`1ZqR9N5H=u;w^oS6l`|iO$UNaJIL(&IG+#+WT&8DHu zSoU$)VRmEyv!k9{7DEon26A42AyS-7%ls>4MrnJxiy)2&0Mk8KD!s(Pvu)kG62wAM zTK|1&89IZ^N+tNpy(VxSi2I6BG1S}4^W1}*>=|DMv7eMy)A*!?npsM~#p7A>n zzlF9ebtb#5j_#*zt*!E?ezmYA+fpju-Bs1vY6ao~QYQA+)_yeZ%z56!b#Z>QW+?zM zo|K7~Egq%r@=iYkjgQoIAeNF!%87-TOvya6M9-nN8Egaba6rYXXVtO@kb@jVYXnKFf|6S$y@c$Q#F>VbMceYm**{BbTB^IEm=Xw10NS?>xZnoDBKKTDf z5_INyye{T>UFpH$V4l}M)C^(v43g(fqc{^>J|AX*!k&gVeS&vGJRJlw~#%azCo0G3wx${GI7M@Snh3d<|0f7V#{D8C3dwK zVVwv+jMg(y%=PAPKz`WmG6L$vkVq>G#T_yi!VRHVAtLUPJ0Uz2ils}UH6{?PxSqiL z5l8M{kF-QBK{$C0=zAfqCo-3&+|t5_YLq$-;?I!MGg_*SZ0KaEN{jKNFgBCmI8Tjc z&H;b!*)sD!bU7#%X$_(ysoFe00A8PR&y}TG$Ek<M~MQ{me?Q0(?0q_ZE3}jXlLCi1$Z<;f&<%@-gbT#^Du+Z$$xKM03|m z`JT4-_y*$fD8P$o?k4dHuqe)qO1}}qL2N-j@FJSKUEaFO0%t>P8U?rxmHVu;7=@Qa zSp&L496&%bD&B;(*{mJq?v+{%DScTb_j7sUEDNmyupxxhl!3mLk85EV z%JV$~;1xnz|NQgub&1>*XCJx)eckMH5Z{NUy77GGvst;B&X4tB$GZu)zSxp$yV_~t ze6`(H#ReeG3n{&Zsxfo9%^mF=!l+7XEnlq|k&GfEc!AHo)H!*frLF|AFr*?E_}oQK z6GTjlWgUq7Lds^U+Pc&E8NHjH@nsPF+OkbT^a9Us)#N_qth@~={T|5gA;uoTUfXkD zbSmQhManM0Lw?wT%Fa=1?i}(DckB<~fU|QM#(M;MLmU_dI6BBZ z?2KP-<2n`MJOWA8M5z(m zVG#WMZt@wGs_B+rXU|v){dQ$+$<>M1{oML)1wZypK;)82ioH@z-P$v)t^OcJl1i$Y zyzb{-;HEc0wxg?*IUp7nv!&Dk_wE69bg%)$14V2F*K?g+H@}}rNP`g08B+$)DZ41@&FDV$Cg2Rd{tNd z?-O|ip6>>Nxh-xgsoN3ip%!H@2!bZxVRwR%pi1)146YMqJ~kV@>>}!AV6+0ZK%YJt z`coSx;L&1+Xb3Hvx;cAOQGM6nqgi<2z$5r88_Agv1= zF9i-%0cLTwmkJ{ZI`ce6B+sit4?5@mjV``q&fU%ew1PotsJc1(9QHdLnGLGs;rLyB zikT13S6z?BnX^H^#$R@WIkzGcxGF8ZAPy)7>~N=LSGrpD!zr!x!PXzdg?3$yn=|!MU>AfvgQM+-)AKfD^s!T!%*D$POsaQN5j6 z2lcW`puXxnJCy1HC?ADtfpmw-oV`w)t|qteIv7+JL8Dn;ATQF$8_omhH+kdjNKGIO zieS}*UrWn*%jq?YNPEcLh-geqA(jz7PoDFEBLz^#1Zr%)80DZNG9&Pg-wh{g;9~qH zSXc1<6FU3BiF*<8lFkjkT(QQBMN{Or7jTif?>a=8k`qL8u=D6u=p`NNrwG$^$m z#QmqH#N7r;&-e<6w*tyPSqb-*>K6D0;_)cJzA>kid&{|aj)1XAM(#;$nW|rd{{t5F%kb809=Kiyn01mLL0k5BHN^oATS>U14u) ziM45<9R^;uIEdFf+B7mpQlaFHIBH^!oC?zx;V9c2xeG)_OqdXBQ|&gqSlEbB93sD2LAA|JLlmzyIGF zKN_f?UZMlfX<(n4g&N!TTy@@pcGC9gGhjB`Yk++s-T<>?GU85nKgc4MF7P#fq@Dp6 zv_G?;9jZ|U+Sov=YP7$peaHiuOO44ukdZXEo#Exyz`OB3CV5BTW0SWYc#u4M@bAgv zYcrZWI%17e%ELgj7U$g_n4~i>X%GJ03tpi?hE|m4)O_s?4v2qLD(CJMV8+G#%rP% zLzFMEJ5H($0!#cjP7o};m%T}16A7g;GT1Eii-Eqch&1&77_Ty^rAF{=OGqPmilz6j zhTvVFz92@26jPkM^nMU8QT69Z=R&%Uq{b{*de6HYR_=iRHfrWvYDHt^FTMY=3e-*z zuP0MxXveNp$9Qz0c=&_&e}E?F%u^3MdIXPbuL~lR=aoeEBUceCBr{UK$dfgS5eptz=?iu+whRV}EXYs5;jF+v{sWu{WFJ^rjH8u-Xp6Gf zclRKTS(og9U>{hSfcWSGE6k8sub+D<@O}tXfl~oZxUS^W6*!POB6;4g*eB?0+&m2v z0O{kN!c0enF?dNWeKw6Fr4^>n#nF}K$g401F94)pWsXXwzJZ=DeWnI#kGq-lIZZLG zg;#@gwlRJDpRlZVGwD+qLh~$rn&ugAY|>{D7$RTM%A{w8qefuZg{OX+UJ8$SayyJ| z#g?%Xv647V#Ca~{m=X)*X{fsc!uP*k_QUU!z(4*H1DRW)^c(LOCb1FFq;DFFNT`uH0Im%n7*YL^Z0Kra4YVzR?i=B^_tT#~9WTwRk=+2^EC!v1UOWBG zH*qCVOJ4){iI67Ow^a68KnI%6ww6jGVO6l%EZ56-Q{kOP`Ugkw9-~@n0w9-Ak|j=s zrGI)_fz92104^>9b(NR8pk%+>XuXsy+|u9O%nO7&|8xiOafzeuRg zB(gnLr#$a<7)^9R3E=;a=`_BKdA4^InogegJ-y4I#?QSR$Mw@6m&5DqBP;1=IAl=q z9eubY{Yhc_&<9G=cS>sn${f-eiTGO9!{0Ge!s*XQZFrW&M3MBst{=7x+T_5x4cce= zZjnpic^QS{QQ;+#`S4s42&SL3!Cn)&8_I*B`U?UlA#Y;*2l>rp#6RzTkx!u<3sqT< z#!yCb8LRq^{0*hlT0d5{(<#u8%%%S$i!gXeMF2UY`%* zH0MpU2S>I-c|1_HLqJ4E;nI{|*;(09Vyr}tyaVLp5aSz+xIO$Hm$~$6&R2L}){zsC zQ;?J9Jld<6OsyslwE>swbOr86bujfq&YBv5N}fK->4F!29cc@>XNWKgrkAQFcjHo+ zKEwGokK9-=vrfg8NPo*=T=>g#@s|eq%iQ8G^Mt=lJ%5=z{<1{)8$BLWnWwysX-hZVBt8Sk4(3a5wHN8G8e~n(G6hUngd_F7vpu?+)-fpIU>@;Na z;Imrkhn$vl^Q&~}pE&oS8JTADsZ$-+_1UZR&zw#$tj}bnf9`aro8zPOFC6y$rpX<4 z82O9Mb>XOU8!itN9sDKMk_ljO&+;hhz%O|h`BG;^K`C8yN_Xm8o zrVoL~AU+dXFsowej`ue@8@2Er#E(M@7AWOii|e6U_!Z*cp#`%lmR`YoV1&fR^AuI? z#q}Rs5C=Z@kzT`l5tpU{0<9pnBjBfkt77SOy&KVWsD(igM?@_sknrBSz*@Kx;x$nV zTsBK@={>U8MshX84N-v0X6fy{ZGJvH3-QG$z-6=a&fd%Tw24OY5X8e#fXim-eY`%m zTi_pvB{oJx{oW20Vi<%= zDQZhKovbAmc)gI7ay8VY$%J3C_-|C{o4f`W0^0=S{s2Rr;qqSkgWf2Nk9j{WuRwf@ zfL|OsBH8Kvj@~-KgnR?>X9AI^n8msDx4bv{O6)vRam;g8!)DC*R|S5NF8zS_AbNC1 zI2GEa2%<}K=|{XR7#`}``U4nAC~`If{qB7`)t>As0E>!PG9R2vPf2+X%|%VE2eBnE zg{1Rer_#%$wC`ulya4gFzzhI>a4x-K%C)FyYT-+W-$pGcP$y*&ibzwPvKe#p*lgwv zm1R6dvy`9F`O4`K8c{S!VULJruSC0)f%p)HoDa2UNSuvk4dNJM(K}_>)gZ<|y*wnW z4JC%B0f7_ngLUcGr(~{x_%ehyL(zP&uGGrQ zI@k{3YiK6}JiqvMAdw68{D44sex)w`-V&v8F>quslnH?vUQfYYjrf)NQZB|#g(C~V+z@b3 zA4YDJ`bloW^}vyJP&P+Ze&ViFx)h)Ta^!g^2LjcUYnZ*9s)wlpXW>PJj{$VH`N=H~ z&z%mqjJqEfVn?b1Y)}MdT|oS@5bg8|sU5UCXb-0UDY$qO=65w&h&#gc8mTLE7&r;w z>|_`SKb)6dFLfgByd7Bzc}+3og7!%Cx$@<0L>`5_GemS4Qy}fy;zTV|*Pv1J8tBM} zK)x=9-PsjbhtxG|eau0F&fpg5s;bF1xB!&Oa%+Ni`9oUfw{{VAlG2|=^$nTTp|xa-kpq?_t}b% zcZ>UA*jom9gRw3wBsdz$^ZuqYOPy&bvV;MO?y>$GiiU1M4-QuI2c==S+^!(@0A{mf zWUSpRhUSo2pU-MHnY_+_w41^XS?7$}UCypo=Lg$O<)wC6J+Fd8I0*2RO%b-Dt zm%!dv7mGX$<+)HTO|_|B58Ev*UuZ9f{{e7_P&t}_&g*)+mCJ9&RU6*&D|UZ}`dFEE z+2mNeyE>sS9YMYF{g{-+W}*U`?Rj0$LmD#(r0MXE5Uaq@Y$wANUspVdFIz zK?^)LejR{m5U&n_`UI}Wi|CBP{%N?Ola)}{1O!5}Uu*Z_y$t;@{GSW7cq4``D-BRN zF#d=Chk<6t&S5q91eKaaQ``p?qczf%r=^^yl?2mdFr6^oS#vnUulkya-ZudR6TO$i)D_q=4#PJx(R%~@RtEm@Z=oWPo#@>J;n6@0ZVJlxa$~7I zVoN2~1){ux-3O$8q3QSsG~vHv^+8X}Y!UhqyT3!|69buv-s-v5Qf2to$7UjF`tGE6 z5EqR>e&>Sd9#TxP88Z3rAYO)^yd6(E7Sbe=8na-c_j61r$^!VWpr#oTS1TGT^gXzq zq|T_l0Mr%`k0n#49Qo-iEl@g8j{M2?-UXVVGfzG8)Fa!=Mr885A1Km^StH+>KOBu1 z6TP22gr1ff+OPlj0$P+AxXaBN$vm}lzKmlq=i3RvdSJ_7_{f~^a2!qu{Nsn=L?Aoo zI|oNM1fng~UZV#hxmlNNgJ9=;#~^AtrOSxKdZpt61>p4%5I7akJkY6Lx&j9hN(9s0 z*eB?0+&Eq5eD8lWnDeD^B-+mTnj?SC*BtqCz8a|g>9}gmsrxVk`E$OKZ+SH*>yM zLLbiXU7-yKbbpf7%=un7(;ArqU{(OZh?(>41YM0Rg|;TpeIsVhcMGnS8k5HX>@EhG zIo}sBY*I@f0{EJcCfB!Q=6r8PN3WJ*NLXoXHp`Rdd?%sZsiiXkG$E8^$;|mq8DVp` zGk|_YAb-v`gSQFeA>XuXt+A(%Zj3NzN|d|BB45y$o5#B^1PienrMp>$oBTq zX?z*;Y;OjdPM-HUy;D)+=T6|I8gsrM>;>v^c+;_Cxz|9pYv^wK>nQXO8AF! zzI%~{-eV~Cj@Wg^mO-1*Io~1h97*BJsDL@&>F}H%2&T&n=X{q#xhGVQB5)FdIp4=2 z?@mS{bH49F`7~62hJnbO?~hRa2~^wZ1arPu-y*R;5Wtbl$1xp-&Bi{M^L;cQ%LT|! zM_NPeNWvsMnDZ5kb*tkHjtql3I!f3%-|D!?YnLKdLtRM1s~?A--rYoKa} z5YGAjF<4@(M2_qM@=l29fH;`*{TY)XjvRsfTZk~6$<$!Zx0{Zw%OdU7v6=Yzh@JEO z`Ffga2KoFDQBzu(gE`+0my#O{X2PjB&e<|9{N=g$ON0DnZt<6S!e6GIzf2x~St9&B zfdqstgmb>EwZ(nV1U`Z3#Mj`nJ?`_oYzPy^~ zLn`SXI+fTwcs0cQZymbr{O>t*+xg#3Xj1djZYB&J}Yq_;*Mpp7aCyElj79 zF&SJ1N~2^oUJ4eBnQ$_=9hj~mSBWPHCxeGUxinPkL{v-$Uj=1JsCGww_~!k|;JYDj z50GHocVGp|XxLt~)p{@~dqBJsP;re!Fd4iRb2$x3eGB5(kkZHmlfl1X1xu;Zp2Da9 zv6=jgGg6o}u#>@`V$o5WK|Mbt^mdzB<71z@qx%3G1Y}Hzsi9yp_(|NoFF*mv)gTs< zYQ`vrlfk`l+ni5e9mLIn86Wt~{dOT{NeS$R_-be&m<*l-KrMU$@n~ovm<+xXv*c>Q zdm6ckEr^58^;YmUEyGkUPjM#1a|oC^W@n3Qcz0utu7E%u#BNawb~1P)<}TI3ScsFN z7VKp3gLw8wEi8gq7`0$0gDXt4k=z3D!6;xSgIA&8G!?Hwd?yOn$>3Wrv#0nL;*U|l zP6jW=N}a}`^fMU$U<>lWP6m%e9A+|^4IySn0XrEisA39qhj>v41e3wjFy$%ZAzjES;(r1&0PJM&n(@}c z4-ijAE!fH6S1`$p1bl;?v)aJXoySuh#=4(9O{tp%)c5!6P1k3deD=v2D&*J$Nhqt3@(cnrO++_`;wtJQ-nORlfjj66D~)9oCq;? z^&kce$5s675^LD4r|-n`uh?uS7fc4fil+b^sShPPP)&CElfhe2`5fsCwO2r3TGLJj zH^Iz|BbPwAB2cw086&}Da97;7IC2Y^RRISpb~3ml7Bleu3n-68RXZ6x59?Wuybk5_ zK-FAGI+2|WehdA+BfkNR@A8vd9JZ6eb1;L6=N|yJC<1FH2a~~F(J?vF9n7dxaPjk* z-@#|}7}JR-XwzY!wIlfhkZd0{QV_!r2DVwjx_ zt~S=k;uu6#!xrtTg2~_qG)_$+w<(6$$>5p27^jOMk0^%N$>4kLA~Fl|wZ#xS8N6&c zkvk!8Du&p};8~c7bmTe6ZzUs<$>3lLctoknM6byla- z07duNUaL?vbZ7NI>&s8afO%S4oyM=>9$+-CZE0U~#?bAw8F`p?WH2}kuiXi+Bfrv~ zqh+^K;Z<;dGef2NZl}+0#o(0sQ>2`V!-Co+a=Ckd6-A?-D_haU8fZK`hq@;ak z4u`m%zCvG}_PseA?si&;>vP(F`P_z+HOlRDJtmmajvLFDxSa+K#o-Tprr61v;C7md z%U0Tt<{{d1h!7yibSmpNNIVEF+GTko>!y*Lkz+yEmWUJ?baUj$%JtdkF1 z195Q_D2p5Rw3n*kUfWpM0C8&wbe1V>C@&XawBgE52rq|X7rCw-#8)n`RSDlegm@$h ze8j}Q`g333yz?>=%FUFN=2sUP$5!y#H9;)vgUBvMeTV!^+uP=5-&S`JgHBDo-Z;qK zX&|mkrnIUe_r68GrM+?HP~YI)z_ul$KJ{jaVLr77#Cyq9d;rV6iyS~MrM=a0p^qL1 z_GdEcQ*VzL3uYc3{Rh zKhO*WSo;4K=!z}~^uZRK&(wo$2(T**q@4&$OV5Nvj6*S`9X$6spZ^f-*CEeO0D$_9 zRzIB4&!^;7yibD7CN;FGd}ql-2a|TF8^%zsGz6C&urRiU9qT98phmH0a-}=Oi=x0% zcK4rNi^{||1MvJ8#2F#bS!!Mc;PZQX()>*j)>G7`Z8GpuCXhRvP1!H*Ld|6t<;pW) zUrFZC(#NrVefcTux^f8W2@L$I(fi$4TbYADc<6 zeT@g{yy|Q?Yi@zFmRy!2u@3e1?_uOFn2OUo)JDZw~ z+W^L`yNO#z`fDN8l1(ktU*k47uvJU$H~t#8sezpiva==lDb5_6N(*m=Z_6+BcMxj; zv(B=a_n2?g&%rK@6}T5EQ0wpc)=gAv%9&6)KBU&a^R44`qob%A9iP&OdT;oNt|?hC z*YQQQRE^#?y;~U1ryTynkTj#eP4D9<@D7g||1N=};c*6(;{*h}e08{0c{t^(3+iphW~Skk zdNWMdk0`H>Iihy5=ua2wC!w9!oQZVPy0h20816DM8-0%Rh9ie?bQoI(O>uHqg}3qc?Me80Z~036 z5OhqIq;5yJkDRk`p?Va6)C6%Rsc$s=C|xmhK6T~{lGsiHZ6W4G0WJwTUplX0oOyy_ zhC>`nz{J43GwFQme1dxdW{}K>xFi5fFNA5GsW5ZgN$YOSYyxqAKyluOz^~3ptdXmk zS0KI{0KOT{dpUnPCo$Wq>G>YS@1!(6@!w6Vxwz=yb!aRrYn&^4$rhIvoszCh^3xAuLNQx>r^G4kZp9>q#{PN`%Zk~$c@^&Q%DM+zON`|s z+p&8jpu!qcz5GHV89-DzR-mW$GLH-?R z>KAAht5Xd)g?_PwTV(?de?p@ha={&i!G1 zrlR%vC7i~2$>DKTp3-^QISr@RuLz)?*Q1+@EvV1v2lVjrww%Xmk_2lag8l@i-bpdQ3VQNY&o{T;Cw$S|EC_8?$l z5Y+Rtuay|HQ^rA@9sqs?we`Fm+LM|o1hF!p!g{_Ex2$UBL5R-;fN#du^E)u~(e%6r z;&W1(p7`e`)wZ6m!tH~e>`xFSA(=S)l&$BJa2KLyJRL+MQc1RKJ+Fe>DwBQ?eT&($ z_57y!*488tvy0iX^}J>eiLrcS1$K7^R9KUOS{>A_zz5Zuk;VH@2$x`G!uwBj8eg+N zLXTU3<-d%6p=8U3U%rdF%N4tp*=!n}#?*zg?3+`FVL6jBP-ASsGhPRicXWSYXtv4s| z7N*fhNoj(8 zN}KCf?pf%AG|t;V>?meSo7i_Q{#(Y_dI!YE#cXMF{lT4|@24Mxi;PH4o^~TA-BN>X zKGy(o7O6XkWGWVVzf%+V9fn z8FC{oqqPrI!%g0s2qP!3i&F{DSEK)Mb31%0uULz>^^~=pb79#;rjChBCL>+DsJleB9ZEtBLkr-AOA2yB@qA{753yKJ4VS3!KO$ZR z_9nIr%8|z}KY`!3fq%RcR1}we{PIr-Y49x6(;P+VI zANM}il-P>*5`_JMSft_|#8u%^h;j_OlceGZEb$+4f}rAkGF@WR37rPt8rUp!(m%gFZ{o5juYh}L57xp7MZI+K@Vpk`i!WyIZTpWu9btv#bQ)DjZc@M2(7cu~$6UM{r z$I+t_vVZQgw$eTQMOf+BR-%=z2`iet_0Ol#9}_qo;#pC^R=Pud@T3vLbcEQMfQdm+={5kE zL<^%JP7VOSw%AISGTWND0mRaP^6w>nb(UXY&1{3XBLI9ew$eR<3$&)^9S|Rr()7eX zHmSCi?x8aFWWR!NA(=S)l&y65P@9Q(4G?FMO0s1u-J0os`a$#{rRn!=*-F=Lg0(dc z#PnjeY^D2q5tgAzDtxA@ULQWbeiH`qr(@J~nkXP`L3G8I z@e_9bpS&*-IeH(HQ#C;JawX!Ih_w*&T@FfMWfd{Ri}FFhPJJ=T}YOpJG1WXKozZRP!nB4e7fJzBsQKO^px z!^k0e6w116RF0}RJ`>w5vb`4mMfhz-xloQ$%7%BlVp9L}AoYOv;3Cpe`4hc`I|JU! zWVsX+OvZZyub#;`u8`%ZALk!uRNYky+$!4#!s|yKAx7k~z4bU)Dd#mn3y~~zQ10vS zSS14-wB5vNb)R(?-82N=kZnk&d=-%GOeiJWkz6LX$_tkxTn7fA@qr9-Rv4sPBuFJ2k31OZ$l1E zjm16Lh>8}wU8M7H*c;1?aG!x5=Y-T9nvKRccBjaBScp%IcMnh}sXIiVX@7+J628Z= znYhvgc*;;laO42!-q#pWV2kLC#H3itOU}pW#K5(!3+@~+Ed!1&*m<}fb+113uJ9QU z=yXB96iT5?WB3X1SrF(NKALBR(u!7=f!GpIY9&gomZwwDLQ9GJG@yL}NLO;co@l}| zA7l=E1@XrKH91fy|3w$?$`RCaY$ow^iOJm5@vnDh)nRo>9p3-~zI2C6dxFb0g~DYO zw+(#z2Z8Al=G?fL^R_cYLvYz6!P)ylN$ZCYli_<+5W5`6v>=o$}meJB(zE4W`l`!Uc>_&i+*SSr(4R#lxQDzCvGZsVY-doEaf^b_WES19}lnR_98M_@DgNSEg0EPSG1j0WJBt`hth zS)uT~a(6a-?+pUbC2OQV@(8b%^9AlT(yv)?5Z|gc_=SF>ThGgmUCHg z9>o&(VqYknVRt`(^Ds6OPr6WLIE7y*obz{ogHO3{lXTPQvBpLJSc0nth0>obw=O(d z1hBT;IFIpAc0EGX>jUZnkC6eS4VNuxL@a9}y<>^VpbF&{=EqEUEC^UXKPvWwv<%)` z11Z`dXRtw{cds&rc239MeIDR@0ZdnNA3#HS-e=e+W}w?xE$`dT<0QP&j`_*g&Lhra zOnE@LORj1G>xHth8Gg=yf8&6qi~U+xM&gBR=;y;{XrOZiLQ4>rxh&y$1edw1u;wDw z_$Y|X1<4Cf9W2&JL%j!sp{rZN&=N?u2ZsDynb!)^W_a%kBt6F(8PN)l!nAehA4|;d z$_U-p67T_de1Aoooozr_yF`Ho`_KPTuy>Q;WD zfKT^8_j@$X|GPusJtL6l@~ifPE@%2<2~NK+mCVwB*Fe_M9q)B*FFMSluc`cnvW3xo z2p(@@E8bs^VD*UaVjV%Z-y7`5;N*LsrOWp1DYx%H0$Dq8k-ME2)L5cBlC)Izl}ETX zAcLqB?G0zEYQ!?UfAtBr1d_>RODZGDBp6-4)Pc+U+aZSSa}yrIhT>c7u8 zoX70g21Ms=s4%9}Vs+ZkGnTj(`$B2X#_}ed$FZH>87mt+$kJKz;+ZprnRB+17PHj*FCKcv76}!-;ucC7)`JEh+6NR}$xW>Q&|0|zRXnAO+aL0z0H!M$o(#B9 zRY9S?`eO?bxn?dXesGwJvgy~?GcwAr3FOZgbFGCk>rS9U zAx;ZWx{^_TA9b}zlUpY zp>VF$9S?C)fYKF2nv<$=&VBNO?a-s8!M~7ppcyb$)HBv`4=*N`3Ys5dHGtfuYmh3VCk~gV0=GQms}FZ z*AecCz5ERM>=S;v6<#Ax;F<39nGP3r*2v#C2M5b!yjq42e8`4V#G&wg?h4wB17i6FT=h$NSXG{R*U_beD_7Z}mjo19$E_Paemj0q^Z zl9S6-f~E2W(FG7~sei1kIM2INM*~@9pl*e#ErTtW*?`MmZ+Zr8xgx0YzmU4{LS2Wh zUC_fg%xy$Qe_>@Zw-LbsZ};uNGO0Qq&sSy)6h36+r#oYi{LIrZo*fyJb8!wG3^0;w zw3=qb#r8X+NUQ)+<1p^PIX5r=Gd|O!@$nBdKIUMVY>>Tpa3Ev0JO@LJzC$w=CQg4Pacsq`Z;2SixV|1$zDqY>~AGy>)z zDCk_rFX$CCfA=XOkg1ghQGATV_y6A_&^a0b|3D*P4p7jk?85$nxwPN>g4Qk!5|@PC zI`D3aEm-|El|ehOI0gScyy05VdGP3s%|LYF9^tTdxIL(kfzRbd^g{WV(tLPt3Z!Vq zT}}I2b5n|M7wZV1P)ae-;|Q=jIS?YwPolc-!29Ds(rE=q{NAd24BjV;N&Gsrr2dW- zIcz2Y8jIxKjUTOb8-h4LpwxB|idokOL_t7lPl*_Cz0;iu??u>xrA>1_?I+_DVhO$} zSt$I>g}WLao3R;)F61h|HBu=2?8yH^+Lu5_QFPzWo0)_GLP!K5VUY|W5Lv?>Kq2fq zB#5#I0wNIE1Y}i^C@#1lprRlms1O1|j3S6Aiwlc8qA2dDpNh(dC@#4F?|rYkXA+X{ z{LlIIIXzuf_tvYb_o}L^yQ+Eu&m-he34E#WOBsRp5&X9YMc*H4`q`})*Xla?Z5(RC zGlBR&@iGjjrO2t`V%_(0Im24m0}Sn(xxtWqGsjsBMDB1STP{^9gEcvt<&LxT-n3lT z$OKk_;4Ou5$5|w}<1B~VjM5I3LcTtVtZp4=akJxc$!4VTe?_I><=7o(Ma90K?#iTN zZX78s6@DQmP#Xak;xu)r7V&D}p`C!1O63=zolZb!c?`Oomsl0!1KfCOy^!N!yU)86 z-||ZcECq(NxQl$Lw1uR=?TGtyX_ELl%#-AJDwFBf6@L67a0mhK7LN|e{IW#gO9cOL z4#W@S$Ug`^|Lm zk#hhp@~Cv7YIBtt){o$Kxh$mpb|c)o+px;c_4&&M8A{JQEVK^32#>GXV*KjQQsKhE zz zF2ZS&^_2#4dz6wVA-H62s{|S9l_JoBmP^wF$QW6w3~fZzoZV|H ziBOu=a?hjU{CeZ6OfmNCvRtN7?rv8ulk*<4YOTq`4wh_BZYXN3RLS+I-0}``4_0wh zDlZi0JsVvL`EMiO6P#us8@%)gZr4in6f+P+RnubdJ-#!t?8rd;y%^#xmkbVcIwQa{ zX31ATX$pHUihF2ezI)YIKzND7be2)Vli2xY10AdZ*u zM)Wn~9Q;zbY6K*0MZjrF`>7qi;S7C8mCZWxnB*WQYD{=c4PAI?MsYmsdZ@mbTJ{tO z(QPh==zk%$qDZtvK+g{YR0F{+i$m4~W7-E8?rYX@B;WYFgJ0<&y%BV&N2d!dI(9S* zF}DN6U5$`g9`3%|Y>5&D@HbD$x|<2_{pq#7V4AK(K_Vwd;cI>IfkLqMdrVCvx+hvM zh24sZ{&rDLEl|H;2ZyMUBhnY zYujADw&l@`yO{N7y~JVll}wlUn$ThHQ7w4?C*suzJzI4Fvv+(6hPq;pSYolBOmw&mhK(dlCYbImh z<#?t*hN}M>_~X{$eY!k@>6$$d_X19tnJ=6%8V-adkEL(V+3Lplf+rY^n_zP${>ETPyc+=< zJgzq0Xo-&t{({e!kRZN!iQ=2F4u9AV|Ne3UO)%fk#1?4+M+;DV%i zd*LdNX)xIC2%J+vVxdEqJSE@4zc61u!6g%nZQ_DY%WnwtPn*x2I;!Y~tR7NTd=SGF zsEXl;WqKgm$Mn!dVd{afDZztFQ$l~lJ7G%5S0&tpc&3E)aG4Um04apF=PKb1p8pPODJ0u7G9nu}Y1(Jub zBH>#_GS-o?aEH``KVOpY`>{&+@<*%z0=|!UZod2me^oq`6lr}Wa-7H&W*{QlwW1R7 z)zq5yW-PNu0}*~gYboI*!lfB#7QhUPYX-U!@ytLwG-=k-O&|>=$*HB^DTfA%+u$0A zoNYKmIa#VA8mJ@CC<7H~E$ss1%!RO03{)V?0GM&cB5vd;lxu&$IvmKqA7{)c*({vk z@dED7mlN>cj7Xd1QMm4QsSoAL^YB05inIP951IJ+JZwov@Mp;HzZIkUha&Al?gOO& z*$Esi(Q!NqV4nhU<#Zh1f<$eUFv&D9wuuXt)^R+I ztR^8BfurYDa668B5X(9aqPt8FonDZbsV<o}@z zBF>KEIPiqpk&dIEBD~QN$spo%97L?+Ad(FPN-n3_V?`xw9S7lD!lfDLD}Z?x*9`O^ z;+cU?Y0~UC>Or3cBsm>N-Oa9ny1``zBBv?!o-p1>#sZPi7mM89U$;7boGzLd)(4l;R@Z>o0 zU08`NoFiL|ES?n3Z2SsJ1yH2JY!EgIr!@d>7S4#cV9ba4!l{rNk27UXqj<=qeBt~F z5gaCy^6IF}H$9m;7KvMHa$SNecYr6?Lmat8aBSARQf4caYxz`}NsdexjQMb*=G6n4 zT@ReJQM2oS6#b06I1h}yFGV;l`mWkaSV8&aIv9_2I~d#Wgr3w zxr3Z15G{)dRa9F z+#8%6oS~dvnhdLR51@7*yc{lQo};xdL85X(m*nec?Eximz;*zxZQ|l3`&};nXmScK z3|N-_TP+cU{i5-?24oCgwKyZYP9PR3aYtph(9Zz24w`5eoNWIJv;7mc4%&m=_J0PD zt1!kp9Idc-pKukHP~<8s7Ueq|rLcBDtb@KBE^Gf)z`1~W$eE{kpu(0YkL^E7VUK~d zgTyiv=Hk{3JPHwd*l7O}WH+G>HMSQc0~^PiKnQ1Bxkv=xCfMOtQjM1YuKz2bZP@u4P#qt%(0>=BbEU zPq~VC1f+r}MRW&ZikJYGDWVXZXK{vd?$kU`5v!C}LJGN18{A^J9u)iO~jKyh>&U8ui(`z$+gy?Z$XX&egXVmJrt!%?aDEL3D z&3g&sdylYHLD>gomJdG&SJWeHuJZ^>LJgcS=l6&hH4@ETYZmnwu0?wwIk%11M%3eG zQTGvcxbp~m!_%%sw^u`6QzBJ+BM`IbD{z@b_k!~Z&QQ)sh_sRDKgy#;t87P#)+v@p zfve(lEy~Zs+f(dHxVDLln?*loL>|`0FNEx*6sqH~s&3W(1r)2=M4RD+E`HWbuxb-F zMR;&&ifDldnUL(Y@g|r+vAe?vxa{sQ0tFmOlGDa-Q4a488{slVj0b0$Dq_55kyZO+ z<&{vxW{{}avJ~OsridRQLXR!NSM?o{-D${4`S7t?R0Lnn$2`MP-?M)ix(;ZCn*#WB zAz;o65Pm|Q_}1XVgag5Rc?ALe0qqbjqoo8+AoPTMUsxq{R|%XxSm8+^oJsg6+=eOP zlVTFC19>`gXcFR(#U1hp0(Z!L_E95L3n*W{hwB} z4Zj(hj!@L9n_%i4`kZJ(Z$epwN~?|e0Eb#U8+vcw<<`c(;Ii771jFQ!Tt~GRzY|%T6NbKDtgoJnJk9;WG351hw}f$uZ9t z%At9JyIu2;^Ou_EUd;nLiyU65gp$??)pxB!MizW!Stk?tT;k_ghsZi2j&-g^4$V454gqnk^9&GcI7ChZ zfrj@cyVfCW)*&2f0JyZq(-mL}LDxE!_PEv=43}AF5wxC7l4G64%As{O!)1+!oF!_V z=1`h7o)45)qVXibI@2JmEbA-=X4d%=(W4IQ(%wUc*MU;8cHrE0L+~)bl9utMyOtp% z1HQ5>a~Ak$;^$a~NFEW#GL`qbmLakZh-;aVK+G~k_5p!*ht+f~L)d9IfR7O_%`&_h zowm5vt!+a*Yd3#r(tM-P5u~IGBbI5pj~rSi8!od9Ila^}uW26GZWb!9gk?5?lnG&F zStc8pS>_Q$FLo3Pr^|<+JWFxnR+_I9<=esADo20DUs@peHbPDO59>|%F9f~;IA4B% z>o{E7#3gN#iof8GClL08aCzS}M9f9v6|TeEuNM(e?*&5h9Vm}b6+rhpkPkw{_Hdrmhu(j^#p7sw$bzEj?w1pj(_g;BI{r_CJ})SJLp z8Y|(iav$)mUB=UY`i7lSVG#U<GZNYU?v)a z6Ky$7Vag_K17;5{F56zGFkV7KjcaZBFydKTuD_q%2-|XXSTB<#r#BxTF7oT zaw2;^NpTgi3>15EAX>*1(Ntk7g0LyVgG*CHUBsIftq9*iR}s_TGDWQV3G$*8u}V4Y z)SiRO6!9oHn{kG6)@dH7i2o|Dgdzk=i2EOkaB)+F|B$B$&YLzxb_-Myf7PQRIAdB3 z6jRg1Ku-e=91YfW)wB_)sfj3;`lG&F8YWCN5jHh>aA|7lig*c)qUuYXS6nqMh0D}* z0L9NB$*C_pl|was2$!kpEpXmfH67GEP)(IyrK}QaqKa4n%c?IfZffGkeWU8jKxDTU zauPUNDb-a3zv^y^AUentafRxMiXd!?@Zi!EaVg^EMl0eT%{*VCoPf&|@ig+iI7$(T zud#qsL`%3#5xc?J&+_FQ);v%V<(u&IwR$nLsERD?}^ z@aw!b^)V61At0FgcuK1h=S<%MoG+aEsPj4t!#PtDPlL!IO!S;-Qe!eWXG%sEd>q0= z=1e=O1WtYA;mjqDAq?kC^AzFK2a#n&oT(2YHc%n569_7+U$aLW5w?K};lqSWv(YU8 zPgq>*+}=by>)h(T;o7JZGM>~VQdutpVm6u!m)VG%-Z(=!Gc^yi(JtkAHnIUeJGM*+ zE8Ru~k`2u4^BJN?4x9aW82R0d)0_S90-V{8%5Sn4<+SOeF4dX+s0&078jo=)sl(HW4~mzA!QZQ|ml7k;7EIhvg}8fuo|yyNfBK+WHXvmNjgNHDQ}i93F9 zv()_#FG0W=h*J)36mIYJFAq}4brkY;5r765z&!#XO(0-+8A9FwPgjV(V?tt=2V+x{ z)>6=e6!b|3glxoF{xBv@Amp(!1oa0e8>f60B`8h>?V_M>ivYfXb2+H$MCZkwq|Cvf)XFnHsE^()`uka3Iva=_$n26Ka6S2;oNC6OZPCuXk zHZmb>oju`wgx$`bklV2>0C>#eTE{jNpml8bz-1lVqagX3MLITa#JA4=1YFj!k+TJ7 zC})hSh@E|ncioPy6I>9+iNRwar9fDTdG5hr6i6lj>(Q=e4DYa>{%%Bl5U1DEdjU>Q zzW|Y}r@zOgIz9a|N8CQCH55|u!f7^MtvrU%f05mHo4Rd97u><{FJOJ%R9{?It|>)l z_`JN2hR^`fn&XV?iF*=q`l6h{%Hz1+jQ%e~t&m-r@b}>^!!5GHhfk%0Jq^sbelbmG znIj0}=UMY*KU~@B+6mW8xUf73%$MYI__qsp`Z9JA!mwoZU?WEV41uI>7H$_FMd3JO z?#F!uettAoM`8bBP>%5Xh}8-1kUj|5As6d!27U{L>#bc%r2yu1{zSkI`9Xib#P2q7 z;mtBDnmlKRY*yC8`g>0??k3p@e*yBbMY#BUCUS5X1*p{jo5sxl`9O~V%@?jX{|T-l zovb471bDIiY_jUS_sHR7RT^B|bqb1{PzEaDAF>z1qNkxUK|-N8rFAn{i*aH~%ciqT z6sNN&3dd#%BkeoDS%R}tza7E_?e6ii_K7(_(venN?=8AQ?jiWI=T2sld+DBV(q_3C9wVP1HO;A)Be9!gzcZm2_jDWCt~fNNJ4XK z|60p9*duK1pKv;1xBU}x+y8!mSr*sYf2;SYdJf2^!e#A0gr+i$BxhjrsB$>4c^NKi z|Kyy96YXDB#PJ7il4k?SCjp%OI>o`_BNQKneg@`|r*e-eK$E-a}@;z!^8t z*24`0$C~?x4ie)u_sLG|W^BLvWdCrCevxidyvke%=nS%WYx5FqKDb|o&V=yAPa;lm zdFbBYlfrF<_aWkgIOFcfXvSLu_Xcu&^rU=;AqJ6kiVjkg9~FuHsolW<^8Tb;3GRBJ z?~-xnw@1xK zeV>g0?rO`I5pdO1*VS+}g=?F*)J<{=!nz}@P@ecDN<HHa>AcjfKTn;TsZ_cp|v2W!dC9|0jBLP$ajcQ*bs zN+Hf>iT8E01U=XKV%`th`uxYF;bhz~J`VDJ#%A*%gk+!qH{e|%zm(e!vif(xq#8f9 zK~HL4Hi$MrcJG{ftQDn;HKX9Y!2=SPE|Wn&D2$DfCu~`C3SY{E>?t_oT1dH;ROPn_ z%=(C``~a@Y;j+aH!yIC{8Fqh|p&Z^HmcV6;8OXT;Cwl%bk(TxTMr7|#BI*biGmyn( zODtwsPX_x`_6)Our=S+ZwUa8XC~Y?aU)5xb;QB;ekHPgPTu%u1tujg`qQtMjGvaXs z82uf%jD7$vqjR4v>Di#;OpP0e89k5DyCeGB2$%#Y zUp|Fvt-4-@i>VdJN{#+s_>Tf96t>g*5q$&B__~PBc3SZhMrS*{5H9D~s@%Qcy@@lf zlU%I2Apatde+T*7wb_zYgw(+7*_vA8E7#Y6TiYf4Hcqs^l`4pBm$0>64|dyb{HM%^ zJ%PWAc!wbxaqUKR7eKpFJqMTFsQ!zoh|?rFH>&?Ahs`(kGq?Hv1`ZxB(0nUs7I~w} z1ZvHgvTyKVJo4B~$uksm@M}dS|;w7%OrMPawwsc6o&w~1T zsAm_5ugLUK2b2 zMWZ90$25CLeN8h1f%%e(->RQ0izCw@W}XVj>M3KuvXSXz;5IUi2b_%49hoj=OjH7X zfUXY0Ti}cvD0gbqq!YLYfq*Q*^|2*#<-b?~0oEZVGDLo8%i=$Zze3eQW?qa7A5F6^w zLh3fu?TQ#f8KeIZUb%DA|w?zQZm{x-_$WbcxrmS zR9)2b8n{f)jBwaLX0fN=)XfBCrav< z_)y@n7}#^&o9Xry?Ad^fvt$%|HfW#{_-v4Xo-3&h zaOc@zgd!X+5y>RtJR1p?0a$?0-AWoIL%o^aWSiJU^5p_~Pp2X?vhl*eZS?Q-qe;39Olhas%=F1J8V z0JHA)VML4^TXnlkLnP4#XWUfzRny^~nWsRsXN0B>>^>vxR}mJqF%oWzGwy0>-hozR z)MH*$7j~nb)u@F!h@FXO93aJwmyJ4#mCKMZ{Y2&l(Vd#O@fQ7o8Uk&-+L6MK2ww8Q zhubw=AHcOyzJm+z9SV>SmhmjSCjo2`ZhQR!BGM5qR}HzC0(8$R`qC$a-$42i=ro`) z3Fy{8Lcrw;ackFafc6pk1`uoJ!+`9q)ls;tW|DLkq>?o=Bh#&!WaPqEyk@fFw%r-k zFf>_5+^L!Tyr&K1i5w>4)J!7Vbps(0UpuXt)wNJlP?28+Y&9(SEk&?~z4to?g(NyP zEE9;;u;Fl74I}3`&QQ*07g0g1Ve^&88nzrR2;%vitp)&jw14)~vzs_^@l zXKxX1KE4z(657MSSMOI{q|y8!=L`2BcSP6ogx);K%K|T^BUWTk|1$vDjq_o+T&>Rq zZ8XJAv?16lz?^r5Ko$c*IcjQMWLXGXSr~C0;o@bnA=nK7cUoNQ54c>|tknlDvsTgX zc=<|_W3Bs@!y(vCxXfDQ?7|t!S)zHMwJM^)*$^zsT2=pmS~`?%t#n{!tqer>j$KmY z3KaeZwz`o}^I(8qBc)~o+(&-hH?7Sr3nHBL4tbIF4!WMzT>EgUd{|9JluZ zk{pv&!M(;BSZlb0vr-kL+HIQx@;kRH#Evd7BPh^c)>>J^67&+lNBP>N@?XL#`xmdWIb+Z;(V! z04*Q>th1}(sX$G`M8CudEoCT74HGsEdvIwQ{u=Q@7e#5f5b+!h!(|#i4}Ew#Nv?)} z_B0HaX}A_R^>K!B9@RXkhLu-B!~H=TN@5urc5&120*KJV6!8Mf{0)qoWn^U(GzWy z8kF<6=7EafRGsw>QB|!Al)%E4r3e={MZ5eZDn7m*XTMdXA}5Ox=lH~f_kQhRuxfdnohPsW*Wu}Zi@C2$e>M9@qEVSabf zTSUIOm;^2&?~QYsNyzELk!s0B9vSW#l*y94sQQ-jgLQxrm&Ebs&^9$v%XcNys=(Mj0kK4cwPinn{SH5Wz4l9>)3w zS+oHhkt`tYV%V-gZ74xxG!U3(d=ILIrXg(RAv~9GY3AWqmzG&v8%l8Ff|-ZCt(j*c zG`f={$2?UL$;{IRE;A1~GjU@7v*v-F#W>}aFwX@T2ONX2vdnWDn3?A`M2|YmI_xq+ zonf8i!1i9HS%-uy5K3BSF2c+@WE7E6hIO)lpCEotgCUa8C1Rb`$e~$>NG1^1I^O~@ z>kt_Y1l9>6!)6`AW*x$F372M_0RWd-T(eFm1ekShh0Cn-GzoB<)@g$1QHOPD&m%CQD`c0ph@4;+z>=1k zhA^`X8SBU>!!jp;A0~c|Wr&<6;cy_vA)4sK5UD~`JF0TMD8N)B61?Oh}=cIMdXBR5&1rd`V1$_uY-_E95MmU*G1&d z!nI9Yk}V>C6JfT9{176Bx;y3PBJx;R>IvZ@azZJDSbi=dC&a@Rkuyn_!dpaMAFwSV z_aJu>IUzf2{8$V1Efb<;b$Wm1lP~z&fn(!GqIGbhYR}VAIByArZT#rLrB&^^h?fn? zh-+2*a>TQ$y#Oxjbee*cOOjKy@xL$Nu+!NMmsRbH!0CZAl=Hpjft}75%JZtW&Ck7n zn#RYG(yR71adE5Oe?WvD*1qpY3VFzh+-pjRM-OI7AhHT43UY($h)N)AO7P&)l)!lF zSUy(?y%5ioFb6JE!iT5>he&diuueHt!i#X368;0uDV(94)0zh=;b-NQP(m9Ni$j;P zl;Gl~gz_-Ab1aprS$O{Kh-c~{IBm!8>+e7#Hmw-ELZ=mdugUi#5jaFfBl(z0;;RiA zSB}SxL2|FgWAqS-8_fxI_#4iO@?*K$kQ<}?p*`~B4eIA?rGI(c9yv2I%AbH2D^SWS zG6ru@WSA^Ks)6Ol7aWrL>ku$p_-W!XNc)gXn1F!Gg@0zW8Ub5{U%ps??7fc@QEOy# zo}VAR2tvSG`$Prt)xpu&aS4^-?5vTNX%Bs|3VKm`#TCY2JORjK=< zq@G;he4@gIU8yHMsUG4;C4$2~dqIg>mJV({&$<#_$o=R=aJfRvs0TTpyikZjw?liF zDx~duz?7q81{9Pp{GMGx4C{3oY8TDX{j$nGr4aXNc#vD=CzsRA+N5E1L`pKb zSvi!;KIN7Q?9BKIgK!pLuSqnh=r)Nxa9NX>0aq?bPLudXIcyT;PXgV>Q| z8m^Jx)-1v)J)^X=4v=-WwG&+}^+ZMNMUtbX9zaY>xp0}5E(K>CPVE2JWT>Up$}6Fz zx~Nrc{zuJnann)}MCh?q_}R$!k=1IPp;Q_T(-zbhjQqOb^^uTh&M0Qj3RJ7V4HaO11_6*An`be9GOS&jR^JPP?mcm z$jE??BlF1K2!8XyCLU6N4<+tQJUpTZ-}n*9BjQXv46n-Uv7;hV00fQW0?i&97GWEI z6W&L-c$Kn-l?L#b#kE070peMe`2j9#Sf@j%3cVv$CiQ%B*s!|8WmSfpKgi2jrg>nM znWH?f%Ghg#|Daz=hp^Hc7UrUXS#@~`(IbbgnC*!C_QC0`nDqjj6|+T%WYc3^T&lB# z?j=W@S)4+KBB_M<@W${p7 z*Wzy>dgL&R-;ex0iqo^W7vNa@OGGk@^Lv|0bu7+R@H}kq6Oj}ol@M>%E{`RaX6>he z^a28F7i#A~Yxf3h*1iQUvo?v-KrCtPl?XFyld+GCGOT?V_zB|Yv~MB_{UX-hpxI;l zCXxvR*8XQGGev6?Hfs~kCS01ej{?lKxMuA$h-dA)eX?uq^|0bfk{oMK1!C4-2A5fz zoIh~} z){d{?h}*889!tk)?F7=2t7P(UmWOjMVQ`+%Z;uhi%XXhP_i_y&yFC+XiZkeL&^3qy zKMyLdYj*_H9I=uh6lu1XF4NGr;GDr3%BiEWsG%#A=T%o58@IwRheM*WH00u@ zp*ax2!z#+FNZ>F|wI>@T3uB{M4=PbnY<&0tih7uum?kGRdmJC$3E3u>@EV+@j1N8N z9Jw4LtV5&|CU@6JSHn#%aO)r8gaJ|Y?=3*4-SKr??Q%GmNs?3lmI5*DJ_(m;Hw&C> z4*PNzXfo99f0S23yM-X}>7p#{y0~fgcZkr#>fb?R_cTtKBlWLfCRqO}rO?It7lzB~ zpG)-WpOIMqjKuLFNk?#c<3o~g*i%jn%$SW*%WaaaX>mztYfXzwNUtW>dAb8L*OQeiai=KcNGfnsY^(7$Fb)9;yu34Sdk>vCr zy?|K%F%mA*^^f3)>Uy^(LtQUZUI|^Ng2W!UEM2>}>3Rc1MCqC@Wp=VO*Gs)CnF+S( zXEhn>`UKflKW_l@urZsCC6nb2rMdN!@QpZ8?u9Cd^^>sGPY*7xRBO{WBi@NFhyp*5eH2{Ah(i9^O)337u7ga_j$(Htpi3Gj5`G zbjDhD6e%PjCvvwus+wS}`wJYab%ZmR(Q|7Zp<_5psdXMyTtTk(KSHctmgcmpT} z-@R*n4tN^VbZgywK&HW+aG3^Ippq;j$*FapD~B2kG;lSz7Mv$onQ~fcGOTrNfSxmI z!U{GYTX9*n&c#iGeIX*M*7-3=E?{Yv$%B>*G&o9=VXa$Cw$-|-VD2;K`f+Z#p9XGs z62jGSqTIizAl5ptxKgdw)j&M{=cA{yBbtFLQLTT5%XC&3q|;G4J1?D?pw3#s zWwkB?oc1_FITJLC)Y&lQm8f;ML9sMKSvqrZ)7f;0(8KQZqmjZ*IORV1S(D+N{uWI} z|40NbyVJWw?@n(d-s#tX#CbTrS)wdHu*gE`HlBr|yeC1hk;5x+nLL;1$ukn=k;H)> z-yStZbK=`YygjlvN1rI@TQ2PrQNtcX8nu3l$G3R#0>0LDw_^uU3LM9#<8O@{@Go5W zm+QfY%9CgRFcVx;o-h4vRqg9C15)xZ{M&}{*cos)Y(H!}k- zH18X=U!t-TYj#pe1U;Md{8^x5MLohYkWK7dfU7%P z4)J{ub4lF%utyx~5vN3mKY^G>V&OrLnCB5!kcdr(5MB+csfRQ1(bFEWz$5OC5NCjt zN8*lTD8lmii$|=`NG0;yw>N`y8;LtJmB>GFu5BnFb|Pg{4=|g$zWsU&a_Y+JQd@_ z&a_Pvxe|pt)AEJ8(mv3{xhw4?T!p$T&81^k8a6~=4OYHzN19Q&Bh9GXk>*hcfXW?d z`NG|3M&)iaQn!gqvmI&mnlL5qNOQxz9cd!~*^ad9)WscXB}H&o+6EQD$&>mhS8JT! zuC$LdB5wr0!{r>?RrA!rahj-;)S1MDxZ5MHsjL2OaGCl^JZtLz3ktK1fkveINkj># z{sCZKg0och+aSIx;DkY%YHv-IgQV*;RpzpY!t8c63e0q4W>03a93-6pZnrDKS2C?? z{`D$|w=2SSyYgW7c2%Vr%Wt=)lt^#Npxg3z#s7P!KN#D@1?^t7l(Bf=e_@b( z*&E>=1Mz=ugnJzX+X#0H3S2;4c9-%~Smz@f;S#j=b0b_YoCR_iv`xAZE)Ra&2*>Dm z;q*4b(Q_XI+>LM#gS(^nMmXYUnPv}ZrfEht!hH=ka>k8tkAanO30OU4JXp37u44;! z5Bx*};b)l8{X6s%4Q#|k=s0&H>^+>=1SeA&jXPh*Ae!|rt5g8{mlqtO+rMm4&QT!y z;Iax%PA}vE{mUns2lg*UWCbVD>0b_jIhxE;`xo00b_|@kEYT1dcMY||9bvW`>>W*< zyTK~9rCrS7^r4a9bXjYR6U>yB?xLW8** ztQYcXyYB73S{zWO^oXABm;v`52IrdTxUlrx~Mvk>-~l@;IuwN0r#Ct$OTk^bnfXzg*|3404rQ8GX&nEz^ z|8I@Bk)u#|=Dmo_zKIh%^K5I~IFM{w;(!CWTkGaJ(e)ok_et&HkcD?bwNvrN7tmJZ zan4M48;|qN0r$%tQ~1dN4C46lp1HobDI{WOkBz-U@MvLQ^tpx`vOj{PC*?&nwN%JX z#~F7`rE59R)YWno4y0i zr#M47r!)_=={L%wP5*++xvy7-TB%ykrqQ3MaKRFvsCZI$qAi2?%{b$(&4H3^Gg@Lh zy10uw4K5_X4doL-nnL0=_|gvi?t{{q3PG(V`X8FRW%DS!1Lz?MmC%92V@)9htb*XF zvt3)eTekK{Xek~odx$Lq3*!3*(8gQ*H_2Z5&57F)^%a?N8At=f`3CKF>FdKYB82Y* z8N|3*%<4@D+z9#(nFUwA(4!aSCBGL zCMty$$f010?z;#h<}kJr--G~KoBhHQh<2E{8Hh%~!QqEU*#?J%p2CTW@PcNP9Rp#j zL>}x`B0_E@;y(wSW&Lp9|1@mRqVZiuKe((Cy#Z3v&`2ekr5skG2jH?w^d2~$;>7zO z7{QhZzoI-=qEF#+Dp3sVMVpmciCnNmCBk~m*J$zf!k7t_@gNU@cOs$DbI-MSi%!sR z`-sIekae~AMQZV`9XyM7DPeI4&jwj8l7F-iwD=g%qb+_T{I12pZ-W#3@SI{6$A|qK zivwOkN>>@76wl&G_|p-!xWhQt;sA1)o34(sn%@}b}a6~uEhy? z76-VD#&j+IAAn}@*o!=igH%M4(`_^ZVz+`ExEzav^C`|yP8y707GI=1T6`s3uEk+5 z+N^YoJK(t%znvCuDvTMEfRaPt0wmPux^pd_F%%kZ8nO5xWL+(up%(ueQJps4ri8^I z`~-EJA*Zzvw0O;ni(9+{{I12pZ;ccD%JW={V>PN{?K=T2A>3AaC~P+fn1z;h(Q_=l z9#MS5kc+mCr3WBIvoxWNIAN_dkZ6`BY?k(5*V2SsOK(NIbcppV{V+hY^gg((ZNCUo zFOnQff2$m}?TQ^;OTPxrJ2*o*m7#pI^u<8!rauTS$I^d*L|c_=X%{SM>BDlSC2pRZ z4mE`aKQNyIJ@1eZIG)FcHo`ef(UX zPX8P9cYc%3kLdgkKS$)fs<^l3Afb0;P(y5nkHxz|9CP25QSiq1#TWkm{deIJIfRMc zz#_b3I4U&<;3J%~@!nRB%2c?IcE@XgDo5m7q&<3^&zEvU3Rhy2#&!6x{yXwBoMX_T z=H=aRRAd#Vx$u(m--W(AFUNqu_kJ5_TAJ6uZ+^b`2H{SZf*b00ctk9KDF1bMge;eq z0TTu!_CX9F{WmT}NPTQ*@df-bb!Q=D<^qH?!0_4^48~kNb*9h%LVJWX9#2jv216^K ze;(yDpUV<)!eh%4u;2L;U6XqZt0Pl@ZeFA%+CY^;?FJeU#IokRhRRT^MrV7KC(R ze*75^!`YP?@$+xr%5`H7{9p8dvp19Wr<2>CY5JRyJAjG#7m_=WsrWx9cQD2KJ44as zE?2p$>ccrkg;j^r%U!9?-t*zSO66veo2znHk~>v}RU`Krb@n26y2@R85Y8J^!n9a8 zZ&bocRETnSs;~#>TtaTlwKK2sHSrBDhdc0%xu_B4eyxhH)-(@=y40zNacgKvQ3YO> zwpZV>L3&v}O)vMX)yuul>*c=x=w*e(F~a?I^zy*PdRcj?URI6O%Y%37W%W~fdFZHK z*7z$i-othDvaYRO9v!Zi$L8u~{R+M0KckmTALwO^FP`xV>*}SblU|-0p_gqp>*eWn zdfEQGUUnSQ%QHXgWoH5^Kq&O=3BByX1{(OD3+v_iE_&HLRxf*&>1FR0y}a<2US2w> zmzU$wu0o;x8G1P|NG}Jk)yttf_43MAy}bICUS9iAFRxcQkMZ7Utd}>t>*cL+dO3Wn zUf#~v%aMb)ln+&q|LV1(RH#CKoHW*J4Pk!DhiVIzQ$Cb}7lOQ|3Kdd5)WC_C?!>!L z7^H%EPTD2>ZR{? zrS#jUm;SHmWx#uS$-Z7GIhc1rgiEGq;NXRNxpcW+E_+NbLpdl5RT$PyFT)4w}vaH1own0XC+{?}?l6>ED` z2XHSsC-KiOK)^$6D6yj-KtSvrWAPh`Yx`j`q{d~ot;tKfOL(a?{<&JbO!z@BlSV;U zsM6#c^fKjsy-Y3C%QXk|GW{pL%&d&YAF4FFfnMfy)5~>Z^m6?oy)4+Emm3c0CGS1G z-1wbdZi=hJ=!=@@<>mo;xpll=ZdRpxFB_>g8Ci6k;EI zsJ;*X)XPVi8u%ZJe!?PrZxK!!^S{RY!J?nG2xlyzUo@fkE1nHObo{7bn3pk?^>XEf zdKsIgm#c>AW!yBqjK57U6V~b__eH&2{U5zdk-C&JHC->$`sii)WWCI|PcJjK=w;T+ zdYS#UUgmtOm+Su4%lxXTl(L|aUT)~Am%PjMa^ppD+?*u>>yvDqdkK&f&W=0iNq8Cfzx-M z8~{b+Uk^-Rg%g}rewz$OmER`vH$NZ0ekqSdc%94FLya7~1p%?QB;mJe)^JGfn~7#9 z*fH`=H3)yVtNDBt-dTWDdgRgyp+Bs92sq6=sLec7rQwPI&?=4YMl+}~LaX}0h7cC2 z^q3ichZ+9`GyaQa{Flu5`_1?VX#DeK%$3*rDsBC21pYgK#b6ysqzlkhSI_oU+BSC# zUJ=v=^p^`6UgZ8S3p3|K=s|wvta(a?kkwTQJF*DW}xiE56+zsIIfTqN4i6-{}XrkEB

Pzp)+G`(W}5VeGLkC<7+F4G zxc)fFeTIM}veRTjGI+iG%HwEIm+{Qde}c6rCn_P{qGkW;xg`rsC(O0{qiJ z4uKU!q#v$8_%PE8$HbOb74E7odju#q8HM9zvyO}U(IX_E7tmV5VRRy0roS|4{y4xf z7M0`2h}ILAfrj)yqg@J(!EyJwj8n|vRAX@LSt5t7pn=TgE~9bC9?7N47}8MVExe=>=>RcDP4*>fwxkd1fL8nr&JWM`vwAA zr&X7a3z6&r%V+{@w_<#TD2Cm~Hoi<{^1-5*%!=stlYghN@E)gFyfo=F4A|g+f^7+E z`}7Q($S_p4i*ZTnf}aa#PVqIaaSI<;!Y#Vu26Y?rgIiBH1Ff#cV)F&V;Rf*CZoW`> zLN0uFm@h7TG8Mi%&6f~9dmDUrnXhX2(CzRoF<(-6Y-9NDHeao9&1>OXYQB{49joEH z=Nf3#pIR?`egb^=vWELp(@|jpY=pJU7JR5uWkH8S*6twtCNt50)0an*;SNMP!l~spvn9<)BDpC0C z7>Vw7m%A{4Nq$c_x)VNDmSm($ZhtUd&=T;0Gb#~=A&-Nh%;ejw1LL!(HhqLQS%UB` z7S4y$NZC!*X_C1dj2>11KDVALdp^dV$$gE%N7{247qWs6GzOn`jiHUw$zRLI!MM!Y zG#`XDAG{fSJ{`b91Ndm{01c&1Zvdb0mqrvmFI(m**4IcL!Rw#ofL@fqC+SG(d<~^l z4-mfLui|{fE+!xb!>QzW;YA62_>L0LNT#CEB)8Lx5;*LRNO1MHVgOi&WHyb*=XGN^ zwqHZ=xacUF5AhMuwf&hHV0Ox|SFp*8H!IUp_~jsdNdEHP7x|hY1X3@NvRKTzK+KU(LTB>gK?&7Ka|kIL{R}b3GfUF8I+HYaBIp#C5Wfi zia0G@H+;C%LRh*Np4fr;aUzYBb^y9Zzy&Cv3yzV?09+XX`!Z%*IeH(`nY^Y8_S!Q8 z*Mo3dgrwpf(zHisI;3?VY>ALmQX3h+9+KwBZUC=(p!4*eDTNaPzKYi^x(aE02K0N6 zk;rtBkzKVA{pP_bPHhMxv?5MNFYSaMp{lrK&073@Dl?iA!F=t5^@3MGhxLMO5Sm11 zMzFK%>`)gSSB4Vow_b20vBl6%y?(cFjUI299 z4blG$y3Z;X@s8a_8leeR=`I@)wGd}Qd5k4!It}kBdlB}U7oJ!dD8Pn{)K5MJ@T~_r z>S-%gass|81OLjyBmhA1BO~!R6KYU&BJ%|mDQVEFv+&?WQUipxjF19Mr>&eq>8lJG zjykB4`hhT#B+Xq%?M#j={JsWQ zt)WN$*+CubnyIh@t(c*ZEO$zA`%v>^K1s3w{xiJZ;54#weQr>cd?MK_Fd{6 zIs$T+=#c;3+u^)>JcU)q)Oqa{8u~2WoYY>g&i5#6lRA?@sL}6Ta62t+h1c;l=3ZC} zwd5_V4X<$>gZcQ9h9*_xdgZ4Eeg5G{>Vlv3HPeTy@xmnqw=-YkJIbMuDQ)jT^v?On zXG;5q=)Xide~SBYN(aX?Xe>OP?g0+urd#33GNj{I=mROpbKtE`cr5RRe7PT9gjYD> zt4KhOy380i#TOoDKICW>SmE(Z8gVA2b-;f^cyT6MzMVKzyi(K$D?If8<0ORVv{`I# zMlGGWY9BY9dFBiG{B6MsU-t*%_*=sYb$b>-L$zZbLFm{1?zP!f^u=#iW{i^%+WA=z zm?jIRfEH^*<~aoUgBS~N>6Ru_P&>la?TLm{7FLDQWCp`)*`omGFx>Dt3=iA$2`4q& z@QYEQ!e{)v;R|OuB6-lEul=+GfbV4St#CLoKm`k@LagpG_ZZ?2nE*j;{aUd(LE2#iq{ zof9u589n5Vj$r)m7tY7%0I6iD8c2_B0bh8&X{?7#o{b1Mh;YhA??`B}CorN4Z_tOw z*g6Q-EYJmWu)OK=D;YakGU4n_gkcW=>9Wxe!t?s<$9bQUgf!WD4+w9Vxj7}I3>5JU zhQZ;9rUcFr*&{HYR6I2;0%NSB1dpN5PieA<+D{JXTYSz4=nH&%i=QS>qH78_wC5Ji z6Ihz*a_UipA7M2X&Ks1>Y`Tm`ml1xSU6IsEDUI+0^|4i-r8A2WpsV_nUZhV_gNtJq z#HCih9T{GL;PAv7(ZrJM?X)jE2lubkWWG-IvroALtkfEe-t(DGcwxMwQybVJuG;el z7`1UB-cIkPliks=OF-E3y843QNf2A@Me7Peu-{UI*9-Cua#zC!qX+?QiPvj&V|!%E`2Y$$n%q};&2|$4gY%#!fTqC=iTr`x{xsz zB28*v10FZ9fstZ`x!q&XMYG|OWF`9cKJb3b<8()a1v700n2`Zr=|1pWi!r5x=myTx`}$( z8nG%`sN2lXi~x0;26M*JW$&S>w`(wGFe4g(^hTY5;p2py)3j{$kS>c5)?f4)*p$I; z1}fj34S{>T@XST<^rdQY2@Fxj_ zMS7=9gs+w`F4|Vc-3IX8%Q;4W zYRK28%@)SHKd_-bhUa%$4C&k*0@7MpzB}JL6rOgRyTJhD`Hk>&Ta!gkU&+sen4(TM zWA!^j+RE-m2-x+Z-+4-Gi1ioEaV8WJ#?#7y1;F>*j(IkHr_cvjP6W@C>rkisFCM!K z?C}VnLToD4hbNhvFv9d77>GVbZbJC&(b(S?0eiLLHNYN5_+}5Y`&V1JcLE3>)P;Dh z1uuc{sz*Y`?z|QFC-+uz@GpV=?BP21Z4=;)B)uy%km~;mRZ4SK1DdnvwuewxjFl-L z)3_%#LaH3YYN(&{JgOl3~qd zfTZF!<8L4bZnKgHq&(_U0#8@a9W+A|=>Rp4LR|_-BcLs!884zK`J0O$70ej@fewx^ z21-0@eQW8A><45LkQqcZBPh(>=|C@%%X*{bY6?q$KJ3LeLultbQ07$!w;LwuDQP=6 zua)4b!IV5enuF!2;)CPt3{cd-0E->Pvy&O@#)z-fxGE-zbB(XIJM z${C0ZNN2!ybJ3v_llEoHyj)PmOVj&ExvEskk4r$gMp}<0)*hXBFN%Bu zzlyvB&RY@QEm5V6@yq8xeu|(qpnO-rA5`!8ehH$Z zPsC|8c9xYL|>9ErL-9|dB956;kSXz@DR)&8P?ocXg z4j79fEUo(vtCOGWEtRzfj7<@imds)G^>@V+tg>DL)&H1359-iN{s{1FG@-%8AUy7`+QT87*97m*a5{PzEU_%b z)BaA2og`WUY#&V+%}nn0Cqa;wVlcqVqY2aT^2L9^&k+PWdYJ`qel&q|G5**6d*(TW z`vIy{c|wZkv~Bx z*R&W7j8G7Qe)8Xs=U1r>w4TR6of*mDmoG5lPA3~30d^S2HzNHF<>FP^KSSAyB={^T=CyL!g6{mWjz?y(5pyX`>#O8qL34-0Aregf^E;#8OQ zb6~&AN@|W39XO+^Orle675I1Hg*J}BuAmK!P_^9sjrmKb>whq-~$nsqZws24c>IS!+H{o-4T{^Pf%8u;IC+yTFCdo_-}+oS;h3H{6WD9 zcR2iVm@!Ji=@d6we@eX~I2!d=MYjO0V{t0v>L)#wA2H581iBdkatdRei&@(>azi8T}q)AQ>sS#G588@n5u&jh%lo>q-f15KM-@jTZ!)i zcTFjLs8^{qVk&NML_Y)C8zra_jX3;9F(06v>%IFMaQR=sPEl2ZPBmN(b@;o+6ri1I zuFpfoO~o0l6^ceKlzK_b5p>Tg^mtF%71l=f=GDX&I) zE+z}ld8(Qwh`{$CB~|10o60{D^DAB%D1Rilb4%lEnH>FVr2oXMxyy-k4LK{R(?us6SvoC0B)Dk z_~(?QTkIq>D@|ksBFrf*QsgnrNohdr*hWsI<%qDQv`AW<=Q^pURoqi zdv2M=#umA4`cFithH=$7I*2?-I@!BE_5rug$UuZ1rA5*{W`NAS0yTO`?5YbbX8{=l z^882y)mP+4>%ai1@F-#}kL7!4YAzrTAjVUr#flg;N1oxWbyMuLhuv2lA0UR+ddjuO zoE%w&dz$~n*hld&Ywt{a82y!`4HmA`@gIp@jGXHrwFX#RZ{v)I)Mj4BF;L_x3;)Nl zSKg0Kw+DEG$h83$%K(Lc&%xT)v3aAhy%E()CWCRUClLgG2G@T&_Txt!!V-Y@MH3!F zg8tuPD9H}kJ9USOLy%efv z>VR_97CO|&L3<%W^)ld=P5GCXn_ku7e+2HyQuuBzCYRfbnxkrq#VxBkPRG{K86Jqf z**~w`NsOhH+8nel5o&aXmAbfGw;m341ZXoN)N?Yd{1xTmhdKPaz+F=c9~o9^LAkg3 zI@D)CI~1WtXE<>IGQ6YQtlf#>i%*aT{Tp~BXufHM-As>SoufFac7e1 z;$m57qod1YIKG>twV;-l;bXEm3l8|>m$_Y3@g9xFqE}se#3`Tu0r`?>#(KfA5S~Qc z*9+P&=XNrJ_M7K|84B8ObKX!x^_wi_i~8kwRZ+hcGv8u-eK<4MAc{^raRpudmRx+* z;vHnLe!FKB2?lhUseWt5xlA?yuaB>ioC5eS&IC%8$n62kt(1}_2>`0&GzKP9`0l2D zw+n*!z$YRK|6#Q)@w@TESs=b=tKaMKo<85(#QCSGLn1gnJBGJt_4_@N?%>ma&57U_ zkLvEMMYAjPvm9dT1@8kViO$9$Bp@kQokT$AUt9TnDHCkTOlMt8GtpU0^Kk)?Ne;4Z z3_O#~qYG*{bMHBPjpI#Zr>y^jNG_jHk#zVPS2dCM{9ip24L<{?vrJbz*(Ymldu^Utja}3O_)ZLv_trYIgV$`i7Zru+QI_ zTA1=Ij4bpIqh154i-X~Xi1`0V z`wlRximcmP_uS@oOVfQDZqpaK=|n>}NrHeN1`s5JL_t6hkem?|5Cs%5U;=Z-tYcyv zbB^dJI_fxv8OPBX(~Jpq#x&`zwe|_Oga3Qq|N8sRt+3bLRlBNAojRw^S>0^Q{_U7N zCsB1dRZsl~>glz=AW>C;-fDK5B`-=;C0O8APM%)-%Mw*PY58ec@*^M{ zoh^Tx_Paj}E2`f-$d+cycd-7wMg{WIAv-5qK7{Sr=X#*bf5`60mY>Y>`+Xb8pMz{~ zw)`E+2OJd0KZ5M@NZ#8Wh9zpJLr*|0@qsbgv;c?SNu0rA$GASM!C|lYJ>a>T5W&%s zKx5V<_^(4VjCSq9R_?s}WMssz$4yx0d(TTC%6Gau-^V+rINyrsd_Ug|KJ=4Y?M5t& z#JcvB{v(ft`cFjqPjbYV{!@INSZd4*Be9vhV@-5Jdjy(9X^M6DlWD5v3NUH zsLQY8XTf+oR-?;{@oO1p?Yg`azXITqyc@p<&l5g|AvX?)DMXb@f0BFWcmUpyZ$!<%Az&4R>#_lBR|4>1yaxAz z9jUVu!pjM;8ccEmd=_6l8V^2c;a3no5d!R09Xy9;Is4)_tn$sg1H}6w3N;nr`}lWv z`euHDu-UMnoWKk>7`pr`emYim@~0Aru0+Y7qORsOAANU;dAmCJg$)H_LS)NF6|rp+ z-u{@SRq>@jtZQT|wH2sb@6T9Ong2js)5zA~i-5}a9>pk@tp|a4wvny#E_JakDeoJs z&e%WhJs>^`QPGGwwAC556b{Ewn1gZ60(vA`!$5|Es3uXxsO8#kFJ}B6u$g?o!jZRi zWHjSRI)5w-T@~&PR_>UqoIQ)9~w)~MdaH(&r7Z8UMrFIVL<&V7o zoEeL;f8133%nDIilU}`%$B~jf^4Q8f5*I)(Ls3nF-{ zaqJxx76Cs1_X=lUi0XFTrv<_nkk6TW$I;06hH)6+>(RLWBXJzx9-G%T7q-er;i=8k zIAYzufnoUwv^!pyw=@HESgnkt`MY z<7j1jXk|=fWsC}2=z8G7=&p3S_T3NQqF!K#Lk7>rIg7y!d5c~djKvl@u0a#eE9ree z=mnjWLFl3uSnNT_e7L|h>k{`5T+(uWWb1k^g(-FEtXaqV8HmnBRF#;u7mFFM9Dq(Z z)Vz$KdAZ7&#fN>~!N?dENZAV@1a#Y2_qB1=eLjSX7UJz)WN;x7n{^4Az*~dtO@SUG zu*y${W=+SBw-Xsx2U12LGY!d(}e#jj|*-$MLp0Fi+# z$TCvFkT~W?APR8Jk!y^&EL4VXNzUR2S6&rFJp-HyEMhX2;kQ<^_&JX^1ZjRsCsQgA zEjc?@w2Yat48P}@#mAc7GNji9Kx?pBd^OG6hRhxH1=fP0T&%7zYpFsuzyNBRMHQCqvD=%0y1= z+T&$=kFuVD>Kaz23buX#-o4<~UXS#f5Ui@3hL;@fLaP5^SXAS$CUF>SXSj+!fooki zD>exkYjCJN7|CkdISVj+murZ{GF%p)I0S%KQRRUhKx+u2JCVK%$2yupo!5T}VFiR6 z79rzH6?+ob%JGcEO99mpN6{es=LeuJYmCe%vc&ZOYAB8oK;8?~(~Xg%iL7zs zfSQM63y|*t^?76DQX+f0l|Y?{;~^k(vEXTqqki+9at@J)y3IhHf#Yi+djU1DG4c)~ zN4X1tx)evJ!(D6!P>UNQ_YyhP?E>l+9J7Jk2Gm83kefJ3?gr#*9G3(3FF@8^jZAdb zX7@C5-^1~1AK{PzTG2(Q#$3Go|cr3&BXfu414gb96CES3xd2S5OWX^~D;_FgO z&mW?mf5MvLbfP4OWj))cGZ!GnZYQ*;{UH^nGK ztSN}tsHV7uWwR+RA}VZ(v(ywPpc&qVp{AN*)jkN+411v&{9!OI=k>(JKe`2TCbDjW<<8aO6Yu`Y+Za8ZE0wSXk!5_*#iFy_BZ8uxl?*siee7v|AfF+Z8BD`>$0GxGk zB3NB2{JJDo)v+#*6H?`uy>H_-e7?3i=Bo95$6YYA&Ed3ZuMZ%;Lh|?{h_`f$5gh5C zph{_c*;s?a)y9)3_#BtOGNAj~A0e6mkdNvI#BicI$GZcymY`E07VbjgRt;yBy4(s( z*RXl4Ii^5y36&4B=D3-PY>wYh5q~Fr&Iz#ZJ~TjTe_Udby$z+jf}`H$=v>zZ?dAGX z02cREd{cX_$A%us+2kxO-%7i|H3;0$wOp)C8mTfeI|t%&JepUdlGtCMUvyOV<#@j4 zof5Y8{5>o~(K&NfUO68b;kx`=sIh(@V1>B_W;?^gG@QumXb+vV?hC8ex*rtgp67O< z9)|&OzDoe>?bx;H0!==r!ODZIWBK?gXid&N&%vP0Jrr)kf%EN7Xz6^T)aIU0>Ys2O zN6|mcJ!e7beOL|Vo}$rcXU;tX5wR2QCOkmRJq8dv;T93Wxo0~fcEa5Q#KSne@flW) zC*0#i@r3&=BL3XNe*<$h4*!HJ90LgFo}P%T4}?1DCL%|F=K2+=WF>0g%12N2U0(o% zxlZBL<~p~gr7j{wgZDj;>b@!y;0>z6$oubqarr10LMK z(s{+9)Lajxja`2eN|$B1{s$<@^_n9C*WW~cJ{Y+^1_Jf^3PjBHzX0(W4sSg7p5^*= zL^W`oJ%0DkxgH4B>-R%je`jgHzlTb`D%a)qi;$Yz6nuaKZePKY={BY2b|`J^_J>f~ zm*w`qSX~bGF5?2X`=O?(nc-lc1cBT>0TFY15D+79c;j<$mdfqhh-%>WRzNtWo9yvG zD7PPncHlSfC9AsQs){POu9}Qqmv}3_wBqzXKfV^zB`-buV0>;*{5L|#uR={uce+QM zuY1IB`k(Jl|GBY~?%+hWYb8|P!ZBn#{tXe-{(z(2gt=-U%HH8JoRuHo6uApX+-mY3 z^?fLk#(EF3euUz>qmhZSVmn3eU3}Z#N|b?h6Y0H+e_<(oAlebvQ|%f2w=lN4<1b+Q z5m$`79Nju)u0c5$x&tw1W?pZ@=n;rsXqT=sy1 z%b!zl#TN>$>aa^m-uE4cq41rHph;K9`j9vWFd$is6KJaU?XM{iW{*mDXV z|3<+R1%*UD)lbK)=dRPfS71$);jc=GH_t10^-~3}AUNQ!~9fU$2w&yq7RsT#}TSIalt&P|NWK-P4M};g2a8{DOiZzf~}F4#q}~H*A@L z;p-HPI8DK*{S=HYRxqYg!PqVe#=WXwJYQ4J@g}|}W0U@>VDjG;9Q9uXQ^{zV;~jmu zf@x%M%JHV(t>Box3T6&cFl)4eW2Y#X^9KcUpF@y4bqt1l@BKUsX+AxHZ;5^$Qb|%o z=Un@4YY0RUo!odUGOl_Cj(ehr_RgLQd``0iSK>6xY1Z%Mwha3Jl|gd;jin40ysco# zAvhg#l1pbOShhyN@^cidxKY8XR~4-JLcs|+EIqltTET|H6r40$!O5p7IOS#qo9|Vy zw+_(N+v=g3KZXzHJu!e^%NxgozWxd<7%Ds=X3h5T2h{pfuajStZcoXWbkg~#e5yf9hEYK;j zK&NiLnP(eWpz{WO0=Xv^XiqHAMPz~AZ&bUXfZ$=yCm5v7->9`zESD_M`9pU$gFEq` z>`eCjGdZC%Ij2Qu(Bj5&T6C$#NKc6c+Izk;M|1K9>)-pWf1k4cecJl>8SCHYtbg~g ze_M(LIw=t()%Kr01DgwL&epvG>$;khJyF6hTmT2j!zFMB0P!so)C9g&q0;d4=u`ve!^d=fqvwRD^j z(7X9Z4#aIwiQn0Yd=fqvW&C7rJ_(o=?JOJcDd0Q={|w`byDA_c+Ee2%q!$ zu1V1-KRGp@gwMFyGU<$b5tF-GhDjh<{H!sjngb6wq9y}_$nTM|CEn(Y`b%}tB&c|Hm$OQffa zK-i9i&*`HnZb!oB^f8pi%1QW~p6m~bauPnLXLeTQ60r)FaRL&RRP$m<5+mAI5qDpZT`IlaYkb>+CIDkK8=i*W@@e;il-Ugq-$svMrxB79DJ-ruRk zpF;gmHNgFZT%0c?e6AMZbNcUQjEl5FN)1^p!sqmU9+lky3iaa`HwYQUL|2ROIXyfs z9M^Wz52{PT=k$>#^`#_yPJd#xx>U_?%vBI4&%$X&Qj5MfjYaufgQH62>1G>4l)!ERpaz zeX&`Z8Cp^-yI7j87U6UHA68i|UF$V537^ydG$9wX5<-cD&*`JBUAV%vy2^OabR>LE zpK1`Ueyw)`DG8s`Ej^7AE{Y2ov-YbN;d6Snsd6p{Zj^!+B}ioKqYgwN>})(yI( z>PI8k?|7a`9Ypw?zD%bC*ZEdcHWXwed`|Du(B?m8Se<{$w>H|zCbp4 zn^4bYb4>f`AK6)s_YPTl)gpXOPx2(ZJX8!jwvc%kY}X;(|g>{Db|8+jbDFocss}FyBz#V9G68RNeL<}VpVK0IW+yt{{aWQ|7Gzl@d`=tT zvjDs=j=YQ2itsrt!e_~O!(7h*nV!=|_$&Z#rLzpwiRn3QgwFzSg&kQ4+K+_K=@;DF z>^$Cm8^Z5<5mOK&$eNV#YGzg!mzPkxTr}kL(xYnPY-3m(w5WhR>fNX@YpW=XLy#-qNOhh#7o!2T8r>mVp4HS zVqz>1af8#^2%mMfP9We)n%56+F3=Su8E9>U&&+Yl0~BQZE~>Q=K2ybA6vzq*4ay zEW&5y7&6u^!GgObE`fz&MynL9^0V(`Ht|XRZ@iKYTyH1&Pw`4RKFa7CoRuZD?3E<{ z4PHrC4zeWw|6NH>-V!GHkMBx)an+vWf4nQ{&829P|LU$}0Eb(W|KqOYaM|VmxGNbf zyPL}q9U{Ab9*XD)+2#MZD;XoZ{2zBEV`Z2BiBgt-MB-#6W9-jRqM)1a>dk4&viBWcs5%YS8syacE?CRoJY=0aDPXgu& ziHP+SNp`{~$sPhJdAJP$AxW|mK1ud$2o^@dULwg(h$Ne)Ja;ODXA!W6_G3oRotWyb zK;CtcqMtv_-GjWx!~DY6SRY?_jQb4)e~5%da4-|*LL}LIjNpp! z(+-F4uFU%&kz@w{BwJ_D70A7gAZwStBFRpOB>M|wyZa+q>_EJ)|96~ORf)aGEoQV^;;kUsuX-rc zmTRzYDJw(kR3-j{X#f5Hi6=6yMc)fCu_gJ5PmBJX6_R{qxy1l3B9bJ@ZgDVIIR}Ug zyTuXikP=X-;wZQlYV10aWVaaRCL?clm|u7kq!5xMyTxd?8iGxs&~KjJ;=gVolI+$H zy36o$BT>6)x{&ok6Okmlg-Eii2zm@Zzm7nc8|X`PaSM@T%hI0#_?945vXCc7;ScZ` zT|$!V7Dket3*9z2e3X_=grZPV!L$%bc5|3Gz#O+WkX0$4Ce-Q1|4gKhv&zOQm zaC6GAB6jM;=Cjm^dpPM3Q7TU*_5(*)hy7 zJO)t+Ns`_Cct?8bA)(Ok!~rD9W}U+bs>x@8-4b(wEoQX!0jlil2d~7K>X+%uhsNbI zcHz;|L2Pp_=1G#B(U=2OX*o%Z>i4Z zB+1T9v{aXJl4NHlTdHe0NwPCjEY+?2DqNs5GcC1$`H{1cnq{f(Yn#iOD-%deAwT5}Z5qJuC}K2lxqoDpz{g--&gHp1KW*fhHM1-f0>NBY3z}Cf;f8 z7?hKDy6iXtFcc0W?{wKbOC@4S@=lk{XVK6R?=-g;OlPUxjrlsuECn6%PM0men>wj7 z@lNwutm&+y%V9a|EtMNfl6Sgn!(X7&Hs?A-KaRJDPE~^6qYY$jxSgR%#AcFekxiF1 zv*r3^3i$(#=?Df@i)^~A#O|iJ`C(mAEwbsdGP?~qCoBI%^h#Nk-5YUxB*2qwy6oFH zFPx71B~cx;?6#j02x5op;d5D$$5wURRIxF@+T-?uWYc8_#x+2=)e;myvgxu`9-Gy1 z@1>CKs2?biY`ScQJp<#8jFf`){-4=53+!f|`!sg16FyObI?1NXW|=y-a2g^8i)^|K zWYgT)(L$r4S2ZG=F574=HdtiSWgwg8=8tA}4E;~BbSk?^H?AKtTUB5T-9djlh-|v- zL3-x6PZS~S=A(nirpq4HeJ6L28Um_CHeL3zbvHMcgn)}An=V^yjlkU|yZz=}QrJwV z0WsHagb<;7w`!41m$mV@iE*b+!HeGh7?&GgMl59H37j4_MrTUNu4#UIh`w#AmM-%x)kKRaCl1&#q#waI$l1&#q{tKlN zEv{DF{U(}hpR^{j;Zg$>Uy2L-@LHeFa^Hn^V{*$7yL5N_C-G-ppJo@WJz^AtIYD@1{1b7TI*+Mr#gk zXR0~Svm~1?1lctAHdT4_DaoeG$4QZUoxy2NvgyKKDVuwr0h(mfh4(3&d!bPaznbr+I*4q# z@O910++{Vd&@Jf1!bhx0xb2$N?;S)oUEV5{F}5-!1WHWNZ1=sUOmb z)RMl3;Hu7bernCDSd|?y7;C;%#xdKup_Pk~Ds$AuIq4-yHk~@2%eN%glBpB^z$n*} zsS`hDlym{94cy;Ml59G)aXq6Xn@*j~z2W3EMo-y}=&*BVU}85rYrh$ z-w3M?l1*0(;phL(4HwyKN@UX~F{ii4rc)xD*4L=NBN@UZL*Fn}j zlJ^nWbjrx4hai6xWuw`AxFaChbjrx4k4651Y#GU>Q${wu5&36^GP{2D7TI)4WYZc2 z*8y;A2tviSZ-W7mO-ue1WUq&E?WEgwdY#CoD~xPfHTwZDyZ_NmkT%`>h-^A#WYaCs zv~6&hBW7lV$fhfNvgz)S4rqYrEwbs9$fi}LNdQa_L9vmJWYZN!HZ8!aP-ykljaF=w z$fi?9Hcgx-I_{eY9-x->5k@v`h$kW4O9UA~>}>)VYL8A#8QC;F_uMCde3@1Ul-D$iNX6^)#|mMmBATE|B($5TivloeIdNM?f-;QdIK}QYg z#!%lnLX-1okxi!pvgr$fxvc?C9VYN7kxi$JY}yPz3-IrnP(UU43UkWHra6p3%?#YX zBCJe~aqTg!r2?|)3Y>R#aiP?PuXtra56H)_0E}#UI02tR_!R**lTH*(PRhupWg!oDXDJ;1{N)3T zY+4pNL)eo5voJwq(FJQp2@x2RB%4kd*|gSFWaK`LfM7)N zi~N+4P50t}AtU!~A;8L*AWG`gU~iy@@B4^)28iDf6*UNGH1Kg%%E+c=>Qeyz-pCZW zq*F#VEmH;iV-mm-Hi-a6HZ3#VA?!;)P-SvSr;Kb`7REt1CEJ1kMm8-As~}t#S+I&4 z*|ZGofb8nfK;Sc32vSBity$p#AfAa(n)@e+Mml9=(?b0bh`&ZCf3}h>Bbye=>yAki zhu?nwY$cSDO$*fth&~a@pNB}zoHDX$p^gM%dW7=pC6tj(3$+%A?e$U7H3tJlcq5w@ z{w84WkMQATCx9B+w4kp7_HKP>fHJaap}qqm*&}p0I*0tSjci)bD!{r$Q29MVWYa01 zYw|2<5koP)0T_)cHVM8KL}Zf>1^_E!2HLycD78U$fz^ z@J2Q*{71lk7vZzpPf#P97Btlp%K;qzVDN{GP)0T_R9_&5MX2od6V%A21)UApvIy$8 zAL*4-KH2nXkX{}kv=)pkjt~`d$|sw?8@MMMVEv&elh2B5S_S_eu+Ji>Ec&f3sF6(z znuDFGN*q};NMWN!m6DN7OX(mejBB8j-Lk?P*|hMBfjy}SJo-yeBbyfVV!&>10F7G2 z#~azSuHDZ8`(}h!3;M&54ALnho0jQ)fH~ZrX1hw$sD+?LHZ7~AfRTpVhiZB5ql|1? zs6jwXsE;c2q2x498QHYTUJ4j*jT@G&wnhbnH?nEruLAbbpTpOiFr;Z@)6#qsT3iH*u@J2Q*`~YB&Y6_p-RZ=ptX(_FQ!nR0BU8Ns?XbNv+ z)57lp_K~LWjXW{3X({~<3ZMO)Qqa&wHZ43~`KiQ_)zj)jYh!;Tsb)qtEv18?Fu5tE z=r+vnQX`v|(h4Y?-IS8t$!=&Po0igzPuXtriu65VE|8y6x8$4k6Lb&$fi?9Hf>sKp>aV|T2ZHt71?yk z$foU4#{ANj9DG z$);<7BMrCTD)a#jPO|BgkxjGOZX^)nLyG{AY&vCR(*i7kaCJ6-WYZ}ln=a!*?i>g& z%m(l!sg#jTtI~Hu$QNDxN{6kbRzZov8`-q*e+2f+2p>-A0kkUlKAs5)n%j?Cpp8uj zP$Qcbly932iJpfdqm5ka#nAgGZ|3wjn{*GAArz6oz+)51Rl?2Ap{ zQDH%iY+BF{0sBV;&8{$Mo>N9PEodPg-B;r9TR6MIf*RShpa%gqE`m0yu<%AUE&O6& zPig{>3JYpv(}G?M*v%0%yTYV-P8r#>pict!S_I9mu%JdZE$C-}IXub!xzQuMkxdI< z3T)RV@Tjn$Mm8lWdSY+Cq9z^?f@yv^XW5tL+P)6zT-T31Ax zY`_3zWYa?33&e{NDymO5-pHnf{}9;!{v6(>t^p*QW}^-u*)(6c)jK@g^7$V`_;&MD z#2u>21NahCcalw4_PT*3gA8?yQvh}G%dRVC>G-=SV{|!^Eq3k$fob6e1By3iRAVl*(yagE%{i;CP(svK)%RE z4MMcf3Ye)%tOll-(N3EncBRL?h>Sx?HeI?P`wg1K{u?y!-U`VQU$Sd95=*mQr{T`M zUZ-Is*6DOJ*$#Uk|7(+ceL^M~iFMj;Cb^mRzc$Ht2xO9xSOq(VTX9GE1Enf)22#Zw zGo7x-;BZyD`PF`sWU5v7@;gnvj97IaS2@~-th%4Cv<>(KZNt1U661rR3@C4UM} zGOzipsX8WhR~2?K5Z6Vvd=xo0tBu`NB|ZYg^NnngW3$@WUCn5mX0@@qvVUAR{PYe{(TEv9j!n*d;TQ^YaI&+2Zi#u&E9M}=J9ms)uKjLd zMkm0g@Q#Kf@3%vuk;lQEJ@PKg8hLkRjl3J`jl6eY^L-ozG*xfpeT&@xhLXZ}Adf~~ zK31@IL+IKJ#>|JK;6v$$BaiH^j}UMWgoCmH{>US{>sQp74&fXEtOnu8y8(c0w6GDv zGebZyWHhk$#mVj}GuH!gTZoEA-i7OZGtWTyn-CC~@kbunUFFYTf%pee@~7}0=Cwca z$nL7b3Xxrk!|EKM{E^qv^Goal#2}*T+44so*5zMzyD;$4S-GUT7vso@;0`? zaWpv{8F8^)fbk1M9<2R*lh|7Z z@u>ks2C^X2+}XE->!rm{zW`}p4oGW2ys`kqEB^t3%pNFBpCPg4;T?$?Q)hxTe9FIJ zyoA2ZpWrZzr?~|LRcG+aErylQe+I`^NWGzfjcT(In|_MGzQx$gZ}G&a@HW1C=G;uu z(iHx}62-A3e7g&kDqaXbW<847vAs*P2xn#wLMq^!nez)=%|$me_uq(pfFao1&E-F; z@X2QGScEe=b`_lR$!2!%HnJJGpugSoK_7e~KvfVVI*~mn=G})+$Yb7M{5tPLyfhd0 zK8DouI@}42m&9*QEJ22v&aouwo3mvh9BD>|npQoN%?>YYj_Y2tb9e2>;QY=?U2wR9 z9mguzdA@=R?@(~j8wxJ|TEQiSXyjzGOS>t!><9&yPgHQlNeZsKUcpt*DY*I@1=kef z)JitnRjc6okqT~DsNlxa72JG_g4=$r;EsI??rK>;z1`gv+%sCiuhuBI_W}j?-J#(A z7Zg13p@Iivh17fKZ3PeSQ}9SpikXl0Qt%i*)=M^fe6xZlu2S&S6AGSrSHZLYQSe+P z7Q)G9dk$Cd{9FYuoTT8_S1Wk&2?Z~GpkS}pk_s=EDR`xig5OM5@ahQ)Ub{rW>klBv zZML8Lqr&FyCx!X0tQGUyI@Tw*Sv$wZ$!%8Y*etot+B-H#ZnIinug=%&B)y!M2BORJ z$WW7aWv5(JB{^symMF>O;ru=)nH+qSf+74UCz%|&Pr1DIrT)Md&X zeS?BAcPSYAkb-eD1sOkF!NjG?oOGgs$^4urnLLXBJT;k|S|-TRwF;*7QZW4x1;;!q z$V`5+lT6O~y@F#uQZQ$cAanUC&3xWbx8EW#bU5u$IM+`N2 z8?hA3yJ|EX&k;jS&e?O(9?AU<{7+kyv0p#Fjh)=D|A`Em&p)!9!2%L}B%3e!RKe0D z&i-WcWfcmRAF5!*Q3_U_s$k8v3Ql-H!TL88Z1`HiNv$fWesUiLr%Y9_dA@=z8x)*+ zm4eeAQ?T_t1>3$;a7Lzz>aRSYy1cdqXK}Lm8|N$dT_4HbnxNqAI~2ULSi$eNEBM0; z3O+RTPfg)7Q~2DFUl{T$Q{QI_-&#TcP(k@KZ{xtppLK0DgW11OFy~nXbN`^=INtUp z^XD~h&tQJFf&~XDSa^(rMVk~XyGp_GXB4dbNWrRP4fR&@eY#}+nqdmo@*i9#^G{f+ z;KZ#8He9A)u_XfB4DZ*%b0p%`jB zFx0ddfdPRvl`9}ajhAxEaaJK+D25sj3^lg{&uKn&AxyX;%8M>X6rYanfv$6VA$%tU zq&Vmt$W&N_b039*q8yA~{G~;0lNPm2`sSMf$|JQ+i$OQSXwDY!xVan=+~kPhrr3So z)x`=XY=yQvycxcm;rBsjBUQwoSc&Tjs&Q{Y9@TYIk>MRY|Bp|Gckui)GsDku=xEV< z)T_We9_S4=y?bEz|EgCzHqxs#y}$im^r&LxwINYY;i#i=!E-LwhF`j+-Z;)uvHeKY zQ#7=cY-70cOWu(T0}i*5%uJVs3%86Jvk!k zDQypQqWcS&jNGSGTrmkk65{ow5G3GuEGW#`@FFSby3X>kstE`crW#YSPYFe=2y9 zsGNtYy29c6k@}}qKc4Yw6_pUf>F^-pmdKbc=Z>Yw7aelk@+>Yw6LKbbBd^-pn`pUf1H`lq;^ zpDZgN^-poRpR6n(^-po7pR6e$^-pn?pR6k&^-poNpX^#d>Yw5oHwSYUsDBDR+l6FD zw@}I61*HBduJb+WSMWD_)YVTOTtMod;{DylxN^kX4=f<{PjN3-E%%2MJX43{0q#&G zhZd0fr?|IUF3ZCTNc~gX&z+*=@B&i*6c2K{WNLH)seg(`y3x3bf%>OlCzGT6~V)O{8e+o$bQ#{VE^TGmB{}fMfTdOHuihsn1YNZFU zFY`$K)4Fau^xBL1hx3M(4JB`IMAVS_r)0KcyhCnA)IWa*xMLzSD@r2feqO>r%$ ze=^5V8mlAqPiC?|DC$W4lbQJ-B>W1b6U#_o4(d!bFP2B@pUkW~AkHK8Pi8TN6;$q$ z=)foyN<{sW+2XitbzH65=~E)=pUlT`XP~= zbEFBmlr|wPb%iRae=_S#$`y8fDXD)lpIGg<@V1I|6ZKE#3(GGN^-ty;4FCigI5{DF}t5mcBZQvYNwHcOv}mK4h_ zmZnQY{ge5JRhIVz^_rN}Kbe1;kar3aLW$HrnWL>;c4D1gU>Aiwwavz9Ia2koqTczX^FOR8Pnq(aZ|#2CY-{qY>lNd1$!KsI^*RnI1=e=Yp~J^RBLr)IV*`V101usU!7I zn=>tysH>_)>MTp;){*+B&Doa9uOszOo9&iL)sgzA%{i7z*S&x>Q=4-wm8qNC6{+(q zRaQsppEl=PsJ6jQtUV}TuBEb5=k zzt#M_|BZ@+52XIdJmD6yE)Ru5#?T|IK#8b-GJD(#LU_k)`ht{*`X^JOY1i>SI;*Na zg492m*Bl$s@fJH$52i~}|76~DJ&54lcSA(6sDCm~$phY(XBEOc)RELbnKNtx<1M>R zedLq+Cv&*v^Bz9(-I}^Y)IXV_<^XT+8`~!JPiB-Mc<0|3LF%8(k%r(y0Ym7d^y^3J zpUhEqPV;$z>cNY_2dg01WCA`x@CDsP{gV;(4?EHEv4T~eW@9}>{gW~39|8ElA@VNP zUDQ7rQU6HJClU1w@I9c6QU3_QXB1fmdWiZbW7IzaaLpcB2-=U-KbaTYY<3o-gjDp^I1nE4EmnbKbcS5fmG*xOhZJ^saW>7wx4B+v2@_e7;V4M`i0a#ZNKCx z)Jtzbwl(UXjWj`QQ8|9F*a!7bTT%aTA?(P$BS|0z^-o(-|496BeQ^(M4!1SxADyl5 z6VQp~^~2j0bOm4eZfn#(%yIt;P>}I0m9|FxLlsftM9Nl;9*)#MZH@Y;J5j^22quGD$KSC{U62*5i+Zy$cP#1+LR<39yDhFGn{%LE}Kg@BviRyzAAtUuqTciG& zOxa$_)Sf*={nOT{f7E1O1bU`?fT(}k8ugEqdyD#~tx^9d$B?l;2^QQZQG-G&8115H z7e9Ldvx(0m^-pOBuDA0@{ZrcU2u4Z$Q(DVj$s_eoX;%)iJW~IZ_T)`w9;tsydsQ<^ z>YviyT#DwA`loaNhg%-0e@YLR-5%EYvgvvPYvghW%mPOC&@0Ue@dsz?&Td3oh@Ue{wbZKD5-x+kCWYj#4eQG%ZObrW2F8mU7;wc ze@a)$E~$S?Pmu*u|CDYK;IcYIx69b2jGjwuJEQ(-XVgD^`2a1EJA$_z2a@_Hca+_M z#Jql@{>dfv&u-kVKgwHn@|w6JB4YhT{gdlc|GWQvc-o)IVQA@LeQ4NYp>M zqW+;N{5!M~Ow>41lW0FSz)GI#_{G>z-Uu|Ey&Nt_9%s2qg19NYp<9Jqy6A5lEH>i25h@ME3y%Uxq^e zq0k|EnJ(9;e>@aah{JDEnnXoN{gW%|ADuyU$n8#$wacNR{>c^f&q>I3Ln2x1ummp3 zXyh)5X~?Z$v`=DQ5FJ>JLD)wC`|Xn0LK%2;pm7eOgZh$6-?i*pg(pRMeBq*Hf6fYd z+|O<~fQyJcQvb9(n5&!tqWEcfgnJ39uj5E{gBrVz)ITkUxxXOqt1!Rl07xMu^-s&u zcmRYaUN}t2Z=Qq2>eEuxKQ}_tajU2oQHRoW5$lB}BK1#8QUBac&?o@7_vC|W4fG{u zh?b)MktLFwY#~UMEaJ&gv<=!IK_T@|OQZg|1c+NAl$K3|qELRA(^Awwd{w|b2^9ai zoD~Wyr2c7X)IaYc|BD7zRI5Wo{nOH@f8wZT0S>=LEXyA4@d~DAe2k#S81&J7aF@in zD7#OhKh!E1?UEQ0M0?IbKf2V6kC4%VGCtE(C#Ghp6ZwKdYOcCgpKBk-Dh&|DPil#~ z0EtU+q^QqMB=t{fnY$Iqd&B&q&k%)>)IX`?-E&C29t!HU@il%c z7_D5W%D#TMsDH}(@@ahCj9vKN;2^dG7xSe4Dbtw4BZE3p|C9|fS#BMvf69hgD!-1@ zKV`!$m8zRcDPY=lHp)_Eb)^0&8*Qn|x+~@*HO5jkb=z-5YAn6L zV!n>lKV?T+s#6`Qf6B&Ns&gHwf669Ws!QGV8<3i8sjhXT{wbScscv2hOLea!^-tLxOZBKD^-tMxmg-qY>YuXtmg-eU>YuWOmO7x0)IVh_EY-V?)IVh_ zE!780ds6?DolKt`H#)ScvWKyQMg3E@c`LGAmjpLO@<{#DuAi`~PD$kd~# zl2~32DqTL}ExM2>A3X?OK1LO3kKv;&(;h4ByuoaRBd-7=kGx0~m8?(CLy~CJ$^$#% z`ahJsNRd1?f zbDVh|8%AEFoOzZ?#PZ0Clrx`2Lr1(w+|)9irK~jC)pV9w3OeLP%2_^*I;kA-BJt6; z>8#^;2zAz5DmRvQ;F-|ba2{|qIoBcjar_m;yCmMg?{L!!0&}fEWM2UEja!Tx0lUr^!PDhFtDW^>LXdd_AM%AFrk-mLJPJ2Yb zJISz_P6J}D-v}W>_qQdYN6KmAX^V#2J=&eIEt(S1Bjt3q`$}#CS(g=y9x3N_4q?Yl zp~&CBoB5dQa^B(+*>St5F@W?)Id|$=2RD);0NRT5NIAQ8r~6@jS%>^8(Id6MiCedL z3-(kpwtEn(BRx`88$RylgYi7lBUQDf`dHE<72kij=#h#aJ&LNNM=E}dQBIDeM=E}N zhEj>TB`{n3v`quK=)Vf&cS-OGe|B6?-nsjr>5j4t63V?O$gPd#eRn3d2gdP%V;-53 z(koc=F=9$egDL58q>A_h{o7DNv6zz5y5Dx(7B*ptn3B@{tqZwN9ORQJDLugQxp8dy z#bQcIe@iD^b(mcurlfQm8$;Y#4$P1#DP3x2rUdy#jG(LVTts97$VN~KnUd0fGZ(n! zt$dp@{CS2b1z$ zYPIJwq!ZqfZ*fX$MeVJbi3QVZfj@izQBU6%B=BSI))5{}Ml6O2;yLnuCdnYVn zluK{##5IiW!2Pkefg8+uWJ>Zj-p44JlDw1ojzS)plDt!XM0EVQ80z`n`QFTqmp_iz&$yQ<82@pM$}@I8ujFjGH7fC3#{>lKdmc zK9A&wh$+c4rX+`o=Hf`@4W#ZNVoLIiDXAUuYqDizO7e^;sXy|M2xWFDJ6KFfo|uv} z3T6U8)*0XU!D34C#FQlYDUh8X%Jnvfz0%P`OiAsHDM>ZE4=}r3f@ zHd#zbo-rj6=eg+s&LQ{*4$J^yOi6|~8PcRl4ndw^xShd0&;t{p|jZy z#+39EMxW>QK>Bhv;%Ur&o-rjE;!{Y;J>ysAC^02@0aH@5P8gOrtRko?nUXwXO5%w2 zTpgtSiI6ka5t^Kj5>t{FFeQxxW_|;lI!xfnuIH(+W=u(DcniQgn@~U{$du$6Qxb=< z=k5gVp$IFJQ(SvYYhJ*V^e)79aiP?Pz<>f18AmDai|%lBzogR#bQ1$;GCK zDai|%l8y)=dNqYV0VH5bS{On&qZIKcfCNlQ+d~LPgpB~dpnxgqt`H)Rz;Wx(l9A;_yeq(Ki1WQ&QnT z7FH-uBM(eT1A!YBVW*jZOi9y_J3o}z3G3^DDQO)fTO(;P%*K2vn367mnW*cOi3MK)9nG|^$=F1 z*7Q-vlqA&WK>QG)G?ILjF(nDr5|_hr9DXxt?E5HVN)oCc5JMuAJo8b;lqA$lAQnd` zdKjCoFStBoO5)_?wgRy|LjYsB0;~?x9f^=UV@i^Rkr0m0 zwjh8pCCS1P2v=uYAXAcegP4+3$#WpQFdIOoB+rtwu0Df)f8B-GHW0&fV#UGB)O>Ucc#*`#LPYC;E1NcDJGo~Z~CO~*} z1ehqMB+q9`S^>dk3hjy)o;bKt|1=+Ve5RyJ0J*+C37e;yjgg@Z9A36+m6kqi#MFZ_B5WlTvz^#WpeeN@)9X}Xw_ zJYz}{eh#q5NBHovgZ7tcV@eYAT)-}`4-HVplqA%zfOs}SMdy%j(3p}0eGjm|MNs)Y zQA|mm&y*CyW9)n!zR!O9ad+A?rX<!vXuU?2k})Mo>3b-&z-@DO8)Ubv@WzxRd@Zp3n!uxZ1vRE5K_>vV zumLn`5g%_%NxF8Q3haduUM=W%2kDPIV@i_gI{|w$~5dlYh!;TsbO3`hY-)6>?B&DuU7}k`M+{tceV@i_JY$$AON-1o;z$ar$lF}tm_+?W{ z(T${EJ!49e(o0bIpeZHIF_XoVE@t*q^z$JLx`9F+-$zn?Kj48>qdO>4MQ(94{ zP8Cy_mLYb#A58`m z^>T;jGbMch+!w^!0*gMN!O4{5ecWvGu~_Bd1aV0`BrL!YuI9*;n-MhX2p?)pNrLVJ%weC=Z#teHfmL!8dB&6^XenS_BWQL71U054L5Bi1 zBZ7t%sAt-kl7v42*fW~I!#9~WrX)eH1MHp%nq6UX6nVy!BR(K5{K31EiAk-B?*5PuvavJM}-A7rX)e{1?;&9n%%sL5(R%(0PEJ5J9smJdbz1#*}m;r;!T) zyDoxePY~oZ@{B1-+a-?x_Iw1TZzx+RV@eY010cSSP@%!#A(8OLlq7r+9#;3n;WtBl zyv^Xu3raGkBx#O<)|5z-Lo`4cQ<6}tfFP|*Bm3ESV@eYKI$$6DIlRp;|HJo^|AQ!2 z!M?#eH!xnow(pX#U+(SnN!V{G8dbtR654NHUQlyuy79rYc8_X$v+@U$DXFGkKd5Nq zi7)Qe9Kd(J4kS}jP5%j!Bs^_1)%2mxF`_}L0aMah5MF^JMXN5lJm4*_n>=U_bhkr# zPl&)S51-xCh$)Gd-Anj+o$^k!0C|7(Q;nFCmQwy1e!hw1GxZd$ModYPH-}nF9KL>Q zFh_8t1|iy~E3~^Lx&u?eXwOIRMB7y!cLp+sk}0WjLH0W}i~Vq<68OTUqk2joLZ1!ZtYvP~ACl0|H;a|v$cl6G0XTxM%IbPO^*Lr-t zDc(Ngjr%QLp^ESC@uPkGk27!F2By1v{FXo7zS0{va5vIDJU)bqx3BgJ9Sezn7I!b9 zl-F^jSPZ`Jao17sdE9-7%&$X%{}6ei+lh}6<6p24w$=ll3z2=x?g6NK9dIF6=m zZ`()xGd>NT3Uw0@cVwHnm~G&^T2w%QJrKT3fVn==tw6ow&AfaR=l%l0SD~RV zI_~~61bJk<>Ub}|z}8E_9q;4vS^L`^@8_$fnNMzw#h4dHVm-^G|48)_f&LSb{*#=H zO#dmqk193hg^}27-g_i!ACIpXhEcraI=q7SRGbh@cJUfksP@; zh)zV+s~3roYK?-6{o@AXXJm+qMogyF8Tf~>9kRwyn1i!|1@uXr1icClqArPTj9RY! zUdoKa0GrKQWsbbRj)+Dc2Y2?!BNbCH@}6bfA9)Ye8+l*B=65(!G*xfpUb5L{Lf#^%rPtp%Z9x1q9BVZhaQ?dd6$a`-h-bxz@z$ysW5nwe4M;Pc?ZIeLO@`~A9h?5)H@<$#ixMb^6AZ}=6 z%O83FITI5)gzho?JR72-xh@=M;p`XYV4$&pK8b%ouY!Z9OCkoZD=gQ3i%Z zj#qIvN>^m&}^A5_C|!lEh+5FN7O)`?!4d7E`+Hj-!$B z4dXCO5I%}W;yAt^wCLp|aHOGF&adba-APulywf#|(gd)Ak;uaPO$Zw(4Z#Kyws_ey ztD$l@u`o(*3vXYD9uuL*$mk+|B zW5Fi;cn2Wk&_K!vr2JZ80Y5VF#v@~XAeHVya*k=m7hAwj7`!zQpA|r4APcgR6fY!% zxdMp00~8}J3su2)#TM{u7w>6^UJr08u!zZ61wV9Iz;7wMkC6Un08xRfX3d(7&nlQ1 ztKi2J3;1xyD;SM$hjC=}^a8%1!f!XvTq1Prnu%Tta{ug_g7?FS({ka z@>X1FZQ>-l{1w({69J2t%vn1h@7Mkv@ntLfBl{e^u@|fO5;=Vme9ctvo01G?E!VUE zO(MHFQWbo4ZY7Cy*bP<4>4`&4qHZW+GFCyw6H2=PwSez|c_WdY8~_=Ct9b+AD&K+f z79wL)AZ5g1+~JgIFD{T+g$HDx#KmYDyT@8o-3(fH0~pfmpwHHTe}{Ro3R3PY;42v3 z(}=x;LlujOD9$Bf5v@`|<_%1ku<6zH<`)5r6_*wW3n9POk-g z+s-S4xK{vCkLtAXK4oUCg73tv;~0Ilmy6xl+r{3P;9|Fp!?wr6$jnT1vGva((hrdh zcO!BVPm*tebqC-$V>67b=lL-efY`=$Gx018$|t{uEN{o#D^7VAkrj|_qAz2ia{(ak zob{~vWys&`c&bt`9*5UD{sk@aOr>;-YmM12l-9ZRoW>~u;i04Flc04gOhR*gN2DKy zY(0H`7m-bzX{W=fCyCg1n)?vxP3zymZ_XqaJ81(V$3eUrM`HYBdc74{2ST>~d_+bg z65HyoL-ayG*gT1er@8x)-gLUV9f7xU^80ocngxLVC(@0-@hSLeuSJN`V>JN|q&}uL|AghGgV0c_Q z)gK-YA)?`NED-&O*tede<1GR>Kz>9-17sNhYjGsTpTM#?K+2Ey2S{H;`~mVjzDN8W zj>N?E93OqA0m2dT4kFuJAU%a6iD2szj>1H`r|;D>lAh|*W;AZbxO_kP}+p+`$Oy1 zEZ6_cN^??39OJt_XMl@+8oAyL`Evb8MCAGs0FK9z7{8Qd)AdscYT)_~K&~RJN!J6Z z^*Yq`chZNr1|5ScZpGpH&X^4Q#W*`}r~N!cev8Ov$4Qu|6LENp^1fv?ow>&hkgn&tU@IapLkdV@WacNgVKvh0 zdBJ~{a*ow*s2ZiQV=-3yenmqwk@Xf0O+ci279QlNI#&Ue0m?ffZ#}D{vRI`_fSju; z5z>Q@@7>FdszjJyrC$JdHx94KDy>Da*FZX4Rcd_{s&p>0)Hz<~oJ%nd=MLFm#<#b3K$c;ra*AdYg{#+uz_*BWn(Ja` zyUmcE=kjqi-lEy2<$*5N6^GX)PczL9pw@Gy`4JKPS(7dW;xgHtHqCF+tB(tsl)}|C z(K>!VOJ$Q%YE2qSn`qK?(0USPgCmUfh~ zttqv(4y8@BbuVbW0JFg`yAxV!>)#-vwtnVNEDeaTw*G+twsqS@ep~Ma;0+v!@n^7X zw)Ggu8n*R60crNLZ5>F})^nhqHOvk|9bmosyM6)?<~oG~&GihWbe&RjJ(M=# z`e0~P!ffFBt*kW9u(uGA>zAO)1Bo!#V~c&)s}a!|b}az6$n{fMHeH`gP=hmUA0TwF z>0uT~<@#c%>rXd`t5C(M^n8$}>Qf*zuPHduye_~{l-HD+*P*ltuQxzzU6$8(vcB~C zT}0&d2-Nhl$m^UXzSp&g$m+OKB1)KIdkjm?oP`AHx9M>@C z;919R`aSITEP-p7tt^3Sn3hX{wR7S|z+MpScUZfsi7tlJnux+%aG-m8Qp$lrsWnk3 zZK8>O0j*E7n&`jKQWMQt<~PwN2jlMSxNu->N50O9I}uS6?E~OHI1=NpWZ4`T?-SIZ ziFzF3V!Z2Ux`_g*n&=-;*Ppq559(Nn8n|Jv9_zcFw>)s2!UxUuu9VVsO3n39+Jx(m zKx-f!^Vcw2pe5J8Mnt3IZg_QUL)b(esKZ821lj|?d_FcaW2z0H4#R@jF;HUH=O~4O}n7NzwghPmDk+*MESz{x-gff?vb2 z-RY_`GP>&UNz#~uFk~ThBmab{T4zH3s-R6M9ESs)I)GBP38mI1p|puMISN{-dC_n< z6j~Y%%MekUOh!-lAi}1|O9)__Jcx+eWF`PhH5_hY*=&=~2x`zK*8swy)%0)(q-vAc zYQIfvILt&Hhoc5=q#E}?(3CpI}={1eL&WFcr!KS?qr1H8G)a}oD{1sfnexTpu_u^N+9|DN^PT?DN zWvru=Jx;0l9!i_={Vix^@X#-q`&O{l^!*w{14Hx&9~AaU5#k#y^i=xqbu?<~oHRnd|K-rR$WM z>!Gv>*FS~ULOSM8`-@mu(<0s_X4CJ7Aa0VVBp|A(~i0FSC@zu))X&9b4m5FmkoA*4VE9YW|G z76=_e@4X|vS3#tRpwbahP{5921q-5L!HU?h7Ze+cSU*w!=e%>v2GH;KJ^y{4J9lQz znRnhPciPUK%Rd)vsOv`g#I(DyUJPM1T0tvB*?uh3rGL*o;iPMos0L3M4T8`h400AO zM}xx!G;l$A`eF@&SE&X}G#2~iWn`-CpNSQ2{K>uwu`fpKi(f$YKM2n)C~-NuK|X@} z@4v5?6S$)gHVWTLDs?-LkrCM_{M1pYJB(|Slt30*bNLr)V3X8D;;ea&V>glcj^iLo z$XcL|&9WJVW-VWZmG;GJ=wH0{shakwDB1VpDpsjo$yIyUny~Rs* zr>O8tGOfSCdZT=V|EbTywgkU9JLFq9-H$chBx72lM3-TU(@r@E>nF&`9N8(wT6y1V zin|?~*8-m*_nhxFjh=4>dZZyMo!|OC5*WA~TJqC7m!HUiw{1S%5Hz1>hzqCaSzZ%> zgm{)$%E-pBTIqp8Jj*L(lyLnj0ptaE6u0<6i;A`1guTS;ux>~zA)D|xC-8$7X$gE;fw`2>wFTCR zlVkvRIHM_nAGAm-<2b_!{GdfzS;tv4fgiL;OLm;a6Zk=kv~rHKR03aoN-OU;%OvoF z7HO9|&hiQTpha4W<4jH92QAW49cM-YKWLFw(Q#%a97Xj>OLLsn68J%jvO774Fj1!o=kR+HZ*;pr?m z>xz~~dNhF_v`EX5$||{C0zYVx)*aSlx22QAV%JI<(RpkFKWLHGLz-&569X1M zXi>2x%hKWpEz+~@LP?g?4_dH}6kBx{PB9!NtR`{c4E>5l;UJp2U`C(sz%0$LSY-4g zT$*38$QZO1p#mWuK$y|XsR~4$@~dl|1JBmL zD^8iMO2a29bL~UmBxSBMp6fqQ?7Bbnc71kDVmGwY+XlX;o|L)q8oh10LvNd(*V`7p zRi2c&^^D%OCDx*AdsDsLI8<*t*6Qu1JM?z*5xwm?rMKNSDo|49t*Lt3(@Jl*kJQ^; ztXxT%_uQ?w{V(e6{x9`*ARcK;%6uSGZx6QA+e3r&_V8T2J+e`6k4{2Yl9YMyD!m=r zqqoPN)7#^x_4Y(*WN}jFleP8s)BwFby;yJ0+@iN3Y4P-j4UjtxRTNc^?m6nam;*Xvlj} zNz*$XTf|u=^KxP4l*vpLW=omObYX^+$*k;z%W}e1(Qsw?O|nWk>F83D%{R%CDmCDi zSBu{ytGqKCwI^A>NtV0~LvBf~m2biPp&9zSxjxNuH^D6TODUYS zT042*VtO5G0jhQ?mA6C9KvGuAVW^`?S*<4Otu=alxY}H)x9Gm+bhSI6xAsryt-}j? z>&VX!CS`RRptsJW_11;&MzSdR`8D;{tC8M%x7AzU6MF0Sk>2`$ zt+xR`>ut~iy$$C37D-t{uGibp9eNvHQALj^!dsR4jr7)Fb4$7!9>6WR0y<8y7VJar z-N;8TSwG;Gym|yOASrt^`^}{6F?;kjVP6}%CO)UPN&LQLQugFu^>#(1EnQO^>up9~ zz0I1Ux4CQeHt!C-&3{R63(x3nQHdzSEvcZlrFHdoWiP!go29qqoAtKhUcFt-y{}2x zuY95^z5X35TlR@C8vCT|H_s^cc9C{;y)#O0@22bRWE;J`w^VPRo8YHSfNxBIZw>Q1 z!~EU^|G@+}XCnGpBdR+1ML`Tzhjd1hm{fIGU%d^VrneER^fvMqy^VTQZ=+w++nCdO z8_V68Nma*H*W08#y-l8~w<$O1ZR&%1oA!a;W^f~8Qq`HoFpEg4IxAUkv+L+>UQ}-j z2I+0#481K{ueT+)>TT)cdRzXv-mW^Uw-w=z6t*%GxALXXV#xRLXt$qB#%POs!csQ2 zX4@N(1m|0Arc(}7@V?cy7yL(XrSh0{i4c#pgEdgm`BvNW0N?ZosjOeJ+r)#k7S%8${Ar6zn@;Yuwu|H8PcNZH|5p#1A!z9fM=m}vvR8{=^!`{5U`M#3x~ zWg;p|TMF)IS#lMeTRdig6kJNT*O2uxt0<0AkbCP`fy)BcocdPa#1s^fyaq9EQ`AW~ z;lYnbT(*db%a&UbK|Ud~-oP@2lK%uT2ssWpTR#2+U*!8!hNrvYDgdqIGb+pK*^qGv z`PmS@Er`5-1tY2?tB5?Uc_zI9jPO9GHeMnr8621f6Z@_MH?s$u|I7!fu;wQ37|xpc z5fqg4_5EQc4=zpn^(aC~FS?yR$=Nh-N4=Hgh1+0OJx+9UF+5w72B2$8d{C^ErE8pL z>**dC#yl+DQN|qqX5R|uBQkR)oxx&!yDV|AEDB+ye9bgKk4gZ7tn^Y9Y)r zz?EL0K-Rv|IPeI{)i|{U{Ue@W6k75%3vf?9xejLfa7dB#we#uo({(iWVyq?UTQKjC zWS&_p=})vpX{6_Dfm!vzYhdm}lr@8KX_j>cab;#chrbU3m(RZzlk>Q5kUbfUGY1^^$9D>ZmGG(&DF@S6xfal6(7B8350D~lE|?khP-Z31aB4>ClydL*X`Aww)8 z$?LblOg~0@x?oLL(qCpZOz(x3QPKxu^+eKN~k|1^=tr-lPXxz$2+v=a%oHxviBy zT5o->)Z3tKdK>((-iExRx1qo3ZCF{%Nt0>~Z-`rRk6IK`yW13w0%~_(r?(!))zjSa zdCS<0W-wT1$Nb{R=`Fut)h6?YChQQ(J_rGsZ9igv^2Is)GZ4sl`bzW*b?(|m>g1!O z_U6w0%srLS&IOV?)x<6RqYn_S{10f(C0Zg7sMQ@0K+%#NQ?B{M6k3S2vSgQAj5EYa zS+c8f1w)(C;p%2w;o8EmC40zuL})`+YX47JDvp0|DFwf(o_}O0P>c1mWQU5dqIPye zc#--Z#VeBZFVKKWdY|6Z`1Cilf6|opwV%OW^#Ie}Fu|>biy`3RT6pDIlOXqjZ1l6b z|KWk0`lDY9_d{MxEi}%UTKFySbGTB6Lu70%jDt!kxC{^(3)roN4ItmIh1nj-OLFqZ zS0I7OH;rd9Kj}(yUoDz{vzJQ03q>#K2`y<~Qy6CX4L`yszGO@h)+vt4fYFargzb#e zDMI6Ni_p0IB771G9i>u%5|HW_;oI;#)LNv>Im_NxcceCHGTZ2XI6^=>q~9;dl}A^9%NIQJ{oPVB=V);VGDMblQaJ5C$Gu%lq4bD`1J7z>0?&5P8=?FW5_Nun(p=!G@xz&|qC* zi7dhRO$`L&m$j36+{_Wcw{EZ|6@b$K9<1kyO)ukU({F_%_WV9a>^HDPeuoe>5UkP~ zjO_Yyh%Ai|EJ9l#S8Abh$K{DU1^;QTI4^PY+{BGz;tni?I2s7IZY09lqM35XMdAJ_ zQ*z~{15hJRKKT*xed>nua;3kUD;=0Cm6sqs8i;Q#R;b+glFK^D_QL&hZr+H8BB|NU z_ya^5xxvcyfZWt&nwz~a{Y`4Nhj@P%XQCpV41NzDp`>OH^a4K5#p#O7F?iEi3_orr zlC#al>59B*@WYr%CpDAh2!GJUo7G47LhwSdJd;3t@Cx83U7V#E83`}o)lM+}`JB=I z$Hlu}0emUEfH#@X@as^xm{U2~(tRrMjqn2AZVd1qUDg9{59c7jEQ+HLidp(Tzt9BWK>~98KMRBdjv?%rE^Xd48{UGUI z03#i`Y+4FzzRagwDogK(XMk{aH3*yJj#z>pgU5`#vt4yri^Zs%7o&rq>x&HXS}knK zVD`5hr+8zu(M9@qC;k)hJS@B_?i*J(0Y68Yk~vkGWwENA^?B_JnIL_LJ~yeyh+818 zAxNqiD_uluUaoxoGipObZe&6CrxdTCS=z|l_p$Dh(7>Wgwt!IM)L5q<%=&OQUP*(0 z)@P2zua;^<=)xlqI@ySS^itx>U_B=x&xrr^e-w{@yf6n#>aq1!D4&EC1Wg?)U_@(S zu3UdoQ}^8n5E_7>sq^X&^xKf6siT+70^x$x(O*;Nh4E`2La)K35UEq~n=d6kzb*)Q zmWqG#e-xi1`?1`Sa7drj{~)lY?xH8P^nDl_zY?zvP@M`$;za|7tatF#aFI6BioGZe zRE%S{v0WXz4+-yqV1A9A3@_jt8?v4r>HvHi#j>6b021laN%1Fh1oiYN@f(S=o+|De zPCb2!%&E$JicHp1pF~@rymb(A#--u~QJFqtS|IX*)VkaXd<(jqfo_V+v@bCoN_}}SUI{O`1T9f^CT@@N+T>8yjAqQp@ZQ+?bY%F?gQps31l_^Rm;dK*^`%IC z?K#3}j{4UfhWefX_4gfs`W>YT2++E=j#3-tAwx8gI6kYyF?_D+FOiP_AfmCH{0xky zmduZ3_*vk^=4QdsOq6F;j@M+niFQhWp2n6fch(^Lj8{Nh>=-a^TiYgRY!58VH(EbIQb7E8q4?9z(8>n&Tz7T^1X!l zv6(E$l@86&?ugQnh4jq(QZ%9{T(J;P& z&_hq5O-?rAS6@o}-~Rz&ml6N`|1ACprtj!&Rk=`Rta94h(qH={T713Sr0v647~PGA zZu38fUW}1&!YC7Z4nqI;7;~iApX^0A+mS5@qUAzYWawk4kh$_=cgT#$gX2*ek5VQ} zgNuR@8X)vS_l44+OMWe&vX%z@wKTji8qf`W_p4eOD!xpmONjrvHR9i8#Pcwm zl@LTrgRaQ;Pikq5#F}5JLO~rXbfQdeuy^V(nn)UWXj@?61`q85BcXPH(}*T)L#M*0 zDP7L|gOf58VR_83N|iKHcm0FZ9C;Y)r==(9F!D{3I11qOLYp;uN9ZyJoe=ye6e%sD zVUn^g6-HC2)0~2V&0Hr}9{Ch)dDuwk=SrYFFV?IbOC)d&qgNe#LuX65VqwibVU-!5 zuBC+kI_S-jI$7uunvI80xf?-LNxC8g7n=To~6azFe;k>}^1npJS5EO$-_}G;|mlvxR1DDeM@wKrzQ@o#2v=~%E zscfehR08K7v|JDnV-s6fK8i!Al5ME?c zK2!fxlp8>}pz$C}+a@ne#IqsvS@iqpDOCIeml9tB%cp3Y7)E~lpT!SFsi1Ar(6#XI zk*}OqQTl7!hc2>Jqb7yu;;PRfSC$4uo)>r~F2r4?b=_9Bc`K8A7blHvcYhyzvvgw(u&B66i0 zpYq4d2%rnp`@ak;Rz8kr>oN0WUg?J6gY=J&d+QecaadT#LHlf!b)Zd~dJ<^ft~t!H z>eKp5tn1f3G0DJfpG6MW`^B1LoXO3@NGnu5hAN-2RJfH$xF0prnAI&;#^XPqj4v$p z|C#5MdH z6t)>yM$%smC%W}o)6mNg(HMG^F4Xpu3;pxi@S z5S_rpd}*}f)>@-jJBde9Grlwax$|)(8NBg^ z$33|wYc3$?%A0*a8?D=zr59;5AY=e;VIyhj7*IAENmqN4)D{~pMd!-ubs+z2l;y79 z0$F@$GQd9!c*F$}==;I&?`QIbn}dz6D%{PwZUaHN(onc@*p!ZoTJXt8u(g(OKXHUM zlYhBVn`JW01m#9rKi4C-fQI-#nhM4}hQSTU7c*w0ZUp#{0lC?^0Qhu$fLEAe;1+1Jmr!f47ChF>nuD=L9|mrY zHaaqkFd*2_71+&MX}M$CR}5G!G!_|;E5>cq1+Wc0fvs1W+*@5hW|3~derGWWH(bYr z%a!K+faP-l7m&xifL@VC=!a@{1h?>WFxta<3o@T&;iTo9^-=Ph@o zaRoyaF@DZnWnAIVn6YrJHm;(fZ`0vgV_d~Uzg-R2HO5sc^!zHg)*4rt&uGG-#?QmVcQ)ABvl`am~4XoQ%dKRjR&Bw32DFyB;*F+-^`}TnUcFia5 zGxzf;!Zd@BHv)v+j6}Et-OntSu!fJ>4Jv_q(=U{eD|1kT9eo!MnAB3w-L&nYd+62JA`daw6GXC7HZ$vYbOvdL*gX_SEngnno|HZNw zECi#YVQ`QC#f&Pf?p+Oo+y4ziA5KTVx@?7dn`fJE2B;qF6h4^>V6g%Cu7Cq{kP00D zd_a@h3SS^F%2O;xjkoj$ZtG16e6_$&U7&;HL_zqHrs90(pn!llNX)oQcvAx3Mu-v6 zOeW(I%4n!JB`om>e#*+efy~MLiEl6@W&X#!$Y47!Bn0(^grsmb|8GtTR~=gj3)KTR zBQeR(VbG7w^SeJmQj)SCGJDLQGJDLAm_6oCn?2^wnmy)6xyL+Dh7F${$iDj{w6iA> zQn=MTLK~ow<7Nf256l^c*W?IgxsburKNtni^ecD6OunTd&EK}rd}$iZpHO`yIU$Q? zMTC^}YcZ~r^e|cjNk7;YL-+KT7Q@U~i?L#`ejRS0%RJuBf_WN$^hjps-WYlYIv)8% z0`+spK_{`&-}`{!PIm^Le(WpSKWIw()!a~(UL%{Pbs5c_8yU|?ZdFRpx{dZ#OhkGu zZU{}Uv6kj4tj(aGYN1diLWQPz(EBLL_|6Ko zEC}Vu8tm?9uvu3|_>rcpJF;*P1>~6_e~$3@MF(H%;wWO%0HFr&EQ{IqJo`8NIU@T> zaF}vx`OUa)Rh`230BYN9fMEx#xAIV&&%(Ss)nha zrl~3#Y@iL$4st#gtq**0#^<=r%Q+Nr#+QQWen8q>g3*Pq#{?^N;LCYkGf@*Nb?gT& zdLO%+9_m)9vn?_WAs69FB~2n^VBQhz2zu8)t_fh1)&`*4JqADhC?C6{`1VevzVbEv&iVlz|NdejJU`Xs=u?4pzySwI z1prljFdGSU!C}$_Kzkpo$&gj_Apc4eceKJ#p9%~EVUkZ$@eXOqt{Dz#1qj#sB$ZTK zM&Am>XUlE?`#sQ^_w~?^QdOF_Y$W2~_nKb!7!k$`MGlrn@a6fbSR|(+UxRR#B$F>a zr2$l|v~~yjlUBq-FdPgW7t1$3m<+!#t@*)B*V-!$En&VAjA@JYG@^tSrgrEi5|lEa-s zB=#FJWR_YkxrLtQFr zxmX)PtSvzgzs9I@kn_DeGwQPKd-vo$r+=S*dLKF!tdyQGxYsk#XNdZaN|D^eHlQxWgo!+t#O0>aQAQAZ~`cS0n}Dme_vzlEH_yi zMi<1C|F4T-fj)B>WAK~v&7c)us|bF_*30^20IX+_czkD;pT-RSbQQWX84A53fH_V~?CZCp&4hzn1g5eS~Yv5f=YR1j{apCJkcgEMDYBZAt$mw8F;qm4r$*M*cZ9WyU zDzyZwxXi#vSy??U$oD4vCXLxa zSXJ(VwN)8fYuyBEYwj7amZZSih9ziy8ilpPNm{eW?W}TZlG{b)E+)6D%Ke1ge3i== zz?uwDxmzp2I!uKnp^a}cT&*1zz&cXpwjg(`%H2ZlWEGZ3?iFfnPwrHeyY4wy7pa6P zAy}6xVGBkwP1dNe&9ts1*S3lu9*N#4HAFAow54%{L(lestDSKb4b?9TS9{|s9_mXe9gM3~=nG28Gp;hBdX&=9 zxXOpNA*QCCj4L&?Z8Th+jVmLx2Hgi{A*xGOXdPW$jjKxNroC`=H?HhZ59-p>xT=PB z&4a6#aa9Ywfk{-;KE_o&bR!bkbg*&N2z4C>*AU~X8QMmf!;Py}s0(F|G_KmAn<#U% zan%XEN||Ggt8QouWnN)iIiZe}ImNi@VFni8AMS-rlNl2f=LpFXPfcUk!mqLCAK~YQ0A@2#C+P&Bp9iWI+$UVJyB!F3J--BB zj-#g2z*t1qYKo3fFPGHg#hLi907;uc*zJ?18`7E5h^J5g>W-wxKzNxXRgyDUa~wjT zhb)@{=CG&wLDZ*Uoby@CNu?sv_VvLU^*zew6eBH)SW4nDnnB8q%$Nz0fxxoh-;kJz zOQon*JtVLQtXUiI;7S)T`WIxG-kRm9eJ3qwYIw`nqbK5n?;`H};8h3~rZqme-nI6b z&N8e!unD?_6k_ZRwGitL(L&@`g6a5YDMc`%pBduTsn1kG_J6+1dRmB6H^3<(RRNu2eV{VPg54Hz4Ol$ACs`v3e z53%mGsLz*~`|b$`0xcSyLj)pyKSYb(qOs%XF#?X}htc)`xpD;@Eew)%$~N7dXF*rL za1t^jWG1?YAvi(|s&BEz2w&26 zBUs)Q{w3`_48*s#BRgSJ1A*SU8sI>)ip+PpHITc~@F~hSWsF%A;~U;)m4MH$%XqOW z7(+~OzWjY5qp_@R2FCA}@SSj-gIt)ZcK8679Y|SVa;&jToP_|3MEKgcd46)_H2Rm6 z+jIe_E4@_(+E5%!Z;t#z#v@Fb@C|dHp;-jNUJHcBN-%Ty?)im;T)F#t5MDOL&DYYE zfgC!Q4*&5c6ZoFGS;pe}f}07SE(2qPlL;O}S3PoN8FRm^{RuVWa)Hk7%@jXZ?i&U$ z+e`(yh+yK(ku$sCfBYoFa8cnxWpiXSX4@%mvyT)mH(X5kp80XNE`)I*!Y3drDpC4= zoulq3h{Y9cnY0QDABA^l{L(<6WtrB9gI(-wEc>)9TR2D;&hA(ZR?B1tAMr4TEol!8 z$-NA3R-`=^X^)`Qu;VQ4aatMlot_{(!EZDnXlMe&rXA7#KRt}{dj~S&gP4>QumS&5@#40@0DP@I`(D zV$TA4&Wa69x$(_@*S`|ljEaqoKVS7X{yCD`3;yS*x$xD0m;NMLm5OCe#o<{1uK%CI z;9t&&i9-Xg{t?=s7!#2zmyZNxhIwRpaDb^>jKLLhrWzO}G)=-Y1x!J*{v&wdMgWgk zRp1bwG;rbbrJ0Z`%SlTzGI$b!FT;%`f>q;+Uz;TGkOHHswi8qaQI%;3Myg57agRY8 ziw(E1Nzqpu!290P2ayLHxG@}NCMBB~c;bQaA1Ws!m=#yoJk6C9X2$}P9Xtp@vjZjj z!D{$-#FzT$r)kfTX=o-|b<==6CBc2n&!G>kctE{p#IT=WQ9r2O>s@ansj*aT3G63J zc&>s`tFg4gBVDnx2oG5>nZafT`SAE20NqVn#iJK|(6q%>m|a8VS{t-ynE#R^jn~6* zT-#-y&tOu8Vu^?MA(JIMu)zq>GRu(_g^@fi1q6fxaZ_aaw@Z9*Is)bgJHuN$!9L^Q z4%!o%jll!PftNkwj@DQrZH*q;E+h078I?L7uJXdLcqVOYCMtzJot>z~&fT8*Ag%1& z?OBIuW#?|sK1M6w$+qWlfzn$36yz_cL2Eu*c6%WYn6UcOy69(EN3TV#FKVx|lRBXt zc$AW_8w^d^4)iYp*Y(B~44tS9*9}LJ`FNEyFgo`xhTCNSj!8qxM$dFL9id0gF7#PXSw7_D7d7ueCR1K@fK{vX6*e>MU3 zVv#F={RscRJj@*m-T)!?yJ--w6@v4r6kLw*Dzat;@DFY%=HT^#wfFFt7gd_+NU?Cb zbqcjhHJc2Y8Jp?=RZs2cA@8%CPw$0PSq8$og0cc*1K~N?|3m9In*X znzIfgU4Gf=eHU0IG^ZBlN_AW%le3R=x#s4k6>%?D7IY*`F+ zMJ(e;I=pL(g$iaEw*cMeGpfsF)xoGIEpKG_CxIL#s)|5|YqQ|pM0$4!1X!bO`2^^X zUU*XwzcJy}Wo{A(ZKNc+AzR|nWmUjs5*<@uO3s$rWOb6;u5|@B0=eTQ0ziqOXzlEL z`F(+@#e#D51Bnk&OxLt8v&bshN!8Q<7MtxV56l5nr~Ykxg_Q6T3}a5 zy%D6m=TWq>>1<=Xq@s@4S4z%0QvUKN`qu^xoGz}E6*B&2QYv6}a5**2CO#YnMzeMDoiZp76+liKhLzO~#_Z?~j^lO9lBOjQf7<#RD(U z-4%>2Hwxg856o9l6FkJcf98ZcB2pVjQy(1)v3Mz41HT~B709T9XiVB1-f@xH;9UPt zyaG{vC~_-^2Ys?vKML?piM#~P2N&?PxpCtCR^)rYaahHQ%}!R50-}BqNdhO`=S_%7 zWt=7TfJA-tk9c3ef0(_cE&U^Vlt*#qj&=0U0sC^R?LGJs4P?q~h~}ol%Cy=H za#**4ai7o9n&hx*SrhJZSjWJ4+h=LrcUa9W3$<2bJPXF3K1);PusT|;Q6-g?gt2it zE+?OuLc9{)kcsPS@$+14oTMojZ9JAs7-4-e44+3LVKBf^B$$@8fqo*~o?x9p>#q_P z16<)ta0s)k%b>1GxEbJHUqT%z6oL+mttF|b>WtzkfY1999KuSgDhMx-@F~ErVkHc_ z9TKjy{z`Eq*!k!ua5-&g9Z|wIYjkl(LI%L9B$!mxkvRxz@3xj8J5eB3GnL7Iwv0Pl?@@MG=vQ7b#sw8!!S zz}I34Tno2fvYwdh5WWU@HkQEEANzIdKW!XBkzP1T1DBJ`vGO03v;C1Z8mdSZfQAH3 zkC%h`5YZau(7v^1Hvp|GC<6-8(3gjU5cH$9>3T4x0-fVAP-g~}02r_bu5r}39^h6I zOm2^ri40xZzCIbD?*(wk3vC*~vC?-a80G9rXy4^^pznAL$iHO;z;t_jk~60I5#aA6 zxTVQ&*xGgMua=>sWrZo(8!Z|xLojjF5oNWuTiAFrpR9&pv?a^W5WIOdYz7_>n=>L6 zH5i2P7m3=8H>m7U_M2d-sO4a+@kBvoB}}rvLCL6?+W_9>i2>m(^533mKZNI4B^(9# za;yX;EVO@^;7Irq;2B?nQFN`nwzMOlP#-M);fhU79sO>veWRV^wnNpyXy~(?){0;E zwQsX`p?tLM=n2LUpXIbx%DTrsc#FfD3&vGG%W18Yb;zEFny0dMf^nzMa@wJ8EfM3h z_A99S%Hmr3>psiTOIauEnQr^|4H(kbOCwn^eN!D#{s;C8TOFz8z^&%&YSJFJJnc)lPj;!vle zbnSU@g)evF{uH#|e5x0>JJ?eG`nZ&<9ex5PFLiKTlnobEcn!HPZt!(Z$W90~=29VJ z3rGVUife&+o@UKb1lasffsk_LACLP5O9sln58Rh7#n*&6`LBUKkK1vL6X**BIPVA2 zqEf@Dn#%tr?soJL8c8Br{MxvjJn;D!rKCux`&=hbM+6x5Pl4Q&q=u@yts*K>kG1QEz@|v)g7YM}TdY3Z!jJw(wI=_S(?aDn>I~9)!nhegMBp z`#F~_g?Ay;b)obd-B8~kL}-YY3w|iSP$$U4>{@RRO}WWk>ZpzoeluX^NfTr%`ZW7U zXjd7RmVXIa9o;8k9}lgB=3I@C$zUy~3Oe>O(|u153>5Dfg9iHj(C|&*ZUb)*xn_XH zdWj7GhJ&>)LQ96?p@xSX2IDzTA_%W_2H}U$`xs{^;S+%Tys9_c+l>sde+?BuLa(My z7DUD4@(A20VuuPnj3!i-P6yb~BbX&mUuhf^MSjUbmlxCGzTVq&2uQFBz`{-90psj&)oy&MY9E%YtM(n`Gw zv`s!WR$-;CEYv3IQ1^p&)Teqm=H`X+Hx|0ApTqwc+_RV9Lt&-vEA%QVfof4?I9|-c zcH@OTOBI@`KjqsV-+5SDT+NIysr;N z{%l4%fY#rq#x@X7mjQKQxO@Y%=;pAtfwA9bc>>*Wi}DYI zo8i%H3<2^YxL^Mh-?ZSA;l}iAICq8 z93GzH@cV;1^Pl+Uah)Vj;pnu&3wInf$GO;YI|5{lt8?KgMB42{xJxoHK^A?8>GPIQ zr?=cdA2LvC<4XtX%*>gf5!v^I^6^rnS>(SA<@Zm40+Zx?1H4PR@C-CD^j4%(F>jn< zdM~aox{6gt7%0Z?b(=u5-8e24$We?DL9uCd-9UT)B@p(e)W!bz!l&dZu-+!qJ+jH^ zCbjmfp(~%Yr3rKf|17wLP|>`ja~!^}nezYT_0E5R0%1N_@xcy=Ak3#BK4?t-+m;_R z=4cnpSJ0SUIK&CJu0DAz{%^akdLYm`hst*yT?y6(%Me8W73ANCt?P2jPuDll&9-j1 zLy@4ZfBdzs$1s!SHXBeATTTExg)5a(#qZRRdrD~`zX1KyW8i-`uBNqalM=+-1KyH| zfS2P+ok0n}x$@b%{hjRsfrp9b!n>)Dx72mb)}3z2a`4{32KjisA#Jht&K*$Zj{KPo zG4a89;Dl-IlY@DVv>16D9({kov(;kEIiv}HDC*{*@rO~1;dp-^kO>ZQGrF}F6OBVR z2yt75X9@IaWJG3;`~MKhy)7z|mO!5tM&z9TACcVPp(1HP?N|h1VJVDV6pVuZlV0J} znfTx~Vyr%4mT;e_MqmF|MsK!L(TaRA+o>GKzi+4FRvV3;mOz-Mm5ye!O+B@)zYEqw z3FBEhWnhLYfsiA^w!?eBwzE8#-@F*fbNhjvPY3p)zBJj(!+5kmu)m1CM~CnTf31t~ z9zk(;F}y7Ey!&)A$$JYvPV)YO5HER-F=5@)3Ysm>N;5 zIAmc7T#kF2;NZ*%=bu$iF3B-$J2W|Q??Djw#VZ9DGy`suBIP z9ZE$tJpt@JAD^Mq%IK-uVA=8=0aF%CJH{xr(f$Ub4J>;)iaB9hHe@x^%|0m53PLp6 z(2^DC$c zu159zMA(1cSQOruHHWpE^|z*0YjnG0=A*{icKKh7sl*`so3ZpHeHm%nt4bkKt2lkH ztc@pfZimS;@Igy9fYzB>@SQ~o$#)Gv>XP}#fuzsr3A1Xc8)3GbihlrJn2Y0)rCRYR ze9&@&|i0Zx48 zeakQa%j}NRaf@VjoPoodGoRkYPissW3!td%w|Oico>pjgKQjwCWc_v%+thM<;o7nU z)^r>3hdQT%b6~AwB<9RvRkA9#G`+=(ESkid8 zG*Cjz-`ZlAnue!}6~Nl6yH%l80&9S^&2a`3SOu)@_62o-hfVBdMEZtOgy-&fb>Lz6 zKjUE+)PWNKct(U1P!BgUb%1Ajiu?pD0Igziw+wwOSO@YH^uXi-=Z>;(;281M@0K3;4J5Ft392^t`+ZQnfgnhV&Vj`$~Qs{E7pktf|5(F7pcpXeLJpo+$LlDChY1JtQz$ zk%V_))3dA(O@f-l)-GYQD}&`C5+?Q0m9gu*xwtbJ|cvO+Uf!j)rO_6ot6 zW@4ayxh-SyiCx5reU3BNgOGj?UawY}1oQQjxBTE?#M@^b z`lsTF{Trfd3jIHE9XgaN{a! zJ;*?VnnPL#*?~?eaa8G>vB1jczlIT^&4nhm#ANRoLj107gf>8XQW0wU@Oe(CR6-hR zr5J2pVizZv34&Dd3rg|9wxEV-?ZRPfFgoKfJi6B1gT8m6J34GG9K=RvVgD1rWw=tw zGE-EHgZ@SqMCbfk+8GDk2y8b=M@b6w)Wz@Uylk*2Q6BLzD3AwNeDEchVPoYmEWpyPwDVi?e6FM^bb?y7|P)AyDzl)0Z)Oc(e`t>}SV5ofqWiK*8rTBq}|M`3+je3?tv+fqhbEr%9DnV{x z!WpRXOr5CkFu~m)s(~ay_dU1Qy%v<5^ z@3>3Z){Cfp(c8AO%5v=@x~Cpg(ItuK-o~(25KdR3MX(ikP9QKHS1O-niBJ(2Eh=&q zkn4Q3$7~-hhRJ6$t#GO*{vfWLu4S}u|8!8lI{w~6qyHPg^zMg!9}Z}{ReWZ zkFxD?(W)X30XgEMRbwRA5IF(lV;>!5(8>!@LbXJG1oF3sI(>lI0T;zP8TGJQ$TBL6 zHXsw1Q(|$?R*A9f$_*{MAJZ0yMr+Z=(r0Qb)+4RTZlH2 z!Dan|vbcI3Z7u7DKo;^%R)VqNB32zfU~OeF25hW;at{~}dMsqs!5ct`N`Lge+RwcT z@U2)vh08(6lM#*G^aGRyo;G^?77fTc6#})Zp1Hy&P|AUp=21cT7QART$;Nz&51}*x z*gBRFybgpOvS|&v4-y6e92rZv3=^toPic)7o{yp|0(ey{;cPz;dP%#o7=5DklAQqe z#1d{m9f|gqN0%bINH`4exmdygW`7^)dM##tXxroyfTv>#osk34zA~)^+Itc#JQwk} zyz0l7OQQYcrKV1nr31{4CH!;^2m|C{^cz~jZ2)$RC3L?Tgn`l;`JjYR04K&07N8Ty z_Y3Yxb_go~u8k%9k^;hDNkprv67~YTCzf#jN)U!f9i&zX&jWllme3v#a&)M?+Rh<- z1@MPh!m?5z43kN<9YSHus!QPV@?rdT5Qd9|l`4&*D!@9igaDtw5%OU%htLUN&sf4; z>_SIM4!RAMFbUv{SVE1Y_E*2kV!L~ z=64Giw_cict@L+UPk`~F&%#5_2bo(nqc=#aIBeTRy5w^(ejrO5*a9(bks2v24r0tes zH#rGi3dUNp%*eoL+%*aNq-SA=wHJ&7K8uZ^o6tLDdA5_#m%(_KER)b!);;n&hF$EV ztxy} zFlLeE>t!;{p}s6xXrVNJ*Mqj_0xHu{fd9HocKL_Feck6%O}9L_*#b+TQz`}m3z+V2 zKs)bKRjQLkd}%HEp&Z)mP!rL*RL12bE0)@?IH+Gp&#jKaEkWyCkcyH~*4Hw4sKXiq z#&nBwnkyL+zLks#ul!IMimK<&o+aEOb>?(0UAyoF;1| z7*l+flXzu?taj*Bm9-j-?LNy>69N}-++D(2g2z5*4odPt&>r)sXkT=(HQD+L&8Zv* z@EJi-^TgPRFnuFuuXR$3jY3Z0@AtO?be zRCEJvAgLxt99FFyuqs-GF^;-G4&g(9r+k7VA`MkWFT6_8a>@1 zqynt$6UNGEw0P0#Rx2b}ngZzHf#$vQvCV zgTSk2^=WC^D_ed5@4U}t?Fg*K0uXt*)?|!W*skFnK$x*LNQr?ko5uWLZJ1#;SLzOP zq!#9AEX;9Zm}A2*$A4jt@#2Fd=Ig{f-?7sNe*wEv;#Htaq_-h<>02L}6VB!O*u_Ve zsINJ?gv(;y(Iv+b{#{(DZQ&bpbjjE7`^EE*bOee(&e0`>km03pnLy5@$UV9w1m>Lx zDb>N?DK@FSDLT@SA{2qMcLZ)iw9bK|wAF$8h|I-ChR4XjfqpuFn znjHZv9>PoGax`LG=ERa)ipE$_Y;?y5bAX3w%~y|n^@tB{fHL{P?gVL#4-Ry#UG{>E zvrPVkM+z~lOyDRz=X{c@;d?EvRKhXmlk9}^PR~DLuYy+I`6Q14c)~0;b4#eX9$-QX)EowOelQ;5!?gA}0B`9qouA{*+EWSt zKH{0my34h^G}g3s{{jX2JgOp2?}mt!%V03QRpbo_>hR6ySZL8ke=&gdxKc@z$UQLC zFj>!7_0$+zpylm=!_+BX*RQ$^HqS@n`nE=#(J}Lvq@xTk7kHoInlMIQ{8H|2p&7$Z?KZXEM=@xce6Onz`GL0aR3 z3tVd#)>1ql=i!k;tibcJ7ryu4N+lfgd^`!~G0#6@U89BOoZs_4fUi8zDKxG1RLrwL zi=|-U{4<0O(~8wl5c0LYK1f(? zi}65&#G%5cQa?hUSku}JU5YJ#N&<vq`d$VZ&;jSwE( zbQvO%Gf2wMxKc~eQeqTFlNa08APW5S>T}&CKqp_uj&BGEix>Tlp6r=ynvD| zgJ*$qyL7GW#&Zyqqdtw9g${o;mJ||C$kl@}dqEN``2>{H9?fOEBg>Xxd0rK^uf_YH zxSTX+%R*}NzBJn7%E$y-jSQ0{hw-trZtlux2eeD9jA!E^<8yh|lQ9nHlvo+cI4$`d zT^VbDULPwXHw+oy%4}$Fvi5GE55&q)#t$<7GK`-zEw2K7iwskK*>Zn<$oN&#%DFPm z0{x8)H!aHeLsHwhGD@P;NXF&Jz&in$bR_;QGcov|p|R8l8qo}&AX7R6w5=i)@PP8E zmHZemzdXP~RyT~}ObVtFvF*82&r z%FoAyRBe;2+QVIKPsM<$Z8_`Vny$9idOuG6%cz1iG>XF=G@TU)I@&6jZk>dBrrI=# z3ArZ~+E%tw8@eI;#e`I_s@4BWH{>iYB+iV$$TTq=ynBdAr!Ch3+=a`OkLI%blw3On z+-kwOS8#y(C^*mhJbjR|<Dr_*v9$fV6uM!=T_xW84^8f!vn?v_cu-+J~?@;Ca&klY%ewa%14webqn4P(hAd zju^&TvK^dVo?xv0D=^-Y2jKav2SiFj??_cV>@H=pC2s@%%%|kWpzCb;8Hk|Wa#U_< z(5D#hB1=jV@ldDRFnV*1GvlBEDwdSW0!3D;T2Q88E|vJ2qtz63KxOWb1pxzCaCG{6^q2@c^# zYY@_-5Y1dKHhzV~ipWi+e?JIcok4^MaLd4B&B}VE(L0JQ%z$6`@Z9_=%vYr7S`8I~|8Y#Id-X z@qAQ@Y`_`nxEu<5R+sW_+=1Do@Enrn1t}5bnfDkIf3lX9a7v{gXrl^JQMi2DG4U_! z{o)R5F&Jxn7JGJ=^+ntaury`2fpMSD(g(|tRoZ@Sk|T?M8@=zdsFzW0tcmu=xYO~- zi623+(YiXxFvZ4y$nJ zWL2l`4FzK&Sz2>k7T@ttObmU4UP%+U0*vb~Vg=A*CN{QD?sa0k3yep|GG*A)JaNiu zZg0QUiSalXANsN!RwkRR*7nEfu~qxuzzCu(FDOe{?d+%U_lrI`DPUxiWwdu>y^#Z1 zi-Y%9!vC_!WN8CNH(!=hJj%K$n1*4`gJg{dW0o(=VO>2DvNA*6204$xdN4M7tUy){ zBH_3(>jVZiI%`Ybg+nE3z~?43!8$?X$9XwE{GZ4elGvE^+OodOF*8Cv*MXZ0&gTul6U=trR3}Z4#ey|_Gf#7x7SQG>2yuP2_gdSV^ zOvdumViN7HHz0j^SB?h}V`$srNI7o+6KuVg1?xaAmFQ{Vd4rgG>u3-74ra3TsIa^t zOn7=U5gDxi!RM{H6>{}I_`GXahPrT)x0cmR&jZU_$0kot3Cmm0#%-<0q+wG6d0V9D zmO!8+u2iZifomP$7LiKut?wbG$2kp>7x*se0JxV=ITwpQEMtI7_tC#%(P!lX1R05+qS%n!t2<)Wt>Pgj}fxy!wv;)}16XOz^$$b#? z3JGHYUg1kHom5^snF3HHtOB^+m*5b($u$)n3EVn!pD)35QhEL4j_QHH=ZxYQz~jCI zhcH}bqc(j{!nXj=#Y$i=mN!AVEOsOm+lHAiE~f&RUMz2hEa~h>r~$AZ32r{{B$&KK zQn{C-WLJQ_V+lM7ChuxFir!B1VG6+6v4l_vg!S_H4kwE10B(sT@FbYLt@6Pfhj2f@ zM`H=>N%M9|$!<;)@&>?@u>|&{d3z-|1Pg=Aho1oc5ldiCns=AHidw0J(%bPSBrY$R z{5vY|ajB1aX=&DgT!5`e&?hBQ4t^+eWgU~}G22wuKrqJotV(3*$s>86%F9(8(ozuC z`Xm))NZ-f@6)^8&e0xB+pCrw9H$EOaDy4#yh^K`iyU^9&?bFZ2gGl zM9u*HkI!&wyUM9=eQ}pl6}g8w6PJ@Z?MPLa>2vc&Ss!9(rM0#>XdMeukrC|W^Tu1h zb#Pdtz?kZ@VtVWI&Z?dAFQblyR06CQeb z2b9l!8ru!0gU@@$Dvc&z{sUA{>%7X&p=;jD)+CG%_OhCk1DHmFTiILp0pU&SFou$k zlh6cU>sSJZ2zjTh2^eRou7d!MBcVVwQPxk^tgD?zVi_3gJTY$Ja)^)@u#cf?YVO<) z#)B8J*!kz-AR^0&@l`P1Bdb7+%1W_I-r~ggGZ=!(Ua&f`^Uuq&OS#&Y1EVro1!O6! zj-5K&k<}86&KJpI=bzWsE?nCgB8&lJ`bDyo)z{wH*BK(L1!L<4vb;`R*Vxz{{!7RI zFC6sagHdSt!83>;%vL==_&cq}*Ei#X#ZeI)@9UITksd45YRo$HFj!MsZv@td)jF7X znRsLq5AK3t^_)fDjPHTP(2zQgDDT$ni6_Q2_1L^%|Fp$#8 z(^2>yzksB5fnz4mf-1l)jt`y%HB4)Mkc#97Ej$@vTGvQRtS*G3JFUsPF@K2Yz}jHQiAAbh+Rn`9ob>g9wfa5$uME99x%c)-2|M#qQ3N?-!wJli=${LS`Ip?>f5YclM zw}o1=3&`z6mow{tUNIKv3)bUO4 zJ8R)fRpkL@`2s*Y#98YQ*@ql?d~Los!v7y;u(a&?6oh3&sqer40rS zdV`SYAJ#miL0Q*=vF*|iUB-C=-&fTpA}o8HSA%_9M(`UCSIDAWB&w}#<&8EwI0ijtf3vB?-2F^yeF2R zCECoc)D~~rQJd!hzDh!ArU0iOv%`zFus77iYB~w0d=TZu{La@>%MbnyBy2pGu>4?g zhzQdfuVo$|tVoY7Xs^1AM1zkV3E%9)lX%g`RMgk}ree=U|kQ-Ja$jALY#rD*dZaQ7eA;@9966p}uN@q~On;RF21sgmNMaWXEWn;I0n(}cfAaU>t zaXNoOItoxue2};J;I9Z3rWFe{YSJSG{-U+ezoigk zW30oty2G^W*)G=|aUNpynD)9OnJ90M!vr{{;YwxrnE!B>!Ec@C9|;3RAm=~an*rSI zflf6T^4+b-pSojT0pRR$cp0i?wNJ%DH)0PA`5Cza!uLKQ16Czy9_XLHw0RaJl$8A7 zWr#maYoC3W;q9cjar|m`Xf)p6jGL#a#LH4M7r`~(xPqaD*fbuuz_`NJ%QN7bt${f7 zja%3O0`WSDE>FcxC`lJPt+?qLf_WAlmFGyLREFXU+kGDGONHQNSD zU=HzQ5Gs;%j^cr{MTuLN+gSpWh&KY(G8X3$Iqrt8?eW!1hUgD$7;#k(;T7NcO&6@J zG5kDWD?HpC{jx`l+dBqIsF0l??D0qtqWFOv;40)vV8=Y%6~a?Q;|`^ba)f*i!Vedb zN3KPVUYDVfh859&)rJO7^RVJE8J!1$Y|?CMqph?-|bOv`GT2Gg-^~+gj!S z1wzec-G~peI${0?q2b}M#s`0=)%Y?G;)7@K6rugU8{Ugi`PaxBe5~RglJI_K!$Vw# zMG~iSx-}v0QQ@5FGGs^^&6)?&sHCDnQAwJVAtg$a45?6w zlu#-{|M#=j+H0S4uiy9g`n~@5^;-L`y*{7ytYNRchG#u%pBr%bB2(sL7xJ#gmn(HA zfe#3foer$x``-jEbb#q^ZM2V-S`PAMgq}p?49cfU{RF%(lM<%;CFh@CCI-%=o2-fe z&?b_r>Yl0ua<)Tl2UJs?C2#P5Y8vMxYZAdzZQxwychVS{$s@QR)?Wt=(uM>tT zcuh5G1WAorPKex>y*dj%um3<6)HbKIMh*)F&XD z9IAT+GSZ(>C4Qnev!#kjEArHzP+|*0A*QlwVH*OiqPIhi4yzM^t49=x7xG@Y5MC3n z9du7Mh0`|T)kiQZls>fbcz>@g=i)up7kFeu(V}!~uBD!2NR5y2c5|H7Q+L35>{z@C z@pYc$MgB`#@?QkXf2l3`FLfgSrS$S&iYNc&iOByd)Nk~P$cBlu+TtO+11In}6XoG& z1#-pyM*^hjrfh(DH5Q#9uf{rW!rP37!qo4CnD@jtdor}>d2ak0?|gYbbT|L4caiwT z>?i)6*FpSpZZQ76cN)UXJG9kniY#r$6W`{&CE;S;6W{K=FMgSH#eeW*BrxyaPo9+I zEIsP%)S2;ym?7gA?_ov`{X1!V_y6u8L}U)UkJ9{u%b!NRWp1qje!)nUdWHQ@oI#TJ zfQRsjz%_vyMzDU=R%{htwFc>#i6$RGf)QhR7y4>AoSP!vGm?l!+xhAqkVhkQK^l6c zujYfi8=kT2{<{PkdeQNlL}85mq}GU7eV4yl8o; z@m9>O}U> z;wP5q%xp_lfKoN0$$$W(Yj0}p%o5Y3TWT-xz6(Q?NuBEDw?RZYf7P>pQ1wZ29x!8|B|Ql6UrLk4aF$kz)E!Sm)s(hJ;48EQp`!I zYHHuR@a8BMJXC!xoYpMKjnyof&R8pzI;n1ad#1$X{AONEb%fF*SX z#VU-I*fL+&rbQKo3tw+dRv00jzSdqvsRQik)U{Aj8lt1wxq2JggT&2jl6 zP$lPa4bj_`>I~8=LSGWJh8}Y(+@F1~9dgG)xK&86i3o6+J5-oC{T{9atB1Kf8R5;< zsA0on6`p8Kf9(mrgv)z^>ny}9{(N&Lais;{$mM&%jr>mP^KRt*O*NaI>rcXCBx|$3 zR5EA@ORsqfLU}?eMTFHtctEM)l7%lvv7A)r5_F+s5L^1r3g0{{u{#sq%VEiNc=>cw zO&Xw5!??N0VRn8VHHPnbapchy520av%i~Pxr<~G_BrA9mNeL6YQoMg_hPg^`!QgYL zibO;Cuvu|+wGK7v>R}L^x;lF)^Iu&46hhO~)n^iRt_x4z1xh4)fUY$_7YDk9hxzSq z8eQyHGN^{a7$>ZUM09eThzQlyn=VtazlAg%!jln6e~&FxSD)O(N?HP8wUBfs&G@ha zeJ_u~{Py>>fzNi6#WXnVdOw^>$R7sw&|P1T$%ADLPlQ zgj=ZgG5Hf=T?*s!OqO|$@_jq~K*hszlz$i>LQRO5PeJLc1n`5qWF{3nAfR}&f?1)r z;0s=2w9mJ_&w5+1H0`r~lt%k3b!xTGl1Ha~-o?#cT)xCl(>^P1OXEykVoLV71R1rGIIi&u%X%#CjdaAPC{wh%kq6P0)3qmCoXG9ttXy zRB#t@65=grSA;f5(TZ3yMO~BeXJQQNI&(AY7>zwq3FtixS zXrEUwOVg63LYOWjUEENT(LUcppRXm&hp?oWB%^&E$}6ZPeGcKyZc|;#uyMICO zsHXJfLhbVjvMMpXJH_4~Uj6jI2PKQz{sO(8N}}oPQRt z36-3qj^-^&1@}ns9W?$s)pzn*p?#jRD$+g+DP8+4?@FkBev??C_W4}Wh_ugZsKZwf ztoCyG8<#IK)3wi8D|y{;`S+&-XrC(+c(wyf_ZexQn}KwU(1(beK|%Z64|rH6B~AN0 z9^~!_or8ch?emi$^BrnCAg6u4?LHNIjtHLm5YDHL7ipgtwNkNZ6xUO`K=%s66x?Z_ z6?5y=no;TlmIFA)u-fO7>E?B3p=yEF7lx@Lr+q$jqf9Q_f)qMb_Xv^p`QL6TCauU* z*Fm`@qUi~^(>@=#NF+T7JU609JX5K)l+`}B*K_%I;jE5$R+QB~ADAMdwgT^qC|ZqP83B`w+=qrE+I*OYR8cp;X zUfgU%s#{^)=~yNcP80nCilmc-^(>56B9_jK(?lP<)UwvV*buQKQ>ZMgCVDHIq3So# zqY*_<5D7N{PK+ctP4rL*TEZ;AXCets6aCl?R>D%i4^dw@ET zB)$jS5lL{G=qFJSmKH+nWAuMGR|>0%o{QpCOQ-}`T?nR?nll0M+QGs>RzeHFHt7 zA9*-kiup6(o^*oML@Sz@CM4F-7I3y6oF;k{`c`#1Kpg>1gU~OW(?r*lHD4>xu9=Lm zWm!#hNfh&HD3sBT7HOhCV06%$=z9TY3L$J%Rug^Og(~)~G^&Mw?>Gr&RB)Q;9!*tj zm$1HuvE7LY#}2EBt}#tI{DZ*pwP8wz5^AEqXO*Q>I~77rA*B^O)I{$cV-sr$p+gZ# zP7}T487t~)7{i^YNE3ZVDCQ2p`<)mFRuetz8Y|&Nz*o~HXhNmQu-WuhDVl&}8bY@xM8+jCk?^rz#XRfE!`2rcS9LrwIXOeJ*UmqYEF zNoVz7G|^>vqcrJ82zOc{!rVfB>UwZ<_C!C1y#tz7lkeW1th= zKbxVgK&{3&0sB{wJq|V16>6eipz(PsScm=}XX=3XRuf(47C|e6)N`nQQH&6$iEhU# z2K!$)9UTuTRukQlofJXveiW2 z+)Kz?A?_*RoF;mK&eN~J z{}iKGP4xBHyLc+eD_s$1t3l_fma>}YXPyvBUEm9gQLHBVf$2i&0^Fw<#cHC*qN4QF zSm4_;DMk}rOU*wQ-SQk2bmsHsY5|vY{i_fErhcKP~oZ8F^Ugnw# z_9G}EvzSzHM7$s9&;*Yw4Y6l`2&`p#CQG3c5Ho)LpVKep5x!kqTboD;6<0hrcIJYVv&y z-rJMlXMoj8$A6&P!g7WgoX*ZAV1PpJNgrpRky3x#;SMW?Ub2zLi$6)F>(C3RP z_3;n5YWkB<=L+3qyrb$b`1?zEYJ&UfeZaMmyejfQTByA;jbC;OeTc8NgYI&SSV#3W zeTG^-uvI9+U(cymoXxznBcp)o$O#CjD~_TxGpU^ot%0K=>nmw`D{rM^FoX_(m!}h^ zFxgTc#2A$gVL0IR>4Y+@_|>Y4EY=O-e!zz#LJKuQUX%}eF+=gy%K)!OU`I8%8Q@13 z+opv558&77ge_9o)dy0c_`QIK9U-aftE0MF-hz)OxLoFbjp+x@R*7Z(Mt!O^7qUfT zvU&lG*2iY8J;zmVUl=1ZSxITx)ZT9DO?`5Dk5J&<&>qR8hOAFZ^bA?A!C0BeO4g9) z-chZWdEB~|Q$y-^(0<9JhOE!}^bc9V225XZX{8Nw_<&6NJ};Em%4PwZ!>3PyKmHP-07DSPBCnC?m{Ky86jK`ohH<%pq zSHoQ&@#U9vDC$9x`puZjL)Pyw;u~F2BdMC-LgmrHsPEb{@A6eec$FO&VY8%T{eA*1 zN}ivuE&yzqPPqRz2wNx7nB=g8uX+IXj|eT)sa+s!fA%sFKMvqN0rjhGDzLE>P%fmV zxj#HX%atz5S1-U_oXO`+zgpg}AGadcS8GAH3&Zq6`bE~4o326PDD}!5xIb;CoA%Y8 z5l^>nhQ`K>MX8`PsVB@2b!?#P%L-1F0E5Yo3Z(+cPAU+=eDx5){GtcfHfq>Z_QJc$ zb%mnO94KWGpYBY|$3g3>QgJWVcBVv76NK;&KJ&W)4b@qTFod0@SPSy&&jJc9)=+(u zO`Pr~{0#{ghKW>P9k~%uei|E{e+Fh!Y@^C7Me2`om9*49E>$i4LN$Lf0_y31nsCx) zE8L{eMje=ofdAyG@$(&S1;lScKnErNG~r4|klWaFRjmx^HrV4OL<5!>elC|A2})eX zrQ4$d)?FTddJCoy>g}y)QdY*_N3>FEhMGh}tNVHU56QV|FhhO!9QR+?`{WGu4-cU3 zdV61XhD!D0enS+$+c{pW?nZl${AGubzbU$}mj%Ar#`hjnr#9k#yS<+{_CeMDVgi1! z0iWDFQ@uEVfFEr@ESRb0^dZTgY(RbT{JKQ>Im*M^7jVBbx_|gn@~|tqzh^M`?)Xru zO_%wTo#4Mkd7Se$_lG0?6M68DMEAp2f*+0eD@udMN|-vN%o7fRd(r)@wcH0KMw;|` zsB5nt8ms$Zd`@%Ed=Q_IK4W8bKaS6&atf$m^^oGnbrAY#{O=Q^pfjow^lf}q?lboCxew9b zB{nL`&~W3X)4kZElISv69|=?E%o%RnOU~7|gzqULMdvCs+{mV@RlW$v*&In)R8LG35un{oLPKh4r(H(`If@MH&2 zB3Vn11b5|eCX#Iiy?Xyb{nQ)O5Wre`+=T#b$RR~B_8a2Uh8#MGEj%cxpbK#l;>`*c zQk+yUPy$XX%R+H3_s3_qs{14TxO_x5`vGCd2A+KEHM_gSs-e#hW%s(H38Mf+^*qrR z;_}avyAbcU@*@@NO|V+c`zcDf5swm~Yjr6Ubj4FOt2pv(e8aIESK&_5H*h(2D81|1(UQbzVV$E0e~kR z=w8U(yhhm%wlC?$o}zlx5*RBT%e)(%)NR8dJ<{+v+WscMUm`;E2A!C_NW}9`;`8r% zYK4DNx%`tlbZuBaR(Tx7LwKU{FtdVdh>#UrL>Us|O$8mqD|MdISb=B|j?Z57!f&)@ zVaS8lc8A&TNsH0uIN9$@sr2BRy?nlSWt%p8#T(+4UE1uGG8*genq{wgPQ3D=-|P=B zArJbyX4xOL6R&iZ*{k(dt8PqdB=>dH86*5y_9nH5tR2AROJ?MwDmr|dQYC*v7|sC6 zg}@>Dn^LEP)QM30xOLovss%vTOfdO2@r{tvOcJ?D4Tdu&;;oV-EP94g(?DiK=;vu@ zeWm7tyb+olJtLxsR=jZ`CG-61->8c57 z%haE3XsVN-+!xWbAak%Md!1U&Eb%cOnR)@nD~?63<>XKHM)lkuDmGULYXH9x!X7Du z{Vj*=ZR!E$zgohtfPX|1%yw$_FY2W-o{>=cXC?tSE5YoRX8)niJJpN5BT1YM*gy!T z{aC_b)#N-c_KFZX0A8LhLAFz~?Y+FsG>cIH zw+X0g(ez!G(Z`!Hj21BybY3PSY&f!=nmyh-okfm%7s^UUqe=9j4QAirJv+{3<2%5g zgkYM4Ir)=4-Mf8={iV_W088w0gidM*;>)%;m#M0%NO(2D(z0o`TC?Bq0-pF}sfy+> z+8>*>%DaD;irpuyt6+>2md=PNaxEnrve|3B5==rl{|P*^2u1I;W`FN>rP_3A3n08L zq_jL4(mwB%cAiP>D+pVQNHQC;*@wL*EZ4NCLon1Yp(rX(js|51{_`vkb)G8%Ru)27 zd9vS{eZ23Fuo5l+Y?&@W6LS1NHd+Zi0Q;v)_^dq=s`#IL!LNDJFRNPsC#Or$gfsmO zlf0NrZPk;2b0Z06J2tzKf7L}ipmzX1aCBO2$F=PA z)%z^zHwZ^FNxDSTiR`#$|LcD{kR0axN_~hkjZB6F7+rf)Ysp~J7Bbfmw25P|_qTsG zVBer=e`(1nkO2f}C`tBD z%if@#+911WtKe*jc={|v3d&p~d29ivKzOFMq+L@Xa~LJdR#W8|Qav>acrs2eBIKrtUWM2g zo7?e2$2y?+EUS13bFC}sQBuKTmpe_!ezGLf6E=X4EHTtue{BR zHIk4wxxA0Fcys;BO)c9ULfxV9O<-Fiyg{#vV=~(e|5J^JsDiBE2%Lm?`SjZeCaT`e z`q#zF$*)6uxA~%sr~KvQ=b^pv_EwdX--q@l*julh{6Mrf(cb#yzM>I%lk9C!uE$Vr zC)?Y2x#w0EmNfnLV@U21~$6#o;i zUdN+*neGTRf&4CcaW#PsHEMzm5S*Ie527E!}7%PF^V@LN!6oJ1Vw8NFyQK8j14mVDOh-g`gmB*AEQN-vJ;_0f;gtoo%+?W$k$=vMu!x%mv2FY(h>{o4rp&4nii zf)dHD`i}yXBE&=rSN$c?`?Bgk3&5`WdzQ7Ue#uCz*9T)Xp?yS{K)6;5=sM8LM)5fh z1r-YR@5D)nxA6ROTASPGfYavcQo8dU<}N(nVeZ279Xe8TRzC5Y=Se2q`Hm5CXU=!% z7~1f6l&-U4+Fap=+T0v;=+d`EUl%%wJ%^gO{AOfOB}H0NlBM$O`Hse*EgT~ZpQ1Vw z*2{$_FOf*0HunT3o?nx$8Vli8A$1h-;6|HUrL`AZBlyE$Pp0EWn_C&JRCkH71nfP* zb@qsFw7IPsd$C_7{zkAL9UiJr&H0W|gRGDv5Q0C`gcxn^y;oTwr-0RPcqqhZbB~O+ zLRvs5C`K~c+**HgTuZWZ6@-yO(!~uW8Ex*_^d7oQcR_f#m?WdkeW;4f(<>0(Ehfom zb7x#@Yxipi+l!DwZSH<)ynh4w)T4d6`oX$)SfB5ZHlww<^5p*qM9UUNRv^tO6|_TW z;(feXL7{j}sMJALaBEp%43*$A+~rW)0lD)X`}o$|G$MFv9-NmQ zkLjBIy3p8fRBRBX^3-b3&xBzL?#_4o($|B58PV!fUgm@L>q3deB55@6l!zknOr^T> z9bYppd1@A%=OdmKWzToiZYh-afj^HZT9j_h?tDk<_aw=ka1I`eC+9OHFY;f~lK&!5 z{!4Aif2kAsFQu3NQat%DPelHYrvT9_BIi4#)fNxo9T>vnOpJt|708tj@JfI*-INV5 zug1kRbvfVhzRxa>F!eiOzb+(0OL)HHA$dP^H~+0SNBs7D$4lau=`3FtT38nUq-C5H z-|EdmR(QUnEs2EZJ35MACb{9)h4grldA>tR6`t>qj78@=`k`^qN=Ic6Sn#ExZU-@f z#pSPpnsL5kG@;`il3WX(e!gP{(Ci4-k3Bly@hZqinP_qY5{#JWe8*-uJ0jk8NyMU@ z@AwBKI22|s`CA&w`HozWY7tsU-Gt)9^Bv~{U*afkLTJu+oX;-aABa@FU|i!^Nu3FI zzN2biFLqE^lVRK+v2rDcfRBBZz^^Qm80@tR1(&Il0~a;I%6qZ(G+Nadu!R#75)S$u z*|OLsgzkX-A_?w%M@81GTEfkMlOhT3d`HVZR>Bj2&qfm5`Ht3AsX0mFJ-}6w1b4pU z-mYHkHz8~V{5f5MJ>PNjL@PlZ=KaIjR_e}o^e$y3R0gaegs>j$`Hm%+O6X#?1iUnz zV9$5_T3`wN0k26X*z+BypcK`aoD6tZI>DarxFl%_a{*sUC)o2HHJKH}oNKkP7QNP;`xv9=OVXf?ok7dw17_IyWks#om>{X1eD7tkTP^Br}rhEe)I4ng8IvP3i_=NG3^_h&r+7JI<~~(i5QE6VYTqfYG%#ZTZX+ zC$)m{4CsrFVYQ8%?>OaEnb|A{`P8ANy2A4vV$T zzY*fjcl^Fpcs1eFaXh5h^Bq&Klr&m{bVx_-`Hp$-OWc7VH#yWi*Qk2k`Hq2~3wb)k z=l=)Up6_^*r5^J?h@TfB%hMx&_I$@5S|_^`&e3D=l4ayIaOXSD*)KUL@2OZNTv}^@ zV$XNH#G1}i=K)_-j3RngzBE*V?#@%)fUk-udK%--ckK5}EAi9>DEAbj+4CI@Fandt zN0>N6FLg!2cGb*z+Ate-KJJ8X%uq4-2oeT}#>X z9cQl)N(12L#VGcC$05B~=n8ywCM7)Iu^*ij=R4G`l4pL6G4>cvtA^#KiPk*Xn%Dl~ z^XTFsOs8L=ny@P2nhL%^P(o%gD4)dptPb5NUPCB)<;T})2NpE!TnUgF@13gE2z0gH z3_rJ&ik&s!DXQS0uTOXkkP{x>A-@J(Cg}cIa>Bz~=ZkoMfE@Ag{`D`>V0C|hobm7u z`(i&Uhdc(zArJ3}KleJhPx%Anl!tfJ-gou&uWxw&+57JP06FL3#R9|c?GKQH9-Q6^ zPkIcHlOCR@?Q^{)*l{p{Ee90#MIGed@rb1p|EmMuqdV-il>q?E((!a~* zz34yux>!_S3VeAH3d`e(8r({A38=-T7=Ol)zn8eys!Khm=l-;x5L}zxJZ*T8{T@q#PTppK}i)W zg)@bNA%`}+ul;d*LdF@OwbB`KYQx*$?_U`*T7z~-XRMq;TiWRFToEz`gN{gN$iWV8 zlfQ@&-Q@Hx(1#tvbQd-C5f5*(|3>AI_8OG89F6SC84vFp|G*U?V?F3L$4KfruBi`s zcw7AHv^106VJL}2SniM}r#!rG{gKQO4Xp~4+Q+7S=jYJd8QP^#x@FSLDT5aMn3 zS7R+;MDB&6vNFmX=2Fgjct802c7(Y+8Q!@?xGia~roHLI9yOI5_V9l8vGK4ebRx#J z|F>8-v?bPVe+u?>CSTKt@kA6$AIy;FrqiMza@@oF)jw=|0e=4&@&{3b99{uv2Sx60 z{?9eS+-!yNS44~C>Ik*;fe&x5|1nb>UzI+N_aEn81Ud2H?ehn-fn|<-)CO&s&X6M? z-hRLHS1KkuQoia4+BIU-(&sq5KmBcEJQchJwfx` zDy>}nf8E!(72(I+*O0wDYo#vJgW^`|ZHO7}Yg~**Jab=TpU6F)f=ULDxv!B8n&%kN zzQ&n^o$JDr6^PHI-&m}%ZE#fzOS zG42CgNgjkVijmB|#$FaKT2fO8ZH1(Z8%i?!8jpWxCH03eyqF}juQ92!m2^9V z2a8EE`x+-Kv$gv>v;2!hMaa7$DR-z;A?Lp03seN3%t-QkOQP_cf#){SSy{FAXUb zoXTTKJd8Ihs3BexDy1)2gp!5r=YvU_l&DS<=W89P?7t-%>rk`({2v6j{d^rlZouW| zmf9 zejd};i#3x(uL2q>Or0~g{T#zIQB5R#hG4ovl3I$+Rk-~eM**Uqhw*wQi|QFqM~RjC zdVn1`y^4^VCLKr6pQcN^_f9H9KW~AYho>s{%>Su}gm|%1*H;P13hI;lR8Uz!@zVc= z-hzH~bnI9EPQa;xrR`ViXD>?mdi~@f*!^lLl-sYqft%ZK`4ZoSU#srtc9siI9>7Z^ zyI=h>cW*n;HiKTPYEnP-25kYb`_*;v8Y^{*VvW=B87p-O$_j*%3jXDq5HH&i6ekrN zUzULFcnh!Qf|dHla`fZIN?jPT4PmU*C01yqzGIvh6Qb%s^viMi-^pEw_Zx>ow* zTB&dP3&O2{_eF&04Z;###Pd($^Y0Y$%Ri}H{z)CWHmo13JdWZaJW+X=SwUGMWCgz< zDMs%arUR0f1E*Q3uL0Q* zq4sfGEA^cKM>D}>AL1J!k(GLx92GkmXVOj%kt8B3^|L`5Mdvc6xVEwmHJKfz1Yo&R1d;<%CV9YB^hU>-n%-JQDMCeP=ToNL!{Z8V{`|l!g&a3vyQK^O#yRr+U?8 zFbW-uTw5#k-&k$76T%3DdrZyAJPfdN`2p}tk8sT1TZ+!mBLx6FIohc2XKaf`Ykklm$OoT z@k>}WKJ9%bnW?(k-xVDmW%@J=Cwl_|SMSgGF=m{pv5 z7I1z<2(8phax_#eBm5J=(z5BS)Nkp>xFRL}8O9&SX07sO5ASundOln;q^bt~8o(yT9H;AdTPHY^6DMchXEA^h}0CdJ@ z!Ps$)<5^`4R3kz)rwGWz? z7Z%1)ZHn6be3su)@>BszjUqJLcWT-Kzvk;?tSOW(MQBk68d|Ae%1f{NwxLkRWzs2( zu~J{fN=TEYLwF{Wq_at#SS$6R6h^%TWmQCz&K`#B8)2p1aRZs#0{Vkvpf=b)8?bMX zDlaYh5J;(tt|FpbJ1g}?*vWaSGMuwBd9lz+eHaP|PhAAsC6i%lzm~FA>hG|8_0$kJ z6C$2|O6kd7++16!zy2mqNIe4a*@!GW^dr_v{rfGZ2V?&S%I8AU&EHJpL=#PEWxob1 z^(O4^VgCc?&q$oKYbbNkr(>l)n$r%R%A*F)#OXzZ+%(av5c?9(?!aV02Na)W6%S#q z#ikl_tM152jMd( Ll_uM@8!q+f5(49*H9fL|RWPJuK&tkfSm#ZI+a)|Xe$TB*;6 zC;Jb@t<+a(#966JoXAT32;d0_%onLDDWK`}oR#`%0B1M`ZPi$*U&t6Fl2uc%O9Y?A zMdtg)O1&m~#ajjMMex7~53SV4qH)*wtzc6kTwA9z+YJ9xjk6KMfpItq@fNJ&-Db^w z!D*DZ*qXcGDkhg^&D|2OTXXLq`frjCJT4@iNz;_k zo<}FcPY?s$S70oUSW;s1%)&Ky_Lclnh$Q+AtnI?oIdf}nbp}%YCOkndY+721&Q&Mu zfN5xBmXCvV3XB?=EVIVw)YdMc#X}2~f2p7idC3Z%Bkfd>B3eScoc|8J1r=$-te9Km zv&IlCZN;pgoLMpJM=J}9di^C!ZpHi}H?QLICB6&4R;?gxoeNL41|^bRF>eL<&4J;H z`QF}=kwGUwwJYZSaP*2vxjtG^=yCz(IIr88E0 z*2RSc_s#ae(SBE)NT9hlozD77^jA)C7%wc_F>R<=u$1&XCNj z^uk-b&O-W{%g;j6nLO63#1N5)fnn&?)TE^*LvRE8dBr2RP$ zt*#zTBr8}+tb}+|I)I;OCm<{MgWRWrZ32onEBH0^7D$8UWgJq4rX`p(E%&aSD51D~ zfz#f#+T1pF;mPapM(v@gv*Hzy);HIBy`!8i85!JIQ`NriZ6RYOh*i+l=b zRbiN_t*JC)uR4iytcP`3nu1=EF5^}D)ZD+-W!*ve~dAHzanA z(qJhsmlwh$d{jVrV*v9XBxce(itfNPtBTd4m>SIX8aD`Io+qGGEOxA0Qw6Kc;Y+T7C*C4DwW|8q@^Nwss2) z_Ec2@8#o|2ks42)!HbGwRL33asaC+9BTAh#6r-*IAR{950)sA-bZ_z0M3DO&YKIM@ z$jqJRFQQ$wAcA@U%3?=LwiY3E)fSABa;JFnF-np-jrt7624RIAsw_xy@9;{X!j$?` z`vCuOVvwK-_j@ldH}$2;)kFz|vl5K{G529F?~r){svck?A(&pl5+3*ZvJEFSu2O*A zA_+$SnESMs`W^EzA&dsRDUx6b^Ssadc(L<@FcWZAx&%>B=Dz4vU>jLWcmr^0x&%#F z;8pvC*_lY#2>5-v1ktJGzUHkeX?1D`0b^&nV%F6wyWBUtrYwm^F~q7oz)I-^(H`c$ z?Y%=6p$UxvTSNq-oydJF7`vVHy8`qVP*+k?o*?5+Tjt%lYvS8D1?a0Afu}|k8CgTh zrg$lI;l6qTctIv5sd;s^(j@m!@5v+fsjP;!K9kDB71c`aQE%;f%laM0zY$AD_K>wB ze(CwPWaZDI=(sTR@+MkY<^4x7$G?Ht6KUqH#AGgwG{RP0qj$rx|%Q~(^&TY2seFkHTuuONNJCVBT zfiB3(Es;+P)sOBk7+$TStk?utjs171dR@SiVN@5Ed4>h%jnk~A{#7WEb!%?{qac!H zS*J_4)zV*ty^fYO2*#*lvNWreKMwOGE$bc_j~0{lWqoAb8mz(4xEYnK7QuKwl4Z-N zSx*E*e`Q1#)@B$xB3YI-bqKOfFYzcdG+BJ1+ETHSIQzCgtkgUv{kiukGYXy!)Ci|% z=5k|a=B7sUq`ap3;zMG*@2|(!M9S)`o)Aajs&CKs^s3L+pp2M$*i7n}b=BRCn4Inn z<}xJj?o1LFV18pieO9EtOnhMU1FvBociNg9{z_mmvXvf2-kaxw; z4HRETFC5BmD~=GN-(fn%$-8a2l zpz{VxIrX+<-YwF4^tNN(t=cOy^t{`oC)7%!yb03m?^bH$fKjo$JJeq!dIXm*xx)O~ z0$84xIfqvtXAm>i{RYWJUaIN=H;pL&q@$}NiY_`?VSdGC4v!Q8#I6)X)~C zc|Wb@lyepl)e}%(i0C>gOZs!=>*xG%S)+QbfcPZVqMn1I9Cs{JD1l(jh$+f zI1jLCIze{l@&+m|%)=Fcz0(OY0Ot)+&#^MlJ%qTo!JN2B*lCTa85cw z2H?Cg>H_9En(z+biilta;JnG|y|O4AHUa!3pl;$xX(>ET*}KSlNOk*&ha{cke=thb zbF92H)@(J9u~oB9hfybDou0;eN6kK9E0vEZ$GS%>JszeDT&A8s!&dJYXj6+&wbVf- zhg;Mg`>26gP@a!yw#~|zp0`i!KG_Oe0b^anN}C_#CB3EJV-h8`xeLaDh;^nZgO*j< zo66pve(uTo)P*=xYw2UU?5yNn;QcPfHVvUPaWv{x2H3nyz1RM;sTBhD6M}w^k~TFN z((}4|b$LEIwVPqw?!;uUdV4d-`3lMT(=ZkklO@A&-Ux5~GF$trVXQAEOS49M*)%#W z>vtIc7Lz5zaNc5urkUh!*JfC-cojk^f259 z#jlf$V*6n z#h@o%6B=E!g7P#F8=NoRyENHc>qx+O0t%!_vMW>TTssoAtS?hLyDQTInjYF@pCaSi zLESatc4Z_^v@0_m@EKgbNL6~Sn50rg(WXBy)J(k&`i^6`U74ZNc>xJl>$z+Zyq-vK zyE0X-$M{O{16&SAc(^OG;xUVtC)&w48((%~WH1i@Q;Q9WofVu9Cn4TKc~OGgADWy` ziM3wt_m!jhHOc0cnQfh;E`=v5JJIjw?vR<7HYdvcSqiR4@Z4Q8755Gw4`I)RLf87a zy|Nsyqi$TrsI;FShEcKCaQTvq*ahkEzm)obz|S3EG$l6HLA4!VPXx9kE;Uk>cQE(J z>zr*J2c}A%$4(e7zd(y-%$ZM4JXI3)SAQW?2dte=5WC*o66)isUTl~U+5ldbP7uRg zj@s;Q#;4pw=wQGRLNK|nt1WwT%c(0dVVo=y?gV_u5sWP@`~8wmo;s76q89TCj3tgm z*P{uQ)R=Ns%ol*)IYKCA*zJg^p~g3~qt8Du0Y_b$V^@<`o2Y~(<(@b%|3jRq>P7f(gmI*T zh+J1c6&q*C5|ZFy)QK51WzgawJdMFr0&{YG-Gk7C35c#)!62SWDk#+$a0A}Lo?I~h z+;D+2{}hJ2#m4+oCf}j?=hq$h=n6ztK=dxS{BPwh#QQzNs~;6GU0n17DF z9!;0v_i%YI!kzi&T*6+Ga3j~5e=a5LV;7#>gH&qJnty%+@N)##H(jU($Etq-vY;D@ zx_`}xK3?U4o)Iw)8rjzT^IYyOa-iGLGUlJVZi&Tipn6mf7*{)%>BK|x&x$uP{kjG4 z-iQ!w=3?S0;`t}>`FAq;<)2h8|D+Dxd#E>7UEfO-Py}0k&3nXyjQ%&=JN~YrPk(iqj-(Y=TT`c z#^y61a&ena$+ENgoYsVzz~xI0(rrGUBJd>#B(s6jY(C!uSrei58C#prEdcv7!Q`pL zH$ozt&)`B8D}ys>Cu>L&k1tW)VQh<7k}0%J*5oN5=XriervecWdnvk|k?PNKwPK8o4qG>_S=5t|R`X8!ST?C`8W07lF^6_QjRFzn) znGgm54iQ2}DMMuQ`67domM{hI?nr{O`D``NN|*=uawNg53HdVd%!~Qnuq5#j;JQeH zB^*}kE~QR{unTZ+x&&+UdBH3z;kafhRu*SlptJcrgswqLI1{k05KJkY&FAIk*-W+r z?3_-pHlK&DvxI8_N2L?2&F7)gHi>%xA514$o6m9cEMWoQ;&g(w`5gR0EY?Sg`5EAb zbb__{TyvHs>;wEKA~>7RwY;wCgyt+karRBnuamR+oOT+Fb3mJCGQx&qZ9b25gjNWp zr=!s%tj%ZrVKy6M0dEyTSee%5a|_EFJ@t45aCSrpZ9Zo_hV<77UnZFDEKI-ZY(9T^ znzvV~;u{!0ADgwx`=^j0M_8(b;#*3{(it(boXuy))9JWWRp4`qP(qu}CcGv(wKfpC z2q`U3q0MKDsW!2p5XKdeyqjuQjH+I-%bWhHzK z_-(obO~~=DK`o|B{WsvzbP3kx(`yxr$ta{MwB+MyIQKSKo6lkLfm0!z57)HlK>Ns>Xs&iWr5`-8q}jQIEiQ6!a;_U@l>7KJUBN_8D)1t#No# z1|gG>v-v!}p{4!=?XMzKo1(S(?9RriI{qT8zH#;uYKgY*v^JmTqQg=3ptLDMi#pKI z=JR#>K;5_Xg*r5oPGOAAXP3JyX)1(=GfBEc)QPqEOkGLRFGG1NqREf|Lo^fEe4d3c z^%>{}$6!BY|7^g%L1&tVr}lvS=TI~2kr5GIo9EyS394vb?!_ur8JFIeLz~a%p!59; z&^DP2Q~S>5^Nfpx*Bj25h^Ol`sx0?q;`S|sd^f~LBC_s&oXuwiCK1xbd1?`q4}=!I zvPHg39A{|q)D}29BXQEMk1bvPDmaO%Nem&)R8UpCIoexWyoQi|y(BX@ zE0BOxAaM$gBkw_(!h@}_*t~=txH4CYSL+6DV})6!XJ1x%tY=aEmAOi(2Z{L90vf?eXy!sn_B2GdYfi;it=ISbR>t(*YY?;Nc1nU#wHB<=> z2$k9PRzJQ-CGp3BjTc-OlGW5N)yUo64(tu8nS{@An5lr%Oa%l=EdqHzLd#IO^no&; zDw9yxv3$~1uo=dVA}sx^mkqU3W$`d8mb%XhdQd4@!C0;-?Z-SxhnzxQ69N`WIzgFp zt|g#^eu#DLLu{(P{f-%A1EmVUuEgaFNhJk0MuU=+wjQ);RtE2ui$HaLRqt+YO1CQT zW9OglowJa_6s$TytCc3Tv2*N}_4o05TD8(6&~?)(rdE1QBTlU(aU!+SFM$8z@}o3{hC3lY^>VD$vQgG;1Vs!-31eIj@}f;&fes8(9QfhCO( z0UH_NqE3=;mxTYReyNG9;66AB@pe1e*3be%!Wxn&vBJuN)L(cA!25w+zWT3Dy?}RK zK3Z6R(V&uevU*iuZEoHfrm-fuR<%K8h2M`kkfbt%TT*W~N%#oKr1ZLWRy$E%yQggFoGTbi)6@9G_*_O0WkwePu-1KYme z5x;HUui%f`_u1{~I&t|TDx-b3CN$-cbc zGkyn*nZ;z;_MOiFW6BTXono?V`_5<6Oy~Y<7~6}V zuhW$<=b;tLaUp5Ndpbs~SjS6i#Y0FaY{e7AZ(H&8_@h?*CwKqi@x1DTJcm&&_5=cst=>Fu>RBWT`T@I&gZv<&;_u2I>EN$U*Ez$y%U5nfHw=l2`EMxoGDMT z3^_!WZN=aHXA`RlqoJ^Lo|uLgb6iQOv_`5 zrO*mxYbwZne066Usovb0d+%uMZkktSv*i0~&_r1(tvB~ceRf3}UG8jsqD60LJzG&Y zdP8fT*p1dv)0hflTzxa)lW_SWT9lqT{3WGk5;(^J#vavtY9{xUMX#{%22*cySuUh? zI<}dh=f2(z!{WArf5T;aI<9x5-s;BA*Jg?FFPMkNrfxnple_HUQhX>x;#UN#=5W(^ z%%@~>S5N(eo(4=c8Jm@`Tn&He0$bFGlxU_%@p3eme!8W9rpSq->8B1j|}+MW4qp-oi(0AvxOH=v}j(Pok^ zQ*w48d7sOLI1A{;*nm0<{(1i^&SJ(&=-2PWWrXkq#Ud`HpJOU`8p#P0kbadY-J0<@Wf}DqoNy8~`aLF5-7c}no-{T>W*5-%PS>o!K$^(>7I!*%_2En!!%F#Oq_eH zw6h&j$&=02SiyHpMmUAK{0eHQ*eTR4tX%9VR3W&db3+g_5|_V;P#4}xO(N_*7oPkc zlt}gz>QewOJJ2a>%qi6BhNfa*goUkd9N5uN-*M1)7@J|Bo>f{=dY@=rwi(vbF0 z$VA~qydqjsSwbu0OeT$ra0SxnZ6>nTO!T>6Hlogj(K=#DiH$NLJcWA8Ef~&9qJ3Zu z5~j`>QXX%Elxrr;1iP8=dx}WWx#C%}hng7E|5{j2!&s2XGHSfttmSnx5)aMjBS;DH zrvh`8fUH2CUMl!WK=Eb;dqZ!*CoDlZ12^+ZTDxG<+T9triiB3iXgs?0YsU|$x6*Ovic>vWM zSft@?W|6y;*s2+fcEai>qLY`1h_K;(Kbo1DkOn{)5s}&%l4*FqJz^!@0pT$r=}aD@ z;XO4KQ43)#i&#?P%!W6CrTuG?=w?{kgsF4p8eVV**k6Q~Bo{UX|Il-mYeJ(G5>LJf!B365>w<<|+YM!922&3VI4C-mKv2&|9z(1s@GB*@K2BSVqH} z0qrqdzQAb>Z$4p5TzIlPXw>jl1AOg3*YG~ORX4o7Act|f;l0m$Y-A_T`66t1l5ySe zY?+3_rqd;jgm}Bnuzg`8Lc*TesNxhB zOY>t{;)^|^RQ4#%(DL9R zzy8v}UhHuowVaEo4_%GIIlHj8nOB>d%?x58{VI}!oX7n-eZqzGlfIB>gI;M#D(4w} zuaC~=%=P6{__Ch?>~Em7duS|Yq)%o zPSC6FmHsXa>{^S^UjhFRg2|#?b+7UFeTkWvRAy-^?j)Qcgv({U>i*L2gaw`!Qx8TX z#|l^7oBba+KBUE@0DC(^C`PZ8xBEx=Hk@XSgE2)|y1*ezuex{mpS8A$&4w|*m@K_g z{>@)n+sax6#Hf@KU-jR|dm%NICpnCi@JFBhJC2X8b?4d?D=2fATu8^oxnuf>>oYp3n{%rmHV(m?b9LZP<6QN zP$hoUp*~7Rp2Fo%BRHc&T}0^n4l$W^9qROD9NGX>o4ITg);&7D>rfxP&Wqh7gnzks z1JVe#L+#wriwzgT$$(YT3ARI>e7qNXM1(d0yhsQpi>^a`6BUxwv+4;r*b%}$&UUCR z(T{5}lVIHGSW$;M2Nj5e6_H83^^OBXm~*$(yk0-M-A7)Of9 zvK?xVNjAk3DP9#^rYzf`UNSr^Ka4iQ(&Z0Rv>obKBW*qRgE6d#EZvXFvv(d^aeqpY z6-Ze)en*6acvCu{+sC?HSM}Z`+_dY{y=)9=V%eXX4Qv)>Oa;obI53=BD0~Sz6gsb^WUa8m&i-6W`t4X4cAd5I4O7LBDb-#o3T96 znyAPZE0p;N<@2s_<&)V(SiT0Y@tJI-t8ciNAMDkI5l)fvWd_9x|1^TTMS`Up2?f{Z z1n3Dssy>&b?qIZF@f8uA85HYwNCcM~sCE#up~^!gU2d?F+EvpDaSQ3B=q$`dKbMAT z(GPr)Vz82os-+=SW&lZVp3cgtg#3@JY@R}{Yk4{=Z9?j?v$7E*EU5pNtURi!jEcohR;Q~WtYcnB(RHeL zWQJ94M~rD*dlkQ4?t@C|YYyfq^&-i>fy)=NO1{lC7GfU~{$+$M6YMk{&%2?d`U&J$ zhsNru^$7HCE~%s%ln=QK&d9Y>vd5JA1x1~AYspLbR-YI$DX)yKHiZf-)=2nkxyTve z4a1Q3c*!v|J!!2fMR;#VNNO#CG0*j0D)|}HWBDx&H4erUVVUB{&t1eGSL&04wCiOh z_pe3vlfWkWETu-@2k>gip)44c38c4?0;KHqL)Zxk$O^>!sH#B)PxJbh6a%jphEl=e zkqS1yd^Dis`{b4i_6L+@Htr29DL-q$kIws*)az`bDRl~wYT)uEwn{GKO05d!4JxS` zbK5RLrRe6TlBhfVTS-GpeoP;ytAx7yf;_2V@b8G?NY|=O7j=P>Z-d01z`#vX*L?N3 zBijc<=>$myi$N0N&CFR}Dy4FH>B3sj{1J|8 z3a_g{nu)1_*a=jn&iN%2?g_}*!QZ1ff{!m1h=f$I2!BGn{G=}B=7-hwb&UjzH%s%f z0tv_pUMwXcI|VF3W@f80T>ZmxKb%>%ntvMFW_;XlCvdhp$mGI5nULxZ7azD7KhIVz z3cxQQq;(N|wpx$^DkQjH5onG|F(dJBA^2(ajOx{Ec+7vD4vN3oYJfm@13ltmiH`(l zFs#m2lLdc?kT;9qvsE1_%SQx%<)8#UDfb3l?ycMOvreLi%&hJ&PC1t2NeMI zOlN_fbz7OtL9%p(0;k&c}mr01>bTrPpxVm zi_KAcnf3Z5ufwW9ar%!>v~2)dY5amiptFknVS#e`fG1x$dbC?ZJ_42S_G7*GtD zK~X`yGOh_l0YL?2fkBA^iUhr#J>eQ*wRo&Iy z02AEgqp`83s{=5>z2XnVQj-2c^tqGN3(mFg!7Y)CP6>{X7YL5 zCBY!!V%iV+eW&L87*ZwZnL1$bcANipF6a*D9XKBnytksV z?xp1aR3snQrXmZAlSONBnp_>5@o0i$akA(pQxAdDl8_uVCc0A@pVCLW(*e51pklP_ z-e8m5S1VxfiOeezj*lsdxe4y1n+-Vd&1|w8zC(~ocd|p8hFc?L z$FD}&c7dBs^2PbeQZG4uJZ|?w_YpvC?!kCV6^nA(y-**B3Uk`MFfXS)?2w%FIjNVN zzIL^x$TcN(^L$;Hk)va~QWu;E(kVu*Z{w~}ALFi`h%bvF#qh}WYt=fB*p9w_6Owyk zTruz_+iNh=gHFK{NM4L_#lW@kKkM`eP%sC{2QjXg^Ubr)w6q=B<31d8Fpv(Msj*1E;lPL>PLIy62g zJ>7JSn1K%6(aXACbI{Qn>Cjk*VsWO!EI|*Z!kIq&WL*)@K?I|bX5$2kQRKnL3tz== z@G_EIj4K9y3=6%iJ6h>iAo)7REq!vN&ARGvgWqA)x;FBKX-Tpsx#=aas=Gk14LB+$ zDwaPQ|A(<=qWg)a>!t-AfP2Pd-3N1}I!a3F>kpVKewuG{py}3ODacJe662Qu~?cZfEa^+dpWIybZzkEA51Ir8?%Z>h&t) z!gb_#4ub1rl45ZgpT;VG*5N+5r5ixHF!B4HNc<4eNpWJuXm&l1q`4oLe%Vs!E>`9e zKNsNy8Z1P*E>59X?3K?gL91U#a3VjGTwQu?dSMX!2~cBjR1RGXcBMK_W%QA(towcw zig!oQCMGEsmt)EI73FAe>H3f^Osp@c1?MBZCQhtaY}HUppwDz=^d+^<_HnH;_n_)( z9+<7gbP3q%D(|aZQC*1^)zw?3ZWzBA{Y-Lqaa|`pCJ5GZ^drGnmNxvkQXTUkbWM#5 z{Y$a4Xb8`_5{b;sUFu8wi* zj-@(IWp1=S{hj*s2n5-fWW7;E>&b=#iBp-@*1tD)hx;;uT+H<+IbM;@IjyANO}JV2 zBJtouD1XH?#ghH@30E|mbIwq+R@yT2`6($VWd@jaJ7^xbGhj=C_lja$D>&XODCVCj z$hrqLY@E&U^#q^P#*7JW7a=uVS4`9p-BSl5r7|ZmgiLWOI)G>0m-;sb`BSk1>j9Xx z8zXNp74edMXo9==CXnNUaNg7XY>qyJ^K(8=+4fEa6ZxX6&5!Dc7hK2NP6*!CWM_LU zken7xKPz(wv7B^m5RA76oYSZ3Z2g?Ou>S=qAEyzY44k=&a!zt9!{M_RqN@lASCr~F zm65Kj+eu4_+ZByTW`k^Hh0w(Oh3cD6VNa-AqW-Y}ru7eP#!@r6I@O?)gq#MDWL=>K zkq;64oUbz+M1FOW`|+c5!Ec=I%G@_n-17QRu@+<2@&43)lv~aXQregjbv)6cj(0q9 z_RylwezNZCmr-;!(%uALXvM(i*g5ew6b08Jxi7{Qi#psj$39EdWHQgms3r~Jz5qJj zUA`~Rm36TR=M>jq4)V?g*S;yzQ6l{g$y^c-??a;DUH9|lOwRJ{op?H6d_UR!!$B%D zm0$bGx}|TSs?H5u-zIq56$9UGxw=J~41+_FoE+nJJ|FKssLf+-UoFU4vugJSv~!`1 z%%{m`{ZoZA9Oi2Qv4CgY3TKL>qai#AQ22(9lQUADLb6iv1&$zw>Ei)N2t?jT^cDO-PnJ>z)$S6mj!PP?@_@ zt{;dv-}QNC*3k8V6EAdqfg8d>;@p~bdaNY47wNMEZ-8Ppnd_ITyDa^JrO;y^89lwg zTJT;eKQO5$;>%*lmn`dU5p*5m5tX1a z_o-aF2ywn^^JV~Xn-VW>Q*U$NPyaRt$htph2f?RE{~&nRDpt{^Qa3Aw9%#tuS%R$7 z;|4)pq>TtZg<`4@a8_{y!qZ}k%_{O6)#y?bb%QZ5W+kT;*JxTnemkEH?G`Bi zjcJORg@aP67mThezQ(5`3j~IT}<%RqnI1- zTA$2~tKXJ!kjm%0D6UMMe*i@;|}M=zc86BjpmNGAsG*9KOS9cT4ezQXF_o zm_mDgqZAURGR6F6-I=>%PHUp)5WG2xC1*(}Z!D@lnh;zDcuP!GET5{6ElhI1*5SE_ zS6uKY_>`EfSU&rD*jc9+q6PB-KZ&X464^T_RsYwK;L!BK>fl=_zr{4gaFkvYoOL5O z>jpJ$<)Jr%FN&R&^IP?OoRxz^VYH7~isjptW~DvJ-NO#Y!mnM>6MRt2RxF=g!0pwn z(~jfdZoubas$$Wkpr^Jbmuf$8Dx=NQTsxSBB{QL{h!fa4GT+`BIanKD{2sFu%eP<{ zq)Bc}skgV*ZCvyvcpoU1&%T){K-OuaYH$qTIWbkS*k0|8E!8&ER7TrbI~Qm|)w$q+ zZfcINt8v{0-I}A2sBuZi$7A@-x@R>{nn-jR!S?;@;8@X<6{MsroUhQdX{yUyQ7Sr0 z&gWm&Es~o)BkFFCij-V#_tbK`bUix_K@8&wniQ+3AL95vJ8Go`yp=`MgdG(TOkgnV$AnF<#x&R663 zK#gNOY-=1sqQ)U1ubt#~qRaWY%`6VyA$aTkl?WYk#^9H$EppwDMC;xWwjmuHYdcK0 zF7XvAv9%%5V#%#s%*}a&GG0UL61q%Q_i>ZpmT~WLCO10IF1q#%xdrtOl zfl}|zs65Hb8a;JcqjU~GaO-Y{y9c~uW3FNqeL@pGdfyh2--YZt0^gobj{Ah}9>;w` z2Z=sm_pwo;Pk;vxq2R?>iA@~xy{Rum2jwu{i&={0`$u1vp6I^AoAimVfKzux1y(Gd zoT???G}W}FF5tm2H92kRscB1TD?fM9hlzt$@GgkCip70G-wMv}6Z&{_*6Ewd!62CW zB)4x*mM&Ss=p)=KdaF zsfy)OTQ^ek+fdh- zOhf!;4Ea2=uJ~1;<%qwFAxrh7o9te1!I`*0p>A3zgK_0h|AJO>U*rYFXunS|8_2pH zHT&2F$x$($yh_tk(~Z(Y_<{TCM7ZtX^@_QQRSc54c9hE0A?vKWY7&FwHNY?AljA{B z`)1-nQU{4a((mG72%nCU87No~D~a6moqVtg@uyosyHm2@2gHBHkS}xA>G8W@yOC`A zB>3KB^UwT7p{KrrLtwOvS&HSiWIZj`x!{F9`qd6i)=WE+?@)*~e03%g4qu%lMKzNd{^^2dD|+gJQ_8cLC|Sv7ja5Gh@hR!1*52<4VB=Fown~ z#qvF-$DCNCsT|_~%}W8Mm+GkWDSrGFV!KStZ3z`+I?}lWZ?9rB-G?a&OAtqmG*HmcEHnxV1IsEx4ZzPz0~b=Da|QG{fBu@tOHh*ibJ_&T##Ky4n02>1G$j zGu*f5qW=OE42YE|hOM{RH2S-@z;8h^GRFM{$E=&dWGonmctQ->^c2(HSP%3%;`uRT zGh(2xYXYrAygr6({tL8;S#Pij@t-kdb69*oPQKsef#?LwBxFTGhGlNH zSjQ(><6Wy`dBm#Q8Q>5`QIWv_2=Ok+@piMc_(BoJ+r3gBhy0<{cNOHJ39`jsQDeW` zO!!lY)+H0g)8sI#hZ3nRUMhMjGmc;SxqR@m1f!$+j(qSe)9;`mVt+BA`AR7w$@q07 z*&F$xaT3L-!kZvu-DIge3CS5Tt{8YrTLK)b>GMTMu8MI@q*bO9kCE5*+X=!mfL4^| zWGd(POx0d4q2j%WPaw{%1%B-(>$=FU*&KgF@J%;fzNndNODt zmMjn2k|pc({8msK%6>6TF&oIa20J;>lUk{a9-k_69b|SVVA}?I2ENej1={%qlEznQ znMenH5L`*{X4-5U&rR2o;3mZP#E>lsfcDir&BqXrk0HC7DSwlDFb(nBF=X@o{DDUg zpadVo_&H`NmOt?5!4)PmS`TEnAzYW>EmRCgUyFfRccbv8NZQ1Byk3x_wN!{4{o}82 zJHzV{b8WqVn&-4SxE%4*`A|HbBvuC(+D6mFcoMA+CQARyD9FW16vNg&wgh=w7n4^Y zSr_BcCD)$YoM&pzR5zWlU47Vo1=lMyZS* zfGKl-$(t7f+mN90#zTUn(M9$~tT%$e2yP{Kr`dXh!WA_E8jUy`L$}yvN~S4X77ZpL zo)JTKO_Wsk33?0hs;wY>_%Qe!@eeWNFKBb0S!S?JIJFBQVTL@wvZ$w)MWy=uFFEJ~ ztHJ*8+QeK_qw)>V*H-npFnA}3*BMTad>)X#!WvwTctk!Fs(2z&p--a*55svfpN9&4 zX*8IEc-B^szRVgdMZ9J!NZ&~fHX{CcE9k2Ifr3XVC&9ZQ^3E0e0PTwSuzV;v%$B)b zcgFK)iPb&)7=*m1jxJ$z&!VMR*Ckm|N7ptM8jc>}4xWQx9bLkxqx-lvSruOxlFya4 z)m4y(Cdd}Ij;`0tm${)zw8LYG9Ab;3j-E*Ukm9AH^Jz44;`ZdxSa<+}BMIJ9wrT`w zdk#=r#GPYEF*>YXd69Knx`6jZa%+so*S6Iwby+*=m0iUh4KJI|MUCDn5llzCh!DR( z!kc2NkWvBB&a)0$lYNZfD}pB}hEW+?hFvNAFC-=Z&BwD`N&#w!xMd6_mvcMWlMQOM z+*aHv9Znq%l)h6*a87B}tgym@PE}Tzeo~>C+b)3p<&$>P9uGH%NR|MNX9u?eH?`pT&Z6h&GV&TS3@$KO@ zMsRe@wHp}9xM!+xi<6wQncc#e)0O%;9YNQatQa2G3n;QqFTe;cM{;+J$F~gB40N|3 zY6dG**N?(`HlK?cz2hO6jd&R$ew~A_VOv_23P@%2W(Vf{T7P_oU=zWU{Q4v7&eqcB zAH)sEMNoXXpPG%mdV_d-!#QDJB5t~@8M{sy8cKDP%IMj&GWV9?6@uIE>tWw@tDh^XpAPtVsop?AivP4A z#V<xyoq(&CT@UPx;lDssO=qWoVu zidWj*;K_R-^>N>rs@))RX;*B~z4j>>UG0vRj4ayxe`TuL-P#>b>9qT)%sq$p;7w_7 z#8@MZ?72pJFs8^KNPT$V8(=WDNc>XmE@!9<^?V{dMNe$4XJS&1KM3_qED}Fbk#)1@ zpkhZvdlAB>b&Z-blVL%JA^uMcDMs#BP_GkRDRVuxfu4=5cLjqst2x*DGgXZ{?1G9r z0c`}nV12~}3km&VbE5m`aun?!WD&g-EAn?ZbnNeNl)0HWH>h4lX+L?AB^b(@ZU`fO zqi*e8(~|m)y77Uw?uQ4_<)zw<(s~K1s^Umlcz~4Z1+PAN>yz0`UFviI<6JTBhH>EM zeZ!}owrN0%qyf=^8Q>2z&0l;a+K)}^fh4IPBlQ!jFkr{XfY-$M>whz#ebRvFzzpyQ zRBPW}w5{!MTtkAdamA?CYQ0tMdM!e*KazGa9^Yiq;HCR3(cm?dc+dsj1^Ham=*j=! zI>h%7;)ncwezrU-6~OMw0%f{Pi=8JByh!jQzu3vT^L1aQ9Py_yl)NvqldYdB4@yTU z(GMi3_Ee-VPLv$+KBxt62RM7iJiGaXN$+#hCTNbhRSZSzyK!2wo{qR{3`I-U?t(5x zd`%1~hIc!nZ<1?vmEVwi55loA#Wv*9YYsX~y=Jp2JO^mKMhhqnGTQhjpa_i`R zx(D(;vW>AOe-A{*{vJq~`$65N_0wUu(M;XCjUsWk@duiE(Np|E*ll!>=r)(0j$%w~ zuq#S0kWzIUpCarwI)Kqaj5lFa>NbKa8_*)m(+r3X!fxXY*s9xHBlVwGVZe?qG~i(| znm_YD8PGmyKy(mxn^4_Ksq2Y4tCYm0n;8=H)%Y0yc9LiLh0=i@z8nz2k(^Z#(}>_WjCs_ZbBpEhax?j z;CrNEcF%?FN?)JHfl57?cu(RyOF;@t9Ny}Bb}uyC2&4kCKP5=ptu7|m4c-`e1a{UEP?3KM<|+T$oS?$%M)KfLCb2Yj-+D50#X;PO|Y3BsM8y63cxb;TgRn zoh_h(`w7;hOmH+Q^Ko_G>gQUra8lN@1u5=S3Qfw?9>+UBDH98ok4fb;5%g4jLZznA z@uVyyZ{LS`0w1;TlQK{6lQJLolQPBS+MZ0%ME+kVWv$U3bdh#V%A_Tpl=*{jQlHt$C4seI%ogbYz{r2NE0# zdR)v^3|;z22-l{h>kK3p$GGXrU(Y?$9g7CTxHV?^hZwT16(^2hG~#RwDMki6*y?SQ zmUu5Cc{j%6+mf1x=#FGG4;igx<2rcX#9UikV&};$aorz?4}KvkvqAB-*u+i93vIod zxE34TglwnLv=s_YiIv#u5dDK$5e8imUlc<=>oV7`5zv!}t;_2Mp>LNBhDfM*uT+B} zy;T5vw8_r8A;eSCdXWj;2wf+Y~~n0 z!WO>gBu{1buxk|8y#)CQ1h2F&Jk(@bcmM2nM&ti{OU=!#V$^+Sr6ik`|Sr>uKHOaHY*zb1HB`*rpd zch&+RE^59*FL0CC;Z5)i#hjl37HuE=!aYjAa0(C93x=_XE21O+;n= z0>+Oq%L+-8={_@+YS=vpCiBvNg7<*!2uP}U)$KcwN%e8A%&qH3r5_D7x}Qe$2DZn&g4CTqE^NeD8GuPxE?UPk$B?ylQK6+ist>hqOkP`PCOl;sldHeS(V;t z8T^UV8tAB8+-ffLao<1{r@4QreD`~4Yx2+p+2SbT_u!OT|VQaButKf>Vvg!!Ka?q2C(Lf?$ zDx+sX%G{%3U7KV@1BvY%EVEaO22Vk-dXg|2NPOJaQ%IgBZSPe<9-1Iq+y;`H&4krT zRCj73huGq1AW5WtNbyq9QyJxyb$4qS-V{M|f_H~s^GybvIl-)cobHz=ts}T(&u6`S(@}60WMk&#vQEE@(i6@rI zTuUjsz(X zHKTd*v#d^o%ry2t5WKGFCSdV_K!+giMzEEq4w4HaX88EwO1JWJU6QxraHVd0W|hv6@9;G5wN!(SrK(+6i##_ZYrJi`w!dOt(O)weBz zk0Ja*`2T7iz~?PQOl9;53pOO9BPf|}FPjS;U=K(E=>r(S;XvmSO!3P|;;&~^VX}yk z$=!*kGD>0AW}UteAKWU&R_gRrl2<1z_P|7u?Igd$@TtU8nUB!nbt*|``?h=5jgaQG z5H=Ic(7bQPSJEsGh?vUgEAm;_s5z;tzvfa62%f7L8GU(}@Xrnc-w(+Vm2j3i2Lqjm zxKj)%M$*#5m9)21_d#-FjGJmdKXqial4cM3a7QF|u~QSl3HA_L?NWQS9gO|Nm<%Jn*h%K?+NH!j zto!Lc5?V3P5`|Vo2WEvokQH{1V2F$E5%iP#ku8dd}ixV57L zGr%8Eo}c8x%TQO@g$JY)E{qN=t$(*(?81Z6-i2jup-fwnXPVtVkr8$w*juApakX27 zJ1xz$=)lzbgV;9}_fLxUMEy?X$&znVefy;P=)lzb14@2^)b&8!HkCxXLCwbKz?Ap{ z`so6O0hS6^cv(S|c;8Fe9D8|z zPh4hie+*`k#(bgkaoi{Me#f{^`UCT(e;H)lprSs>9W(iL9lESL`mJ=~y@zo6^O_jP z%}TZj>yCo0JNiV{>vC+aI3u%qds>KpC_WAguI09(K@ zD>NWFFa!Jn>h!|O;7`<5_TB;Mg!iHYOY7fX8GEmyJDw%ey3S7e#+tf}u%TWmJ)DGiKn&S*Kkhn( ztOw+jut+ge;~@>OiT;sP|7Q>cb7eJxIn9yk^^a zjJ4NE^FqYdvl7jSLFMZ((!tgI;e99ipj2x7&US9THbw7_Z-#|cc5z{w{&$#5-HjyFo3YfP-sr&emW0Utw^8g8 zCv}njbEN+Q>EG5yi#w9r459<6t?dtJet+0G@E)nU3sqL&i!m(fbP}=wgkR>$r&4?4 zh)y8*7U5s-k#+xkBOfB(6hpS9-gmh=?-wli%s1()QXFu(!TO)NP@Rtol!i=1p+SFv zrh>UV|3UDXC`N;S{#%`7^=;EKcT)>kXCRMTVEly}um|sR$lo9c=H=y|oFr$RJ}MB@hOukRQjAjQmHM6SrSxU)MO9xHMIKH0Xo#5580aQAtA@-xk72)WSMdBaKj7AS- zXQPM6sP~U_Hn|YZi;=uf@S1IxGIba1gXW_7TU%SFK+@3Kx&_raNLX8Duk{XkDxpS? zyccyxqlbji=;7nmi%yb}6{Cmk6~K~xWXaS2rtq?a!Z2 zx$yjA2U^6(M86{V7U5syl66n-1hfV5feRzZHqfgnu=D->g3Idoc2U*np)_P73cLU7 zp{X^J(_&4E(cnAmto~BiNu$SPjUJOo{TPY znn>~T+NL_}&Jd&Yt>m25=JSGWKJOES^Lc+@%d>%&=LCCwFOxVS@tn0{KL3E!AB_6S z2JC1lsMnXp81}yzP!{GHF0Z{c<^hkOPH&YDmY}Y(_YO!WycZoK zMb$y_wJMhEbyxJHD;0-Mpm(WoTeh8gbD4~7i`=S7ug43ApH33;{$?b+1pHN4=OGwK zNLb^0S7DDr$y1pn+`8t;mNOyWf#AWI9PNj=s}s;uh-b#oq(O`@(sLCL=GaGDP_e8t zyd`i}$Gk{Iio2Y_mx%v~A-l&Zvj?Rb&XSndKf#*f`h5hK`@{Oj%7&3F*nO!>9YFAf zu$2w@buWi;4C1yiq!=UCR1|SN;cf8qko1jlf7i9lwZEDQxC!wD*X~emXWUz?YmBKG z?zStK(52I<>U^|o&b5335zfi zHh^c|mY$F^)6}#9K9%5VxfqGe=z;t$LO+r>Ch3WmJTzmLSvnB-dL{p@!afSF&n%?Q zgnlW(`%JO?=MMG7gBearo3-Y`DB%e*x{KpwgmS0!lx4Qr*$wzY0^e(R8F|i1@dNyn zFURGf3h=ygNc}LdmkEV~`3^kCKNDj0So>rbswsHKrS>OyYvbm{dot@31Z1P}MRVt% zUV%2Rr&4p=`P5+!y{Qwp7l!V?mh*6ie=Ft{_7dxR5WeYOjp+pxXRce_CzYD#F8_|g zT(zQ^MgLi##)<-1Dth0+4&oZc6@!ZMJXB4RK( z$hqxhfsy1akruj$u*mI#>`P>`U0W`vNq!IkcRjXDdi5=UB6QDm2ZZqcf)}K7?wA;= zk%XGMoZC5sD9&tm!IeCQPNH*^uwg;@GU>e>;U4G(mttXEh3`JyUES74qwaHPgv|!7a}!+6xW3(sV+pC>skQ%diaN9 zUk^%jD}j30WBJzgAoym%Th~Jj<-01Zho?#Of)X|?IKlL)9`?B|t_NWgh3`->%y8Ai zf52xt)k6&DD_?B&@Dk}dsGw0jbSIs!hdWGz>R~mcO@z1}UWiGHiTQf?5W=T~s2&to zqNpA|ff@fza{49-UrI@rzQ;o!1V0woUFYN+k4F$WA*Bz4aZ1dx5hI_~|5VD*6~o*p^*&A#Tml& z+!BI3X066N6^t=xu~D9a(pQb{0*1^GS>kl}e-g+rj|{PNy4zngDpk}ZGj55KXT%sI z#^~VCmC`I{7-PUV-x0-_LI~=oZ&@LR^>XPLFwVDum=U#sld(00adPS_B%Q7{P(NMn z`XC5KojWe)f^ZuBF zxtqK{j$I|?^2fJuyfXwZ@XojwcljYtu=hj^SLKPfNLRD3c_L??*prp0_e5u6-V==} zVKb3JPh4*td14$f?}=t`jxtZA%tU!&h4CtR;zPXf)xUTm!o4THLPh9_K@@rw=C;KW zTE?}X$WS%vzu+u!bEkTE7;xdu!Q*Cy_NfS7>|Wz+uGEtS2ModQAvp6U-tXb`UU#`# z8(P*vS?4vZ^W{MJA~df-aKnCR_>nV~G!)*P)Nm{0l7e)qgD5u#6FwIB0>b%j9KVa* z(IH`^2n~xltr~cy{c3m5J8l`!veitv+!Y*mL;qs8W(q9`y<5PFYLj&u=mnsh`xU5Y zxN1rpoJ4APF%R;No$uyyJl{>{m%$s^Ql~vqVssJX#`*4Hj&trVe$O@yXNCA6;eD9} zaU9$t-Nhj?M#%Z|opx?5w!SKT(~Sop&`9_1M zU|&CiCkw8sex3we=+pY~Vle4^{p5)G@!~98x<#b0ettHN#*6y5NA)944;wF<;Wb}B zZ9o$vr>`H46%8-jcKtL1^YwEP$rFFRdZuA;TPQ_41lxa9RrQE42twuR8IR0Yj~J`P z*hclN2G8`bs(OSp6B1U>P%QM-BcuyRTs@0`eDw$#21NCA`!K2=!M=I~j}cr|^=tr~ z?9=+{*=bVZLuM;V(o=1$M>M1AYyN@`xS@pbQHfT8i+IW?^Ph+Yl#WnP8 zb)SY{zItlhkykx_RJ&7M8A{PE3?G$yj=(N}m8)hLGG8@fj2B}YRWliUneeSfGa;LV zgjKUU*7>RtQj`6*an)P^E z%va47cyokEVbyGZr#PybCd7Qzh%=N>((z)>FTUq=GG3*sc^J}olx?eOw5ixv&DA8& z`y5l=^)JJRF<>NnmmXUXt`F!z8B%?z&Uplv0lU$x`?#M{TJC_WQ(0%_Sb=g8Ezw(13Dv^YS8u} z)JTvV&@_a6G4vV0nB{p+E2ucfVLqT&xx0<<&(Ls#S!ME$GoVkl}2!Srt z(imIK++#-6i(1~Ta`>71VI&2+t?#T3VYEw5Z{aD5c9q0bU5b_ zN;*!)4Bv}>HJ*A=^?S+E&)la&dQ-%3=H3}7=QML4PHdrzaNm=bD53uR%>6%@JKp~q@3rHGk1wcBBqC}-XJfiP5Sejpz(sLYLD{)b3UDKkFP(VQff`@Mn~=O z6tzc@!k&2;i0_$a6Z7p+oU^Pww#S*iXWnhRxM%vA;Xrz2W?;qnEx%{Zb&bG$TYQ=1 z$v;0e`~{0!z+vXT&lgoq4Mpeyp>my!K<4X2jLBl;%|9yYq+tnXI^kQ@iICJasuMqR zUxgj>ZSC1GY#n?vmbOFx^->Q0qY!nh!Pk$`*)gz?l zphWeQ1NrHppcX(>PXjFW)g#zfkKhi1tE!&ffPH;hUp=)Sj;iMzV!nEQ#_eN73ajTH z#@AkEwbjTaQn+y&{+&)k)zSrpCO8$1%t z++!%3xeM|sHFH<0?+NkDeP3WdbB~~C<}Sp~+#@8OxeM|$_qpi$l7IuY*i1w-_twCE z=6)uzg)Sobnfs;4{LFnB33HJHG;@E(AkEwbt&SX^nY$og49(n?rHT>H+~))PnR^UH zGj~D$&(GYI?sq~wbJrUPbt6?D$<+3WAj&Kw5chK7DyUNzD^0#JhwOg#| zQ3c_h+2}a4iqjnxc&odP3w`NP+s$=d$Su56d%KgucTv8?>2r!llGO;=dAB?5TQ$t> zuj7@{z${&fmC~Fj(OwKiZD3}_yoY;xT3qZ6<`)-&+7cMHo;D?#EC}|Cix`g1MuMVc z*2$#Hp*9}!x&itj?`~p#$Qul4ok-!3_lj{emFYLte?_ifPE( zl~}mUdI^#|TynCyAGQkaGffLzsw*mh`;9!TZsckx*W+1 zPvj-iXuX=;-ruT{*0>dLz9hU3_JQN(_5Ie=Tqi~;8i?SJ35av{;pgG95MK*ax-Ihc zLm~LEf$zDql>b;)lf1hVCLsP9{hhwA+(_oSnwW0+KI-%BINMb3MY4kk=||mRr1E+H zA@$y_4q#^qe}at^`XIG+Rf=9$S)c2AfQ>wf>K*4&m!qKhrmeGXLDuu!(RW6KfB{;5LY z7E_1@wni`@oekC3*9a1hBBbANpOenl*CoJVeN6^?UHDu|rTXIUL-&k^!oQaxAKsq5 zDA0HMf$hqK{E_e@*JdVZ{}#efGS@Y|K5R8EY^@92<(H(=X{)CX(c@dm-)OGWjx;W> zm1LT%QSP5=DEoONIloKj&&9K`=%2Q&+zogT$+VXZ@(w zpeLwkkBgl?iSY%LR+!79Rpm|}zW`b4^c@W$JwO^hQSS5s4S>0B7=lG^Er;7bCFkms z9U^{1;8PlxSqAz@2ke<{?Z5;YFx>x!z-|mT99Qn_%i}-pU#nQ&UhMQ)52?wLMPb9j zayJb@k;j+1J{+VdN>1p6ayN|Q65T-Fqp11LDAV^tLbBA!0~!Nrl4L)^1z5Wp<32S5 zqaOL5yFgB^9W;Zoknk9^f1q6dQ&h)_ISRAN{kj8Pt#+U<+~Vd{yjCknrRxMYLr9O} zd~siQj_U@u+cD>h)mR#C!8W7p-n)fUxSTWys@lflt7#h~?M`?S+0P_B z>lgKok3dLS?!L4Lw*71o<|rM|)dU>K%-xSedfEF45 zC(9b+U#OsOraEfw5;WHRsF-3`vqbbS>h4B<+44H*f zloJc3Z~)5v6lE;gEtHuj7ydwQev0xau%Dt#Bu0TWMR^+LIx$Zv^i!1iV19}sXgq;w zMq9M|1+!p3MTy~PiXupAwTEK@=~A?+c#85Tpr4}XeR6(^vIbHkk-{lTXAr+CyM~yb zqI?SH{|H?FG#j*F9&bENQDzbgrzo}Xt~^}j6eR+yoT99CUlnn8ps*3CFC;8SY5mRI z5g_=XKdPfOt~vNgg!91c?A*~Bnr0{sXeEM=C8Rsz&87$%Kj(cSQ0ZDw-1M0tc({RU zUG-v@>QXoWcs8Lu(g#uh(^lEfbsb1<*`DjOWr8Bjw~_2VLi*goRiyG+KO*hktjS=n z3h%){E3;_w{H=8hDER(`IiO9aGYKF?=@tsDV6*?I;B(y|at`Mw2Urtr{Cwzv1I?6* z`N=_rnxEVbyu^%~gZA+%_JM_0qPW6JzMBVvUFO6(M~T-LYbR(n1U?;1#&GZ=njeu><>hkZ(d;^WQ2LkYSV)LAtNmZfEtH z!@}uGzrro3dYYs*vh*+1Kw0#Ha#-sQK>y8!o6y~^Bb&yMc0l)wTj`(cnwdUkE5prS zKS1@Bmmy&-Li*Oi2T12Dukb}Hqbj!<*ipi7r;MsR%lLFMzOS$Y^5+P9LSIDUy?(D; zu(_^Bl<`Q*cpy}tabFT%A;tF>Zbv$w@f{Tzj|6)}_~>NDXVGM)7EDHdd}lI;-kQYO ztukKar%6)_1er%iVu&@~R|_;ayH0+dG_64GfsM179$U>03iPA;{exh_CI{idR#1{xmlpeAS@+L|#x{Zm_nL8#XN>Y=# zDQ}`=xSuHHK${BP=0qt}mf~-Q^~q%<`I;~TYu%sRQ6p41d#&q&m;Wx>1Y^XR)CR1* zVLVOnmwhO36D zyZytswz`U-&2W#9s{cPqulxR%Ubp>61HVn+;$gXcIswFAJA4M|d?5#!MVhdeF^4AV^2hd+ToJ_(ow2Anxf6-Jyx^^gNvY_a$zaah1bh>t^EX|5o@xbfAWwz)U^KG9VS)>$(C>aLo^A#&xePktet#D-K9<<>@3@5hmd^ z$K5PR_#{j>OQM7RLiBRv6yH$hF@V%JB-uH|eJef3sgqgaL5K17iv4O|NIc%{bqJeB zEbccdSNlTg{6^&&PFb&`u&ZjMQ%6#e6TqhPyh^N>nLQNhqugz_2qQSlBqSNO8Czt# z^=@I75~5-uF0J1AUhj8 z=WZi5++u@?O(M3~sf8%TbW#NOacOHlg4ITPEvCN^(r3HORa~lq-j)#ba$C&a0}vLx zq8u6#YiO}L#P%mfL)Ehtm%tyOG(E^d`}vO(rrSX;av*K1W%6kM+(Rc*p@$=`BsR-9 zbKt09RQtT#o{dP4Id9R-_>4CtI0Dn zSYLbarakL{V$>noC!BJ*}5j*LZvx@fm6Lsd@G!P_^>3_GZ_8l?#%t=aHZ@ z)1?S>!F`GQ9>;uzK{bctvhs9afO7XcLd`>#*fTO2Y;7iZR{C~>^^6ReQyqHtrv`9C z0&2_cxgQ(-^w>{?1kqzZ<@VSQxc>Z$#&<$vnfn{J1T_o()feGg&%2h$7vWpa&nr=) z=#^#j&qd1~2-*`84NFU-2H*%4*Ee;2fj z1D&3qb(q`dfsE!l#kcQKkB0{}Iqj_J#rlg%SxJgVYp286N_bU=v7{|7|Jco{Lq#7E z_;aKxOfKJ>YrW9^tUpmE8bhtBEafBSYc{ zW!JA{xs~Dhn5Y&bB3((AuR`TIW!bMJY586=G*6f1B77*qX14=*CN1v+2{p1@3{$g} z<+JUkkgy*Kc)zzBf*?f7K<1qpL1$fTF7|TS%9aSE762@63_`+T~Myc68O{!S0kqr0}Xsa}a;k_pbrV>gzHZv1-)#VQ3>8i`)#KNmCxt`3l3DLdq?Q>G5{ddO_Tj(O(-w(eOnf-ZB zq|RqL;ys~T;@%U(;CN36E+SBxg=U33A=rB&hO6>K3F#W%n(#!9blwwx67$!e9_+yd z8IeLy>^Ud$#7V?LPr#Wd)P?WmM0?IdtxIhLQiM}XoBfy`Q zjYfd0-;7285py!RU&#uyMcCGnQZ417hpk8c> zRNI1mZO3p`wLOe-|jyl=G*<5)M7&xeo?zGUJ%vxKE!-&_l9$o)%GD~ zqH6m*<5jBdKdI@Oy|!K35$*_cY8MAy51#IF^Z@KYRaX+34&&cu{or7BMT6yOn6V z%~g3?yI_Cze%E3;dn<9+1J;s8Z_*-7@*G(2t*8fx@R;dOP3VVPUrlyJ> zpuQ`tCZ3`Uo2?8wd(R=gKYQ=6SlQ|9En*QwdgMqWs_%ND`mTtfdW@7^bEQ%eAFLSYrZ~?_MgWs_#x9z3;m}OOromi8bBV)4nyM7TaP; z)M5qiNubqTXNuHf1^X5o!&SA|rleb~nvGiQ)ui)%cQUcC@6y1wh!mc)))+_II{qLQ z_FXtvsUdd!&TLSN)f+5wwyh&^_MS(-)s%T#EjGgQZ<}~WG{f4Ow_Ag4UMq4$YjW{j zSMZ_U5x1J3n4s4LJqL7TYbC#Vn5Qdb^A zsS&Jx#^l^8j&Cr-7Ka?KKclzAzUP)|op(sE4hsu=bFUfZOjbZkwp!<<*1EH}NV`jM zO=xTSay=93MracoMN7i)0yay+Mr0l?33m-Io5o8*lD7a(?^=8+E3V2*LeLJNRWAwq zf`m)L-HO+q}1+KJk`|pL>Mm#Pao_V<6+p6upfeWNqD{ve!S?A zVtM8rmxFW~g$kF1jf+*n3*J>uwj?B{b;@av;`{5Wk7`MHAFy8%y5-SHWe~*F9h9Y8 z$$m!ENky<`7#cx zAC09CgZoiL@Gk_$!*@-QMiIe&6p7(z6nS5osU_Wr-$J@E@=A14>A6}4XcYM`F+Ykt zcp)b>k;1WbzHxL?*+|TfB2U7ZN+{`gyqTy`WT!RKrD;$zV$qWDB9?@NXcWmBNlU_a zh%I!v5ci|V-%6;za7lOplPm9uI~zovsQp3Yi4<@Vfzo_vR>%{Ay(eP0Do>P#Bf!f*pYN?RmiAKj56!hCcY#V zo?j_p--IV>exwr06NeBB&#!O}HBX#vCdv~R8n05DPeGI=Gc?HcQ%c0YiaukACb#Z4lGBfwbWsJ3Si z^R?X@&Q(_1ZOlZ~_IJjsRNH@2(>4F4-AA~u?O=Ue+qyh90&_EWS#96FQ{;&TaJ(l3 z-{n2=u~{Kc2=<1Jpxc9`hs0iD=EeSEVhdj}=xWmr!gwEb~SvFb{R^Jev zy{ADOB$K<9d}a3N>@C=zy?a|sXKy7Ad%#-Kd_}0VBzzXG?*SrwCcbt^f;wj2dZI`I;p7EJXQ{SCHEL;*oEP_ane9{W5zUztVyCQ~`izStn z`tHxB%9ezH)kWCs{;!hdB88TVVQQ+d+?IskjR{!Z+$>k$J@#{1uCw=T#KOKS)<|DZ z$L<=n*tfuaixs>lfmU~)DN>6S>|1OMSJh&hl5VnUHtM@YU&sKB)UAnyeU}EdOr)^I zUSb^e-Ft|IeHYGEYKR@3nWz>!+jx~)>^%Cdrp()Fu@PS7k`QY*dPkhJTjYop|+KucZC5LykS zCE>mt*ZfL_+>Mwx{x7316_mN%wTa>jilBRfY@)a`xrrh=uuT;HfE^L<_d&zoBsp;R zaOXl-lqT+MMmr)Tj&?*S9_@%wx@bp)ves?qK3r$n2Q$wCd#g!8Z@E)ewj-hhj2pn^ zuAW6Q%4@aPU{!5s^mKWMb=` zK3x1LTE@VrcIUvxYCq2-`yMps9w)Zb|EVgE2zis?X-CA_G3Vrvqa6`banH+WTPSV! zHl^q}w;I_==*YRn#ICZ~EMnt`Ew&vIO0kg?!Cm2wh=oSdjtEcJjtJ5Hj)>XNR};9+=G8vw+bEUbBGR&@xMsEb-@^QOD1Uw<9%WXEiIxo1aouL}3|@od4^iy^Kmo`Dj3{IL;j`(wA7=~H@j@d*b| z+EJUX|G-^vIUATi2rrXOzHy#^tn$NR?ZntZ<_r8AZ$C0Y*Kf45v&|i-{G_-MIsb@Y ziCac%`W%B>kp;?M-#eZ9)NM!g)Z|$ZumW=8Rg?Q75v>Qb(ns8+y)-DQ%@vG#?1pjZ zX-~Yg9}5OgSOsCeyBuM;Q`0jw&~77s8?^DBb{^T~To&Qc->TQErCmg9y_*semx3sJC0=8f9+ubNj-0J6nv7jjyP(4fc zRT=fg^MMc+yZz86xCb!ri_bZ=+-HI2x-p1Wx|2A5+e#=}PeSQ+|7j{ED&-oO{++`S zTB(#Gq)>4CATBDAc#0GZzt|M$z0M83m%$GayO0>J);dq5buwu9Rg5)$mh=>`pCt)> zg}_{KuIbS%NwA+K#c(uB`cjH1sxEm=CtYeJbrDUP-`b@7HEI5hn4cvrztp7~i4@Ki z8~-4VW=SUy^RuM2aK0pzbUfTl)Liiz<7t+37qRe?*CkZVjf7~Hw7^KZufxX9s)+A8s zUrmoZCfIu{hO6>e9ny73dTgrYFORJx<~_C>q`nD{{bU?@tlm$N$M%QQoKVuSubC*1 zwFmVV2@@Xs5pSjXZ`)%L?mgBE74|pFWuM1Xau`4;y)EZn=lB}SVG^-NLgEsayNc#b zLl}m|=?{xb_EQ^s2jMIz{bnU!vNQe==+ejM{f^5Z}IUCFa}r^>A(_lyt0bCaSik8?RFP z{*2mEjcluZN4T%8rKqsKCGK1XmP0YO5tiVIEeFUGIuWjiv&2TlHo&cbOQ*S44A!Vv z=U0u$8Ya#K?ko71v4*PAw*mET6xxG;E55cO$c=)%8)LXCH})po2ze-SiW0h^y*d|IpnrW@h(;?v>}?U>a> z4i|pldZp4Eim$*^!KjyS{MgSqKC{V0dQ=DhFwp1rY3B_n_Pa7$kkvX8r#~xR&J4nz zkbVXBr(MBYR6Y5pT@iFPPy@OPO3nMx@GT`%>p5{t)OrNnOP~epgQflfN5Q`J#BkJl z1VtyAQKV~z+PL*R1n67ObYi~syacI(NMY+)ZydFr;J2vtybk9LLP^I*%?7oe!$AFz z*`8QnEhz^du zcs=FwPx#oEw5%?>T+QyIrtZOtadZsy4Nj@GX?eC=F@olR?m2{7hqyn1 zb58FRonb}!3wRYV7DmJ#4~dy8b8Z&L-x_BTv4Y>l(LK87LXIBG`hw%#K>VK5qlo!S zl;TVxaG~#g%TRkxJyH8kMWiZqnNlp77T;v#4R?so6obFnZnrnNh6drZn%IA&JM0kI ze-^^)E#G#;##!tbVpE9CbQ8-elGJ{Xmk@l9z|%h^=IJYmdHMlK`f1Sn$Ml{ty>m!k z=pthlx$BWFw;W%6B9UVoRD6rzM>A_3v3>uLi{2xq9Fr>kM0N@2Vs{_0hLo`{t+IAw zR7?=v5@v~QBsRGsJDf=bv-5YrT64n@4Wc(hh zuAKW6VJ`?vt?LV(9x74K9|hvi8$#|U(0iL$LY+4R`<@@eQO{p*nfmGFgQQ!H*0|^2 z__ti6$2u^ZC=;uvRO7hx`2-=#U6M`j9-yxh#>6@XoRvY(VbDe9JBh0yZ{4RvVgpAlm zV!T2J+9J1}B#(EktCc(G1$zrx}bjtH*-pXDZp@Gr{fp`3e*15dHvR{U~NaI{vb%jfv)n{rg|+WD^77=Iw0@4n}k2QWbvxq8UA3z&yFeaQ4M z4DO;7r@mtLUWrU!2IBe>vCD|@91z2^cmv=SpW+AZr;Ve5d%AHnaEmh%PBd^YHjW+^ zSVwG$4aee4hQn}tHyQdz0TM&6SVOsIDX z4Tt0K&sRnkU>SMU>gHOsh$=((&)A8C6ZS7qOqFpuF<%)J89^7VSGz9XM zA!0KTtE`N+AQhFd)GA{>^?~qCagMjpz%A`4L^5w+JO2FEU*k(Tj`agm^^vFW;QbXg&yKRgdUA zPz2^j^L>%l&XWF9QhSI*;XCb&#Hxw@-Qm7PltU>gPJgNe9MBBREPbM3b-IsD|%Jra5P= zJ~X2`!!*NCZAIeDHS?{uj4$9CxH_eAR`>OIrzy*5cKV*Hv4Xk$iGgOqPjS*72lgfg zU3*-#wXfo7uhqEYV|OJdgY-$kxt!PZc-}j16XJR;b%wJiw%XbgTN}{hpV(@E=7wX) zq;1gYXkAU*>WM8en!(uC6I(^+hTHSnLYj80adzzQ;9&a}c4V z;~KL;J#LNh)Z@M*hBs=EvGq20RI(SbS#~Oki20|I|Hs&Qz-Lut@Bf{f zkb{|*-{+h=H*ebh{_p2A$=rFKb7tnuxl?YLTOVTjG#gIhQS;$sXSDcmauQih#0YUX zIoS~PLqhUG(&0pi|LVeFbdM^e>agmuVVZTXS;CFpv+7=}_pDb&YTC0tkg2j~n;XLq zYcXwEEy-Qab8F85-mi}0@9ElH2fOM!zv62C zpaR`h1lHzv_LeETU(a=0`k;JRg;*uAY2ihPTct#;&Gm_beT?%yv15q&^RqjqoMa4* zr^We2M$#PbR${(57io6_lZW#xM@=A{s2QAysMF$HES0Ur;#_NX{icVb=g^Zuc%Q)H zeBmA{_N^qoW%*uB>=%n&Oso@g`MU7w{Y@gaIN$hzNbgF_>79r<{lr4L7U%bq;M&I! zbNY3}M6VCAFmuCGq-|k2esfbMxE zv&H#GBy`eLExbi+PhxepI$kIe!5ToT^D~X4`rywg~pIC4=MGvNO|# zIJRtrTwl~?W6RrsKDLx$3LjhE;+fgOBBisrZ9x3;_#wo6Y-xnElu%x^y_H^L%T>nH z*m4&!&KZp@T{vmiC&by@R3mA9F5B0Ki2ICgWyVWb3LG5us%N$apB99=iXtU<$0y$c>#YX!lq>Z z9>W3{R>j@0_6fJc;wI;vT+RZY7G|XIRmzC<`4W!5mn81+Gd_AF>5~bp&p$QMbuMOV zV2?eoOl&)1)6CazPKlcH$hprljyXIrmE`x?+*pLwOC>oXoV&M5vMV-u!>E~S;uM=Bfows<6@U%2k z=iSks6;|iH4l#d|U!2_7^sH0oU1=nB-hGJq`cR~9km!=PB*((_p>@l?K>rrj4}@%i z?yA(iOO<}p!ct0j1xpjj&jUkV;uq0ws4 zycNVL`Zg|r3XmXy&b1}pT*9OuJ>{2gW* zh7y~u%H0Fb3jLoP&oo3Mf{;ofOsO;&2=UuALi&SbgTX31$?QvXLDfKX=zChpwL~9m z4?1hXFqN2h>isx{>qSgE^^R++c3LoOK`g!K3TFU;=RZxCI`uP*mv!pCMDNR4wG?G- zcj_})dB!FBjfm^#OZ3H*wgSwC9}Qcoh%eCvRSIf8Y^5zVJ#52?`YW7Hl#eC)R4d?q zBtA(F(?SPg0Z6dc+3RsU+wykNIi$ZX(Nn|Endm#2XoRDv5KX}jq#Z7&vYL9@5`8cU z(`*2b$y%bTxs0!NEP<<0&6emw{%y+2G)es+T-brGv$U4FABydZ*Wp$pW87K?#T9zf z%XfXTM!G`Zsx-$y<}36;BtLgRwnE>!R4>r=MUTHgHwVolp(I|EcXKB?rWTX}PzZuS!p|?>v?@)T{ zesZqzxjbvWo??FhA4_bWjaVY)YSI$ZM8<6ejJ0inF=QY(YbxPw9cqSz_K zFo&j5dlTd^Z7$Ix*lLOX8g}o6%D)kko~5hNnECKAiI<|;cT>t>Sx9U283t)Pr3kfH zql>_AzCCU-0L`PQWb)V2-AudI=sR^+K3b!XB1T3!E&hPni5k#S-b$q#xIy*Aa}U5; zso5G(4@0jF=nq3z11%P`EQS6CJ=z$}uHF|H34d_w`utwj=0aVt7wef4!L}pKRq*R-ea2`2Mx4~p(lD8(X zMsFZDA52DC(KMKhBR0(jlSphnnAC@uKFtP{c+`AAc?vBHf(De;$*N*}(}1GK1Q(da zg;WYj2NWUxs|%;nKdO+bgRRlkzh()n(bcu;!9(v_dq!&7wd$!@|JlRljbW7@G&Y^y zxs0ybK5-|yia-0sPVFF0ZEcD9DNmvg%XQhZc-aPA%7n(XZ3;MtJJ3__$0VmaO@8R#r|Lk;24+n@9aDW=>5T8HddkZ zRqmf4)r*w&2YY~ce{cdZAA!ZmVZ!pN>#Ypx5AHXfM⩔p-lb3VUU)hEb9;Qwz1F$ zFc^OCjl*y8CP?^iURVbcenbWpz+LX+`tc4VYzJdr_|KgVRSG&EXoVCq*~ZXgQZ83b zmUlBJIU0$sRfI!g^B#YbH!qLMUcwHOyCuU*IA68>e_!;?3hNIbwRdvjJG@JP@T@T9 zcwSTAKY8!bT<$4L_~S+r4zz@YBuo!?{VU|2Aj7GI4tYad1#kry z6wW0##bhM*>- zUn|qolQj^m3);3{+Tg1*c7I3)p;h&i>32W%A*f-?hNKzb!Jf9s#B1Djp2b= zjO9qZ$xN;vsXg(Eo`*%x*!1f5JYy+kYUUZYBAj`~fEl^mgO-qbh7x9zFg+~0hw*?6 zKUPuuB(upcA3BcX@;Y!`7*q($GcG1UkPOoKW(Ex8%I-7Ixc^Ye?m(hc=fh^il8w=hwj@i7TI!Iwq1qUM*tzEu+PjKfG605~=D zC1#!x@wwqdlFkI27Xq;>k?Ex($}`p?;SPfq{nMd-g5(+hCP9$@riTr=I=wowTPx22 z$*Weq-AH^EQakJxSau@Jr=?S#u`LPffz^dA z$v%VR8T*hRNWYr!K`ouYp18t+1b=bh?-$?>KzmFDI-2D3GpJmBh+ZQ)fsGTCoGW{* zF2{og>n?_dDUoO!r1xMBO_PV~Gx7k?CGwdL^`!w5V4sUiLem2{(KeoU6$(pIdo9BWkJpx%W(!eu%FW+eP}l=Rh$YmC&%=lCOH(@S>axoz}=G08VVc>q}GomdNh@i!uz8g3JVRc~1F>DcCOTT!y zI>Hilgh%9VMQ07cdsOQP>G#yf~+z-~@xtGlZNsEy_rJP3 zaT-<5|JB`zbUuOZZi}N@b$7dh94YkI(8{?rs$La+TukFcKBs-A$rl zyt|u4jE`eYjNRQ5j=j5+-~>YKmc(q)-Ax4Uk0{;UCz6j-S36bj?gV*vw-L}j1iHI& zlT>%NGq87eM-ruUoWu{l3vadvNl=Q~#?qP$}-3gi~D0X*(^z-gcSstWpV|Vv5 zuy=PE6uUb?`gwOJsfmPSz?)WHb$3fFTXlCr^U5}McMhq$6SP=R?Cu14cQ**=QUWL6 zv!+yC+MmkSyE|cH9QW>S{cXHR-rcD<%g~$*ScCq;ySqLxyt@E0y#r70MR0{*ZONotpM*bxKvRP}zx#f8YO*S5D1sibzZ3YVz=MmSrD?DQj+*;WbZLPQDc zlQ2DebT8w?+C1}0U?FnQAX)D>5)THh3+oiZT8QkBLORt3-Oeb2Tt6~riMkc#q>CU? zs#&uTQ?4_^UFLSyWLg)x7A9&T(vyUL!Iul{NzGq?{e~p8 z5Ybn2>j0;Qqlno;B;x+j+y+4ZXzmPTs#QdtB3r{Q?I}nf%@s68kWLZy7BEPTt|jUi z9%MTV!r97mK+@l;_aup%AkQ5UVmlMV5MrJWt5&K8CRb$4Lo()tV*00em%{u}I<*j) zgFSBos|!;oPX_74dz}P9`aKbfxa7VfmvhAh2KZLnK!{gc<>(ZhICLtAg~K9`=38r8ehurK($TrshL`5_h(IH{#(ODa}1bz8Y7zBf+7L zDO4dy<7(Fw;u}@Bh1|zT{i)*o7*;Z+V@W((`PLaOY%MYc&j(?br)BcD^HiQnG*hM_ zCa#++_ga~Bb474J;1=WJbEaduts@3NIhufmCo>I8Ao$1{;T9T1P!Y9|7=yIBF*Fno zm7UL|El94S9N$C#9PJmK5{F8~bg`a&PAK23FmHEyy%F~A;SM|K=HHi#(Rf8^@^30P z`q0npqm*BuZlr2^Md`e7E!JNV-8D+Mo^LxnK|;~!L&xRAeZ&T#h4)#A4JYQ`3EvU= z9)#o!=(nBYYaY5}y?0p?2AqhYZlGLC2;P79;OcyM#J(?5bXl3w?+vx#?9IsN^0M7d z$>nOp=H)zoQJo%ab_U1@J9vt#Oha=;SC;K;E>t!Mc4OFSE0!qC9oAeo$vsKAIt)&7 zXP(a8f{#{Ba{AJVzx$Wo%HS*6b}QqhqUjq@>d|F79+K-4k2~r30v$_7GMZNgr(liR zP<#YalsQHEteb9oT%7ANuSj=8l3q5SdzR?~g}8+PaP6tG)ZQen4qP81G&dYb+NLJ* z%QG%=oJ4L8^C@;+SWuXF4*vN$3A@0TXDpn^zfLCW%>(?fVAv1#Eh(gvp_ zJ?}V$;}eZDhuDS2(JL)iMn%{8^m91DYNW>Pl;i_`QdHuCDuY|#GGATD|*Tleotb(<-C;Gd#-T92f45UQ!UzME*HQ4 zPD07(P9+<3<^v+TaX`CF3vWNrMBDf4si9LL>rX&fbzwLj7L^q>l(XM037InaCbaqx zDRaYvBrT&LJO@c^wH*@%ju(l|4X^NbCyxDPdPyv&F1YPur)kjiuicQP?n()Lmryi^ zX^rkk^+(X}P-jrQBPEERtCdja$5C5dR)z<<+O)j>FoqbFVicsRN)htm0%EtQFm>S`qNUhhZBTSo+3fHP3A4jP{H+fWSQKV) z9Diklaj?d4p3X<4u3e8?eJHz)te!sWf1Zz=Z{HP*!}-WZ>?op6F>W~iYNkOtDT%naa<~NNn4j zeojVCW=>Zmb4pQthy*w5JhE}KzE7;stfjlEyHfQf@dknFS5Usf>Q_Q4sJ{ERxbKVK zy!!Pa0?kb@m9G0E=-(2$bn0-9WwDe*p6%psKeC`8zY;CO^|vH+DeW-Y3{^gbPFVQ7 zAT5W14Z_4-R_HK0G-S!Eo(z0*5&w?hW9J&rF?MQKxM8_9Yl7164H^`O z~A@dy|uYFa^ z`NT_M1WuZawT+eDfW{423cn-_SMoij9WKO!*xzVQIQ6Uxa!HNtknktGC1GEt>&f`i zBe&KxqT#Y7;UFd4Te{saiPQ|A6WGD&zS2!8_`194>=?X&C)X&^L^4Pwls^K&#~3qNr4TW|$;u-4pF>)X2>Qs??S=Gu&*s-JFejV|qD zvTu+$W_M|kr5lN{bcZlEe9ZA0d#FKt?~}a|t#;9a&XItgN*V~kpGp$EKY^zZYD}~G ze8Jx5XK*}kZ!^{Y^7X;UO+W!2e+uDh zIHL*WRjXJL^%TNY#HQ=}rtBB1EBO$mE58toJ zh>eKWxaiyGMkC$@!Hp>RGXjR#%wQQ&up2Rh+cM(U$kod}ar>AzkaHvcM9ht-IxiI| zHR5{viz6fMLClR<%xrE&LV49#D}#)9p7B~3@mNTwiP(-2Bko4L1{L=6(|L`{=<=S# zh_{xmcAg3$BmT>>(doR5*vwD?!HxLk0Zm5S646Q*UHANG#H|jDMiktWfFaH{%`&23 zH)002WyBqk>yPTph$E15Bi0ggBW_Kdhl!LL@onSCi2o(#M%)q3Ub0QqhgJp|ajS!* ztA!C|z>7s}$A}SkBkqNY0wbPCaYxA#x0N1gmXHyTuxw<+(Zptki4fd~C-!SH;>C#O zUG#(tq7f%Ta8DFmO~4ROnPwSLup2Rh+cM%mky|SJL{Iz(IX7Z)RWzdNTsFDMh+BfV zCmux1jrb2ZH_A3u8(R@C)~!iXP0`clMpj2Lk@;vJ|cFyiABw;Lr%ZZEyZvXK!V zv20|-KZwl?y&$*|XCK^T#F>cpbJ2+xMk97SBpOlh90G>;#Wc%^g58K2+?Ej+AU90* ziAFpcIXB|<#L_;II*$=4^~9%*BTsybSlTDTnIYR$oo+>x5j!3#T`i0#1O6&vJ4TGS z8*x2U6d3VGid!p7+)?_mWg{c@v}|O=Gl}tn4+J;jiib5BaRnZcX>`$VhD9SD48c87 z@QMTsv75m%qF^^-2DfFz)sQQDs=$cXBj-kZoLJf?Qs*8brAB;&T?HDoQZp1xMQDDSfC~j{`l8hJL@&G~8gUE+H=^LN1PoDcnq@@6Zo~|3 z%ZL+@>w)Ubh_55(M*M-8d!p*xSESU4>kNoS+?`n3C&IZ=wyE05iYOxvHC_uNegNr9 z5!*3h#NCKjqoTlwFH_t>vcz4bPg*uI;@y^wjQABX7W)v~hzAXnv_Jmei0CL6^@;W^ zfNnrRdOI8=l-ue+1{CZD%;2^R_yuxPWSi)PA0y`mT;-@}z)941u}G-_cLs4UJepYA zAHta-yHs6bWsm`HGF}S<%6R`3u^j_O+zogiDxw9~W>qtRwahY^VSMQpm#Gw+lQ;#^ zg7D^@4wpT{Qin@;pK>f@UU(rzx`A{V%p&OJ6sij~#NI&X*Mu%S%N{1BkTU%&+{_Ab z?aP@)Bgv}l)zFW~OVzsga%wKQ-o>_=BbSa1IF)<>6~$=M!UNS606wH9%VPXv*J*1Sjo8 zOr)7%8Q`LDD97`|2!XO^sc^33P?0!Cm1lMJ0Y^$nB*oL#LwI zuM9=f|FUW1WLJh=k+^TW^d zm6MRECZFVy(x2oI&idWd>+ zWiH3FL!DB&2Br5CE=?I_Q(*8Kaqp9i3N`m+}y-|ZRAtHi7xAJXxxLGciEp3^D!^~ z54voT(k{EJ-DB45YiDBKWsCDNp}cCVE2KeP_GQM)x@><#qnL|f%Td;Lm(8AJ&uPTk z7UdHVZ~E1Rr8n@l6y@#60@>cpsVz+4-JF*>ejTA{;UB~jXh!AToO?K4ma603CptqR z-3c`LGAr;L5{tMAJuR$+-6Oo_k-VqGu@GH;l;|Fa9qFQ*U#YrEblXfc!ckO+dS^MB z#;P7vkX+r#jsu(@SR}E>dJ*y}*nh8vZlrF8v&;%d z^`V{5H20VTVODsGi#{diSUdkt!hCy)s1KR-LIz-kk;($l?UA?+tS!YHP8MSAm9b6|OD__wMXykF z9eVB~_)RG53Lde3puIdjOu7Ouc&(W=WlDiDy1<-%EHr*#m2fON9x#@Epu`_ut zl-wJ>1^hUOOLsyY)aUd=)8&Mchr?y2@`(zL2-IpjKe-l1X7S^r_)`63H_ks);N(O~dl;#O{Ij3PEqb_v3gO z2m=YR_2}xNncsr(8KLB<@B-T0fV)F*GY=58&fX{sn4}Y-e z(a<5e+`1$z3GW_RluM2&%9D_c?ma*3J)ZY$$bS&>q?cT8&pwb?G`jaV|5AzIYT)p! zf3>)1^!~i=rH8VF)PQ71@kRGRWMIG)*HGwukUbwEHqV^mdx&Mz=xL7VkT-`|Xe4>WkHp*~eulIGHjN(9 z{Y)v6NBoVLm2UcDJjMg18@iGcie_QTd}tu?NEp6jq2Rv2;aQ(tj|B1SAwsqwFuCq( zf|~aT_Uj=T9OpfPG~3fhMYcw62wJo2AGB-B={3iLA z9rNv=B|89oliXnL*=c5|#R93*ew(CDJKdc2OLF^31^YI6fz0r{)MZ7Nn0vJmjsgAu28}blM2E>9j8) zB?1O=<9sQtslS$O@V1=x?{eCPWEr%1JpTSCjOnA2+G4j;3Z4f#!r0 z_^eDa2A@BIM86cLS>`;7Ov_l7~rf*Y}SFLzUw8M^|ev7Wa z4zht9tvx$LJay=ym%16uTg$e_Wy`iVzg=B^J2`1URq^#am`Yw3lJhsWwd1#w6G2UW z`&9Cs9Y?=?x`p39ll*KrPvG{a?z6(_tPYYFlkF(aA~N&Gaz^q7%MjpXUh>(ks;yk~ zM__Ln!PgNm?+ym5X#{)IWN>VnEzfUq(HoH)iR!Fr?f~?rd5)Mj&FzqCL`s|HE#s(Z zej(;AdM}(u2<24|SsB#PY;{3wn!|~uE~-sUe<8%C8D=E8=v~C>L&V)hr%F&ichLI~ zoRY^9`P4xhz}*Uh9wbncU2jvqvVvf@LI$^Gg@=)AKy7A)ju%ENY(dPe@C>A-BBfUN zyK!WNGl;nrro)*-D6g7iWsnsn7*8i^ffZx{c~pB=h8(fFITeN{g6vc{WeXz1llSbH>2vNy%`?tY z$6jqGMA7I`m#1GK9AOEY3{!ty3D5fLE3LoYhs0Mye-ih9SpEBM2cz~HgMPRuo-1=H z-!Lf2!^z5H)QCD){=7JPiQxGJTKa@LqL&DEFUjEOB|BWwbgsOL+!$16Uh*5DpDUYR z8olH%*k+1Ish1oI;xow$h`E=n0cU+edDS8-gS=#-@#H0S#L{!6CnOm=ddb&D(z&u0 zx1H)k#G8A`tD%7c957BR5E~uuv;L%rog?Ol-|)+uZ(zugjUG(azDLC?r6K>0#+jkp zOSZs)Gr8kZVi4~`NTdry?6%vTD$_L5emCM|Vk-|<6UlocuV`Q9$Z}POba___`bthr1^UCJ?J{ERYRtMqP} zNTqx^E9Lu5r4;EE5!e2Q5#>eSXQeE?JbF>&WuE~Q-fZKVFA z%-0EHV?(Y@mhMHBS>}HSy?Hs$VwS`St%V-DJ>sVWF~S*rOcq#rId+wM(Pk{zVU|tiYB@v z%lwfn^T^9GcSxBF+O05ihm?5+wVnBKNL{4NHyNL0p3gFWBg;JUvdkS)=7LTv%-kVm zoyeE+Yo3B#YAs$@t{@8s+mDiJL;=Lw3Y=B~}-Hc%_M0 zRLfwr;;WHVL`yTDOnm+`g^z8{ns~4AA4tfaUMANI*7QC(Cc(dLiwRQ$I zH#BWxi#^+nS48tE z{VEk@_2RuPhvw!Je1+iF=F6bwHB8NSKSB>lu%h^6(<}3>LAI&+ggqj>Yw-lbWxlP! z{UpfX=E~iCk0Y0NSvTKa$hr9rR}Pu^M9STS`R-0S-W$z#wvlDND=j;DUnFMcbCS#_ zQhkU7H{Ttkx%Vl3mWr}^@l_L)Lv!;9eo1g^^JP%;8m8v^6rnF9SW$ex>6Q5&Cfn3} z!oCvTwfIBBWxkid-Fz9`T)CU?TjXSw%=_L%&dv9Qa>&dlQg4}WOtSBN(R_(LBOvp2 zA?Dr}iJAGFB=d<>&m$qO$<4PJX>LBHcOYQCnfJCfpWsArYx8AL^BSh++X$geC0J4X ziRqR3b|u@?e8M&t-nF=!)lB9)4BX9^!OfMs`L;r?x68Wsor;{B?^5NEnNOr@LULO& z^8RSP+l(ypJ!IL*`yw$jpOa)hk=R=@)#T=@BhAgH^gaa4S7bRf_ddaU3T|z_3~FA( z)O;r)bgBd^iZ?L5GG7DPrsflNy6~>W#~Lp4Ew%cn@5|uk%H4ctAy@6PZoc1;bMvjl zQxHw&6DdzfZcgSr5Y5*EN;-59OZ&c*n3>N>GT*L{==)NFo3DyAH=ok4B4EBfEr;gj z6MTi>*5=Eg<~2;scRxZ8NwA{$c+)HMok+H+`Gh?pyle42hRb}HT76``3~sJG?fa0+ zyR4gU6mo99dzAw}A38+Jjnes(luV4~n`&fvpB~C_^F?B2J}1e1BGrdTaPxgiTH5!K z!z>kL_2Ll^Du?Fglh{jwTbnO~n%6Kj-=_$DA;F5`@upYiTTZsA`GkEXyle3i!)3nC zSH+VzgPSW)`#$7k6=dCf8zSfC+kse<`9#u+JGnmT^H4NjKO@V0Cs}qnc_T41pOa)h zk?8wUO>Vx6NK5-Z(mN0^U)~z1x%niP2ySh@3~FA()O;Huw5bFuiW^O@%y&K6rsfm2 zx$v&VYg^4^zWb~`^1cjit~~Agkn8QTZoVnVx%uWP2Y!Beu`esH{7X!KN2Zq-KLPgX zub}<3Fys1nmcL-{do#Fs{yzOZ5V^&u&8EMr{!{sD`nx?bpZ*Sjv`nOQ`g@3RH2poF zm`{HP!x>88`Zrg=eER!{@mfrO-@BOypb70weD|I&ihBq?6q$sEtO>WbMwI@Mj*@`%-)XVn$FRB)_rXCCfo zUEMsi+^mA?_J!uvRaK8EsBX0>IG^&jtnRxgsX$3`adPmaSl!#8dvyi(796W9$g3-8 zFi@yl=syh+v-AM+=?nID0PtT*Qj9fR= zW`n^4RsszMi-`GPpa$tJQaTv?VH^zx-L8*=!6|UgCX`pL#mVl2!NH(@GxQW<>0N|J zA*tJFd24^Do=1sb^IHhq0M(8A^5QFba`w>TQ^=s~S)w)J2L2|OaQrO6?<6T!xaq?9 zP%@pzAeHKSAg#1(c#)$=LiMIeZl&EqZbQmeHjt#U*%vd^97n7s3|#@ui-`VAaLv2X z0kzgF94Uz&TAVzAmc?7BXdm-8>B8|&1Xu7FIfaR~5z|ViD|w=q;S4XrZW}giA+J;HW8kdd|~)fo%$(B zo|f71Zf4Rn*h26LFSOICpOOe_x}kPT^6u6;=7w5-TxChHr`8512XYIrX!MxNmxK?$ zqF+1JdVMycxcr@P>bbe(v}C2NM95z@Kb%4Ri*Dl%u-yE#{&r_~+X0b`UNSaWlM}0X1_qd%0 z&Il`=InZEDE}jJT9cLn%O)ebL>@kDl3HzOt>ipTA{EtDUHo08stb90<<7GFhv~rjp zH)*OI@ws6rX(y4!Z+dv0!tH%m$X!9eRZ(lMOVXz24 zhu=|J_%-v_A`pBoV#J3t;<%JZmMZyvs2r#)Pi2sw+u7lkI1mXQu2OVKwl!D-kzgN)GPt>4`#>}Txm-P2 z$ETAjk@Ho_vBZ2J+WbzeD^fZTjWmu1qKAq3s-zd3y$R)2_gNWqQT{#SX;tzcV(CD% z2Ho7|gt#i%=~iW^+u27Es}B+PRmpJD?B@@`+(2=AQ4;*{t7oGnZieGSvfxo}iCqkq zB?P-AGPo^E=+k)p3oY>?a&C!b#M~1466UZ1OLVCC)Tn z3riGX1=Y4aOGMl)aRn+0EHO@1bxZs>C0gQkIBp5S6WkJe8!Sr*c1vV%Tb8&Vx!OWY z)LZE_InjekZi&g%vZ25d-ENPT*prxBA`j;kLV48`D}yX?zVTXE;@@;}s%?9gh`3wg zT2!Q#&|v)p#a${(3`y>OUWL#gd=H%Y*84sSTsD{CV&Bl;VD-N51AiEFZY>6`6uiqW zhU(N>n+G!7j6&ZhaC+SEoOH{Kg58W6+?E+XM6Ms2vs3FRa+mo1?;hJ`8%Z=dMn0C98~GG$Qt@(=kw+TG`Y&Q`CU1D*`Ee*A3&lY8S z-5nQY6_}$3Auh^J2k|9$H8KBrbtj;tUiCRXd9yB7cM2q5g9=_II96AXS65KQyr$|3 znHhSM;?@0xV_$=cIhb^+JKFMy)%7K};A+9Kx_j7T6uQDtSl!2=jS(%bK`(;lYfx3S zS3z~3Fa=tJHdS|?T~L{Yl3J7`CvfVhWoJY6stQ^xC{|UFS5;7Mep6M2@IePsysDpZ z>{S)BAL&%}QhbeBf7-HMRl$P=$ExmS&rP(f>TA%dMT=EE9hz6QjB2WNW6R!R3Yu3n zU2HB4eRYELO!~pEtYP*G_ftxB$Mkkike-R4rWH}orWMf`iZja}G2FqPDAa>)v%*WS zGh6PJXoK4;ETP-cDA*;r^{ia(4omoMClYqIgy$^b`Qs>5Z%bH#XAan$2i5je;-2>C zVP6twg~10P)+f2}!d&is68NQ0zIRuhHceEYUgLS}kDKn#QRpczwNs}}6G3*;FC(M$ zq~EOhNq-L7Ixj%+mdShhcov+5YIhC6Jp@PB5ag~Qs5ekN>4mU72#?gv*Mr#Okg(A)X0h_8^_={?qc%nV{rv4N!eNFEadrfb@`*g1M(QA5V*lT*Hl90afG^F`!daqNS zk;o@QiXNMx%NOyDCx1;(@I>IkH=g{NSRwTwtuB)nyr%aJoTXAewCGJ!-rj3^t6-5F zw*->&iuRkSR?r(yZ%}A|D>xh?NktH=fqLUnISz*PEEX@w73dg9-7Cr!$SC zH=b@HW~ZCpcXLDmA3%Yd0-F>0`8`NSGgrhx7Cv`jt<~?nQq?_0+H`iM+)+FFeOqb3!}w`fG=QyiWHu3F(LNriKsV zfqw>1Zx#O&au3KQe=9l*Re5`>SXt-o#o|kd(b9Ue_!XG%5K8tfs)6Zm7RN;1EcVY$ z-Yo&v^+i;FBZ4-(J}p;rfYsmyK>woTsz7~}?SYt6@BhAIklz0lG)TqQM;Y|~uOR!? zgtK145jxCCa$6Ama_=6TSN5I8vvM6?2`}dCO^D}vF~&4>;z;jdpNOe?qjlkiymUN~ zD|86YnA@^Rv_bw^xstyIy}fON@i0m;D?G|eQ8!BE-zf~Q zm$BBMgSi@*eYS}`NQ`?s5ax!BIiADuydXEIMli41^)1bZ&J^TR6H=Xu9+FU_39ZZV z&K$oI4!wYh7D6`>Iy9_OuPn|YP3(L)f!I|KW1j_KKYT!>-0Nt6Egw$exDF^E1`vCf z*v!xkY;HK0<5eHgac_ZZhDEm zoURjU=OL*FPoa*p!eI%6=g;<1ohGN#WB8NOpwr`dV(d$7aymV(n5^SG$9{S&u(sXzKBkt^k)9s) zu)J-T5Yumgov+`M*K+Y1{9Ntulz2K6Ozr3ME+JdlE%IGf! z+Z`RqaX#$H-!Z1)FDYIvob8U*=Xmn7(yi%+3NTT~F|%!^;j;{-Hjo;goo&~=eU~kz zE+>^)!n)LDwq2C-&5s0i=IqEeKU(EEnb)s%KMvSKV7yjz%k!$FW*6@e^V!Av58)Le zrL&6_Ul2#Li%McXyAWq{LV49F^7q-rNygLc;s# zFEGCtHmGbZnkijicuI4>4~Zaq0-=Ra;{;Z=O}BDb}KS^wr;9 zy2G7bFKyX8{lL6=dLUl#^VV6L0uP2#(zU45Yi+fT2sIE|w$5VGymiFr{7(C=(-*w2 z@K&uOWQdTob#|eI-a10YfW+3h7Q|aeNFIdN8Q2h8N3ge!;KhR5YMny>m$|IBP9t)D z@@>3~!w?uzI(5n_6ceh@U){5%bm&=K^b;1y%-4&Bqz9MeFQK>-0uhd#%$S%v?0c_Y|cM({+zZMDqlfO(fq&l}{tW$q^CEz<*wFBK{6)?PJ^ z&YMq&eQ3RvIAu#@@L`NC+@=L>c}jExccYiQD5FmcAJcw&BiYZ|)X%mx!3xf{W^JR- z&Yy`h^+HpJ&6xA*v-4Yn^p)n8Kf10pizS2 z3PDi%W5!_0G-H@Va-B_Xu4O>}gwWw^rY>46X%^zMnhYA4&T1AQmA9pm&uTQDXu2|s zTpQ4x{7Hc{r`i1_5j9o0jo7Q9$NRb5mkTx8D)Zk-^UNi<$pZzMi|(0cP|SSe87(sR zypKn`AL^Og&9=Nf-y2~wYXK;nB8i+QjVaQ{Z%Cb{NS~QvO_8>qDWOIPK1I5k;}31x zBEj4T2sT_~a$07zn7a5f<0OdPL`;_%E$31FzNJZcK^V^ZmjG6}tT)e4TO+7>9wp|@)Bj=C2qLA;(`Xzu&yU2s zdBi!MP+oN~M)T%bgGF9Jr|mP?;gE)*ti9$L1?JU{O#B} zg1vPFR|syab!Grox~#X(C&>9gyg4gOZ=JE66oW)cTjy9?d#ZIt5cAd%=K(u;mRT7z zMY`8`El!@Xv`#h3+H0LLVBR`Y5HI+7m-Z4fhgv9YPLTvQ0=8_K&Y#7W5u-Op?X}ET z;6sGBY8fG;grqGqpVE2D2&n~$Ewj@6*fK&IKr@yPyiPTQGJnrMPIk z9dirDE;@B6@{3NLe9t<&6FMQRxfKTf3ZiYot522NCcKJdoACNUx(Tlzq?_>SfXlag z6ycg&hr48Bo)e~=9hUG!?T4|P)swmY%eC)p6W$KLP_wo+;a!Y9vQ2o04PRAA4Ixa5ukHsL+^eYNEh5*uvM+d%ANi_IYRUt;sZanqRF zBGP#&Tb|D5`r!l;R9qfsd#^hYlGEWNbn-n5c7QhNldx%l>-x>#PL5k_TT*QFb{B7QHGJAY{J{)1J&|F z67PUCJG?=R*If8J!}1)M(kCiUZNfV?quylHD>CYD6jYk)Mb##}yJpl%qi&E=xp!$r z+n?jlESK6;wCoE+wF&QQB;>>U{8h2?VJ0yZh>Lzu=7w)LE@7qVzgI(FQYSU4ozqQt z0s`3wqJ30I)ti@k8;Z;HCgkbf#ohz>}-WThUP!CWSx)vmItL&rDlZ39iV!p~n zA@@1d-q@Q>c)O6>)XD04p7Gru5@IiRP08hh|nc#6t<@aK=C z>)xeQkoDj;^6XN2mL2Pz2aJ^7+~3u{+Hy3@?eymU9;Md|&E+m3A-%cZr*sJkwg>Me zTopZ*YnmgGPx_Qz_pyw81Bu#$cbx6YT+T6lZ^gK%a!mMp1;bu)KU{)BK7#aVA@YdeY-@E`LWHI-Y(hD zj^jfsZeiti!ngzweOUqUOPR=Ywser2UMLv7}@=K#9b)(~^A-5=5zky5XnYaDs)SH#?F4})_w zp}cC2l|f#+jxE3Cwc8R)z4mHIH;dTTHoOsR(`$z!B?1<5>+B<~c&)aLF57hl^}ajc zwNp!KU|sSAFI_;;q1a& zi$Ugnp$^%0;hkNwGexN(!&1-qE-rs0q^&#TERGch9|G6D*uf^9X zOENRH!yFiH2SIldutRrD?RF6CcF5qi>@XI&euZ}U6FGP0^;yxn9VS8=TwsUYZLKRi z97oLU@HCt{LV4A#RtDMOcH_yJ3+x~p$kE!fL&Q^m&UWFIvzG0pKiY-&gAj1raV6Dg zdTKJynvm6RWIXhncHDMciJ&I8ttq+Cj-%U-Z{fBRN-i~=O?a!Rdb$bkVRA10C+kyBEw!?{e%Nzn{Ac5~cSrOGT*BMVOGnrWGp?6}(hX}D{78yw% z`ZKZm5OMd=t}Jrx=l*#pf{n7oqp5#x3GP-9bOZq_yksR%XDisPkil(PVE}T=3$1X9 zt*v#QUPH{Sa5ALM-!`464;n}QIhUAQ;cPe;63VN#qh0-)%b&(;VFg)09@U-|BHqG3 zy*Dj%&@0NAF_h#{_3iUqNn)+|FLM4aDN2_TO|x3-S5GSuWDaT@F`QPCZH?Q5x}{s= zo?&iUur=Gy8>So#@%tiQY%ztD&02Q$i6QY+K`=Z%`GB4)@@To?`I?CAqz1 zi+{^7^5CNwvc2sDUrM0uhJPzqZ70~=IIj`PtCm?AKV)Y^7 z&D-wPu$%%6{z(f1+ZuP2o#jni!1? z5VdKhNE?gT?Z{;+lQuOSU_|Xss}+%NjT?E{_K^;4NjnN!nUL++>5yK2&YUCO@Cap8op)>_@alZjNyO>ADSQtnJFEu~1qMO=HF z5#>ewj3_TUF)L-{WuE~Q-f8l=W6^L5t#J~re`unnMYoh zxkJia(Dj9xJEY7rsCDLQ$XcZ8mHCE!EOVJ?f@LlfJwq%tkw}dqZuC-C%6VBSwc7E9 zjJ&Lr4ylxa<`FUzIiyl%Q0r34L|;jY9&N3ScmE-p=!Y!xGS&^AdE{l8JEY77eOs8h zL&`jZ+Rl7sGTu~~Z!$H@d>vb=$T_yjGLO70bBC0+3uM|FcLd$^C<6Wcan|2!YuvLfe{GFB znpnCz5v#^W1|K<}0P~Sk&@BW;zbU3fBd1^=IWxFuu?F?#eX!L4p+zynwoWLGodzxPD5%wW^(^eF= zg7B`z!wpv}{$lw`c?LIE?mNt_h@7mF?Gg4DTOn#|+-}75OLrEAG=z{`Tk_fRXuchd zEb|>e%*|Js5;OBTN#+xYorP0^o9{T%+JCAHr^9dU$ylZit;WD2V%6<}LaC7BuzGILZ;JG`#d*^!^OdrUP0c6lZsA>ve=}U>TMyjLm%+`IyZP=xuGVGU zd_8SlF7Ml0Ib`M&X&E8;N6Cr*jpjSn$THu#mYvKOiJAGFB=d>HhlEm1ZoaEYbMq9J!$pP z$(zB=mAm=gM{b$Ry7^`!=ic|Wa>&dlQYDl2WJJlmzeV$XXJnbLgmu54ypfoh&q*?$ zNcDW$-8H%S)+Ei%r}Q6Hl+}yZwH%t8Pw;nwTbnO~n%6Kj-|CdQD*^NEW_o45Ey*@D zpRl!rcP+lyaG9@<)ko&b;O5HReCr}7t03#BYk@U<~!PQXl_1VwDNlW`a($6PgzOjEOhvw#!*igZ( z&6h#VYnYnvHiYh!U`6p%(<}2GMz*Q>gxxK?Yw>c!Wxg}5J~CehH&>qaeaO|itebBH za&Ep`l>rgT%zRFg`9z}cOEtOq-XtyU`$&J9 zfcf6F25N3Ti9IQ}wfQorc@0zZEkfvR304&U*YwJKUyyBTK4I?)?^?Wr)lB9KT!8YS zBZHeOPy0UPmbt8(Z*{w5rlF$;G5!3a-*OhGOEvvHFTLou2e40n1^riR*DlGkS^k1O z{|s)PzfXVvKrXkeVEQ}6^4IkDW@0}5?Z}d*LZo#1TWcIme_to&)87g>-3jGYn{oxr zr@v)(38}^O_j;zjWBg0y!bE9#{hh3U@4!j7#?`!feGPgIX-mYrSp&K1dThxu+VT|M!u<}3Rf~#p zr>@r_` z9>6!nT`M1Qy^(HI{ZA~prdSQT1&M#R$#TDdRItc2_GZt}62O&J$ zM2c_ea6HGpS%;W=6WG1tZ)sst~B&Ud$y&+ zv0U-kzB^2_&zs;A+9Kx`MpA zf+hmR>I&g@At_$n&RkscZEM6_PCC`?X?euz`eq%1JAVfpt9zzhmTOtvA<%k=7I(0? zADUNJRb8>5x=Tz!Th+Y|CB0FSoLq8BNv!U7(7n2X2MdnX739?wGzutISIEpTg%q#u zDqN-W>WbM&I@RrNc{H!C;N^m2b?ku+kAzsTWvI{r53$zij`Ves+%=aP9e{b7Uw%vF>^w1_N9a!=k?IbI4 z-f8R8m3iW^lAd6bS=rCkrv z)~6E2lG;G@AY_guwAlLeJh;B~sR)Cl^yjb~rG*=az6^;DMjMD$!5Su3s|`e_2W@?- zEcCQ5b$H$Cpsi02v?~nS`t%uM({1Zh5icdMq3P*H)Yhj?)YhjWrX?3kDqC!Q+KF}f zblbF5gb^bA9G*l~VaY{8jY=+tscBVmzg>AB_$asjdn?GOx?OpJWwIqbi{J;9Nta|x zgXO4#-BB~REk}JAxmp=5UUaQT&Tm&1bM?R-^=G`JL8P?1+0w2n$Wad>=8js7ldfWp zI?l=iJ*y-wNgTnKPW^rnVAL`p5OpIsu5CC((~mN)>89s}q5zg7lW zVw~|>SVC49@jomPaks=%s3@>Rp5peVBzW_`{}L@x563Mbc!pbI4})b1!ET8RZp#w0 zksDlSiC?Ysvc#sW>D?07P{UCLmN?i}`?AD&#M~0M!@0*SG1OFU@27M8dPD`)^| zuk(s{^HIoq@CR|ui891qX%9Y?9NY+k9wyMFd()qJ4=&h^kil&k;W6a$g+}{Yjzo-KQTALY&fqF*#FhaAS2vpycR}~E2yIF86o2C4iBIr{n;aJ zEAUWpuG30IxlY@W+>K|29%pRcrlbaq6JKPgfZqdnlU3Roo3|+uWQ&4jR4LtVZ(Cag z*dCjj(tb$j{1e9BzGT17vZ!Y8f1ujuc!GNfj&nRgKF1T(8z|24gz)eNDL%(rm-W2Q z;Klr$z#Ol{^3WVlbf3XzaGc{^Vpjq*$GewUoWV=O5VU7g+7(!k`y6i=<`_wcbG)9m zRM#A@FERi53_cMPCCOh)c3L@Bw;GaH_y2MB9`IchTmS!ez9}S%1cORM#7F?6fCh;g zJBSLRXsBWbD>ej0#12*z3w9I>maEwDUJEKnR74bz*bv(l)T`LJR_y=x=bW8Q<#~S3 zKdmzu%)s0;X>&C9b zDNVA(=6W_W=~INg)q-Yo@^{-Hwt?>4YkI{Hyh?Da7=pZF2+HueNvs$`=7$ne zykZO>?oD3I9oT3Czfxddhf#EI@+llE#sffp)BXmb*yJUl0_kbR*om7juNVt~mg@w` zFWDSvw`HmrXAtr~Z}Nj+^+QNDH^2LaQQb!&xw?YK2#)Fsa&-kw1B&Vj;Q)a034y>DPFCFFyRVI8FmJm?q< z^K`a!iA`y6A>bnWy6-5UfwKbg1Kw6ROlB{ox+R8fj_ ziOsjUx|VSNv^Z4N@VyY?s#X4-!pco#tU)9mV7FI&37tY{ei#Mel`xX{)x;MCRfAeG zPLy{2s7I%f@UUf)PKzwl49hf$cn&uzuZ5>4&~=mPBeuNS)9qw$k|uUdSV(99_Y*Xh zc@z1f22zcrv-Zuq#4iS_39k{ln-B}@nDEbuzi;sjpGv+Rej@&yecSr%mMk{Imbbva z%&fAZu)fSZkWl=a8&2f)M=N-ju-OuulS!BxcB+?bOKk2>!om=lbHndX)aBzRdKQHC z5Eg`@2DDc~SK_B|!o}frG8A)?5(>KEbK%AI(&tMOD;c>iv9HhsR{(2?O?BBLLHx5x zA^kwC+tO_4aR&7xBxnRs+GX>4DI z7$L2(`A;nO3W$G1EKc3ujIg=B65gJQcmP|y4^E5TLOKhrNi40p}Q~k=h2&)O|R6Zi4Ysu*~E@Y;x{(1h}T}05` zbRQc}UPS0#LUqK}e?$B@e^N>;v5}aFXA`0gL3lgdPJFSo9~H5NG}c@y+f35chCGwn z&^MN86@*uU+RzbWKeqqq_p(dy{)WTUDF8&vD>>-o{2wS!&!a@teLnJN;cd%a+c1{TWM9}(CM;bWP_Wju} z4HJMWH_t(*vBb-<$D;7=KN-g$cLtcPAC(0<1*j(c4D>#sCE=cgv=EXOU71gOL72^c zeppS~l5j@CD4`B((UqHsvnn(D9qFQ$gkcHZOE`FNIxLewuXe{QrZUa9}L*!*$}B_08X1*G2WC{5*?1?Cs`i3pP+H1^3X(%dIv zEEi)fKB)oE~32_W{m8is*h3QVo(0|Ly?tHHrjH0KzvNDX~A>6YTyGJXLUW z{#gV#)APE2ej=X_|8_x^`{y)Fx?H4W_&3JRBL7@V$o(VExomv@XQ+mMk6Wmbf3~3e zT!XN+`KL8EChnhC$X@Ty-SYtjE{DPjQm1xm&OIWGfY8`IT4cc8BSx(lYjID(tMn21 z&ACTNg^wm!#HwJ2Q1|75oddIPfyak`Sh|-Bli^Io=l6iyQc)q-7}Qz_5Qq9 z`(ZH_f?`WZHEuZqM*uc<%~aCdHDc6=u@={q(gUm(-lR7Z(z>9|HOEsrca4w=kkmB~ z0eQ<2R1Jh{4(%LWBiLOdc$DDgT+# zVTrR4PT}B>4AmM^jXSLs;BNK%;OI_D%WUT3(AMTucj&X0KXqsW=j?Gg&sC^RYmj7X zNF7f?tz|fr&?khrbuZLuCJq$W%qTts$kmgbJ>Li);-LLDhn^hLqL-5tRHf zYA|89*T5l}*Lz%|`!D1j9h)t)c_|4RiSSFD^`S#}KdX_=XmZsb+31p@vCYMtbtHq~#^I8tZmdG3$?| z;xOq3m=nZoI7})fgAbELm?^@REw*P++;o^ELahkR50lma9YP^}m^2Ex-k~ffTWL$` zx>h1rhw`YEQNyH7x~Z9Im?Tm^NR2y|F{F9NBE~c^*3z*EuMys)V-d1SNP}ULQd_TQ zol5;-l9H=PrbD?Och(;!391&nx_~!C{#6 z8y;yoOcEi}ic&Wkx|WjWJ`tmr7;EuK1^5WzO?)C`qLAb|d?`ir&R)n2khHUZ705e# zK{Y`5W*@6V8o~*${WgqGMawgi)w6xI1>l5ymp8wvS! zSe%Y*g#(|pGH94I+jwcW?ZepJAXOo3ZT_hSbN?(Md%Zt*&wdnm6cmO@H=|-x_lPh9 zLSy$VC(Yd>M(fsVch3aye!`o$N5~i+^yF(G%)p|8=CtY7CI?h@e0JskAb%)L~ z>8V2-I7h>z+o(-dNJ@uEZ&?NnlRhUjKUCXkG)($~xDS(Nl4+DOX{k*OleXAakRGNA znkXm^lLXcMeH30|!17&w_3I&XJzHPUmr*evL;0d}b|+<9Q5Rf2Ga)X4x~aWntopJfj?zqxZk|+w{{gN4nCc z1S~~Zy3(c+TJ=;yveM=}4Q=a^^ul6W+5P1uRh85ZhJ=xRcX zLXTIuPbEt&S!@->Q%ShnNXHO*(n7-ttu*?qSDd~|bgiQJUlN@DDIur7LrC=beBG=n z$E@^BE~Q=+_8_9Om5^SnRTPgR!HYD8kP8|{$g@{i_VbCCklp_lhqD+C+=-BWpscic zEyk${kCE6F(t>agp_*_L`vdKqT@(5!ol`4qo|ICLFzTR`x|o7W@?=r9(&l<8mBJ(S z2MChNJ4`EDds5G`vrJ5~E>u>nw0S29HQ^EVDppOnKFzwyvd$%b3yA+M4FwzW(HQY` zrA<|j*_QBlHT7d`j{N*B35&xmxADC% zTkVjV>oBmBgg;Kxm$^EFxw(3Yg}DwV$46l$Pch!jn?ZlS)mz+zfjx`7Gk1=CXV(Kl^^(_h>Q4 zrZU+}%5N!~(1}8S&YxpnnSl7L1|icxO75H!-hc@(Kg=S*CpG-e34FSWh_!4?YIwj- zph*p|eYQ%9=HMTFVq)(yO77q~Ok{YK4B}szNXA0sGlOGJcnTT$-=8$JKv!^8*X!P7 zM8pqE`XFxwh4i^w10eZC4#AnWrg4pFEXY+BR0i_ugXM{V~8 z@hViO?Yp5nj6Q6CQ-lx0$GxZyEAo=JNfdknvR?`|cjL1>eOhn`QeFXnj>=-diNyn(GsTZkHeIAg|DxuM+=aI3gQ4fb!Em}!ljn$%M(7X!C zRMqv2y7ewijk-82rwRT2?G-1M2IExYQk|T=g@?s zE78YSGjK-SG>Q8nZyeg!g#VKGK0;m#FDLL_P)e4)U?*FaptK<6R*_X7=m0$DX1huw z<&03tvIRl8=7xvrrRH5thG$7ohIwJ91k#h^{Le#wE6ETNdjii5t?I!xOf63!wNJIc zqscc5E%H|-{o3B-^GZ3Akp206L>A^k>H7->(Cqv(tpJ*xFDQ?V`-nwW0NqCj_IWBP z9Pc9psQ~+tr+{r0V#(|G5i8kI3vMj@{xB@>{%BaK2|N9Js63 zp|QLaGoJ1UjwghD^&)9A`epUa&CXMaV54~|bnhB%&j=?S#Ay3UPH-=qzgB*90#_id ze|%ad=kQ#;Rpv4t4BP=USiarSPAv zX|R2B)uP`cw|^Tj9(ldsXZz%4%}nyc^xflpA;D*|Vavf*ujL29?uQhPe)tL~`r#b% zjgX0>A8zjz{jh|P`{BIzxUkgo!_UT%A4+;hKTLsh9b4hRm#hqW64D>kpHv+|DDlJl z80IUsc&k0hNP3}nH=%_g;(p`zk}~RVUO0=EcrV4hpDnvj?rvs@%Se0|4r}0|bcAy{ zF}l&0*@Dz^HN$%r`KHN={d2op1yQ&62L$i-1kV;6yFEeP?Fm{A6uUhk^TQfa{94j} zkJ#;rS<=qBy;W8|T|dtR_I^)rh2YrlZP`Z_($#Yyp?LLt8d^WmV!!wF-m%~7hlz)? z#f!;G5O23X6Y{@#;Raa+AwRHX_su=m)P0o1+xv-r51}Us%?;{zBQd87O>r6tPEu_b zDVmQb&6yDtDmy**Br1?!ieH1^<`Xx`JF?K~+FeT_JoAK#Hq-5^*1Sh`ALT>TYD`XsB)qM|EEzXH#{% zBVhv4Q+3zhH>z8Ms2 z+={3!<^?5%%Yfe}Uqzk|l=b4x!=> z`+ANSO z0i2E;w}ar>f@6CZj;V*JFwSy#N zHmzre?e~v%Sd9%b@7LL3G)U71psT~B2q{5Gc4Y3pdq%fk2;J2cTqQWFE6CLqG#n_Z zD}(_%DX#9_#9du6uVh1A=7v&`hU%tpR5x=#bLvh-!Zf6(ZZC)CZeM}AQaQT4+5|Lo zyU&h)5FxXq&yl>Im1mEE>Z%H=6%HF4*ykx6 z4N*(ZriPG&TBN6jC>R(GQTPEb4B4U~dVw@HgsZy;LRLwi8*{hrE0WY53fuj0Sc znx%47x8tCu>UtGF9w8H@&rL}c-vO$tDrknF=vhIos-PO6sHzYq`I6$Q9!T6(74sA} zRDH|L*-+IKj;cOR&ZerKiiAvQJykz|=Bj>!s!}(qnmf3us#Nh3a{tN5z^eFhNfn=w z^y2p-z6wHiRBlHbEXn5^BghRQxLR;DgdjJBpiw~45JH%~Ns1d{FXCX5FgUi z8dvcYj)u64oJ|cO3Dc0C`usg;NwZ$vq323et{|X`f5RyG1sp5r0qpE^N35u!;a#aOQ28yZ*;r#$9?%6GgyQ*UT zmkm{)GIKUmHHD+9myolmsy`xOA<|P-AA#no)}W@;jh2y&kbE)g6JA;=9Or~)V&LI~X&DQ<|i!=fR?tYpIw zH8y%}XowV!h8RcAriPG&5lBxB@enjO#4L;;V?;xIY62P>!mIcJ2$>*##^(N*s{1Q+ zS6A>f!BJg7uCAcjKv7*G{1y!rf|QDIg|}`AGLEdR5yjAx_ZFTRNdi7ScCLb z-P@tLx-(E!Do1q}n1F`rdM|z&LRy!hfje;=x=DyTwGR8^3xDySMLsw#xv!6U_0 z{hhe0D(0DNsCtWyE*q+v!co=X!<$p}93)IddaCL~Xs+s1)RekW)tM%sp{i8zndE+v zYrj?TGms=P;-WmgmR>(hByzJ8)70xkTIemo-_ds4dGS%Lxl7~NcPO! zcWhj!UVIUBS6A=|!BJg7uCAboKv7*G^TP~M-0xozcXh@5gbj7CwR1G|dkRN&`yJez zx}PDT2I;A~W1zXZV^CEpM|G!}fQIUN6%X(7cuD%4l~nPEp}MMq)(DEK3UXBim2|FC zRml8MMT)Dsgt)6JW(zh{J=aE;4OLCysOnaSG^gr1NEnXvRMkPyT-6b%DRrZ&XPJP8 zs#3+rko#UP>Q=?iPpbH;q>Ar{_^A-G6LS~Ym{2~y8bNLd!7~L%LkMz12&w^!J{Ll_ zMv5EaS>kR8F$b|>h)e7o4GodP(GVqvHfIP)SdH}55Y^D!5Y-q##)yWPYyuh@!mIen z2r1}-K9h2vv2mf)y$!mnE4W;6R9BFzE2tk(R96VIb4hV^=Mr~y#XOA-bx*f*G*mZ* zqq^-5YfjzqNSKWDRNXzGxw^ejRVqhyPcQ)u)%7ZV4MJu}p9_*Iem+!JRZxwfsHz}W zRnQ8csH%|pjOU`NcMx|~#k`3PRY%z9vZ1Oe998{;oJ}uSw;-Vu>8Yxn4v(r zfubRV(5;c;KEIN<8$!&F*f7NLc8-RINa1LRFUi@|5Rxz(>8T+)9uW;uiVC zJ4ZuxQ#h*oH94EAn}dXEq^Ig`Fe0kk8daroRCgDU#_D<%?|_g|2+3ZaRPljOT~$Go z1w~Z_xvGL@0!7aXnI9IC;;N1%?y8E}i49fzP{SHupHn!h`WiW#s=5UdRv|rA^=D|_ znlq>=b)%{sMmALyh4irOSDrj(wnU-35?y=3bzKFO3W~Z4a$N=W0*bl{nIA@w;<^qd z?r)F9oJcylZo^2ePFH`8B6ynMsOv0pHq|xD)1z6Ul_al^mqT-1^$KN-jG3&OkvXy% zU3s7PObgzm zsX6b%u;M-vZp+hpq&e5DCc!3t+@4JQn0($m`7dW?Ab zsjaU_YK-{4W_R+hq7d0T^4c@%@iF5;XyASloY@LE`bm)cNl*z;^pg;pA1UsqGl_eh z6mu^&{PYgxbU%si?`u*x`e_-E`{^%2@pYFZ^h0{;r~IR%pB8??7Y=OEPg{d{^Xo&X z{$u--5Hdpg%*b1pk&ml81(K^Pc%tB_t{_)e&ctuCGP5qc`6&~E-;g- zx2aP%g`>LNj%iNa2}oFh^i8QxmR&Il-C!zG{>Wsze{=K4LH$@6JXNvX6x1zo& z-X))#qTr-xisLAGrdypUdVsho1`~2qjD>TyG#vPel|iPs#CVNN@hPP5L|lt0BJQS` zjtKjk7v@qS*IN-XZP>EU=Jhg5EGF?$aePFw6<7%+&Cbc&#>PDwk!*Z&>>~tM2#$S( zAnzjt^#h81gb*%Wq<9~3JaO+MObBfHh%c=S4f}``j(x-eayIP}E08b&>1iLa_2}3~ zJWT(fej@e}H-a?o5|@UlWZr?WYo2Vh#T$DrdDwNyGoZIBNKR5%Su8C!7aWi3h&! z<4tON@3E5AsJ8zJNdt?u)%J)toR;Lh-@hsCC>dg2GBIlyXK*73`qYhZwAn~T5bQ=s z;pU9+Ir%2mH^KxfxO%@^2)Pk{fHbY15oQ}lMtF~q8zHRZr@i;#J$OHf(ZZf89^1CVtcmieRS`wBJ4XMU zQ0X{{)J(`oj58sfqnVK6$a)_$pKvmw$|+NJe%^UU>71Ggc{Bu{2`Ts%wvuIw?PQwM zC=|yi_o)Oh`c!*_a7A#7d%>kaK{2CS-)u znUI2Xwbx9@%gEOYEz+5gO99<}UmDHy)phoFlo>94m*h=mNa#b3?CG)53I2> zgc_Y-Z*(c#T%!vgb320QwCCwUKEKZPBjk;4JxG&9N_w7SjiW|4nUFWSP2hB9D;&75 z6;apOM~v5~=c%F5y~eh-Mi+5!bT1>q{=DmXmovk;$;8=8D%C6E;a zyA@KnIV*fbzS;Gy@VAv*UC-v@qZPh_R9nvqyMy>>V#2po)Jy4EhR4(DX9>JBCHE#dnNeJx&M01Nb3yx1pxN?I zY3|kB>C6ebeap|e_3xa_9exLQI++*QbWm|?WzQ~Io;&Q!w^xy;n>g`w0VrO=Wdi0Z zN!>j6AB=tGgw07zmbY3QKKhq4T32w{>X!ejo%dT36UHK28$mLv#P~jEj;-rtXvG~1 zY#BCn(puH&3Rojtj<4!8$5wSp&ov*h;>-|d%NECQn})Q;=MrPN82Wrgi!fOJUg^1f z<%9cRweDeZD$uIw$_FC!6QTK)4<-T)Th!E4dB$e-k z>#uyEsHNP4*W~5pSM<2F&!dd_J##+jFI*n(Uc`{7P2wB^{SY zNyqiDadahHO30h6I6JWw4&2c0In`uy&yy@Q*=~dorkm&PU*Qgf#U^`!k#zI?7@_%L z1eiD1-;}A|pMP54@pEpq;IQ(+kK8IY{j^?$84w!#WFcw({k9mZ#b~hdL7h*k!AmNe z^NEmNLXz*dTb-|FsL_UyQ6TB}+lK=A_uGP|0^yrJb`PyCRj_}*EqJEj=KOOAV2$T> z|NN7D?w?-?xqnW=q^m_r{L_7+IP%W{gxo*kjAttx_=J@~{uyh$M*gX!BW%6h+Wk`w z=Ki^a?DhWKJttA%UQk&1;5zP4o4QAYF%TNNX9j8R9x-agSc`k6foHaF&OJiPg(U8| zg%Y}Zgj9p1?pX!o?h!Nr2={z^vJ5Bp2zK`fo+`LG_uLIQ)APD}cAFI4b1@-z&oY|D za*-1EJZ&7g=Y2x%9&uJ!^BH1y^>WXj#%tuB{qf-%gsrXlwB8}Qr}%;f?(vlmhJAsB zpftPkfxzK_ja@UDG3WZJ|zB3L#sTdxJd|(9PX? z7irxG-P{ST0xnthi9I>dZJ|)cgSss&0^W&@p^@Jfb_eqhDwvyQ#*_9 zsxLLR?y8?B=}SaPYX1$!QSE<7e$1VZ5~V`$O?tApJwc&`hb*qz8JE%XIr-JM8`$2*ZR zE%dp6_L`QB$a48}ww*y1aY8JEkedQJKSA^&rQA3@Ftsg$2BwflW3{0$`6Snx!_>+rp(G#2D4 z3z`8GpYRIdtuQIB^Tt!6&SE~!hR*MsQT2ou)49$m8XxeEC!;^$t*`Ji2v~ve^o7qO z(EO$FUT7+fqqd)!fQH(>8@~C59tYO$sF|!Euuk^WF>15DDEJy=CvSsWXZ29wccgf$ zEzYXdwz?vHdeAoJOV$tA)CdD0xKTIcRHeJ1W9zIQ2h>z45k$eJ((Ah$xQ9E4OoKZVKs}-$;$5L8_VmvfA zs!Y|IEgJPT6VTA8etq8_A*&FQT|YbDwAJ;nC%GE)9>~1oq)kgwx@Xpg270M7|2NNQXzC0eTY*S0_!-uf#8) zOh4(nIVD!lzA?Bz8Wi*r8$J8F^kzO97wkQI3df#ZQ0&A+ ztGk_2P8KP-63;M>diECxdCxu*&Og}-2cBzXP|yCO@zk>yPUVz79{C88`sQYP_6Roa z*)s)Y@9G1@C)B^sSWWh!Ke3K4Qs3ijuVS=@-8+-|DDNA-j>k+jUo8vpg)a;6fZFL< zrHSV83auHKV3(8gf&?=#^Cllm7nV{i7u_qJ4N1vp4PxdTvpUWoZG}7tGez)T3@=$WU z&hgRdUV>SIV^=l{$gdB}3B?QIMMzmFTI|Y7Z;D;n7z{j-Ep}!7K)fj)M#%qOv&X>q zAmll=>?2p3wvS?{)2E586#=d!=sHkmJg+L>A!LH|`TRtl<@iN!-CLrzLZ=ChRYj0%D`+-Q z)K&=d(@Ak{`w(|+#r%m4ZM)bx8fu%uQQH~hY+6;;AYl#CQ*Bp4b8T0k>FRpgR!o;Tf(?MpEp|J+7@snq~p z@H>gx^V|wu{!5Dm&%QW{$30&8_d|+XL1>lGXazxT1wqw7(F#KNT7eX|!UW=O1u?s^ zVTCd~M?)*5aJ0hPjjiC?_C?4v=`(*APgh*q zgJHY2LT3w&+6r=Q1uX}P+6rOpO^R!K7ID{B%mHj@yS|;Hp|&X;wS9-2O|`8?LdhQW zwEY{JH}w%{DvhJITinr9+a-1lJP{!k2+6+Wn(hMAH5F1VBx)+iH5D`lC~7KXewa#% zYkDYg*Hp~0Y-sv>Gn%Gw)bwd`Hq~?-5@sPi_3KJ#u4y$|O53Pu;f$u5W|oG917h3^LJRuTGlL*EgP>BNXa*sCghh&*p+9jq zgP4D_VTP=oqoKo7IGW);ayB)CBvd0kHN!{H+zdBk0(G0w3~ldhY6jP~9bLgF>9cY> zo|U-MyTNvCg-#Y4oi50=6*LnlYAb{;jTF~*KjN;fn5ArJySf=|Q#fjSKRKIf+XV@$ zke+J$IyBdI3YtpesO_&Npy8Fwt9NgNWcEa#k6qJNcSTKwlnRNO3UW;a^#Y2T3gJ~E zDX!_(#9dP{`?8_wduGjseof)1=@fD{)wDknCL%r6^k2|iQ*~L=Hfs95323M()q5Jb z|K=HmRqt25dap`)@7HKNv%#~Ay6}v}&9E9V?r@>CLZcZ3xfukl0*Yo3GM_7bG(-El zqZ!0}iw!fZwC7?C&5**;3}=$FsTm}p1nH?69)sp)=!FT?(xVx^FaZtC;MMy(gj66T zyLbca;oANM+qD&1Ei`H?$h8$T1}JJPgg%WFcY23=qPAlG#D=y@&7uvpP2s5R+2m}h z?HVM^LVBw0-Oyay3N)3*QQJi(prN*2z1z?uER;S=T+OC>(y$2(GB6#-AJf0u98D2n)n?dL_q0tP2+zf(d0Y!%kp+6(V z&G0R8Z{=bh#D*Da?D1PeGo)}d!@l=6X9h`Ff%Mc27eaG0w8jK7MKr^+CZM4iyn2sA z$QtSM)(@$+wXj`Vp(TCmX)DOJ6;uTjwH3nCds1B6)x=#}G0$Q{+ehpi4Yf_-sO^CJ zn$z}NBuqehs_p5}T-ywqO5>>QZ6=_hwqCubA!MrbdE5Q^PnfQ$kXb^aUj@0Qf@*=H zrb76UHBwyDH;B8YV&2Y%rqifh{sEJ2&i(!}g`=k1%xq56JCV@3Up-9^gyx#+ZcExm zP0u$04K=0IdKU2t1Nd^JWWRA$uZQZY3h5^#sw&7;6*LMcsw#xJVWhaKj}!Oj5Ms_G z9aS&1hjr1Z{v1MZjo_&2`u8`d>Ko9Oi&m06Qr!`ntEy)Zx}A=yjx+&{RL#5@mg!m8 zqA-HTJzxILGg)Y#Q=s3u^KSSsEcvKzQ4nPBI#zS$AM+vF|ijES(PY;mdj{1za*GVz&V#870>>P5G=w2sNI6A7&1JO}u z6N(RvBw-ZNQ%ALVFgmK+Z~USlTXfXEAbuk>f{_2Yx(g68QTo(|5j-Dsb*Djcbp_85 z9Mu)%>I$j>is}ks86{F&-4BSnx?(P7L)}g691Yb?;i&G84>hOm8%W6Xucz)c(7aws z)xP!A{lWyOUe>A0DoSMjlILZ~M|E!mJ#768>WBVO-DgRCTOB{D`zq))%C-;3*C^ju zj)BCJkLtcpa!fow`Kaz!W1IrRKdRgIXC_p!W#0{(*+Wr1kGlZapU189NPHd_iRtq= zC+T^dNcyO*n&O|xGsonkx_>8ie_`@bT@9z1042LJ9Brr4o7fA;>u+K|lN5hm{|3yd z&h)1~T^?0=yN}_qG|<~@Jh^$+gy^Y{V1Me9!ttrkaG>}|c{%xJAvS&Lv;8cc{E#<9KDr;jwf+nZ}IjwL~*O}o9@ zpm{$qJVFopQvN@gfQJ2me<*V*%t>t7uftPT6ut6m{kYDjSAGW(@(*PqF~0J1j$ZkR z6JPmVhNxcnGW%_~??wsHjHufn_$xob)7eUv{bVQ8D?gza_+x_q{gvlp)MGB0o^z$0 zUUR7;)bN#GOif?;DTBZA6ZAJ5ul&xnlIWG+Pr&}lFT&|7KS652`cS5TG7LwH^p#)1 z6VgTYDctuQuw~!DcX}<=`bnv&rK%&8zLpZipPO(reZ*{;kk$Kn8IttG zFx-TK$9ng(m%-K(o9y+Fox;tTa2)xT*EivC@_F}jDIqsu8+wa1^-MU+I5OcIgxrLi z!|AGCW#Cg*2AMGLDamSNLUlbF>8;I#5pVeN)GtSGQQFq~nIYT=?Kp!QLC`yHg#Px{ zMn(|q^(cj#Gs1i1D@SZvj|N%6RgcCIawB{Osh3DeJ-XI7GQ#78+z3Cy`HQV^;2bN1 zjPQl=8W~|E1{nW87$M?bkHYMv90BT9hb3otwBQ5(u4F>;S;<%aS;?6i>x@Mtw}a@Lyl$SN)H_H`UPoWyvq|<` zY3~xt{-7nwF&C|*9L;=DvXGqqMTw|0WXEQ|C=pL@6bCF}5pMPbNzXA}&8p$|$%lVGSmC^?FVIW{RQtOzF9LrRQ24b|K59uvWO7bJ2=| zkhmZWW4|bT|A-Sx_D769DB0M+mbMS<8QKB;gO?qzgmU7m%&b$%R*T%pVD>@D(M;Tgr*Z(5)Mg7vmj{-_SwW2gj3k_`jNCHVQaz?lR3brVDC@7ChWofSCg<_f|mtA+4ENiFduHZ4K&CXgDQs{cKSQfH7#gZqKkSM|Rq5j0y+Y^Xz@ zRgLi9iC6|$>-l`%>A7=aZ#AEgH`Gag(_4v@G}JZ5QA2GvH#Ssprmz(bJjP!f(NGTn z_1@|XLI~5iaVX8Jq`I!R`j?S3ZhV^%>!5&nBVGTww2@L?b=`7H_D^os;qX04AKpUnRVWON6u@D3{cjOFC0TcZ-lJknoiE zqo;xRqZGZ6MCb*fv3JIh=H3xwh8Sz{&IIsU;Z3|FWQ~x-JC9LR z_l}U#!FAsG8^paMq#p?0sjycx_5@wMDJWp$Qw@~wwozZ z;++?bqsH?eLVlGKr;XY8t{IXbJGXdVq14XacqT(yh_HC6Z|uSqVD7^9WUu$P$lA`< zYRFLRYm&z8Mqv36PTZ&~8%~;gMvTc~ti>}Uz-J3@;u#^!g(RM-pmgpTA!|U=b_3#` z5mGYLJoDOmJ-oC`4<%0Av$#*0O^1qdK z^P>~4hLF8<1utX#{-*~V|CU5(!7$x9ZDXkJoP^Rd=+5ao;C6qJdAw&F2;_4mBhv83 zDW;}3PRignPJ(`6Aku7`G@g`08 zAM4ML_a6~W?>_|T8mOlqt*M?9RFIqfVzDEb54wf4VWT^mXHr$^1^b{og`2DN86aNt-O(CC-W@#wXC7POz#fc$y*t|KC56)J>(7AB zqB~NT)O>feFhty2$L@$o{@xEeYrK8rEHZDL&1MDzUBS5y5jmd99@Yms((MM;p$0+^?@s(l510nM? zr(Po;994qoIpG=7H~}MV0ya>szJuy~!h-<;+01ur*`w!#Gl?gtyCi}+pYyAL?eSL3 z%h?Jh9Ix4_w@cUKOVRT)w$~}b1WwtKR|gGs{U)4t{AifVc<@=L>+ubBJwDa7_Wseb-K2*+ux`936>yz!jkQ_s1BAHqt&PsQ(4{NVQ#e3an#VI(;pWW_mx9}s+P zAm{%fj1)OPlbOihgdf9bqOJDLWd8p9@AJP8{~W~(<_j~KEuRqbHrz5GUxvgJ|;NwKuJCCr|=z-6gB+luM!Z&i|-liOmysZewCjvqZPlULCG zsA(H!GADxMU)V8|X@9gVk}b=$IQ5v5GwqM@ST3C(toFz50Z5(`JCjZYO!AzhV4CM- zkL7Zzyh8+Zf!uyH+Gg@vw?AY1$(amxOtMZ;FwJ_V#|knz1$n~+>;Sp_S&tFS$+j4< zKR!@_3UmKrUyy^MIU)bfp*j>y(;>G-Uz8*97R9o89ZyHdsps;GI9n=XPC<)3z_Vuz zAf?JqHvCY6S6Y#;yNuvfRY+YYw=h@Ivu6#;WIDW9qTr;f3C`b4!Ep%e@R9^(pWlh# z0!dm|8E#{1X=cu>mv<*+|15hyNrkzOvTvmvFA^w9cOb8j&^r6}eVNQ=J>Dj~{_6y< zFI_*}NXsZL*)%6pS{&?LWtrjwdQmsphC|@-Nony%oQfZo^k_lx$ZDb+C()M0Tb@s} zT@r0wJQ?SeZjwYdC~iY-FKwShONuY4BD!f3ZC~6QTbFi7qNT;#ZAY{;iFPWU(u3&c zNwmCp0oA9pV-oFF+?6(1+9|xhs|s0B{M8JiUBXI>Ru)eYTApZBRs5wi>Xt-zDeiO} z(XB%tQ?OU@(u;|18@|SH*|I&0Uo0ouGnhZh_AY*HFwx5Jxk>I@Jm4Y57FFRFi}owt zaS*2K9ria-`xQ^2t(Nu=2U&DT@wJNXn?#2f->m3Yg+2QVM>~PN`cDT3J4)=d=hle)aLirxq*$%UY+u@(5+u>g~+2Qej z+2M($c6jnDJ3Q5b%F(uLc9|WX{@o7Gw83X>%bu;Y!{1m#??O!iVhe%4>Fbb+sK96?av>#g%qgGQbY69czcBm)N29 zK0CbrvK`)7#i68Zop9gQI<6ZQ*|BB##*XcR%2QIdX^?SB%1VRGQc_kHWRQ}wEs}iY zNxm&D-^Rn~*g92~i@j zvd2kw=yQf0_PoFjd!I({(Y8z9^X$;?GCS;Zy&d-5#18v)vBQ8KcG!OxJ5;Z4 zsAW2Au|wYWI#eA=&)9a09na&?ZZj^NA$!hDtaq!LUb_)D$x4?W#lCI%u_sFT^5gEc z!-=D~7_==v=~6qKe1{!IKV^qgmfB(L?{*khf~>aX<16fN<^VgKb%GtvzQPXYK4ORS zUbn-uh!zHKK;nHjD@Y+f%((7k;6Z5Sb?eO*^hP|`M z4$C{!VYMxP_Y;e~mus>2d)wht&%VkteB~LwcIG$E{LZtl_6$GxiGH#ZZF%^sa{QJ@ ztVhLayXD9dI~=*K9gf<^4o8o)!!c*t;n=BmIBupLMlG_#@!#0tgf6oqQd~b)d@_Q-!Ih)$y+)6u~S8a!hN84f2xpuhd9y?t8 zm>n)zXot!F;n04Ap7{H_LdFL#w`1^>T{q-(7_p=J-b^UIstbYE$>lGzSr8?=UI_QW zpUqYpdXu|ISLvb_1T&k51yDj*2>5nND8;w5*p8Mzgq0~!bmh8a&1A}cISE49FDGb! zFLf?t1Ej5b7bCROoq5?zZr9`YT8FB7*c@tY=SyDTrl9ji{M>wQ=TQe{GX2~-V7CY`+JDjl22vJVloJ0E?mmsTXT}Hj(X@1VP?P1|=P842b zw~Vdymvz8h_0m5T&TJ8$5%EN{`vS%v&9lmXY2}yG^0O|>WWM2=muX*%df`3JwPkp8 zTOM5V6EQnvGe7@@J3=MNJF}JkK@_|6WV};yp03ARhC4Tc{8kvx&AyXILL5~`-ZHHC zod*nmh9k?OxC=oquVZWxECo=BBRQ0PM0zNjda(8je%(O+TTwb4eidog?+a- zgwCMmZhG<|)W3C}2-yxt-R{~Izc`42;8S4+dFfY*x4MVu>@aksqPgqMsAcKu!^3&` z+!b7LD$vv6Yf6_b+hDWs?ozO4L)aL}rP{tjCcpCSKurkSl31MrMLz)-{m!oYf4K6k zb3o|CIdd{whcDo)^K$t4E~4Q$BBRqx^jga~O$g_aG$l=rb$I5nnT$%l&3~pbR^|SH zmeo!*A+&psJEu@~CS$9QN0S#_c=33 zNUHCl9!)BM$6^KWSX~9^hMb;kr5nyeYF+i+le9z9^rB5blM3(w($flXTuP~{00&>B zvc9F^QdyTf*thLIVCzM6dEJK$w!?v^*x|5C?Qr-#b~xfCJB;|r4kI^OtPDqPufx{& z9%zRJr`X}MDR%hzZVn||mxgEUcqLCo6`vb^wBw68Wk@R7dVWrc9be9AxkT}WIpubI zC1+1NF3K5U$Hh4l?6@RnsvVc+%(P=|&U`z*p0mP^pXdBx$5lBSye4^HT$g z@sFHi?D%KSC3eioz0Z!hxzE`#FZXRbw#fb3js>~7OC_f;x4j)V$*r_w``rEPxM}Xu zcHBAl96Rokd%YcZ&3(v@`{vHK<9@jx*l|Gaj~q9-btm2^?9pye1y!uQ+o+P$yzSwARznWg{ojl#PZ;IDRXKBVy3E3|*_DeZUUd3z}PeXw#(+D7}YmMZ=7 z%e8;|OYLv^L;Dxr)4qGPI30OS9@>poFWs*4R_#xINqbee(C*?A?Kk;eDLYyTuU1D< zHslti40%XsyQ>r)YGs&uuEO{Kto>d`NdC!3X}`C1j^|l<-dra1&PTQH|BUu8OxOOY zx!TWO!oJ)2(s#RJ9v=k-d-Mw3iIn~s5XM!q@*?1;N$C;p<0`q)qz$>aA3;0}XQx2v zqQ8h`);r~hY^LjeK|_iy!dWk}(CBI+Z{1vOhy;SA|=@l(s&Hgvg;Y@dwWGvcj1#s0>7O~(Q?q5JQNub@xO=_X$Ss1 zBcYaqw#o;e81c5suN}+eo$@jH&kA=&Ol7mYE@1ocM4=I0hy*KPorIoY`c#!*hZdaS z<4D?-Sdn&|;gA2CfSe5y6-OPz8R`fL?e}j8cS0!td}bz- za~OnYzc2$Y`UeKw?b`Jz-SbgEac}TxByobH7wZJu7lW^i_|se?igqCh{Kad9|5JG2 z`f6UDKLLEU<6GP>{6F7t{>>vk{&Dc{Hz5D^Vg2{BnY^>Z9$@9)GhqLhWT!g_*Z&CN z#xS-%!Omi(NSQ@f=%G{3@Zp8jx;L!W-5AeTDW})3bpy9!)YVmH2v0_mDZQC4E!&4r zPvgnYVd0GinCM_PP69hS`~YSJHe;qc2>-nt!i}NhM)e3*U^_#~EIOo}75L;WXrkxa z1-UO-jHywt-HG_^NM*R@-E5{+QJ5w(j*?)xvEWTu+TrI(bYiW#=9rjUMY!rS?kB*? zuS){PtlN>N)#K#(-t*M{Kjyjp(`;s);hv`*gVXX#?yc@+m|Olqq}jB`M(oW0ge7Md=Pg%bToL_pMJb4eSglv*@%g z=u#OD;EF^uK0(TiQXcu=Shsv)g}stn$)2wcQ2m%JytaZ@kRU~)e=vM!y7S_LhYSCw z@cvsRxRGo(Xj^0MD&|;Yz9Z(RJsLA9&+n>_Q`~v2H-`1URkv7A+bt(!k6f##`}|)r zc72_Scch>3I%WL-UGbivzuovkm-JSBN&l}Euadz=(Na?(OQk1Uk4y#imB6+c>wK?L zW!H{s^b61HS`ON*JJqbCv&UrA%@kQ*QyI=&YObA#4?-UZ=3494rhjb$*119T^xUlx za8wkaDp+Lou#(vln6xNts=9Ge6p+>+oVDG95UR3D3NJv|=0Br&uc|wM@_*mW+$_?| zKS=_0mDEDy{(vD`t9CB_ljg*)$JnS`CjU3_J;MzWOfLrjXO27?kk~U z(`@Eh=;3j83Y0D(A7iT{`E+>Q3xhiCs<8Pc+042(hY;R_@x53bG`8|v4u34-SLCK+ zDeL|8C@PcP0x6X@s&JKI<32p&xV6ySFpvWM4;hO(tGcL-Qk`~YJlb+M)vYj=Y*uHj zy0zWjdc97JIa}^l`8N195m&6}Q=S!*e=;3U%iT1(3Xerxv7**`uT~kV2Xg%^3h(^_ z;SH559WdDSuQKc~1wvI;vCw+cChk_c)uy@&T^d6CR=kX+HktSykmT3b+3c&({;rCaIKJoUyRmEpOstSy-M@0t_;3D+D- zZ{oXmXkwiIMf`CWGgxcko#S9~*BR&WUAgXQ$ED-2{g{HZZ@3VGbv>$~JNCzI6G+)f zu}qPfT!T7P-f<#Q+ql&G*CLg1)3q#Pce0uN1Ci8vG-|9H<0w{SJFyV_^zmc~!SZz2 zthqc^J5?gjmuB{{Ph}Wz0}={c!iXqA^3t=G-$v>6biq{;<{=wBRfZD=P+czb>Te1@xX^18;{0cRJPJ7URA18|yQvG+)RwRLcWJB5yKctGh6>+;K8790k^thTH zJ8{!*I%j$@-ig%*inPN`Lv@AUH*8g!xJegwbJJ#|?4(#SBGA|wsYk3tYT~A9D9uUj z8Sc4^>GUUCSAL;La+5{{b)yW$ifktqf)DwfEFoB)mzvFE7Ep;iUz$0NKGx^n6*rlL z7Mmw$RV+QLxk*m}8(lwKLeFsOLYe$f2w@8Z*a;OY8n?G8-}^?|&FR6~%`p(_E>YVZ zvClqsQ?T6;2Y8^aMOp|AhjEKQr}En?7ATCKeOPET&{Dn(q{)kP{b~pDfSG&E_$)*=dRFt3o;5czV!V4goW~I@2i5FL(^!fCJK<8%wWEyBax+YG zvoqxIG}@Y*ok7h_fkuL9PJJ0G7QJE@x*lXf=Guo#?f=+`hZHYB+c~^`64%_rLl{8p zAhy!CbjkJ0>@J}eG)P_uquHOG5|YP&yZQzGtY^54PZ#Zab_$fdMp4NkK1mf@TL4?Tl+k zKY`oxj-O>M{X(T{$NUw&ou~{~3C+oQkhGv(k?oW<@*X3V89~#zS*r|}T@C$57pB<; zMM9lPx6N%_$8~a)Ief2l+a;%4LqdVrmEpLJ;q|jseS;<`SpHbtZ65?Yz(Gx2a8Q!^ zkaY#6=s3Yq&1h(do+xEL_tI&igBNViP>8A>zwvaYo$N&H3Y!!XZWl|PLD81lDT-+{ zG`pinA-5k_Hu+?vXVtWZI;$5kXIzE;NPc<58JZ5#l<}=fINBMS649uH zQP2S@}%M#eF_z&PF+np5G7q#T>v3izahntIXzd~pZBQ``-jkm7H4tp=Op zc{aH_jA_;wG*!jRC==0NU4H=B46EFlzfxB)u!`LvK=Pf{UER*IR^GmGo~&rQX18)nnS@*c6*IGIn!ZHxU*@rb{NqLuyWC?f^S>@5HpOGD^VeKTOtTvFvMPV!WyG%Z zSV{g--H2V~vG)0!oJQtU;BxpWRov|We%5e~`GYOh0)K~)d)N5*nOad zh^5V6Ug#MvsDS*Z(t~Ci)twFz$%W!PsNoVM2e2F+ipS8x+q8EPfv^&pc5O>L@^61&Z34uP>OXlNf!YlhJ? zj2Zyrc@;5eK2*JvD2-wa83N%_@5nS&%DMp3yI)EA9-gkbQ+1Yb!&io?Yhdi{3TRqY zQ`zU73u9krXvS4j#+It?2RK8Mv7BLzGbvwB^+LnEZEK#El|vVWmFj%XcR(|@5@7GJ z***XtYA=@tP3Q8$OKhfZxN{hIjvb7kiC%TuW%dr0dqenKd&4yYtbqVcX6o1~=wJlR z4XY=hZx~Gz>bRpFjL?c^QzyagxAB`8r|d_)Rc%}Ln@=mtNv4P8+Vrrt1zYL$aod8f zqgp^c^d^*P_cDfND%0I7QKfD9laJ6Xwk?0&XZ*b2Gk#w589y)ijGqOX@zXDiJo26v`h}*4kMI3#`Dxrwsea2pW7?=?cZ1U-r3q;wT_qt^cbP+jvKTu z|A+RMsQ~SceG<+-WhkAq%{7v_4;^jM-G8%FKakny=KFzq8FaLuH|wAeFn!JdgU)XV z^$b&%v!3})Huk&&to(s;K7dAEe44Ts_XY_*FXA~gE$c9-al?51)Vha1EBsaj-C1Y^ zUfzbY?sp~3YG&fu4*CmBt80B$&c&aj!KS#`=yo?M`i9R#Z_^vPcF;HHaRT(CaYEQH z((S$~mHs~WM@8B}U+^0A&R&?aBYl1>%uDAXeYd{QwPSUeA6J|7W4=VX6~xBrl5Er` zd5ln`okZWTKh<|(n2%K3dDZoPu4QhO^|)_hBm)Efk57*+1m&3w*%uSK#Y# z1n99T126~IbgDk{a)IXnTv!Jl5T52b)M-%PBJLs(l@o3QyhntOB%cWfcIM&X3DV{$ z-Od}+4-QL6dpAul`jT7`JS=<(@N*rw6$(ahWM~1k4O^ngZ_3#tynQ|8Iq9}N6rlj! zNUf?PnfQb>=B{xGX&{8d>PRN3YdH2EB%KjP1Du_L$^Fl^;gREVGM&!4@Mz9474+7W zQKa)ykZ0PH{h}eI$#jq>Aj}cT?NS}8C}O88Z{uRLo(lSU9mZ8p{w>V?4`~Go4$NI0 zgM&KKjSe(|?{h--MNUNsg2q!B%;Lx}EbW7l2?2cwDovN7Mql!4}h$F_^W9{aWG6kY=GsM22l--cNe(HSQ zdaV7_Thdci4OqQjCi6IX!g6*Wv6U)UbEgh=$K0SaeE5~y5_-XOG8R-~`N0Ep>Y{#w z2kY4L;2{Uual|gLI&@&CNsE~wM_B67db-`AOPYF&rH&e5%CnS11gq=qMI#L0R}QrQW|;a^XCjz z&!Hs7zmO87t9%vM%1fh{`+V#}otgR$J80i<*%qW7uc2KL3T!qGun9n#NHge zdZwk%SFJ(}pY;iI;Y_%SRI1w{IFkVR)Lyj3)vEIiLY3SIXI)t-QvPK)>+w@vHK8D! z_4y2{OAX;{#J3w&g4w2G_c3OhiQVzcHW#}WnN1P9bx;GUwHLcfio@Aej6HemLD|rVRIkKutw(iOiTYWMha)^-`w8{1dUbtdMODSExq2Oa6pZ?? z4UUraQMRbc7}`~TLLbFOrLvVq`Y2D-6}IxEKFS+ak*ze=NBN_cBBtt1^ih1&(w;bK zs*j3B&BE=YdNa93i>I=YJA;S5>54NMCpxIl%?=DKf{))uO)O2NQT>Ar=n`!H zh%LT8_m6G=WV!>tC|t1GKlCJ2h^07C6M6_jQAad4>I#%Q?Dqwm-<^QxkDSsPAQ~~% znoWl|UAPGf)bj8!pYI?;-2e=5p_&@H_5k8((+<5Mu{0gPVumD%O)ywF$%?m*SEX6p=oGsDeFy#ktwSk$wg08zv=Xu(F&BCOy;v+Aa87NQH?@tVpU7 z$Ttqu@P)W=DGo%jNJ`(W`FzT~lO1Sk_+MC75k_0DBJQx&0>OgpjJDd_&Xgg14ih@u zg-1cw_--gCF`=`Z#2hG)gfuy|L3VcMB$cM0E5e;l>u|6cTRey7lPLcE>3tj?ar{H7 z8j@6+l2Bv`L+C7oA05%0M0v=|X?7e)CO`BITS0^lva{7QlGx)Z^|`{;tjvp1TCWY_ zXKAY4LIgyuzdK2;n$ze;?Z)Pq(A=(0Bq2 zhj@oHOvArUNz^|M@ zCSEDyE|ioZuHL=Gr?9gOGV|y3r*qzTIgP$DIpIien_e(fS;=L~i)`!&rZk6tZvR>i z)Rg^sDnxb&^yPGj9rV02uf>r-_T0oJoZtMt^fVgJW$Af^+Z?FbRI4|DG zNOYl@H9`EP=yO&%lNobWpBmQ3x2(qK66-?!h9kf@B3|~RFPcR90XLQWYh=nO^f4jP$G2uUWjw(k^8tENAc@}W3bB+P|M9eg zjx&+2y#oK^r#TEyLu5>BBK4dB;48i{5>HTM27cx8*d$YDJayp$D68UZeTxiCJ4R|* zvekNM1`<3C-cfxg;^%wv)m>snV@Rr4dmo@q1El-uI#5W&_ldKpu;emNZBSqk?u0_LM$!fVS5{RSJmf@ zS7zD%#nEOIs;>Qcsh0Lnr1;kG=W2=3pW~fG@1s>I6sIc=ujR7M-0KSehqajxZT}Fv zkTA|f5*6qUWT?Jme_=%0c#gp~at#ezp`4N@;x%FVL~{K{@E9}~h4w4H7KvAiWxT$m z5RzyLV-IN?ypqhdVaF1R1@V*4!Z0SJ3|DYEI5CJSFIw9|@j5dL9D-eZ+VC%^bM)gv zaK9=JO51D>;rDVO<-wy`D&MyGEJg_TpVL`aqvPmJ!RB|&dr2>W2|tm z4L`{{9)F{msNF&W7GQ5lXCmF|0CcOi=b`uTsoo~uEo^UXsSA~^1MN3O-C2+#>q2#L zNf&BLG}iXBXRmgn87&mnZPlw0qHc?&UF=BD`GFl^V}$pM=HcMDw96lJ5O$$RrbNSg zmoAda?9a*52}q=AG00vqNiZRO`jp9onrLeX0*0;Z@RplkN*^3sDxI?~H)=I>7|vF= zdblI2yiy`WY4Lq=l%F^(u1UWdhDxD^$a+4$qpRT)5JvGGU5%K<&iUx_s8KwRsiy41 zi&bOZV`mDoq{i~9K-G?&<9>&;`<$-0B-LF1CrDG&yWDA*Ul2~d_}k^g{{{NUiaPNq zj-Ka#%jhhzE=CX7;v2DyzSqIA(D%%kYV=mn+PQiHjY6GL z`%ldVJrMrGS&Qz-VH0RlBD90e+v8{!{1DZ zwcrx~UpNpFHftL6bI)ft`c-K69NqKQax#@bN#!h}E~83G%8KAv_d=yB8bBE$v1j?@ z{;&>K@l!PT$_6%_5&iOWPr8Sa$hn91j0DjRYR?Qr1^TBgOx!zwD^HR<9>6pQ^7W#k zLttUBdJq2uSnh~Ay__6gXZUGT*eOJt5EFBLIt1_-!?*ba+e8ui;{}`e8S0-*@HDSp zLkg@&Ef{)~4o=rO_fxL=K3^O*$IwhZ4P~i1in%w+!B0t0t9yz4ML<*_g$kyLr=WIp ziE@;KYkftkvz)^Zg)*8|NeI&L9LA&SaeAr|s;k7X2`l+~2GWztq0RPF|NA00<^UN;71J1*=OB`H?wtF2Q#|U3 znnX!+8QJO}@&tr;HZqO+u4Lp(2jLba#5)_ANe|;1@Y7!o!gWSBm?om<=v#RCDSyL= z97(48(B8aA%L3|wc7oeZKhmWG&;QY&Z$8ah99e1foDq^;04GJBR>Vh&F@U=CW0^fYpllaS_x6N72`#3Adl< z3Y43!`T)#gMWa|fL}VpneIYiJTvk1KGu&~aGGLPb7Z(xbH$-g#4s>CsenfDWi6(+s zkb#rt#>9J-=vBx&T||nLD@lZ@KZrg7bIRr7J-N)H=qD(DyXxP#!Po}waPdB%C_9Qg zA2wYOX26&(j{#Hx)c_-^;;>0cKx#W!NJ`UC#Z-L|LbU_Y)1{;)8LGTW-)N`_AZELi z)O|zMQVO+JY^??HmP<*_4AofGLzNWj6A-6digV~o*WUz7RablJ#))o%_{*VeAWdEA z>hle$gY4x-Gn5aTX#gwhuZX3qYiRwsd7~tV)fv$3mjQ;W97wKMXbrK0YayKiQ7GW? zYC=4!I$IbHaja{>0MDw@0LC%!BE*-y7P@YLh572Ag2uu-5Z`A&ry-pLSgLxW%PAJV zhIoMieLqMie&<%LRuh6Ik#``{lOEvF8US8bd2pRbE*^&Xh!=?BT)eGnJ!_(P9AZ5$ z&}9RF-6}5(Ng6sr?Cu2ymqL%{pej{Nx5qRN;#4odv)<|xwdWZFtbn-I3-COT`dr;X zJI*aS?S=S}3-qKrIM3?5>WQS#ISAKS)OS4R!tojGsv1!R7(cL!#pc041T7f4sTN`U zO2wg;bqLg%j@YO{amDnpe6QO%`H zYbDe!|0vWvv6TX%i%Xeys0B`d`q2Lw>b_8;KumKflP;l7_=jyY)JhQBBPq|lDV>Br z=RdT>@W;Sjbb05tgYp;jvVSekpd{dLV1Z^CvnH>&AT#9W)l%Mb|tzI(?AKTpLD~!!k5A2F1XeX-+>aUbvbzsSnC`wtV z0oF3KfkJf!@w7{M%TLg$)(g1|Ivdzx7d7SAtUo@0xyYJ`XlXOl11=$bLDynW6824N zWEkvea6e~YO;r@^fK_;qi8xCOeBcY4r&+M?>VlrO%Gu>v9$4f1pb>>Cfo@obaKn@` z=z##EGX(P1OyT`m7TJ~f1+Z)H!=rcw&6g$X8e@7durD*9ZiyJabe6Aioy)!ZI#@#S zn5;?(nrb+I5UOFlEbDQdN~#|QR>noeD({dAL0e@xj^YGa%yMN)#;s408;VHu(0ej_se5RaajS8cKAvy82LeU*_BRio+&xu-6 zQuBW53wWvS(a5n|WxQU7FWXZc zmk>f5XS;fs(}$Meo~HIky^`0)qFZOi(uv=QP{*U5Mard%Sp-y7Y^FaX=gdhxI&%E> zk~$mJZ4p|Q=HS{ht2H6I?4$^>KsF0JhXc zy$KMsS>VC(27MdYVHb50AZOe*-99ilkKw-q`}=)(8|@c(A2ml39BP9i;7$73QY&q% z&CxciX98Ezmlm`du*NRxO|YQP2I@C7Xb)hcT{KgIg?}NCqpjgz0K4`+JQ6JE`oPh~ z2Hgwna~JiNaL%zv@bWK5V8KG9_5}huC)>gz7=@FE{5g6Ho2%b!Gfw_yO)gBkAR(X(c7qE zZsUSf2p=2lm}vMv!3Gge#thnM;ox8BG)mqc0hZ{Z-UQFXSXz|}4!{jw(5ApTxu`e6 zg4PUHi#6y-V9&W|rUVP$IQS*55;46V?7R2jkzheP1kWrn=oi4gb5U=Cdtiv7(u3ltcgog`0-#@{4YM@3`)okgO!GwknbYYhi*tNKs!BWgWD?@>O6?wUCK?5m;XK3 zt)SsU?eVEFY#9s0Z9skfXkSO=%Q^O?gL=`vpE@Bxi9QJ=jk_k3^(>{13?&Vm|3(Bsz8az}z2~QG zVN35HMl}~PETY~w<}OaKPT3-zaEZ(>>+{t~;>0)USsczPRS-lT1@aqObrSjIo+e-5 zHe07^OHnMpJou|qk;C+-HMpPDdE8GkATGrg&sND(-%4wwHoXq@Er-D4EuKxQQ@oG7vcBbqv1G6=|PlreAKX7f;>~#xy!UIKlBdD)=Bk1gUDCtI7*%b%< z^ntt;#P3o#4qwX0+T`i~ACvq-i_F{Egs~w1_Ci)} zQusOP08?k8t>&z8^$GGBPB|gbSKi3c>vyQw>AXW_4*vTcs+>3v5WFg4t;6Q;xkjfJExL4BlI+BLwl+RQ38v{@5zCySR1N{YKVS#&oeY{vIo| ze^@)i2UM6f&IY{G*xW`APgNZ6l+!wUv*2U0_YY_%d*mbkA%`8P@!5QWVBTjWRRV4 z`|IPkH-}E^jTb~;Y>yB6TFnMSD;BDU2#RGz>Zw=^_Nv$b(Eeik!+49L*i_WQEXB&8 z%0?CY>>12EVx3E22v*xg9GG8I@)djb1rA&tNmRw2gzEPdd2I>2%H+Zbi+HKm)4kA| z2CYy1zrs?{^hRvq=yA62Jo@*(Vmm6ah26O9m9KkX5zF8ERT>^>OUjuM2MJ zhj9!zcmC4E>9bDIQ}F19Ek1i6Bq+q;aaR-ZBn`pQ3|C|;x~H?1Z5!-MS_)*Xi{*wT zTRcTOAbjA81-00dV?RwNAaKHU?B+3^UZ`W8d9x5oj#G69L==kAq>;ajhI_`5g)nh; z7W#$q+@TPF(hQZ7j7TCX(7+jh&VBldf$9TjkqMd{=l5CP)XIl85;0L90D~L|G4Yt! zx-bOijZ1)LK%3{)`B9K{F|{P#>0x~Xv@KqJJ*tLvDH&%)QhEs5F;^ch!*c6#1yFvv z#DYE-oOhpZM1@`mZQd zVH(_T{KMXFvUd|TgWYw;!QE8xEp1fyhv06eINzgMa4|O5Nl$qY?%%UygLjTvaJEp@ zCAU(e>*wQglvwLcxy3Q%#67&;#MA7{k=C0U-4o7O_MKD#SLEnM1BUwQ4a24DQ`gGF zcQ{+fx3N8PmoGQkA1d?iHLQm0gkWQ`<4sV@>Z|<4M*g5sY8UY78Y)%`zBnqftSjgu zBU|x4ODkN>MVdgNA`jskP&D?=3hd|6bFiadN+|Ov?*H@-j>l1PIHOjHNUy;szC%`g zcfu68uTht85w^Befh$leruaC$6?vJ-#pBQG1f z-`@n9fN#Q4so%a(zJW|qlz-?ye&33kpK<-Dk`3l4s6$?_=WEP&1IrqE7m+qeTnqPD zPAoUF)rs!~)^MV&5Z}iZ&y?;d<7EF^80yGBA27|yDQM>zQhfmVTF4xnHL4USX>NXV zHQe3!ZWe6?fd;jcTf?vw#~#}0?xQXK0+V=0TYMjiwhrKGYP=jl@>;KS8;Oq4svr{c z7CX^j`3kpuYwOecpdVlK+eYYv3TS4n9p>OS^mnXx$A}_Vp0yzlDs<~_8^Qm*i8{oh zx;WUQ59FG())!)^Lv8r)ohFc6*Vab9#9Ob$6rgormJS@|7WJS$kjvb9ov--TGjUm3 zAI}pg?L*WME3CL#* z%A>A&-J|9rstTontIDNn(wv*94U{xjy^TcKsmen%49c`fRjw`@DN3{$@~bYg3|Y6; zVno}a>~~eU%uVDaiB3Sd;HrG_+F?r*-GuUwtM>9(E=LsG508VenZjPB)knwTWR)i> z2c^2Bnl@O!h+`#Dwu*Rb4*{q(kgg6Es>3Cx=gF-~bh9>y5l|<)1cw6g&P+s8h2p~? zmOx#Tfk>xhtnap}Q9d*UTo34d5C@s!7a{SpjJp3)gNipY-GU1cuR1_Ta+^;3pG8D9 z>8a6%it3L}05)yLrZ#bMYSHPchAIQ1N+#<3LQu8oseqwcg6Ncqk}gvnYBbqUBSB2b zM5T3wt-915_kFpey$s^DOcYOrS@mcxZW??qp#va}Wug-J0&76y2b&h}ClEIr3PrW^ zc>oQm-5{8V!IpIZ3IUr_mW2ucc#_f(iKM0s#2OADcL9AXNTAC&YbT z;0Cv*ttmMU;{>!`bOz!jFYx>{08i1o6Vd->;4Vb}Ku?C-bMd#K=FcI+r2rIwSkwzN zMTN0a>1kA9zTl}Q#0Fkq_mcqH(kE!;rN}x%?CAx5n+>2n?ZAl;U;@PHULd>@KnJRa zau8q@#Pwca3IM2P1JI2WZjS==f;hkn`1lG;qi?bs z;8}=sy}(Akg?6VT+&09*28dg{K)DyxwBa)PG}Lp{&Zh2whD2^d8(Vm=i|1L;z5*QN*dUR z7#CAHn`#K6rAvve%G9gJP@nY@J+c(jkbK4V12NX6I9+yATX-R&T|vQdrifkywmK3; z;`rSpYc*wm*<^G#h(k>2o`GrHB@64R71}huuh6$3es!tao{YXuQ*fP2Mx%#djE~J^ z)Jtuqzv>!WkAbMpl#Wquyr$6JqHU=3VyiWXuC6UF^*#+k^CRgR4Pv@$OK$O|&<;`3 zGp5j1fq2Wc#p%+8X3$Tm#2ABq0_;)-G!y?h4Y2vUV6&q-m@IQL?eoFUd@++Ss4#wZ zY9z|=QD9YERIKt2C#7j)px@B07Y*7HSQ?|ch`eaqSfE#^)e@87vA||TqA)1bPt>W4 zp;m) zqE2Q)hQF~MIl4zL;C3RHc5|>@TwbcUK^vz4B~={bWX=`UlM^iqTj)l}4JZLMpwC$;E77 ziy74=BF56Gd=jX_DhAD!bW`2}u_qICn(qchR2$sqggOP{yhEWJ_+f}uO!dL=W*V2n zUl4sG?8xwyZT_ujtGKG#-T?U^7Ipz+p@fzig;8Uza;ob95X+#h%Rr>lEu3@fF*T|_RskUgv=79` zOxZo)&eH*uSLI$Yz$J)3x_?{=DeJqIii91{sRU0(A z++JY?DE3uc_BNvTO(M-zQUlOq(Oip2Mh|U#L2equR)6e+d^?ciAotXQ+#3sWzcI*t z!yxzng51Z8wiv|1blGb+@1w1)wv}ixsKLop3HQouRu}nrOj^A+Fe5ckadqI4Y?{pF z4pKa?%agTfpWsWs)?if|VR!^vhaHjc+TMq;#mkpeF?154hoZ9Ztm+6Mwq&b4 z6*Y#^##L`~@tCl^6!n2J%vI$=E-aRbrow-|tMTWC@e^4xw??brzsc3)6U>F_9iA$p z-S9u`Xl6Jzg=E17e{!GbjH8AmBu`eL=o(+)Dj2N9k25lVNkV+}mn8U`UCx&z%8bHe zAZ+nx;OqI4M1A#yn2I8z?NE?Xe^CGJ<&!i64K zzyvZW3v~k>I8+5HgZu_Me|tvx7^FO7as6Y9U(H9ho>mCY3i+oADG6G2);AcP-_8s4 zdJ|vZyUuzFwDzuEnvNBM-k18pZwUKqyT-piO@ZG$$3OHotfI6e&>&g`VUsK3X6T3` zX%B>>kzz#fiF5(#RhM{Q+dj$(nj_0qW8k9`)Y^wZO%>+5RW;OzDyEm z0!C7SB@;2%PxT?Tb^-TddMNNVo5w#6kAIh75C6Du@sG>Usm^j*`E+FV!5QU~8Et)u z;Q0M>*b1^UZ0%$xmw8yU#yjM6zg-7|%YsbsiIxwv1>WZxBNaQamvg1KVh8p=#7N{|RQ(u~j z5BB>4UsGH3;JRRo=fn^`5-$E1iJpe%I7bL2L$=jlh~`0A?yBZ=OW40?6NC>U#ZXIx z*G3BIC>})n59XrFb>t|FS{z>hf%31b_V%brL^&s5)fYCM?$9CR)Ha{z5#+KXQ4-`j z4&qcB{#sz3RgKUP4}eK(2coA#g@$r8da5umjI!ZpMaMHW0mN*VlEfHlCVhzCBNJ*Z zh__sd6NN4*ub&7kr&joYJ$(%IYnR}1lcKS)ef0QxV7~(S+r`9??%4&7Qhh`hg@U06 zCSnp4n>lv|I7M?7;58-&DnYElz*NqI={yE5(oy`VhgfI>v6E{-_YDI-(E8xD*yvoRG&AEg)$_1$c>Ipp-iGiix5# z#GYP&mk0(D)g<&^Bo`APPWJ*l-4dv#CSFqbtubVC6~y&kfbY+NS}Kg6wh&-H#6vEi zCrkoORRI(=ormx`{5Yya1!SZz#KA6*AWH=E)Gdgzq-pS9z?vtSdRif{ zLzVg)_Z2jBv=PKR_ooi3R}s(OOdSXD4O5a3o#k>=7yX04C(4HoiK5>j)09X=R@Vj2 ztEXW{V#^1hI76N^Y3PPJ_mYW>zY@_ngQaxhrGSCE>h4Bkst1UEjwuwL0G7WNN>TzuX`;B zP})C!v+{8-mtv-3B!tbJK)rA+P|aUq6Hd^h5E5C`g~5$3S{7c~7D)Eje*r`zsI6UM zmL^UX0MXXJ{yh-sP@i@PbSro*Q=WcfUN>#VENIIeJ;XO5T@&>xroe3f1wh$0$3tX z1X?Q+M`n0QRG#Ng;P*`gN(Im-5|SLD)Ofu_;BWt3R5Th7gul{ZqUOdPL~0k5TF5$k z76i|(u6GE0Y2fBch~2D>czmwteJIBqRVuqKvvSmEJ-B{WpP!if9?Y#s4j?^Cn1>JNgnhInQW9}uZ2hHUu7Q?u}WozD-Y;F^ncU^N_uhHQ+k0vNj2l^Vq zWo$B%-~%&~&^1;D5#{K2{3uVJN9iTpBNSytY3Ii#A^0F7MDkClf01L4|LUVfTl}r& zu+R;S z^-tQ_L)3#WqLpE&Ie_*qBqMoyi26LYvxKKPhUX~$h z0)%?lq?+)7{z)hgtLGM^@9xy-Pqa!%+UMC>e%wR`lqTU2-jmSG2`Q*h)s2AUmV2^T-bBKYKLGj$!CY z9Ag+-6dhJG3}wO{hH@x-7&;SoO$KQhg1>?-z7!wXdRmSTl#hR7o_1lkpY`%a*Tc|_ zxL=K6{S0=OT-_Ol-h$s9_SbfuVQALb7?oku{-NryiqbN}&=L@mTv1vwBaWm75T1$@ zBZ5z)UQma)L_=-c3`3_tnD20SR3%vdBBGhIkJi}0~F=iObxiZ7hm)WU@p&Qt#hoS$Jfm07dt+H_HVd!WWH^b10 z?94O_<G(h5qB8c0Zea~dzhnehoPgOOmo%Z9u>pT#ZWf5>U8APHg69@cR~KxL7Zx%hoOm> zzbgZibP>ca4i!q^Xq;i_gR7OV22%mdIOWEsizy_DafYG$aibQhEQqQu#fh@Vm&@rv zo>y!RwTnwgFN%xC#`e)O7-Z6LAd_573^~Klf6go49Go3m4q~-KA=Ug0BXEjtf2w?o z8Q2Z+00Z?n5AHCu|5an*8;F-(3(hd~OSBtY)AN#3#HK%rJESyT(E{h<&^k%rNxYZDV0F#F<_T{G}QUL-*iiMoHwW5MTEK zW*B;LjsZS|_=y)V!_a7qFC>vyApYV7%rG?9HUk9kOe6<3QJcLG=hsF5k#%~QwP;<6xbxD+Jfl8lq5uF*%^ioz&%RQ7|73NKjWLO5ww4G)c`Y&dCXcmxF8L%WYojP`V z7}^*GC6Vt0dN2}qhN0W>;q0zHI zlz{q}L%74xacDslHH6Z}QKho$R6E1aJtvqO0A^Gq=L|y^;0jeV59+E&!nS0Fp@%Ry zQ1lL%&sq&3PRCkfHz#2Id>RpVQ9%shoWrgA{4;pxnwg8L(gAib4g%o zGpAcKGg_#8Qih>jAoRl~qXj-NqXo^%L&$Qp>5dFTfBBxxEdaFI4#5Z2WPoCpo1j$2%3_1?g%$lu=zMy=cu!)k`RdiAI!&R^y(`(iOH4b+{KQ)10M@BqJ zKCZd1Fl%i+udW|pZYccb-iHgFgJ+1J$NQ!djYnOxUR2u=(od^1;MKu!C%ic_5SF(A zqOFg>1ht2LRp1nRj1q#Uvm3{hMLvR+Ml3bG=7^t95MMo`FcyF_qfmGW#(LP|7sA&w zqfixo4IKZ_Qm6=IW)z-+kmiU^*Hq6aM1j16q|q1<&oZ@!O^5im&C!DCpHKK63C;qI zR$;fvh4=^50qKX{2f7*%l3@I)(v=5j#Ks^ zqypG<%A6U6Y3rdSz`q`AIxevysj_DjMub46g6JMe=^+*WJhfba?7$hElb!dIfd<(b z7LTxaL|fk?F=1;Zi|oWN7~0Op{8eAf7&KXiF&1k)W8h2(d_b+U4>w_=U`OmYzZK|t*X1G2cY>t^&h_oEL^-QI*=}>hxVP7AA z;<7Hr&_3)wb)h;M($~j~^2X8?0Dm$hiM-GCQT=t8%Jvd!JvKvejw7#+*B^lo%uppz zHJFr?IoHQv+=Zwm{L?a6kyP2&$NB_NBSB1wq)*3L3W14BP<@#mLKI4wpy{s&S2j8~e zgm>PUCbSL}B8}e|i8)4$BCV>dEZS}%F5tL$6Z-I4f8%FZtj#B?EUD6;d!Pt0R#CDM|eXMSSJtF`Rr zkHW_!sEzFAX`q-y^%mUebiN`E(x_@ZycxiC_!zSC6}I?8d}IT?sO4rn_(p7W1LAE4 zjv8P!&O{7WaMVE86#kTJB?f`m3{aBZ#*isy5WU?3@ALpb{|{<)CUhL-DE}G|Luo-# zR$D^p<9}=>ONO{W^=jER zN+JrLk?JKh&XK8e3MJHAp^bwVPTIizpsb=xS4tMU&dK@ks5XD!!^6vbravh^1A#Np{FoCnP?wUk4$B z)~3!npMDwwaSAqF*QAu~tK_*sV9Qv~48%}?mVsI4a&jS+q1_u)4wL)Y9kVm zPG?bwG1F9AjH0>kM0G(lV#;n%d6qV2rW!k0mmj4;?CY3;1p(%(faR(q@*@@wLj2UVpl4}gR;#19L|$eK-$T6SS}?#m)jl^C z7%~t(l~h~*iuZ!7}5p+;vh7M_F{_FCX4_c2@5j*|-*ZF*fu^B6jgoM+dbB*~;P0ne~N_Ak# zktj|szXuWXk2)J`sIDOTyA~ z`WufiF;S;Wo4QvQL^GzO{@c_7GzKvbM*aM-$zX2~Lo-o6w3so~{il%<$>4J!mNKQ! zVNhRjLe=sw!&NJ_{cR9?U0a4K#?4ke|Akt{)@cw|GT9O;*}pH&*z%#8XTxSvZ*1|; zhsKPz-YSlJElwB}2a&*(PM0}7LcMG~QWR%}sU{#&U0a5l-Ve5lMYZT?E`z5*JmXNl zX+(1tp~Eb35XU+$vE3adgUOa*z^UJg&&khtZ~n#A!? zvB`aKNt}c!k%W39L;MrytIFI!K6F9~oI@Nh_tLiw8JlpI|NjccxJ7@CX)6*SpJNI> ziPk%8y@TVh#Y32AD+)gN0zk3AeOn5L}{qP zwE77{Z3D5-r8sKbEqEXoSDHpZ=!JaI88|L6Rg>cf!2OQ6id4Fl&o`2RyAb`G?cCcy zO?nfCCNod~Vo?UP1>Nt6OQu0D8VfZcHgGK%pasn?Y%Fw!*weM3`yFv@>9w+W+{sZ) zfH>W?V1RBkA|2nqU|*sPV?aeu#&>76ced6Pg+e-$MM!Yk{9H$Bm;$ zaf^~{T5n)!H#VoB`1x|&bUHZA0L37d@dEsOIc^^9e#u195Mom=(1jDZgwBmLKre^` zya0EO;$ETLEzDivS%`DJ0C$e!){)g2UsT|7*Z^^h7vRoO+(tTzzOev@A%5-!cpY@y zZmQfJ{Zp<1KSTVJ0l88_&AB@3r@L`S=;L~Z%DDwC6*fb)V@jU4#$BRMOB$#WfVwUu zrZn_3ohyV_AUMAE0D3Vbwa1Q+pZLXPQOD6F9L@o1B8WMzsdSD{|ByjkK6Mk#39W|u zhD(^*E_N!bD<~VO%!fdnb}8u_i80+Ji|e7jDPYjwfcf5ZvdAb3f;(<;ebwzohRO$` zxJ!9DZgJ153P_lgdTkI*T*?%x*jlE3M++y3>j`3nOG)A+THS?>+o={|3Y+EtS>j^c zZkRq>+yV6f#-;QI)a?#|RP$&g?o-u&A%1a)tI08lUol``^!3^RIH~q7KmX)E@(JHj^!(68!NajIBRF zsI3`O&;7Z$2L6}|rq`DrLOlgh&sVP-LYT>nltg^ zVAqu|uC9_4&w{=jTZsT35lg2^N9T5S5a148OSA*L2l!Jvfb>^90U|pfGHc6sL~hiXu=NOPVvuhtVXG`VwXeI6w(7gy4TWpX9@WLE_dVG|YlGPthL*xtl@+tR z=yseBnO$AW->{6T^9b(C=O+QhNUa zMULdq-*b$SWdL4rAX`6H5xN-J1??k8w~g?JhGI_D%xmr|7XVykNOBUYj?}?Y8VWh) z?12FW$^ze<*u0Qb3$9&`1GRxm8{a!057lMVIDQC^`EMYH9Sjp1SMwmE zkJQwWtX_oj1FIjrgE*lM><#sh+TD@Wf1yM{FltF^HXP~^RkMjMEk%W)mSw_I^d;#4 z8~Ie>og^uGMNa@p$$*t3{wWRXs0w%DxY8kyU_?@)PhuhBZ$esME1Cgio}>C^kycJC zqLq$!=n$M-1-IgVkn2j=+QZHXa7J6&<0yM@(>j^>Lvlguf@-%D_cT^f4JkXfC)W3h zUv$XMOP#GB6n{KHSHU0E34||1{C!L7XXO7~w4T`F*#>_CRD`RFs=>3NBZRs@_RS_O z-%x&{_7HoyfFxb_<*i$)EUxu*wm1>Q9G4o*X40j-uzpvEF@55PNb9iM>Qa2gfZ_(j z`df`c9)$W7#Mk$y$p1PhiSZVQI}T+>7UlmKQ~3hqK^h*$X0nVvISSLt>YrB;i|J4} zR1xCi42;2!@T;}lJX+cPJ9D9j$v{h2#A)FI4O>0o7vzupg)L5O*c!ned{UyVN$g~7 zGBFXfa{0@=m+6$n`MJXDQ|y_OgfB!J(Og&s{B#0GXRyVy4f0jdLP4C8 zYw*3}D4_)CcDO=*%C-yRU2HmBs0yn%qhhwGAHmB)tm*>ZGg{nVr6t~r;0RlR=@!-<-xYJmLahMt`u(XS|8Jlq#t%V!;!t*ERsGQ^ z2Dk$87cU@Zw5Gp!1I+GnY63`P4s7u$oCEue*7h%a470lo6m>s<+{+%4NkcWSA#d)n@F^sIh7GD~{Jg*gO zf!}+Mf2aaf1TwGPd4rh#?Tj= zfr@EJzg9p=#!?Lc%@~qI-siP~98oZp24bj7agHNjE6Cjr-F%L84yc7pO3Iwq3aB`= z4e;N|nvP4XNUH4D3igizbri&zND9SsVFpTlF#Qc78!{r3etb|Z7ux3tiwkm+x#P1W zw|-&lpFiLqONh4GA+cerGE4>88Ew_IosEy7Lx*Sl*88}6S>py*dTj|^YvK2n;~$EF3emi`^8tioj%dz$hq+xiA-!)v zFz@Xo!zu6WNRDIzj$Mue`Cue$#ln1$ozd0>WG8GDW{>6}+~K~&F&6UtvKRL~emfwr zfC=uT4y%Tv4jjr}$n#}$Tyy}bJA$WUi@(K3wx0GXD#yd{rYYFXV*M|p^Gr^l*T@m* zVX*!xcCWj-S$5Nx-hsA#K|%dGezLGz)niVW(cm zGaP9!3wg${Gt)vIPQ9~`X9JS91zS8P#=DSbKRiEkgwSV@Jqvj*K)LFw=5(8dJog~v z-f!E~r~7M!*GAlhJjK9NaJla|3U?t-Jt)mx^;eIIg*;uMJngEJkW<@yo<~s4@jZzt zkmoyyQ*HD@o`GomeuqhV4a9bb3jNK|=C22SY@hdN2z9-T5H4L^mn>Qfd_5x-h&yg|)$n_y+fv}l!a2E1>k_Vw5gHWAC zDFfYhISYB7Ed(MAwOb@%R~)mD=Uy1tNFd`K3{}D`# zZw9#2g_&~~^5lI$Hyw&j0=dGNd&!1wGwXa$A`5O!itd4l#!b!Smg_aYk1(SnKHm~& zRm9b=s1)?t*yOj4p7_RrC5?O>;vM=ackrPNe1@V6*nZe#kiiFLkf94y#uw#ieqZ9x zP&AlCh+zSs)piIzhzQZ^dqfdAEcvglU9|N8k{z~Az)owm6KsnMl3{1^9E|YD{T33-X7*8`8k(c(pv0_q@)6S|LD)T`~=;zvh`pS+gi# zzD3nhJT#C2J_q_lBvF~S$(QdXlAqp~&LU&JBszmvEAn;F{;#q>6FN{L-5U*&e^S>+ zA4X_8#yR+Y{~nnAj`tjypMD4S9ChwI1itLU?lib1wq)8k6$TUKAFK4>Cnho-V?+9V zE$scvd(kU7x-pPt3=A|U{wF{i2jD~GXJ9q*H7p^&TSEg`lwV3nro?ja&#nqRM*36g zvm7mno`h$^b0nWwU+wWP%l;2)Tf02|Ei1ymp7uXw`|AQtrlu@LtBy$~qTg%)iTe?Q z=Y~0Tz-*toiA&(b^-(9vnlL3i+DW$8M=9h>J`!J_HFo)usca?DT0KfW{-HSP!kYYK zToN_maNTuWBOQB5^l2IK7hCfjTS*jCLj1+fddE&O{lIDNr-s@2IpEkzrcE4wKh@bz z+Xcs7GVRgYH+I_YIyRFimDAQtr!CKCb~z-`y2|1&X)DA2lFuaCtoJA}Tp~J#1U{S^pfV1~9UuDZFX6QM&{imlt3Sav;{%+17OwiBt?q@|$9Pk8K@4 zPWKb4M)FQc=tyB#OI;Wq7`pZ!gK_ptx_ z+CPc?CBI4Z8rxZ|Rdje_8u?_t<%#{nu;%F&;awvz>*y{1}){2O-|Go&RLJ0n>b&|)ky68=CN~!{p*t0;h*Bs`3iFBMqAv%hs{1` z0`AeIaw4A&x^Lpq60MX3RLa zG*!nM%g{*L3gv*dQ^A*X(#AsU)Fp+P4m&|9I;zY*IHSM9NRXfG;bE?`Z_KY%;5SYG zJdX3ovlexd#^MB--!#p}zWk~e&rwADrfG3eoZmF%Fz#=fc7!+pTRdB(5Q}>J;QXfP zcnH%R0;iLQYjx^xTcLbxnO0!8mi2pl1f56Db)I+}OR{UT&->UNbaneTO>>?z`gv$q zT%CW*R6oPOPwbKa!fVt$lI((-ir8b8C=Pp7Z*8}_AXG_UEoNyFhk7F#?=!;?AU{|C`r zcrJ4Uy#m98`inL~c*hm9BP>d!XimJJcrS>z8S6u%&#^njP+l>uAKt_$+I~s-$}w;g zyT81EJll??&hsG>AzK#iO_(DC5FZ8-SQu4spE$*kS1xaP(Oh9EdwPpgBc%j^C=5kxnU*9`%&bv_e zI)roO40xV=Y?;2s?gHzT*@AQB6d6IjQLO)koez@H?JMVlWk!!<&DHtJ$yJBjI{hC7 zQw`V#fgxSPhli;EF$$sMdy#sLa6V}AN{E0=mY7+OIgtNr=>(QEd9eDJ| z-`cfe_o!p1eE9LKRru-DeM-XNf|GXzVh^ciur3d9V-KtD>}K<^M^sz53(=@39DJ(i zOB|iU7SE>m37`na@GSW{eD69+=u7CRE&Mnv_N>~yMfo;DqzAvk`ybfiFG~1ydB7Qa zK|S+|^1Z`AWr#Js0AC}q->K|)hvzDXNrl*%0i6PUjl}+}@}p(r5~61yPIUmga`Pn+ zdtL2*+n8AaVy#1&Yb5qh75|knvlrqg4q%(%SN~$~szvz3j^yVGh?`7FenK~OuGPHVVH}8=nQT4xBKcxt{aa=#ADk?I?SqQR5rnO?2p8l^ z6m5OaPVKArx7lMQu#_CS>el%BepQ!0%VMf7e}_UMV?W1%s%znn$yImO8Mo?6I8W7$ zhIPB@7Gk%lx_RJstL}UpEyfnlrXs5D>+s#-C?UR#+^Re4qVn~ENS|YOimCY$-l@9z zk1F2~25w^amlrTqHwxe6Sk7T`pGNzS&7{Dox`qG3XRz2p62#gLVAnZQbw?~UX4--1 z>QHXgorn)AikZ<6r#pac##G%Z_%w**XBCJ|Oi6x1uONl6WvcF5TTNsif%w9;Whhg1 z7hoBJ#P|z{zcSe}Rk!&JJO7BH5H_8EJ4RD=ANt1FstTe3QxWMhRrleKl#kC3bq3MX zq1-A{f-5S24#cTMjt{q~DCKDDMT85oGb|oqYdw3kherx8yDlFyY06nVmuijf3GOfy zHSZq!7E}3th96ukOmhZspYj62{K5$+h5iRQeaiLtGFHqC$_@i@*krPX56sFDf%QrY z{2np-)?lkbZeX)~U>2rm)+{gQZV=cWkO$i=ADHDOn$_^%#h^X)A9 zD8XN0;NE;@A75&M1h_&A5TYR4;{s3DUtjo%S{_h7R;VdPCpEQ-$Yj(*(e@^~|GE8pw&UHonLF22oqgrB&bAK^>oWk1J(rmzKU zS+UFg^Dfv;;R?TmT{} zqR%5%Y!1NP;@G|Z{*CZk9t@O%SiuWOyLrH0C``U}Y_u`NmJH}5ns)Pue|ih@ami9Y zh$9`qZt$et{K9|pX=7#qh$RkXx0|Q^Cjf|Hr@TWl2rQGuxlTheac@J~#(^ADm;CR@^;-}Yz4 zG^UjEU=U+7*mA0m<3N>t8buauas1KND+mx|XIMN^pW^z8hT?qXk=+p}!EVzLC;+$H5m<_&RoLR$R76MMZTRkWl+aS>ZbzWz@5(m_ zBAv$WB2#N5yweeQ3uEIk4E&9qy5s>&M_|Sa%D08XFc1B7K0nkOyMYenRvG8E?^Ghk2lbvK2wN)=F31%PpI%|7_SO6M*rPkJ6kezr z47EwT?99o@M1(UZr;jXWBJK`C(s#%mhwx0q<$_-k$3IjRs_g8kxbTKS%2gKYuyxIeVC{S5<+12EHtTCgR1B5v=u=)bIh___z5$E|wTHV;;U!KuDR-~@kCVc46L=NgIVp2tWf8V`4&gZ|>)`i}U zDAMan9c2`Lcxi```_p9N2fTcP*!H7)gK)Y>JZ*wWjy$;2**Az%>^3)uLU6k`h+Qzg zA6q<|inu|XgzrU13GIUJ-XLbrB;S09^fz|u2ZTQ;;hh`AT67LxVjw@nB3{7UAik(a zzRx*K4T$v_&?#_k5T&Q!6=Jr~31VLduv>O>gQ(rkn3)1%mP5HWh(&FUnKcmKbO76o zxj`&_*5v01h_9HE{Di*Jxi&Y57sr^$Zh*Mw+A@^6K@6yGVtfdJi(reiWo{68TiN*s z(TFL@za68wLCl_LY^8x1n8}v8K@@CGK0ZG*1G{++<@TuMcEG)Kr*Gu=pyF~Vhpl}G z7vxG5ZGFN{?W_0a*kdZN)Cs0i-i41{DWz+aGL4nQE&PiQrUN8%7czyk|OqV9OwXDH65TAuDbPG!g)GCxe<|Fze}>))bE0DyY+h+j$XkQ&!!^k_cr+M zbCl3B=x+V~{%7SI43W-YcZsRB65grbZ(xpUECYA3^Z)DtO#OcCyz;%tVG2Mj%79LR zQ@{6M5`YVfYC?R{0qlxt>UUf8NyJQd5a|x(*6(qcP!TgzAqzQ@^7z|09uo4&t0^%TT6%H#=lv{1b#91|n^l`knhtJO3a`G9~%9V>Ig$1Mp2?P}-~ZfFK0ZIx2fINIxrI>mj=6orOS;^A14*Cd{=pwpUS$a?r9LU=) zd_~E4QV%KzlJ5$BWU>c|$o;X9vxBLZXZP2Y2eBf9Ex9?iTC1NHU2GP=vw`<7i__sO*6|KaRCz^o{i z_y4IgXW=X$3kV7Z#Ecomi~%uWysQyLNupvx5Jk+GF@wid6qH4bsK_F$1W86PV$O;= zD~79>xWCU^Ju`cD!TY`c|2|Kjt*&~jy1Tlkr>Cd8r}UY=C)Z+nOB*CQxuqQkU3W_x zM0U<1bdaffx3rOPZ^|SUgOJzV(xz_5I18ao=4ZN4XS#lNOFO?EXORf-5qCi| zo(KnIfYeNKOS`;BQl1MzTrHHBr{eNZ>g1MIygOxDrTw%js~Qm6F8u77p+b}Ko?JID4fnGy z-EVUK08pNnmn-v!^--%m7wtk|gx_n#*bxN1WYX$B_;+2a^VV82kouffpSHTcL?^B8 zN9ej%_bEodQ9fm=UaMOUx5+Q5q~cTLb*--1Xcn6SunjN^)wQ}J9fO;B z5#c)-AT^V;x<`g3<@p6fM7BbCDxzP#)Jdz;0kEFf8Xz_j%JZC}l2+F$PEza&;=mPb zC9UrEv(oZ|I76sw?wD;G4UL1?rU4Vmy4PoA9wgPS)6en+>X~X zxY7`&V=*CoXw%>)+Uk^1L8*j_dM6=xnd@0NZ9C4I}Le7#%-lahztc z>qeJ~`2y-N#O!Q)+?Yc}cRHJys_3>>H|A8V!heK{w(5FoGUBVFqQjOb8=YU-nC>VU zyeSvy;O*?gEP4m)zNj~(?2Sg427|Zytmv@MgW(Z%hBYov4PVU!YiC4u6h9S`g!U<_ zf#LcrJvd@nqr!!Mr2XCaSfJ8Tq2lSNu)vr<^mq3=E*%w0ziw2xgp7Pa=4xXx|wG|yquxZ&hedi3NQZM z%r^*s%K)jFWK_7EQLdv}lBKl?p};9B85O?G9HA$+1Bg9^@;s-gWK_5g7qHtp7Q{&_ z*h)r)XYmR;lpn+mE7(d#h2=bFxS#I_F};B;Z?tL?89^U6373`Um412t9TW;8E1l8v zC$(PQ8~q1C*#I&t;M{-zgsWr+Sd(JYqH9HCA_Id&Bu3JE#4vKkI**cMDz5 zc768S&wI4GK8%ExdqSJ!ZpZBY_92f3&9}&@4Cc$xH1SfQ^(x^<0+jNtlOo zy>3qLs-wf2NYeS87JsD|`g>}&$@Tbt2NwN3fsTE}PlX&2TqP>I9?iX1pB43NA;Zm2 zu)VRozimXtH$U0_k9>}@lTX0m`Hrih-0W}Om5bm4wgcbgrBZ%N9gMCpo64VF@Rrk8DwpUtXn5L zS+dQ7>;c<`*lu;gG?&d;*k&(b)T~D)t;?k(mHF^H7J#&y-O>}ybJ4DM6_<-C`$Y!LKAiD-FM|KrbsXcK9pl(u-@c~llRHt%KiONB4 zylA}+2eUhv0|=#6S7jBQ5uNVpPj|9t)n5YroYQB*j|$H)t}ML3PthKcZ$`>UW+?ck zXg5kU5%%o*BJE-t6y=_6zlUe{H>LMIka0Gp3+c7653oGWriaK|L~eHtBo{V9vW~x#B3$7IUMVpP^n|@7n|AYo} zgYq;Gj8YyNt(rGw1HtQ3z6C+Yb9pHJZX0E^1v59RFQ*-+a3boSqQW(O*#>Mn7^!?U zv{oCLmk=St3zECo2_nEKRi?CYAkc3H)UZRa)F2nb=W5XK9t^)lC$w zgR<5tXHk1XNJJE^^lz|Lc0PSd+y%~9o7IojJ4%ld(FFVIY$DIZb`YYWnW`uoXTPXZ zd?wzuzY2QyXCCoUbU`Qh6z#)-7`+l~G1C-9qB-tx6YPZ3G5&PkCc&)DAfkZi+@=Y3 zpCHfXjg`LVs)lod@zio>tm^&!2@u_MrNlX8J z7sB=-k}jig;WeKvX1MU0&wc@#m2!)dpQ61?Zx(+9_d7zUS5YLo*G?+l&HTnzX3;8y zAQy%FFPAsk5&61scFg3if0ONSAzzXt8#G#bPFD5>(K|!Al~U9Mn^Ddnp{d1#0bQ8^ zMOi7ZV0)-RpD_&E+m_iK$REwn-YCb}m&3S*wk;dN1;sVlVO5fU3yk|lkKOXe8Bw#% z#Ec3$HnC`Ht0upNu`ILZRnI+n^n1E9FLPsEWo*MniLvEiW$etT*&$*^1#$S?4;oe0 zSJ=uFyLytauwq69ajI;DP&cM1r4p*H*|}nds%v)cEzr6P&0-&1vx|gE67v+RY=Rdu zwNlprnw|SriIw;3SrID9hUaC1EmkAr?-y{ZG|s9Vif&4MBC=M*qQWXP%EAWx6z$9j z6ksE`+hiJ|Xe2r-y)yrlyH6`ltL$-Qa{yAWi(Mg7_le13UVf|WW1;R&QPNCZB4+B6 zNzipJ@fEGXfLp1|f9UCIJ!_T4t+DuCYH@mEMO7hYR1l}i))#8+LXtaars;~Arn??= zUAn$rHW+X#Mbj4?;_U%-BZP}a6#jS#e-urhfQXNP)4zedXw%0c8Unj26NyUtpH;rO zjfk>wPPEE5TqKYEGswcSx(0{8b!SqlYd>-~0O-~H}6@uNZq2B1aLmVMWxmL7VQ9J9%Io~<&M^trY(mJF-#IE2 z=a>V2@3gD-!Ftga>xtI4Sj0 zM4+h9cn=k0oD$j*#$K7Gr$868m%5mNutOzmc1|-q8hVyMqyB6)n6trLnyH5lgd6e% zL^r~|qk*W(9`1*z7PhQ0SULW57^L`__%GJ+hdRG#$B%>mKKx$@!DXWA`+8q49BQ54 zxUdRmdlCXvRDI|NfF{_W=DaVNZt?cW56aM@>Z5-EU1fvs#PBHyQC2Ct%dnue(KN#d5)M52O@&P<*p9-oCum2C=t`}!)_(+Q~MBWzy;eKMh_ z)ZWDdh;U9IMiP4!Qn}F1g?~kT6^f=q^5ZJl6Ecw~@~?x&i>A%7@pL#ZWO7lY*6jec zzx@6R5gO|2{Ahn{(fYlH!sl>*s;_`Z+hk*_U@$-k-WEk#+Dclq843zAm6*Egb0@yEPqEOdG>-;{V_hA1!6N&Qfe0a3V*Y*dosGxl+K0>Ur z>(nOOw#XXmsyTfG4KL^mSnLFmXY{V*nejtQR!`MO03NxQQ_t#%Iyf{c7v8YnQM2d-h3p3gWh>@qkE&1ZSq^R)8WTg zK;B32WEI(2@FdF;q~08&m%pCuLvS(jF1W(>(3SZohb!%uzE#>EDeVtod)ktuX^Y7; z2fq_+^f_VN^((Q)tEMgr<1WRcf<75uv{sCw;!R;3Nbo!=58=_&D=TY#? z$b^qD(ihG-grFrVZF`Gz7Ybd_=7NIu2+*?ljcGB6cEWxv}xKe>HLIv9)dSB zb-xp+-nrTSdNguU(U1u!9w@NGw*k5Io1Y1yEaM7(OcZK<%r2M2zo_3>U~gK zz}SZnTvghkesAJO1#RZ5vPsJG02oQ0`Bvq4&&&q839(5XDCti+e4RY)Oe0w z#T(C!i0{w9qUwVW1YESs)xzf>d?$mJw(x#x;T5-sW?p+O*ss8?vU*xzQCa_6B#)}| zy8d_5>y*Y&>8%TL$NGBpOW1=BD&7}F?+oP~SbbFg^Ff^k;<5}Ss(#U?0jjof&D;;S zA+E{5qUwX60$j9@mHJZ%KhB_~-Df{_pA~=5Z-CwELa;xAYtuIMgQ(08&9GSC4-?TS z+P4>=w+YCu_4P_iSY`k23#tzYU#g%th5k-GyjZWYb#<9tTPhxFM;^gDsPhCJYe#fW zY5MfvU{zT+sk~6ClHFJm-J45vovsi(Dkz4LM@s@CR&NM`E)o3|3eK%Q-4~BC>CNHgsVX6pV%|`<}3&_P8 z>;N7hH9s>%#hnb>OSvs@RYt$4`72_I?hpM4bjd7dmEA10w^OxrWS|K^F{6Su>Q-5; zQ2!}KjkT`3;__oP&H<34GmJN1BdI@_oyKL#S|!DC;%DeUbtkw5bxYAn&-uq#&( z=?l1VU)ZN+qIBf`@PmlXgMDQt3L|%hC@1qYusxq^L^3s#mcC2b-t;bow7aV?3&6aR z;k+;vibsWmC{WQxsaT)GSe}8rSfOogbDG#u;Zw(UP+?lFMTbWS9`QmuC*CwWo)=%MW5`Bv(ri=&Fdl<*;oC*=Q5%vxB%C@K=TUoJXP61A-b&d zUy|9ZG?_Hw$%Ken%5!I6bE{Y@AyrU)n>pSeqel=z!w+N3DjTQt#{ReTekx5bjd*$? zLa`Rh$oDex|K-b~iJN=6rXuG=O^%9x#thS0j=uvNcvGiS8XrlJKrnkL)Xc zJ1kgkcZMqj%k7572cgZn4ea~R1nYeoUD@V28-UX3?UmC_aH5?#oyguvyL|+p^?EBSN$=8<)J4c#pS(2El4$>Ryfcj6g!R#qU zenbel@CQI&ji^SXw~0+!n~rMJRjQ-&;-z5!%JAMDA<`*xantpg3?~Frr9IUqCVuFt zil)zl$2-F4mw`*~C%@$M1zV->_mf{es`T~caT|=z%?qBf zccbv!N|oBgB}yT}c&o#2YE->+N&keJU&&f>p*qpzo0u$s;UAc>LV11Qw|Z6p%0v*tur6gzA*X_f>W~R z^x;wCi^XPf*#cqb@<197g>g}a^`}-u)2>EzJ?z^ukv}LST4NPN_rso^iTtq`(Z@Ut z$4|muoQeF=mfX))?tg^sxld=r^jsh&8{J8;%H9=f^^HnU>2ravF6XVWZti;l$X1}I z&jkV`&uzyi;NN6z=t{unm4KbTTW#+`&qCX_C`~I>%5t1O7nEq?a>eIA2N|Ylp)&Ud_>D(H`zGV@&|H6$23FK4)%tb$REEE^|}Dj zwy?WqqV$pS%1aRa3wEze6kZosSx2s?cqr_2faLC?`D+s668P6=Dx$c74#hJ(rK)6i z!kL`OMIrBWo#b2TVe)Y}FJ|)aFiA#b`hD1cWTI?-L^DmA8cAoGMqdlIyrV_y5=tDX z)?PBxq|KFaCm{P}Fj46<^ORWID4A(ps&=)nDs?boABm~Fy0!75y?0*RFyqN^Ot2dS zTihueFhqK;sK(OyXy`qjuY# zPpaG^4FFSRvh^kav>PLsQUBX&NQp_O0dLxiF8efrPueC0Pv4m*i3JCL+DQ0{wshuPL5ZEB>?~V}oynzkLL{+61bk|u+AevNcXFp%b27XgAv6L} z+|!RAGyqwfjY65e|1lSppQij#j)!Kb9L@eD{WAftICS@=@5zuotfwzo3}5AI>*I+^ zG+iq{&L@RfLLUb2nsrDbB=lxm5-QtlWeFwE2-lPjrqhTIrmsyTXX$|pN5Nx))EG|R4-njkgQ)%_A4qXeuBtmEnrQ`NxCcgZ4Cfi)> zck4oHxYx$OOvdi3l#bn-myX>lO2_UklE^Q#DqA&y`9QvP7|1J)Yx=TRV9f>t``1+P z&q$E+HaPWK*CNBvmn0Rn{p!T7JT4 zmZ+)c)*#h=V7r$!wWb8L(n`#9vhB0qKph7o?e8_0h4yY-Ht~5Sd`(}{j~DnCUk(3e zLdb|HF7R)Wa2wNIXA&HpPoHEo$nU>U^80k_c^1wanLONj81(86_!;cnmZ_@W0hMjt z2Q)RD-UpgsEN%&IlMI{950~5rw4Ey65lCeQ6IFK~&<>QSpq)X?%*kQH5&L~WN5)5|5h)y>PtI zRwVtwM2mC_>i9`QB)v>~KbkEJxtpgEjoOn)c(582HSdsX^$}&FJjW@E-DOlW3^F>- zR~|6K;5YRuyG)3CL2UKez_2sV{xJhPmS!N0cm_fw>!Ehdg}DaS7|Q&jm1JOzGy|Uq z(U#lk|B!+GOEZv0JOd#@iPv2dbK79fZ_&N*Z-rva8U9-i*+b%!B-Slj;`A0BX!YQ& zj&`-=7Cm0K=&PlnTXgIi;TA0vCQp&cM+ML=y2Rv=5|d5?exeuGaSL#Miw=Nriw<c{O`;Q#d&{TtTfp0ci6w5(*e=nzS6(TXIu)>|71-{2O#Ib(o$>`LrRZd76? zL=rob8wsD@qInAFj){k1EhL0CU;1u;?VR|0#)ht@JpU?mVHAEW+HLaY7sP+g^h6Yb%m`v!&jY;I)sMg5afhBd$k#B(_PQ ze#nr?-AG^MMkuH*R(-|WX2$oBv3u+!cACucH8>KTK6Geg)8gi9VN|)+Ny_nZ>^13} z7CNj!oM0Cy#lK@)3(0nwv^2%PJw>eOAmw;3Fg-GyFPr4yM#uM7**rD&>k)c?p+ye9 zD_ckZj}Ngit%-T|t%2I04ZQu(vxb z>O!fuJDelm)X)b+)>R+zxZX}XX%Mu8(EWx(3qi&{m+ofUy6!tcSN~Sj4cwqB8r{|> zqI+V{P104nSW&k$T_MozCf$kkbOY+YIByw79&5j59 zxQz$(K!y}WyU?O+mh|6FM(4qKE|ZHw-t!L0Ul@n{LpXnB@@(>6cYeKyN$>pas=+qp zF==%|Xk$L5MKk{C4|%>)o>wRBcV?|}NbbzLiOFJrev5X_{h<0mUQ6(0Gm3pCANC@ibtoo;SB6B`D`nG21-L(pi4)L7}P?x39bQQ?~h7(_SoH`VfTjy;Y zun#k+_dmCXE^cezuQAT_{Y;Q*ljH2Jcj+~^&Pzk%hSoZ&v2%U~EsxA<%ebn@Livm{FkxzeUptoiiE?& zL(Tasrn{`kRTYAu81|)Hrbb+ZGd)#Qq*O6$v%EnZq8CoS&`R*k$b)KjZ^4OoN>W#( z)QDHLH@lyZR0y|{W*4%glP%*-KpaGVYv`yTje@eo zx~Qp`TMl=1W*maDH^y*9wX2B5=Q}4fa#mnI0(e^(M-%*ra`~!6D`~>ra$545nCO-h zI<4uA)c6O%xROw!nSe*;#81=Hne_1_81o6+$Q~R*#HT0P=RzcTa8RV=!9izv>Y}UBg>tZQ);aNglh>i0g)v5Y&6MI+AIct#VSQ zUUUR~m7T8qJ(-q3&ytx7{Xx3QMhUV0t}B#4Vs~Ls(tKa@9sSgWBo}EUaiL%ly z=J&>Y_Ar}dU=2SRfh_(Y#7+NO2KFz_KpIJ0=;h%JI*liuh`EOe;i3`6J$~F0^(%Ms zTV-3c2lW;FtZ9Xdszu|xxQd*^$64~<6Nw7b`1PNn{UGzX-FTNxC^gTrOWEuWo66hT z53};iaBDbWg|Ir7!BN=(s_eV0?0^b^F|TF8Mbkm~@iA})5`tx4cTH|DmE~JtH_Yv- zd2y56w$6_uQj%M;q*;}pq`1O4I^mJC%|1F#C(H_`wEWp--*8FXYENIpim&~=eUg*= zm6Ppv|1SnlD>0bRZg7xH_~hPuvT@Z)ZFsY9wMW|Q+nC8(XmDA?&E@v6DW_ z8s7usE7|^ufvuE-C&lvF7A9rd+*@b`{4HapLw7ENq#ZT5VJC+$H%=BcAW_L~`R5xV7A5F65t;|FU0{eNDc&Sxvr( zNP2;*N_&trBD2jygjS?8jN>~oGMNy{o?lJPpGB&R5Y2)8b0+dN|7t$Cc;LTLW!LOypf3?6@DO} z9Cdz@ekc7Yx7?%}u0-hVToQE&dc7R(bjtz z)I`YHj%@gK#gIA4eB`C^(R?CNL0^(Ay#KyRv$qBgpTPZ{;OcVeGG=(dK$X@0JqIvwBW{^PbBvTE2U2#4Tf$) zr%u(`sqrQ-wj%^hQ8aHImC8O0f8+O>>iBf{ewn0i{Dw!|g~U~R^1INPMEGJHzy4D+ z9l9EiBz}{Ep8*rhSJ@x3`66t;3+WxUSIwhv!e)&0E~MoAE+jDK!#0jXW%*+`-xGpm ze`86D+_VFtwf9~zx2xvGO>)~hzaEj2+*bKPZt-v_>Mm68Xtwk&BxZUS3bgl@`zn)q zEg0@XK3z;sdMGE4{WpWBl^9HDH#kTp?$#@&OJ$>CpOt0GuTFU`bi3SmWG%Z3g@~KW z`2=!>%!F6#RrZwZo}SuOa@i_?j=D?e1%6_;;M&<;LfCPB=i$Z>BFSAs=7Rmo{8!(q zcWAsWsf>l~dDYJ6v?mcWDxAr0(dK^y>S4&)gix7ba||m0Zb0-b>^CxzC|cNmZdL=; zS2L*A~*Zx5CYM_BToqCKf}wt>4FA!H$>Q|TXeVZ_@B0eEY;>7ZB%NtWfGzIpeOysF2J@wA9 z_&kx{qB(?P$8cYnTV_k(t=>J&tthKli{IN#6NB^0)`cEtKfldf!Thp~Jo4&;fEJW> zJt4x{bnFy###7-HQSbA^O$)Euet`QB{EAehbbFL%%x_wPpcpR5St`O%IM)(N9GDbg z-&p*pu%8!UO`4EhR%R37J(l79JA;BGbfvBIy8L_ zNedAl$%GTrvgesoEj-Uu*~aT)>v?R|J!<(YaE<%7>+`SuqLK%dv;5&AF`q`l}|Nkiica~-#jd%t^1m8R4%XgG2&gT;NIKF6-n26te8pHn$R-Qrnf&YRoOCSqj11~v2a?6 zg@kqsgJi+`(#_VxMz59HXi)L=rFCV>B5p3{WvY;wup6byPLti)sa++PmCpN8?Rm-i zQi-#^G(_BPc~TWgUn+CKer5i(C2FJ(E0r%`dtUXGhNLe&L`)9pfKz2J3AOcs_(`L4 z&x=OqAt8S{zN+-$G>s?=jLrq47tj|N;;tAukPt5Bup@@ar7IEjf;~DD`3q@X=RP{$ z=Atl7w6f8;bjYb7?BN-KrMuzOWR^s6vFf}3P}is3F#DVCWWybU>`*A-cFIy4Xcjy-cAqtWoMfy2FpeI9rsz907VOqAwrJ-O#e*zeXCl`i@( z+Wpsq`Wl2CoMyyrm!j@xF*W71jzGrQ8B?H}HR?iP#@UHevk1N(d?K-~pm?D)^u)-f ziw^gQNv0DQM{JRct|2sgCXV_b8$@`(hjpSXHyX4~T71wh#ndQ}&lC0nJq7tgdU>@V zueVp{!Tzf1M)UH8ma#9#RLn!;4MOm)zYi@fRMFPolcIkH;_nRQ zhs)`zU_I5BVuy89Mbm+jQOkePiU`4?sQNo2nvwG{TT<^DKF1mqi?n}I94_c{7 zpCV2*73SYSrjUQTyT+8&Mx&!f>*vQmVpYo{7cK*kTP^o6N;Rf)4im&QJF67Y(Q53n zIw>cino9jA+6ys{g&JE5BOcvne66XtACjr5){G0KEm>S5(9%bZQ!1m2YHf90KMUh% zhCTeBC|Vc5CWN@MJte5MS@3p6T5C^39Rd~2w6`I51Ed1ShdydciCpYksreE#@Z zmI`Ova(KDH=i^KMs!b)jWiV7`56X2J;Y~2DD>(s= zkX2@4rzn{7ZLXaZYo`vS-x- zv~u?@beGWr%5I%w1BlPDp8QU>7Dutg%vMhj9f_4)G{<%zUTd52yOmq`bwj4%vCviW zfwk5I$sm_ZTs27gO47U5v@Knd>E8CGGXe=qb!xrwOElM8zC_iCXtxs&QEF=WK~v3M z;u#Wmv|4ZW5~XeaDTIrIZmqZZhY^N0|0`5z^KS!MCeYGaZ}aOsCybi?9#Em#3-bvf zu55!pL$e>@I5qpJP#9CQUmLf#J(`QFL9;)*Fn+RiLNL#p{4>(1`zz1iM(m1j>3CH08m35^~NQI$6 z-if~dO|?sC8AoA$nR}tu)W~WP&$WJQ@Y)(l+g{9!_O=UYNVRq~%nv;E3!&D3NhQ(N zU;%dosE*`7;&ZGkzmu&eys4($#X<}hf{tVzWVN;`zk9od50DQ=K1OmnlAnlQ;1b;` zC7B@!9f>MPlF(a7@)i3)-xc&WrItDv(G7LIY9@>Rrf9Kt{lB^m--;SIeCU#<)Po-L9nL5a4bC^)Z0EO3An-?Km<-S|vw% z_QIg$K2&F5e9mjN+sN;~N(7UeVkR)^*l5|8uOKalU zQ^z53=r|pgKnsx`1Q1cj)V#ov;qDcAy865*EmKM^bl02AYrzY-z(4e zJg9;`bX-q{2MEF9Dk76MyO{UN5)7xjtx-?9mnz%nsgjH zX6B~Y4KWU3uyY9E0QhUs^t%#j{1jqF7Bfxf81IAlKtlPdHKqfMHHc=6JI*ZX3wtQx zQnZgo^EB7ivDJWTY=#s0Xo21LD63T07yve%;z$)evRoU<-|y%85r4E2KMNbi_XKyZWwqyGm>WdaX(D9d}B#+qw}+@3Gf{V zPuL}VeV}}&Gi#&h5!7c{+eGrDR;!lptOa1NAedn~y?HH!?Fr>OKZ>PV`wL$DmYSgs zab6vYcBn#k1hkkIQoeJo7kVp+`18ZP7uXiccefsZh7tBf_$&5yLZQC1lYDoRgnUmm z4lR%Rpz@_`?^A1A5WmGUphKY_@KijFDfSYzFaqe!gn0;b?VLiW@e{~#V2yo~)qX$K z#);KHpCJ4O{7RtD66$AYGRf=2bKi3`kg31OdQ3GPFg+Q)w#do{*7&i~jd`$cw0?{6 zK&IH=oA7WBU>RYnx8vwj4EG0IXP7x>Dj__yO#zd{heA^w3^8g9}fBW)hTMc$8PCGIoI9nXnkUuVJ%EUzJzKGJ1Ir zae^w?mOseOyXiZFXCWMEU?5NOpmb|T$ zx?=GJLgAe_I)wP~gc_3pPkkdNblsmQ(^n1#dIg~?@QaZ>P6##csi2cI#gURwPcyxJ zorB6{gz~Gh#*{TLvNOc9(~gpk0(2)~IQBon!aDtw9UWka>EPs>5m(DrRRbqWFiwI7 zPX2rqi>APTf-nWUJ7M#5xBD9sFJ`XP$&Y{=DJPFvxs(4Ox8>ub5ttZ52u@B8;&dmE z7n_g4JtikBrNvnMmGC90KT7;rLXF9Qr+$qSa`H~IF@0yWO)grE(Ba)U`W)HD{Zl7< zDs@i2Qdxn)--$ePNSfB|3h++CD}a|fP}x-aQ%uXz zry!e4SdP5y0B(GfwQq&FWsUlF!{KaK_vzlu;} zQpMIxTR+F-1>#Q#_H?anNqi7cP3FIg!{Wz4CSRG*x5S_y+kw=NW?IQ3+DsCU9(UnPduwZpT9I@|g1uC0+Hdov zmuIS}=m%kN2HN&&tyL5M6Ird@1hwG@n&f^9**u#}d~f3XamjDPcnWi860U$biG=46 zxa5&gm>Rpri9FzCq&EWK6vAAorHc-Qzk)b_)pn0E^lNknW@-s5X6RS3qe6SnkP@FyX5J;t!o=&uza-R{ z40wj_cOsAJCuI7s=yw<`PON9Tek+!NB^YeKV=np$qniT$7ooy@ZBioE<6tQ@*>T{3tD>%8l+j)pl#jxl<_iL|EQy zj-M;;&En%mT4kS$Mia(jbpaL+8>npkg2c=EA1CsU*bxxtg1dxZIcwptVL@7BCkOm2 zOChuEGFUM~sfcITanMq{Udk~qARdF!XmnmLFluayNBnKZEK6at?OE7m{*r^tF0zm0 z>qb_Mi3NmL$?p&{vE50j7rc#;>1V_D7aG|;{dGy@8%;A6bP`H)m40K=Pl}ZlG?Y(} zseUxD_~QT z$VZ;TsoCekK}Qv)%~7|Y{9HKfsD(48!2jq{;if}$np zr1A-%?iX^Oe68I9!#_W{^&)e}Z0rlh`&Z+UQD#`RT zlj$YEn_-$W0&CskDSTyhmZj`DZhV^Q%)xJgHW74RpgL{vBA_!(Cl#imcDL4=jwqC5 zn(27MRMKQ1uWfX&p+wV7hayU}gq${+i#;8Ocq5|ZZ-PC1GSy#c(IJ%e6hi2;OE<$+ z+VymAREOL#n2g;?xEmXn6JJ26F)6!?j&&kG-CZ;c+%mc75KG+iyt{`^L7$wGbFg}x zhA<#MAiR&&cQLX0X|k&Qc5Zcq6N%MYa4q^_^~m~Gd6$}5onYUnSiRU2kEL#e6^qr& zo(siNVoNZ(?k;@8_47D7hWHpljY-)vu&onG27UnBQ5iU=~HuM3RBs!F5#z`qs}teGhD`3~WluIt;=_a2n z13XgTQ@NUIU~Kq>`scgdGBXqRA)9COhz>w7&z^%SLd~*+$<9o|YD_MjJRcWK$a?!54=c0Eow-vfy z5^7AA+yj3&LGc>HXA~V=u|7%*Rl31;HvIqYiah}@5%`S66`Oup&lSruR~(8UxZ*6R zSvCgEn7lP~#eDd05K>p%58D40FivA&c5qje*67L`c?9_(9Mf|~dY4LO@u-0o{j-7D zzrw(*N0lhS_cK|EY=0HJvMP1mNKU54Rrx*O*Qf z;KG~k3koD1g*5j9U6*G0U81!FlH4arx`YM^r3;tf@d)P!qu~XsC=uHjAfhrn;(FO|vU8vF&c|4s3xF&LF`gvQ^*(Rujh4fl_l zhWke?CF@Owfh+KsP7|30tlpikUT-oy$AVhG9R$9ByNAA}=;fSXkE;@|3~ zywbF-m1|vjsm9E+gx$&Cn!t}F)R>e#e?L2s4^8+Ua8D3yWc|*&tfcc^WS5>w2Hv;D z0C(-iWrN`}G5R+lj0%U6S60?Oi#Cy8uQK$#U160k8s9SFfdnR7dSz!_CPe-Zc$X<;-&%LJ6r?U ze#+_>)|Di$B`n0=I<)_aVgHcTFH9nAKVlzYtT#F*6YMLy47D0FhS2`N)QktFe}nMF zUCmf5l|pA*1sH!|YQ`%8f98^jVKVczJ?Cb!=dKo|&s{ArlR`_LOIoClZZdI+%zT3n zG83&!O|-^D3M(N2R{lG>n`v&KYhr*C zcxz4Y3CJ=Fvn-Xr;EIpf@^#qHflfrCR+$@mj&52zqxU>|y!(Or2x^+?G~*Q5?##H> zmcR(0SD^%A43L0Eki90y#Dj**nvO_b?R#=K-E>m&Wu!JH$miH~Ft~N`djN=98wzzg z)O6E%&Vo(>+I%_bt&Qj^2eruHaRQ%g3xUnE&52KR^@|eqB~srO^;#HDxcWG#{0~a) zeki3o*VGzrBDH0LuO4shZa50&Ar3qU>P#q*gCXaGY%u`jYH_6_RiQUaKHcRDk#`L8 zT9a(DWZ`eJbw@JKuEVoW!=7iiK^2yYx)*92r=~&ma%ut8IZ$&=ZMiko)E9m0p8LvE zULWh%B4(Kc)HJ7>LcQnIe^B`gihN0X9kho_dp{b7G&lb-)jZ58X`b(tH1CG;zeRT0 zX zz+@Xm4wLibdi&XM51SwV+{aIivmP(n`dE;aAF=RK80q)Qg=yLQE}ZUnNW7fv*FB+G+vl&^U2$DVRrjOFXWa#tJSNPKEV8!%KAWtHOige z$5g$Iej2-H6Rr7F{*FeW)|9_BV(5mCc*rIj9q`edJuiFj2`3>YXvbJ z@dX4sC2rwTeeKLA0H?c&UdSRI{rJ?`9M@#Bmgoz1Ah<_NpPv(?pG+JdpN@%I)5qsp z{i2TIff8}M?u7Kx4sc*Dx>_Xj(cN&6&hs2|h&L!-Q-~r6P zPN?6^rr8(<5VwN4U6#(^(NSNDR{xHfqh)4zJRi|Zgc~sP6DHQWprM)RZsrLvomAf8 zrDpiTSPgykW+?4N2z_j3_Bb@CC$>cmwY#5Tc{;omldSk-*SsRgC`eIC6<0kZ;LB?p7 z^4yvr?-Ozs32hH!f}`Z0N1+&!uNy$~0k!*_E9+qx0dyCXK#Z*s&a=71KPNuT=OcS! z`D8+qxKXWXF0%cvDuU)B_kv3P7TM-(M6vmC3p_lJa5S<-2>(WFFdCP-mQEM*#;~yyd0Oi#XHu;H#2vsMzCRmve~Y7Pus@7wSggh2 z7@+^e8l%+pDruZvWhvf$*tXHbd|Cb;Ce?GJ4+}@4HOlLZmKW{wB$dsvo;btuq3f(p z+FNrnu>rx1NndrH7my>}`t-V~C;EjGXa!~YlQB{2uaiarsP#8YcR8h(PIH~od#G2W z9@5vJ9KzHpS<&|grY4GGj0P}YV5NNq?U7M>yuZK&n4v<=;h(o90uhIT;| z+E9O}@VAJkNPOKS-xyFlN#y8 zp4AV7mwWaqF{VzouhJNq?|}V&gaNRR#Qv~B_uBkm^r{H=p<6`n%YV|n zHZPHvUVa&d&Upm8zM)@INdv#QTj-;6JnN$OFkuO4HolZ8AVS^EW075XI$2wop8{ka zq3s_${{Y#QP``z6na{@Fd_cP%n2UMMJ7|C>}_kl~1DNdIk$n@FVo8?tI-jSgaI-k)*w2C9F$dU>2AFUVU! z7EAq0)Dwx++W=~T>e+T6VY$M6hR_U`#Fe*aBEvOAMuBTDOk7#?Ry9-IJy!$O8~Vw7+ZhG z(R@Ikc~ZxvNeNOw+*V1gK~jlCN!_5N)++0Ocq>8=EaWby>Io|(rSH0S0<=3}B*4u8 zZAYl_@3?A!F~#&X*RII_MVJrfU&xPgjK1b7%pzN77-_Co)&s~lgk`{n0eOWG(yW^S zSvH5Jyk1$-t3MQ$C#+Yd$@T8bW2Q*H9Oi%_-k~>}=F2t~V)T82ZBSP0t2HhHs)U#6 z+SSt@!Pw3CWRGuW=k*qkCCrMvP>QCjR(~sAd@lpxMwS*o1 z6G!im{&xfx0U+@^?fp*ZPCG`$*|BUC*v36_(dpouT*)#GLcMm7W`D=J>?@s{(Hl-y zY$viGtg@aWq(kq!$c{T3`@5C3z;=7Wo7g`Y+gD}w>+1Zq%^a#aR@c4AE|+fCvJU8N zNvMeO(LLxrwG!QJFL7v{?!D6OR@Mo?RW05TscCWIo;0_>M1h)A| zi`FL8^MT4USN__ktOvO7DtXTec4u(sU)uo7-Eq{38hNaG6W-akOnac>(Niv(?t2bK zqCN$&b*H6jx6+^33A+w%LG%`)Mz3FTl?D@9YQLl9lcn~O-bP?0_iH2@mfA}k?tz&& zUCDhkB8@b(N%D5|mSGv)WF>blj|FX#+z=|P8{W3-ZcFjQE{eJ_|A zLR`6zXHhG;?{u72az6^iT)Z}neGEumiVr10;-5Q6TO|u|p5c8eU)h#}`^jx5GScYv zYpzcHumf6Q%Ymd120y&#dC*+9#K8}lcx8Tg7`+}UV(Nzj(F=a)2NnFV7ugQ3)_Fjg#U%@O0&uCNOwfob-qwls7j_+NhB)jx7z`D59SFD(V8dMpU&0H!4umMMAfx`SgHdil zyABp3?)>gZXxD)x-6cu3D@hV|9Y`_|34R`NP1;r^4!aH{9wG6{>gaWZV}fpI ztF6n@I_d=#>ZmC$oi9+*R&Q{O>Zk@P)R8c4)ZIj5lVOKN>_vm|qT z3xcK}v=+MqCN`Cs!|BEAEx}GDD=fj5U?W2P)xmU-kvh|!Wu1@>BHTk_y~zD8*EcM| zT%R>L089&BLff%rcLNKvCcmOI-DgcC?ua;>HIYa!2(;AuV1$Pd(ES$O($Y6=EO)E) zDJU(yB=t+*7ZWGTO#g~$l zWQEd8@HwGD=_go@jplYqS+pg^-I)-kz^Xri%OF@zSc=+OhvuS|g?w}v@!JSBCcHoV zY|;#0ARa8ATtbF+gyE7Ong+>8B)O?J$I6k^*mBq!K5LLYx;xh@$_Ehk!~Qg^#-oMO z(Lg@3o9qN{gO$+M;Hs6-(WX3-wG{JUKF|RC(+F*Q3LP;@`gO{)LAu@SV`aQ5V zhHx=?>Q1~Dp~j@_dFtRqo)=?B%I?)=(P?n5AgpNj>N4@up{xv5WB6;rQy9OS_zVJ1 z9{jrT;ZA7juZ~7q3h>{A^74H23X<;~tkaMj{C4n8jeX#R#`AM;AxkfnMTgN}5%xf_ z>5VKKAcVo6sPJ0$x-}enGYkf(lWj2$e9rb-5ANc!hj^2BIm(mmOV}^_q5ChFjo~np zS#Y0WDVRlPp!u@(JA=bQUMU+(q^t?8eY)vv{S8UHBN%&`A>m#yx=Y4iVZj)FX6r{M zf>qh?doz@L6>S}#GC0azuT@!`PO|Oxum^~z3l5mYvoN~2;>84%@;brtCkRYZ?j z;Y1oD?e`$Yx4(|zUwc#zCipo-LWK(R<3+~$Cz@J*F7{aeLQ|l_fg&wGmtHtfWQr;2 zCCylgvI;Gqat$N?bybPo8dFkUN1HgobNO~o@HnxD6V2w^tW9X|nCOb1T7K~)26!b8 zFE_ebjlJsx@E4t+etH6%Zf7J)gNfy8m>a52HHxXm6{*HZ*U(3?luWfW#-Y(Q)z~)G z=$LBE05i`HB|4vS&9gpGzd_BnFFJDT#mW*8Ew8TPF`(8OBi+8KMlydQ?GH88Zc1>= zz_mK7)}|2;nEMipR=!kI-y2}9#i>}kzB@&)wWr`+@788O&2s7isL!FMn_7r8I-!xf zftL=;U{o|y;@@QO4-)tzHk%%7E8yJ;x&F4Pr?3QO7gu=|>R(Ph4Rst8V}}DEPXRwz zI((Nah7Jvg9rB7D z%XsZcgwGLji)VV0FC+@NS86=P#%D*Pk7=~tcqQw9Gfkao4`7EAT7FUMed#lvw))dA zJc|pg>!YlI>NA)t?<2yWa2wssi_lxrOTTUf)IiGcggt&OJxgCT_~TZ|N3Vttg7s6J z8q#LFVVD^Sw7mZ_7^*Stu50wuzP))vmF~HtT}}b>iRx4`8|hEJXOKbdSq!G}GKSsbHly znrMH()}px%RG z;R?uk_73qvg&sFXwFwr6!{>nC@5wFidteGa(*`7B<*f0|JRK3=7DcsT9ebSqHC~7L zykUveId&4%96N^JX{O_r(?6yFnfA+IYdWlg-&q-ErcEeSIJ?%~Ag;{Lv1g&?*j#?= z@bm0b;@y$YH=RMPziJB8=Abp)9ecn#5oxXI;OQ%&rrMJ&18xSmvIA@F1LF5O=2fU! zP;>1WTD$(<0+aj0ej1~sKY~ey_xswfWJjx%+T9Y(3s&vSJ9Z^XQ!TqYTTNZ6~+vIf{&=yY|OBRWa*ee z)~c1|WX!My!df2?90V1{43%iBVf^Em;V^`~lteOSI5tuEKgJA8Nc%HFI%YV<)7F^b z8qZ>Re$<*89Y4cwt~0H15Fs>hQC6~Z?j~zAkCn;du5!Zn>>4=5nlTO-XCpRYf7GpZ z7!vmF@mu)23HR^(cCBRj6n=Bp!M&9bEQ2NoU2?k;IV?lC z%@R*w=Pubf4#c?`%I(xgT~68Kt3XW1P+s=2cJ`1cTCJ)Na10Y|a{nqW64di%TH zT+^4tu0^mIeY-U`851042Xi0*Zk|xpPK|(iOG?j}HX(dom)5Nf(s~VZUn{L!leE6` zv?g;{PFAjona*6>fXZLv@LbdZu}#eNxKml^3$y8J%7U8wo=|h`!UVV@z^1p^J`)5~ zyB&!b`5ll)W2i@vpNf2rJpq$RDt;FR)H{$5fEpN3Ke?4(V6L*dl2co)gqm;7s3rkN z3D{?v1;6c>AoOye@$n14V^s zWF^pGW$5Cq?h;V%s%9b%?`R}lOwjzl+tKJs;_!|p6Q`rAFJ+jb>Rr{V=#9d1_Kv3W zno3{qs`^8P`Txzigr^9UjIOS6jGsCL6-HOvf!UM5{J-ZxqpJ@cr_t3fP*ku+S0ez8 z7BG2Nwc1)rQ17aCgqmfkJPfjqhUb65V_VP@>`rKUX-{{AJT}M;$YW0m96Tn_LV4`c zzVtc4W1k@o9+R{ifl^O(JMx&s!DE?tWggoby(Og{D_=YH*k(|{W0ioGm3VAF$H-%+ zKn0KW26HMQuH3-0D36VHTmz3igtyd-{*%X2dHuJ0Gp%}SS}F;shi!TViy?_m@&xoz z&ljP>-y+*v3r{wT7n8^nz1e(@=w9-4?4*X>HCvR1X5HC#$x61R7liKY57av%w(a8e z?v>NkolR~p@2ER_5h`?N0(J#R7trP&0o9%TggEKWw(Z4ab&z*KUfP|lyN;vOom~ZL za6m0^E9%bnMjpDeAyA<^6R=vqK9@R9-I=6Gch=$sEXR6{sXNP${^f%4p+6g$%6DPeK`Kf+G%3pAD2EQM#yhn9=%p8oR|4wM zwj~pX5%B7P?p5_@>vvEw)uZ)-N_sS*mXTeMp+~z8S?JLuYI`OwNPDz-i0IK^mG)?Y z^(8bt|0PdKJ=%{TLywk98@NM&v_~6<@&ht(@iI4{>vR2el~-M#CqO0Fr$7Uhp^NSQ z^!glwI9#8SP9|`D9&(?=x;`Zi*Jmb9ug`a7IO)-9&>M;6tVcU|J*BT6?EkD; zJT}d74Ll}q9sFNBmdb<2p2vj$g)VI&DX9L^E^UdYpe`-HVFF|Xx`Dd1-*bye<%|CG zONh?JZ<{~7VwYApE9=slHSE$*?}*r%#XmhDud7S@6kDN7Yq3$*r2*^;kSqC1uO4-2 z-4Lf;S|7T!Aa9PL(k|`lfbuR4)Zl=+$&*u;_89WerTqexbZG#q1?+Q#C#*ry0mRK&bl-tOOQ0UhR+1RUl^gCgum`5P?ne6y1KL%K!hIc+Ekp3&^~e9FhY~s zQ$e+Kg!a2blKzYw97e#UYdt8Jsz0mfs4}WQI}$4G&p<6BuOLHzb_=qkKSR`E80Am< zvo{g3y#-di{tQ@OLeuldds6DpR^KG+&k|_^UkH$1o#TK!AOjaKbOX9N4?`aMvs;7= zSEoQDl%b1Xeki><7a>miGo+IVT%GH=SXZaSNq?4#)2p-DrpiJXq17N9gXOG0y9io_7U!DhDotteYTe>>CLM8p#)_`^qFd3os zcaTPCmqE?4R35I*d!(qp(4Y0~$Kp0Z(@X#GROGQ)Zb1Fn-vS4Z38cMuO)t%HO@{t# z^UYI_NqPo>QXe*1VtGvB;IT}+GLM~w-jY&}4L~n=>zxbkVwgFN=9;~IGEZM>yk=AS&4%2zf*`;r7yeQ9^L>K4kZy0aai!rvmhNDtI= zb4vkUGLRV;MEl{kiPIW(XD{00C$NzJM2=ZOo-DI}B6;v!dO>*h`5H(I_VL&g$+OST zp442^r@c2no<2{)r*qGE&9vW^>98&TA7y6(=Tr6n|9j^1`Is?=5km-#s3=7uLmMGf zim0?$Q`r(FQL?5~%2I@sDJ4tUO_mJWkP;Q4O)Kr%wf~>5_qq2oW19N@{-4L=-19!? z{W|aSzVCC+`<{D0=bkIA%0ZoHR2tO%P}~@|2m5zHT`wo=@;C2`5ceVhaefrfQ85Oq z-ewE++ny{F-WXraU5QlKp3-NjT3>E=qgAY#WTIZ=cB=rK2M|})ZHa(#yO+R@Zj9k? z@ceP`3%lJp9%VPipmuvyDXUIy_Xqgi?KZ9-x!r{T170jF)$KK_O>S4*(Cyakh2@Ox z-R?M8;f*nzW^jtQnm1K8a=W+CX3Ghj%ekh7-0m%>L~eIl#17r=eQ=_Aq>63vMGL## zIR*)DjL~2S0h2yp(&ctn1MqJ5hz3XtZ;U~8Mpux&!8*bVZ;WA$*9k^$cOfkHiY2SC z+f_Yd2&INsT&6~m+pTbFKpKSuHs8aw3-+PEMpBROoga0cs~;=yvZjklgNKs5LI) zd$+qo1@-f8w;Ch59--9OK~{?__NfVw+iiJT(qaNNL*-Iqhv7TC#cqP_FI3_-AYier zCPx+%+gmKjF3w_&DA&2L#imluTkKgVZ?Wcp1{Si|PQ%Dzzd(75T?pnXLaf7?rlKrX zwXtLsvDg5tC2#m|7K`}Bx!rkGAWs>&-G)|y+-_$m|J&j=%I$uhGKorN5Qf3pfKIOy z{;^^?rWt2uEEn9{{aLsR_A79Yt}cq@#TG0Oy1rwI%s5}6_&nI|m{_koHIQ82^*K6w zxxN`t{w7+$4FGW$SF99Ju5T;s(DlXp;M6>S6#T-juY40j$@N_h>YzuJuT>&rd^q<4J+1-GHl=oYI~lU(1$u>C+5cLaff{GiFvKo;8%X*eb&yFnC z2hh+$7CQ-!zgS!Z9E{HE0^z1Y{<(XFy>L-ElwGPh&*=% zna=>oa~DFrYg9|9wB}T{$!!2Tzo4$gMe6zvb2(_z<*uiI@DB*KM(ogC&$F`r0fCDB<%lY~38_7v`eKkz)uBSkGcYOv!c)UQN zyIyM;x$F0!yz^-VrXwNNVWsIH=abo5vgCYfL51#m5}?Nf3}>q68c6QCH`E#z@x8mg zM+Nos?)pqd*hPd=V~@(0A!M;fO@L;qKML$ECQvRaml|6WpW`i7p-p5laW5ut);F6R zSxjtiu_U`Vi(NvwRfR3qgmT_uS3-G<^#HWJki~`>MizS*%3EvznBjz2hyA95EVj{b zMJ%=sYsriLo5do2aqfCE70AOz?s~6PAb0&2l>cpUxpLQUrtG7VeM3`%W7@`pzL@RB z7ys$5Pq>9wp9w4Ahi+|G=++K~|F~ZayEnn@3P;u&UJpobB-0WHzezNr$}AF5Z)9gAkL5Cc`C+WO&gIc^J%h7=yq>n z_5s^{nsU!Zbq=}Rm#t#Wk}IB{bh`lC0K`>|LIv-32f>cqF8uDEKNo&sxBHq$ncD?5 z)T8QJb#lA4FVK0)?cMd|6}nwG``{FDHJ#hZ z6rtN)ON0DE;9RaVE#!80gYa&5Z^RDW?l)G}yImD4O}C(EVYeHD|;m8AGzJEi|n~9S%)R>Ajfw^n8OaMoX$99c~4(CtR-;w*Lv%zcF| z_M+9VS@LI4q1y#?sF20t9V3e!2Nk+qFvAJ44qZ(}S?qkn6|vZ>SWDjU-z*mKi*vhW z88Y&ek=wo6Dv;Z~3(EhtxR2y^ze`aipA#0s`VgHC{=@C^m(+LKhwA#2gWy)&&c?n5N*phUAV~V)HYQu1UK-`#=yI)o#$^D($NtTlP>jvd#odUK2 z$haR#Ro?wgh8?=U%iwqS{3qcTc7NMEO78DzP(wZHM5|8jFStb2$^GR(dG{yaJOR6X zZMDh$i5t4VQ*Y&xYHUB`hr;siPn-jAiVXQxDjT`KQ?S_}0_SqAX(9J_^reye>lCp= z_tywc^pHTs?(;qShz9d|3U8Bu(cMgd2J?3K zelVBs4AKu~fpVqL=-!*7!Q2YAAI#$JATXF$n;Z>hvHf69vZKK~UV=mS_ZH=qnVso*UJk7sZEaDgE{-#sGDnjJ`hFAr1e>0)%x5za^)2;rC z0)uTQxqNtA{g!z*+m?A>km0wMTW}k$2D}@>tU+7LrCnvG236lEZ7kQ>C~Yh^6pG&# z_q{ey$%$>?JU$%7(lPQ|;4!PbTEuHc+qve%8unxjtaixO(z(_n@Lj6*%viszQG>SY z5;dsU=MiYo=aB0EXB68vXp$W@s94buXh*q8YOClu*$puL5SR?*8}t%D^8^YTbg^M{ z8?gf_oB@F8ONezi*;G`6{%klkXqm25=~tR;!~i=8QG?cm6|S9wTH_+V9|G-EP`~B2 z;59xH=R|NVVr*keIW2hYVG^|9b(m3F@H$!LmfI7SPT+^COzYU2Rz^=)<{DB@Sk@ZV z66$qdMqB(vzfUp3#9B-fZMzlb&Lk76yUXmXLx&RXpnwV zyyxs77z>OiI@G^|>|sIrsg}K+?3He5RqjBMcMx`ZL*7x^N=Bl)jJyHrbf|n+zPbmM z9SdlVD@}cDR!XLT%iL$xJi9*Zv?07hPTF(SWhK463Xb86*QBqb48Ij_0P;(78WjlX zPq6NEJQn?EVC|&Am>3o_n3lSPxxjrx#*Z?wseI3OPChePQWNib=ZD z{9m6~s!6eccZPND%{a9QgdFlpY-0l`0{isCp=w6@ZLB?ax5jcQzj6$ZD}bE@ z=Q&aj0pICVS{n#1cNyi`X%pEW64*_z^LBNCR%G5wMR~3f)Lf|5?vrwCwHE@@cq{T} z((4T4z`O;u!rq+|=5>O7mt8NCd+P2BxEbOIlfS>bBcy9=tFQCpy{hg#vb)GH`b zW-5)JUO$5W3CqI|LV0+b!te`$-%W;>K0FD(A%w4SkuvMubn>3G8h4yrsK!=^NQ3pB zsr5UoioK-jH&Cjvu!tkUT>y8bn-8}Z=a@@RFLMkcUM6Fq6$4_Ff zh4NSM@?feFVjT{e4!VL*H=M5E&p?G&@Ueg<2^ikPziuE+Vn2ae<08Jlf|uwmUG>}K za#3LygVZ~Otd>p=VXOPH8AdzT5>-HNb%VN*(c1NAjJL3i)!a>IwXuxb$jEncW6L@7 z%}C5@<-Wq+>s%$IvAHkD-vIG9DO7_#x>gI>l0Yts*-8z+yT-W><`kB4v|-79)tZN_aH@B=}u)k_MPEsEVlW(%>?8%r1%RMCSVjZ4H&)PlB65od&hiJ=e+?8A_1~rSVDM zlCjSHVaJa+u5?2=O6sI>Kw?0iG3H}-oXU~+Az>|J{|FDRduLM78g*|o#hqr<-Ibdjo zb@slwZvjDl3kc9104>lJtNcp~tN^u&Kntw1cg=ZOAL~m@!7twpJC6SnfQ>?6R)1H2 zkCc9#%&$zfX;77}S0`#20&}JQjCHOT>2{4W~R%ru}S#( zSQli^$3WxZ^9Ff3oc_kqRY06L7uyEodcdIsC z0DMV(k45aEVi$J-I2Pt4U)C>mSc6!90Vp#dx&Ukdv`V1x0&or-e*x$P65EyWA{mb<+bnb%RrxrD3%uAep2k7T|J zaA(Uj{|+Tjt3X{woZE&b>- zGFIC~JIYQQLhmBi@M_2VP~#D4c{aBJ;#4$Ywy(|-x2-kT3nt(_$MVfS80Ge|OyV8g z3+#hq@0ovT1n-$2G=i79|1g5>XG*parfj}zNzTiNNxPfr?emFVNLl9wkh#?L@L>9m z>Pn-YY=QC-L}+o1eqr(y_-E<2wZMwgvGp#1LvH#(QQgX-9!HNoE<*d45H z2)KQn?*`2FHw4<&BYmOM-K<_6p2?R&QZA*;b;)vetDLEHkoGzE(hFQ??v$6%g7cqd zf6syO;7)kAzaQOL6}eL`8CO*uf$7$HV31zY?vdA$vB>qtB8y%BpSexVu_8c;T!b@PUcR3_m4bsqVahfl-PsJ8Gwi6)3zF<>!cAo1& z;&yQS6?l)z-A;NX>3sJ`BVVpQ`RP+!-*?q!+r!K@${fTOTfQIz6Xd&>n)0S2+I1Ia zs{0T)8-9_Qtm+#Q=iR6gKLKj5&IGLPY8H_011Ha|hI-mCY9V2!OWwUGO8Tgqgi$+O z4aLvj(^tdbwF&7n849|me+aI>r%$q?d;0f$LCWGz5&gP@HntR=#N=b9B{P ziJ6ux{3oT>nTfH}y^(#78ywkJ1?rQJee=w|EnyWlZhI?qxN%izpbAZKuh5p>xXK)_ z%t1(!ac@FWWZ#i6bH$wM&Z1*6uftpmttuIJFO)a#IDi`fM#gP;^FNJyFPPmD78-Y~ zVPxE8P)Xyq#IP3>Z`>p+GVV{lpbG1u$-aI(Y?#2)D0KatQ0Sq_EdOcP2~PP>xy>Bs z`i+qvwl9Ou^id$?VC_aj(wZt688-S`Po-U(taS(A^t1Jv~PRq ziHJtuKpaEQJ5z$1L*hZD5Ag0Es$)te^MW&th;MR-FvUUm>)kVCT?cx-TLU!<%72`t z(l{m+oQ`|cjREMNu)YMF3l+~*zcxxwSS#G3-l8Y0G^)M|cr+!otErn!qb?=mED-*a zWLH742M|pENwQl>`%jWhG|oUc1)n4H-=r?d=^RanK1a3B-e;T(mip7)rvd0+W72$}kgFj!d!r z*FzV=-YxbEoSD8JDwaJUK*~OtpA*str>wNH&yv{$zzX+hMj>`K_to>s=xk+IxR-z( zq};D6do#@KWDK!#dBBpa+ORf~G1bbcR(&l($;?W>=lBnaiz#_OIYt- zp=l42>GN7z-X8Me!_1aj+$Y*g@3X`}?A-k>?mWrA3~}W@iX3{lmmZr*+g^H~CH!7` zX|K2^-l6s=oxyx#LUM1t{kFH>FodyC>OMUn?K7C2+ih>X*U8=F>XZ8;6@`22eV$N_ z$KNWW>9Z3jqDvEk`;rT$J~DALtURahPCN*u9;Y4n9zpHSNJ6yVf$u3}GE(%=YKgmt zj-b<;O?Vwv11jlFSn6iMu?xymMldZ{VFc5HjYgE^wGt$+ciTy(-ljVFk5(T^Xd2H& z+{c6}WRF8!j-In zFC%et;THM|K$=cmC$$XTDqk{EID>uY;9QJOJdA`I1eH8dwmwXr&7F2Oe#6G_!$x=M z#7>JJL~Q%|!2!xPj4A73R5L;qIecp8E>wZz%u$nN}#?fso#ltGT{E({Y4A!=c7O zX%=x4GHwAfMzG28b#68pOWlJe+WeV5tR2A36k>e*MymG0W*}mz3Dcw9d?(5(ISQ~&v}CYI$E@Fbdg7cEK&PK0v+nTz-H z_~oPW43nABGw8xifzh9jox%(grPMS`Fr##a(nFM%45s-^8PRpCi(iHwn_~J}-fh&P zrn)sq-x|{-_+c{gZL_=QP-MH#ZELIx<+ZTcER^i^?nlz^7+f<*!Gnpwr?|zR zMUxz5R#Ij($;ld}^UZfRQ+6}V`eIIXHLZe0WHtoArct5jW$p~9Z2;Q?)FkH$(wz*` z2kJhkWll55&%yMTuyB&|jA1m%c@4_iUjGV>#t;qG+wpxlQ@vUyb>;{eP2QFEIrhyZ}BNEcFs9gtzoI*@47; z((J6n?FjTX`4qUfNzNVUxXJB9w+~=%bpu}qdyWYm2ru70l=c$>f=Q@4bBALn++Ouum1t%H^hv{?RLtvf5B%Pq?}b;pGZNkhN_u>Vqs+#_^$F?y5>K0$ zgJj+fV6_dDB>Qj1F(czK6QVJ)(uDZBc2d_U)zz4Jiw4OSgK3a_ZZI1o54aiJai<)l znyfGNtIb7!4r!ieRH{C;Lyel4@ z2K1P(qYGQ~M`$=<`LxJaxuP@|y6NZ}ewFL1*xa7-xt;vH?wi<9zRJ}T*^B+8@cUQ? zGGdcwjSR21KgLw!4iMYiap*CXZ~#5RKVA2Sf4UwB*9>0>yBERj$A|1cg&sLx4dB1s zwS#k6f-dgs*l}N}Bh+ocNCS{(-|lK;6#q5`J&e+~yGE-xuOu^eKBM$*mHs9+#7dXs zj`A@>{sns@)Jk^|7ghle0jyjW9r}>rL0zE)lDyqC%z1aydnY6B``7}Lm&$4FGI_tl zPQ6=tsRfURqD)n)8$y}-D)U2Zua&ug%$MQwokFNQ*N|iLdkn9CyJvvc9^LMz*l&i{ zAKjOVzryJ&x4*(KC3Ag=s`{qwICy#XncIhjqBr=D1Xs{3@2L28us;zN!)!^r%=ow7 za8z6@rpf+8Ub`ssj_Rq(tnRQ6c}1K;Q&rU)e#dKz=5R-{NPxY%3HzybEpqq%TeU|P z`o`7~>cDTr+Eeb9`Ne?DzPszo#ReJs>9BO@*P&d-2jsv)`Qex z1&TWCkH8K|-utmDO`baJT9c;^`;}4Zuo?H64(hPkoL<=}l=&cbua!}UT?oH$hdu6o z!>hx#0AE}94`T}ruMT^<_`bu=hrgEK-VQr#UwFR5juI-_VSA{<9vvTr^(PY^g!vN! zvkv}C>mMB#iw+y4Jxs^h;?@j8z^qswKi0QiquE)&%Ej2$4S3ppp&ob&NL;|)WqXM7Lkdxn78ZampD zJV-r5pr~h@g66v=@2S|$CQm&hb&_gU&&V-KJ)<)eI;dxKq0B**nHPJ~%BW}j0>5z2 zxRLe%ubwdqeA)xx=f_?$yn4o6;`^TQ4*dND_gL67^5FTNu|+7gY36j=^w-1^tXO># zpAREH{d*qa5Q^RY|JQ_AbP8_Ps5;#K|F^_cdPt2an$fo*+h59lw?`D0lDo-uCwCAf z!$%ZV1;loZ87!St%9zJ~dK|FqGucDznf!N~a$oJKYXQSv$!ch;zgJ%)* z2jTFQNU!)i(|U2S%;n0pUqhKe1Vnh(-VXuZ9``~~&2`q#_o<&h9m@rJ(PWlt!mIuR zGj2lBYQ|QM37Y(<=)SN_*jb-RE`ai{Tc#ndI>9{?cGmcVc9sj=uDML$nF$@cEG0OS z%!yPs?8m6W=#K!uR4Dybn~7N?{rZvh`3d-)8D|PS}`ZqQd=>{ zbk{GK6K1Kf=NHV0eE@c}V9s;Y_r&4hY;wWeBb4FiAFlrb^KU|O!Q9($ z{jE`w72O(%WxoaP`lr|goAdvk@CDfqpwXW{6}5q8*W9Y^Pl#nUsDvJ}0XM9lCpLZ@ z1Se0`t%|l?PyZs3@-r)7$jEooYH~3^c8>J^GO>&Dd2StN*qa>jStc5+-*=x-9V3A?v^rf9fRz92BJXOve_WUY$5n^r=`#DS&;oRPHr+vS0dp zeDXv~<@}w^N_$+<2gXpH%IDnt6g;jd@%>xRrCS@M>ES`zSEc0{rfU@36Kg-29f7B? zi6nK@!j#AU5;aIP+kM4ly-b(Br@-4!qK>Vuq#kKbwA^PYyv+?pj6_XEOgKR94F|~h z5q^Nog1v&^?hOaXw>mZa$0|hrNx7~5JHAs*Z0U#8tljXE^U!iT5H~Hh3sjyPMrJl_ z{(6L>DRntm26`W=TxIKkJc8vM^(+@`S>1tw3aqCIn`5yOg@{e=Je$6x z&o^H{@d*TXZhRnmFSXC_iqFab*d3{7h0`aTBOssOUF!4+XAjcncLiGGB7pw{Z*ME8 z+tFc2A5Tbrg7mJP#*6 zoQ!faBytc`9jFy<51wvK2&&wV$NfK$ah8D&KwSd0#zlbFTnb~vetfG@UtPW=9z4j- z$5UDQ4YJ~|yeLRG%Z$-|9hZX&<878P$^pdbYb_n|;kI(J%y2$9Pp4PG8ZpA-X9|C6}oZ|0R z7E6tG@mxR$2xp>3AL^O@Z)&tF7$#=Sc99xdT>FX{#}1(Hx^!8`y=q3PNn@5*zb<;yZY^khP!9H#UwGwp$RQStJT7J8l=xkT|Pw6W2ziD_aTmAv6!2Aci`M>zXP70%Y zpv*5IXAqfRbrfsuLt< z0qWO7r9T?2hl;9*b#SJi)uUV1 zI$My*0OELTuC;XZwVi`PwRW9B`LFGCfnW4%JL~LgI~vH5kC6f_iT%Nf$;S+*nD;UB zOh9oyX02h=$zO*m=;Ub+nU8thgvrNvpgOsLg?vo5kj46#eD}@S{=9R*u)Ow4mx4kk zW6O`M+8R)09+Q$;P)(s$Cchiho+7rOvkx-X+1G>oH-lCtzZuk95H0A`H-px>g6{<_ za-(1^OMWY8x_~U`+;x_4uh>!F3F6--IJ7SGP1IiSjiAjc!Do4-uf7qq!n8aE>Mf{( zZv^cF7kwir<8hsdOnEd^!8d|}>1Lpc2rIm9(;V@?d?Uz#C z7g8cSH!z)K=dMP{&U2v(?3_c9|6%9$f)sD(-mnVnJW9Y~?K~Y$aduv!67A-izOwTh zrsY5Fyd7L*=kE<8J16E8w(}t{bi@$|`@h=Ri;|rs>VMl=UkBDNdj@vy?=Ivz@4vlN ziQ=p=husp&e;ruBW&n$Rd#O8l1>as8CB$LhUb@;OMBiS@6+is;(rV*G7laMsgx_8g zr_i^T;NZ_6jY&OS3&bw;?Ip4Q?OITFrj_-}W51@HzZNuq;;?IhK;iP(`{4M?!D1-C zJXWW!U#vq}Gm$O_?n&XaJk~A;1>aukjj-Y`2aIEQetGP16fgL#a97a&(T~-!{`*Up z0xJIdOMSxPX;Ub-#l5ZDtcT(UnLBQu!R`WZ=cDPUbl&NAPahow(Haph0I0Co&3m2s z^ds?seKiGd=5L#3$H#Kpw41V9UHaGXb1kFYT-}ronVu4SM>rvooTpC@=jju|dHSQU z^9XKwI8Pr%NqO|eTobBHz*r|K@tCF!xI_5j(2Yb5v`R6V@t@)vC|& z_Cw+TNu3?9SVHHrk<6cctuOPOLA+bU&y8Pf{GDW;^pxf=dNvWUlOHP0;V+UgYbK~ zYVsZ^KX8Tlk`U{##njfo%~%i(+!{~_(>zXHyX>rjf!o4Bn#WxOwaC?m=Lha;74m1I zEr6d#)n+i=WAS6`O!N=$Yr^E)cNaf`-&_1S@pFtnG0s20;xBi<&{iAJ?kxiDWQy^R zIEUNtg;KEuR7a>4F6Y<+VCwNWhl|PZpw>_V$^K(HGT-JzMyb9h8HAI`xDKZO4*b!u zro&3@>Kfq~yr;k0s*EAF3^7M`29}++G^l48^ zwmiK!l^%f;dU|oZrxzy&4vjv(q|}qA7u$P!vD=FsdHVBVMYH}hVD|Q9!xtf7`VR9W zl5+f;0DSLy3{HY@um zF1eMPo1v-QO=Q06uI0!J1XmK#OuX3vWW5_hvilOKcJL&9_*+G2-WwO6gm&&cF@!f_hHQ7q+TzO4glx=^j1zG}?ES2FYA zuXejm^6Yi0i?}cQ>|@ZAp%xhQ#q+%MO0#V~&niVS1X}05hGNpp z5lg~e=Ej8J&I0qD)n}8~g@&EYahW?aL=6?H8N-PR!EvSgrme4dI;b))o>ETwq29%6=NX17{ z{2Vg8*)D?ef*L{j;+1k$yesKh6fgA4cWRCgk(2|3+p6Y_ci$XqK>FtR)F?GaspU~~ zs7QB;{2!V_(D8!m)3?Pp#}e4SIRxG<@P9UkP`vQ)Kbk|R+MxcA%^`Su!T)!23{-Wa*8z z?W9M9<Lievk(---tBy|7(V-JOQfbVoF?H}`I zl*h%cWO{}2`2Sf)sH3zZ^KB~fdno*EdTI}aQUFgOX#S|za%-#*MlXcsK>0lsggKg! zd@Z+|fppU=xSwPSl=e9O?-zHA)u>6P2WpZjAfri>%rYReg*<$cd8-io{2mI;06jzC z0`*2YoxsQ2_@uYht34EsUMV%Thr-!Veh-DHNOBJa57!3LdUK z6g*seCI}#lK+k0bD!PY)T2mGq3Xn&~1Io*4YRH`?QH@*rSyihi zZvy5<67_u9gVdw~`6d-;6(E}QJd>s-^*}YLfMJs^0l8hsVw=?O+OQnV0k2!WNz<+k zU6A3=_8HSnXDeXYIfc&FgY*LfdwtDd?_wfdWzuPHYavB{g8e3*W&`ZZK|bMq`0V}Zh( zn~JN2(alW`l)t(87R;}NSckc$gQlx}4X39PBcbply17||i+GMuMYo@ zp#x|%)0PcqgX%6+Yj?;{1zR?V)lroc+Ok2;@hb906PWa@t{6GT`H1w+@k1!T!A$oM z7&*ru4Rg426y|0^(mAF+CqWuXg8Pvq&`^|QBt2Ns`YPkc12vKa3`f${Ag2pi>_|c! z)(FM|TBUQo%(bp0ah=FK%Iej&1RagiwgmS=`E3bQWIIJ{8c_Tu5rP~Lr1)(Kf+uz9 z*Cr7HRw7mWwgmOz_-zTcQ~L(nmf${0v{8w6Cz!t4nxN`B*-6_IoB`!Gi4d+kxM+KV z!G@8+?}GBKOPEn$k_La$Kr*=C{!zC;^8jH+M~#Ia!P<4kKk9xO)Di;Cg8QH$yeKt^ zMCs=@iO2`Ekx=X=5#PbsOkGUMc2gzBQV`DcTypQ=+pYfPlZe`$>@ykR9mvNgOYwT46$w8n9O>Ja|X8rn;uD~#RL#S`&ixIe#_ z#Pg<<_LBGw%I_s1AaB^(bCOh65?!zWA@TzNi6>eMXZCcxU_7oBF%MK@+GyGgxG2GU>A2;8V565 z%;=fhQ;7AKrEg5D3@$zuxQetFD7-8kvq2bLmRdsj%aSlh6Zrm(Sx=XxA%;s{mi#j} zU6KYOteDFZ--0X*UKqVhfY^3B$ z_d%M^Oqvc?-e)#ZsW%fbatwO)Gh350ozu5OKPb zxD@0;ArHS;9*t1@tuS*mp2auo2(+*_MGLD`rkDY>!b}l?Fa?eP7E5MB6CldZI7jR3 z7MNWt9xZce#`z*5{LmJ=Htgik_AISyxC2%jSjpk}v#Fp*;>W&ZMy8Ww(rJ4O6b{b| z;rQV>5XukF%3zKo#5%ldEvw-<#c&#)PeIWdnl*L>q)||0cPER#Ppu(7RuX? zEjzXb!A^ADEi*iuXl-UVK<2$x$GcE-h4x-)CW_1_Fx-5X*k+P=y`AFWQqK8__pS+o zZ(-!S$@HtL57So`BK_&a$0mIdnPoQXOy@wI4z<$0^DbaB0mmU+do_F3xAcCoy2C26 zSF-^8yep^&W|Xhz^kX7daHrLy{=Wmty8;1o0n-1!uMxQd4~)jaYTKQ$Il!)j$Q5L7 zky_muA{0|n2Yx7%2mU+`w~QWS0MIo*hyC) zmLET2^_8L(Q8&X1oXUWvw!x?-iL3*1OkINpt1 z1?9)jvtTw7VjXIl_8LDE4Oe9Rv|{XNm=rsHBBmcdPf*_f{IIwO`5GFS$eU+X2(ZPQ zX>V|~e$3sa%_Jrzf*GjsC&BN8Vi)RJ{wh5wq5MZ&k5d9SIgwJ!=mvqCl1TORseyYS zk>TlvfqO7 z2pLQ3=u$2%dA`5YJz)fo?Ux$CUJ&byU@wR*MwDIZb{dhj)O~0~C0;e9Rer0@(suVP zS+U8JM&`SV+wsl?m34>b9!mVCx?F!UW0S99iEWDbJ9c30de?e zy>iGgsZ#Gvq^3QC)ai-T<0Mrojzy|Jj~P(;PAUpm8z3s?TlG@Y10z*e+uswP0Q`v{ zXQO{6UP6RMylNZ&C^v5ejNxnAo2=;|)C#L90{xpYBt6c|RBSNJ1dx(hCmdXbSNoyZW)|7ZHQab|um)d6` zWQo*%I8m3e;G3=zB77%l3gy)naJyIgxGk=jx@opGF0dswoj z`=PwGBT(^bFLx`kS3d;ZN^r9h51QI9lKGg4s8Wg56d^lR{|f7`fn)~%3hSSN=Yjfv z25yX?;XeZ(!_jYr)gxsqOW|1zan%vWP0U{5R7vTOm#ie2@sCQ5h@fF5zl4==5gLim z$LYy=1UzIr^KAE%iDz5wR&rk(aZ~rA0%>E+EX?S))Xnz{Q~VuDOKEvbL@sq-cyTLS zIZpl9kYj4^71C z_z~^(aT43m`M=8lzxVo(4BPADz%!by7250LPHNE`SINCT=8}=`TC_l8l;A#5dwsN} zJX@QQ`7-Q9E}Lw2izEG+!L`?i;5mX%aSxxMJ3H+br_A=sjQ0Ad`npaw-~DwC>+oUr z7IUi0vtiw*eqW1Ps8OH5ULTiGgWrPT zdD#9vpSPhxWGhe|ge;jDnM8h>ME)HjoA8njsIEe0B%TCWc(0FR-!OUF>tig4=|ZI@ zUNU*w>!XSIey@)W@HWWy#qRatjag|SV+Y))&!HPd%bvteUnl>oF%R48<1z5by*^YZ zx!1=LYg2-30(*V*L7=zE3&6ciD!z%1?Dc_eTVWrz*T;qM{9Yf85WtfZ?e+153HhuH z3!GKd?|X43{7RnhD|i>4uiy`%LaXNjds@15O8k`6rOjIrbQBc2)JIT9PNA5+KAxv= zd)0GQqArL$rH|75Ke9-|O*ZQh4K?UJvc{(H#p9B(T@VbQ7b!J}v{`_xeb( z|Mq)*+yKXqk+CMk*Hr-lqf}S4*T+K!(;#`)U^Ye`a61;WsP#>%`GeqR&L1+|oHp(3 z7gT1yQSvqW?bfYNQ2BYM_v#p67p>6CSBp;M!$Wd(0O z+WWuP#Qio|(YsUEL@zBd)X+72@4ZiaZcjbbYU3BB_O*BU+U(Lmvo|GgFe$f@vDoc; zgR8}mut4Xn?z`7W-(n@!0q`%k--v!2knj4$Uqij6_HsK9&6c`R4Kzt^GaI1Z^BWFu zw}5@)o$3pC8kyqz_x#>K;!3CY`~*A*u+V#c0_i=!{ealVa)~^6KI!If%K^%7JxigN z3CVZ-?t$gI;WjA!{5yX80DVhv1L7l4!@uK~zFT0up9gJF6QLHlNdVTnuSstu?Y9R|!BynbRl1*|g4#I37u5CuD(JTd5OBMI(M~5G zr0oF&iU#EbU=I^2zv%8UdD^$8;oit_S3qI4$z0F!K?-jw6L%X&VWYcnnXo)bRfECyT_>g{d(O za~j+>1dQg}>In-?4fTZApd=E_cZ2+d;D&Ni zdW}@$%D+bXwbiTFNFz}4HBt}KYor3LaS@=+#p&j| z#dTefy^h-lQe_6k;#8UEc9VI@`#P;xp~ge4G+;A;+XcLa71jc+O@h9GQkzO%dte6z zyD8QwDX+!{k-WB0UfvXdWtSC_Hz*030i~X-6~&KBKSG%SvB4%!*O83^tT4WK`JV5u zF`rvucAiW}n^Ab;3!Y%Juzm61X^MY*nmk!mIQH1#cq8K5TrRjZgtx)0cc+m(juL1p zA!5`O=>wvpw_sk0FR+gC@5a0IU5P? zCu5!4Ysc3(@@XZGw;Wb%z5AKGd&moabU%!=-nGR*kCMIKT?)0usH>rVFlr!F)sN#C z_I9ZC?jDX!N&78wYjG0O)h0)z%*Wb(i`>qzc``=_nPgNcsLe+GJ%klRP_*cekf%|4 ziAtBFF=~RU^hs2*nNcd)8!FsfSBfuj-=aZ#40jD-GR!}zxNKu}D0foWp)!n!GaV>* zJ=1~ODFeaYN7w@XB(N6{4tocM5nOhnLB-O)SK)plU-c*VxRgm0eum&ajRylj-1lz+ zj!O}%kbni!;GkPV;qM7e5U?1;kN+m%pc4xLe7TS_eVa0$sp22#^*XQH5x@c{sL4>w zd$jM#ZucWM6|U@%AZS2%5>A60c4KhvLY94za|*#_l-T2{kn#85ue#F2Tm$yHA5IN| zqv!8D6TaK)_VT@@qZjy8sdNBc5tGr7dX5azE`)x^HRv4#iP+%3VnNzqGCIU><(MYy zJMJ>$1wY4wcili}wrSPxV2iYh4T9i3_cNb-N}JV~L+PeUSEvP9le^saTuqS;IK1!b zp2BVKU@mL#yQd(xbwIZdTn$QmS0V^T@f*6&olLUK`2i>M_sI9%bzPY=jtzq2K6Gm! zKjd^9x({7x9*OR36$CBIzwahMcjw=V?Dt)V?rc_aE6b5SaF0OtxJ*(y3vYhLb)3oz9%4vf^K5~PVbNWuhG_#!1 z$~mJaO_+$~Sk4UPoP5?p${A=mbCpwX7{ehE>u)*v%BkPtJLUAYoL$Ok(CvV7x?9f2 z$~m<(^MypLv*rA*oQ9KsQcinv-gmWr4uVcU&^3a;j-*!w&-dd^dUr|{j#+83;9{on z(XW09b~I?n2)b!-ui(O9#8Fsu=IQj3Sp7~2h#fo&;jz)Qs*62A&vdcMr|S4xV;zrT zX|#*~oD~G8o)WuiB#A`Tb8a|>u2S{Bz@mxwSTyNzizaWdXv()1J&-}iNK}2Wp+!?W zSTyYhiypeqqUldsG-J6%GvBf3;S@SdqUx+;Eqdf)iypnfqTIVIdVGOJb2eM_#HSX` zO+8lS=GU?4>Gl>ay3wK~6D?Zyv_;F`vS`IYi&kbFr*e66; zy+vyWS@hf#i`Ff-C|{i`QFZ+v7HvGbwo)&gVbP0SEqZB`MK3>Y(WVzH+Wd}1TmH1@ zm80vZ+}7q6y?V7puMM|o+f<8QUun_yT^8;5*`ha&JRt~5R84nhT3pIqVR42VZgCYS zeM(fV=46}_RkNMUQle^2CxeuzdVE-}c37^Cm5Xg{Mu$kv=h|}g!xgHdSheQ4brqen z(4rQ37PZ`H(YftU60h}@7PYz7qPBx9I{%PCE{IvGT^WlmtZY&He2Y5Fv#8^%hV1mV zMVEYJ(WPHo)Ool;F2Bp7E2da<(bda|(mJ;bg6a*= ziZKMPfMmr>^_<3}QnyyaKhA!o9*hU@8ZLG;C+<>*&m((Q4yPaM&Yv+ZcF)xu6WNUi z;r0^QIooiuiR>m{D5`PoSNPLJjq9=-De5=QqW(`dbiy!a>zVrpY^2o0}@>^g0 zpfB))ujnVM=$Ni0vk`qvw-cHu>e0xeo)=kk^|coD8e!2j(=5978H=ua$)er|Eb5ca zg&}dw^~YN@;6jTA4zy^{6pLrx>T983m_c9RYcEEf;2`HmZ=Yk`wymMb98JTZ> zPoW?v_e*~O<$md_zMJda;o4rTx>qlTrM&@AHnYVH{@>4o=<%`^D)ENsZxzEdx+~j_KoTRHl zff~s|LFIYZ^5P}HDxXddf<0!|AU0vR&Tg;fhUI#W*YUpFl=I_c9iKW`In%EaeZNYS zf39qdOKYQ_kehWyW-M@7pQOivl&qOC<^NiSSyR?Ca!RHm-rEGfu( zl++z5S+^&|j0fc(;|1e*R-cp8P^ZgtxT>r>pXU;vRgve;@vPpLF>}j$>`ErkS?@7B z$jbdjUnEDVv=GUW-Z_1Zk_HkYEy2xWfzl2oShBGe@*E;U5G z3gW%PQ4#b`{_4+~n9`0K_m@M&FTi5-%ut~6f~s9;kgT{{$5hBUSFP7IR|i?CVKSxa zBdC{^9wy_}dS5d%pznEbTGb`kJF8rnEL-&t#&%Z4FqvKL2KJxIsvIVpRXw{o+-hNR zRP{S()~xI>$-U?Gl2t28r&J$ELub{F((&qhXydFCqjXyJm#}Zv$x*s&^~=ORB}!*k zA0~N?qI9#W-_r}Sa>DeIsyEX&vQ7_^=T(19+_S=D+*RF8!)CR2&wHy>9Zm~pbqtd! zRga*lvpR>#c-2+(g{&*XWKgZgz=2xsxGA(~kHOajS%bo4N;TFWW(^BdY1MAH85<1` zlVz)2ee;b$)?~LkEUHzASr3LuCa|?SeKG}4T0v($AJ9}ur^1B?2# zB`P`XHTvgp9M;ipHP8P_b#eRTjRJDY6UvnTj+A$oWh#pfvR!|=VX4tgFlX0PO4kLK zlf-8BA}>g-QyR>GwV#a#-jPZD{U)XKl$WP0KZD&Kl{5IlNhSrQ55rBZ+=3!)Plx0}(Vp_WK$C=oR}i$k;tn|F-s-L6 zakDw5Zs2^6y+`MsIPR?TxIQF~JNs;lnoT)QsdLhwRMg@~i&~y)QLFYAoqN4St?#g? z%~KY&&9~^hokX!tPg6(SztRmpI+>keU=xX3> zWE@Wj!NuzZ3_@bySr~e#tUv6Rk&_2`ir^08=8lpLG))$TOWqRSRq)a3<>y6&^6n_D1A_Zk-U=wwmP!HVk4U1-tEFIe>12NwPO3sH$W z*)DUT;`>}(i`Tg}7QYb7HU5jSsTOaFb+`P@vEdePiA}e7YixzZuf|@r__f$47QY_* z!{Y6+N_2n{b#}xWTD(8j-r@tX-WGoz8)fnDvFR575nFBXpRv6b$KtxXCmD~Aq!21-XY^7LYY>p(4x?E=tnZkQLSfWo)0^-1BYljbQPYU z&~&K$OHBA&9SYP>7Gk=&n^~80&B$t(%nm!a&6TA2VRNP5|CCAIJHWAA;w}tOZt=Iu zY528{@v6$XfTs*D_V`HAFW^~StZ{~pqw5LN`ZksQy`$)nXyszFhU&QcLmj97rQ=EM zb-d^e9Vgu`X}#YQo%X(t`=xa3R1Dx^*IzBVl?G#X zflICx7zy}Z6&Umf#eIPq?$#H0X#FDY;ZaymCfUJpZkRabocjxtyXW9+NpeHmAMal0 zNqG6G9hsrAhh7kTkwj!l=}3vb?i8j4rbL|cE=34Wu^1;*+jYEw)9!FB^H$dsXr?GT z1n>sHYiGPm|G`ta*{ayxD4r;vOp!gB@bs`En%Na9lKLgA6M9|6B(#n@n~7tcAjRhL z>E*$7k^>FTb(rSp?l@(OvID$dc(irm#V7v&?_78%bn7%Q7{PTpQwL<$<&jwI%96T! zaw7oz)0mZa58@xWQz)Vn%)ARxlza6&{`u}2U+^a7W~71JH1pDYf-UDn3hS zw;sM#tXeY1|7`qO^xzZED)$cj4W`kBfe6Zi#&hB2=VulaNQ#QU$4O5=lSoA#l^j`?N|7B zM0`CE%2bveux^J&L2%-UI&Jqv1hSJf>z?R7xe3SH#ceo@CwOq8n>HHWZM+qW@xE^o z8qX{k0=~Nkz%*C3LLoqb8I#D&9$ZY(r3rTfCK&sW)zva*wSK^ThP+8 zN?PyfEx}2Y=#`glqNm0su1)$2Oz1c(vF|P9abDZ^@${&YBX2H3IrBAqw(p9|p(iMvlKZEE0 zmCp0x&j;}TBfhpwzdpe((`)vw0>U1Ye^Ify7ztppe*W-oG)9qZIzPjWSmN(oBO;5M=ch+#t2 z>;uX>X@7&^UCMDTTTuS9kq&MWhdIT<|I0v;E`}_%o@~<0*H%yINe_kf>$?o4YgQej*Fygyh!0s{UyN>|S#ZC!i`Fh$h z_-%6PD;4;zANtrPqmWwOOHHd>ywuw6y(umzd%X>;(*;tmkXtTrDoSPAAskMtY1*>R zS()35EmPoU4lnGTO&!;c4Q#&0`nnZT<|q>$5pFx15Ii@j`XqI@hyLd+9V6ocwc22cL|corc0etrexEo}m}!v2F*gUnnejxQ0fRv%uB1WFNK0I* zC?lS8VT@G#Ohxf{Cq=HrW0X6qsT#gPo3}Xov)9nS8k{H6xzvZxO$i#DFB@gM>qWP_ zYA0Xb5OXevX9#8XDdioNfX(#jN)g3n1nz`tuy zXDX_-J9q&-2Ar$Sp&p@(N)@MpGw*qrQjS`$0^a;fRjmn7<8xJYl{SqL8@Q9MIO}4I zyH5aBY5)g4?F-K8Y`MKOO(``bncLNJd#_Ti3K%wRRd4=N&)G`4#i>nt0SQ|66R=X1 zl#fa;$?S|qjYwvP$yyorawFBKMwqOf@iOP$=$J5BH{--%Bx|`t zNKC0&KjX_>lE=BfEZH#QUU6%OXOxrih0dsMm^>q+)^#LLcI7#-l$y;lULQxYfh%LD z-!kI`92y@tI>D0XW^C(7vZ0IP3R7yf&S>{EpCQa~S(a>*(d1%G*W6V%Q5R&~i=S(B zo_o5Uz@0LtD0zOE?3^(}$qT~dRT-Dk294T<$?h4s;$G-}qD4|__R1K|`yh?lhdTGp zSk|11E_PL{-u^*qE!1k*Ty2^9?f4)#t@f9cJ2!sj{r(ZO{V(76E%nTbck`^QaStcD zby`lRE)DSf$FSvmJm<2;#BGnItL9uTcH1XN=X4P_s5$8p=u5&*QS)Ky%jsGP4*%H& z=gGtMB5}To#e&ps2+ir1K~8E9k$uH%uEOWU$B9&dI&SNU@J93XMY^$;gLubY$Mwx3 z|1w{KqRJWS zxmv>Fi$>gjI+^`mJFRT-inVjh%7dJ*eSRIcA77d?!8!vkUV^eG3hEn~N@AKDOwH1{ z;QD%83M*W^X^MdBxSd?Sa;~+`?vxK9=@p7u@qQ6b021-{twhHi#$T>fBuR1Mj8(A2(5uBqG2THB5AqC z!?bj$K+6bm%^4v2c!Uw1&A$EPxCe#NOax!0%4);x3H?m9VVthSkBhBqPEmSL{stKv%wyXFKCnGwoVJj#edG|F;Aai!PszPXaTTw)9*Sj5vjdljQ z{1&RjELz8P>IC2}@4&Ps&W1j^pLE~yA|8wu2kkE2aii98rLhn_ofdr0( zChgFB?;Qk@CS4Q}kzxT66j2eoC;}oPg1unl0lSD@5xd~;y6%}RAw19T^SHje%o{Ag22NDb}O7(m!GJ{2Hx2a zoONdiJt=Ma8nE~2Y0ha*$kTN2V(=+Do%u%K6g?|+mdn~fIKe$rE1b7y5>K;{E^;@9 z+f7{kQGhf0g4{(qOT#Mxe8s)$oa&dyKoW*iO;UwF3UCr&$UqmFxC}s3{ZW87rGW*n z{MKTS*5t5sV&!q(pdoDCZ>0E%=shMU69%GJ_rFX9@s(sUIA4jMPh|CSpcMRe7S2+A zpHlF9c5um`qRkZifu~ScIfF_rcxDNzNsiM5+1Nbna5p<*N~GW)dpFy8JAYHA;>qKu zM+*LPXB#V*!SEv_caaxL!*WE^JqlVj znpeRT{M{D52SGSl=xH&cCK+91&S+3YQ|gRQX^an`2#~J27zr0FE!W~&Lmw%|$kt*9?IV_LIob69=HpYVNlnYMi_BaA zt%7t#INtF{Coh}{+)YMI8W|~ASt?){qk+52uR{=|y6lfyA45hGQAV7IE{26{I&;*S zW4-U7H!UR3Mt9n*635%g*I``Ita3d%r=z-?Rbj0pKaYO6Sxq*wnkWy9*#SYom5Q!@1L}o!YHRwv*beL-s1Q zJD+T4wfiaAgxbyS0B1k7ds}5Vhp4ej(1kS{s?K(E;2f@YTag{Db~linsK!c>outlO zvQyOVs+ZuLrxqp`fb%*9HlSB)c7qyQPv=UqEu3Qe$8yM9Z2sCvqz7lHM$5J1ZAZ^a z=qbx}Fn1skx0i4lYq?IYNU_?O2!$2lrLqUdSLmB|oi5_p34F)u}9?k&sVw<-u|{rk#h`0eohW6v=? zRvaLEAsh+BI5OyoL*y8QlY#gKLuSakw<0~`H|AjCKNIjTfWmOt?5cSSP2MuyLKOkj z4Is5tQAXYaOEV=K!d1TLzl7a6%8itpy=XY%7zTBcPsA8660*B2f-g>F*fVH3d{+@N z<y&3WOfV?zsS3WuPBQBA#A-Q5I_H0{~wW(nQ91lEi*Mo+DLc z(PWTAp2yW%&Vh&_yrp#bL==(cqB~C>@#AbzfTSv@IwUn^uyQ90W?Za4v^MbXah?@T z72fpC19kPSn?Q{PadlqGJhkGLOdlT6ftuq_LhpxjqQ4@^iRj%3mQ80)bcg56LIXpm z+`l)sG>S5dxg1ot>`VWAMVRGMOa zs{aH@$6*!UKQ<6fhz(JCHK$1v9L0Un)~CMkWb%CnQp{J~iRf^!*>pCZpy_^l;N&8> zoVK`}bKf)jZ$>xOjK$CK{WrLTw$SE>rwEx%F#u_iZM2lk7klBTtvM=^*%)^MEpp9K zvCQ7I(#{-}$UI3a?afi?%to}*!5o#%#DCC4T68o=8JV|_#8D@6R59}goYyU`VlFVg z&s@c$&gQ6E=BE2_)YTkS&+NvubT>yeGPj_qwCG`uYG%HJY_;fRj%sDziEDO?f##@o zW@lUqTMRNsbuw?K&7tO~Zst|AIour8%iKhpBh69$%r|Irv^i>!xq&t(nWKi89cXj1 zIckK_e!;#tp36K5KP%9ImU-njNVd;}w%~VoOHP!ZAS6%4W%P<_dQq9#3C<>ZCFzaE zeZ@)+*^}2?59duO4dMJ6&mgW?t-hCFvcnZ?)tLro(~b=Zd<&pyi)wJ{10X(b*9SnC zMUs!*fyb{Ij3;XkyPlSfUx3<@(|cPsn~hFJq~%8s;GnrZ=r#-oEzJYsmJ65Spp{Y5 zzC<&kA>V<=R;`9@K=bDJ6Pb%(tkrM=XiHNqT4BgwacYBiEkBh0u;&2hft zR4`%2Gdq5m3FZi4DuZe@@ppzP)@tVE%h9O)Ftb=(ewb^_QA#AaF{oCvYk(`2bT^zQ zopErZ%(2(;z!EsLTQYr9HJLjBSOIe*u#qBn2(cAEL#xRIwD(q*nENz-3Sw%snoOmC zS#yJPG~_>%{^iYG7e5y9_$zk8{}+dsWZ~B%K^k;GZ+3$a0Pk-3CaBd#E=yJTiHT`S zEKA(D^cn?2jU8=g{P4t!U~y;o7k62#!Y@%`EJxiT(0e!+TlF_j*Z6&k2J-GCJ}U`v zlzB|RuU5=ml>e*>!C%Huw$&gLoFBBDPYjb4Ss?y&gx|U75a#?`b&@OFxRF+KOo&&hd0O48x5PE+tx2E@)xrE$mETA_&729pnh6MVTT@l;!^O1K z9=)UG_cZ4N)#RaD0K8_Zo1fY!fh_)#3IDOC5cutlxv}T{mtRbaKn$~m;1haRSWOnO z^wV5@bH}%U`qIw4xvM6RqNiw8-Q11w-JprHs{F78{%^DG3f~o;pV+E05`93c_c^c> zzD3Lr{K)cnNS_e!{bB&1tSZy`BYJ;0JFnKZNcJVyBf(qYojLY8Tqa7JXYP^AnNx6- z#)rgwoSeJ@RCXB#AHE9@wi-P(@bXk#?i=m-jzMeg#54E3bmC0R{GdC4eW&#(nmG<; z8yzs`e+ugFN%-ePOJr~#xV5|DGkfi>sOE@K>$55tiF$T}b4>dtt zqanAj!82EVQfY1~){GV`!c(8X%QPqxX?*SCWE(a{r;A8mOt>}MgBF){EfF5^E)j>TZ0mX>KX zDaYcNV~T?xcbPY`!{h|+XBu{JgX!902& ztNKax=9ghX383B7$cA>t5q>LXk~K_na7s7qB*G8JOkuE_L6Ps>2BE9ztN1xtAez2d zpDqo;U)lpZ$nuw}()?x|ysiB*zd19xLbVix_p_!*_z{{hpmkPNmKH+xDrtiGb(u-9 zK90_b&Pn1Zt~$JR6qhv>$5D42hd?^$bf+J};BG`~bog#*p|{A$jIlT>D-4Ts(oLR$ zN^qxf6qwA>sXOB>IypLZuRcyEN2l)0ujpKjk-R&b^A3_1KaZJWa~jf_$b#=&el(Zd zm(F?T;2gCQt-gr6$~}YRWj;g8tDD2get;8P-CN92H1lW`9IfGq#K}yFjJh26^F`cs z?t3s*c#jDoE#ok7QA3l3mTP+BpebKYVQ8`kL$!tPN^=qLm4D>288_ml-@B!|!Wj*{iQ5(&Y z#O=mHjMm&ko%`YFaro~JYiE&i_vONqpuGYA|M;4@lx4^oT&3L)E5N)qh%*5G_8}zf z1`Mp+6KjfEy#$J*5;hZgXkKC$soEMPkm-Dh)}<-y0LNSCJto6yPh~`V1}3nbxA;!7Jk+2Hj?Z+ z8U9WvTd8V7kkp&1!n=j^#H}Y=v@83dzTt;A6`}ofY2lnhw~Z9XWyqD2VE#Fe(+X3# zlGG#BQSQCTGki%aT*I)L%mp=!L=5f^HX(n`G0oVO*5En^tePArndsr%0rCq>x-u2A zxz12E&2pSvGaA}Rsg3U2m9-Z{eqIS}k~A7dsGEOqkM%;zca21jN_=wI} z;?6^s%Gk|B&iM#?lo)p&vO>~}5-E?go8+?1m=<6ox=B74B5iy`bEKIbFZ)YFyG2Hz zpI|rY%1C0GT5XV}<;vCYz6*aRLv=3HHP~!R^Ep#MrDY#WW{XTrCj0=vM}0Ul!Sp}( z%IMrkWTLjnqVjhN$VWup19u`|YZ(Eb$jVRf{l{0#32Vb05J}C!Og3ybLDOLt-;Jo% zBO*1Sh7FuTv=^uuQx?|1nA7xHHT z;y02!rhXGS115rw%;s`_D3?i&Tnr^MP@@GYX+1aVV9X-l$HU1uDwP-<&Ch$jL{+rFh*Iu2T`Qm=zJ z7EqcqOLcHsV;rE=84!^+e*T$5d==7^nd|L*H_~)YQU*kMpYniV&dDK>$Q><^z2*>e z2$&AArv6ieJI?t5y+6A*=?`&OV8H@cJE=&nT9^xQabO``l93d5zOx_$O`R4tLA*Dx zV1eaM4FKB+JO}Ym*us$eVPUm%4riZQ_ypotVG9b}?u^9fQ!Pjw3p!x4xk#5;JaM-= z3s4-I$O;gvg@G!#bh-~ZC9bqUYl!W`Kmq3B38&?98^v&lii& zXZK@gB$6UY$Vw?};eJS4n8m(xW@4-(HGwqAi{VGA2R1nt*9DV`Mx-mvnC_gU~lZ*x-jYo!}VhJs3o~TN(Yk?1cKHPr&}&OCe^u zV=u8|sy86MN5I%mmtzG0)OWvLgtpIe_zB`aK49XoRBN}D8;Q&&RjMt%!o?OU5PSeI zWI9d|w>_@DYN|PawuCe;&(!+6P<12RcR{JCAs|NkrjTR>Cb-|CX4K3=h}ZjO0Q`*M zsXN1cs++a272*S73kuA2e;Q{k9EA8vV8JAGrOU5NGznio`^h)pCA7~JM02NmiPsMm z%0(l<7Vi7gMX7t;EvO&uJL-aH5m2_bQfjBW`)*711Ti$AY;UF1v+nGXmYM@%c|h5I zs0*%6?u#z3yc**c5IY0P_M%E1b!T|}<6#gV<)t*EUT&2?;U2loTKxlTLDZ3V4X9wR z(QQIh7d@&S9DM`Izxa6QS@-$Nt-yF{13F(OF%=IvubA05+R* zWo=Vb>|nI~WE*iUU|9jG7Hz33dMsM|28;FvHthmvo$SUdM_l!=g-gXY!__Db zw{_BXoTr-V*1!@0s#du}DirOW^ftO@wK@^l>;To_xur%W{c^3PZUu2~UMgnMDX3j{ zc2c2BZQRcRdpAJ+xV^!a@;4`yTW0wm!NxlI*~-i3sT&QsJ!v4u>zd1I2-W67A;T4< zfu2ojm1zSFM1bl4EfC5_`L~mPb1Z)o*!wTUYeH@LYoITZHr{9hy?_8827$Bz>&`Y! z<$p`Mzo+GYA$yfy1_7ThCxr`i#Q;OIUljqe{#zg~Cm985dA&|=u+uKY=gUc(0^{o2 zNLC`i_6r3HZo_PuT~%OM4IAhH0-U%|Ak7YUUh?`B7>GVWv-3LwT-^BrW#E^F7id_4 zM{clzY9c_}3k3>pByIApEwJ9}Gln3*%nJq5KBkh)8i*FXvcPTCOeC({0{EdIK+r^k zlB*#d-gBJfwBzryc`EPKj`j7Z|z@o$gFw zk0G861DuKF7D(QOE>sg8!6l#+Hk)X_w7hYH^2L+Ordqx(*zADkDV7HXsgvoaLeST$c>_p0y_|(;RGmpRdT8M7CjE^ zbb$H^@Di+izvL+xPpIi4=v*(wc79oSsTiO999oW|je+F`XgI;0(Kq9Z&hIdmR&*$^ zX#pBeu%gS8+h9Dd=t^K)12kWPm0z2j+Q;&H!M=V09tl=-d-5B&*Sv-tr|_`C=&p8d&}^ zuyrrMBf*N6Px%u)sphRcuzmp=PVmhsNO0|xiMYTkIs@3!01YQt(X5na#VooR*i!+T zFTu)pNO^Cy<=+JR=>>QsSke9||M5=!zkwC$;g>}?!6R^s;*Lw%j4d2sFz_03oHt}I1>v@!ND^n8_1*JAw6EizteA&k4Bz&K1NG1s1F87RXZ zo*#&-&>|2ca(5P(iUns)pl|<2Ak1NEfizt7r6i$l(y{p;{@bgOUb%Fq&;9a${Od35 z@IRzTHk*1*bO0jAW+Tdpnmu1qC8B0O+Y=KintczB3{qOxTG-pZ25a4rwa{~9WjwWP zvK~S7Wg6$}wQj(vUOnHz)v0yUM^%Zs`o64nBZiqI_o5qa-NKbq5dXxMN~>aC?dcV! zqCr|oAqW>?GX&lW@gY>}Hs$buhL)u|w0hK+W5?H7d|=o*_dz^Zc!hdObbY?Xx3$rbUpM*!t-x^{!Dm*J_teq8f zd^?nJR@poR2jfFigg6^PrwGx3Pd|;xrsz8VuT64Fh?=A$l69pqdE@_!NzRKHuO83;9P=xiHmEF}#!#YnSD;liPzObFEcb1;hf2boQ0 z$^m?1-DdiOsM6x=`{6tB_*MUbRwC9K5tJy5)Jus%*gGXA0&z=lR1__-q&co|C29`G zS}!GDzXoSeqO6i(htG#MKSiv*D`Q(B+)6+9;zF;_<`HtRq|qtQKjv`NM!0L z6kkgGHMh?IL_ZEA;%NMh7PPPieM_XouFGj*FUG$3r>5j}l)rMvL!Xw4^E-Zu^%ix? zp#rAW91D-H)uSA1Br-i3|K42>Hn~7WNRKeScApM|^M@JmZC4HhlK78|EYfq%R=B_8 zxy+M(24g_oxfO-!iyxK!@OTwlYW<-|P>kWx!KwJJoWRj9fk-RnT5)LzdrzYM(RQ#| z8%g||6+*{v zKt<~(1lI#tOQ#Jh(0 zC(}@GECKli+FxOv57XnH_C{T@lB76lybLyz5`^E5rV;6@YhkLo=KGSRFV!IL8qr zdF@iTA0AEbN9o)T?A4$ zmExWhSttk3BGrqd(uaNzzYMaojG>j`{~`&zqRDhhY>Sw}gY_&^nl#{lm>6pMJ`{>l zx07O0J!#$wPkNHlypXi;9#49c()A%}`BFr#27jf*HXUQ4%@Ebbx^1!-zSs~8d9iNq z=}9#xF(^Kb;<~W1D|!pol8fR2t8}DBSM2L40FrmG?m9pBI@$YJgO5bNL0i;x%p%K1 zWY}f{Fk4!FS7{9;Eq*QIDKZ=7BM-a@3#zMz7i_$cMdQ=UjQCTn6Ixp}z1k z7Qb5L1K9ckTPi6t-a}9JZ+WP*elKZzLe3V9LQkziDAHFSz{F=)2StmL7HGII^Fo{x ztp&eq<77vkh-T5lID>sow1?-N6Xhi|Ct4fT(xU)^l#Xv%hGJ@YcM1~o7@e3}^?qR- zJigu>jK2a0Pu^(`>h;0FE_-mMCJvstTNUjz;`g&9wEVms{P%1#A=c&KV4peA?j*jQ zZK7rWR`B2dphDUu#dolGYPk)!NAZJ?n7~~dkxOAUms;E71SM4?n5U$QRi; zcXimKv)C62YCRI~=4|SV0!=B6$z||+pVzML4(l>1m(XwIAY6muJskG&PG%8zWTy-q z_tD9ePG&K8;tyfqH>4~+P)gOZK*|_gd$IZD@Xta3gQPxkt5H;g zST_vh;zW)QmN(j3pgqK{VPH`S07GO#JqwJ3I5iB6y#v5danKWK6gNU#69yv70SuFm zidx_yh);xp9Vq~YOT&9C@H)hI!$5638H$gPQ)mks#g7nw3j_D<05DSeCM-~FEWWbD z=9k0L4FE>Vf#MdZ2k{CYFc%uU^}@5F_&E6$Wuo_By+91~DKu?P)QL}$_9%8u$SjES z!@!q3(Wc5z?JaN{#LWR<<^jcL%KSK*)Kd`lQq-#*Iz`TAiqDf>sCIb=!pFX7Zi&ql zpZHRlFx_^)e}YIF=b6Yu-6VZI>M{^D0*XBeGQ&wl@imf@glSvsQsW@HlF|+~kF5<- z+oQ&Tm>E!NtEP+^F+CFBC>3sxM0g31)gZP66id_VkjvkSXz!AgdA5l506Ux)MdCPp zCB9XPZn7Eu48#wl%*eoY?wW<|(!G$SQpV%<37e(#T5L1=pe(L#Gg=!&Gg2m_VQQ!R znPY7wKnxCS>4n$YdQ6@~qt`;44Pt3vD@;8nlhOUW%A(y2Vn<+0FY&g}j!466Y@r7=`w|8(buHv9E<)8EEye3C<|uHtp#KGw`8Knmj_!v;F(OXKKK?74?!lE#|vnt zwIi?r0jjC6MbxPS(2wNV^%k88Y&lU=DPgovF`y@<`)xMCTY&A%i=vj5`bGv0w$xz| zM+3^1rc&R_EjTUotos4PzX7GuevYJj2G7WTufI#1h_8~ddCi9T4x_)xmv>pKZGiO+ zP(L#s|MPa_=&Y>85JXck9qf{T*CuXFcR)WB7pHPBi{1t7L85sYoKjI|&wNY02;!}P zvYA(^fYTNiRgLyr5dQ>}pG;(a4m!~IMa}}8_G@|BEHw$QL$H}>(ZA^9mNL${REP~A zw4oTPJ3g57u(Hl0JAm~CGWk4=x7D#QTh4j66WFET)(5OMGR4xR2GSJ2%o$hH=HgLc zdx@G7u~glLpvpUiP?tJPc^|~*`KV(^emv9Z1wpB^a6~b(vDq|pfa8^%F&HsC$Z{wL zu~Gn-8NBhzPE+(s3bcfHWdK+URh?BC=)GxSFvL*=OiyhsRC7j7v%qx_mj}QYIfWB6 zUdzcrhGi3k2Yk_d`#46r&H_=}8G^c${ZL;$k4Tqa>Vl}_%x;4*ABtQ~g7}`478)vi z&@upZo!VP0kc@&$&V|3pAU~gnA^@0}DcELq0gn;tx!@ zz9zMqI)Jzn(Xj}VO=ng&CbsRg$Ka8+tumfJphrpD;W=I%ZF;-^Az_tNHE}9B1Nof< zJIrr}yn~@m+i$xhzUKUR7=V9%bcd0?*isL{H*|iCgWpWwKlUor;QUw)VXZHocYc)Wj8cXuJF(kM z>V2Ay?WPIu{P-PXi^hcB!S3S#+HW9peq4`^Q7!!epdb{J$P1hw%^!rRav$CP!@hQogbH7$^sTG3Q_=g0Q?pjLobmzOei!$zf*q^&C_ z${&3H3pAU~gnA^@BPUuCiAhA?rbuT_^n~Z^!B&d%W57(b7ixLVj}-XEu%%KCogW!E ztm*s5hQS$}A6MY0y)W8I(^k)f`3|Il|8kg!jscrZXHImYrkw395nVvyOy^#)G&w4TCNT#Cymr}Yw^ccu6} zZCXDW1E|z9=o-`d3roM$<8%)YHrrDCC^v1e@T@Ggx)$7Z9R5XPDSmaER@Z4kci$}d z*LQO0PSD-J$%Q*zK5m4AVbZiU<{BUp>5NNrPi(0(c;o@2q}xusDMB`7GQ^n#uC)MX z?4^y9FR#G-1OlreZU}%%^299wCd(6DFtG=KBacJfO~S-cTFTxFV!GT?k?LDePWY-e zHvF^W_3eP%EkjBXIRiO@TL)vnAeCew3M1`)>0HH&Cml$Y0Apd{^T!osfE|@(19A6) zEI5(_q@9m>#0Roy0sf9$6FeO1I1(n$m1Hhcb6lEj^K2}Ix-x7-iBF_8o&*^i+o3)j zw((*?*!V(T^liKh^{ucCB~D2Kw;smEcTj%`+qfK$57NGqnJc|4r_RQ6BW$*4D~S?6 z$=FnkpENIZp*AMr<>j%)u<^T8NcU`XgW4x-Ly5m7qpfFSI@D_e8<>}hn~t=9h10^` z)mSz_jcI|8m&q6)r@2ny%izVcR-O!r33SkD$xfFoUhHpEaDo#dIFXZk}NEK^1eUUL!(eL{q@!c{; zrfDhBhX$E^x^fz#JIAYIEoJX4xd}t$w3^XtCUMYP22ACEW50pMefByaS48{VjHf3! zjatAiXyJ9fYA+k+GtIR7+%359ZbtyQ1IT?o7TZZ9 z>2mxo7+LD{X=wh9R-OlOn3UI{a#~i}3TN&jQ-1Op#IJobu%N(d=WR3$)`+FrR6rZFSxlirZ*f7zuGgV8H_S zIsJ;`D-#0CAl?+Vz|S<(9&{EbTMOGEJ{-27z{Ae9c)F$*jzD}fY=KW4(;jyg!B0nm z-@x&67~nI@v|Y|Cr6Upkm9P|^kJs+l{F2ON*Y>P)OLGgNK85Nl}y?hXVFEr zR(1nBlov(i@{60abI$Q%mih$5cLBvKyGNZ&nhr{{USI*Tj?E@sPhD%Pr2FOsYpW)R zD*}q?GKm{wqCK5-3Ku2m4rF+MaXwFsJ3JrhJs7F0;udQLY&MYVd<===v#%@)HGkdZE>TDo`KV`FRpq9rL4qopdb+iLB8($d=M17buzTS~QcpHH*4=7YE) zpRIRra;MFYK2{k^OQMkFUJ#E4wrn1i+7zvTVNZh8DX~T4hIv_je%wevuBV*bT`Gl;CgT>Qt8~@tyf@3 zCA}u%>xB6P-JWZZzubkd0K^#DP3A~Bw;wZ{%oU<@`}0wW{`E-i0OmgVP&fDvY%XtqMU^C zPoVZia|y*^7Cg;8`*;&HS*EPyV%*hXGwFc zASMJ9qsBSKQGad?nfVYVS0Y`q48%>O#xZ^Xyh!CXk{aD{yG39-#D{$|9*`xE!cZLo zMS=AK^Q2&T-+>sH`*vpL;N!ga5aM5+k`hwnug*qRR)`1 z4!n})Zjs_$Y!}iH$IZh4ucW#6Npuh%46+=0Kj!YE!j=@tKc_bIUlV(Va+VsQm)M zwsy7C*g3hwHpLkrmIjnwNY$9R=H`xYKElvS+x=!>JMy9^2wvrL$2xzsv(zCFZwFN9 zDxbUDsfUDVwR{KSkASj;sa`-WG{e&K7=R1 zs=wI?x*9nF?Q386jBu7!+6P&sZEx-%IjP(UxEx-mVJwJ!>8~0`)vV97X>1PO! zJKYvwJs0Fr`av8T20pnDlVqND>fdKyzs`ZUC=3i7g@o*L)}j#j-cU9|yeA)Uz`6bb z3+#jVvJdEFGdyznvIpk>z36<27WX5DyN-Mb_;`>52k#WF_R=h-gYoB^DLV{EvU=$b(QG^VP`pVw7W!$N}Fw_AQ)jg74xt zn{6c#{e;dfaOOmf$ItX&n_D8cYis<(nR7GV3Q$Eelu}%hGX9mr+1#aau7LZL!xzJ* z34ZPThVVs&-zCJqMgH*)tUb0=+Tf=fDtzZie|V1eh1f#Kkrn7)8182Wf3`3e;`ITb zNjD?t_%BW^oa-xTaVv<218NP;q-%c>|J8XJH)@q2$`S0|4JbQPi5)`xZ)Z00pwy2b z{=P6J?t`E-#*&DlEH;}X8(9JOa9Imn4)KaGz}_)l*uA+C3I^t-7sP=CHen}NuaVtj zyr{byj{(yNOb^E4+-0uR zhSDrh`%*=Xs@aMzf_H}4F95Knl_j!)8ka_cpB2EVptz64}qx zRD)QTz}49KHQLI(wGL)95V$fBQC}?Ygw|RjIv7f}@nDh@(JAzxGso09JG-pjXk1tj z{wOrNAUvJ^g7Eg>e=i8nrMC4uN;)Fh+$U$^o}yhNb>56TwR`qQn8k~9rr~S@F4a8b z4tPJp@|99+Pz?HqaUVj5_D?3XkLV-yeeDaQoul?29!NWC%m#uCqq!XnFN1yWtbrzb z{7Ye*y(Kj2t#@w^{&)8H`L$+`4wU03h4AEKI1MLXK5s4Zn(se6xV(n_4-c+V=D(x< z9mzO{Ep-Kgh2Bxea4Ag3X8dC}Lk-?h*M!j27teb~{Ynn*zhP0jffz{Y4w{ZJUH&`j z$4g>)T0%1cED9j~N9YVO@2I7rwR9(dhX`pRFYt~!6@w2s0OFm1Vvh5^qb}YTlcX8x zcc6YDsVVc{QA=fLDM)4-HXD~((NuZws1M-Xk<1bIKIy3t=2K{R?s) zn7<$oThu=y*WnVs1@|4ON**WlWAU8mGe~SAx(*hy>CB1V?KykQDU4Lq?7tZISB0tZ zYNg}cnnSdzdEu%#OxuF_rw``Ap9Jzf4$fdpW%$rb?j#&ugw6QJR=|lsb`nSh9M$nf zTk8W?4Q4_{cY$Chfoy|eodm+HLehRTqdxR50cdapB{JOPw1 z5d2$gsndAm>BH_p>$wBo5?znd#Fl!E)%kQPY1FKl==!KvgjOTaE6SUAY>+foTEMS0 z{f%AgKS2`k8|?eX7Q-rvQv*$wDG=rcqJHUR#aVI_guC*Jd4gXjk3iiM5UY&sH<+N6 z@*0F=zUZHz-vR;4`~u=%pEBo46Fwu;=vCK7e6dRzfEhkvO4nnphj7lsBVPIiOxq<*>onNE9hjICsgafFQ1Ae zJyCWGDu@Is+R=x#NzbwAXv*DoY0VTaBNvPIiDfv&}2F} zg(2ys3Ps@L%!Z`HRq15snRH};1E)5oSD5;WQhACSN%~N#-G&nyTPhR7+eP*NR3rzU zSNTG$0%TA9USu$o@qucqTf_b-b0MtBE5>ReyfISLL{UoQUNDaaToXoN)yg6-KzSoj zTZhz!BA-Gz9jLXDQ_p;f3ds8ak?8F>{jr&>`OW5Cbd|BYC!u$22a{4A#N|E}>&$4( zU^Qum6k3isPo%nl=pRs;7)z~?A-yeiHHd`)#YExZ5!d-kx)XmK4?7#6-X9PwH!T_u zdtOdW0rnh_R{~58nTN+oZ^$D?lza)|JD)A2k+$fA)Iu)A&VdEk{?~Gy$#L0mL z3;ZK*v`5+qtbn*WY=O^)laibk8?A*0AwCwipg^kgS2JtjRfz9|EzClxC6#u1HnEBP z9^#oWz=y|4<(+?~S|Al2UrB7X9MXjkkCUo9e-*V+)PZ<;7~sR>qz2Ax+|z0m6{f~1>$W1V7~20>g2py0-+y<@GM2G2h(?1 zVu-UGy`a1W^|QQ$*KoK}ZPInl*{;C;0P?Sop-FJ1+N2du!$~$7X(;v#Y<^MjDR|Nv z=lDYVETI|1>;R~uOWDS9ZbkV@Pxud|7D}dhe4Vt*`DQDwE3EN3AeLX4I^_J(3oV<} z77#m0Y1=eeE-g8;keXMWu9c8nc@gqk=OOxtJLzNR3Y;by+cyAyBNR%Lfqr&!mf6T+ zn{ZNN3rA*_tWEmId5ZS}Oj08dEl8QO!2cU+dWumR#-1k4#}mVQghbe*;+Srm;t193kAFAZ;YLKHRJNiG^7fnyLq4J?=i zR+E~!pCm#29fFI;(Y7$y>7r-h60AvWvD7+Dyvp_&{h*Ea^%yTgrX`xyHj{32i(GEerNGvohuRovG-;#TAED(TAp6e4Y~QKa z!){|VQaK9boAa=s1I^I42eD;Oq7T%*&E1TIVY6kybRsi+Ef8DN<3I2 znU$7y+rf>GW-7M}%nNxr{1au>c}Vl&?Ltc*Lj5K$;aTcE8rU^bxeYnF8`H|Mg>s)K z+BhCi#om=pIfQEiY!<+JHLoN!x*=unM@wVa!7k2`9zaGC3r<;cb68r6tpNLFG-)Wg zxnQmj%&}cZZVm1XjRl^c2VRo5p6){1L~VarvbwI z9(ld7AOJk@Z?6cmM79k?6LX5mANQc}--%*5jGDs0?#MF*a8O%j1IA#_9r@W>WT%dT z`o;W-Bv7_a2kj{B$i|+vn>2> zcH!61`W2vGQQ^uW4nA4G2)*;A*iz3SZ4zTd7;AMe3KgHM*MZW)SM5+~jBLV_U8k&+ z<5~{gAP@7A(6SJvWflIG-nmT9VciH1abuceTgG0Dq)Z86tuCA@WqCq0W$ zkxieckF=-89c=O6>#NGGIS_ZNIEo^75b04>RxsqhT%tu5Q(T51_@}2e4C9FU-${S& z5NHd2vQ5aXsQsp2GbY*R6IJCI8vI_p-wk=ME)4IN^c$$Z=}pV#&+z!L%0!#B2Dz46 zk6gJ8cRruj!sF1#wp<1$-@Vj&LjORN&%kRv$-sJ_RqHAKmuT8o=#lB?J8)*##?>QQ zXrFT{w2|Y`@f3RATkOcuw>gE5I2R)#eZ*eqWv43LG+*cy=Tf+f%IpF-c+HX9adbDf zRGQ*5S{2?zkNpIE_xnohcIX&l@PTEa<4%#)XlD@R7v)e>m%qwpE!4P#=1cS z{>IM1xYY;v3a-!>&PUxbkCtJ|Ld+y!Qed9Y7W&rN3V?+rS3qp%1Lpl221Cb)k=e{MO|8pxv{S6Vc5Gr+)y8HE8HG zzGlCN9>alU-G){iE!p@KJW5SRkAWpbMkb>IKSL*1vhi#1b~1t8rPzBe?prd4JCNSv zgI`K37+I15T#IeB@YF3MV;{OV-gx9weaWD|hH7YCa*6OE#Kr;suJt;QycE2-DyA ze?osf-8E2EIeRU{+q5g-05{M~jGd*}K3M&Ndxntmgfv#QeiL4EEP;gv`a^$L501qR{r?H}E`%AgZMDiT0 z64kyO`{8ObshLDNRMi#AReVwBHCep>}%DeJv=*{Fn^u;d&s{Q z{Yx2Ju?Ia{)udY^__sFxH9db*&|Rbx#e&X&hBl&H4?yC+#^RzKE;0cJ`~F?N%7XG}ks`{&)e|$S#SDCbp_U%=Z`x>jirfq?5tD5XI{+hN8zMU?zzX|v$&Rj&L<@Stc%d7Rb zkZJ(4s@cLj<{9-;*`cli_aX;s{cq2@NorN81f}DnYW?Deyqs5+Z_qS4?$(4>qqk89jQ{eGod;-VtNAy} z%^^Fx$Zs+p$j)E%&k?mV*te6_E{3*S^0t-m$;@THdmCS3q2CSG z(EU9X_x3d2gEzHU0e3O(Q}hvT>xR6gw=3Y@1``P9>I2(6E8sq^ioXIb!vrhfegpAu zY^k&=F^cA4ioXJG5eUVx83Omfe0J5k&BQelp=GHFtpW8F*zr9AA0xKT&73Kb*Qj@d zclSW|R=|DX4y%ucHZ9P(@-44?-Y>3qES;R_&0wUO z@y^kX%=qp{2W0f~9T=JMzMdnq+K&YzGcqVje`K};5qTrC19aPw*)F()ky*n>F#i)< zDoy1XnOz0nzP=J`2t62?-M9in0*EplyK70c)bReuY}>UGDMer{c6WvWJ2HExHLd{+ z^AyCr1WXG2ky(w!5@BJ<`w&0(0dGiUM`o@1S~F)sL>~>Au_Lo}eXN;s5UcxuXU2}q zZeMQm(*{HrQktJw7n5r{GFv~#Mm842)qyQb*^${qEOo01zZt}x`E1#dS?TUx{y`kb zXUmSvZoJOgIu7DgK3jHVR<5%|SU=)mR}h=64Zq3g$c#7T`F+qvnb<_M8Ny|=5#>bV zbQ)i??@5nyz_NP85KXOT?|_H7sdz59so2j8y=l77uc~Jwqo2mAqktvS&^Fz#p9q>R zrEt?71?yhZolCcEx>Ml}n(mJ{`VCtuP33921s}(wZ)`@1{Rlm1x{o!&D`W(dIv_45 z^{a;Wo9>)6Jb@+91!Au-V4H5mPO$eRfGH4X5ilw6o9@((cpFIzw?N$F174f6O?T@Q zYvySX&-qkvQ}G*mdNuPQ#4mloGh>_Xk}fts|AHutteE`73Lu5BWt;A1+}mlID}ks- zO4IC7w&~VhVPot7qE|j!w&{L$y_bIwbMx7B>(x9zlnkaR%; zy6g(NY*Gdaq1D6D4dQRTCQZ+wF(v;5;KSKMhF|Rr4kc;KzH6#I{)Du zlKvE+Y^JHlcHXEYU%p@$&ZK-ZK-AZ)Qm_<&KLg}Xgp53e$Tq?^Gy~)!_+9Gz$F@R6 zpz8HuyQ9>G(A*dOH-%;uk70eB$lFYL0>ofaJ83$$nkF(tp>9`Hb0Q}QT?1fA0IfHW znE~>^ZZVcN0eF~@Cel2Y&9jO}YDvs8I0)k1fMSl#l|93*;_>EDiM+%}e*pC>NllqQ z1EkwjSSf^H>DX*sYDH6p!R z&-nNl*hy@ultVK?Xm{1z?!$L0Snh# z)`0EYTh@T@@V#XXh9WKAvIe8+?wf_|)ORM*ouIpc!%rgpWeqy~Es?hniBx_D&%dyx zzRx2M7$pNwNu(>XDQzKMMc{-5?6L;Szm&+E1V%%g6afCR2AA}5B2NQwWChgKBupIs zvIYx(!jntc4&@17jWN4;!fKZ_7_ksfgyj{;@1KYG%Nnd~?ZtB%$hiPxVR?%d9F@9V zoX9C;!I8AxIBBuj96nev&Fb?| zNV}{-^G06C$etkNt|2%9E^$sbacpWY4T*MHgVNu5scjY#?Xm`64|XE6HJ`mG+SJ-* z4Vqr!RoC=T$ZZ*jvx>9pWw9YwheE1Y!)aH-3%Sz|=`U-LWJ}1EBM^^aGxejT?42cc zS%XKi_)g_#FlPf!Pb7a?gD2`ck>kjME2Z~h!Ur~MPWx`%>1#6^pi{KjNSrSkpdH{r z44^H@#LucWS8#t>gT*h1jbS$6oBu})c3Fdae!!WaF+2$P`TrV2u&lv5V2=5QG5GbC zHTVvmXMG{o0ajx_;AHm@ENc+khwcxX&Gw%m70Vjbg3>flqX#vtx2!=2D7}5vUN+3! zA1rI|1lm<01dypf=J{Bx7>)SL8tiD}L^!6A4Iu6!<#njM*T%921+FtSB+o$H@0)=I z1y(yd518_jV-P~GblW{0%DuMf|=8kcAxXs5C=|j}g($_e~!hDEJ!xj{H*s1cG z7z>*r-WRrDmo+$)?3h90^AHb*0lTb0%ZL-%$)Uk#5WfxsoN$9>4fddmP{7@f2m07- zHvMG{W_>0R$$(IkqIP>R)*!As9R|b1D@mV@=NZ)+a_0cymDNK&Oe)-v$VkXD^CB_j z>>>kaoV(82T3HQjV_p=M%h?E6*5K85Ewu~83jxI|yGNZ&YTwl6>;#Cf14>U_YpbMt zd%A5&?(`_IxRH0HYvmHbzU?WeuLdqkpwk7eotEd2HEb4Q3a$sqYD5 zXg*u~8WGDHywVrf2^6x-0kJ%=W%H=irszamY8H^%0%B)i%Tjh(gWEAe(^vb4LA>Ep zoJDaT2K{L_i@6H^2FXEZrXzD6*pa!(g$~Lq$=fd>#D4eP2_~|CUr|33Zl0SYQX&!_?<1P?TasA*@Zxp%Yf;!4}R( zA0mAbTPjnf3o59v2LFEn->-eeTjOw*G?&lxf>O4(HT5Wn zy#d9T(aG@B>hzLwJub3?kS%#1#7Cswr)2>Av^qUaCU$ZnV+s5L@!v4O8Bg-~~8+igfSpMDAub zhd~@026zEZzgk+fvA|-8Hw1vW0H-gJ=Ptqnhr1y>L{Xb~j4cJ#$?1OS>!lxVEpB8d z`4WhC0_w96wOK~u+N#v|ApQ)f??coc+5D?5)Z&NnEC8F0QLl$#gU`$Tm2L560qcAo zs#eXa2&Tw<6^?upNv8F*BbnUWU`BIPX4hOMf+pjrnXTHNz>6 zMyIxRfp{UGEnbGxuXFD4&cG8OzRqV$sU^+~Tp!hziz19+%bQ1DhSP6%_SHll*}|%U zXhh1iLt7F`ZF0sgw^U~k{m!#hOeS|hS<5*1&+;vJkCnLokX{4-$E7cygezKk6lo&* zEbL{ozrsb2PU9QwvHoY^eTvS6!e;*`J=(z|iwz{2_W9XY(HrQ}0zdMv35#S`z!ey? z4PVh~o4%$QxS zr7{|RLZbe^i7bKVYF{u<2yCc7WebFzf#|-54j@A+qV1)feX@fSX$DPR!tQlKsgT*< zb2e0(BguH|Q<1JaM@FsU~$ zF48WRzQr7T4-TLM#9lt&y>Z}+i?lLQgCiuGnF3;#Pa&lWl$Wb7wq|aDxXA}RGrDL& zHM#C`+v`3J;vgx_aO^Uciuv9@t(H7e&r%$p3dHBTaC`jf-hC-X!-91Y-A0gD$@l=yBZQf8P8L&&k% zQW=8JVAX$=TnoP&egD`NsIh1IARm^PEE}QT9}wF?pz8TuPMKSdU_kIV4ITjS`h}s} z@t0Hv`U=1=0rU(lRneK-WuCa`Idst}@F{`KBr-Zl)i9BH*U{bD>un4Nzh%rY4Vex?_O1%$x$^@?f3oGB#w0K8trs0pK@R?hQ5ZB$3n z6Iv&U=uQ~THXgyg$1Oa8i}dRECZ-8oiF@NBed*Kz=>nVsMFzezke_8;i;HrRQJ4-2 zBkmhW{}50T8-+cRuIgkd0U;w0Cr~uSUS#>Jm`+R&X$l~I9#m0g)BXd}6T&cG^xu>4 zq%87eVVIak6LUZ;B6SUq5CzZ4A_tmd&L$HicS745=neG0LW;aI3UiTF-vjN1K+li@ zwGjT(nV7e$`f+HVQ`bzQzQ3u0)csWLBFs|$1O8D&5-xzErU0TMrJz&@)D6W@0%j;$ zBt=?d8le_J3lO>IQF>DSb3$u&a)b_4AIl!A!=TJ_qQ|gLs5_xB9B1ZgDsVi#HgFEP8pScern@f45iJcVu0#bbbiD^DgG^1 z{YnlmHj%7*sMLD4&RgiJw_rS0EBsDcyLEm_TkCmt_WCNCe!c^*H25JQr&G**CwM1K zhOacdiLQS$TH3)x*NYI7_fEP1+`&8PML1f4EtRJ7yp!Gt-}`+fwg|fI+A-0!+8BxS zfhaFv_cE!QG`#;#dM>6pj3Dp@cHf2p`%e00Ovt#6VUpfPyTN8t;J=gp_-=`?grqXW z`aa=(cTXGR#~{AVXUo2mmWf{e5yeH=O#ZzX?K|lQrdeAxKr|+m zCtdcP^syEaVf{!~?0WlD&}8yXr_k2KchYM&=o!LNPDHOqxNJ%}(Oc;>zGii z|4|eIw$wjhmd#LwN3f_xMfleB75yF|WnJ-E#Crf9g7^dhlSJE2UvZap5&bkq zUWa(h2fPNR?erb@^i*r+42Zvd%4?^`+@k>aF^!Z&4$5OQ@pxvmZGGmhK!%lS4x%k7 z&9FylJ3Z-E!(1j!^AHdd^4Ze1^}XBdE^BKUh&B0aX*>Pdy{@g7e-O{)v!&rXl@1vF zoEZ<_rK=5awoTe*8a9LAdt+eCAoxDMH}RL*ivaayzJHrc&_sW^X?|YjAI{t z;!#Xif+i1R_Y|QQG_<$uRzJLiYf1eL?A{COI*Q%h52NMR8RAE1zfm`_XV_)8HWYRu z?cpskKSJl=M2`T?rZW*`Zg7F62c21upgu8Z zU4ns{9ki1B?}OITA7BwQY^e+p8no7hU$*ZbyMY70yo1(mPzMIYY7lnxROXhs{hi32 zG&mE$q6Cv@)~7 z095l7yZApydui+t=3&gX$DlO>7HVSquVGFX#GtjJ%)~2hM9~@OU=R1l#jIXaY%v`d zYZN-HHK_;>bo2P22Kn?jq4k)Eu7~Ap;}PC7NSminogCO42ICEE2J}K!vN(67MB2i( zc$!?8>+hn9CG%!H0ZLoKkqcedBsd*ZwNa;O(KA%XN0~+9%e2*v!Gu2FRx|tev zLb7m!%l<{SLwN#QDmlBVjHN!6HFzP%fttJy@mN6Vy8{0-@f|4VUjSt@k!=oZNoF`~ z4W=Z^n;~LCPpU+e)!F8COEn2mtcXaPqgLq_QWzxC=9nrKo$$uVI*vC7hrV#1uX z);9Y}d55=0k*x2i6d3XfgwMLM)!k7S)DTI=nK$I%0GI8f^- zh0b!rdbr=6nUKi)up(!%GZ%CJ>QJWFVADOBaSMY5UXiRnXt-F;EEujT?_iQ_u`7wl zFnFYWftz1mI)XIuNWV@sv6N|bn>8M|BDd%tw3l^y@h{Nt#u&aZ9olG5Mlh>o^2nh) zj2099Lv(orQSHH&N>*a`VUK@mH`=T4{~*vFqK08MzF(AqQTYbS&%TQPYQKiU(5Nsw zk^;CSHe=VG40w;QA2(AnJo+QP0_430|Eyj4CSY5Ve;PYJaCv_ctlbp7@tp0t`@nyM z55%|@87N+><*w*v+`@6CGMNwJ22v(F`nBn;BCq|4-tC^~`)6U(1Vx)=ya~I19AUEQ zkrSnJ2tU!`pW1hX#~b*)GWz=rd@BwYo`9i16L$YCe6s1`-IUSe7U2zAic^)hPOpE2 zwFR%iH&Zmndg%EpKP0WrPjyib_-J=NM3JW8;@DEPSYix@iZEIa91IDxqtuETtw&U* z;c&LEq9PXIhFAJTh0)7uD4TrMR>T4^pV&4$iF;S(mGz+b9v{_@Mq^ASvr7@zKd9Ms zu9bCz@JGOsD)Y+zBZe zIwXZsDk74(l**j>gs2=U;ps6n9E}noWDbv6WDX(IBUAqG&vos!yU*$Le80c{_kO+B zIcu-aXI<-B*BbZUYpvZfIqehnI)ol6;UCFqA7RbVGrew=oOU%&1Hvik^-k%A<IrL7$*s!dy2UIyuO~Yy_?6e=Ke4$UGt>O8t_e>gv-&A|UXCLwY7q@}( z9U5-PUy91H+%n98OR*AR4IJy2gv~)ZtU+&JJZY$$+2+}zKT_70T+(E;89EF}rm+(& z7S%@|lJEco4O=5j8=k$md}DMNm0UoSB-{#TLRB8?3A8afJe^FVAtqrq@Ke<&zA-xd znB0(ydx4ii`KlVtH%5mBg<~j)B;-EUBaVHbn<6P{TA;9YM^`R@J zCAHP{7=M4bhiCj)G}_}IZVwOA?32(F_{_B^R+V21ztQa_;WFSGt5MRb{AbvgdZ^qd zVG5L))o5u|Zk}&%)$B#!x7SdLtMcag`s@!+!gs*GWRzHyx6hBUnz%m3D#4|8O$At0 z-X-4xRg$nP@ZK3ER^`_D7pP`QI0~doF=|zLulz`BY6Czn&d_Kt?ePyC^V`$UCgCRF z@zp54$3Jw*?@8C|#+U`=$!fH*=^p>DZ(@j0ITda3S8;VI_}_1dS1Ruk2ZEpW~P7QAfAyNgWB@K4zs>S`QhQEqN;Cd z>!DpS4FdH< zCiw{Hn=F=mAy+zuL5?$bxhP%DjJ_h&Z47n2<=g<_TrK&au7uRC@ca7uyB$HLui&i+ z@9;O-pX5j;18 z|3?ov@T^$foPZtzvitbA3en$%VVRh+OD z;Jz7EzN%DJ$cf?BvzP{~)WDUT0_E;7DLjOkkNQzp*iEIwVuvIC{=oV+nK-P!&nLV zWlcgoq928Oh>|OP5wu<5aulctH}E%UxPrSRoR^|}p*;MD0k7$yc^#o~cep?N$lS4M zd%Hx$?}!*5W-6`Yp{K^_Zt};67ZpBaO?dC+(atE!|Id|BKU~4pg$F>JHh8=kT%L<$ulnlIV4GI{Q(`gx(v?vsyr2MpIkCE zNk@&9hr|09oTsYt%0uscLoTUE6rL-+zJ;e8C$MXBX;xGtSk%M-@iLJSJ^{kIcyOky0*PIxS7(rX!MnOT1D4QXOb!}9>I_I$D&6aN zdRnT-r4>Qjqm$-@w#K=p@~zQyFN>kAz@^%STM@K1IO#~}saXv9(ptm0L#JB|ZJ93B z4&#cTt-Z-mLa(VB14ui$lG_QsCxhf8+ght#5%y~hKAVu|GTdrKLtV3%*Q(ZfyF+@P zfS)pwRSNH&b~;77T=6Hqj0UZ97w%|`i*z!=Ko`Ls5TyY8&K|9WqD+w;oATu4Y`Y6@}f*;Hv9}_t} z8S{+~e{TxmD?odEtDzv<_go&Dx8kktZU&c!W_l;Qd-5IJT&cv_A6l?d&;Q6&2v=0p zq~1(@(`E$kok7-z`OuTxm)Ow5#7qtAFgOD;p0%p-uvtBj26h;cBK6jVNPKyNM)t2T zqZGU%EYiQL3BM&1UnT#MR2vN{!ga49hZ&mwEx zNvReuR0N%IoHQl0CC+2SPDKYOC%Y27|5}h%MI=WM+%<#bqZMeWL>F7kFh18{MXpKXzR0|Krhv7{i9|fGfI8hC! z8}C_AXzaoD?SiB?0mE@Fv$z}Xt!}uXzD$5>I#4~i5#Ef9D_`1W*BYlY&Q-St=4y?z z*=(r}ov#S`W%u<=MG;Q*5fKys+Vh4X~zd` zDot7us;mvxr?Rzigv@K7YErresN(?EeG8y7K!2R8BA;ae0S_M!&euBMmOk3rmka|P zm2th7?^3AszEYVW6Hf!o-rA)t>mUW@N)?a6K)HV%@6R}UQ>hDoQ@OS=&XqA92zAbF zC^|yaO1czwv;?0}f-Qed6V!XUn4ki4rN0rSOW`o%ekAUZk*h~Pk*mO5={EfBQaHu9 ze~UXfa;LnzhO59_X&HYjf>!?~H{iV&=bFnGCWm&NcpdxOzqsIYB`@(Od0E1TnD8x{ z675Yevyv8IMnx2uE1k;UF6rXdTP?=Hicx1(8bhxZV+;jyf(tP!f)0R4HX&eloU0>W z@nFZ<*Koc}|RoREZt_WHwolF3nlTpni z(wFM=pU&XWw1YEw7Ru`xO+MPZcFt7lexTzp*$1=NXo- zs$TkP#y>-y^=U<&l6`?YXJq-RlE*-<2#?)?+`fQAGpaS~s;OTg9j}A&&y1CI6a#a0 zPEa3VCj=rB z24KN&-lZN~o(u)L1?LIKSJi@AX+Zh$H@P41@r-I!QOXbER1TduLSk1cryoJ7(qEjH z+i^z)#!l^Cv1jy~Um!PUs4up9qsf*FB=2G#5%* z?;6NMi^%4GkhAOT<0j+7$BJ}MaimP+G^yK*Vw=CA=($p*R1scOO`VPRDV&?m${*-7 z?mCj!2>v>QcG4Yz-*!GCZ6JA>Ok$8EKcOFWD903mQi9G~QRU$kuRxKG4wcA;Di~ zkhN%_=jsFfMsTgaVs5Pc0_ig^NmGJbW>B=QUTBA13En@0?71PaO2!fE2!gw2kQpA+ zww7t{Aozct$W_!6FP+HUWwW|?PuBksq&x_^C`%xlm7bqVw#lcn@y}m@_XeDAGM;?t zEMooBZJm3mmV;LWtvpZu2Cct3T0uTdmJHY8_GAk}_ResVRor!r51+gb>u4B0QtkYv zH6-p{X_iS3!q3QJTeBtMSJa{h6MSU`*@ywOAyp!|mEZ{(WWxi{^9_Nf68z{|kPbyi zo+tRt4D!iDMbP0v$!7$Izhfqgdyn4gJsLj8A5zfaD@h}G+h<%8qk20i*Wv=(N(^s( z@!G&Sv?>p1rl8{pKC3E}ikK8d=-8BGD4c7m@(`g@NRrzLzGp2+r?w><<{kvY@SzLDz`p2yU=6q z^y2RD5G6A(SJE=Ca|_jx-6&PRkkGiywcI99B@KhsOJ2-~aadsa-se2$)zmGlQ-L%J%;1?v=N#Z_5 zoE1*d2tQwe=?Fi6IsT#%etg(?N20aN2h3{^&vW)vJ$-oY7pk*7JZJGr-m-RRDN(vw zlzbcRJ8ubkj7fL(c6Q+<(wEm7K}3=~2g>*`NJ>@^@;`TiuhbJS?F3(~H%Vgb!BqNm z>ik)Vnnfrd1WoIheCbWb;op47g>pS4clbA-;?I@pFts%j#s?k3lY}J1`AU+v`AS95 zsW71tz#+Jz)*wSL;XJ6IqXcv@r1)Y$uEoIx#fW{i&KyZjAfQiGF|=(h3Qo==___>| zFWw=&!x1Zp(SqPotp^?-bOcZGFrldqoA?x}B6NEaT^|GZ99KVj3x`mM29A|e;x+uPDvdP#3p~bZgMIoX;PdH!>5lac_6C>)PIAU?Xp z$7aNMPca_gd5HR_$>AVQ3*PMx#endmMAoSVL2DF?M4nqD()^H*?TTf4iG0THkvwa^ zkZU~L$=ed@epR#H_(g7b5xVF#TqR03zV_G?7{Y+h%Qe11FDS{K9(s)rS0g={BIzx8 zO(lu6Iix3JYx{-7rxz;o-aIj>Eq=q{oA4x%!P(`^mz-~EkTbPdj$fp5rq&ieis1dQ zdh5RlDybc-P;qa)Szh7(R-s*CYy73nn`@ZdlE2A5TpyCflMj3|{*4bmpMn7&!h2^p zKNr5z%w%%NYfY2+?+gR+{j#OZHNhUKhZQ=DQCEE~JTDi%RSdhzh41v{R{q{BU9dTh zY&kwO?L`_Nc^VfG=R{$5hO_!1`$Tnune3B1*7)#*)NWY^%g1Aevv+INpQxQ)PrS4b z>Yq-;)B?tbUnS*0P!;~b+(ygnUF!I-K?&hKi=~UuC%4hPHree`Xv3V7_rEZD58;no zL;Ybo?yujPXi|C;A@}3FMceb`$>DmIA=JODugE+^Q$io$UppI3GpDK(vD7fkmE8XqnYT2ePd&$bIkx$77Yx)W#{oNMPZ+=`&{ zev`uqJ}!g&Jq1roDy8zJYM-M4vq8D~bHCjTc7yYr`gXXvQi-!a6+veKCl7Ev8|SIp z%M)s&zS@>NL-1=E6sO+1s*-#~Fcndi zhesJ+TioJv#n|;~n?v#hj8AcEZ%^=S2ulZ(jjveFg{r|2b}D>}KUb=452ae?UaBn# ztnYhU+0`D2q{Vvlm$?5?@}S(t*NDj49b|HQj*R3m0?Kf%g+25G(ngBpJc4h>nP5Hr z!s8o#YfxFlsPdioS*jwHrENvf?&Rc2LO)+ioF06+IANIuzUCr|`yPL;R6DR;rlNGQ zeZ>_)Tbq+j>WADOI8(IBe&uSCWdRX$rP{&Foz7xnA5Oq=IOobob<#-*72%;p;HMLE zel@%z==hZ6a)NKlAo+-@<0iNpeIEQCLgr__0jedN#3l%+S)cL zC^Xf!X<;iainQg1{sSToR>ZY7JorSVQG4xs@JB__uQ_|8!=x2TK@9FU=pmK#cCL9#F5`IOsKqh zdir)j3mkNDzAiLis6*c2EI!EgK|yhlBnnRoHL9IXNLJmek7}0~oQ`Tkld}}NcvREJ z36qh8j>CEFw4qDM56mz3tiM#htiPW%B$hE?`I`YLB&GS2Rl`GYn>omr- zlgPjkgx-j=ilM4iEhkvDg;~|>Nv(}-f2r4#^g zss|Fh&QjgR;Ive?P1?b&QmR*UMnYFYPtAnKrEG`wB2z;NE)N~|;IYe<1&t87si6rA z^;$lj&+U&}`gtKY2F?WBw4lX@`O)GmU!Kdg1wRS5(HDi>Jn*NDqqU6AS%9w>_)y$Y zaF&99X&fz$T*Da&{vhruIP7M~ZHt>`%O~MX4-zv5_%2-NQOJ;}#&p8p$1NawTcY-} z=&2ghP19$9Usm*!h#nP8bGnT1`cLF@zYu){QSY_rX-=n`F@Ayam!h``YivNtY5!L4 z5%@3QyjsXt^}T_%QcVq#+K5z6!R`EIA@>#6yEIWg6`y?0uzVf}d>AgATG$Y@(yVYP z{L~J|q$0qp*g@iZf!&514ZQ=Ak1ZCDwpzuV?@i!foNFszRc*CCydrGP%~<{hz{wfa zZpNw(#GMYJZdJl~A!FG>OSKB_6qhU5?+~X3DKl~Rgfp#^+?&cj*DW?u{-qK5e( z1BBmjg|bDcQ5l93b_HlF?w6lPaym>3%X;%- z*3_U9h`%S1KZ5HA*xWQND1oe0M5#NIfH!YzR;5&$PMB{t6`?f*Y}(BjZr7fvU2A<6 z?J8n75m#24U3UR-({{$^rWHrOLfIC`a?@UAJehVpzSOi%gIJSkBlwt^_A$lcH{B{x z#Hw3HZEXiZs2*fQyZzy7@J}>IUp(DynX7@lC9o|E~tDS~uqeRlE4h zzj+h2r820Z?MVtV!s&lRi~+P~ILzR30*^EWuEaMG-`t?Ln({?5zf z&kcGx8h^D%EC}0hT^U;N_bQ~!3ZMP%=weJ#yMJX^#q|>)_M0A#|1CyFn^VHvprtSI zSL>$AFqZ3YOrK+mk&4Q27T2p&N!}o1y!@NqARDhxI#X;X8#_7kkCE3maNZ_uI#ji_ zsb#gKD`>M28pNC1Blx_wd<16&u26Opvb?!1H=df?U-;7I_SK$A?sr^` z%`Jl7+}eLz+}sXBdIwz9=C)JX+%hyaw-Y_G8{;^|B?lOz-X^iV9s6BuZ-TqJ=$_cB zGN`=?_V$*+Rb_j7>rTA>Zbffz*AdU#+dO=3!AHpOs3Hq~VjQ)%!uQdF3*fvU!;~#C z9n{|T1@*C@$bvgi@GAToEf~S7?ai&w8&xN|6&h_Ct#C9+c&{V4uUnz78A({iI& znyhd-@fH?a;cC-d!{ID^ZiR!%-LfJpd}th5A-6JG;V3vKnibwM9b|>QK-aQD3oM|_ z)@X$YdObRV`1W%%oP(~b+zib(i)QEv$IT%4JU7Dtvy#jp*v*i^HJRZ;;+4#{Cgqjk zep6j$_ynJuVF=l4BU0L&>i-a%)6V$3Ib8$iHZ#Lg(?Mo9)p*sKQ(a7;+}3D@2)Y?A zCVr6_E=AYQs6m_9eDi3A>*2T=1dntxoM%>&83el-GPou)TtU1+#b$WgRF@fk#OG$H zPxi`-%&^Ii(F_OTb2GGn!=7*2#Al|1%y6FZs+mDOigH_{86xOrxQ6)ln_+{{_2~K} z4l^{R7xhu-PB=aajRu;9V-$MPtfW!s5mP~<(3|*t6pF;^qfiX@Q7B$j9fejP#Ydru zBsB%2#8GIQpHgLg6p|)VHXDVqfOHfpgFiQD6q*;Q=_u4UmE^ZF67oEbTvyty%*6)# z47)9cd=hsZVV$tan3ftH(i!$Fn}qiOUWlIgNg3c1n|=WA7%8m{Q8e2>>TYR!r?8Lr>u+~I+AA?od1bZhI zHBMqD=Aze3q!+poy)WP9KgzT^u`c-57;ssU0WUR03;hX^iH~2@$oxOt^N;*NFX_POaG@5JUUxxSu z;aiYajvTa2l?E24&SG?iK?BPhqw3UovsJNvT)TIY8!Tcv*0%@o2G$>+*N;2k+>0xe zJ&&f|!0s}h>PIEMw1G_`LzTE1d!h*XAoqu2@$&}u3+k@I)jW01(AWwZ{$`Qg7zvt{ zyD<*kHny-jzsD9PxHb;aTFk!6VI)1CO)^quaH`al-8qLjUy|}!sk|~ zMaDKXD>OD0WreSeSIr8qK~iRGv_b^E9{o*x`?(pmK#jJj!L;GnR?!Si{)}c2ycLeD z+;1w#41(PZ8C;VYwjo}xVl$jXJU7D~_}mP;q4mfjGb}WY%tnjwO2hMkCCWQLv5b*!7A`}WZcZQ=N+Be=Dj;bBujW)SRV$l#jH zum|zx7Mo$PsjgAypZMGiPeXdA$P7!2BQyMn&&}`}ocD1&|1uS2hV53@UFZlaS)$PG^!@iBaOX^B#!(eB6;HQZ}19X94Ndx%S_2>U>6|rc>t@Ao}^# zSwe>3vZ?b<4nH2c_u|k59-UwLBnNjAxW|qm_k_Qi>U(TYo}`X0EDUuY4Y?=7$KTM1 z`dvVT{OGn%+1A={nifl4LA*I(ukYFWgrxQhd5Ax7nOW~h!baq3Vdl2@?!d>>ZV@kn z)Do$oe?1bc3?jak5x){~mJxI4)mFp-(~MO6$7MUQ@52Q)4)ECct))GOAg7a79F^oA z4Ozcynnfi)4vVNYXESof@9 zjp{-k(f^6iWJ3ycl%01odi^KD^E%ILlq`@R-DqK$yC!$nAHOF(`{?N-p7w=VH)yTY zaKt_tHdswz-6Zk((cR~U`V>PT&24ev9v=2_eK*9)&)#cP}2zrVP)9CROsEw z{6RQ3lf9)={pkpF6u}o&h4eDN4`(VA)LF!}1j$APtq@gNzRg?r>FCt|8NTd-uH{5u zv0E&3d(VW8X9S&2@iM%(r2iKAlGd`ZPNpzRH6jl>Hz+cae5~T9_eszP+6;;VtswoL4dod188mt>j68<&ZJAe2Rs+unI{M;01pX+cTIPqKRAuN( zVDnmPygCA-9lq&76($msj#yYm6r^{AIwd2J{V6Knf1uh81e|FSbU4O!_+|!KT%?66 z;^|1}Mu3xKb&(c^cK{y?r*nN5*E7r{id4X1^PfyVnMHJP9elF`*e=3L3QfpmWoS;| ze8*)pVY>-$QRoD|zzpX`%b==8n;CQt&Yr|sDP>y}D#JMhyn#%tgYO4?jI{W=K~l+w z&3QE{QaE9nQ9{|`pi_`UI0ct5ua~x`rV*0Yr7f?gw}+C2p7eIB2f%`$S4*&a_uF zf5B?wEPn&IV;vQ+3P@0ngqTUMGy$sFg1wM3I2Mwi_-Z;KUN^*MHxxqweI|VuKA%FC zKpHGkdPDK7aWsWoj?br%Tf*5MS13D`eEN;)#&so2GwEINr8lOXA;~N?P9Y;$^|p%M zrCED=mj{u&2v^kc__C#BMcz)7Srqoh@V$_JC+<)Z{Sf-Td#-JG6~={d%4O2s^DUrM zhS>xTBhs{>l&t5V-}8>;Qph85kc&DNb&D0Dp1Qsci0F;0rW~8oKKG*{7KJV-HxU^} zFV5#Ckj_x(Bid9~?)h-z#~im9~Uh{)9tNCqZ!($gLMMl0mVp2(p~0?-@*_5sFw+IM6gzPkDeC-VlXdF1$tI zLQ7K((JhogRRw!bc@=RwD|4}@?1D`1DMy-W>M2X8G`rxa7~Y*el98Un=e^}75Vpd_ z-g28XQu4ZY>tDk3-~6BhS8gNa{<3}B{Eqv`_Bw7QS3jCV@Eyv~#nsAHHEk}y>$uQ9 zKh)x?rfo!AuVx3D6jifGq?%P)HFJ{cm`Ez(OPd6fHB!2?Co#PW=mF@4RWff%k7oJT zEh!mRup2jns~cB~Z{8u^SQ$4yG8sWU@8Krl^B(RqNYh11d$=czqaN;KeBQ%-2WJ(o zP&G5$b9`wJcL+vT6R)v{i(s`LE?274fYW7#lRMF$j3trBaYg+}dVE$= zOP!ss(M*zBBeueXi^9cpE}cpB?icd8Jy7Ny;x0aL9i2QV1FBTgq!aAlZ`ue1sNSzU3m4yBp#v^n=_=CX8po3~eqI%SZ|1_*dkHh*sEC?+LSP*nd z4L=`7l|(CW^6;6drjdE3DWrk_Q%Uj%Q(wSr>&$QWvkr%9vdIRqvI+hQM};}qU{yB3 zUfD7@R<~4b=MO(XmatK?u~gQOxeGoY zGDWQW1Z5Zdvf4&cUnWwljAue?2`wCxKiA}`G9GDERmRbxdKnCZ*~XbeX_DUaO#}Bb z5Ih1$g?h;ZsSE^r8DwxxWpFw1x=Ghq89y`y^mwqrhOrEqVzR*^rIm4S5U-5g@Oc?* z24@?Yw(KBNQDtzQ@v43fND+{7K^w{G=6J}t^ zeuQOPp0`W+ngx0USn=%GI0JHaVe9a^3LkjrUdC;sL~pHmsO zz;hk3vEIRWyFna?gE%dmM?iXaTp9XtF$tnicEvjhmt41A(PUTm*t*}y(C3h%`k38g zYcXtwR(T`e$nVfz2#xP0Yatnl^w)4RN%L~D)x2%>tflu}ArVB;cn+oz=V@F>n6fGd zAg=wYOnY%2#%0=DY-ye$QFBA2b%sQ(L9A}tko-c}Q)<^qmLaymOZi;GrnPeWqSpm$ zsqJ^5c{p`&MDbfhGf~L|tV#1v?Zrpy!m*NDFKGn#Xx!n*9gWO}rPa+bKj@Za8#q%` z()E*`a7qzeLSelS21&IIlFquYmaR8Z52ss;$;iK7Dl|=| zBHnK;#P=R9!r85bAa$Oq&vS{lOy<})*{Pl4sz#iRXs;4i;qwap8^k|xR0*B~P~IYW zZO)*0H&9`aDn$mx-c^u(eq%EqfsfKnnTQ<1dCPTSe7s&p-riO4wm)qHL*L{B2gpWCma(zQ$kQR&>|-w|)H zjImX+oM^Ep?BN!_N{aG23gfT;3O7nPh^HMIYfgn_NnPQK_`K$b*btZ1oDU6BZ<0Z= z<~XF9lR>fO2-437eWhIPY7RO~sjJ)$E{TJ_;BAyYgG z;*5j-K;oqjbntnZzXfTDNNJfrYaEsNa(rIqAHn$=S18-VRMeoqaf?{yyW&gBd^5^v zXIvcg%Z#KM==u2Og^2s0KSmMV5-Nugq_A9;*f#mjl2Hr(mq}1Le2UM@LBz{(HIzdJ ztz8ZoRMk}Rmh(;o@-jxLdl~#rdOq*sKgT z-8h!PLHN83{spPENNE|IY#f!raC}|{v*A3BE0oPK9aILBji+{3R0eIazuL>X${^y^ znx4&-UI??*=ypsxBj9D+d{St3IGbH@{ya2JH_|bA$3&1uNE0wMJjbB6gqXW8$>+A- zq*ksA@F^YC{&Ws=_W1s5DBt43#)SzmiXPu@nm)ddjH-|CH)TAUZi)O%>{cYgr)erp z_UWYNP5)P*4l2t{3!j?sDwCk0@Q|S@w;}OO#-_+nb-M-32aE^sd36(MBV1P9MDhV6 zgJN}CV33-92E|$-$bXB%4j=O_3X!96pA$X=18vYTn%EZaW2w}{EenD$vFqHQI9K4p zR&2tmGVR%Z)2OmIXX8-W$8w9Ujw(aen)YN!jnke*;V5*Th|HI9ZAocolVC(jIhz*GdGxq+Q5b;GB@j1wjm{dOmm@HDM0G>>gy(a3y;Q0@6c#}9 z3D0yQ6-{`M>Jy%CA+MAMI~0~dE}GF~k8uV6L$s7QGswQ;*kq%R~|zqf`GQ ztLv4{c6KfZ!o&;1VDw98J9`w)CUoP?vf0j_1#oOOluqo1R??PY0)&6z^_p$d3XKJ=n33H*CZ3+{O zsoBm*aJPZrS-5Pr<2LZw&d&hL6!$vD@8^eqYx zQR8|cVB){?x$}^F1L<8^wvHOtwjhWa=g;h(BVH?V5)LU0JW6WnncY*Srk>et+cG}0 z6Om;jdj3|&hX5<;Q%yDc6H`c||K?l9zD>kD#H>c|Wso|z42m_{ zA=T&%iZyyVvGnsJans~XVi!4$9AJG!~;d4v84ymO`sU`XtN0zt>UpgO!^EIwe_O$6BOUyN%=0Zi5 zxEU*`L9NRY5wF@X{f6><5@>@W;qbzxon;7B$d@e@Rmi5>#0n|mMYtL&WCpEWAv36| zrQ&q-W(0Qj)V(t9NP1obf^JcI&GP>?#Z&}>y$CY6s$j2-V~E$kxCo9So>#_m@OcqT zf;6(I2yQfvieMT(FM_FXX5$KF?dgfUWBj-AsujUym|tdIR}nD5f=r0g|svHrMQW3 zegbcDZ0u%j|2)JO!+?H6a(tWAzMVF@P@APw*AsIjvCe&)C)LE2|ep=Wsm+H!X-ybU$t2W#FYazSHVE@Xvy) z{U619Uq=!)jaWAyr})|dOZ>Ig?Y9T53|c=q7rw9Ce-GdPeck@|NLjOPe=M~nuAkhv zRa%7q%XRzh;rrI3wB&QO()E+wQ%RgMx(w`YGE?XhjhY_#(UZ^dgwqm*-^}MmbK!LR z+Gu$w(^ug7C-nfz!>xZ~&NGq?>|!Jza0_Q9P3*!J@C~pJhnD;Dy|e6-q5l5OoE~+~C4R$v6^NQ-6K^*JeP|)i+#}d~9&G{;O%a{!5G{YQZ%u zu+zkQM$j^~tzotCWZGIDvSn&@C$M(5h*4#knm{d6i_xnrQ>%+~>ah;!cpuTjzB6K{0r{ial;#Ih!cbe&I%$|1C3~g1PAa0GJ_xUiNTSVLm(3|v(ZB@R2#TSN^ z6nsBVG>uhV-FI*f*@}ZeJ_+a_Bp75Y@s0dRV}P=buK^ zuz-6lV9B!r7q~saiF=AWdXCsajRL!~$5N`%2LKjzj*42&j*}# zaE`$7{KIt6m|t!@4LJAVOJ_fSFXg#BH6{)?e;7%#pUrmF>?h(r;2cbt{d^u+in{&X z605sKOB@HsEg|?&x5P09%Mya!5*b{RB@QRvsA5apOgtZYU&QA_?{DOAN|7agHjakg zX04+o@?>y5T%qhq(?OQ#0P6F=B1`mu)L+DO9$4KH5qC@UKtz!xjzQgpZi%`lMoXLv z$1NfFShqy??t*0r!ET8RuE`R|6K`3uB_^Bpx;uLvpIhP%EWsnEtWNx499d$s-J&J# zh4YZri5E==S)w!OT9#0K*yO*|iHN%;`XQpo5ySxpRTJ;M7;WpSgUddpzR4WQcQ# zS6*z0M@@Md;wyY^h||d6^dduSxJNX^p7`7l=ffFlhWOBQkReVtUNu9gIw-U2GDO6^ zN(@7U{bqy;dgxK8I|Ubp6$Y3kW)oO$$vlW}3cl$<^MXiBwEXm90-U75Pb78ok|$Y9 zB=4fa{7l~bOx_!ryhzOCIZ5(Fit;3DrQ{7R)bF8^l73%g@>XZ^A~BQaB*_yg-i*x|A?xkLWi1b%FcPU@p2s`%X z!7a7sdE8E*vzdfEAI{->&0!9+0-FM+PX*@`=G%2)VQ7i^FNMecqCn;r26KauAARU^ zp~-C+bY5X0tYL_n5gM)LCKtgs;==sG7yura5%{3=m~Qx-G;#20hSmP@u3l_};a6I? zFTOxK5;doUzwhB$evf?aZ3L~v`BW=C`Oc=F1s(u2fA*aSzbxf>BhYbXA}>kmD!${6u+d>UWo((PyS^FTdJ}BmGrz520 zB2_)j;06fZaE^s=BCb%@07d;a{z*_DLEplc&Z^FVq)gZNd^3Vo2aUPmTWqo|kq*E$ zIG{4f#@|S0YRQp=Z@6!g`oiGf>$LDs^Ar|` z>1-~GzlMj;%HsASZw=d38gbV)Qd@D4!N=PUu*bqIuFv86vG63m`|v#ycE_h*xndug zkmiDL4q=tyRQ}F0ImhGs+T_eNIm5YLZ(lvC)|a33TShqNV9x8Kh))tI`rI(I_*|{q zE5jJBHz%U{NSz%Uf3>z?wEB|(NnH@W$G0GS!r$pZXV%6aUpc4@4`;MVMjON5c^PLe zU+T^-a*Zyo3@2y&&c;8q3jeWiCfB=@>?1)3`RZ49F=sFy^?6_A}SC zS@x`5yq554A6aS3V=IiKC9>1-&9?{X;zUnfoig z|NE1r_4kuC;?Zh@WsUS`way^+t9p`J!(;p;wPC%>~Dx9-}A+r&0KxN000?o^0soVV|8&x1RK{uYm9n@EZ;R&YeJ% zYjD|z7K$EqOtudlH2&h1ZFD;Fw!8D41oQjhm5skpyj-b1Z@^>bOAg` zNu-r+78{{EN$)5ZE>JfY*+9PU>x0? zxl@}nIM5yE6PCpTRePd+a z!1Y+1%e1ec(XbBT!w~s@68wAy*@q$4N=|qt@Gj3p_hFDDNvQ}!WT5VNhi3Ge z4J16%_&%B7W=y6gEAJ1E@nk0(pR~ z5-$*qBOxzMX{(?$7$1%tppHeQR~Y@!@CnFKDc+2nmM<9Ld7#Qq|lGT(SAHKDW|ZEn5}xZL1M+kL(}knfBZ zG6f{NkMNz*eHB-&a*H4M-aF=Oha)!&!l49I27T-LS>wzPt!jtdQp7AoOqf~N^&Bax zZ@_$DsceEOf>$d27iib2E1Mpy`BKXlxyuUsa6QM=6zv;agJF{~uB&=7Oy7eY(Q2xS zz;{4HJ8H{zA9J<>uE7;AnShfCyA8ZD=*wfdwlMvMM5JD%-r$Ni&sIvBEw=&oCpSV5 zz%kL?)?iJQ1^YZXgX2B?=@OjYha612kw_-4A4BsVpx?vSD~*%n`Jd2}iIhIz-5taq z@OHuH^W;TvUdI*6#+nYghril*dUA6oKDs8IXqR=5V2t+rHTu>+vE#qJc@Ehf@jS?sbpR=~2@bHHvfq1)idb+>^ss4OPf zEtbJGS*#WDmK0m;D@$L`y6PViEw(45guy37=c66wWcYLfH$ZgDf`4c-1U+ zC)S$rUn~}Jx7a8|*l%uFS&OL$DO`tZaCK!^k6K<~Dd<~C3sa&$x#&biI1WdXIL0id zCl|{^nIDdz$_u045&rWanM|Ex$)W0LbXVOExFv9dIbnvux}iP-*o)&5;0}Th7-Oi4 zV;HCxhtQEYisMU5Tg4&Riz9<;Dvm3N*B{AQ1)fSgufR+3`Hi#;FiNDf0@pq)7Dp?5 zUL1G8nSd*lbvG4N948sCT5+f-)Mc-$0!O^2d%c^{_90xn*Be9vdg`ZsOW{umn-ktf zgW|sHYSE^Lk(gYJkDOH*G{jVx2!FhEB5L);QAqyisnWn)>E}HDvRCqae6le^#*U08 zhv15a=gHyXb2+wYOe=7v%?&iN41u!t9+>pwOf!UP#>>ZtI#AcYB&F7$VU9npK2KHl48m?C zZe{3!Z=U&%!}kNec_FeN3l|c$|KaNL7n1a2;R>!Vk?y^KXQf%md?%`L+Ad#n((01W&OGugd zOfjDg6N$LuQr;GYbI#{|Y^&h2n1z@6q~!&oEm1C8h1V`nE;VV{rIU2jyk$5(pSFm& z93lgK-iVsEyax=fS<7cdTp4=d>sY3npF`0&Bc56rPU6}*$KaDNS>`qT5~a*E?amBk zIRQ$&GJJr~MYSv@^<*x`^xDi{O!JYb^g zBis|fCpu1X5HJO-GVG1-4YBMuKirSqUw}FnYSx za?$Ygz0FtkvtkSS;dhv11WoKcD4)N(z7B;w=9(OF^^zVJVS) z6|5*afr@Y%jwW%iH3{wRxW&lY&N^FUUrHlZTk;08W+0w_+8I);C|OL9B3{OQ}!uLXe#YB;%~s-peFz? z6MVo8hN?mD*fW|?=zTa$xYX2_2?e_eGq@%bP9a|I^`h$8gLqy&Z@}l(a~!5=DN+tX3BnReUrHmq*W^4p$MJOw{^=+v*+ivt>V4i}HG%1ULv5JsgP zJaj8QKYU2Ua+xF^yXGVvJ|q&)%>n%YqB&gqW+X-GkK+KMdxlH8wjGP^8*v2p6C78G zJEXV38C10lk*mkYV~8|f5laeBnOr?W{vNq$8xwYy@D_#DhO2_q=@lzT23HmCr?E{W z-eQmIPoFmtcNm?P zGY!Ut7U4N73f*ChF~PdSco?7GVMJnfhv6jMVTdFn=xid%Dwn(lq4`J|U-F*LzB!k#7v%(Bu}I$PqJD|UbApQCU0ma@77FS zBxdrQBzYofIcKg?m%azv+ zndrT3@@i@Fhi``6jfz)SBl#KiHZ-D+ICG+8ia0&oLF*B56)suMgzO#yL{cB3tx%Hi zjvD_NRgNz@?o@T>dh05}N)dhy-ASf+E7WjEq@k@)&0uXOW!BmX<(XO!tnM4i)b3Zr zOg%&N%AidBWvS^FTfCO=Q0K)gQ%+Q-L?lHizCX;)O0lZqt@_A5Qe1??MEEsqNSeip zi`aV-!O*2Way|4J#Y;pzlSL%Xwt9;Y;#Xw@!4(0h&Y6vJk^%2_J4Kc>-WQG8CLu7DGhUiPYDaD2u zYRYTsa~D20#2`ouiwrT}I5Naid~S&0a7N(@WpzwN86xRdgCXw42+Hib3=wfR#HNU_ zpLf39m{MMd3%iHgEEzTU)|QMq^A7mDGmpfq!8=LySfp5yC2OSQ?Lp_E1H^ioEUl2Z zz+|a1M^d)-!AV;CAd-HILc1?egz3nwzi?(Up?{)YmvM1(K|EkM-D-495X9TGXTv+# z^@?ls(8|7}-rF8qy^H|%7Yyvnr!y_!Hw!ptKrZwNI#+p{)6_+10(~E8u0%%Y8-`u2 zx}gbl8{jHOe9nMX_ut0y+H)xkuRVfh;%EwQm;lut!CreZIM$vyK=C$i4)IzdHfu)L z_m9o!VSHYDo`BRwq_i2mXdKm^Z}EBUc?r(HafPzOu!S#b+WL%Gd-lhd-o|yuyl3HJ z?HO$(-NwC#Z(fMF*PgA<^y1M&zRsv{%nf>Qd+rVx;;f((v-g4EGq&9KOcP|G0bz%0 zt&L&FzQE~>4WG~0L@ZZ!;*8BnHe-XdFiZ#Z8QU`^UE8J=X^A3jROm8F(lulI6xe5M zf)lwoW9vR3+CPJ;+MmMHjBRfs?Wc$(g$qosW^5l2nOy0Wzp&*>w?*N5!*ves&)`1u z+VCtTBVrS5+6otrp&^LW2FOXB@cGnBq>XWL>a|%KDNen5!sO?9YD?0GNHv{2sXBF$ zC8k+u2352JCnsap4E?v-)jytDv@nN%I8IvSrBLL_B{;3O4-Nb^D@ctPAx zm=}b?H^5O4!>(Vuod~WkcF?Rl znnrT?ZCZ9Q!bRafH^#oKBLciHy9%H8Wg-rSn3a>0 zR8Ar-3}XSkj23ath(qgDq`8W;QK6+tui97ym*8qBqYSEQ%CwA*CepErSW;+fa#cp3 zkZjtQ30tCcTNLISu8RLVxZAtroM`VqF`c@q%-#n9IjIbvSA3C@qQ0y)enpD*?hBKj z_hsEk`Xs3q`?6t{nEJ8|s+K49WvkHkrO_JO&$xh%bm6VBY(XOCjIbHc@y|lwc{qU9 zH>s3%B5;R6B>QY=`4-Dri1}Pt_D{-jNa)Ud;Y=_u;88^D03{3!Z{HjXcoeV~@B{d~ zfJN*DF)Lsvsenad$t|E4@Jn2KBUGfDa1?Mb=~W9@@b!Y%ZiE?B%^2PrK1rl!6tSeR zrO8zR|3F&K3BymOJ{IZ;eO8Xi^MBeM&mihdl1jd{CJa~L2e>t zJ|CA=jG-B+9G_Q=`yo86%8@q2>1m``F($+G-;A&;z24iT{4OpG3%i!9EDj=Yfu*Ut zln5s;^QuJ|a!47CDInrYWd7-LyPI51>`Km4uI!voeAEWrCW$pgwP9E|l{(`S zy!XI;f+zTI9Fw$}CP-QccC%)1RW1BJDgOgSBD2Q(q-N(!0o@)Pi_a%`>HwFEluq!5 z8b=enyYTr0Zy=oExI)>srlM{SUNxTXlZqyIBWQ!S;?_06i+I(=4E`u!JG4Cz7cOON z(w)I)mV)jKk_(hy-Q`A7c4y!u-5H2vZT?PLVmAbxBw-gL>;VFHH`E*8=>WO6G5N^Q z<<{5$&xGI&@CJO|07Wc;m^DBrsR4?#Fti5r1~`>#Z-9z)HjV~(`7M%OwE+q~Q}Egi zFoUWVCUP}fyp2d>6|tmnkI7X7e2HY!nj-8@;Vla9fftX08B|rUH@>@x(?OYxjqfvL zdgIGq7<*;S+EsX2<7)-vr2X-E;}hw8Tx@(7rIBLeI~u0{IJ{~jIx$jSiK86+vrnf% z@M8;R6Z|HwR?qO46_JiD7-nf|ad`zkUtAuE)j#_b!~L^Q@v7=)pJpJ%7nd(2sb1J1 zE-wE7#D2^H*iRr$q-gfprz{}->{H!~q>nx~xHMAJV+%F`v7etO{5$Yq5(>wKJD37^ zMc)OEKi_MQ&(9MUajZ%uo+s=iRdkWmd#Il|{6~g!$?F;xm^}3}Jt3qwklx1}2WyG5 zo*NVUn6a?Dj}hD*M?Xrq4$ z*{jV@)K^*J?NxV3w3pz+apZZh36Z@7yS*~FCVL%0 zyeTq8v{yUgdHw2(&+XL}(n68a`gOT+WUqVixxMdzvxMwb`;yFFepuNPuvR+D$NRQ0ylx443P*nL zH371fV7FBU*JP__h*$UBB3oTTJhxQ^KDX6tkXnkA+Uil`$W|ZVb6b4~=L=k+tQj*` zf1tDBP|2!hD?M~j{aKf-BJQ@@0TKSQ#e;T~%A(MOXKxdcvBQ7(90-iTB)RYSYR}%{ z%Jsv8p!{e)sHLsa3zR;Y2_3=;qH)X$fwhy0zY~4bM7ysqN8(J|eJyThxXHGhPOaV7 z8BZIW#nTOgUP^oqvmV-nPU%c!44`+=599NhNF-$)w3F09i^MNIwCGkADYi!18-G(t zK|X#s`@q}-TBK-41@=d=r+iW3Ontjt2x4FYG&Zq_MQH?`BwIopp^Rr-gklfcwI} zZ7+)p`$U{8;wc@Cr-gk&X@4q~Myu!{4EBY6>l+4KY0LUn z;PYjD88Kbf=Nv8TlQ7vuYvLqIdC8XbDRp1g=c2SGE+eID;=)zpXj$J?`26>XnMR^o znhmGlUEMTV)pslScwAi7_Z0D`+p4~ZWUKnVu|%}0Po#Mv5`0x(pQ{y7If&uesy>gX zRed)@@>P8q>A&VctNLz4yEc}Ct0pK1YZmoAjx=A?cNd)gaN?rAy|0lyw5acXd^|q_ zD_+zm{$j$iMSY_AqP~ZKRtk!X`gR(n=BGt{f*O5bi~3GP6<^eM5-?GN0 zxs&^i_g)gXboo6}O-uR~LGUGgLg#{JOZs-XPO_F0RJ^25wDoZfhMhc7Le$ZYh3QNB zB3i9gix3y6bs+MI5^&j7CO`|+egpR2DH6YPA%FF1u-xQqn8cbAWy7AhZXL zsl!JmM^gvEK6S|8ICZ#Ng2}3;@x6%G0m<1k>$)41z8)3K!{<|neO6OnL`tU)pBP6| zhr*3<>QD-&3|A;CGZi(>+8flT4xR8(m9=r_8c1VBOs83sjHGu#OYzMM5%;M>i<_h? zzjR68A1vv^HMnAqr6P;%48<)rT4cAFNF!yjD;8P-%VG3a5n(@H(l?RwMjpk*C4IMB3R=?lP)eL*H^8^W6&47KF8EgPFzndcGmRZo!$r{RJOzvZ1P*4}yB#6#6I* z3qEWHmIVd71v9uN3oanuC>bZ-G%Y2bTX6kbq6O9Xrihfb=Dk3?Zk~Y8EqD){hs=Uo zn2NICb;he!H~)epE3K<;M%*np0TF54)Ox<>QTGd6T+jE2!M>hP;S1e{ccVh_dcNmH zn`!I$R=`^3EML#}k*6@n-gBYkB;DZyuW$;1%f~BYjUe>s;{UX28!u*k+!h7O)3z z6dv&R%J*fQNAdYnzX#z|N>KX9eO4MLKJ|M8rvLo5qVw-ew{hXcaaJ0-t@z&L>QQf< z+f*8Q)Ejx(ZH1F`TOm@sOOdE@iF;ysCT=ruzhB!c6Bl`zI44P*NKu?b&6T*v_L-uR zly;pmaeXpzk(Y^clEjG=#YxmMiF@kmOx%!6+~`bPUwy^?Usy* z#jpuJFI6QcPA1Ap5+zcmS_ekNez@@26PaqeW%4>^@**#j=OoD!NjcS;H;Fo1;y&Nt z0p(Pyg-$VXS}k;;iPLJK$jep>IZ3O9M3T7Ic$+XCQO`=;v_nnY2ZUV7hiRkMS zMO=x?)+dUjK2cfDA)$oSsx9-|{B{jb%Bu*iMff%RMl!|A{JKCwjMgXCg4IE+8kYGf zQ+e=SmZ{gXOx;U#U!SNaT2Lo0s+D%fq1!8O^SJMnVM zifnMX>8zRu5pdW_%jR-D&-I##SLf}^)MNpxI`C<)|_B=eRJxG2Z zfvvvS?uD%Y;VWTN_&u;G{3}c0LkaH*cx?|})q}@7aGYlV zY@2Bc_jHMEq7!^EgI|K+55VJTNz&7>eJHlOVPkB#Z2=g*Kn8c>N>E~tHN5;E!E!T++aX z^M~L#cCYX-qSTqV2XtoQ*%0BjEgVnNWmVHHy%86GIT;3 z5S+ioj5FW-C2vJ6+WuqvN+a;Rt~4lsKV!ENw&Ks&%>vH-jNLneVW0LDY{j3kD+C6E zjN74Xd&Fn#q_?`jXY5oJdp)Yc?|**AZk@+7p%n(1q>V1mze}3PbMP_dfIPQ?t>h;J z%jEe#pAY;m&&5rs^rr*=%XKlfnD33=X9J6b@9px*z_NHgCOk*}H|<`?MKQhPEW`b||4kwV61LG2L9aGd@Y>ez2j*Qc=%o^Lt=SZzw!&z$ z#vFo&;kW+epY^Ur%P`hS3`j;aT!$Vk6R<9XrDDVLE_h(4 zagCV;i+uRh#@A=rMdbk28c(@4ejBMhmywO~WMRCqa1W2rFZ0t%7$U8eKr zxMm0B@Bs88a2F`$XMT0`l!Kh;=;@VVpzA(E5fY~F)prnX7Grq8Oxnz}@V)u~l<0ev z;t%lP-MCYd%J(Y8`d;W|X^E)2=|4T_C->Yv4j_=j4U_+hb3inIVerqQlcThg_8AizWYVs<+ zS6#WjSD%NU{C1nYNWnj^dIy9zItPRo-+~=clC#4-l)6>Mp06UL(zgWvf=52|F z$8(nuv)lAX3jf&V9nalvCZh`e0NEb1ALR;qr^BPo^JJB`7N}<`S;eh}t->liUw~NG z58r}Kj|&pGnAvwPmnewqhXi4O3ZbqYo`GA}4jE_%9;_X%dxhG$c1XA$UZ!{}#qQc+ zwHMs-@z2l@QgF_uG-S%~7(+I_!kuTP+!=eD z7v0+Z7;IX*nW5m9#kG5%U|74qgH3DqabUj1V;A(6B(ipAtfsC~wYxq#hK~QEb8zKa zyBkA={PYyz^+;}gq{QqrCnOrKQg)GOxQ4nGHa$g1U>7FYJw>P>F1QfHi6T$SJ_*<} zc+Bf4E}oXHxQ0SKtn>>6LmAnA2-zP`gHS1_=sX_KR^=(#ayyi@#7Kt%n^L|Hm?LDe;B`p@DIY7iQj{BXChVau)ST#ePXXUrpb` zrc}%U=u`w1<=44X)P+r{SOm=dcsj7$aPFu3EoZc;Mnd4A&Fzcrz8a&6TShPjtO00>0`UDzaHClT_un0 zeh4i(Cd@=s)>p-2!gA}qg!0%fQ^JIL$96pr=h$uo;B|c1+J!pDc00M6wD4y^97IIs zArsi?7JffqwD2jOiwA{2pvWzJinZ`Paao0bC&JZ-YOfvKi*VWwUV=>ve>p&12y)uN zVZpE+oP|vb|8ZcR!($ihmo%{Ob6=vaQicBn8VkoB7b<*Lu7%$oD&(h3Shn99N+upP zNw2v~^aVzlpg0N-ax+4RVkb3NrbaTcNK(&cunsn5qB1~>BbazwFl6E< z*p!JHz~tev3*MD9kcrwG%3xwCSYU21#DptXCfY(p1QRn5!zwcIxCy=PGI2RD$^^x8 z@PLVHg(xyXu`=O_%VOdVge!_zv110enu`l7eMaZfLu?oV~hib27rEYRt zRx8+)#To#0A;@W20|Y}BZ-z}-tOrapJa$1%Ng`QXC%95A>jp4LrY^*yD_0iZgbMlT zd-hMnFqBL@@4RPEK&~uMWYDi8CtD;1WPxI3!4sFof{k!fBUwm!*=3;xY|26+K#L<- z=qDJmFby_kp&BqX@z@1nl(!xVUL&|tEL;u-M*I&JT)DEa2Pz_IxE*<2MH<#PG#m#& zX`pBx9?(!ENgxdrD-E8wEE*OdTu~$ql{dRIG=oiPxDTLX5j6A_3~87Go6_(EFwf($ z3mWcrX?Rg^rDz}pEbt3e23M{$ya5&ZD?S@7wq0f+C)9XZ*T;Xi`~a{A5byB47no50 zWhjy}#b=Nc=f3>kauK`77S3_DqdzeJNHZJ{4@{6SC0_~s!Bb%UU-RT1E>V08PiL86 zgLw__ZX%ikQ7#e7sUN{3@CrwnWB7uHXedQrL&P_J7$W`uq6BR;4IR)_fJ(mci_Bv9 z;U5J#h*d<~y4}=-d%a1;-yWiY{{dnxqA8->`414&A#r~A5(5MuA?41^bIZpM1UwDI z7PAeXdOe57ncf-Sn7zPCV7w^5VVHkVpe9DbByQzQEhye{i9J@lTflpRTp1h(RrMh@ z6|nlk>w+U8(#aY{*W&T63#y1`F+7o5IVo~}TH@c}d%3&JI21Mux=R9?>1P>+i6XZDaG{`(=lJ>h~mVebHlj6^m%n|!2 zCYcl~nVz^TGQUK)=1}dCxd`EOB={w4N+$E(n;?hGgd$={W)^HpW_e&Lk)wilB@HCA zui#3NSr4F=1UgGBrO9;VO6EAIkl#9U8ok3gB==W5;H;rA@jEgiXI>558Xc~ovd%s1u(pfHz0GaA2>IpL=WHo~SWDg>TnZrv3X1#v}%pdyp= zt-GQU{~EP(SSd&@kGe~P;mfMe8l zXrrY34Y<$H?R>vs3Xu3=)fXvTh^PbKL0B2REEkECCgzBuOp4q^A{DXUp{O}UC3B-{ zZER&<13+&8%t<6P9UhNKq&g;Ph6IhJ@O$TFd&bM6l+cQ#3kd^ zwb<4OH;ajK=l)T?+VZgf}EP3FBsPJv9M`PzXF)Sc!iw3aOVWV*k_ta7>KDT#*5EeB!KGRf|8i-Ne^ zLXc&>XFdd^ZXEhBGzh1Q`B}P{KLF6^2sz2<&Y7)VblGo^Ax3vGY#JSb=Od$25ThfA z^_?Yr3b4fQq3;)ST=cP&3kcBdgdZW#QMqm>+#+#tJ7K-3(OXf6km~R882%F}GH_I2 zOwxC->G3WX(0IWb(f*YyZm)6 z!nI?%?>65cSQ(eUE`dh9{6%bkV9UPzMI71Um9k|(PNLR(%q57egw{23r7Q~n0zQlX zT$}&XlkoXvC|+ZDtIUC7>>?HE7{EW{F-tJIC52J`*~aEoHL}#cy>**uSCku}|E3DE}oBXy*f96MYnUn^u()@lIfBulLn_ zN8V=W$DV=`?If7rXy}gNwId6p4j7pNk_Hix^xKP4zYH*9c7b!Zb#VG9FR5ICkUF9|f@BQ^ z!YuKPJnGW-7{p2+#qZ()1sjE3zO5-%`aE%2^c_REsZj0FSLdKh-yGPKzH`X!VuBp{ zo)--1I|!T7_ct)*P&Mp=+LA=lXT3#TrRZw{PzM5?5mjmWT)EO$87kzbn^xZ;x##hi zWxm@b8g5$U60_T^LJGt0@tq;xl)2CMG^*eokU2xF`+d*DV=p|`$t^(Ysaz4d3Vk1n zE?xs{`ZkkX2wP9s9R9BXYA^YJ!1u+wF8`w-SNBDoLZF%S9@KsEjkBs|wiG~_JiFwnYT@&Zt6h>!P37W zNc<6mJ_#W=Or}DpWKv`$37K;w29im!lIe-dBGZp>^`X|Q%v%vo2TiA8)5`o5^4^;u zr!rSM;*!|}HYIaCFt3oKf^(7vk~v0jrO0GIz}9i0%IwOO%o$LjKW*2OP!wZH!(!jX zxa+P|ECxuap!fzn$j(Ca4LW|LSgG*DWl?bx!p(}LVxJ_R_3As=l!`e3t%#r^_8pgs zI#rLouB+q{$_LQmY?vUbwcx~E zLa~o}36%{Kh?&sh4HMVH*)XXOyt85AN}LUoj;H_^{{E-F9+y+MByJ23_JCoVbj8Y9GK_u z*ad${8d&%_?^0K(!oLe`fDP+Hh40F>@Y_L!{FDi+5_*F(U}CDTBQD4)6McYDCMb@= z116RUQS1>YRwg`gSxm$rTnm~iFFL>s7xU}6Sh=uakY_VxJ4W#TemlnILG;6ZL4kyMZg zij@gZTow~|Al#%#ChnHhlZn-^DHHbsG(Uog1A-wFKftC;JOa$qcNSlUcr7`85Q{oeh)O;xR)!xM4EK$4|ztf?MlT zd@@=VS-j1+6qh8mKJA8BS){lU9>Kw2rwgs|IY!Vhw=K zN3hsVFl2E!Y|3IiV4C5v3$BnPvOcX4T&b2-8w`@E3)LrAt}L#F3i&x3CWs;NCopll z^Pb%Wxw7ylLyAPW>L3!bD-HB>~>a69tapES&OXm||(rGcV( zc#xH!BnhN}Vx_?omqo(@gqsve!(Wng(vbe4OT&Et&5xkrVn~#R!LTU}PXO~g9=l)! zMyN`|GQpLi;TllD4&*|W!IdiwFF=LqF+(Ub0;31*4TehH+fAocc3 zenddsFL@H8#GfPfOA(4{Z?wUAGu z+}SU=8WQKX+sua`4!L%hxh1p9f!Jbp1^w1vc$}HVN4}N7?U%qsW-Y=w`z2pUn13Zq zBJg)g7}+!VQbai?m}7os@p_2%BBVKuI?6qh%OTQb0*Y?L0N{FT~omC|-sKZL5cf*|sRww&jW4wC8-xwCl9~euT?`YOjm=3PK&i zRQ|+mTbCd!T?lf!7)YEh1~zS5J%PCb57s{=4eV%_2##&*8Q7d@{Sts4CD56dz9%3~ z>&u;FnY(grTaDo-Km7kHq`=uWStIqo3uL>^EO;NrX(VUcXNw>HhpWo zh`b*o$RTr^VEESh7&awy6EHi-Q9+y}kz^)*MqQ=I{0Jacv#m7i72`cT z<|W@)iG{l+H4zKykiDPrs#- z4YJ}pB@J&UBDbKqakaPN=PXctZN39xe+u_P$mwYt2(=g}dJhk%td7FfVxU-y!4sEN z3?CreB&hX@VIab3oxTM&Eru@vnop2Z3=av0#jpc5Ery?g`2&w#uvF5(V)$HerHX;| zndN$+VsPbJr~iZs{pkY9TCn*x3*vz9Pl<l0}0Iua)JXOz_kik2!*M-9Kgm|u+ z->L>k1)L^$9Z$&~b-$T78DB>p=G!z_dQ|5hj1Th>>aEmQg^oka_(Pv0znz}&UoJ|AxK0M|cEblUBQSO>LGdD~!Cs|u<9;twd5umNpu`CF| zXGlvW?EfMhBzSYLF`LDLrE+550rp#}j<;8wV#!ka9Rh+v*sQNuFf3RPSP@%uELa7x zV3P&JrE-Ga#p4w$L0Yh$$SqhEv0y!sTd)+#PnXKiLnF?4<1_;9cKr8}N5Hw{VIj+v z@nE_98_5cn%fm>UE|<534V9G3bH;Fwzc2Q7wG-M0CE5v5yc!QWlBc0nJ0Xg-6Y|6^A*Yyj zB%bT#>kzItRC}FJ^;2#q)DbrAgth=QmLR7S8YUQaLbt)DozQMz-oj%S1SN^=gjNZT zolp^M&Wp7w2*|2yUBpR-lpCD$p$w3OEv8wE>m#^_pg-46; zy!G<6{+aNY0S|p0P|s7;wZ$KcEmiF#PeZJ)1K;=1s-Fx$2GoZ{uJ;cYB*(LwEBdD58MQ2!{Pu(iyjaeg)U2xt8kQCIJh(!=`ohM__)#gZuB2 z22zpqQyEk&0}XtSU5E--u2kefh5U4F|9+I*Njzo;Dg@W|+d!^s`%l384Ln%e-zg+< zZNHDCfK&Y&VbisJ7g%ztzs0!zy0-7SN>2ChgcfJIkErT{6L-450TL&nT-#?#m{4zR z-}7+R_D@QBcv<$K3w74^&$^nl@atDcM}>&Yz5dFWK5OAe{p=P##ZB>`@JHkQriD+j z7QQDgtMFSO+|bCv&qg?H2l=pR;a>vK)QG|#DHs<1T-dbmF9YUEJa)k`NdpW2dBK(H zsE(ttuwh-O@LjnU{_9X7KV{-LVpvQjmiaTzx=g$ej5Y&`Kg9zkxDKOCP^?UN;!E^3_=31lK}zszt*Rw5G#um-+%`!ZW5CD;-gqu^u%SccoV_}p&DWFonvs<2jR3n-2|J~r#S%C zC&=kcmI;RSX%lS9;v!(~$72`dND|57alw^haVr=kQx{^5d1qG5QDlWmd$vOux2;EBs(VI;y0jbx!F!YK=#VN(_+0W>v&g;9bb3-e%8 z7G?r-2OhiNB9yl-<-Q=eQY`S*Kly*K;L4SST~HB8!xtcWF==?rq2U++S{W$%8V_iA zU6Mc=C{`LgaalB+Mz~dxH2f+_XOjy4>eBElKt&NWG=)T)RDal%20th$FElj4J5Xtu zDY#NJya)=3FhmRR`QTD{H^`CxDpc5*Xj}ML1_k`(Fw3 zri8g1VYc9L)LAz9`xzo#(taEw>krUX4s(7^0jm8@5s%|i6okl|0;q^%Pm1bOkw|)U)ZJ-o? zi3bgIBzV<#9>v-~J+YhrtUsB59R;64xI@tC_13X}x&74TusK7&JPbVva(e3-f?+@P z2yEIwzXj$j9=qT@NdtT9LxN)i{Sr23_FfV6rsHuNX!75TkhAxWux&A}TpQ^1@RQ$G zIRO6~l52rEbHLw7nBY?GTw->cApDoZ)2VQ8`{$s9-hxcm3{4IeXc_c`f2suK!d2sc z7&%w12EqnTczAaRkYkBFg1(STxpOFkkh76(5YD3TQ>UX`1EH1!MX%xkm)}VY>?kSL za`41umBVWYw*qRtayW=^`o8!PHZ6yJ0Iem+DTnxfiD5a^gH6lfePBMpV;2ktQaj2% zf-6-HM^RXxvA~?^V(D^lOxy~nDu|FGp@`yb}49nADV-W6k4O>UTGM2BsSpFpx-|j#HzJu85 zHNKYCQ^ksM3Z4p10%E@LU*{=l2eB4>f7npAoCGfh(gMVsMp`%lo+v0zfS-U(6HL&3 zc)STPK{^5UMD7Im6%nx$@|3>h$NQq33SJw4 zdh9<6+M<1H1#b(fbA+h4qv-|^`|=A_a93V(%c$g8`7S3dYbbP7tK+x&Ad<%z<-h-Z zCoHUr)z@i$ittW&(@ZP}lBfC4Kgs_!;{4;3rO-2!tlr`e19zbndH0k%;j>7@g;(U0 zA7#O^=KcV1G}35p$LV#}T)9VB2dCUwc~>CiT6u~42@fjo8fk3~PV28H-Gg;~7OW>_ z751b#I7xp)u@u$DA#IoWa2u+65dV@a)n~0itcQ`&`waezp?M(#Z{jn$M*Y4SGGwZi zTG!sZ8Mo;HD>8-1=|Ol;vr-$0_b`7HYGbE=apwX0iXcvHjJN(^c&vtKtGORz6N)TU z!_+6tRfuK1SqD#wH=1#dxE;jNH=&w%687Q@IEw-2=*#qbQOSXX#0Ci}={k!l$pgiD zQ;FhZ6uT9iBDNbYg`a@%jE2>zPg9%qk`;UbY+Av81t=5M$nC^;2!@^bN!YX#C&mJW zc0rb8i!aj}<=i^n88#^6)x5p{wSzMI@=a!)widog2Le%K`a__-_iTpH-v(nq;b(|o z62z%b;$le}Jk|lR!MyvAisn-^8KNKIL6Q6(GR^v8z5FR8=@&c?OPSvJ4$5?~8P)OtLq(u|JR5_EX4!C<9^nJIq+-^@fPEX zwwVR+E07>foFKy(WQq9#$zE$>B0aAIp;_=42|OEamTfGeC6eV3c83R*;VYQ1O@(bU zUPZwx%)(f}lP3nm4&M+L(#_}=C!x=TM}`jTMy$-h0Y>1RxdnU4pbF}+!G#Lt*2 zkRS9T5Xs_)e2HSRye|;zXG}jLLVjCKdwfN8Eg*YYR}T9Rh{CJjc}8OH4VxV;3ZM2F z>jNNJqN#79gE|0@sC(nM`?$sw!GUtwY_5ucb^Z<=P$X)$qSoT;M)>ccjxztDm^EfC zJUnHrn^3mJxDeETcme`^He)4kck@T_PUaJow^VaL_b+Vwe~g?)u-q` zs=qhJIt^(TN^cAFhU)Dm2_)eg(D?f#lCa*K2WTr3v({w7GaCG}4E%Qlwwvbg*lxo3 zyT!PIL#8v_?yvnkRD@mTVzx(wT9AQ{Cqvnbi0WVfC3)fYi1zlgO$^#2j`o%$vvr?^cAE8y&jbSmdB8@^)=0juZ-}caG zwn|o}Yare(HEE+%BZ3M6>iix0Z^$2n9QRyd`xLefQi+J!O!f}Ntd~lpN?3!6%pnN0 z>crq*foavL23us+xfE_KW2!nuRkH#{(!_Br#Silny z2%Q=WxB>J=7Vua^t_8dbHe`tfyb$;x@g)lw|1%Yyk%hZXsN4bg$9Pg>%8fu_DV6Vt zVm3-rrLEEhmQAO&Nf+bMsftJ^6>TvtKxsXTXq48d@+E1l2lqO|>@&nsJji~1q%Si2 z{Q-)|zSeJIKPJ9p_O}>UP?Cc4=!!oB{0BU#apmrmD6(VOgi`T$DxyF_n!*}D)vt>u zHM-ohLewSjyqoe3hFbbU)&&%&mM^#66l-{r2+NXo^pJUH58j=hB6uubhx+ckygWvO zi==6!6&m_KV)#;=WTicBK6zgPf4`57uOEI7@NN z%pQ+V;NN4vg6|sq1z3?8i)0-zx6pgBJ$g8|yNhnYzt^5{6E1(*R8c!F3W%i^EnLw0(I7<(}bI0CWaJaS|R3@Ro>X4)7?} z-rN(rE%FyptpmIu!p(weZw7NDktyN;?;LD8z&lqThm#0$X6e-`62k#rTiA4f=WBpn zR6KTpElK16?|Q*;mOc+QXSHMrK!pT4v-A@J;utS3iLJ_&>o~6!{N$%3wnK6^lZpBE z42gy$_5wypd=oZwbpR-d_f{$<@d^Yzr9tP$xg@>|fRae@06ZY#ebG!3DOM6aaakk| zLAXSWjyw`OCA%cv0GpCH9C@x!kVE1_f+2}JU{eyu19KC(Dd;LmB#A!>t`v#S1GJUE z3y|o_mBgsZB}kly2So8U^3n2G*7jORimx^gA)FjPd4SotEX zOOlDZ>~6vYYvPv@4N1(aN)l%Qpd>y6H@j2ziD3j?p+Wm5x+H!JfRae@MR-8O)1sLq zQmiC;;<89=jBrKd$E}I=(_9jVz@{Xg0XZiLa!8yn7?SuLY)axEB#_(`1SN?i@gu>N zB9R2P`X3~^awYL6sE8nOAd-8YOx$fRmS{*~xe${~68pkdWD+p}P!gYqo3DA2cs+vV zK!Tw9Quz@=C6J=YctFC}qLl+>~rEk2;cLkfe^q`+l`2y4?|3m{+9kz$|zvJai~vSs%#% z8CVU5f)HZ>f}8EIJX#rZ5OcL9Av|Q>gL|tn`1>`qo`PSh71c4BOy$6H5}@l%6WBC(8f=Twv2nqS;!KL&Mep||A)MWKqLS4fdO5tO&U^;E zEl>gUL=Nx&h6)|tXH-Wa>F}Oda`T_zy(@?u-aCAb2YwZvRDYCCZw}l62PNaf54_kv0PxuE$S`C_1B|VuB+rWb%h%2Ah}IF z6j23{8h4wzGbHlEx1n$piz%7S)C@73;Izju<8F*uwR%rQ`;Y0g$Q#h;?IDqja8+2yx&T` z%Ul(J#{qQ9C(N{^_~71j?CpGP(vhxVSofVZ>z0!y49CgZi1SwKXbmoW%tt0|)1WH; zPQwl1%W4=avjz4yTl%euld)_#{W2u0W_=LlH&G8_aoRU~5$v@((8pJ<#$@>1I1~2T zec)r;<*uG^qvhM#5S-{QJ|?h&dS+2i!v*y5Mfd0lpYs)9Z~PE_ z?C9=`;ZsCCtya?~5Z!@3xi7%pf$8zpe+1T!Oo(q5NcMMP3VfgC!`hWm`*Miw!8m>O zi0#S9e76$Yi?R4VCAJUM``V)*{8x$I2Wr7OOq8YcfOWW7yUu`hr08u&>{!veg4hY7 ztO~Ic#oC3~>qPIOJ+R&)8YV@-I$HoMa$vnnl-*D3LSoC^aN|fT-P#CP)aFI*o(W6{OpTHHsBd#@K`$zx(H-66)Zuf$mHFV6t?RTty_wqmU4 zC&mM##CUL_7%Ml3@zDEXJZ#4?+#}V+C~P6d;{(NbV!9Yl-Y>?}Tf}(wxEL?^;u&sr zwis*Mi?M#N7%$BgW5eTOY}_HnrVqt<`ByPECnYfWmeXRq;zM-^*juy2*w#sm?W4rl zu|$klSBtUpuo$oZAjYo5M235#p%}aSh_Pp~7<(6r@#Y#a_8k^u|5-5(R7QIW*at5X z-0RRQsA@bZ90<$F5>@x=M`vcq||XqB;k~=#nKy*NepH zwoxG6i^S-$UyPpbiP8IJffS4qeiLITUiJtue6AQHCc%j9-vcN48c(uOnXiNuOMKDIuZGLFzZ$Cgqxq=X zQA^P+8Q+Xm@OX$#Bx=D3cmx8?u7flXX#Q4Z8ZA!Kh#B1=g~pgsVqCLNjPc)yajgkb zHX&7vi4DZKZjcx^P8Z{*C1OllBgXUtV%+?L7&8-78T^(;V$5nU#_Yag%$Xv_Z7amM zeTx`#4~sGHtQc=SAc;5}il&yM&BS;&5q)YP=KZ>29GfS`2bYNP;b<|AKOx2!8vK+7 z_*Mgar^xRW`J)CuqXEupM88Nxv4giVzStoX@#YD{4x28<@MU6*cwUT=uZuD2xEP~< z7Gq3ohyljd731n&Vq803j0sD{n6y!h>)sdR`hUf^F$Dz}h@D(djGHbNV@e+}rjHe4 z#;sz^yibf<){8M~w-~cO5##nKbi;wzJ1U7WH&2ZDone%3cP0LGn~&EMhOp(ou7ZWQ zqf69f#lADsvf}f{G0XNJ+W!1bJF=x61rqWWVbl~z2+wET+mpu{74w90yh%CUsT{wi z9KWs{zo8uOCdYAR*zg;ym=`}8Xj$x~4XKW&4Wf}(-(H zJfqI9;NJt+<1gQ4ofo5*x654x1^zg@c~6W519oc~w%vz@iFyn##e@f-%#RIPFkRsx zG$T{KOYCO63o0~cDJNEF@i;s!-@DJi(O@^cDjtS)S;dNG9^MT}LEM|Gm}JbXNm7t2@q|q}|uRS;KMGNeWMcGuyOArSxUh zPx`hH&RV9UI2$M3MQM(cqvlDcnWH+6^WvoJF>qdF`l62bvf3rReFvNk%>v1Or=-_& z;B17g8A|h$-ntyl#-^)i?wr))1^h>l=4OC6yCk)^4AiwZLq%2hq`Q0oUutsD5&5$E zBrTz{o8#=C^Z=dR9p}KLD^La%dpORaNrja5G|!+!d|4xtX6O2>ioKmQk4;+N9uZw; zhDf~QEnha0mDrwT>HBd$$}s0)gsWt?z6T%uq$l4Cm5x4yOeEj=0wlu>?Ue(`eFil| z1;>lNik;l=8w5(Jc^N}=ZI0_ROI1T#*urff%><>dW+i*l;I1q^^0{-JbSn^js@gGlr{y|Vy z&ycx?Qony0{0#rZ%O3`HaSy^54Q1tZgx|Rc@N=q+1DkkC6&W%;Kt^(`pMlMB`pX|D zx=-PeKy=8AK_8vm#V0t9ha|k4+=kCX*h_^RC8>~_sv+n}q#}8$N;!BcDZPf7`C3!Q zF_k7P-Nc~#N&a5_L+0z2aNRAH!OSD70n^I55l<(m;ovT0;tPQrr#KGAl$uiDka@Qs zV56lnnFECJ50o5%k)WDpj{#)4YWm01B(}(CsXAm9km6r7u^jG|pm^&92>(b~ErQ=F{=n;~W{8CFekc_8I`3so_&qFv&gK`8_ z%zFG1z!3i@ESJ@a;K=j8h##2335ww8t5gbIMZK8HR}{uUYjG-F#HfpbxLOe$zA3^< zM;h8p@+K8>lv_ghI(p3HiCPTof#c+0>Lq3 z;aZ@sxZrnLaNVV@#NhdPaNVu0r;aaG!U~ohoxb9I`D42EwT#M9|8CeK}mc!rsScUAJ=LO-WA#nB-T4}**3 zSIw=+B0hQR3TZ=$FaaU+Bq6)aTtYY*((nQanXWfNm?GV-;S?z%sSe^0gC8~|(Qx)u z9Ng_LU%3j1_Y8+$h7+sOhzv8f2M{|Y2b^+6L_$BLu@A^ho~IocXJgXz;a_(l{5z;W zr)R}^SE@s%`Mp5oYX&%T`>*a97#t>dQv@e<|3&1og7;Dc=X;8fM(L!l5qqC2v`up= zDCywK;8S)wx2k}XLq|~EWORk#1pl%S4QGs+c&fE(n8&Vw+%JXzIF~HWomJg5&IjOY z{uMbVnI#mI!*B}!OqYfLIQ@)JP{T}^2S5uk1i*1|u?CmFWEsQOgpH{U^cmVo-yZ{=#t{f%7-Qw%&Buj_xM3BfPN^N(-E^f-YAnHCUS zQY@T;47$Q$<_ZXg7Yn;FWS)6<8PYTU;SQEnzy#b3z`SCRsCPh<9>3866$0==F-SD! zn$b@}(-hqHv#foduvQ<$f~`lhdJGOHPrq#>T%SPtt%rzbyhz9^Aq2m@PbTIpEPfll zsb6_&zo;*KRhG0x&pyB zFyg7wSzU3#W_Yhu>7uU0V1H`qs;=bVSJZN;x`M$b)Y45|q2PmZh){ z!H3$zHCSC21$zyHYlyn)1s|l&;p(a%>`9#?)zu*Q2z8EDSHs}j)HzmNje;wvbE3K$ z2fI<{By}~xyCddGxMwm?h6^UrY-O-%H8iWHKsM_)c$+kviz~h!vM$fttDW-SkKpo^-lKxzD5mUy-R$L)`9hIvGyMby$j_% zycDmKlzaY0q`s6^04x{ZEtt-vJSo=qsO(u<8!T#!1)|DRHzMZX+hJo>o_-Azfq_KL z=5XCC_$=FM^ko$C5NsAm!SeXi0iavfVW(>vfBYOAtsKW?cx?yUE`w%B=FEkool2T~ z>BqhaGUZt?lS&=20*U1EQt&oRn^H#-fVi7pKk8a5b(Fen%l80KsiPS+!dz3c6%H4A zVa96;oiNwB>GjnDDs{re43n5Tr70$OTr|*lrV9OTJk!(_uzbycN}WClxa4w=!TObN zE$nIbCj4#2)Nt)9et5F;2k)kt*8&!$@21ZvFSnoa=q15iQMvHbDIDGh7CgcTwqFrJMXt*y)_1jI}i5Z$f}u zjNwXQJgYyN;VHblQlFAh+I94nB+!Q9V16^quS9HS&I}h7ixK*!%`ngS0N5sjEG{>e z287IuO8_{i#m$vSK_H7~F_canrzCJ`QpcJc5_mM-2E+)5gsLt=1}Y(Q8`)3w%c>Sv z$YeoFSG7WB9lD#;JRKl#-Av=mFh4vF|0ArshU;jh6Psa1qZ>$lUxp1_Vf!!ONAmHa z3|hJNRtx}FwWxiq3|U?+DXSb;HRVnu_!PW@<7Q(4BdE(jR&dI7aHVqH0;^t@ZvjwM zt1@`2moe9>xT!(Y1gzs#+}0osLF=r>GSGHf+1nhu9Dp6o#AOGsf!d0%vCjIk0w}*f zpd-!ZQca{?mQc8iBugliodr&Oxh5;VwJqO5BqMPmliSifaTV;%{N^6WO-xfYwO#*s+K@12B4nzK1ms3-vRo_Hy2Th=B|l(#mRM2pWVnp11I?ZeKz|$lOj?it6CvbFmILmI@fxC!W?Ua9vvbwVz;O5LK`R5Sf~p za~^^=78{HN&Cxf@fcw!W4UucwZVW{vsj9}nMQ-(PXg;g}1$BkfkVz*UGn5XleG45Z z*%J%k-_38h5H5*FnO=`>BCWRs|0ct6f`Auen08#K3#2Qo=QQRUl=SVdkQQ(>TPp%m~V)$CDM3MqC>=!I7Kb-T2qWXl-L6 zU(n;67xYJ~Ai2ho6rw5y$49)a*)ho5nii|kAXOQY@qbXs-dR-AVl^6}DhK{wRI-Z_ zm9$vCxaaV1POcdPjSbFXl+(Xj?ctfo*RvQ&Rm-j93~ji^TrCe3hTTi>J6xi#R;RJZ z;(|jlOsZDDt+*0{pJ1$2t-+<@N)En3S;KU31%r+1!PO{NT%q7FA{%QAnL#dFS8Jj% zv%*0JN?lx$yFQE9%m3t zl|A@-6?}OT;TAl<;jG5*fVDlEL@`6-EPlJaIE>PM_~g-+sm-$U-@EwM4y3srf}G*8 znVgQZ;I!fYXvZ62Lm>Rxm|={iaaH`~Y-kqXFXQQ)6=e;nj#wUKEREe*5^*m?V`-(a ztk75%AxI8n=3*z76{TY7#aKG=yX%al2=MwiRdFj~dB=;TlN(DrXzKJTLtNqJ<&x`1 z;Ukn+v0;6UK$5jLp=A;y?U&E2{Q>_HIs2GNAGr#D87JfGk0&iV%JS84b2ie66GYTy zgwwxq;6nj@7SH8?Hz5345f{TBq;|{mK@pM?79qwp<^Bdp_aEIG|^k%d@-Ql)k=xzJE z4uV%KdrE&dS~1}8mzO08KNmxG0(1~h+z`l2JP}rcEQa`<#gNb8bJ{~d$i)!9vlxPf z04o}g2Dd86Vu)WBL#WDcszaDVz$ogs5;f-jhP(akiUT_SSDFI&4f6csCow&aaFCe* z!SrI`Y{*>UFmo3K_ZJIiF=Rzq4Drii$Xq61Edbk!L89IP$zq6r-UZ;(VvuM`l*JJL z6!S9#xD)2&I1UvI*-Dbd5Wg;l;LxL$iN~RoDv=N_hWKSMP2N##0qTN$X!Lz^%ckqjUuRL8FX* zfY!?V-^f-KVguYK4m7~m=dCo^CyuFT-nTI};68Cok|ATLgrQ#Ta4sdq9As2kc8L4L zF+s-}2yve{Ce?Aqg}6@~Q`K=MhPY20ljb;+L)<5h2|3PSi2KAb)f{Ii#C_tJbjO() z;y!UqrsK>Gai2J*y5r0Vai2J*hU2Ug;y!Uqwy9o@iL4*`wh+!*rnWd6hqzB1ljG#5 zdFV8ARL5~%9O6E4%tdCcWUyU``@}H~O&7_2rx5pvV;Y&7;>-_mpE#zmsVka0hqzB1 z)7-QcXO|H7iDTNE*F;tK5Z~c3ml|!(eL{TU#&mO>{X;DFnC^~qV2Jy~F+CjT&`=?z zJ@NH;=4fPy`@}K5oivXPai2KmGSgAw9dA|R+$CmHy3Ac-wpE6A2Inp@+i689W^nEj zvm;Ghb_VAzF|TO}2T&@5!5Mji<9V)00Y30O0@iaWO{1oId0c{bW)=hMV z+d+RnICHLWVfWL&0ju^k@XuwgT$yQ@HwsSr%dfIs9@?t>0&LjKWw;JMBV)|c8K~pC zV>YmL_$muLOQMab!&h10IdxbESE4Aa+OxcO&o}tA6W=}VZ$+Zd>NyM4@myt~CK?(# z=Hhdefm-?Wi8xmosNEkvk>@G{b;c1Bajr7ZV20=^K35rNc#r5QK35rNTu7gYbCrQs z>**75t}@Vp>5+4lfsRawoU06UVhZG3WuPmgmUESX9*k4YRR(%8GC5Zn=v7GTrwAPA zL-lg5GH{jX<+;khFj2;Hm4V@6<+;khNYTr4m4UIMm**-26GR!$RR$)CmFFr0*NI-9 zs|?&C8hEZUFk1jTR~fiVl<{0;U?H(`uClrHU;yu9zO!Q+uSbDIJEziOn?DbioJxy% zbWSV;aw;wQOdAw$w4B3?;W^BT4FcsyzmLghp!}Hf6=_^EQ;hKsiE-@)F(w=kW8xQL zT$h+c4xwM-6^P1Dw@}eqlt>8F&quK-|-RQdivWN?3{u#C=syj9)v$h>goML&RKY zW{A1naLF|`?sfke1d5H@<^NL5J^r=gzt?|2%s2g~#N6+^Qf%DY z{_bKP@{bksu>W>3zxEf3dCI?8%y0aM#Qf8LO3c6fF<4`ajr-f5C#K)-CZ=r<7qgr_ zP0VO}v6umSm6$Phk(g=rF)>5-88NHbfgts@vNOfJ*lsRnYrD6Y-R!YqcDHAV*~4A| zGY~&`tr$Zd#ke>SKkPX%hVK$%gdEq4A9+?>qsoT}8C^q+F)hUyJ4lSHZx!R(hs2n` z(_?}7NneU_T{K3cf%xm?xL*8?oy9eIh!{7G7h}rpVoYBl#*8&$%#`DL@wa>?u35i| zF}nhW+=2Mpn~HHqM=|DJDaQOMG!i;ID#pU4Vk~-2jK!~saqmenmiRDQ4izEO-FpNaA6KVs~xp3MNSw-IC4P%++^BgXD0#n|(P7<*5M@#eo` z?5kdr;r4eF9^I{xHMNb-=5Nq0sS>6m3GtS&1W>v%V z#3ocTBquf@(~y?fge*fsViRgR;c}dCxe`v!q{XZ(w2-6<1%$!u0|gk<@aH*Wum`o ziobE@#BKOG$dQ5I%CyFdD1JzvNmd~uOrV$iu`2N3YjU?MS8`loC3b3JtnAKh@pqK? zRNzV2%16hkxZ)d4aq;6<-(+=0R|B^uX)w?&2KXxtX<)Uu%KsqxK9J9mSI}8ZwhWgcX!2Xsj~@Jq_tk9s)v6L1UdMXmkwn zf=7c}sWJtPl_@Ay`ArUl^#~YG{Z>_txxZ-#zs|)09ses$fB22`{1c`yJ&tgYnGC_~ zV&N8K&=n3dTz`C|SU8U%(_{)7D^t*gOu)+kyj~0v^$tj;paS{`fK$aF(NtBYps`cT z?-1~irRF$=RR{}zG6jv*DQFs`wLL@vRU#prg2u`ebSXScJN)TPkn&PZrl7Gh1?Aq1 z8CWc{((MeJW0?$_H$O6It!~eBtu;6Wtu6rl>zpReunP&<1(KZO$j%n~r z8-!j&%6#A8%w)>F#5r5VVr_w&Tq*a9^*|F?R|-})kj1w${*z0}b5xdL-^xgIo}6{~ zS^OI?6HNIKe%a@q!@HH!teKH5Nz4{C$C@VJm z<7XhNK^4BN@>WgiKaHmrGxo1lyHnT8td_HXflqW@%+!qZiK#~^^?ie!RUJ`>LEl2c ztKQrn)|^>s=?S<5*eni-%6$a2AcIyU%Bo2=JHsK$Gb~>saA}z#_~gpYcxdX)48@)C z(DV+}i>z>GJan@Vfo-nbr_j*^s%1Rs0;^SbfqA$vT&+eA35NZ!5AyMO&}>GTmz|z- zFJ>r55GKqIilyg@bqzX;^gL?Te18VHBrVJGEd@S3yaqnGn=uEp(=Q6dBWYpS)9cg9 z3}x8g1K@k(MR+!#H7}Un%)ic9I|0aj8R~=S%^!umj-B42H_Y(WYXI%Y0uHyp%20Zz z1o&Fn-7)!2Zz<)D9P=P^daFVRSa_`{yI5s`?89`mRaad0byU|*k%@I1K$kBo*$S^F zD8D8nl!!Uq!-mm@AoK7&0T*tcdfCun?AtJUB;zwT`5fxRdXe3diquB zO3WVK5Uzph3TD698m>Xwn`dVCLZe9^tXi_OJ6#Od5Ow7^`5#&faclmEF*%z5;o~g) zq?#Xwr{uq$}bpgGTB%JR1L2B4B|Id zCcC-@`_KcKj4lfyX!y!7gt(L#V|**~eO5*{V$w`5-tied&UD9?ErmnyXEdG^hBEr{ zB(M=bJSQEfyiZGdAuUS*&#b{eOhV&Bj5@hX6z`B^&X~&=cljrD=Ces>K09^h^P0|l zUe}q=8#?pZ&6!UVxfoJjE{2dW!wFCVZ4mKdNO`#!LZv2z2t=gv=skJx3?%%aBQd`- zqOxT~6{w!~brjN5J-jIzJ&N2RiIzJg(Q=2R>B2O8tFT5xjy9Sd>FmSbQzNhq(5%N5 z_y(BO{533+)@a(c9%8^349dD;62)sI6`QYyf)*89yay_*oIsYGeBrD%n!d%p>m1n&>9GvLv>jU0o?it;hpW;rqZ z1Mx~2_=YEs!DOWvo;o$0ttS{19(F-^3??gNBp9dfu0M~#WK}oJk>Pya_2)5|tg}A0 zIKv5kaZ(cg1Xlm_MgT0Uvrc4H^pj%4Re%J>B7YDukHKU$^G#y}TpMsB;4zr2N`7)| zxLAa9u*igQc_BLC(Zv%~1N<%bA!goQdJmMM5Dmi#IXP#AH1syf>h? zq=znLlS zGV&7r8DWCh$P!Yp1-_Z21@zqp@CfCDJ%WNMgYY(%N~&MlHv5T)w%taK$7JOh)?~xp zL!*zA<1txB#GAcI>2$}*@tCal*E1aZng0TKJSOYKWvoE#fr%PS3eV6JA%ztC|T(~t+|YPND5JTOrL$z)n2DGl)z0xrF>?(lfi|m?X><|%<9!*}rxqC(hE&$Z zTnf+HC$vd&rO5TKOaCgWiz`R2|7Doq)b6PMTuBmtts|XG4+>*^gK(BmBH|L08}J)U zI%`+dfLvly|4ybM6L+=mXk8}^mz`YMyVQ5J&xd>o{alJlpbeR-i|H3+mt)!`^mBPC zfi@7)o#94mTwJbl({Qkk_=_$sU#YG(CKkJLz>6L(XQ`e}<`mOB-Z$CJ50|*yw7tmq z$NPr3Y2&h&o3@V#8mQa-B_-x~c4jc{Bh|AqS$J3vi-cqlhy#A<0=M z+PNsFisQ^_RE?ZhL?_qiR9&3Og1VetqKQj(ZhoI-I$!Zg1LP8(o8L_+@Y);IpG$gf zes|FSRrTi*pR4CN>UqK^JrtMxTsI>M2rx$rqOpT|LjD-sUvYhQlRASI^HVubh@f^l*vM)$<4aI~dW!HAmGW z7fEv)Y=y@qvO$5elqpBsdEnT|6% zpBsdE)g5O}J~s&SYBd2Bv62=gv8izHs>B57`WmSs*LESE#yMp4$W!~NF74D)hmSf&?Y zUJeZp;_OA|RN=n;C2LmpN@OiOcq#BGXG<=FhKKOjW=>okId17kY}w;xLvK*Yva)&H zvQ8@Fk}y1OS*PlUbn-rH-JDbe=`8nIIW6eIeayT~xw4O$w`~~paUU~pJFT48avw8q z#~5+h+1DVhyw@~+0lcmA;GbbLmyvdvY_J4s6(T2;Wx*l7Tv``j=L}}MMkLQGhHgX0tH$`=D5209x8w<~1=APCpaC<@gb&$%$ zAf-HmnVYGZ$@UPmvDjc_YL0jYGxtaBCb>1?#!y6(s%i|}t5E;0at8CFy25E2IfI!y zL+RiahR}hMDT-|*L(BN-$rg~hwql&)|?>9n>HoT$yNv^ z+Q?1q@HoZAW&&4oj-}u>a#K4zT8q90Vf+InIWRI+6K`sVm#d~egoq}wv5~sbG97K? zrgr!jP3#ncBYEXb?eL!}T;vK7h&Q#v1C*EbUJRn#C5Jb)!*djJh!B|@xl-QL4k!7g zHhfR1R4=E%cvCw(OoLXa4x!W+2`_c8joj1@uU15ZG7-F~9iE^F?ma07UJ4T&MZBpU zenny2vMWxdi{MS|@YRaA-$OXTc~d*QNrf9q3tz{OBs@`z;XMl3_LN>J_&B+v9bO@o zo_m6tM&=Ve3-4%$3#I9Cqp&z(knxUoc)Q5BdssroJKEvJqLW*SC3NzRcKCPcsJYJ= z5w4Bg(GK^~3GJO;z+%GahibM6M&>g7>Bc+Sp*y%ynaw-ep?ORXU$nfV9h$E$JDYd3 zLwBkxkj*>Vp#|!S%jO;J&|T_E%;p{K(B0}v&gLEM&_ZmP)vxTpAH4ceKMhB?sJUj);VQNF(oPhv#Y6#a(D=^zi2$ z?QjS6=eD$}miF$1C^=JKABnqs`PB?v!idsTR|D-q8;09c=+{54|{dR(H9h z9hN)VBIo9M2?e~I9o9SA0^qiLgn~|TIXkR(v<1Lb;9?D0RofWe(GKs`X&QIx72%XU z?`Vfl>KYTb?~8?Q*`K{0h_B6hwuQnn5GC(uH{KZyT;(IVaxu4FQ*L%=4=ltMZA&%) zb`iXoTd$S6>}+1lt=C>%foxvPt=CyyaoN0>Td#|{60`eLOILLzXY*oiy-U><%x*$0 z-P9Gze$c?xU0s>kyqH_Bhq|(}c`>(MPtF?9MP&10ZoOXW%FX7*+vmSG{ar%&j+EUG=khF}L1Gbv4N5 z#oT(M)zvVY7jx^4Rac|z71TLVU5&H5QRgIeH9?2Li@Eh?GEau*2&AlZpxIR}=GL2a zF}zKN%`*qNpJR8))xHHgQJ5y|(bViS9YK~kBQA6IQsW~Qc^=_QAddJ%| zHLr0byiHSce8f^77Y1Z0j~1&z4^{d9Nc-;iDvIyzJ-hc_0;Ebwkdg!f1VRZdfPm6L zdI>Ecgx-6JGy&--y#$CN0t#4=E?opgtRR8{q9|V*qKFi`@;=X*-J1aV{`1S{Gk0dr zdFITSGks=v4ie$j5)ZU2f_njC8(97XzE@Le!28OJN#J`ml?I;GSdj$2S5s+_$ssO*yZB0jO%90(e6Oa`5VPSg zm%yi7Dh=(eGOH%=y_!nHhiR-v0^h5tl+iAfn$=CX?hmjj3GgpCs&kLMqpN4ZMU`8UR*L@1|j@BUKQqZ;I@*Duh;Ua-E>11wd}0q+Kvc{>q)k1e0{WBS{x8$voUy zS57l|h9ungFk)S+s}(~NHZ?)4n~6o@;{%m@K0$GB)d#tkIcU)W_uoqLRi+(aRvlKt zUw9~|@<6vNnB?%U`YP9^p^~oQ&b@Mj)hJg|CQeo=H>bH;_ZT(Cs@$GNNs6QVM_AaT zkJ0uj_huoIl5kI3c@Pz_5;F1NbLDED*{szW**-0SSPid0OITThm#7g#E#0^^ zffA+Iq>5N}fNBkyMRo^#v%N~{BVfk*xVUOF3_oVPFH;TU!;@7Dod%_xuWGSX@RMR8 zxoTWH1}lSIwfIj6S_$KDxm-120>bPeJ7C?a<@m$_FVYL*u&=7#;W{N|NW#m}h*sv+ znNwnpSZyvNkr}i!q^&L1M|ER;%(~3S_{e`kwWO!8*iE>Nx~W#4&pRNW2gVNUV^yo* z*69QN8LMb|R7k=mWK%8K@In*#zc8y+GQ7xy$8pkCO`l=LwY~P|YE>4X7=H#1wlP-S#Nw|169R$iWiL~) z&KORrmovt+5{3a-y?kReyPd%QFHyaMiTSKn3;C}EWO(t4=p*BL4zXk;CAQYL@kWuF zG!V0yj80^*E7XxO6%a&|VKa&KF_Tyy>%!i`C+#P(S;g_WIlCgpH@lQ7_&CNIdj%h9 zvG=3K?5wp&W^b*4;45hmXOBW_xA#v(FxEE>zqJWign)T=&7OkU)V{PF#72$r2t|nP zlefTa{OnC64hR`&0FD1bf3S18QJ>ZJYaHp?$K;u0JjVAE8i3?ohi6tK?;5I__pDNm zVN{e_W$?I#y~$pWp=+8>7ET-npnFX}1NYlZPRz{dyEF#D3fFH0D1J zvETK33j7+2=zD%sD?ZC=mxP*^Cz#ex0}jMA^8)!It}Lmpz( z*LWE8v6luo?{Z+a@)pK`CU}ONzZq@Ny&mvEek-ihWTogsV8Gqp+m* z8Icc=?HRae!o=z*SIPKTpAjEQ+*X=*a46BUCIN_q}tKcp&iz?l) z=fjh-U{oU0QyK~=;1w`;6W}Q^9D3UUCluMqdtjUmGQ*j`N|OsTPKfgfG|@V~4#e+4 zl-1Rk72kFgzK0hBXM~4$M$qb}PhQ#uoUX{BHzdSdqba zUw4lhudvjMXd~t9x=sc<-XrbVF&a2#nQM1&Ff7}fm8DIlEyi2>1&0qTp`$n*mb34@ z=uj|v3YrAFwcW^(w~)yPaM6<>Rjlq3iCM{R=3FT3sNo#B4DKx=9w#E4V-R3kOyu6EI&3>$c%%oFD5T^@m`b&B;{JYn>ZN zEmy&~mCZ~OZC~r1A24RA=m@6<)+%VAS# z2SgX5R^msjblC^v+8dn(_}97|C1rRv)2hgNi1iIb#l-sNfKkx|mm(O)c&u*?gQTW@ z4Xn=|YY(V_(WP$*NPW&WO~XP{*vV0Jye+4IKL;007)J+XOt9q&h`$CIUKdQ{oHfaA z(a6;<3On8yxaeV;JWWn>uzt)g;Hh63%$hj?UoS;#oN5O!P^%5wgPE2SFdQd8_B6XP zrYZ%D0dr~);3?7@8$SDS`(v*Gtp?)xdr)IX05!v|jdrcZJPgEJM48g2i2`QYVIJU1 zFnI!Tw2KrOKUgs~+H+>Q4jB4+@x&|ZX*LJora_C1KH z(8gY57cLIOMR2d&gV@a~U1>i_grJ(k;7rLqZKGa7F3;L~YPi~#2BHd4+A2I$1D0u> z-4dOnGh22`AiCUz!Us3Vb3L?YE;wR+V*ra|F!c&rb-KO5cexf?bu*}Bf1{69VF0u{ z)P-pKTVF$9FaX*e(%F~3(_J+NK-{Ia~G$(2T;D z!*-aXxMZ`B_-xq<)~i9b)k7|^1V?>0v179318~k{bGu7pG$i{?UwN$WDBYH8;Qkdv zn8O^*7EFE2_XDhNV9^iY;vCM^fE~~0d~r_5X*i8TMfwb zcfs6-aMS0=Ua;QGX8(bpw^+I5`=AN_n+6N<*H zf+GEnOa^OiHhTwxUKyhN@1p4*0>zQFcR`?iUXbE_d+{4*g8WT&um(@Ji};fsyhCyB zYwY5F`2m<*b)Y!;Vj7gTFRd>Apu=hr%KA@Z<)uZ4M}ov)B5xg2-d`47ULFLa(LKxx z{_9-FbOob-kQu%f;*ngJBNhFFU`&||?u;M;nd@>S*}vLttFi{n=duCra-@>K7_^i9 zV7wJ%ddra)I8s#cck%T95{U1Js>DKbD4{iK!TNuKnhQkN9JLYjtY6z7iixiYD2^1n z3j*uE0Yk?6s)G^7V7#w>c94YB+*%P${oLW@XhGas+Rgnk7Vv2lOTMWHtW%WR$}da7 z*__S2tA;w6Jy{oj-}-J19R>ECARbnn$RV-2pa1$xtMDr@ujB;$nt&}qZ~q_+y$bL{ zjZiqF4{W5W42F$jK}`yB!bc&9zN&Ni5dS%hLX$ypq%nTm-399X?m@acYru3Z zp-sH+QE=i+kiV%Bu-b3-0)He9<;_xmt)B}&bU&xVi=4Bc^%H29DCcx2#A;lpai_$S z;&gbMdxZ_U5qC=b077>xHSFhH!Zi@)VpOo7cL_HIYew$!?Ztix)Wr-97tO5kZ~Wv8 z=fS1^!Z`bp5@3|g$&BDowamYt%(`GS$;lkU;cmIV8OAYr1dKj8nX9n)w^#UI!r_Qa z0ApHCrslcQ--)Y|Ofc4vS}4Nm zSZha(f7)->72KHdPr1#Jj0=KIILxtk`~N~gwCzm;b52gcDVqLO|Cdln z0qelroDFd6X0QKg>;>gDFplM9s-5=vvv4*h7r^*mPNv#vzrO=lm%oEy)ekDxMbu6Q z{AJKcq#zhYvze~ehy3l`*-@&4`5*yp-D0WMuldhmeWhA=2D3*tz}5P&Kb4A&1!Gc9 zrfU7VzZBLKvILA(Ihm^U5x>LU^a>ceb23%yqy9tDV7>>&N7>BoqRaCW{sRq-QVx!T zF!d9mwGrM8%IgpMwARZ>|9*Gsa^!w6OToEVT_*IF5p3Qc`oq!n9jSR2+o~9gMiT3b zhizkhoxqJ_Fy7aTLBr!|S|9s~5FX~0X^1)umAxmxPIw+2T8@kW87(TIH9OZ)9#~-A zn@|j9l{W~(s<*E&ne3N6h)18nkAyRsc_@w`=598YV-ZW`VVuvdY`1KRmyvi*g$z2% zugJl!hVT3|#2dnJ(PXoQzQ#3jb$c|5$TwA_1ej$BXzv2TX@eSe7?yc@qS6q|<~b#N z$Fb=Fy8*g+cc$qJ=8&8c6j00Fjb*0-W`Q|Br-UNx1hwtv81x2G!bUK+Sc$EOA@gah+9 zxL~u$#VuiL`+KZ=hOX+A_#74bNrw06QJ5 zA=&JStP&i%4a2){>2?R~3a5eM$ZS9s1YsVcr@a-8X|^IZgS(XoW6d6B5z@2VoTc!1vUpOR5CD0!v zPc7jtX|TIr*+Mt@^f3B-ig72_*9EvZ6YRqv$G%t}f8*U>lH(PJLokG6ee(%qFm;Iz zTi;0X!-j1=UqRIXle*)C99p5a1bb z1v`s$0KHd`_g@CA2PI;ClYxt4Fn?$WswB{<7+O$)#`uU%Sa_gJ zY>#k%)ISm)V>K!jTan9=>cB9Z2lnWj|-*1 zM|n``%AW$>tZaT^3E++~@a0EwF8>+uo+n=miSILfUmDt7`-7{f{h+@Uz9E*b;dR3Jni!o;g4xD7;JDC!zfQTj$QZ5<4tni!AuJr0Y-`kuybyoTd7 z9P6tO5piTzq6A+cc?k#!T8Wk2N*pMkeU5MbRTCKv-W29Zkc5+OHE0@#3q#})3?QE- z;0)$yQNu18;K0(lEe6w)IDAP%fZeOZ98BEy>OgB;?C55P_=wgnO&VkAXe6l#MBN|?WvMU_fYgX-P)Gr3VD`)jcoCgi z`b4~pdQziK1ao!}VALHhk3&zH7qK6gC0dLT5@-O*%7{1W!W$`1v#C8D(S@`0$Mr2^448#PL{^SEkO_#kfuYDfAF@-d)h zW+S`H5kTZnL^qgy_{_h-b=62{h!ybVZr)rw$_lO|a0M=a`r4vC zk*^lL9=CN+(~)~`d|vO+jLE0Z-+$$+&xW?$b^7L8Ge4T%apjPFhc^xGGvW7MfB*1y z-+8UON&a&~0=;|JiTLAISjhb2al>kLj~v+It9t2YMvd&h?!&K~+D%UTn*TjB?9||0 zd7k@Y)2?bmR&KBV@!R`9t^50dm;N{8Y~``tE;c$5_VI--bv}IYrQ~y^9;!dqB8+qoZxihzojNP?6@Z49gJyYfMp6}MZo$Jx6zgrOt zHsxLsvoie4{b7Tql&>>1By&ig#nP?!H#gf39^9+vkRoT3`_61-^}7D!^1zUZ&q?9e zZ-zYH>5Yh6$Ifl-+vf7C_kF+T&=Zs9?EULv(a(B4T>gB48`oa?$iDDKJ!)255j-{ zy!*Vd};@YY8A+rZumty}M2@HIsQ?Fm&?caCm$dn<4z6}f>Hm>mLf4)fiXl~ks^O5g0 z`>g-)i+g|n{ij0<8XS5x`pkl@>EEsY_~XZxe)#MgN6yx0cl~1PpZo9suz#lm&wm!! z^-%Ma?M=@og`I6tIL|A;G;>nYC-~|e{VDxohl~9;{j^|MrSXRbHhywP&v);i-tWNL zQ^QN9TpG}Bc?P~2*(C4&y#?*!6-)U$9ICbN&BVM1w=YTCndBR^qua*YpB$-l;^eL; z)|@L>bj#;mw;t(}RqA^0AD&u2Xl$OPL+#Ch+)q7}5`JZ7|6HT;b+Y`AH+yY){t0_7 zZAscTu}0zDp;-$~EeShx=Id8~x-cpJ;-`5}pZaK4{Y$5R{%yx+1BOjMANzj6L({sJ z+WX6w8C!>EGey3KTU$?vxb$d=*J_=u-hRu0 z&2O&R|M`>?+nZdzy(_uM^@9iJ9ohFz^3omcpI^T-!Jl$+-_pP*@0aQHdFpHZ&y}b! zq2G=@&3e9J7as7)GJFK6`k}l#pIs1owD3iL+WepF@-xg3qR&vykZm}|^i}^8Bg0G? zX!&Yz#J~gP9A7wGlv<0}Z7YsL4PFpLWEKW}j6GFD1je!&!0G76fXtTB_^J$eyaXKI z3lj^%oS(+G;9)h=U{tf>cw;+D3gUKE{`5&2QVzdE%%jyG!{uu@*wz&Bak#vahc}9{ z8nE$)IeK5oqhWqt2w_Z8RBtWV6&ao)r?{B;Baf~hE(BBkkt5X~nreJKt|Cns$+ltC zl+t-MSw2kZCbQCcHLRJH&f5bSm}Dl5j0*u;k@U$tG_4)tQ~+TdoSKFKcao|dG7*u- zWsW?D$=7Ze(hC!f_?_f{&zdV=VYgy83gP+ZTygNIy4^U0kNm@A&4G*K(ds;rGg!LV zQQ~B9StF|;aD$f>4+X@^;G#mdgUA=tR0o%F7;~fZE{LCa3_jEgTudy?EtSxRt6u3at4Dw-P1v}oGqgUjOL?Jv<0-~ft3A?ILm>0!9y}2 zIfjlno_A$%&n5@KI_}|2S9nrlumg8)fg1c$=QQcjqoKGfel3^b^}wGb{DV59yR z_Ug|KYyB~7W$-lKnF(Z;mnQ=laR*`;F?NY-iQYd;`1r1TmRq)i|Go!iKzoM{VqfRh zmA)0n$9FS$q2PQ0z!eXzqOA<>Fy(g;eUG^1WB_f3+tMlW44ZDGDPkfRrihWIh#B1X zOA5#Xyu@nwY$LHT^(+JtOT$bPKfulO$}qMpXtk*sv>J!B^MmOT5Z22GoNMVZRvb@z zGI*}!tOfH$56J+R;^gu+#5n}QX^-m~4!!+Bn_EXKgQxt?CGdZ|17j@^*@Cv}|4k2{ zi*?s}VtAVHiFiYwxIrO0ac1zC%qa(8JvcM+LS)WnnZbwboYr8cc@P~QtqeX_=L{h6 z4u;wAPLXU008;>J^lw0Jx8ndxfh$uA|CI=!VfO-;NTMFt zu)Ed;G!w2T;M)LQD!O@nk38hQO!nX`c)5Jq1;zVtEUNZ7068G=5qK#YY8^$Qvv68t zx?9cejMfUF%(akz6fS@1fOQ@5zu+?ED1KSKl_K}!Oh6hB#IE@yVBt7}X#r>%OqZ)< z^uYe$(R>825UxrhiGZ5{R0E&}!e#2x1enzdsQ`9kI2?RrDdzyNmi3g#m%P5c9E*b@ zZkF2+hpu)K?8?1Ze%;4k)|=qPo;fZXbNE)th=&^@HTU!O;*h1Xo2NsU*Q$1*%jBdQ z%g+cxLNW6LPIok6rm?I#N&mR5Q6<9 zLumgRTu|Po6)usC$1@~1hJZHEJdFcInSj*}ax-UJRcDXUnv0udZe4};$gJ^vh7oqFTg zM07SP5W$j1l?{MU3DpTS^{xoQI^hd&?T}`@nen4lP<^o0%appnR#xm_5H{!m3Gw{i zuOvjIAd5`l;Yh$ajDH033~IV0V$C3qBBgFbrtoaUW23E#G{7O1)YYLW9iSO-3nBe^ z;R(tj#9oGb3lv~`V%H))r7xPrR!~pF-3Di)$V=QVWay;y1*q{*wR%#(dJigXl3dM{ z$z-%V;DZXa$ra#RCo=(m5zftOyPMUJ z7t|7S!C3$&c+Y|*crFg%{hHTdkiUcb2VxIqmtenF0_#PQ|KVs{-j-{C-GWOg7qEWI zhQ94VH_3c9h_^khPz{_+EFA9Uh8u=tsD^Lif%#JNjs!IY?s;%t5_yDn{Z8tF(i`q` zP?34@BB1^wBS3iru3-6qHMK7-t^0?6^w0~IUMKUw-3PZ>ieRBDRcylS#p&3Y@~!Jd zh?QCkbs}hi65J5h*1`TH((pn%4U+TqqvWboq_)kS2_$cluedI&ZF4niFZOMcCb*$O zoL~$S%cLpl_+=S^_ZX$C9YFUu0#WNE5<=_3t(T!_Rnk{;`wcAo#rhVZLBSlqVx*Gs zHe>0)PKGO3L0jdHqTtL>&Qwt6z_kLWm#R39gWn8SC9TsT+&O33?7E8p{Sa;z;ENTW zz)qH_ve<}`?}IeJ1{LrHpnt=?WAe>Sjkc;Fjxnilc0~;B+4*ku@?9nawCK8^e^blX z4p7x+6(q`O6_XATi{M6p*Rnq?tm>ck#B7ohr~`nx4~K=<$ta-b!L8RVt$eIvHhH3N z;_5_hn4$vo7TmkwZORsXBU|)o+(-i4EXozV4(QjjMdQ;suoyPeM(h8T06I$F3p)u= zI}FUFzzZ8dt<{QA4(ke5d{&-hmyObw%*Fw{LW2`rf%yzIu3C!3rs83IC{N}S=+5sE_y`)Y|pQPSaZp(tBrbWclOb@*m7WDbXY4ntRH#}V~} z!{U;@OwMMT?H$drs)}t);l45tx3&SW1eVG4Uwl&=mD{>n@klA8&q zaZy-UU!jNrdA)pzJ54F#g#s*nW zlYF6s|FJL6Q^IW!@P}^`qm9M-zQ?!~>zjq&6>e zT6l7E1?=l^a>AD>JhcfdwgM$OKVwes)s|B-Fo=44$rd~ zjd!a~yM-!dQ(slJUR9MSW|s7R5N4d_$HEWSUU1pl{qcHSGfhuIU=9{N5~k<`7hMgF z7~sd?GKERi9CYXo}$dy1k_=n+IBd08g4Ik>& zyB?t-yJhkyEcCMJ{MYmpX(_;~)yi{_bUCxQ8rY*&mP|FV+rU<-&MQPWm8YX6_cYfF@oH7XG#gU#O9yxfTJi zzLjHb0R4Sv_t)^dE#@vmismxoH8kYHO^W5xFH0;A*(9rrAs(wa+lxanL~*2!%cU=5 zFOJ0ctrpia@Zz~xPOCb{ks1kr)yNfv5;%*OO<6A)WkIN^`5Xaay}Zd;q>(9f4X&uC zU?4sKjjzKY>D$A&6WIvj!(eAh7DAX@_sAjyU;z)hLyq8}z8f$*M9I+lNFZk0Q+-s|}pg%~b&gF?nPGoTYheL1?#TvQ9jx$>Vi!c4!{Nm`waNnQzWa zUXiseFwDUXfb{iplZ(n!EoTD2>y&*7?3b~xmkzl&_O=HD1DPC$F^?hD%Q70*>@q$V zKVZ-g%+2xz=Zy)u_?-b~@md(P1s@ifq!qIOh%IuMciWS5@e-jAW(tVn$$`w$tU0?S zA=8#{myp8~CWlR$1C*Ky`Xacw@(D%@S*sNVowf;IxRRZ@wxS)q+Zy{R~z}>=K7F4Z0*`K_G;6J!hcS5o5ns(RuKdgo;NDTv^BK^VV^dQolqbV z0%UKlFOa{fwhXZEZW_z*k7sOD51Yk2@b79CFDNNzjjdMsl~A~JIC(vnk^MG+rb%2t z$ZHZF%*g)<9MdF-F-;<&*4<5lX5<@a*nyu!4o+LgY5-6=OxR%5y=JV*7IRV?1{(7+ z>8xhcL+Dd#%-Kl1T}FVM7s=PlDJJ+;>-iv9Sjd5e^-C{H{?5gZbJ&a1+<`(uILdqj z)La?OK3Y%-tA%Iue?hsJHcHHr7eMgUrU}*{bU#A)TPKUa{|L^NcSdt94{kQg=w?TS}S?^K-Z6M$< zm^hoy6c-*8fQ1-XCe3A}*&w_n=#C_P;H07dJVa&+F9f{d{1w^es#F82?2vGrd^fA3 z3oVG+DMb;t7q{3cWi*ibs#HT@ht$XKAmCPO76;owD>&)r&rNU*Byfescvx@JbSJ4;y}*R|H%aZr&^9*2odVWLeWV`)XX-U6 z#Iz`^lU9g8!Kq+fh1-NIszCfAxJ~aD zi(Mxkb+>|dYueo^6Q)=pO(EeL5)DXotjLD~)(gn;q-M*TRb;zMA(3R~MRWPnm!)^E z>A-S@!xzlt2fuX*X_}6`V}|E)>1$~^(|L%663+Tyfp@mOS5Gp-_T6V;@t)Sd!aGi0qA5~NP z{h$HZ?>7y=NwN8$Jexn2aOT65Ng!?5H zzal%O9DHZ-r;~R`O@!W1lWh~e#wyK2sOWsSPe6`?qW$1Z+q6G~+*t)-$_k>B!$5343c<{y}1l zzrhj@^h%5pt`J`OZbcTK!`pn;5vA>a@c0$YeUN`A=V1u z_rmF_oBFJgvbz)f%%jfH7kU0-3;M${HnwX37g1 zh}EaH~V`akj~%+;>^5H8>sN{?%f+>Y#x0bEiY46>wi6%gGS^ zB%HCBS^&Dix_qryHsoFl+^cX^8(?(^+@2toA+rnSYrV7NKr-U5=eACO&j0JICS?FO zPyA%j3OR_#VaWO$ZV2T4j<_>{CSe+8izgu{CLR z7eP4;r=s-U><&>(wiaSG!{u)nu+AfHO{6F$gs9cR+xHDF1QN4^7ws*8rGeIV!=Q~4 zb%2`(+WkmdUDNZ%8R;=eg4G&sryK%F+OVqlxhT1sJ00XF;f^3>DpHMxGu5iKfaIG* z@2Icp9W^FP>wxgV)gW507Nmd9V>zMq6*jd86 z<2eWc$tz@{z9TYEWDBT~CA>G@3jS)fjK{_+Vz|vh>B(9r9(jja{laj zoC>_JJC1&U$dUj;5sfu#J|xfy#qSR%r6N}-lFtKFGW=qI4goKN{G`a;%I8J&!{o0P z@}CCpWy8-B@_LeoYhuiF94mT-O~WbNNgxs)!M|V!v)E%iiPIa?UV38+OK%Wf>|O%u z8fEnf8#|eehj+OF=R02atQIE+!Y*lN3U7;pT(%%Dy?qVWR)qzP&MFrWO0@>1-$|w-m zL=CiB;vw1(GV_PPEa3%r18}pXrkg7*xkh*soea=+xUS&OnnL5e4yu}t_t_1=>IWxn z!>+@=nZg@v*Es9ML4FY;OmRqW3uhyGgC|CYGDe+ycNnaEduOCINY3LbK^#KYr$4)gLn$GjRf=v`ES+tYBxn&N4go@Na_fHG2GIb$6^VxCMZPO=UfCtpstIdKku$336-1K<+h_8wqeM+%Y6* zfdsA^*F3rIz;;a^Jam&6=Jw*2CXYkX%5eW6c~*AvTX!YDap#Hb>FoJTs`WrCy zkM-RLPDQ4Lq~;YM$(NV05s>mY-1CssFI$o?@12qi7?RwgcyU!Mr7Fbb)<-cHLDX|_ zpF`ZPY;n2o5|>-^&KBpzRon^Q9)#=DGg~3*SGa=BQ2*KD!u3fSx4CRD40t|;TRrfF z54beI^F1CkOTL`&MTG#5QFt3b*Tby=yj?at#)G?7G+R_3Z5_`-i)%jD04|Y^E3M`M>z(X;ir-cmsmX^Z5;o`CYz z50r7c{Dwuq#2Gv^g;;_kv7?_P-#_Z*Y`; zlD7%DNbk@#Fj$rr@+FneQXWRg6qCTiROjD|c^0hITFm?a7J&;E^R!B1F~8Fgi}@Eq ztF@RxxK~UAXE6!-*J2if_&7M}hm#OKDpC=V>Ld&Z&C*9jB3sff+vHYVw2jfB>EPXj zO9VL!#k?@fYa0x4#lKHx(fYt#qctXmP68uK_{{JSB*Fn~7!SzSBK{=e`?Tr_j|1Hv z>kL#ltDo#Ft^Zw`um%9eGK9~93tHxkLTQ=H8dA$3WGoYedzLY9wT!~q0GN<}rvB$Z z`aI^4;c#2Ur=8a#+6F4fcil zIsmwn8ncY!S8cXQle)0r^iZo8b}ev`tpe6RFh<&(yG@Ko2B61!XQsP@ zbd6Q!TF@XeFq|@S}j=rV9H{MSHdX}=>o*zwkhhcUK~0lFAd zc%3f`Xw&)jYlyZ#hmf&-5boLDz-fDeOsix<{u$dZg7hWKA=~!d5Z%f`%|)}M?SIz{ z`2GL2V9{LvY5XAI-;EE$_o3kzhi-+Gy1gB%Q0st|0iz$Cd$-|@h4%q>oXRW>O#>u{ zg}(?|_z}o37JeP*v(#^_(*$T^VX|{r*uxkLzXkOBOyOC07SP7R&ufSlegh$6;UL_z zuz}OU1Q`o6VYY=MQOf(^)WWN^b>BjUxj>S&u7$tS3}|6L$YjC7S=zjRQ?YE}p>3!I zn|Khk0fQ{Bh7E|VoFM*9=C^OEhd3X>48OqXJY-(d&{q_yhmdNX`>!7IC&GC4yMg<& zO-dmsn?qSc{rX_IfYhS%aLqK|t0fhMmcB_}MF5oVd|;YcCcmLxbY^-{XQn<#YMR;r z2pa?^J8+U&4Db<%yg4MshH0Y+NU9!lLB#E z24e@|H38=W;*^58xF9G?xVpHEkp3Af9EYawz{x?^3KtM52ph|u&~8uuixtSf0k<6{ z`Y-KWD-folJS&uM>sg^5LhHl>{FfYK1rHUpLI)K?D-6{Ttw4ds3PHGMg_#PX6$tuQ zDE1;bkBLvgbL>e{)(>!q|2r~e6mlZe#@jG7f ze&`6OJg2W?Jq24$L;p%zbax-aQ@7!6pE{v^DzY6fi1~JvoC@WeRQA{r=FKYkNaGvi zk*;_PhmzsseCQPj-Xmi{gyMYnM9<7ao^iY85}=k5c_Gxa(yfSWC*do!Qp$QAkvB-V z6k2@&M^?%z1wFDy%w}xK{Opf zyR{#A^1p-Z-zfil=&wQf$20-uf36|Q{{nC3;*QZz)>S|Maq^O6Kr>lIXuAWt@O8{%h-D zGv*iPyLL8{2-vO!AV${vBVdM zTq2=Bm@)m&i1<)E$rmq%#Rc!v2R0|GU&#IuLyj%+^bov)HDs6LV*-1CYTWW|A0YhQ29?EF_^64!GEH z1OFd8cQfVm(&Wt0vvW5uKeiNpVNfcDt%dw+a6dwwQD`N;rT4a!wWznv`mU%{4(o-* z2%hM{>!Ta=7~v=qpQDl~VQ(NkZnbcDU;x1r1+)RadPLZ9ww>xI4_`ZS$Gu&`cbCZh zjxA&kjt2R*k~b=1n9L~A62JFBx1w;meA0Jda0WnyS%Ad;_~%9)0#%nCT;aC*m zB^iG6B^mtXa07wq3eF%na}AK=Z5n>{Wi3EI!MzON41m_(19TtTdLztzYztbvg8q38 ziS8SK*Km;VAQHU=hy4;b)MAA^fr%&%{A9R#9Rt>v;9pS;->5a3@>4G4{{}Z682>VC zpyBS+bd$t#1GFZ5Ev%yJypRZPi?W)4`nFQfAn_}5(iJrZA~s8Ro=Co?pQDvFyM*r& z5|E6vAY-WpLPRGnkd{ds5I4)q6_Mg&6)0`6`O;ie%m*r_6wpS{N(h=tK_9q+YN{Z} zS|NPP&l-qB1h_UJpNBSI!DZ^Jex~63I!q+^#o^`v^AGr8%e{i@TYv`055yz`R3Gjz zfTaOy90YoG>AvF-rmu{^LTCj1a7-H{8VvUv5~d^3@Ou&h$ZyAt0O$$0V5aM!TA<28 zys*MIBm>S5=7NJ)7#*7MZ)j#L_*s0a9<&x_Q+=|+}*8775qtG z`-83aX=_eKnw6~3pTid+Np?eCt*?&`0Q)gG`71nAcq`;8%KGN3nOni@Js20HU2s^4 z^i47;gKuY|8h0t=0w7zN!$RDykTV0=WpW&(9nu2v4T$fME(q;KXoI#RCc4OcSB51* zWR^A|CWKJ7vs>VOL7`7UDBmRgmOO2SRBHrO+5q<_s6CN>a89+XL$V4rvlaZka1W&g za1*!@l*5R93zq@P2Bg>|`fZk{Bi2H&X_ov}&NV;+LmcZBzzzZS8Qk5b{%Jdg-9r(4 zrQ9@2eh4ZOi3Z{J^IIhR6^TZ!x;NnmJn(%#%;dBrVf<`@{`lQ4e4Yoa3ha_A@+eo3DV-HAsTN3nSp3g??y$ANIGA1cK}BI${+ zg)4Jbzc~}^0QNvQ`8(_tu+5p^cSwyvr}I!uDR3vi*er+n+<=6e=lG9LMm6%ZZ5-0h zVEX*wKWTctoE6y(>GuiWn_dWBGP92fF92igmhV8!k_-5)LDUAhji7^EV&LSF@M=Ke z!VMLkZulH+BVp4xIPg0tp9AeQ@>gs6H1KG5@Nr>?w9*L`dO*KfGy?P|;Fbfv1Bo}u zQzL<_9BE$n!~SgoxHIA03*V}d{V_GNHCV4nRT{bOILvBr??XiQ)y$NygQkM=Ask-( zJS^XUaQpTiIS*f6&^MmQ??V1X*(dK}9%Q5qZP6gC7^GwhU!e86+b-d&w37iDKu8nJ ztbC2uz0TUD@9mO16gdR=Z*!RKx__b-eb<#pkmc$pVW?1)71fB1~& zGp*JUsfZ5(*c05ydU7VZk$wDUM3XdfR5JPhg=X;oDo(-WIA^4b`ih<3xrUK!j=Wg{ zr04a^4fqblvcG(wO(Lv8*rz<`@au>-M|zb5tw|U^KnNPIdFRMuwLojC%^kF_m9~*B z{$Y>ymD2o8L2DMq|HcCx-w1p|dO>5>ort_Ck4B=Z;+}?*$D~dO=H+?$@w25A>t{5gsrY;JZFv#V@aC+?+f&}cLoaBT)3F_UNB)Q4 zm#}?Rc}G$p?@S}hYM9SDi4n!NhG75flS=pF_lIV99;UchThW*fj&-akJi%{IK!@;` zM6bn1tOBb$Aj!0app?S04WC`~7at4Cn8~1&P6fs1^A8+`e~9(^1E7@aM@)#nBRrd* za`IPtloSbBNjXy~r!tOlASYK#OcC~PD4W0PQ>6HEwO9noValnsg_Mw7^+_r75-9bl zkDa^*!3I>so>~mShSb2m)EL2snYEorY)j^8S0uI-Gqa}<+nTx9UlN;2@pe5}&fit# zt}2CKPZbu8QPJN^gAY$au#d{EOY8uZyOP*pDvVzY^AFcxQ({M|+=Xu;_?Su<5kPR7 z0#>3*{7mNO)k5$@A&4r#ZZ2+n`*Dv|8+N=~3s2`gb@1q3fZ$-Na2`qd- zV~g6Uw|InlOP*10=>heYeWl)V!C)E^SP`pUW*zlbc2I9sZ}nC`pcAe-c)Z-BpN_SVDES8?Xw~o+aIsqf%@tl?5*CRMe4owl6tS7Q19pu>b(&j#dL2b zt9PuOdT)(Z@Awnyz5TL!@0?KY-JjKaFW-Gk_kKC`K4_%giN5NcoTc7}&#QOpEqJ*D zdE`g+^Gcq4jE71&_3szzlRHpUXq?=EIH6f`2TBMHk~>h^O_%7VE2HTG@76_?+lTP= zn_O9JBq1U7N~%}Cx_S*T0)f~N6Arw_VM4D-jCxH=sP}LM^_uTeNQ=YjwR~5-Rv)X^ zW}-sc_EoR_P$i~LQLn>d^*XLsuX9a>bZMwwT5I*Xrm6SHmkR0rgL*xFRWIFEUawi| z^&SB)Pv@2>an*5n?;?IBJ}#dsovnS5Ehbm$iwOl?Wx|d@#+mWw+C-ni@PjgP=k5R!L7IrS#CQg8AI^&VTQ-qdH+o3=~6$3IbT`fuvZC=|=&vnr`K zyS;iJ{H`i}$p1eblK1ol_0Eh?-Y4_bJNvDA=blsV{4w=Db>f)dE0g>?li-R;@Pk4A zXplddNi+z%1jq|8_}Y>3 z7rB0uVF1g-nz7$73IgUm=aIDyOe>ktI;{W^%h&p(e} zTXJLXSMM|u22x)FAuuxrzxnH?ah{#r8ey^We_Ifn)zfoK%*yl8WMtcT0Ba%ehZ!Cm zx10O4n}Ti{Wu#mj#P37-4mH)b_{3E9FkDAJV(^UR32US`? zdiEM^<$d{LH#~vOVz3QFF$7khf#a;aJ09(cn>sW|`O9M&e!kE8f|&2|_4o}uTa&-P zt>o`}qwrg>1kk>Ud6=*oiV}6CF@9(%tKh25VAWMt8?vqjSd^D~Qt3enED2&VA<+^0C^9be6lz7no95Xw0QFXb?fU-vYOZ5d z*=IJwa+TfysqlvgF3TS!GchxU$6&Ra|30CjXb<77>snU+Xt#Oz!Y@`uG{%jFg!gQN zXdyQm8eV1!qW8Pe$nZJ!5iRUS^M~iFj%X1#8WTRN2BJmXXp!)Gtq?8dM&rV(RYNq+ zjV6RYQ3=s_H<}oJY%rq5-DtV+BrJ6EC&<%r)Hyl)%34HA$$E`e4S#~%M7KmW!oO#U z%DK_n;R*c_tso;YB-$nFhM$;;Xl0paG1@TvXdK=^j-^76Nn*EC;z7AFB}<*UcKw11j|hMSm$bVYo1 z7U1nP5;-3hJpB|3QFJakVZollaIui+)JH0#xnY?T>x=I6EfU3XLl@nJ?6?iZ5qyMP zD}E7LR&)oqQN(8Cc25Qekr~6p3BGC!GC@gs zHwnCH!u6PN8D=_1Ng0$M^lxmX4hi{zT~yg?qS_prWH>jU;^T zLcnhtVO-Wlk!z48r6r6JoyTEfIY+wwxY=CY#Tn%b^Pu!#Y#(VjBe3C8hT0j_5sA6)W(44A%Lm~ z;ZbZGQH;VgT-uhDu(iMqGB_?pjcM)zmy|P|0PClXN!}rhKM-;fUW}164V@x-xsmi& zP?CmnW=qi}Wgbm@%P7mm?j0uHKMc%24Ut$0r9@oZ*5PhGct%S?yD29yvN=l^{!R%?0a{ZWX^{7RFA^(f4mn{atb@#o9tJH9q zL2&JPmxi98*3@#JfpN*6t)++PTN{Xh2EoOvLAZJpMxTk^ZJ1o+-@!bJ5i@$YsRo^Z z^+#KAYS5hA8f^?~lGOLrR{WDmxQKX@<)qxjNA3tTr47JL|%;a_@ zzH$Q)XHy?cJ@Lutbun{H%oiVD8nL-1782io0Alk@EHwUy5{NxvVv+H`%|`4=6U!fe zd@f@1O)Mt9cR9osm{^hc!lMyeXku~k^Rf_IG8`7QOC-b>!1g0%DOVlgpEi`P{nFD5)+KHR2Y&&TO1)y1P0M;`T;r1)rSRUXBcDAJ|fg7{CC6tu$t(k?% zdL9wl3^b&6b=v|fJW(D`2Ka9^KR0&S*`W+i!xqu6$z&8!-VQPuLXA*?lCpu2V={vf zZUs$xg_M+s$AB5F!>(|Hm_t<;agxbD6dF;ucg#-i4VU|{fQkMXpNj#4+seBUi87!i z5U*I7Z3ZyzMYZdLUVc94^$ney)9kVvQG?*ZYpd z2hR_##kndKe35K&Job<=mh;zB4PEv-ce0b@XbdFd6uddkb*bSs0%|h7{&2^EsyKi# z+40GW6#NebY8#s01%Ou%&C3aqnw2e!Nu;vJiz3vhktCA_02L}(%`EF7qB;}B&>i`d zss~i0j49!w9{X36S|h)FxWGki2%{bNoy1cPU+#ywgsxmN6{jH0&1%|mstAul za<_Cuo1vf5ICi2%&b2B~-#G-BNt7qk|Dm$E@BDMk8iK*=)X zAQCiqf7jbSj^SI-O9Dvp6GSpnuZ!S@Jxb6}kW-v9(_SDKLv zBBN6NMklq`o)mNzws5WkoDgk(&oinvXY3S7LKlo`BpZ=*3tVJwtR+}=N^c^s zf%a~Y9u)yDm}Qx$gID-isNFkb zvGF3PG^kawK@Rh&E>}_ds7`5UgDR;70FMx)N=BixSy8=^+NvSbM&3VBVd1J(DZ33vyTnLY*7dLmUbNO_8e8643Kygi`5eU}u~s)ksP0X1&f8lXN0 z;`=*MR-GQHBXlk9rG1Fss635u@c< z#I^*PZY4f=785Xa4hEnmPr{OY@8dUy!9vfdvZo#zfqhSnLMc2ljqkP=j0d!pVPX1x z3Sy?smGH&a#LQW!p5cYWzu5_~CMFgdU!4M*npk9fXG(e4#PY{~Ln+NnEGE7hr8GCO zBJrznL{q4RiN(dQ#*|v9rHLiPKd}L^Ryr@1NQ_^|SZfn26TfC7Vr@;VYl6zX7N<>Ei8f>H9P%;6?hHNH7zjxe!mSf=uk>_U@SCgEwct`KxzYt@xa8Q@J# z2U!w)Jh`?rFxKB+gDVTWGn(=J^L3TJbS{Dm`T=K0l-MoBdNn2Cxn;juvr>P4#$0Jq-rXl_LxD2q`^q~7P4WsBBwBkg)4 z^3W3S!FhZZB6SVt!LKp0QBW{|vzlVPImhwHK7Kk5W{UM80Q%P-g-`qx>uX{@%U%Uk zv3|@NX$F_9g}0M~X@;0mx@m@bWwuKJRczQ(OcPlwBV~>`?=<;5s#f>%8E;}CmR%jF zViQgxO;P`|2!3Nn7GyybJq-YASVM!T^iY^vy zHYdD&Fs-4aj3T{=S=IA8!lP%99&ff9yr1ysb+EiFcEje}ExfSE)upu$um)|t^@rP+ph2m;BI9Tr5}cpVxOSp zSi;MJdjUVu9xv;**on&tfUQbV`c~Z(#ooy)78)Bp7Ya88IeySIoU_K5gJvr}15;6K zA)bud7yg~Ee zuVGxwSI9IRUa5KXzk7mS*oc|!(W4lGVk|^SDcT2+F{aD%{>`*4=HLmriUXj0QCcS9 z)tsqmwtpng^8lDfY(0A5h27o#ON~%cW)K!_Wbi^STZWfQL?jU3n4p(CfdD-Z7^Bdg&-JxV&K6>awtm<7#=4E8I z1t2}C9(Xrx;q|0ZtFhFd4q8hQ-c=f7aF~I~4?Yh@TQgSi1~Z#!#$r8EsVfT{z}}$! zB~fZELgbW=%e>|^r9!pj26?|R3GY3P0Ijn`nUx2{;}#Mx!jPvUo}R%b__hSN0z3h- zt^mtzK-^~!F7Y6`8@C$vmXuRyZR{VWr&>iIGC;HG+Wnsz&d6 zOFJV{lh-g0iJ`~g4!<~0Q|fEMyMED?W54m}D) z5pWalLR8m(>|_7^26~>VTn~VzL6Fr_5=KM9Nc#Xh1#}NGjlNU|@3+YNSPI**@-lKF z&XFeoTtaZ7TGmCBkYAR2h?l|LOGFhSOm}G|B{0p{rRCUcQ*uX61M+E3LGxG*<)s$P zTo%>t$S>gjofC0{jk1#1XkZ2rgZ3B;=PJ`$!rAJpNj<3VND4T0$o+rpy$6(4MfN^= z>YQ^!htqV^aA|Twcay;;$0l`?X>!icdp$@ysA0VfgC1?E z5s=RCnA(>_gadWbng-Y*aH35wg#Rut&+@hX>iJs-g{8 z>OmhupV1!RCbV6BtOz;hLnKF%>4EC8EZDMBO}SYwNGxU4M|`nX^4wo_$DXHoP#r`^ zXQ@h%Hpb<8nvc`%w!eA=C1V~@bCC;66#>}C2OEQQ|8t|7-V^IJcq-m(u6{;l%;QRx z0=G244%UJPasG2FxO;qwZjWxfCzLt{$$f#e8`R>Ai)ejbsb?U0FHstoHy3wCsc(Qu zYT##!S^```lIN7F3SiR!?E6Oo?o<3?1u#Q?hm!*~Zn|G7H5KAj0mOHb1XVvOwH=si z1KfbPT!u__J0uSW(kk>LH=%#Ccq^LfFA%@yL)_hxA+qy`H+Xfs(=diXr}_~P6Jvr~ zy;7PkD$gt$>!PXwQ7=G=C%LG6a~4J@(bW}*egR5+-$ivYd2~`x(}7qNpd@E5s*hQS zWvigJ195GDVh)WVsx31&!u)Eg?wr(pKs@N9JV1&083x;y=-<>E5WYu%?n#HLDRU=gp~j;SHln$3B!i9=DKXSIyJO`uoD5g2Xq0O z&4vJUCSW9l6XG>YyagJ{%wKD`8dgAfX}ksjTx(8EcQx#X@JPIdWr%7XHP@jy#K?yr zd@>$Tw*Y|K%nIFI!21w>5)TM77x$T+HoHmu3Sp>mTs9}r$cN1=D3V;%gs@ILU_MTu zn9rCEFnF?~SDhj35f9*P74s$Yk>xI6B81c90o>#?Uo-z*LfJ8;ZU&_h9|1zJT;w9|4~k%juV4jk&@# zBdG~e;iY}1ubR!+6|J3B5W5Zp%_t1afc_B^fT(KKLI19LLfYR)K>y*55aw7jG1$qR zY6gU*1Ze$3)H|$;X4c;}V4$VLY=v--56~U0iz>7_TUZ+sbsUI?h>EjhsG5jV<|C}$ zyN>!L$_JmFvf@pYarX|EAa9>5-V!+I;)b`58VL7@c`xa zR)V_GI)eI(_53w1ekZU;13dHL6^uYX zwQfQUiUAJ;_Ix7LQ}|EoX%F==5d1a3IG4$A^DPShV?Ex=RhZTk8?m_J^W9f{#cI#A zZ#xA4%ZIc>fN=Hj?xk7VexQP@XBZHZ0+d@af@)%~-{PWH0kJtixnqK$y4pXYVM->C z0C9hSqOOGU6Z{~1+Ey2T2H1}Se0=!{bezqfHxbqU0W7JRpIz5w1U1**k3LXPIY6`s zP(dFwMDAgmm)pC`yU>1sjS8URH+@w;u`eBj@+*aOV}OvkV4%^(-fb@%2<&yh z-SIoD>x!cCDZ5swoA9%My%j)3qg(0%eaCL%mFIVWIassByTcy}RU-YvejWp+ltEoY zDEM8Z_>vX8724xD@o-?L{|O%MDbOmRlp9^uTtDvn9W*Er7vC`SHrlz2-S+_dWPq0v zbltEF#bFkPj-j23)$arLO#l_G{D2h#9UMA??pd@(;o}u>xuqi0a~Cx&^!-W~)dYx6 zi6}jjAEM?DLfR`r$<^JoM*=o4fcj}?xYZ)~9ibYVT>KVbZ~1Td1c#TH$3o-E+?Y=y z*11268DBvX>A_HEjM-8&7ZD+?rJvuxJhu@D{!HjcY#9i?966g) zSGtkLBErHTl2ny^#FxR3p<9Nz_-()*`!oC>a*`4rhzW*R_5>ol_1_|)rp2i2aAU96 z`3_hI9bQ~bOC9Pmj?YO^coy1WA7)Gu7p(2X<(5tja0B*{*EL5~cN z>+MD=LxkJ^ERtV(UY<(A$GtZF3?h8=XOV)1q-);F@LsRa_!$v0Fd6$pK}a9dPhKQo zZVO*iUt4CWMgaE+A_UbhAt||jD)|W7L0Oo)(=0hlO+t*-e-SvlD6B)hS_pQf7 zjt3^p_rjC*pwrF3e6l(&w^W!16!@2%tbG<bg}fTKvz{8u;yrX_JAw;aNC@c^DVGQ*Km=t9NlYau-D1N1&;VDu0v|l8))`czs?8*S@dqRTh(UJKTT>MSI@|VKh3iR=w6|*Cc!gHk9UIXlW z0F5`eKl)~KdE_h1r3K30<90B@xmx257UKou0Eco4#w2>};IIz?I z1P_A+dMxsnJ}z`UV7mfnyulf(VerYw;!!U24!|A>pz#I^^yx@PuNd9}jLY5MmzZa; z;Lk*kVLXtsh++v|8Q1UeFj%0UMsBI>LYo6t6hPw*?sNzSe;?`T6~j2d<^|Arg9U0v zM_un~-2&Lb0Q!d#7JPbiEQWJ2_%yID{0SZg3$#|0FQpLZCxHDBK;sSG!L5ZR(YY&K zXgN4@Hm*N$34wNuwo7-R?Eo7PK>uK{;QK_+qLqjhGl5uW_Nf0lO)H z#v42ZOB8cf^w@Cxk~Qj1JqFlo0rWcbR$dkJ7^Jy6S`CeT2-xaN!2T6LSs6%MQ2V3v z2Dqq<0>j`wf?EQH8=DzGOW|3h?A4Hy3!uwVT*yf&rdztCs0P&=-`q=4sFdUYRQM(0=Z#K0Kf^DWFirjeO z9je;Rd5)^tUtwVFw(CV=TXLJJc1y+?rf!71b_YwHhLFDwl1{BEt`BdeA)VE`ke>Gu zxS7Jeo7zP+Y{Q^t^)o(9L{1+`4Ulu6t#;4bdf@kkD6a~3?LaG+VtA#&^N+$lw5le zs4V)-$Qga{3|LO5Z^3Bx9>O`@Xa+r^Sr?MsH5s*W{(>u= zs+2KU3tlzx{42QM_>zq0AV)V7!S+nvd*(e@3><(^MY}>9uJpf3{2}V?g#dhLu7c&a z5>Ow){CL1(%%k%@F>^8TJI6S^Ask46wqS@7z?bHNzPRy84YMFz>I3wBd2G5doeSpC z`L3EWAolqvSSo;jnLpm)s<{WkM|^;%hP#P*znFaEjpXMoAU+{V@{{q2&NcVB@(k+` zCW2z~uRtV2q;2+487v#yYJwdVF+3NDe4-L`rC$bA)H;tYROcUvVSmt7cr{R|)aKKc?Wh1RTZ3t?>ZY^Ue)Mhr&2dLHHs8+5+G6jsoy4 za;!du@E<v_ADyJ{Li*v1EVYFy8|cZr*yK|qWnO7fF2 zPUqV7yt^GYv1LG97U*(OuIH7v+!PN0aqAy+xt@3ZVlV$dy!r=SuIF{0?dtkF5I_Dw zm+N`IZpK)~vP{QEC0uT8_BOTUK zkn3@cy}hOm;OHuslH*>?h4dgK<0p(CUuu{qrB}ANlz|7 zl&-`==>Vb&eROevE*7QZ_?(S33VMwW6TaJ z_yFR6dJs_%2bsp#BJd>&p`O_G#wA8DpyE(jJZ3b84oK^bSx_AX4#0a z0@q?h`Wlf+r-FG0i20P3K(Yvzs=mMrE+hbdiuJQx!Y16}qfE3H z6Xk2eW~pt=#QaAQfs?8ofJRI4yI_FNR%MuxsTFyyEFJt!xVnrB8zodF_OI|%%~oGC z)eUD5NmKzEosZX*0lw3RZwTOB2)}X{KFLc5^boE$0DqkDtGiMxvqKme;Pvt2!^Q<4zQ=>lQl|+&v>3(^PUtXPV*y{J?qbTf9D{5Ec<0nP)l>CELdQuJJ|)O0ZT7X>s`8@2FzWA-{x|O5iH9&)caI#H_Z>BH))|| zdk^xb)Q?b>TR`frw@&&{>@fbwj0hRL5Di-efO4ya$S2p)hKgE&d+N88WxZY|yd zI42uPEPa)%wL(eo2kAE9g^F3_+SFwW{pWdSD2F!Qx58`HOBC! zlvN7GCS20qq($jAGtQPaGwq(vD8`5~_5t&thhsp^$Yp8~Mcj-}nUjc|vBx-rI4h`h z9de@<<9&w{!^Yd7_hD|jlA2IgE04&xz4A`^j;=~ai@6aI?q;NjYC$a9dzim2pMG#P zyBbe!-lG=20(vF88W(_F-6nv)favF`B1Nt24jM(bk{yGmh9%%(%sS@E6|Na92oJ+S zg_twA%!&5OV$ggMBmTzlz>9ekjC&AQP-<}<^cWuXvz~|e0}mn{nRLA77i8*wZyHxg zs=P9O04uqlt4<0xPTh)6AWcUp@~v;fP?9-7R>x#)C8MDv*RWVeL)aM}0(GUd?j`_N zu|KC^94<3vu0q68cIOnXo`F8z7uHjyoB~jQMHRC)5pgC!A>x((74$0*l`>No5LnAW zdLa<&h`3PN8f4{305n3NJp$|0%TTuph|6%<13zQZZ-P}y)OiFhN5Gi>PlWCPf_bwC zU#gN2f9=X&!L>?P9bDjv)~kvTn5C;=9sV}R`v@~{*_(~>Qyb)cgqgQ$YUwt%iAroW zAvXBR3#MPL?sLK72 zEn`XzntJNCTy@+f%)kNa{y_lL8xo`AyU&v>l zMhfP7_@iOp&)|ke40c1B=Elhk7BRSK7J}Z}exg=i@Vr+5rCX(>-1h=yS^1>W?L2;E zTa)n>x(kYt6)3{|2IX4&TJ<`T2(aZy?7H~-m4fBvX3sll1dC}plk*KV(OL}!&g7+t1LgxTNk^LxfE%2InSf?aLRaqwmts=T z$fgNt&KzKqZAonoH0U4}YJ3;9kxqj$)F|Xv&9x4+=f7SG6E+N$YbDf1XeNd5(0NKa2A0V z5Xkxnf!K3Mvhvpmou}*~0zV)if9cW)uG|gZOKb#Bp#hx1Z`yqJ|2KmFS&iVIYy^{Z zBk-IcIt7hjG1+V_Yy_COc|h%wWd_(DE;7LOFnuZlY!5Fo!1i#C0k(&vX$Y`Av}Azop&tU3 z*d8i(fnUFfD~oMnD&=ewmmwg3FE!`D@XQ{+O&lDe2Zq-X=fPe0?M9^S4Gi)Q%GX;X zqOIS8t4eYkR8I8`tnK=;t;M5s_R^VK~4^&$Y zf6>);n&GZ^$T=_$^GRnFkP)ZdVA$wG)AqXCP9^az34j zRg3e~1U&ugbb>uqo!5Y==6ny+t2=qa@l2$1SqavQ&PH&uossy7=335W;MaCOM=Cka z@uB$bTIV$E$#Z%lFLj(|;MaBT0kWR+C~T|mTnS7AXE5|Pbf&Q}C04&OGF|t+O2^ z)6Urh%iB9IfYZUL1Dgw+`@rewREOoAoRP@&V}^4O$vQ_$=q_L(bBj<@n5ST0&ah`3-S1 zozpO_f-?`bSJ62JYhz9aq*BTG1qo+4Lk6+lnxS;7IA0)3Rh^Zn!)ngmD3$8Y)xgwn z(vjnu&RYm)JMTkhEhh<<)OKD)S~*Tz#L9I><1^2RAl*7nBS`ByO%bb}GZLKo&RrJ37U%p_6k1!l<{|5TM>( z28DWi8(&Wv&RekWDZ}{}it1^@v5@y?4CfOtpEVr(#-j0@;WPsCdBbUguNMr5KZo<8 z;S9jnONKKBUoRU@F7ok;;p9)n8`}+MBl7>M;gsR)HN&|MUuO*GW_xT0% zzTPmL=kRsbaLyv3Hx1_lP;VK|-|_Xf;k=6)d&h8=pqkz_ob~v6&v4#Db-iymdqJHu zoTK>qz;N!u*N2AlAih2_oM-WM-f+G~^p7!oddIjIYlP=NI_X z7lv~H)ZYx}R($>4a8BauOT&2rUtbwcEx78}_;DN5>o-t_uWt=!1w85kvWc&M7|u?7 zeP=kI!%@FCoKv9wX*f^f>j%U63%-6tR`B&NK=5_ZaH41gKN${x%<12Vj<285sPOfR z;oOd|{}|3kD3D(b2UAz$H^br2G_6xk8mLQ^^FFBc%K1CKHYn#oRKR7*c@AHfE9WSR zXQOi70JTXu=kc{!Ip5-Ii*kO!*H+~up^mOlP7GgHDkleD+m!PqzP2mpBEGIt&J!q? z9m=T>Bg&M6>9Mg>Ien4$UCQYVZ@*eO55uu`E9VuI(jMhxp{(~R=R+{}Dd#JEU89`O z;Gfqj=QNtie&sZUOI@d&s)&BQa>}6dfO0lMc2GGzP%a-T=X*5H-;`sZCj!+U9nS^j zl!KOkDCaVy{+)7C;lhyBMECL$3Iqn8S58ZOeXN{ck@ruOa~zOQm2&}J@EJ@(Sz|0s zy#l)J)KAS!tlXULum$a*IUp$3GVV0TTU**wo?T@8FETs zcGy{uf{Zx#!-lA{1*(#qdy)TSX96rvaUO(*RA&xK(s5eB>NMvI#46|9jM__gHUpXA z%!I||omb#7nNB$rVFhPCI=+g|WE6bN8H*fLb4q~kLfnX zsXd(`uph!##($tC+ZoFD@kZW4NjSqhfo)>(_dIkuBd!)I8rcS~aYnL!%$(H7UQ(kp zm2OzC!XRg|WN{D5-C0u!>XL148<$s1vO7ZQl&3SHbS5EIq>BL462kjJlu;EWy3Q;( zi*V+GDbsMIpq?Z4WR^_D#&c(4&77W@3qW+yMBm6bWWwyKsR5A@rJxG0NG5Pdq;hpo zJ+-M5A}in=W*<#Wj_gL2nSC`iJu(?iVHUTMtXATkM}0qe2TeZFMMS1M@>@gVFX4F!$s{8x>StFbCB30 zHDyN@z_sjAnu6op{|yqGB^7uU_Smz+tj1vI~q(+~v_Hp0=g`tKl0=InVTMp~0%1X0eJ)3E`P)_T2AHuZM>fqJ*2M=+c) z;wz_=dX0=___`sj?&wt4QPbKm$hta=2AkG?7APxchl+GzFVl(ETRB&&NGtTFX`Pub zD`%gITuJ@Gfb%mS+u>h z#7OJSDz$QMP?5i)OH3=KyIMKNRHP8ql-5sMal4AFMIog1*H#=?kxgi|X#+HQpNc#( z2jsxMqUwGX`4vmNH11kM)oB&k2$xSAtjPydq$m2Sv>}>&P(`kT)1(d6W;~>Diw{1K zHf(+>77=8!dAXU1b_3lrpsN~aaZz*FwP01o%}R0I%8Q#B=149-Dlcw&2XBn) zgm50y3`fg#`WoMny9&YTvKdlV=M&9Ab>&VF-^dY8E!RC8OVh}%ieUGoI)dJ62CA2) z?8p%$Tdp@#W&1>weuEiB^bSbSJJ8juqYUz+R46y>h#zG{LX?qSl&y`B$|#*?G*Z47 zDE{gh(oBsU>j7$vrqYeDU2ei@s(ZF8*prxX7|je%JxBI8jLVZ_l9yj%pk}yv!A4WL zb}ewfqspcRV0Vzc@d2> zqb-9>qINs<8SUuDbO~8c7kUwaOQx9_1uOiB9TOsUawF>WJAW){l8uaW7)a7H3U@Qw zwF{xAh(Xq^tnP0NQpn2B81od!Dr+!d$QUcZ614h^aW^9m8veQmPcf>$i9WQ{%;@n- z2Ku*>rA9_Cj!@8?xe!EeP1u=>CQdUl`e+J1i0o(d)l_OEn`Kq3sr1NmEb)Gtst{R* z4nL#6rm`}}FI;3~3}8}bPPNE3_;toWo#WY&-&h-iG&MJ}6TM5u&~t(;jZ8+jo-vGC ztenj%GL`umuE{G^q&ssu;u~P4AFfJsM*gZvGqRY{QEBBxYSmy-SvikklbiL)1jI8V zx@4$C=#UX*wNZ;FXPr@vM>G8z9^KH$xCW!fh>YoXWTGIaEi^J_=)4$_UrJzsOPQHd zA)2X0c4P<(%ca7ZQy`k9MbXHQ%!W%PXHJG_wicyEj$p>-QE8b|CeJW3=IA0$hYnD4 zHB}*V%A``fno3hykbx@IR5i$!85#36l?^SR7HBFrb4m%Qg_^3DIb|ZKMVe|9`3WAA z!NcXK#QaR&#?4rwsTP@2W*~*7nrf3-0;88{qdP<@vmRWkW26w{QpR!(>>P10c4Vy3 zR8i(aL|dt&^^CNqTewv3$XiT%6^q!+=^Lp|=UT0!4ah86&%bcJo-P|%KYDzb^%t@Nk%`LM;Q@XijPG(YGbIY8fWwY^)JFwr! z<+`)g0)ukqj4!}RwwaCah|JlS;3Q7uX%tlETmvljZ!=LJne!RZtAR|{Yjh1{x?VHH zu&ScB&0O>ipw&B|5XY#@rPov8cGN?rTlYp}30ivQ3JNgnM%JN9Ggq>@*zIp)*{`A% z=!GM_P{x_7xsz$;%#P#{xrUZnIbSIl-43vtGoh{2yveQ~GjN}TD~V&aTjRAjV=-@W zNxK&3Yv!%C9u1?lWQ}l}OQzP!g-e>Ziyj=Ct;N}#d55j5aYQZ7qs%*9a#XDbXvXGU zwq8<vb zB`$Xv7$v*y9w;NM=_l=FXbZ3sP`$l8*`Jg_=;C8*hE47 zB@=NAZxgi|c|)0<9a_QXK5mCrunr@kbwa5Mm0ShZ2~mKa%Q{JB1I$3J`>P;?V&?=E zYdWTUfu-`bvWmTk=GTl^cSB|JnR0zh_r7KpjJyhH2i&eNh7 zUC}&0m3fj%UPY|)%mo^B!38bwK?^jf3+-L3S|dS=FLtH9i+#{y4Qfl!GOda4$s%Z( z4_c-{*U({C%Hr1=?}AqPpp_bQIYDbQh%a}grZqljjer_2M{i_Cluqw1pmbG4q$(PT zr$t0))C-|cH!mvd98lW3E(YFpQQT45#81)$n@mFoXf6yXWmoaEE(|fkC2)KQ==nxo z2o2S~PSpg);z#|dAi0o7&EQya*A2h!F*VtJ}Ar?37*vVdi~kwuw59puvs z5N8uJIRGTgWw1ptT7kMoQerCoaIJ#46;6z_LQ2;#rTfT`w5}ol18S4B_A{;jfNUda zUB|S{(zQCN>qY+zNs609dB38t)CoySIn}+oJ|TSsPZO&X?3&>6>LgQ@-ddd`QZJX) z{VyW*${aw{1MES#U{((fmQV{r-b*hFX7%tA@~~i5k4%>kq@erGU2W4gPI|~nirIe*bbF+dB{6XmxxJKjmJ|~_vjaQa zSx}f>9ygAws0&E3papmzAY#Y*2$*I4JF&+<0MJofYQbq@UIyzwz!;s_;Ztyo!bN8( z{0gk}nGkkncTd3`6fP-9fx;XLj4mCJt-HX@*9jNQ2Hgsxf)WIJGcW>y+ZZTD;1LA6 z_5`+&Rdohb;p+%|hCtB?sCfd{AQVR7C*XFOg(QmJ0qZkd)4}fcJ=kX17^6EmKj7+S zz*2JX*W)!fkokqJSgZ?hO@IOu$H1j%Az;z&1FxsddcKfp&PmX{Zos<4{F_ZI3b(hs ziswtY+xt4iU9yq=QPc;+&41bjg`lIek)<{W)MKDA0zDC6b#oTeXB)fx10h8-zQZ*Y z!X9flyDG618KrA*UjfYh*|4u0yY&)_UVRq4c6YKbnk@8^xv)=qi76KCXXUfAoocaX zL*4hbFjq9ETihDk18`C93d`sY?OUO_xAbbuEjrP65cZXQ^+Y*zAD+B4I7QFJ787sH?jIRKNRkj=>h&`0KtMd@3M^@lB zAtL>U3ude@08O?(%El1$7sNG(>Rv;g0qPPN!-mQTt4ENb(rw5nJWM8~dT1LV{Y5?| z2_toA!4$mDXq1GTO5KlEEaj$B(PI=VzIjt_m*RbOtX>>L=cr3(t+pPUyeQi0c#fiA zEtv0tD7XTFpAi_i2Z4cnWzfJo`SAchp25cu#y^hu4&r05mKc@s8?~aN5dz&kX(4rV z2B(mE#xp=&TN$9fzc4_ZKOrFXdjfhNWBtyz`|n3ly$SlU4$dHO3SUHE1_N&(aG01{(9j51A?x@paPZfGGoFvYe2d9lYX6JsD}whe zMS$7rS`V8Z0bJ%b`wXQM!Fz<#qT}E`jO%Y;7rqJhm%@Gytj};6 zaEHQ=!A@BObQh-dHQ3Xc(ji+?X-EnFhN_G3Wap5qKj===adm=lF?0-*K5n1e#SN2L z>OKz1=;B&ShkPxmrGO8YCE|WIt$V4uZ4n#)-$RNmlsboQz)e?37^B_X!_e_}nPF94 zjJ`FGYuYb`ZUcG*rgmS47;`wN;?KCq{3gUc99>%nF4I;)<2q*NyU=$qbR>VC!R|Ot zdf&cA(ftr7Bf$bBHlhS?q6pEjB~*>Jc2TICKy`l)!0&MN#ktb|ggBwbxW%^lYe+Y> z{!A?$sv6-k%ZDdGV?t^@jqc4LD#q3O7Oo8|gqha2(B6gXLkjoN(pY#v8R&wIG;)cQ ze%tT3NW|+PnJ^2e(H7jnh3s5C6w+;@M92ZCA9(HRjPvQcmwE%xL(<7$0O~c86Yqya z6{@Fr1J-ipBl3PstL&xKy}#sI|52F|zlPYOUKtH~u+{x?BpXGtBjzF3&&c_k#>>J+ zZ%(kxXGPstp!Fd2ob*ioAmx$nAoaZTRj)7i1}ROW%K9Bg0qn1Xrgaks(SJ!d#tDLq zQuQy#nH5~-uj&La?kL5DBf0G$8C+KZL6_SmM+bgG(HKSKH`|2MFd}P;6U-v4yMo?{`$d}UE@X3$ECFd0 ztwOZtaZQGQjF1-hfJtv#52=*pAqa27WjC7(5gmW=?Jvn2$C~MK(Ad3%kzV~mr%WsvvwPu9OM}L<2 z=n2T#C;cMZY~KiD%S;b#s_*p@1=1(2LdH9A#<~yk57`@(58X`+ zXRXFaPFd}aoUfv(t}!~W-*^qki$qoqy#-_e`;KRzNBWNssIbW1ibGwvLJi;zyz^|< z46(OJTaETQd&*qH%no_;wSMUpOk<`G93{YJK5(=L93fi^W2E;R2=Nf^RkT7e4#QEN+1qurIaNj%z9ztLn0;pSdmRG}~>v5T#LuE*>fL-$)#IYn^BCd$yFL3e2tlID% zV$XRmf#sTuGudnbAGi3s#$;)7+@LJMF7Q3!xjpj^8bi48NYE1m z&Ion>!a(;cI3|pUr?$wb)fu_;*kKkdGn?)K~ixQ+`9}97V(<-}ejUGO4ab0yx z?{hhbduwP5noU)pyH`TOy>S)KEP>!eh#Mjyt1li@8N%%wid*6`Plh^{!=^>p;_~TW zM@zzl9Ykpl=4KVM@FK3ZQ2Pq9QScR*^Fb6`MBpj}h7fiFkf*3|VQ2sa0=t7!`aPwO zQ@SxEKK~fwbIc?He=U+>W_Y_S8JO7SZ8!=D(e}ph(<#eJAmjNVXI+%Um>ZrNNNlUH@sJu z?eR6O+tdI`rbIUZ)wwnbWjatRaD`77bO8A@_yze0{1XA%ziSF)b;N$!p0nLDBA14Z z+$Ns=b!dMlu(bVkY5!P|+QRy@a3#pDo#EJGPGfD(p*5|~kAUtboRi%EL}%`19Y-1u z(wyc6qd=YlU#98gk6_cNN3#ZVi<+i1!Sw>Q!<>$HfeHUI#;X2Ur#XierI+C{*N2T8 zfY1}frxPZKPcwPUKw3)6eOk|{qI$acEM@HwSx*qRk$`o z@)}anOYL-TrUURxSOYsZ2$;YdaXkjGbBPD8?16h#L@k?@)%)5gWaT`(z_}6cShtLO zaa}~bZhpMlUOd^%F>AXs6&q=u!1&0Y%tB|ok2I$?I%m_5#Eng&blPaeiACtSs`tP@lwmMq@vO{j$>3Tl`t+`1P-qaCJwjQ9?%s_Y(z55VIR(Up8 zSsNq=wEh&XmmsRv%*(-(ZVrY?FZC3ADHQZD>7<^bCbKN6bN5VQ?mW`X-LuSHwT)=O zulk1lm4;mco;K{SR96g=ExXPP7#&WQC`$oN+P^|AKChU=J!snRq-Awok zKjE*K@H>9OUoqi}lJHP93RUCmkP>0SHFx1O{3bka)7&eOe@D>Xl2-K)Xy&`ibR@q~G1>OGz5u%bNw*hwN|n>7Y(r?Q>@Thn zI|<|iGufNN#+?B7x(BjwOz|`*{kFwSA(>0Bk%Y69HvGaG8F|B%Mbijq=$Zvn*>b`) zl{=uU#(b9Bf{#GCdlROfF=#!EkFd!J^+Zp4*Q(qkhJ1$z1(B&qFY6!Yyd- zw`0ofKIqBkdBU%^hR*+Ip69{iI`-wz7U_l$YY_~NNQWQ2|4wDt(I&^iPHKp7G@n5e zwubH9#6Eoom`xc>wxeA>#COV!yTB^sn2^%;ID$nd5j3Kw@CZ~^v<-d*&q(TvyhPg( z0#!*nhCT*IYE$kcxci4- zr_4hMMSBSME+ic7NuM>GZunRXXc~1?!ZV_GL)MEnh3$>_EN88|3idS{46${w9D*%~ zw5}+{)R3kK7(ldGA-O!UK}=AwXVn8(0G zjx%}?UDJGCNIPTje302#*HaqJsJH-REtgEqm;*;huIF>kP}*Nn%ENG&0Ph(Z|p2oVGH6>4D#pG$Mm^_UYlc%v_@-$XVKaFMa(Sg+9(ScNX zbf7#BlBeo}#VoSq|Niao;T06*1;&F6q=MCuF*-!8|y0z;Xq3k3cN4Ks{j%Y1myBi`z zs3#e({aS?Yls9_d#}O`}q7+FoU%2z&+E&wb;G)g1z*iX0HuCcc7?fpOEk6NOc?Ruo zH3}eG)kNZzKWDVono)y{0YtRXjOt|YE~3>|7}1JkNUl2wqargv%Ub*f?NufjR>4LF zW*AmS7K;(R4uzLx)gOc0>8v$GFD%*SiF&J%rtBo1sJ9wxDq3~1VKwUwMYz>b6*pEo z(RQ2=N@|S0+UiDSJTV%!nQByy>085CfJvfsgqMUU^^W)^@tD3f%1r`iYra7x1jqEP z+0rBOwKUco3G&3gB`5Zya$?`w#9Gmnx5cYGp4hjxdX>i$`_>f?h<(u{p4hjp)K!^e zI2Y(33nJE3oKuGD?0ku(-v zw6krk6s4W?BH}yS34`Y)t)%R#>%~V?lX@}U-X(%ePijf(8ck&-HHLoYdhNg2Nw+iJ z5nVpHDBMS(FT!rVd=K>8=5qBa7-9P?KC8>t>;;5surg{$h#!#uh_49qS<{ADQJj*h zi|J0r>qyz$qUfOTnT(-G%-rgdI4D{J*erYKCP1r}mKgSMwq^jOMs2r7wVT*(jYg$L zZMQ~KtMb;AJ(^a~RSqEmdrY3>8;6VUK~`;h{7cZEB+pe$WOXosuVI+YSD}DXNh3*> zXv$3bm9Zvk3VGRzwvlDeXp9+D(ixPAJny>3x(?Qz0d7rG zN_GagI#_=L6=s`~~iTJSnz7p1ycdR=1Im)K`bx{@x!Hzjt1ajfgF&4ziv z*TtsqIg>H#)vrJ^J`xNzyjp`-|KDVNWwQS;>Je*8DlE?4kcVw{DtRZ+n#_H!pMC(o z6zsmhPxr<7>9v8M?hpJ_2gOeh`hI%IVzFvJJ#4Y)&>^qpjf=YxA?L+ zi!YC}SchrxMzI*C+3?QL$L<-k8(>=Q9Rk^zh+CYICARFXr1G#rX+B7&% z_A<%fJej=(q&`n}5>=545@s^k#63?&g-oT@)wnAS@k!{!y-;-x1)IUpXGvd{ud7B?G2t8eMmzbHkkM(xH+2_fv6?ppSXSavB`+Ol87vO}QTOaJ;GJ;0Y4 zZDFWs($GgCY>T@+VQKs4NX;?Kh{^W!1E_XAeQPR6Pq*kwTGJ%%94F1V71tGzEP^Q= z*d&!4>3ovlCaqYSUrLb^_Z_Z}Ah^@RnqT&X%F5f|BrM-A*(o;yWi)Y55YmSjYyTeH zZh+v43@;TqOt>Db4*EbLtMxDy!Szlu+M^&Yk;8Q-84ER0Adljy`-g+9qR$qx4OQ{a z7FNN-c=~K%6+Dcm&lXnk&lXl$=$$RBf`{?kvxOabw(vR8@3xbt4#JY@+rvhu@-Vt4 zu5A!^=21gRo`l5c)E4Y+xNd={qds;>pXc4}F60lwrTHJS0m!kqu+2P%Z9Y*HvGCFS za(2|VZWb(|o_q0ZI`sF&xue!{vdET^yvkLmTsa{dRxFxsq~T?nS^%o$uN*cbQd4Hx zhO}v5wULR^DDlIMpo@;MF^@4h zMY(~r43uNVl|LgbgTpv+=5QHk>C?xXEWsh5yDft`6Om5Q0%oN|6kS2!r|F<43-A`u zEoHu>X|rs0cV=fNY~72?oNY>Wo&^qf^ZPOJ%baKyjs^Xxh+4hPobECeb2#!E z+&%#NI3DJZUS*f$GJhv;F0n#)$^{`$V6s4SlU0T$n@iO&@D>Wl z?e@H-hD=ymgYL8*skK3BPa-AlEwv@`FoLBWi8yQnTQb9#q3?JYF0BQ7)B zk{0%ph{Ei^%d)!`SLz=4O(l2eu$ObtDFUklf04*uPRVeP=v%o$ zZc@T^;#E?CjNIrDUY`pw57PDI=}-GA22sL2Iia_&Y9!@tU&2;mU!_Yw+DvqpQ8(_v zG<_8<+uq65=4q&EDoarz-zO<+Q6XFJ#U0qWhP{jX$-6-`Jv$9)2zf6_S<>!hMt>l* z)UaiumA?0+->kSY4hWHH+`^F_K9Bcz{!^6HwQ&~pS z#l9TucAz zGzGi^-??zu1wdbf~h?{Ygisy=ZVcVm(yf8vP!Nk4qq7%T{^VKpa+Xw}1F`2X%$QXG8 zNz5i)@@0~9W=!_zZ$THGXYvar`NsPp$D=rl6jyDYoXLF~k%0Tju*HEt5oy@Yb;v2Rw~pgSkfu-yTr5w>|sIKu6tu-zE$6Smio z!QY5zz8lG#r*zlGR@LA}j4_Bjw}#uboszDt<#o8{$gb>^bY=TN_TeIV0HRz#aheZX zx8do5!uP;?5W;rR7;cGu4$3SWQ2afqql?c4X0Ppqx%)nvC|!@)C5q)4a~&<|WfnGs ziH9L8%tqh@0~HW>oq;3-zCfVeAzIN2RP->C>ViN+2Kpi}3IYAsV*rY2$Wh#0#brKk zwXTjl&H-;dAcd0<*o#0H4^g}foRd^@83J!Ia1{b+M}V0P4e#PA-VaU(aEfn4U#jk>s15WXK z2y|tDFV~q(%&&;t9FdE^2j>ck{)4~)1~O5C4=@lx;B5q$;NOur6MKOPzHAksZ4^eZ z%D)JC;V%$6*z)e;A&SdGlnqXC4Fozf&;Wt)475UEEdyN;IEg@)DbV>OZ7BxlV~U0& zVBLtoL#`ek7?Li31?yX~G3S3%rXert2>sP3 zZ0o%goA~{>&Vl~}veHxbDtd9R0t4tJT=n%DgEX)_>&bftW^Z@=?8$ou9+f(P+c*QD z=P^3l=yzEtd%=p`gt!B5MW_tI4=J2b_z=h@6d3*0K+dQqE1GZyS9h=*;JFuV#^iW2 zCc9=J(ol4Z=1j#1k((@I4I)kOBhAzX8l7qTY(_fCwEC+KoY$;WjIjgP^Wc8%$6D#e zk{qv0$nmO#9J`dxaSQ0V$V_c|6`BSy$6;##hPs0~(=#B?ss#C!gP3Vg24l)$6u~pk zG~`xX>gKRfJKM|mj(B5s1o^JPMc^LA2xoD%MWhjaq&@NZ-p5GuA;+%>HD?juBHK}n zb^FaY?FGq)e#~3kV#Z{}yp8OKAeQ30ooapnHDummoOeF63UPDtQ^=v$)KU3mN?zNhD8kF8{F}!PH5_lpXnxWt_^DV^<$rWY?v0d@7?^ zU9^qQq-`|V!;(t28}26ph4F9eL*x#du(FOTCnulkbD%ZTWv$O#O+v0ls8UV}?oqPf zpy52Qf!_i(UaF175Qa*~T;to*3Xrq{jjE+gL+_JYKX}joNVzw2LiDKN-I@1)L)}lu z5a*N{G)YGqG+e%oE}pD-E*R~QUh#4SmLSk?0|M(2tp}@%xQZamzgf#+QG%m(%ZGzr z32yNYM0o{qjUKE;M!ueLQtUezC*Fa(9EN~K6<>!q|6sz$5XiojHI1oY8LOcYD?DUP zM{{Vli;TvaF`JAx+5O~mJ2fN?#^DW}a=1q-Co>|LJaUyV|2L!@vQ{z19G2TcP7*`b zGBAv{O_U%;JKmy|SEE;5WJ&V;IEGB!b^`mv-_oO2sO8{U@(}{cTp__%M79nh`)>@c zBG>*c2(BVlb5r~vUTz!dyMuL4xVf8xyVW}gTk^497?OZ!y=NUoqE!b)>%GDitrE1w zt`m%AMD#JA=&Al3N zQZ@qlF_iQ~p{T|WE4-QYNwC7-&De%b-_-jhJWj%QNO-V>k4U&D!_HoWRoVn7DEA72 z`aN^hxeP4xl+%Sw{v6L%goy|<7SQ#TS%&drp(wPQU#i_V^i_8i|VMUaBS)f zP@PUoyl8AH-v6RHYbq7Ud4}qusdP|~b=6dbN@7r|g2rjd1?)z|YJirZTJ#Y$u_q+hTc(l1}GOr=CuVdiTZRY^;@ zHOe|e<)vk&SZP($GE{k$j;3VB3@fc&O8b;v*cY>Mjg*v*ki%i!AR17pt+JwoC_uuQ zz<0oeBw{NoEhPo~5c$!1;8#NnPjVH8s4y94B?O()M0HB_66%o37^xwH5T}XZNj7y( z>y=5}X#tO9xq#I2bYB}%(b_V6jIiJoE&PmiNUescW@Z8dO&z~#9#}-vE4mEPPz{J! z0s}fK#WQfQBVGfxv^`QX(kYd;SIJa8GNqWL_^LXFF3Vn-Z7}_-rc|#?7Dn}2C=C99 zNsV%-0#qEzT&jh_?5M%w&qA$J^yF28-Zse$)NZXqEdVCelp(08ZE#hS?ot9py(-o>Ab}KWX$Xmzj zrj>014K%UD&3)T|onU;s1b(l~AY1K!C-Jh|A%X943lg|AmSx+K_04>Bsw2&zbGl1+ zX^*19vO;1>^K+XA^IX`(bq~+|i{csBnF#W%-LN|f9>vFk?~#dr?UCrb+xe~qNAx_0 zN%W>+y4Lz+DvgH)6!op-(j>5`@LCa`?ZVpM=nqBFz~u-0A>WKP(C3EY@-@ikrhuzG zda$%?mVk%EI?=}kyrFfF_Aoya;;O?dy6tNO_HvDp5=%6B(%_k-*E%Knv@_RpCwk3z}0?8{^X$NlaeGJ zzcd%10~enfFx^7e22K-xd=YE@bRVA*SU1B5vyOCbXva*<)r?uXZ@?-z=ri!#Mxe)y zVi?ZeHL>DJf1$Y6^RTQqR>iX1?QhXA2T^YV+_@Kz@ycbc{tljGm&~+~P`J z(g0y%5L7E3P)7YrYh#;S=0{HHn^N6vvC9KyP_iom9iH)2z0${OKlRL9<#$msc&_%G zjd>>O>si6+!$$d96wH{S14OxlGg)ilePvCLh*{O zh~vj8(zSafggr8|Q?v_jQz6L}^R(TS(3Y$4vt0P4Gljv!ukJF)y}m44+Vf7z{pryz z)l&NCt3@Y=WID-i(aP@0OLGt9zSg}S8vO{K>hxqnU89-h1u+OId9iOwh(k+mj>kaDv3MG$-x41K^sTU*`M~RBU@I&^I=AZ(Y`TNx;+8aR zyp#EH%aF*sq@;8?VCN2{qI0K9sdZ zmY<5Vg%gbX`Fd$iQ)10DtM;3V=vkA}1wa`I3-jo1%^?ja-dBRYgQkLnO?c}zlv z@wj}`{wE{^x94E~q)!0*lusa;r+otY{&eOa%<$vq{oZ^eq~{~ypliaMKYk?;4Vs3Y zU?(LokZN)Q0|utJ43q?-0Fj!&KzvjKME4*V5*N< z&hK(fZmPPYj$R0*CG@DeQ>4Cf3He!mUw7yqiOo zK)M^#14xsgSHtQjeqhQE#-*n5!v)qpR$7Zx9ld#CH`l`J!CS_6?pX17J!@+M5>`0D z$k8@1h22Oyf7*zC%IjCLqG94eqz+WbmRcYI6n#etpq6mh2O{jXbq)$#_orO~22<)9 zknH~oy>?sVwcBo9yY2pG?bh9=`0u?Hb|^eoP3*0_I*NLAl%zd5Io^9x;`_8zuX*EV z47}MXYcT9swAuVU@;$$ z5{eWJjZ)l9lDIBevywMM3}LikF=PjLw7~$4&4{2U37jV<(c^MGFU<=ag8oq_i0gTx zv_(D9!KQ?lA%g3>abY9L27X*Hf|MJ&DZ8jf0V=>Wb``srCZ1bf;<;tM=ax5 z7@XUA!^!`>?K7#iVEZi5!4h3HC^tRgdc!ALupUpH1Oyss!Vt=K>Ma4d5~?0-U(q?^wy$aiRqBmq+1~b5Ej^&RKI!dZ<#>%WH`u?*3wi=37kDB)J{W@Q zdiz)Pg8i%dzNLuRz%|Y-mxjJ^{=gi#pj4I&72cLslXy5KaKWHXIOEJuoMI$wm(g$x z8r~*q{1gMjhsRFHPuw0F`0-PUmI*QRjDQxkO5l4X-a3Kn%^%u$y>VOJ-L~^44(;{C zp@X+aP~iJIvd~dhZgcuAbiR1B;+nkQ8>u{G3ZeqP!3HzWVy3s_?NrhQ#7F!}|I0yv-9v?eBBx zcPvM86F1H@Z{VM7h7I~dY}}x&17n8x8I{I6)VEDs5SwM*?$~hdj*SpCtN=etdc#aw zolbs~*WKY4n}hbKOFnM9OwW7A2FdHam~nvtZZ>gdA;EahvHmCRnE3_Zc?34k{EZOo zyU`VJJj3e{yzM2!nCp3`#$f-9y)wIl(gdBlAH$t{zdqc(u?0SiZpX6623q3Y*rK48 z@r*la-P#lU!f+E^juEwjjfUt#0t+@ zR>!lv{Vu(S=DIGKI2Gd?hx`ZT#qFZW&e)}Y*crob;Gy`vov{trdx+~*du1kWeqEL* zP841qCyd|F`rUS#r_(EvO@G)Ki`z;|*csarB%n(*NFT40gfQ3{yFzi2q;L3e&&+c$ zz4F*5`(xX&iQw_MXQubRcDQ=znPsAdOJUA{WWUUJkzImghvMyN$OemPR>ay46m^g9Oyf%L_ zwQB2^kQW;pC;oKSAE;!E?hu~~4sdZdeB;L(J<*ju3{|bWcv_07ZbGLQNHFL1BwiEf z60o4e^Y247>ZSPfYLO7p-_WZVMwXZePk8>E%rndvl`L zN7ANPDuTB6_02&eC8OBu18`5+Ef;{b+w~6^db%-CkWC0e)3b3Iwi>BQX@O2}n)@)=IaBz&Z@kUNdC0OB3#>u>#gB zZo*QwAzp^Kmx+Y;ak*9O-O1yPTZw^GH^oa3V>2Y)T#p*J_){y+8{_Y`>6s%78&fK1 zx-#BQ(A(l|K|$iaE3DL|!C7RyMa;#Hc)a*tSv*EKoLTC7hP!kK7W(&LQEjw%x8#lU zGPwgQEm2#z*RzmFSh!CnhfMn#O5%|IG}6_%KQ1Qk#_Byx#=KrtcXP#iq`V^=l#*`a zoIi3qK7Q7yyFktxIalL+(VwevvZx82F#+#N;V%-`Gg|J_M^Fk8S5bo`_XCpd!w_2xveV3U!a zU&*_ZlNIa&SB{^yRtX4B;;Q~H_PzwLuA=%o@6AiNDd}D)J8jvQCS`}_r3F!u6c80? zTELRFd1;_cO7haZDNPr4Op#ql0YO<(b`(-pWeGd7q%4Yn0mThWQAAX}-|w6|cjmq% zSk^!K$?|e%?ks1{oH=vOnKS1`E#?E&ZtLC3>IPdolQ6_}E2mKsVRtzKJF`Yujbo%M zu7yXP+Kdo7a?-M0iFlf9?}~&{0$cFTPgK*`(QY78NLkEIj<0E@h;+oqIVQ1mEdZ z7s-7hi3St1uTx0&i~5kQV*iLhBzXX??!04KFrB7nE1r3>UL7QZYlxhWtbzY>+RwIQinZR3zgf)mk;61uQ+Yx6ra zsw}>GR{nH`YEG)7Ulrn|1%cGPak4yX*kyFMYhKE$YH@^eyRWNiapaCb(KjOO3!LAK zFa}|PgZvf%7aG$eq@%2AaWqv66~hH97I~fwu9&N^>=qKY(&e^08#0 zOQcHjeG<}q=jG{nZ8{fEySTOR45|w1(kaB?x;@c#>z@#bho|%IooQ!7&9ncpo}O-( zP&%3Ko8a^E7DUMKtlbOkLDnKicD{vM4bzT-lvW_`M@v~4)RJf(K{Gllp-o!WiJKAM zw^MVe0Ys3+tlF?r^InCt5D~g>o7M%qf~IXLWcf&FinbLkM5lsiLq;yTLewi@rmheT z34XGq?=xaH^D}!GuxW9&RP9^B&-U^KZr^}S2TsdL{Yu|KzB6pMBq%(oVVf?UR$Dz6 z!h2pG)dxFbst|5_Q_b&uzL%vyIrxImW`NYh7hl`MLW2)7j^5T zsle*1mkQL(VZTr&fNmhejTCo>ti{zL3^qo$m&Kv zjb7BPlVZ4aL-pM{tvd-FI#mh2&95&#{#eFD7fy>gC)E3HoRq5Xh?K(ioYFeNwK7Ab zE0(@9NBz6Y*2&i%w9eg9M`x9_?vYxdI*t+FE4BO@_pwGuIjlijrSg8i zCE)4-+Y^;?)O*m|?K=|)IKqS5ihtg;WA&#o}l?%?~SzKW9#3IJ~g(`W|ja zWc@vT98j_Jd~+xlSb06}n&YI)+|v#BW?u)b-K^us8$^(DBk$%L24QpEA%_zUam=Bj zz4h7I5wlQcHP>-g`5hk-y>NV|9$~5}7aZh9t?T?t$Ost&N#S5C{ePL#zv@4H9nJn% zqrrs-3x`;FQx7RbxUx*ddg!3GO8?~!JeBGuM08|_8auo2kmB?mJKsD?aqc^s>t-SD z!sGIt6Ax=JpVW|h`_1M%ZOOF{mB~kfC6wGV4m+EA!XZcu303D_RV!H!4mwq?eEy+@ zE2tGr671zu^dQXcBtyhhcmP>D^>I#CW9p^fUPN#34Jr%$?1z~{xVg)&zQRq2|FLNxi*e7f}oCt@@WK&onCe}b@ z@ny(UJhOQ0kOI529#QasLgf}u2T>Y#NLrC_6T_}oqKbeLA|!rdK~g&{CQvfxbYBDn zn?1uXA#{9ZEQhBT#1`cZy(^|v#Qx8T1j6qK@XXV*3VWWy9#;{{koGuj{+%&pdQ>?m z+?*$Wu_ky#K|Lcf@Lv!m00s{$KHS>x+x5R7ei?arJ-jlk)Pnmt7C&lh5p zC#4MwA0ee}qO!`SzN|9b$ts&g9A0?J=1x}e?6~4#tg;D^&%UhxuQR;B)Q!PRo&Y;|V)X z&i!UYI}T>HsG4*+b*dSJ4Jc@36_V0)mPeQl%Hy!v8*7|^ugz&!#ih|Bod50 zyo#UfTF<-!r@LvSiz#OY27=k6^y#dBK_8`#Rvz&#VU_iW?#o^5sS8R73eBi-IJDq68Z zVB5L9XM0~y-XTX%-qGKCc5+My4BsWV_v~W#o?Y$Uvzy&}cIQSj+ATocXo};zN=bw_ zyE-^>$II=)W9}aDT_w)Jl@F-@oxd{uU@W#V#AC6$%Kt?i7RwUjAz0k5;`!ux40K!% zOp$?(*Ing6-Bk|auJWa5%4H8ZIGO>WKls?$xkckdE7-ou5tiMfoU(~S;+xCY?B;SP zHy4kgTb*Ts6OFCP8ryt4-W{@SxA}MuciQ=pxtou7Xs4TxQ$#K8Sk^2Ww}(5&m@Nqq zcgmS7gv|HXl_*Z4JBm=%o~!>pbu#MVQxKS>EU6*nF&_d~7ti4nWS0dfNH) ztec0YzB=giFwkc!T39{p{FC)QJ?-RpMr-vJ%7s|7dadvnxf+*=)}`3E&$zq8z)m6u1CJK`6V370!0Lb8%uBym;u9d-s-M8&x@;+^R2dvkEzkzy^zW<_hx$%u!!3+=Mnm< zTL0ljrw18JJjEH?>?yv&Cur=cqk1)R)#t+9qB@RLYC_# z$cYmuPDf>nYf2Pnh<=Iqu(knUlKE#zr@oG<9(DHEfTQNk4B~}HU*Yb^mFhafB@L^G zxEIt`rM#tNSN>cbGsehk8}VD}_EM#x0$|C>L*a=fDB3e+PFP zcapJfL~D_7?=IcyJC*DRVyGWmQO{k!jmxw{w zecq|X`I7HA`NxP}=RCYhQhLS#PzYN*hMfb&N+C{+QYdV`Q-fodw>(vtBViBwSRvRc zzMu?!x1Zl33#)lw_;(B$&cN?&i(}zz22#UkjH71omd&J{8yYPBTry5Rvg2U6@li!= zzIL|_?<(+g-jTvVQquAqH%rc4inHhD2q7XYOHqpvLPcnXj7u30qDI)2qJ_Rnq1atz z5Io_OATAU;4cZb6hoSINtc}1SOZ_WuNh>4q9X0pJ9;Jt^ucDfv!~C?z8EX_k3IK61=a zfv$2HieJb}aVtu->n6lho_{3Z;S@5IRWm)Do*2vJyburWoWQXc=Fg0JbNM~P-`Q4h zbYQn`H{o@(UCeeTD#~dP_|8(E^)SlItG7FXmT7PofFXL>mN6D>9QSu4T;gX? zbaUyg@p@^@tH}3#k}30jg?LR@`GZaw&mA1UU|%b24pt}EE=Z%X)mzI# zcOOb$@qM^f*`jvUERN9=IbIvLKs$wL~%$zH~Y?zldSkCQJ6eOe0LMJx$x3b4< z44`NI%C10tt8x7RVtjbDH$*M3_PVV?)t~5cFQ|=Id-VwOYH8D|U)L}dwQ;RYffdr@ zDpVdM)#k>D_OypJUY_P$FHo{|I|hW&1KhM)+ngIAKHGIckE^&2cXQ;2c8m2V!rV&; zJ;Eul+$KI~KbDf(7yYf^wI&hL7%qVY^xzezqAm7h6v%ypb~qgoR{}2X`?g-?JJU}W7IZZjbV+jyr!@MgTKa; zw%nED(e^qavG8IB-|#)@Fgw5TAS0*yt))_#hd1q8jsvxSXGb57>-YXR@%|6~d!+wp zdk@S1$!kxAnzy_h-UoaeX}$LUXL-WMG377VHNjgSB``zpLs0)18bDhOmS>;buz0T z);%gB?crp>We6O$7pEKhijC8Zu{;z8rxgPV&FV!fMsFOO>cq0RW4)+5=!KKn+h(x z-XM3%1Y2tME)Hpjm6j<(AC3#&I5Tz`igJ*hQ?b}@RU~g))ZxpJF>vh?#A$*jD-#?d z*>ji+CyTA-YR8-^=ARh#=GaV6{n+-1qlmCaH{on$mdkfEz|Rlm!JE$3AP#4{q%MM! zU4|?$7OIbwMo=M}hh}UE+bU;puZwHXjZS-ZYB8ZyfS?#hhz^xkoLG41Q{>H$YtLR- zcpPD1T4l+R(=75;VQ9v7=_yv5qNXETsKl?b0;!gg_yEobL^7u&rAo3&=XSW{-aXW1 zJ2Ed8yetCiqGwh6STuM}v#scbt&$zWPV=cb%511I%iwL9Fj7^RXL+r!FDpTE{``3F z%9nXa65$B*;kdPTfkC0KRE?{NSjKcS`@rhs{>xK5^Z+AVh{ z+vaMAFKC0rs%p0^V|BsHQ6{b(LeB-7sJZ3dDss1yt`hxE^xKfHQNP7m2>Q6%%FaSq z*T_h1aN}#GH(#Dt9oOn3)N%dL_YxvL?17T^^`a4JBrCfxNdGsYp4B9DQ@#nbIOlACr-m8)_N6HDqarurpM=WkyU#+HP2$+HUk7IDJTP zO(^C5kgQtOt{#?IBDeATe}wf(tDsKK$)mP^rqSPHiaXHN<1#jCye_mx?7k3cKV_i_ zTjOmZyN9y1r+p0%ZSvxfg`O(Xv%ZFh^mAxW;p+5jVs@$PMsTC$=P|nYS?CK2Im(LO z8?HwcFgZ&Hy8@AqHL!-@6NPL(*BHYAjCYw6V1VJ5Kf*ajtZfA%# zE5ft6JvH3Io#<^DE9#oLf#B{e(mIW3#NcFz8aUFlX+JG}^k^_lT$;-IeS% zI5NtYT}=6v^DINR+d1KdN6%hJ2-}8pFwVz#eS4}qQ;i)o?i6)OU~Dta-xy3lC5&C7 zf*7G@?P^aXW11s}xVsb<3<(&v-O;WQw@s@m8KP5LE^+GE7*)qY-O+8c?8Z|ZU3028 z3R{Zxy|-g~s*Xip3zK5HZ1)Wd$r!n2_lsl$;NP99+L)>Fg#(X(yMK;<`CB(6HW|&}|84jZw zdbkt#NfJ2njH{u!I-MfJ>2pe=n){82GL#O9SoJ*fsVLX;OuKc5opGJ?7>7Vrkep*# zOed{~^{o;u`;TjY{$lbjKt(hLO;BAwj#G{F_#J^F@3UZRaY}?SSyzb67BUhfxuPqr zTgX%@h@NklB5AtQ2EF4>rQA$7SWuV_wmMQ$Le*!6>pTQHSC_NPG=9=aBvTuVpL7yU z9Fo)H9LHh)tf)7apO@#Ia|#T$6;HQw_@7O!@4rB+gHDHSE1-DjPC0R|1U-(E#tEZx za0&zrtKbT9d_98!ACwy?+Nr_muB7Q@-g%p^=~)Gi@>hg$&gKfI=LnxznWLzMr=7w_ zEnUQwH>;@mfrhP0<|}WUP+Qhl-~0vTt8fvRyoMFAU+kw|%m*Ed)#tvG@KqiS`k(@5 zMV7~*V3YsW_(!k`LT)_c}|r| ze*4Ro;~{1Q6qu9NyUNScoaiVMY=^2|s5C}u=5?YtGG4Kj zs~E7@KOp1*W?YrK0r0B&q`@MnbigGPgc1uDA=ItGBB&s!n&*2|s+wn&tQ<8Du&J8I z)%%l}Dn~9CSNAk<1mU2XCyE-F`dVL66KMF|FID24q8C?i@A2k>(*C`obm_Oh>>M$_ zw~!E4-Qj5O7ySF`mZU;^=i;12)l32O<$MrBL19_TQv@fb==oB(+BAT^p4}dk_ z)6dX|Ev-tLY>eT2Q!W^-LTs@;Unx;(cFc~zA+8450|w5}o)Jogh7iai+7?BD+1pK; z%BVc7gSdl;eRvb@Pn^#Etk}Ch#a{JM4Hu_k7aEn_f;FSmNy6coobLC!E8z=emg)E& zt2&Fyt_VLqTjul91NBzlK_P!3zX5Dt^6mqG<`1@ePUMHG#pr?>j)?r@t5OUPhqzUy zIQW{{fDYv!pq<-FxqU`?IGRT8?1$Osz8HnmBCRL;|3bamrAk^JrnLNTKVR6Bn?!^z z`?Y5QBDvbwHy{T@zVTPYwvOUi&{=xGi3n9p7iG4Y~kKmF72$6jVifS98wFR?ug#AjE@j&{%GCo)5x zCm+d-#Z_>hhLF8rSG%=I_5JBv7-?)`|KWk;)-z^9={2t&$p0V*g%32LgI=vtf+vpC8<}bW~@ug^w6{^JsWcSc7yQ1Dma?O1qno*ey=@3$YZoyx(i{6$znLx${*OK`XK%yg;-q1W3|1?jS~eK74!;i_Yi6Gv=t7P^LHnlZ6o%)}E)U zbz~-yV$EE$Lc+sjaw?rgFm^6c7ty4h40?Q6I@M|Ojf0xQ-s_{WYE8AGIpj9TdpkgD z?Q!qjg$dTrt=*W@I_t4l=P1HjHg_(ydTXaaC?;Zo(mt-VIstV7u#mUV$)fNGah<5t z0G|;5I&G6f1mz0x2eI<86*Oo~w9>6MvNVA{WVXnnn#EGYP)xSeR)&{cU79w+a90Fh zkV_GOf^xPU(W$mY%q6e8hINtB>z${2IdTCanm+<9cU@&3Seq6=>qbw<4T~Rz-820G z7R}>r2X|?h_Z+N?fUaBp9+|at&{4yV)Tsd90Ax0PiElmvzob!5%|PB=1?8@;5qw($JzEP2NzMPd1k-Tmi0~Tq zuRa|XiLN=lxuD7t2X;kh6p4Fv@XeJmXxY(KUPtx|1&kW&du!7K=t$A^8{KXIaS#{R zc%;EJqRIjnEUzX!MwPYgxK`i?5)D;z^}A*&x~UkEs z%bpoS){Z}#RKB2-9guYLy=y0V3YTuaZB4O6#3Rd0_eMfP!SbZ5U?nF{hF>I z>Tdp^Jn5B(NI#|jN2J8^%7Z3AJC8&Oz!6s>K3^Lb#R_H6{|n0M3)%k*%KE>ctdK(v z3Z+$SP|6|x7nD_`Ip>X#59X@}m1Mpy7LLo0`6RfL&ZA=d+i4RT4#$a~R?BcIjTjSh zl^UybX}$(!b-vAn&8aV;jDM^X!}%T>i<3oYm%1}1q0wm+sL=tH{7OOoaJSp1oeaXo8JMi;4 z&{=9bt99exRu2yYE5NZ3qOj`5esbJKR&Q-*4J-iH@Ms#@joW4sg4N=ItS^xt95CovoDpPykp={9$5;Pzs;WY8dPFvjh2TWylJ6ZU?M?Gssh;lHXw-!{G$DJgnuab(yqRt@nq z%3q6gPYsK@PYlcQ!s(}SOScxi!wZ~#I&Lb#Zf#-RHg<8$6^9s(m&UFvx|Vkj8l zahl5o;BRWPwEYsdpb^N&ktVFnNQ9gR$DMkQVK1@@+(fi6TE;-ewU2|8tYKd-2{PX= zYz>n_s`re`ER17M3zpyHST`D0Ds`~3QrcfRgaAjM%2mc$_A{PE$h&N~v;+MN$bfzm zIPX+$g}6J~&X=7pKF&CmgMHO5z(X9&ZfpFS2O=Oo)EfXG#$l&LDaV5_{C3oqzv9@_ zk`ae^xK{zmBkU>H*S%rLB0Q2K#?3%N2~o{+EWyTvFggDAf0SR@k5Ra>II^t(L-cNI$CkI@ zNgn+8Beci>aH^}#JC-vtBza-Cqe6m}#CC3lD6`q#EeD*bxwlqEfk%j?e(*&{VBm{n zJp5W?#F2J&bheu^C(ozDK{wjbpj_N`&^wZ|JTN5mF>XLyrIrtdbibz?Ay)-F?iHpu zvF`0g!cx}V9@EL>zOIskVn446y4^nnoK=vdqkXu)FgaE^6**#v5w@ESlOd>O@x70C zvcs8X;qi{S@glZ;gT@cCEYA1;03T8R4-~NeA0cdCv25w9an5pxpCm^icMOS>5FBc! za4;sfJS0oBNwS>at#+Y2a7Jao;EBqekLZU7R`q=CeNJ+u*MzL;Z}=JDl6IE>e+-x^Gvq7jK9_Zl^_~DtBuw&V5(9NyY;YoSG6?BIz|o~+9P02z zV>A)s(S2AK!kzoDt`ngH*OsHTLO0>yZ7xC5+Stbu0fy$Fn1?%@@_1+rN2BCG&IE0# zgZwIx_3R7{;RCb;OHba1o7fXw;364p(>Po5Jm5$UkbmunNjbgvz>)g`n=_!`CG)<9 zGKs|d_~cXq{}9ReuVhZ;%sEvh4cV&7S)=P4YqK@8s!A$nP2YF#lA3+@-*tf_6BH@dpEv1DpZZAo!)$;_ImCDqfW^;K%`;(d$vV!7zQKANkkoi?*^dR57^ z-F7R{N>gjH4S8QcxT@x5KR#G}jJ{!hLw#LcwxqG4z9hs%UdfC)%)!*gnwit5;*~r! z%&fGtG^c(_ebvkn0-6FCN#JUNyC``qQCztQ|}EpKK{+XVlbB zpIup>onLZdLtX8(*|Y5;mo#jUv#V;co-1e96yqgWa^BR+hMH+p8nX2@wbjKl$f7H= zb+c-w)nw-*nMAyb?DU%2ES_;VKL;((u4+Ic1&<7@`1#=Dv!WyzR#olvs_D~f8fMR| zWPL4GIeRuZL}j+7uGZC^HluQORefD;Ra7j>X{gFJ&UV>#vu4*d)MV@GqpZ3)RrP)c z_3XBOR^9ZfnXZG{x@=9RN4ID@i=nz=+4{<9Csj?KRynJxzB1}zT3v0nzHa91%G#=# zE^}s0Rc&@!T|HrjCFhG9{WG0AgXnAY*GIJ8c@f zs;RBX)>O`{Sx{AvovwxljQ=y*chAUTu;HUF<;?A58JgbwQ&sBt6X1IiPeWUfT}t>qkc3f zqq1=(DGKNp-WD$49-|h_2?^X**)lry=#u%JqBQZ z(UjaZapk(JmZ9Fst@c&(N+f^LgqpUU$D)iDZI~HPphVeqtI*7dRwQR7$0y7Q(ffpX zwkb#>e?d^Z%JfIS-m6ENf{K(04qO#%yXrdpi#B%X2-Z#-T{6b>Z(VlfuA^6vF*_BT zZv-QPve6}`s5odGbIO<*RjW_mg|B9{o6Wm}k)x~4fZ}C$nv*MnVO6VF9CO(WGpHjN zdD*hdE?ai_YWL5|U_{wfL5W$=IpL(5VC3ayaI?v_&l!FA3stMvJb&-@M+M8w7Okmd zFbjaxWH7|xLLW8lFYJ!Q&gB+`W*_g7WFi!UL3&6B_7Y~}pkq0*pKQun9JZZ^G>{4` zDG{`SczInE^-Nz60q>P~8~O3a}`--p&h zg2_})qtpWiLP1WL309def9xPLVAfy@{T7#>hpP$CVTQE&ClUU zn(6bToE*!O!fc->X_n(jn$F=#nwiU!G}q%vnvu(skZWaeAWkuRNPXq(88y==poNH~ z)K2aNx$MZ5kjws%m%vW9(2Q*}1G8pO*3`G1Yp!1sWX?4clKUmrCAS}n|H`(l{>wW2 ztiWz)RwjaCY>4Bwy&E2q$t2hx8k^mS#(tMbbYj!Ky=eqC(~d-PXGBcE>k9x{GVj;u zwkN0jxb}h1ZMl4ej-XY4d^Wn_{d~Gx_mt`LYb#+lnBq(fQ!+Cvvv!Hv^#%H|kC;d- zWvn*PQmADHxU+x9p9~xYv>5-}Q4)cKe~@n99yrJFzVMwYe-8ti4PtFk%0f%-B!Vo%XIp zwMXsY_2mwbWzVD3PD9^8>+5IWXXNDYXU(0NarXbP0N>fHpyaTyU~;>mc;q;dA>-0t z3m`}5;Ip~$GGT3wPm5LqAQshP7E#RMb0fi(u56AD%py?Hx$ayo?MmvCOS>N8dCbp! z=hw9@`@OopWx&w{C-)+H0uD%<;Omd_KPU=S*IxEUFzI^!&)Ro_!gd}SO!ohl3`N7Q zFTe9^n8`cwB3S>3|C+_$2-XJUa(<$cD4+AnCH+FZJ_|G!!Z(6t!JIde`wS%*zzaZs zJs6hr6MuyYq^+=K@z7w5UmR~)e9xgMfR-%9+VWBBz?0Hw^SI=fhX%v&=bLB>*(7t4 zE*`>`@Jz(IX_hBaASZ_jol%`Mf2Ns(mcOd_&Ws~9NckOxa>47bEM>n|_`K&(EFyho zJ)w3@YDWTvrTz#cdC;}xztd#{yl~M*i^mdI@Gv`wmdWd~asLg+p2@r~!(P{8XU1`y z+O|C-_h-LZf2w=i7w~AXk6r$AIFX5tSMksX6#p?Nte=OJ^|@+UA9rDWcDnZ`I>Y|# z!1|9oyo2Gss=mIiUe(?l4cDor5T&7-g6Xi7qN3`MRU%=icJ^um_JjBxTFC?P#F97eIf8kA!^Dp$?;~Yv>S6^ph zVPD>v7;?NbF;xDLGch3FU!L(ZF;u1MH~VI&e*F@`Dzk0IRA$Vc<>rWt8QW>TnlWXa z=HQGe?KEG>m~^xGa>hK8hZo&ucE${E!{LV++Gb{D%-}XtmoY;sOl`(Ikk=lpF_rCR zQpW5Wj4;P!%+B~zkukfpn~51y*lp%!Oi`Q3W=y{>Gbdv>E^=@{HLFjU1jad$*gzGGnG1q5Ont`mZ^0Q( zvpFtfwre-XXUq;6b8N=!k2+t=nEl#=2hD_x8P{&Ulri__Wz2yY^F&_I29#}`VXGzO z>|)Ejjkpj+`a*kf-V|=GM2mo{vfN{;7$Fa=>>6yG{ zbN7;NPQvD$#OAP0;$lcAr)X$1vD1;)9c&g{Zz|e|lHGtmU}+cpnF#uB2YCmJI6p;Q z#6%(TqY2syNSjW=9znw1vYkXXZ>mht-d)7e9(V)n?A6ZM+8(IF{EtE&C|hy4De_JP z-L#W#hG#I(0TFjTFy0KpFgvuHnxI1{xSf+SFher?X&wmo?j;%Xv%Ge57yg32%su$K z4FJOAZ{1F!9g!hD?2DqHTAi)^Go;sIWPt=q+DX*AXSk9c$qR;X;(^;?n5ARQjBYcq z8z^6||Ga}graw?We%cY3KGP3{_AuFw>6oz*sI<9Mn$~TGb(>mSDXeR&nto|g^}uot zLD$I8P9e``PRZ8Y=(O?{kPGL0U!uIQg1Fwi4eX}AoY>#Ef@`FICZf+^{Iv6?&X{fn zb#bwc2wF%rd!zp3>FDTb0C`1UFq69MIE1nWld}Gi*BY!@VNL#pU0 z`0@V9P4iW}gjYCx$M;euRxr6S^xYpIkWw;lE9}ajsqXvP$--Y$rSTJ~4t=Pmy}2=p zx&4!!Pkm|@j?ZkCKfbE_nSs=o`QVF6kD<=^adqqsr^wHEu0F9(?S_v;jURdR=Td($ zI-Nqqjj0fFkQi59B85f0P@!`A4r;2P(9;f2kfvj;Q6Uk1C0BT-uN)6BBfUxVP@ zt9BYGbD@(aYWaFD)S!=|zp^%b?!+I?Dtg#3>MLuf*U^0z??WXOPreR{q(AbwYhL&= z)LxN-*DU-+p?U$$;=mX4dCXNwfmKfj1r+fN)udJHgKh{mAPS(WiK>aJ2dAEuW9(y<_)iJDqmb)Yjrm>!*BTVY0yqa#3!TScsEX5~x{nL6DmkMU?5 zAu}l2r_Hc72+#PFUKbo|o>>g9vLP*|HZ4*X@`oUQvblK)@;45si>1xR>0s4lQ`8*n z5j2>&X;YXD9>+2HQ;DDp=j1h>dl44reD^~hwe1-STnEH6s1iz&EG9sg7jtAkHtwNNg2J~a z+2*enrzaqB<&vOzQs^uBVqRu~`Ejxp*?(A6aTr`9Q_Eg_E;xTjv!G({m7|UcSZ|Lk zUVlTNGKA{tMd{Pl+=v%{91wJyTTX`D{3DYwXZBA|KG)n<*JauV6`NnxrKtsMo;H^c zsxS{Cck}E~)^ksNJw3Ni_2)~NO`C&V(D3tvAg-S=m!MxXFS!%_`bMNuaO>-^Zhi3f zOVO<_-Aji0`H4SZ5fGa)KW&1aU)i6_t}8=>KLxU@OV=G*R+=tDS6jf*0l67?kD8XG zg=4E`RC~AyvU=z>*n9*E4FNh*=FX;Ww(}7D1*=Pgp@*Usx|Ettk`vLAJf38IQBP1; z)a#NN$rm@*$dwUwMwX+&`}|Ata5?Fa)L1;V7ZOCH@8>m} z>8O`9v$(j15u#ayXb2!Ovw|Ub+=Q7kHFNTG=?vbt^kUD>#t$UB)|Rd-CFi+tiOj*9d4%TfB=P<; zxU475nkAgV=kkd0Hoyv(?mTjA0L~Zd^5Fl@L4a{Ln}@Nce}bVryto)tcCjH1|7MXa zlsrCjun7#k4R1dnGR@M(>EOInf!U9VL(BP8&ZqWoqxiq_V3ZQid2>^u*_<3?xPX3* zDabdk0aEbK#U0}?o;w%A-8~#L8Nrp@&{F2w#ljq4Nw%!5dSQ1N=Rd$iP+)mN`0bzb zvSIu8qx}V4=zav7J%NCXARs5SpNfXASPUy$)P9Oy??Z^qYYbRY5jNMk#n=@xrV)RN z#{`YbmX^J`?Ar;trW6r2$~zu2sRH|#$*06W)8N^;*wzXijvZ@8;;-a z&DXWgNx_@@9kky;yNr7Gd{Knq>*0oqzJe0upJn4m*6p{0Mva1(>PFQWP%Q7N!ro z;CT4hXWP$}v41;gMzy550Hm!I&RbM5hZTO6q6l#D!ZfY{tTkAP`Q~3K!q<$fe%NKF z1r;MFVuq9EcLSJz;mHK!%>f+S_fF>GS)HhmM)S=%36}U^K{;~Q8}gj97ZtA$4luL2 z!#3WPHqMYX{wi&pBW<)LxF4)*A}ODfPmsD76h9n%&-^mkJ*jlm*mc3O5UcNT5){>^ zHpwPi23~;`jMcCET#M!OXyxyT7Sj-3)Mze^#p0oG@FfNRe{Ii+$!8P@nQ}nMMQ}kk@eHnmzZ4vAFfVL{24+x-Z zF#-}r$~@3SX)y&`ul%VFS~W>zrXa>>ilS&+Q=3JGw-YILdSrMavp36~I?I1s6tr`e zmzwq`%zSe44;F#pURRBO%fw`w+6d~PjTcrAvaY2^h|qi5Bp+$rV@z=jC_e zv1I`l@7wv!@=WA_UyeXxO;h<8q<)TJl3$XOf?qbTgtY3hzF$K?6yBK3hiUeHm>rV% zO!NQDw7tbx_yo}t`mhFx6)z7rd^0i2PcL?rxZdnrS)k)nalV(7vUfs##Oslj%sUdl z8)9zH)6-QLFJe&Shp3?1}S> zrecH~QkSEoFrou-VB>XwGI8K1REb9~8be637IlsW)dLOlnyISHHr7kD6cmp9(FCBG zh`5445L(L}JOIMj!9$pK2M@@|Id}j%;sO-qm=pd0Ip%F#$xDwjZAqAfpIclJjDnc_ z*A&fZ=8T2uV^)6Od?m=HAz^PuP3NTKxWs+X&S#|8QKvgUUo3g2EKD~d^@Is^VHEsL zQ*-bw=nV{ffImstDN_7fVE$r~JE++j!aQuUl8szdX_*JZFpDxTM;Y?;IM0|2D-Ki_ zbb1y85d?4+>86sBf^Le-_(5b;mW(SjL(KTSW{4U8myBBwn3KDqjyyy&TE7k?8 zpVtgXYC2K!`DABk0ywJOG{XC50xWCIW*8Ks!2God3NyzJMP0B1WUx{!gZWns7nEr}2mG=Vtino;-IZkk3@W(~Bkz&ry(i#+cMK+9qN4$QerNHj15 zgxxWpMVBv077MardFnvJFTmz>byM-N!GvI1up*d+tjCdcYg3w8M~7MWA?sc*Yt-(= z<~HO#28}o0Je8!m@0P{cvSaxIFd=qD1}{3~#ag^LoG-4zi(kl#d*#K?@ZuZ6>*gX1 zBH!R6IB4ZDSkv-hW#g)NY%yEE*Rb^m7p3n+D2#GbhzqHxb5>Y~<(`*1S4*AerOvHV z=V`5jvpTJFidUyg>U>}7bV;47rOwN?&QF?HY4X@{h%r%Y>VqM#1D2aN>Ne{z71zK% zQDD~1Bdn(s7UTI8SmRUX>_pIl#Cp7DB8}6SoT=v zQbJFspw~VKQPx92@I66AG5zLzDkk8)qarZJ2hDx7dFGN}NW>x@N|8m}u`pdWCt&&S zCptW|-LwQgf>;ZHI0dXE%)Kahb5Qbpa>vbtpPY+VD_j-j4{GA;2fIjnYGZR+e)3C+ zR6p}K;F+n+ov3rpA{P_J6q1c_zBe}40#-50c9gf^R42J_ z@2~oq`%T+r=CQmk%+s3-ThaA}sbYCf%QLMpn*XqAb_JXJESN9{G@H7PU^PHF-whU1 z`+8Hm$Da~r^%Br7sTK^vBMBhxnkAhW*0)GxeGV!xhjybjd0oh`#L#ySD!wbmyuG{7 z=WR=HgvjHckc!p z@4aimRnJ#@0;)b=B}^B5UvbQtZ{A-lba`qrIXSW7fSToK=^znE#uKWua1KQa_fNpJ zS|L9q%sY9_Ec0qYjvH4CPkR+_UtY|O)Y`(|&156Xq@) z!F@$IB8-_l>bM`K;FP%; zOMuh$P`vWjWqg&|)qy!pcBBTGQ*n?Nz$HAnr?8@gxmj>=4sju6D^viBbDw5E zv-`zx&8?!a2G*r=UX+bY81%IP$&B%xu$we0KZMX;eV2^dTeWl*MtW1CD|Z*Av~YH! zyJvP_Y9fx>{bKJjB#*Uw<#FUD0Iu(sy}Y96`AlBWnHp^Vur0TW^G-;c=iw!fjPthT zvC0J}K%$x)919hs*@%SlL8zy|D+zm#p4F9rVyNJN*1VH6uoO<(DRdqPW!fW9<|UkR zBYV9bR{ss$VX*m|^nMz82j_FWpW%8xM|)o%^?rQR`*ybXXJWm-AibZJ)BBU!`v=#rCXzx7R*MZhV=WN4m@4t%m{Y|xhkJjc}L#CPm8_hzN2_4QX|j$-dvdJQ)=vI zAYPseIkZg*cJxuO1(4hWUzP&%AV^ethKA9zXD;1CL;REZIbMAPYOPVd;sc0rg=VR2 z0UuyU{;+Zz=u_OGEG~Nvz9B13V?_ZGpF+zU3}+2kl(!iA1XXB%h`+0d=uG)l2otRSQdaleK8mXZA!-jmy<{0uy@LIT0 zBtd6M^9Ee8ip&bEr2!Dq%JB?xreeJombU@$c56r0%_8ug2j>+_)J5h8OPZGfwu2;| zB`2Zz2qZx*LqcXq6pz^g{rwOV3mXP;_ER*MG8cnDV3;d1gS$>dAHN00iqKQBJQu@( zBSlxN0cJ`U@>_)*meCIR^5V!Ch8JffXa;x?gfPH-e=&X3u7Y5jZ(e~-Bxx>#O{B;? zvXD*yPhm2O%#DdGAhDN;EVyCCt2*CKEo(7Z$V#M4($FDb5dkZ!wL#u;i~9u zDO!R-xyvBKZe+gO)PZk9fIbIf26y1qMYVKox-mt~<@WyU?E8|_=H*;g+nFrnn7APB z-KO^i(H!}E0vCf@4%{C^{f9(a%pP_vq|EOYw}n2ITtKEZSrJn-xF%>|`R8J?vWHDa zY-MnwiMk)BI4_)Zw;I3-HZngD{&g{VR)sn#qugH2pgy}cNW6Wo4RWcEv^G{Hxn{T; zdRrNmopNz1JGG0DJme#F6kjXi|K&)y$5JVim6C7XEPxdc{)E_Mdg3lHXQ(Qw3j>tw zgo2eQ|0wQ6>nf5a$f{ly#tT-wQ>K z@$E%Yb<@D1JUjppB?jLx$>PL+)|Ay*g?mKAQHqV>w+785@ zTkOvx_u+nL@!q%e_%&s1JPHoROgs!9cQC_ntb=IKlgEx4+sVtMx5LmMsiJCj{byb~ zI!%b{{zNmn*i7tRz2?xe6>}z)mY4w$uZ(^Lzm z9?HDWLhj}>tPaE+($E4FnKvZ6zcISZ6!HY=JGg|vOKsgOR8U^PusFwO&2|+tf>ld{ zzXZ$8G5Cgv*{$Npaigm)3zn@hMdjw}ps`K6`E`q+`r*|k1HXrN7Iqt4z@1&uWd_nh zvIhm#Bju^QarJ5>CbU*3_ZpTQwdqj@?lT?~KBog9l$+WXb7XQ1ObFw~?=}~%c_7$i z3GP+MlW9)!#E#GAUl@?&(gQ?tV)sqmF?Pb-rXOM{;GGWmJ|rW%g6ByDh#rK9-_Txt zmR>@qT25X(%rl~k5z<-A`8W2_IlPR- zUlowmcNx#tcNs-O@fS~V@mHV@l>)qsL}6A5MPWEW$HiYDrib{ef-MjP@e*}?nHNbr z5HuAV2)&pAK@TrxL2Ygj91D+t>|UZnT|W!~wvv3BlgM{=v%N z#9+jUhX*Uog0?5*f>fr6d(%Vzv3t|!5vKWLv9M3XS-&t0?BfjmGv=uu2c-YcLY8gN z#{Bv3O>^pJ)>X@QWnhlsmm({t+i+gUh%raG2h_vf6Pg&fIjI2$oY(GYc+B0?xN~{t z9q>52r-k*nr`aaz^m+_Gr>mc4MePl|kJEE^L*3ln4Sd?}Zr-MVp#TU8(1pi;x0j(v zxR((HxuzU$G-4@Xqw)z_Y!9sB_OjU_)?H3~cLR!g>}~+u-_g+EhwW$>d5;|pC?*Ux zXf~3*P3EH;YyhQ_k{Ew_?tV}0iQVsCIFRAzB>y;oUR9T#-1!1Dy7LnJQl>pgPnau~ zv?uo;8jO7LvY;_&2R*dE-;wT zEllLhCVYdXki!p=&Fplz`UN2s20-k_d+<6<|X;+Y8a;~YE{e( z1|As1H5$RF3d|n|XKeH9dN%)R0=ALRJh3`ze%*&Pk8i}T!|;CvKUjwt^E~cN&8c4w zD-!xn6iDcW0`rYd83$sdi2W*`74SZvcYHh?$Si_@yjgsv2}Uq!D!PXiV&r|}FtP%U zE=nBl8})BYniaT*W%KkNR!GTShjA;)FC&B%2&LGoU(I$BIz2313nJC#AIrs(dWqqh zm15}GIEH?$y_h;WmKpOZV%w-$=-NfddCv5M^JXfQ+-tC1NT6m}NbpQZoQ^l!ZD!wK ziQ!U?`eDrp%I(){qt&PWfw{|Z>BlK2OX^ET`;6l?8>C53%pT3IE2jUsgu`5K6fP=-2`~=_w2n_O6Qw3ap z()innzsda*$&Fz7dSE6sja^{8?_mWi`E27GKw|7A1VTgov=Z#SQ%-ECtNkL1tp76^ zm0;rf(1b$awFL5=etq=|IfJ+<%#Xl-#;|>kg8auHNgwmri%ISiYV;qWqfg|7u|Yc4 z|3A8_iwOZ$jx2Rb7$ky5NGJt4+8vaNxc-6+Dg`!@glJ0)DiK=A_|6Ygf%mxz78Da- zVMH?4r`J&YsMyArMw40r!5q}CRtFPjRpqQuF~rl<#*8Ffer02}E{rryt;EH<2*=|E zwg_{=GU1m~b4__1XKsv)uwoc^0;y0f4fAb4f-o669N3ptJUT~0ri9uylGM@M5TMPe z(Nxt^&^3y{farnZ2(Y)gs?60To01aD10c^98Qcr|ir5?|5y&d?&a$tKs)OU30tM58lHX?X$ zs=6QWA_}L0MQy`r;L!`G!IX=affO<31=ql6n4`fpBtZ*{Qdo{31_senmwy{4s0f&s z=uGy9+z2UikU>UE(q)VZGlCJx&9%r0%t4(n2Pe~ThyN060{ zeF*Mt?~U3$TNdomxN47Q%O;L9qbtrG%dp_-ajQ>6>eYd=YY z3zqleBFuw}5vIbb7Du4`#q`=QG`I2Y8bT~4+sn1zmICvyWVu zISroEe@(WTGZq&=g6837dnT+1e@W7B1(9(V7vs6yoV~bZvY0jC=P=9sHrZh=LaAGp zw3zyLE#@Xuj=$+KW?-wC-L+x`Jr(9wj0r=Z|7LOdgyi;v(Rj*S zlFah&1pZ7sE*M`r$-J_-)m)fNf9r3^LzLXb%@cw@o9`uCesVG{B4sC(j$DZs3GvQJ z6jWV~@1;swJX{K@uDHsa+`8{1W(Aup^WUss0^h>npK2*k&?*#DP&M&{15RGX2l z)n+(!&e`47@I_eA%-_mpzS$LTzTH~A40oyVGXSaM`LH7%+Lr_)nnj^aZlP@cMvD6fH%ozLpv*(R{gC?~Sex<5BJr3=5O1sy< z$tN+%3`4a1(@g;K*#OGjB2Kx8&w);_N8Alqg%;&f?rVWi?x}NfDEIk5DEF_8Lb+%4 z^C*_}$;VcBXfoJ2vks{o($ zDjO|5n1RKI{&cx{7xa8)4|@J1>G{-sRW=BimDg9y=xj!|t6B#r+puejR45s1s6xD`v{G`Bd8 zlEtxi>+0&{&YP{S#@EEUs?AZY)$1?E{btlXu9v0pP`EVCZ3vgf<3(H=?>2C0oL=?7%@&JAz4fdaiTybp^A^fWRiOf z<@3kLD9vr-BW3J63_fDP&cU|+zqA#7h7k7{HfB;+uSu5%)^-H7sC3SZ~jhWDem);B>s*&dbo;|A7t-A-opkq?xgw2 zA{eQWNShV&7*FY!5C?v+0Kw%m=Kg$e6EUw>nDcT+& z+|UOhT-aX;;kAV_SFON}F|Q$r`lmw(?T}WD`PqDF{4QJ@Vq!xHVQrBR!pjSV5Uvo= zUKY?k9YVOJh=lNXgAl^4n0Z8dYT#CVb5TeLSJi(Z2;o+I7Dfo+qI#bYUhhvrxTM|@ z!mIs5Lb$X(B!u$@;)np3EgQI&R$;(=Mpl2Q1M&u6)R6>ZW))#S(^My}1U{XYEKMMc z&2gx}7=Tgu9?2AE0h zK*GgK5S6S50pA3~C;B5b&|HqdcPM^eE?mHT?8wtx%Zt*5=4M9Caz|*Ec|>PwJu(KG z4xW$Zy?7IVd?icn2?Ut9R%@n34gwqm6*?vk^)q zJkX);^j?4TS!kY{9drc6_sCsR}U^ENcW`L*DXWp$;BP0h0Ce9LwMr?x|*MoXs<$nUt*=_o2!H;zZ83h zXMF|g)O7=_a~KB>5eUeoJLpe;JJC24QEnL4{d9>@|CMq)meQB~E4;Z{+Kl&mL#1HA z!$O>j7gwXZ-}T4oI7jnReQaR(z7h|}hcaGJp98zNKL_@!1`h0pMLMwGHuf>F`-S1$ zEj;F@vFC7Lr_JkSWJz;nzKra_g?3~~b5j9__T+pnpqmOfxF_fLI=aneXjcRO_)L|A z)VtVFK>W?3EQWkBR@Qg$<&t}oIQhbFv$+>X!uwW00q!tQGjqMU3D<;&aXw}(T#DvKtIqxkh$0u?C>1;ktQq&ouv--xTnB3#|-aP?SpxPEJds~hAa z4@rEDx1ck%Spn{e;A1}su;(YTvQOqyE-ElsXP3!Y}xD~S@L{?r_ zRb92#QddNA(L+dYU=Tug8AM49wka8n-r6jYjV%Ky#_3GJ?2XVc-=F~4(>@lVEiJ%K zA~XdF4Wh0*F2!oJnU>H{kne&uOH-Sfr{;;T&*cMxETX->G1i@AhxTL4W6@Dw7=n2asTBFe$Z#X~kZ-DLz|F zM)BIlAn;A`p*nud;;-1(_*y>G(vOAOvgu$XK3&72zXi%RH5bdbw|)b7H#L{cg?5TJ zUARcIg*i9d4!-x#CJcKEe9(tG>Uw-gguXzyI)&YR3$rQ<;G|4NFJ-QlGA$ok<{ByU zoewQ@t&}^>KXu=BfqZFs(*ku&$Zei=M}cMf)E+;NjcM2whfV^MoH zl1RkZm>KO38}p`U3Qlk-kf%Joh@dl?_d_UaTx7V8)=vyU>o~MV;9(0RrHqu|TT=&D zu0r$Uli`)7G6JIBiR@Jo%MiyBI;}v^kC%fT*~|DpE(iR5FO+Mz?(RsqU}i+0?EE46 zlIFnyVmUkwvLebNZXm-RQ7F@37FxkTI`8m918H_42v-Hs)?f?)m1&_|#|;pXlOt!_RdE=At=_#`$PoIdU#9WIS49 zI&hiQ`c6WWO*NNJLdnw>fLQX)TZPSN;#6tkJ*)>lvofCx&0iYjQ*Oipi>-%%0&Fd; zVC>X`LHLE{%q2lF#oBB05gVIOUJfe-25vYxH!$>465qTe_OA!M^OHhiw3ZW$OGVQ8 zHJ&#FaE9Rt5SO<*g8D+K|E9EcAx=XOfCSHRs2MZxU_c>|BKjdjS%g7Gu*1jSDJfl6 zQaY*e$7Wz=5<+_qSshGTXXZf811GD zQEEM`I$rvgh@w?ipi)%(&!^!-7$NgAI#kNY5=wrsIuZxrI6sRgV`;&^-xZ zjVsJ1YQWA0a&?KT0ewV4L)GOzS#5DTABg|NQ_L9Woe3!ok%P-|g3 zmHl-Bj>1aI%EpeXUbTF}xvR|xZV`WtAp#3Z=Jl;b&`RwA+8S_19G`KDcS}d-VH)Ug zXY9s+51)~P#8}c&HOWkBHCuKkONOEJZ$NZghHUU%EGv1gx%*AL`g=ha%xlpdQ@|U> zF4pykMcn&&Ty%VAV6wwk`RwT(6=yx}^H1+wX@s#H@!wVCGDN_}ZCBuFI6f(`rTOh* z(#9z`(9`srlKuePQ`5hb^rQLse4$tCRpi2ihRw#{L?C%UoKPj2H0i2!|CL}ExH9fl z?UDwUM;*Q{>8J9$SO``Sf$EQv`F_Ge^(RUHJ%Z{jNxv7R-$oi{KYSx`OGIF!CjUVS zB3YriXrY`9b)`Cx_})VBq%g{=$G{QWj*+KYCy(tKhw)r25zu~*(mJ#oZB;faM9HP#1Ke z?z{M?984BX48HB#8csE`Uq7@kkRjm~^N^8;9yT@@IdL3JGWecCdul6Kupw|1!GxWW z1VaWhm6jBvs724ggr$vDt6^06Gnw%~vvdiKSRX*`_z`AK5Hw-r_|?JgIa3bSJ4V)K4BeFJGEA0{8zOLwq_a~QeP zFjIr7)N)>|UzSGAM_}!M&-!9ih-~Q5=NkMkHw;9$r*;H<&6u-cvRcoO*1g!QwxaEY zHY-@y0bM5$!)M~E6KLTxp|<&yX9h&EQUT6N(;iGGt11X83WBwmnOAWAK4ipjZ;l(Q z{(S}FZLh$?b;)+Y;Lgfz{CR6^>;fK0H9r;_DfUwa^@$ z+&iJBZ_@E4Sl^RMyUNyslCD_axeD9tcdCU>$#xI}hWZvHZCcC&IUyxrnKd zPL3LGX5;GwS<~2lWoh*<5mBPqGl#&L07OMIeJiX^Z+x9QJsee<-s<=_H+X`$KZpbikM$U zh*_?Pc~QppLm9LG{J!L`P{gQxmC8YWXlvEyze}N&7BTk;Vtyuw`7zc6<-8TUnE@*2 z;hUv^Hu)TW41qV-o@OP!)gtlzI+XY*1SJiHAbdO#CViFoo)L*}jYxdYip19ji4XTH z7<>ZK71!Qsz{BSa6Q9n^SGn)6^Ra-e+;_1w@f$ROr7UtEpW_k~UadgjGh^Og5Xyb6 zC;_=oq^VmV_o2BL@oiD_RukkQ6u%211*fW@z2FqQ>s$ok<+1|Apg-4K0L6Zvbculv z!9EhdZJ+cieBl?78Ft8;W7B4b^dvJmV|GlN$&4EDa4M7Bm9hdtbmJ14ByU6*&P?o3Z9q;z;{awEK8O#Mw&Y>~1cRL)v(@W{{MhLjD zsm-Nn%sx|VL}U=S4q${+6X&uk`JVIJ2+x>=@sRWNSIiop*$6#po|xBa4sH9Wh}iA_ z8WHA}LYhdPo69j>hk55Sx1Np68?agnl1KN2Nv(G;J>|yP- z)?Vvdr0NUCfU3jPfN_Wt&d+M^i1UvIxb3`@L~(wl(X&07Kw0k@#2Ug0Rsw0k z=lUw@+)Vm#TD~`l;{5evBI107KEGezx?a1@*wQED3|1fZ9dH%Vi?$)^R)$h{1Q>6S(3{0cj(2tS|~cbQuCK5sXV^~VoXTsXUYCVN1nf~plx}6 zccRMkZ;dhX{1-`-=k0!%_89`3@Lq*OA#94gSOE21$g3OX?1^3nr6di5QQ-Q7sD!pz{e!)M49(Xd5s~n$c(&%h2V7RD|T--`>4re%Wao99n#o|{IX>$YXt})FNi)Xj1wtCWt zYa6a%>_u!hOLitTgygz60wIC-dNXe8bbJ=+xJ9RTYyJ%!H;=5YcLreiB8|G`EMm^UsUMDek~N8zDx7pMj`EskF+mt)xKEuU1Z!Rln+|t@Ij9$ zAGAjKAfz2Ws80Ey=k<+Cl@EFje2^u}FppuKSxOmq3Rq{RLo)86xuIr<8=8)}jmHc( zG(oGFplrnipv=R#rWIR(H+`(!&`n`(h(d0N#h43j2+!@r;Z0b`y%+nej++s3w+H@B zLhe`XjF9_eptX>Tdn)9%zIQl6?k)&Z9z;PSom@7aLT)H+gxn7TQ9|xlI10l2f_)0k z&(#s(+ENO+pJ@*x;O!4C>Ug!@B%9JrUH7zuZ48H24h(o$^^ zxE$3fKb&Y7s2U~Iufxa!mcmM?7h}Vzfa;aonG0@28v&t=n|J8VcXe;MqW~TmBq+-h zdF!ik8r+4<@0mYUW75nUA6)L76uuYd*Ilv+m0HjsUZR!LUPTjfZ=tPTUF30?;~3gh zB{tW}pla^(*A-HB-doOSFH?kub(6{~^KkJsjB|K_Ah}5E{)p&0=792=L>ylg5`dRn z-0J}dL=mG0C;$_o`%91)0#v@>)Csmpe)Z|_28n6&PB9>0!dw?3#DaD8`trA#M#}-7 ziECqnlyQ+lIF2G?66Ka>5J$%3Jz2z0a+@BTA5Sj*C@e!uG)QwCYyoA5+9AzEE>52i zjTpRKyl(p+>y4ZA#tnL7cYI||27!Spipe`fSk`6nI1h!T>KE*-#ai~IcvkqjrfcFW z5#@SKT!6-7+qBwS@%5TEO?#Zw!jp=%0hSs?gb^bwjwE5wdJ!J~d)dHKf0V_1U!rZ9Vi}&@$Q<{DneQ_sRa%;Gb zRi@}{z5SsUeL~aq=Ef|&*seDo*Ys+qj;bQ?`1&=kn4;75_NQ9(K~2AEZiEJwWAcFB zSc^KI!qv2J9qUcesd{^#)^U%fH<%k!^x{js5gH0p$HXG=qS}u4Own(&^CoKN&C|y= znHvZ6Mo@2rI*rSCOOc8+IJ<`eU?y(U_T!D zKIrCZ&tdA1F zQ;Mu98zW~tPF4XQjm#S9M$X~4}xY&qNlS295T?!f@shk*ty-MSM-HAsqP?u8K$_n|Lf3z;Ag0pS!CZSkPKTHvFC6sLD4a!Z?A zfTtr{TIg^(Y}kht023kR3k+Q5U|j8Y7zExSvtY>*b-;KEPhkA? z>E(KkwGvty54==Z=DD)mxmmsXkM2=X^^mjq&nDT?Y4xF{+j{|Az&lg|yo;G$QYg3g z1OD<<-TiC+6!M3mCEWJe{3Wa5CM9etj@V1!b#Hj<&hClBo`qy41lwELz_dJn*H&d2`h`!sM5h4Wm5?=0Um}zik;tJE;570i26MQ>pvZJ64;F_7`eud5s>Me1W4) zWwf_h+@aTcNo5|ymW5!B*uLNzQ_P5JpLxTybXxJD8SQV%+GMnsT46?eGba9bX0#th z_=yOkeIG3eBUA}7JB;tx{BefSekTr$_PLn-E-y5Uh~602iqU>}yubH3LzX+M?H^dA zX0)W-iMrd0+g0vaD&F)Ho zIQV)O!uD9X>feQ!>SMG4zhxypRyUZbV>Qz>keP#+`IAaHu2Fs;l$5$AN#bO95@G1f z6gxp5Sf;OjRzKsfeB@`Ey;QTG)9lNceWKxgAA^andHfVD_lTCG3!*u-?N%?_zC9Z%`uiU zx@KsSqZrNx02qd>=t!LcT=ogF5wWsCoh+FL6K{a1lh2eRz;k})0{iJFNnHV(aRwdX z@~A6oFkiX=Yq0}QzE&43Up8-`-Fp~s7ch+6<0@g5coGpZEShTLuXyX#AUe#*{R5ev3IhE?T~5BN8CGDry&nc& zwj0xeY*{y+slH0{S%)}}nLoP`}>bBG1jx`U!Qo)G6m_G&wn zHv-fJ<(%$jSWuC-;*50=9MV`7IU$;=GTo9B3M*QJN-YjuIDx@WQO!SX$P;b4b91yQ z5kEcnt22(9no^hSd7;9qR) z8o7?za{DB=v)UA7*y#^Txec~m&?U3g3+SVE3n&)$PznWaOet*;)h@MZh)}(1# zf(F6nZrO(QUW_4`c8ZSu4Z21?(PPAAW4Ka z7wy^gkbd{!y*PU2ALOk)(eh7le25o)+h<@Ux3wU8+JMXhp9@?)`~T-DNY3s5reKK2 z@noR)^vpESjl@|vp|nYHEFJ#euWX(>^@TV!h*h&TnDL(X|`npymyX7PT8~chmOgPe4*Qs9O?T6erV~^zfvjG*1cHWM@e!t3 zaT?O0mk>$h9_>KqB@AXcA3eif!l|DO%9XCBRpuQv`i_|QC8O{>I0D4WSNchltu#&Z zZ7>dJbIt%0C{m2%dHfr@ld;>*Y(yXZo`X|q)nsI4WcKPY1K&E;9o@^hxNUlwkRP3h z;}1fxy^I!IbbH2Ip?+)B*9Q4k4rkO$HMFYXUG7J~5P}zwny{*`UGv)q;tlqF+nOk4v%wl=xBPO^)J=c?&Dk55 z(t7p+O2*6CySwC2vlo7PfZ4#%!U>pZb}xvLGkfX1#LvC2?1!4Y!2iIpP$zi`K6{u1 zhdX@%z^123yGwq^`5So)Ii?%1MA%XPH-RG)*b=}BaRT30{2ga7fT!Hf4DNy%TzNER z@clOEZy$8^ig?WNF7iwfcd4CpyMl_bJ?G{ESm|(y*^XR3bznVTL8-_(h;o5C^qs_dST_<#S*@ff!!+uS-4*Rz=5`?}a?csP@=?dF zpzm;>mzv)K)aa~&4EZT*ZU%%6ykFgQ-DP4~pelWErtF0KQWbnLKLKEa?J0{YstX^xJhEYL^ zhW&kRxKVsI+^Bvn8-=zY3$3yDe!u2yI`&7?98Rv(pQ1TWfz2Yaa;_xgB1R-kKe^FE zYW2v>Vk$d4(xnlz0UHy%y`jtkG$bzX_0-7bV!KZ6@B$4N&?k3!@wjp~>q{!(`JM}1 zR4lN`^T3mcfTP%HR%h}#+K}VWkX;G%^qb&C9e~j(@lSBH?q6^v8H|!^O9CWsUReNC zAG%PoIuhbg)tuim!8ml0?RvsK3mZ4nMqSTyAp?N|*SV6wC3t)STt4&}z5{B;YIj$e zFqTj)lM?FW>Uv#TR-8KdAWYO z;mcn4V*M8P#yaR@=bc_?Uyc*DWSIu`&nurn#gHs7<3!IROUr_p{g77$b_aGjCE0p4 z!xNN|G;l^xl zeLv*xE^V%ml`ejUSKwvJ=hrCZfYWcPG4K}l+uG#B|dY5qspvTV6okCi|21pAJRw5HF`(3(fc@b*UKH?#}d74i%K z{eIQB-p-T@eDZ5DXa~RyL1rk=M*0C4k>jSr^$;#hbaeN~)bXHV4RP5SS-AfySVgZ? zj1NcxH5(o?^((f{9 zMxOj*nlzQa_@AFNJx=*goiwkWik44;v|iU6tMV#Z79Hq7?S60+C&saXtFUNZYTt~U z1EX~1EByh85p;E-QqSmtS~SIxw?J$>@(O@9t)G&rQMonmG`wpE^sC#fQ#)UpnT|F4 z3e8yFEej(>;PuzFr_y61pzOm!i7IT{LB2|mS4KG++qLJ#A%uz_@tj))GW)+sW5cf= zK4R?f?n8$RFDUAsH@v_^=VBzU@P7x1(9|lVSGtB!{$WGIr6a0I;o$T!0YvxdKDuBy zBe|px7&hpvGY=Md?8+g-`6)kG_@{qIh^>GA9f$SV|Hgo1{}(Lmth3MRUeIdQ{aAws zYGflP8kGqs#Q0#YQ0Ofarpbh;iVo(5z(Jw#Lx^X@fI`v1z$^rv8qJ_yc+j~WjMPNXe7Iwle(D>fE%RD>fI!$VP#zMLE<5|?uoev!uC zY89HSMJW>$ITV@#5**DVaI6I78LSRnKA!hhLyyf< zqgzya{$aU4XHOQIoR9YR>x=wq*gl~cEC=S{>Rxm8W_jIw9=H(K*pf zc|rmZ+tP5%MT4cF3r0hlngBBnlQ)5{(!2xZxqq-H`SS4KEC`_quz0|OGQ&lmiJj%S zH(a>PmzPr@$MQ_)DTuKN@+?jxT(V3{tVC&-EY~Mjmizi`z_ZW8sw@FL%Wq=ZC3_(9 zCje%j=_NSpflE`lzwdutEs51EbQ;U!yXB*}>^*V|%o0BUlrjHqj|*q^nsX}U*TFSa z8Frrh&M&^;i~^}b9HQFp>1W7}I2bS9gw}iOY{JpY2-Vlu!$eD*S5W>&8rO?KxV5O}mC$636q_$zx93S1Nj?Na8Xp8*ZT6jyam zTv%Q>PV6qPN760RT#DMsd=re^8$in3 z4|=;qY4CDlu7O2PBBJQ{ddZHWY`GO$X_q`F0lB`g8P#X84LSDl8U+c)n8~d4w_0t^ z!)YhiBdS@NbPP(Mnc&|i_~Z+>?}EMsa!o1X^&wu~)Y8D*JwCv(YVHll-GgvG*Ovxz z`pQmsBa6;J<}MViDh*U%M7NvVS;+kexi>R+vJXJ2TEp$gZbA+J&>G$Yb`h(XkK9ct zJP&`TA{^j87}`xOPdh!cqI>$#jC9nx!&Q?mQ*e%%B)-V!s5W>$n!WpO_vF6J&(!o-v|tzhb4hZ*PH2qK=C=a`oil+^9lew%%g%0 zWoZ@2T#L}~xT?_^^g51CL+Q`Fb{fAXs+VwYKd|pyIN8K9dEI<2$lDtwSl?2k#;>nq zq-uo}X+f!Pa_0Jp=~wfM_p!xa;*>b%i?j8Th3_p(wN5=oCRo;QU`h3|emoY>1I4U) z9hAgwS)}O-D=i%)7x>&-rT`(x0{sBB5)9^Fkkb!ydu~~7MfXfYIW_}+O>Md)n(>oU{3OX-2Mp18$%lcnOo%w8?{e&YX77(kl9UoR{A8X{$!k+ z+Hd8^iMcRu&bCW{&=5%Po{kCmGFB+UQbNW49K7gw&7*T%1K9Ces4qJr)KV_;SH=;_ zse?=dh9fRNhoL$z*a1t+5h@Vl{v33xSEc{@s&s^b@y*>WBkT6a>T%70Wwd_fN}nS~ zHTvxtc2mAAg4%w)s4Iy;(Ik+bDqikQ5UMqesbBVm-l6CO`v;X5Uo`F4M;|s-LyP?@UI92%CDXa|6rGF zF7V5n9$I!h?@qH{05SOxFfNIRXoEsv3QDVM4@i+QS5^`|Yn=JK?TCpb?O=v!H(l67 z`tdA2cA9hZbKJCg9*y9h7mm&>EEqLKder&tnbyxbFV6$=JICgBef?IrC(rd}%lkMI znTu!+iSnhS0m5C|LHmN+5%4OP+PFN)U@Dn#H5l$94T{0Ti$EN8Z3e7{5BU3 zE^_UH8Kl^G_M~q87O})qdlCxFEM|x9^y0q!y56_Ox27RelA6<{5Ow8BVX7q7|F`|n zvG>|%^>^+RvGY^^J_5Om8?vNhT{@U4fIqbJX>@~JDGAswOG(Ygyos7d=Sl~kj82sf zdh1~+NyS}hm%AvCg^qGRY5%0ppS~b9w=`g&yUsg_dy(7QXs3GZLN*H9YGWRqkX(J2 zA@%~m&lXDcSU@noZ)3`zh3~OW=!`Q4*s+b}2URIQwhQWhrqk@INxF9|VYQ3$2llp; z&#{lPdu*{Q?0i$dZ%x09rV1zwZy2kV0K3&j`v!G5eIYIkSRM@o3lj!JErSm%%o51_ z(K^?dDv+@YLal#hH8hOC&BwN@OK}fv%w-#b(2$>0@ORo*L_Z`lq?$I~T3`xF8=F04 z31itqhZp6UVx+uFUbpe>K&+b9b&34e(P@ zz_tGxygd@6cDxVgTfE{|hB;L!WY?_JJ!!e_PbU2WJOM^4j4l{)a<%Ib&(8%+U9gW$ zIOs!MR)pGFFy89JBS1Qo@Cp%I7|tux1#*FKUPm)<7gDr^N4k#b#!xQ8dGXBt0a%_T zX*4gUE0Jb2ucN>kt4G3hGz@mh0eJl<$)|wJbIEjI+a<}KfWHEdKMhY;Xsn^O4%z7` z$0<*Mm=A}}x?S_HWJJSfq`adWxa7b`ffs$mq2n(i2G^T%PiZz7fNJcf*|LG#Mv^?_ z6nF&%*2)n+WW86aE+vQ@*5ZwD94rTFoLL8eTyn_+qD%Ixa-y4<2JMZ*ha?GnN^}ER zje4!_M_VU#MCO80fQ6x7G&0vwCO%k_iOePPSecatQ!FF3p>}l8cwH3d+BH?UT7kug z@C9JWtMKOcJ$9uI&^%Za=>YX=V}Q6JAIg*d9l9(R@$RSq99b-=k2sFrpZs~V75yy7Kwu6Ba8 zMIMgnakwhEiwOEJxCvf{Lb_K0`MJ87_bvQls2ahDFG3rwO>z z@7R?*7&Yy~7yl#ra6bBQIJO`=z^N{sIMd1B6W$>qZ7sg_D};3bnxqLWcc@;xg}d$; zb|GA+5a&uevNEb8l}tk_(rG74#uKlnMF;A{<<5YRa_~if?7$cZq#09xC{kv&&()>eAP;BvL_}V0I89MY;X1Pv<~!BC7rlGp#s8|^6VYqT?%5og z{6A9m=1W7W_P_|wkgBa9Rkt%fM1nQcr9_A)_8s*mCjPE6LqmZ3Lb`O1BFi1lSbU1H zkRq}%;I+!F^F!>+6J|j6IQ7Ca6YR`UsCsh=EqmIcM6yi_i(Cv^71~oAdPFRZ2rC2o zGSZ_(o*Iy&FUsp6T4MXy5Lz`qYK~?$MrJ5fW6h9WfjI&!AA764RmNawW{#`ABV9g5 zu%2RDdC}hZ=E`xjraP?N`9>3|`gW!DF8L47IYIemt zoxk!WZdOB@h1Kp{eNt~Cip4p4Wm9Vmxpb(}26t0sunaKrP&Xes-w5Qy+IfcIQXVNu zv;UjlCtg6aHhXvBOEv>1*ClhukiXpwYZ|6$@NUv~06$kGSVEh7mmm-}v^RDG7#!)W z>Y)N{0hPIMO7_;u)iu(ds+NbqDZAvA@<#jDvI>^H+m*tg7$6r|7^@LBgpOwAAyKW; zD*(QC!AmCftzLy01!vI}yPyblEf}BHlsP7g4R{MD1Y_!<)`7wbvf)+;rY^b77+lBXc~*LdE95dz7tREz*uBr(g$5nNO8jVZqWp{vcp5KCl&8kxCK_Wxnk@FVKTJ7qOJ(Z!QA!lPHEUcMPaZ25ij;06n2knOkYGRrRhWfSnXz*!|jO`M$B1U1*y0Nco0E?*Z1 z&zEUXWA1}H%2cl(f2o&ffL{gVYe0KWRaM!`%H}P0@lz8KE{OfR*yXq9L(w@^^<4X4 zp&LqnNqhFLvKBL^Bj^m}nXa+}R>8cY09_qlgY^5*oH89G5|bN;H9KS{$7Tk!-#f9A zXSj3iQ*g^UvDxA%L{NSS*KHtUL9XACsC${rMynOuc?tkZK{cbRA2+tEN}T_ zxeik<5fU|DdS9t8M|OLt1$jMPTL{DaWp6ey$z1b#^0E4``r09sEMh`{Tyb)@J)6zQq!bjE1lnYExt1g-LvJWWQb}V(g6Smenzd5j@N{rQRjTdI&Zza z>c+}|HYwRBBUGEzs4L@UtPE(9FtPb2Ol(GW>sYxHL64fTVcl1Xy@@juscihsMIcsm zO|(*Yj`RL4)ENJj8e@Onvc47F^YWKt2JV3^H&kk{UhXRQz~r52zoz-V8?0bP=ESK2 zF!2{SQjcP!Ucg8_iji7QTjk>5N4HTBi+t`=&g-D|3CLqE>W8=TKv-@=jJ)$@Grr)C z;#_%8mr$KR>3vRbRX0;nI6ILP{`qm#tGmFj+9vUdn=76fq3a-;cn6#)@CXi>;YejQ z?%o2F6u_QzUUs2f0eeYA)cr5reVnDTyTmY9H^4&QI-{$7I>|=PrI|8<`^n2X1r{se zcuD(uu{RBd&n12;dr#~vs{muq=>>B91WdVI@|umI-U=PX3`~-Ec~o_VFF-%sBs*Ya zo+vkHHP;ZBLADpcPhGmE!Ex;=Vu0%BEEevH2Ej8?P6#4-6V3}0nO-el z11l;;mO)#9O`>xU)!mAZwq=`Y10TXhks>Sg^~<44j-&y%*!po=9^C2*(l5eki=Z8J z#|b0ap)Kb9F>S#&ZW&uw!2`8f&B3bGzx0O)vGT1>asX@nJ}c>-e=skS*> zH&xZ#(n6|gmpo>N093irKJ1Lr%N{5fVGc1Cr`|*oX<@B!mGl5PwIL^Snmz;%&d6tn zy1Wddr%}jSjCdy;l3zuci0E8-BB8oU+68#rJsV7$}~Q~%pX7JGTY2M zXfyT1%UzXWMiUBa1LbIrSiDdsXOZvq}BcSOL>gh%de(EjkL#2qLRol*ZFGW1yE{>+J- zzAq)#T>$|Mvv6er>CJLP%4C{j_pGLuIca!tq`>4_=NL#+DE%-H+EZke<}blPnn|N` zYLJ9fhk72vAw`N1+#RQQiCp(gqX@G{(Nf@XE%BU|SgIwMjxND~&MES&mRP1Gm=2X7 z-ChE^`UxyN(ERCo3x_{YH39H21qU!Z(s&pMi7E23*0DH|f=mj~i`lA25@Cgu0z6D! zJZdgp(2E5KiV{^J9AV+_3t=yTj=a+mcv=scU`PQ9*#9&bprqi?wn09JqaV*T8G&~* zD$+B~&|#vUY#8$X(KrexI4Hqkp(bwDa}j13@_w@?Sh2`nBRdg)dPY3>9{tNRI?Q(L z<(h!+EWVFPdE5e_($s4BwRF|gHDz`s_H&n49>9TodqLEBymBhyTAOrNx=~l~s~Eto zBO2CPD+0(B$gsvw?B6Z2C&{%K7rbhw?ms+! zH|Y*gNwR&r5TPDHI6<68q`?!Y!K9B5`s^qC_KkkYwksPmmtHF8WXt(=eXMr$MsUNL zE$(huvppT>YEa|?=A<&`tf-7WCd2kyKMy@M!Fei_N0*@^j&Q-x3_cX3E-%D|QM#gW zVgU)CY;gEl7!&_}NJww!EqJw5Y6tGAZ{+9R1@M$kjXH3;795VRZEeP!Mwrg74ZN20t5diEOaxa(5!WgfoI7g z3b5cRq7TxExkS{d*0VL!uc+{Z%2wu<;(C*w? zk}!%e+@U{qN0|rTQ1yE4h==u~jV&azbQb4>tiaLW>KMA%N1BU%EEsDqqK=BRfzQ_W0qjb90d z&n?IC*(>R$dmIOLMU+=misEv_1D7L+2Z_sZgyM3<3voG)04@jT84)Amg@_R;iWtE( zd*OH7(j(v;)X8Kc=kqeW*1#L2M4@v;<{>E+(K$E|nZ`UsxeQg6ZfmLMSf*eE~{ zV3b&lbwYp+T^ub8hSjdbp|mN0;0PKB4t&KlH(g0X{mCvf{YjjY6!{RFs9SEcFrngQ zzq=Wj7(pzO+klCI_mJZTiHkL1;UY4)Ri*%H0ZxW*(pU`1mr(boDEtO+O3HA)*?Ohn zX=A*?PpZbt_q*z?M9xu8{s-^F9GyyR0@Mbef9X;uSEWf8%>C0a<&Py3FqmeQ$8t3c zrWRzGMM|;R9e@p^uRz{&2l^CXy?iM!t4Wk=L5OU59^lWRswx-&H-IpkDEDB1BKbj?;>n$4 zACKEF7Ex%v$7+yiP+A(dVExt_eCq*Qxi&NB`FmzGrWG!<8zOlVD6xE^3?eXMACTSUlBn0ON_{T(f1DXOzMv#A)X8!%c9$XLW zSK7s13kD<+kh^@tefl&?Nsj4{2lff{uh@y3yKns_b(%c9M@>;I%<}Qfab!1;zR8Wi=2$d=N)a zGFPgt+!*&tqx^@$wn=a*hE--Ob7q%!RS983V%yApW2NIJL3Uq(Ev>+sdl)Xd@FGcePHqRN#^MhJ&;K)gti8-X@2XYq@l=a_SrP|)Tq>2Bsps9lkH!pdgp zR*reXdA}U>qvk?RpgVN}y`wrplWqbd(t#8+1$!P+NBSx*Kzan@n=OvQULAPw5*M*wRJl)-dObQ3xN+nQRGU0&-lo^j1BBMZM7930cUgO0_%&z3!i z)|hT(njZ^R%SsAykeeQHIw}geElO1u(l(Kg`IqpKT(@al-_^QweIZ7b-2RnhGYxM^ z*7G=(09x>t)IIJmYsP1+h8ILMhuLyg68|JTQXIBBm2cA(4f29Fo5&(Yokp(obIi#I zml?ghjkFWZWvao(_u(?XZMjFk%n_~7Cx^$<8m^Nca5uy{Z}nOsr4og4vCdS;tfX>LRoTMJ6D6u4WurWO-X*s1>!lXPaHr!UjJu7 zJ^p_~sra6_3x@?G5e5uF;=5sn{4WCa_~Cl$$^iqf9y?(4pno0=fsfSM$9`>mYsF#*8oo!~k(P;2jPUNEpfkdhHmPjQlvD z7eu3iw8Z+r?Uv9W$Z84yfu|JyBQRpbPyiGF^CK2p!>J_-uLC(z$Qc6)0wb;%86emQ z;S(YVAtrTYfuE=aQScm2g)QMZkR9`Rfq?`0f&7BdyJJy6!Vdsf0x!p96uO084I40g z$Vk53U_)HtA24umz$t6+F7RBuc}EmpiSt$m_Qbhz&`X@FF@pojNP2RV(@7z(H_9gJ-Iry0)h7T+lJ$mr)fyB1J)QUp! zXqCaXg)l~<;8HLk=#L>IP+rGokbz49EJhf91?jPzrKSk`AzXOKaE=TfbRa)WM>_?b zj|ZShEJ6rIWO%`_!J~%^j6jg+YU0S4XQN?4OtZ9wsH!cPkT5g|7HtTr2gxXu5L|I; zhp;{H5~t^f4H#)I3^!IFLWrb3 z3C{9y3w+;vxZ*Y}Drl%3W2e^Ir`V~B5Ox>7rm1otEOO1U3~U=U81XbIuC|YcxspsQ zf=!F<8)6Tc0@?GAG!Hlt3IkjIMup}Hst)~|f3^L5kJE77BLFMNLRCEFQn&jH0^8;C zeD4?3oA#%JA#8(MJiXp|`c#(YiJ41IrKJ03Dke1Z&wQEYT}rcsLsenFiYNQBjx$+D zU#gzZWW{}1hvr?x)4`tF^oznxKRX-FwGTQrUHO4bJN?qk2WjT9ldWn1&Ch`?spoE*#hE z8;HTOM%}_6gV-uE8Fqypc@DZ57=37L)yd;&#PSuqICmG+TVzX8ne__+pW>IS0?D`5=QX5RDg} z-10;TtlmSP>o(4zY>pmF{T2FY6D7gv(zQ6QbIaGTM&x%-aaY5co#8*1!WbVJ&%wf$ z7d{-Fz_P;8=fHXx5$|Eo0hO=FI>gF}>f&g(ZWk~a>JXygCn$ECcFk4<1q@$ogOwxn zik7|#fC75K@d`sg%6<>Kd^=1}(aZy-7_@MNIJaX7)hdJ7!x+{ncmn?35y)?ZC$Fqtm%foGf~4Nzg>%*XP* zg^RV?18ZrbwLO_bx_2bV)(N%=N`=1jO7*xP?y6Pn71;!y`Us<-U7*3%e z4bXH7ajo3vwvClj0BF9A=+L`i!_V$~2lhrVKey?aRtqB~WW9!&$_q}EP&dh}VX$2c zO;K2Sx$EpcIriCHCtsH8hfaZovq&Sr4p26-dY!g7BYqKHZR|wMh}YbK7cPRE8}jFs z*x9s)+X4e=x7_YD@B`0x8Sf^Hx5(n~hZN#V7UM_*R(5C})11nouR``sWAOcj(S!d@ zacJ;w9TOS+&*9Stb8nY3_|L%@QmM=q7zH3ut4^>dEslSl91)OFjdpKNf*r-$H#5CD z3EpVOb15?kUa@o*+*-;>vdzs|a4Q-bngz3ACxy||W6Tve(qx*mU=s}JX&TKDuT4`#w@vRLkD4%oGeg?zwHMtkTj*sx2ggFY zT-JZN>^$q_&V%*aZ2CpH^b0e+Jjr$`f$%CSm)*n+_+WFY!HtCGnC6W6RRC)+Zw}h` z5W)z;-2gdr)b-0|0JnA6NL{o@en6|JwJ+DdlX0uM*!qi0G`5McevX(EM_CrPopg?` zZ-GI&$lpjO0lX%RyXul7O+dD*nLdg(rLfyzx)U{-E-z2Uyzq^PvR#&murqK=MKR;@C^Yb-Kr0R#u@ccIDq6ue4JK@j>Brs?4Aj^Nu@jJ3)!bM+tc_W-%X2D(c{ zMMgTHkUpWM0O4DL6?QjV?;1-2v{>jWgIV#J(u$>kSO{@@*W=6<91P7+WvxZCD43_F z!b5JYo1O-pWtQTBY=;XM)7Zm+BQYL-Ix89nFUXQct{R~9g`sqY3mSf4b95j!2U4sI z={lxq5T&`m=AcXA13dj}5Bf@?NX&=!iur(0b(p2KgVT}w7N`zd_+UIO0O0wB^wa35 z_VUbFKPQO;IuM1=(GFfwd>gz!WHNy}zJl@mWbB^UZPdnFClgxIkB}d?j>lZ>ERSN| zqv|{3an)X491Bx9A@&C`C8FwfXrvj?h8MvjD2V|Y1V9W9GRz9tfoLM+Qf?e;=T_kb z>%jmgVH@B_Ehhuh4xv%OEw`6TDf#>kMd{jAwTd&~5m%iJhZhO>`*qK&$g(HiE}xV) zKp6NVXKfk`3|-1$s83{l?Iy&q*$hq6Rr`F4qP%vW87|mRWZ}t@=Y4MX)3B* zSPo-emwW-{fdtDfb8-Hkq$v!3y^~2emQW^LcTLgg-0E;1wo&KtYJ6Ur^;=gS`X26l zoEvBB+`yaLBNQ#psSFwj_uL0y?-iLDl}Hl}1Tp|HV3OobWv&;X7m{S7dO$8H2YbsK zemG9@9P)gGO-Pb6dHCFy_G+7fU)UMulT5EdFaf4Ho7Mplzq9N?XLXT>y}`M-m^LoE zN|H&efP9GS4ftG|6EJ5sc1oCssXTHEPK*&qiVN*Q5QtXuliOPBIfP9aKuC~jK${`o zD2IV`G=q(*UIaWICap7hb$kysdkL2UEJ!r=QDtEPucK)a{sJ4JnZXu%h+77C6OJ^X z*s-u(9$ zC;@U?IX5RaIC&Ii3Rso8Ex9q#xn;R={Mf92-|-kf-aAW7xY@3hv)uA59e8m>iL>qM zdqO;H)GmV}3da+QehGUmUAa5pij9`FCP*>m5sBDkm!jMb;HJSTR=?~q?Tj_>`~w^h zBr&uI_kLL;h^?I5Th}uF*f>9G}0JdKl%e8sdD@akUOAh{JjLr}05qQtW>dk1QA;48Jxb&(R3* z6Qkby8t8;e-UjF^I|h0PcLS(|9dU?<4IlIs=H^Eb*-&~`Db{VGd|>J1s8T`k-tko0 zv}$7HO<)SDP?49eZ!)$T2f%8=NK;^Vy2T?LJ!<}hn>FBhA#Tyxh5IR7Uo=f}X3{%# zds*ei=|Ao)QR22LJf3Ffb=E_8yL3rYoKm4@-RydBLi*UV;m3?#r}bli@ZySj8W@&% z>M4Ed>2G~%PaO7mLFg~CftWt}*rSJj4932Uvvi0qq+@GHjpc?jhgxq?SZUrUe+4ax zAySQTHCRR;mZ>IciKQ-HtB6_~szKzB5v`aT-q|$>H2x_y8sHFJfPQckX1rBND2qv! zu87-!zKg4E#q5_`AxeSmhtnC!f3=e3MyQUO0BQ`>2sqInrRIGA`zg0mr=iT7io3UP zyz&t1<2cZmJGk)>0wKBN)nZQl2esN);VKzQuOs$@EqlqqKzBgi0qCd{Q4P-!VHn9P z;EJO4g7M%HkR}2V)5<&oY#^3-gcCSe#xR3`R}#;yEymz!ygdVT-2(|5+DU|W!o@l)T!A9L@7hr=4F$Jq3cc;kXs{UFtj!Z$%@5~g8 zWceI#EZ#6e=(;Hj$2GUS-Hiy?7 zNu*2a;pU7;;i&Cf_<;6s;^8oS>t-x_=&9=hXaZ}Vq%8n|f=N63@MVkxI01^U3KU#b zf)!>1A)AK@Kld#GVRp+q;4PKekT>G=i#7LP{Km2p!)WAD=yJo1PyalNAaCG0DiQqc zu(%G09$cR{Qg_u}b}Gais9AXfP$+1~jHO2+b0NgXRy)31&b5724i+Yfl**hThpcc0 zgwP<3x%+Q}dYYU74GafE1%$WnP(n6uymblycUtWKRjPk|9k>DZQU-Vr>hd@+ zj;VQX zva7^$32)JVdSJ8sv{C%fRpkuMT#lX&3HV?XL(HASfxH5idlI$mfU$^dmp0SJ#8Ro(! zCQ$aI7~}!M57W1l`0R7%*?lvzPRq&3|4WYx?A3kGpVuo39X5leqHvVu0f0QIk}{B2 z&;9l6%nNdc&{N|`%0ZS~O)<#eKiibx)w$kMzjiYPNuNC4=j2G+_n3L2PX63%15g;? z+*HoINVqf%P3Yilx>YBa*8><>5TqdH79Pi!x>Rwfn$y!X=LpUN=<_-G*Fj6k3q#yV zy`vaZC@WC+n8qdu5@RYQg(kPJ>8IUO?t2Pl3B4U+&@|w{Tcv8^&f^grHR>_cXNq+& zO`}+v{0~cYe|u4(L+AwLffYNutx4;CV_aPoF7`?`kUmK8UxWIcZDgIH_7c1QUEM$1 zXzw_9v{Ynd-c+%*MH}Uhs@Iw^4hO138!o{~?=|eU#pO^)hI_Qd{KX85J`4#?0U!!W zN1gV8Z>$V6huGHPw&CW{T54Ofk_Vjlj(VPpiZlSNA6NIQ5Nag)8l153^zt?3N^0TX z6-qCH7Ydom^=@(x_oEk^FKU&&AcZr0`FG{qjI`BT9EI zxzP|&UsTp|wZ{_mN90gM{l+LmcSCRQ0bJVsZt|kfmGJuz1SE=TPc4h4+Ei3wWnr7c zFNqHvfhY{)XncH2!u<8P$o3IKm=W7GvTh^N(@eMa^8ICpCd`vSBG85Rd`q#Zrr6zO zhbGJbbc-R(bBJDh2vT|z)WvxFEl#xuBg~b=77#dkv>d9~P3CrqAf-GPkH&17J2G1wmNr>f^$Ko;18K%a9J_bxMAI-V zK%Y-W6dGUF1$f~%x@{;ljL3d9c$qXVH;3_F0LbKBnzt0~zZJ4EU=pEED3E!eOG^D_ z0K?Z%ziV(FjBmLQAwF90x39UBzg?{R|4WdRJs|w-ndjrGl@i{GCd^=v)|kZ_O9@{B z5|j)K9)!K!3w=a*W7d&=+EWLY&j=-aoH*mkzv5-PlsL{%ji>3%-ib={b^%bvEtRYQLk7gF zFwNTy5z6qQgUE{Rh6{BJ$!miZy&gIc58~W#0pD1zBrj)m!D@TvXi8=<#-MD|1inG! zA01!ftHsRU6sZ8fw0u!S>8X;IL@9QGuA?w3@Rx~c zkxXWU06_6jm-Z|P7Jxu$LZeNaGcH7Qm(qX6$$hSb9NHWum#d)1gA%1Z+w%@qVLw#% z4;89W87b}EYL7D;YA7&Z+^P98e5S0ETtm9=8%OPw`N|OK*0(<}PRaKw;YpEOz9?#L zn_9LZ;wTdP<2XSE93>3+XkgZ;=WBC-sw?0`+1@#DAPuFf%X6ctDLxN2VTQPTHOkH{ z1X_Zf+HWv|r~KCLZ1)4GP@Te)J&*5a+P~C&tbB@-IVh$eGaM^5*twV{7GMoDXh?go z=kfya!_?yNT|g0Zl{?jv>K*6_nXX2(E|lGf0>@(FazX9qE_N&zQS8+bC15Wo|oUnYmi#)kZwxzgeinyeg3{bcwx+B;H zjc@-dVmnx0gzGlDC(nVOii1t~8ThE>UT9j-h+2TVK&-~>gVwDyszKpzjXHU4JBjJR zctK8!>8c)9n?xG?IZoc1ph$Gf3^IpicyaC$YHsX!1C8$>C88cN*j61A7tv}3d-2*n8{VilTort`&~gZ=Nh^C`(j;vLj>)Ec-ha;O;R8>!OZ?CCf;!o#c+UPeKE( z0)}k|f+rjF)!Mhb)F#y0iN+(zn9Ss);!VBF3){*Hnn_?+&RE{Q&N=Ka-gD-{Mvxd*+_5x1(f0yaBTSrBQ$S0NfJ5GuyTQe$VqbcDDb%*rs3D2agQi0%(| zxakjqnRNu(2K526X*e;KvVGlns(Sc=D`@`@9d~^R z73I0|CbYECT-@`}fk${WJI!DgX+w@fLkt+hMaoe7{1Y6W>USV!hR^Z^Xw~DD1x0D$ zYDq&v)v}vr!ZfX`Y{wxh%t$~qm^R{$C4CGNXNfOx3EDA%hnReVFOaOj;i7u-?llInub`@j*yhK(4WUO3t${vCeW>G0J3cf9AHf5#8z5B?);(!o#6ncchkUfvZQ1eBHeTHDJVp_uLq6Il;`nIuxe)^g45hy|a~+3l_;a`Nzcx#S1FU5Zf&gRETQV#<3@%@^6kV+4V9`e5j425i0o9jAE zLmglSP|=oD5eq1qgn|f$s0^rS7(oJ*E|eXG=78!#WDUvIRAW;wP>uFP1SFNR`pX|xWWg3jQ&Vg`1fOP ze=ycF{rf{P{eW#768QgBB=`^GzkiJT*Z1Uc|Cj9uKin#%h!Y1CoWTPI#W3H|S=GTjpEBk4;VgZ#4xbEY(gtIC~a3*5WrQmAb?AQ>4X|XTOxS( zK|_GzL_sB*rw1z?DuNyxGbGR8V4;Y^-{Y&D6!Jzoz3njhEQO?lu*7c(_Xsaq3Ld~Q zibaz`h7oblD7=UGPJFB-Zj%Fu6c$2a(2~#wUPsW9kP#9kP$$Mhr3xfNvI~;Yq6aQf zJ{plqA3!x>xrRjs<_{)xm)5T09#cc|h79*pXfYSV2M}+KrHAAV0GQW^;pWzmkprDF zgE^ustcg|}NeDY?z)*HXc)(C20iJL;4rOXL*9m{=A?*1yaX)E0!U>C}|LDjZz_@p87`#L$N2GUCNkWrUW zBKk8GoNC?S@%Co=ap{mNCB8FdNVOJjgl%$j7KEK-1jJPy2x0x~lltF`V^m4X-XH}H zvh~;+Fi#DzDFE~IbO$?m;MjMiC~(%92=jTeD}M%VE*nM0>eUWGIWVvRf$meEv`?~6 z?0>V91m=6H^~)~y#gf>l*0w(TGW%k_;vqN>Zivgp;qP)}ocQ@$P|v<}ZnqWo@#{ag zkFS*!7=={<0LsqGu~Y27+Wsv0iND`pr9;{o=`ympmdu?u*V}iQ6f{ehT)7I-7}8LV z@9yAx$@ZUX7eKPpoLQ2bD#O$8shxa(c+Nha9i;KeEU#R}qisu$_Dg%5Ky*a^7fCz6 zbUd&jzq?W|sT=`tpFx4t#oD;=w4jE@1Hi|Wr}gupat(tG+Yg5GtV0*Nfr z1N?O`E+LXY-Gx_6LS?_d_UyZUs+HCmk;1a&=rp;aA#Y;dpn1Cil_WjTUuM1(*3l3p5usn zCDoUt0bwgn4gz-IH(AFOo`G9HpQ@LmQzbta&7W*<$9x)lA%1>y`Ki(^Tk_y4(s$9r zcKRi(Lt`awKEekS5en>gjpZa-Z~Joko_{Vvy5`DVWp=>-TOdX;lyB54>s&#*kGyBq zz$nm?xnpU|fO?o7!O6A-b<}30_e;;noG;0C-7oEeiJ7~vu?sG_R0gKWN%e5!$?eOb z3J>xXxpEpJ0?(5p{Wvk0JUTeK|D?ZUy^qSiZeL?}zCfWky!2_dvb}#pk^Q5B%S?gE znD%#ETxNf0pG?hytcdd?mK$IK6m>)X-e_;M3+yWB3w*zkc9qr%U7pnLo;SWx|8{Pa zjLJ#!;P~L)Nr1m8SYXez&#w3g5&?n~{9x7ogYVpMo!$!Hq9Y-i*#Zd9H{*F<>hS+W#@Y3C|EG!lwoY{nHhO7qi4j- zBrLpNRoW;1uBTi;BD56Vu`u%V_%FObP9ZS+?HVU7G%xsxTRr|qk7^Cc>p!88F%U8={%!SIMc@wro3lUO)9U4SKNS$s%B-(cVkJj6n zGi1^DMu4agp~q$CM7<{=?P6X@ehoG{rVt{Vufv4HtUz!QpIi};^8&IZ&aU^LH`Kmb z5R0Wlqa>zEVQ$)a!!AZp75f)<-iDj(lh@cs*(blmAG^0yw8Q4xyT|!iSD{f$2GN3W zVMnYvkK8<*vvtOCjWY}SATW19`ud#i7ux+%Z0;bs9&S6f8Rxv;{GB8**sVtX0;4J% z6%SCdyW_a#NwuToMVvMUajGiccpGFQTstj!9>Er~X^gfH+iHOfz|EV11c^HQ=3)tgo*#c{T4uqU=GT|m?=oLzL2qAG&R$# zobCRO4Au6=NWZLBtGT5JLt)8m9LP2mvU~3DNQ0_3Mh1Cb9(Si*CDjSEX`*?BB_9oA z`evwZ6Ky~Eqp4-+op62fuA4TC-vDLM(&4>*IL~xla6Hq?t(_3GKvVmM>8Q)!0$1UI zJCZ9G6v&Qol`>nJ`I=qBe7J=>;pX+8&cymX)l7#+%3(FnXtLdx}Qp}tm>Y}hrS+Gt&VaX0`dsF8!XwEU+L7cAh}_O zbZXX~_#~fGYvxfbF+*{D5USpf*iF=C{UnWuc$VzQr)BD0N2LiuH(4?*Qf@lSA?y8o zJ)(a=>-nsZ*0ZQ54cLR&jFaqS>>vSZ&TACj>Gc#}R&QLb$S2)cc~lx*p1|+rbLd_; zDlHEi9VmNqhO(WkcK zsVDK&Gbq}LPX**fV7pjycRp#?yDX2ZsoI`BC=7n(K9p~ev_FoKI}uXq9l_=^ABp#c zly-VP=fobg72Ylw6YY|(Oblu3Yg$NAi1Kxr%Eql;*tMb0ng6w)fe4a^#e1d)dv_ zX`L^$Z-$dZrk&R}BXc^usbG)*^Mo{dJ#j7-;>R_JKa=)>;hH4fQcw5`aO32s0qI!( z^n)^{1|eI{klFrvd9y3NW1&AF8@r|zfZatVXu*rjeFV8L0g7@l{=SSjC#lt$ncXs_ zn?JLvn|&sJBWC40zWAm1E{MesX^W=Z^n-D zO}P)o1OeFrKoyzds+)z_G?uLPbKIA7#nhQm#@OP^dgY(iLmI3!0aj)If=lH^1VnnY z%r~$vQgxb=q}OZJQ*dAX|{ou8i`%&D^C7=~9`F_@#U;uyyF2&J=i=kZ#nCbMU~ z_BQ@G6_qR+9z@|;$za7h0rztYOflymWc7$3-M@3^EL(4{Ic;j*;5@7QQPRN}1EQo) zIyXxO5K+cA%W(~3PXi;%$dDDob!mNcq@5ecs@3Bn&pWX)sN?Z}b~ zQY{ZO%_!D~F&-XGg~{ze{lGWlxG~%ZOEO4bYNvf;7t*SQL)Z&%c47X)AzZ-kbP3KM zxLiJlSBKiseF8z#ikky%#t*8({^1lu-|s}`hiljOI+H(qwcw9XC;B67(tntuJN3yRoC1yGPhheJ^PtfP&Ek~0daKUOarvao>OEUb`p zfcvQycJ!^d8?vx)lC6>YsS}MDT(CJq`E+0ef$CXTD}xJUw$yu~*&)R)h;2wYi4O=V zCy@-RAdN|e(RCsnQd&}{Ye4b&T*%;pxly`UQvmA4SS)TOZXv$bInDIM)XI=M=U^ z`@qKRS)Gyj5L6}g;C*C3nsl?1yVFmzYryVPai*Q}RAyc`IoWR?Up2!zxAXm<14*T7 z=I)G~47)a?;ssvKfUY7lV|7NwrJutEs>(jyI=}O(sZP?@dHPg5JJWs;s+?Rq_q@4O ze}WP5_^9p4;{4Qi2sL>-;tVQy_K}H@^q&8`$kx z*wx!vr$@Qq$tgj|7)#3)6$7leL1RA-EQebjB*KjD`R_oTY(emCW6w{&vS7&2LFr=x zg9i-jKDuByhc$iR=n;ql0+XloA!nR@R(hIKX7s@HynzF|pP6$5Q z#$TMi&}_%t>xrSJ@h8}q6$Kc|oi=bY%7TnnjK6+(RZBZxU+5-l{vUbo0v%U+--q4h zNNY%Pnlx6E#yzLz+KL=YOA-TsZvZP09Fiab62^dBK6ZUQn7IQCIhYyEoxx*e(+Rn< z+{BG{SGMEC@vdY$IZnNjY&EAo-Ibi$r|ywd%RWhZv{vMk#H}}Wn;y53?Y2qnp8kIS z|Mz|OyLavoAVE0Ei5?&@b06R1|M>l%-=$A~s_?bo^};v31pmf8oR4+*6NNw5J9YEv z>8aDJr;DeK9Gbdudg_0Cd%FCwR|;qAg>N}rcB&c4JADKmrz6u(&wu9c_CJSH1zwW*okvLIK=3R$bpW(IrVV^Nk3oiS ztKL`@vI!pIkwf5*(w+P~1j4H~5O6sn1eYAcv>W<8Ofua%Byq%H$Y972hNtT6=Edfk zA&lb`@@^jWnCDQ5*AJ~mEgqP%yN!DM@Bg>*Udc=9w>BHC+M$lgGBkhIHl6rt^|ub` zr>d@!D-P9b<}OiTIFF~XrE<<(k4@Fg#hU7LC|;`xsc3D$6~AYKtN4V{R$o}dIc9YV zP#_gI5Iiawh`uz5Nb>ep?@+UOYyw|Fq2eoWV-IEt{w5B=t9v*h4S(UTzQ%mHpEv*xC$Plr0*w|KRTR!dt;%NDtILUN8I(Dk$GQ za{ZTIdmcfwsar>G9eM87{Ax71I#&2I^zMK88}5DmnU@RqwiuInqVQMXO8(1R*Dn?B z!(01bJ#q0jzU4sYn+pHKM-KkniPxt#3-5XL)^q1R^u>{vKYDug#>epEOCyUTFHWC& zw;C<H8&HJlAv35&;{QS%R+x?Mayl&&m_uqW+^mP2%>a742mUe~&)h?1{n;exJDU3on1) z;Twe?MBU6Epm*U9!p-yt=yLTois0UL?=O~TzT>A#pMBKBo?`t#46dhNAa8|~X0FY-Urr$!6?!yEWdA4g#G zAnSjO5@__OMup9R!f&D4Ci^>m3~!=V^&L3khAy!;o|uH{o}Bvi!uG}4!uP{n^8Y1#I& z)mIDO{wkVr7k=}dhexlmaUFUm9mXque2cGm`x{u__u~ju@b`<)VR=5kS>GJ_%nKWc zy)vly=E(J_Bi;Gp{hL2G^3*Th!qxZX&Oeqr@5`Nk{0$dhEUa8C-0l^QUN8LN=Bx1V zynFJ-=J_d&og990iy@9D7H$>Zcz3<>qVkyi@8_dVA?{_)Qj z{$}CTDKs*}0Rn~BU!FqWsq4sazW3%w-z(aAR ztABlZ_14S(-OI0?UVZDY;^*35U+YJ!Z>>iCFBaZ?{r>w-eM!;er`fvWvxRSb9S3uK z1t4YQsoZY_NN)+ZMljmE+z|5Lc|mBPt-;g?=G zT=>E}FHT=77C!sJ#lk;&=f#uX`V7vrU_=Pss_&yO9If9_ulB>*3EgCKSy^;E*!av&_`NEr*3O|jd{Y`Xf`)T;yK8d#OfL3*^7vg0& z4E!hL-^sVeK7W5?{#2{+!NT|(g@wZ(8u`diyX;h zQyvJ@3-5korSQVxzaKY5xSI>+ybD;2V(1xP_@^_ES-0k-_o_`q~UGMdd zeD|;7h&UznEgF-Ul#$1A=a$3{)TxjV)`-X}jcx}WYpbL3>>iuk z7t2>F^_hRNGJ3i{|G)l7|MaC7J~fJfa^XL&zx>*3tFIJR#XbH9PrNbpO&Ht1=^g$W zf}rpI`pDW3|G+0kUU~6HM!snbL4i-bkvSwUEFg|T$-zc&OZV-D4 zvJ~u?fV>24rawEh3KP4k#&#Bm!k44S6OI>)JVEV)Xp>GK$q%I4tjU5O{9+&|@S}sB zcuup?B5uU@M2esL`2Hb9$c(@BM318Pry8F|2lk8izWV*b-S?gx`NIS6d+(cI}p{y&pS)j0SvgfWrB}5AnxS{PDB+!9e~Z|G3E?JY?qpk?H~JZ^?f<@NN9< z$MNHdCnuj=gr@rW@9DjL=&7Pb6d}g*@h2|INB{KZO*n;+)q%_YTjZwwX=s%XV-SvR~gjbxX0X}CM4JFrMdf~H&~Oze3#7+9csLGe|7q! zbcP^TY_fmz`H_#_c;8b`7q_63e*5l0-2Asu#mwJ{fL?uK@>@^@-h1^!aU5@d7e4<5 zG$TTMv2guX|JkXv-;buy(Wn3R=Ez6-&z!vRyIZHH*k$s^&~QeB-JdViaTrhGKkxnI zy|t&Ozj$q9`uWe`f15Y_U^}Dy%&F#QX-;V8aVmyS^@qI`Z`=;ZJ+t6NP5|P~kth{@mLyPCs*eYU-J_ z>Dtua|C|hd6)8V&oJAYhH@_Q8K5`Zx9(Ynxr=INcccu>NkG~ZbW+n^Mhrbm6K;g~r zd+AW&S7Da?B>M0CnXeRnE$B&(BHWMP4CE6W9{mJXlrMO)_vC?Z{|ktg|2A>}%?E|Q zQ2*+k7gtxK5502w^fUDJ%zSM6+SHHE^~Ya6ayfBYCrXpBVQhQ zZvkmo-|}t0)c?e9fdYBm$M^#(?W0HmgL4e-qmi|dDR`Lf%@hD0y4R;V{i$azec(eU zpSkhuRPpA>M(va6U;TRF*!9AfgNwwyucPh20h~G4`|8Qhu*JgE=jLzqZyqna`}HrL zscoDtyyx|i*KQPkb3Z0(bfFtf_e~!KB4v!RnsIgZ2MU?l$20>q# z9!R+U+*{v!W90wo7kU>9-}IIK$b0`e%Ic7U_h)|~D*PYFXMF`r_j|$Q$dR`SHzy14 zpDf&%EPOkTZ=0MiyaI~)`uE&Bed*)<(-#iB|IdH!>G?~A|MaC_LuZ7q6n+UI=6~?S zsOwiIdS^Z<&pW3SAOGup?k0J4};#q&ENkkM?PqF zpt&$IU-(J*RKNJbZ^P*-pI&_OIXHoT7){rZ5b{F3v&ufhAD2IW?}fwDRsHJ-zWu*> z1k5`NKl4t~`d42#%mz_E^Ug_r^)-C;{i`ESjg5@mdhN}^yLz8H_46N|I)w{<2Tgho z6n^|8^{MGg`17~q&%Z6LD}MVOa_>)}pC-NmPvF9jencMoNBY&r@RdIHss3BAjz{ju zkna(v{x|Qy5e5(sxa2JrI(4we$icPEsnbX9KY!~+p{<06PEb!4zVMEVy!zL0wV8F{ zx$A}ZAO6YdZ+U)X6twqapThF~I(k^Vv+!9Q&%}$_O6>l|uN3~Hmtf&-{=((xlT)LG zE_0mz%e(0Ci|h z2ZDR}xlhO}t%$4LUcD0cm`tvUwA$%6nDT9W)?a1F9eocDAPM#*7-p!GPUzg4+)Vg61-n@M2WEift`eAizt2myD z63vx+6Rhf;yL5TtV%%;Wy;f=VqZ6|?%e`)+wOT5Vho#c-O0Cw7;<&U_J{BSf)LK0# zKcKaPYfE#jMz7TEw!0yJ3ujvG-dfb1>2&5R{Z@4iPYJ@Xg_7Dz5}BC<6p4EWq4`gp z@&i4S48uLGpL-EG`FPrV?jm9O>A~p_m@o8T@X5#X(1Djdp2r@X=6?ga>w1liD1)lr2vy3F+!`0h!*W<{ zceX>WSzKDIE?%mZi?a3Q-Z+kdo*S~e#Sr`7#MaK0$HEd{Y{>zC;|V1Uqu6Y3MmP_= z-EY;D0>W@TS`W%mZyt0jTQ5YGGl!$~E?j@54NyR*QY-2|WBSjy{&N&jxo)rBZ^|=- z2#d#s3g>!Jml4l1l{h-yh)W;tSDGcP!Kl)7Ii3iYqE2xP%hZU&W>mQo)%Yr`W_-LG zp_02Am2Tg@T@6;Fo)*Alc;WZ}Va_d9vGyIlr=d@3Y?W>Ycfw9}Eu3$xuJzX1{WuD* zbXkINrCvwb%8l?`vt8*8TZ4&OrB}hYdg~ol@CV`23JO=E2s_qncL!sd9HTD7=q$E# z357>d_xL%~b+o(N!oJDJoUW{uz8sW**hCFf(~Wy!yUx{$Z=;L{ynH9@wedwSXvCNM zASyH5;<0Q{b*@^Ph#N0NW+{8c6K=$F;ftf7xOLpQ-d`^*UMhzHIhWhL*$V6gY-UuG*ACm|;wT7fCF)+TtS7H8dV&CBI}Z60Ml!cX>TM!@_+z$$ zGvk|4?acO7jLGa>nSsS?OQ3huH?3@6ZbLvVBgWY7_q^@%WFYokC_wi@<)Y9+vOj}l z+KPMv?YWg3#(x=ZEBCmt7<;u>jC*tCqu|L5f8wLk1nQ|Qr4P!DlbwFNhFz-Ok?lt{ z+DZgk<-$Ke4aBA5Xe~0bH7YHVZU$ugB6QRe9tMuZ3ii%XBm{S@vIzQ62%TOx1S@0( zKHomJ(JfA_hMj9mAmB~}$q$uwGL_s=Ki85l3PF8!#mX~9ZMifOMSl8{*KGT6pC*kT+tFqFJ_^V;QGl-rC)qa;H zct#-%Xqsaw1%nkg1mh@Cbt-X!QQU+Ir%s9FId#hJ|I-J(kE!LzDdqTBRUU_36WP>+ z&H!~#JRv)z39-+efK*DBH&2mZzvHOnQ*fT}hVrD+3hw%#!tAK5&s?&NA>=ZLnDe%= zA{GJ8i%P%Q1JOWLLw-Rb-X3y2M5IyG{>7rM`yj1eb;x}a!lfGlHSnajc*&Y#5f?(} znzi0~J0{wK*lISA2!tBH@Cu}Bv$CxZ-zOS7stdnZo(RjcLO>qvLmmQY49bb}TEEu= zubgdfwt@|GQfc+D+0kag!;eZ)Mt9~fmceWfN2lhdMC?A=(9B~Vu#@?S^5F(6;E`Oj z6xC6F+8MSE9xeR|4y*}OulQ@Ku*pf{x^?DJC~&)!BiD`_EMTvQCv-gpB{t%j zZkN(z?n<~`>D~c!+6e$W+imoyZ_JYIlL(@4wJHR^HltS1YnOZ5fOuACzyfemItYo6 zmpLX+R24^o)MwRpqR_fr4vWXk-;1;qXjB0YoQ(h^+S_5JzcpE}G~>vqv0f37A(hlw z98djujQbght&`ftN3pkSItZXJ*xUXlTy5QHQKnL-V3PPQoQszvoOxOZQRoZEbc`!Ta9=YP{)`uaq(DIV{_$h z-v-!UZ*N2kg4K2J;}j;{Cqgi~NZ4N#_x`>IXgp5_0D)5}S1X-Lwb2vpOJsX8jcj2Z z_dB?d_+r0@IX3P@mH1V{L}1Ba3B&el5aOlqJp`}@dvHitBbO$l8ZzfXw{fvWoVYa4 z{uG)L<}IEOkO@MCJ!Hgi$1vHx&FKWRfM70~wz>AN68(Oy=`pp~jFk3;*ikZQ3$U-( zfY@DbmmtPY$_g#R*C*uW`}*=U2s}e^3BVI*+UV+H#=;(_buHgPFC2%zsZ;6Fks{87 z+riwmB@j2^T@0hG8v}_3bqJ(QLAki)XjilfMFn6ztg{GuuBq3=MsE*srCd*JaTpH9 zED;pgAsAG*4Utt%ui_GuJ8g_V zc@QA0JYvrmi<1kiY*2~-~zyq zMG%$xJLm=o09^WXRtXsdS5|JrP#2ODNVRWF2z^T%Otmqk2nLfYSd!9+5Y1F%Rrl)i zG>WF&dw^s;4&Tg~Fj#?oZ6ITOG+OWUwz+sX%6Ud(_nIQlSwE#QmQMW$JgaUc-Ad_bU;_)O@&29I|8Rq#jEAmTv0 z+Ddlh!+j$)>+S?JqANnZCDrXP-doprI;@4$`b9Q&}T&R@QIaQ1^AJSdeF*?GGSJ_;Kw z+QP&KyyA=91}ukdI_!Z(#Ycf98i&IlPKf+zbrs5)KVyWtEy zf8iQd87@AE9$pId&}iW?y&Zi*)ORJs0O)uuZS}x@QSEFaMtER)Y$Y9{2XIs zV0!01B@Ty26ylXJAxH+8aP&6G@>%_g2@i)u9pk9pH~u(UrBR?}H+Zrc)paKaeb2ky z6XU1Lg@4#C=ifa@@yhLf(Co$BZY_7=sRby(!cwrx^3B6jT?Rf-g7IQP0x5u5R5PZ8 zaS5%={W@1c+@_}POB-4da^1HTH(rXn7DkJwR9)+xc1N81GN(TwMJJP$ zEl^yLC_3@*dKeLmd^=Ewub80>%f)Jp3SN>Zs-2ayQy$gjM(UVW&W6peAq9n;$0l^o z|0K-PW8jH9(Y6{3IhK#^)BxN(X0fXfV{fe?c*iB0cvOP= zqG{s9@BrK+n4YP_<_ZvfDI!V>DB_%BJ2*qC8!L)5A*Ov}#+%(y=h8tWv9iTTqAt`v zS<4ggW~GD40<+x->(`bpMcXTF#AvL1FfrE@WIifkCCmhIB!nfe)FGz1EY4vRz{p4k z!Mz!(b4@YzrLxBc=#GC9-UTWCsOX9TdnF+|@LL;I0WM8zs(2Db#J$ zt-}=tU$`_8q}nF(4%Wj+!~C%Q&Q{_zS-6EttAb!!N_Zv_-}yGe*0tcneQ15f35$3* zW5JF3_FU`2!r4$lQ(=h6{E94(2bZ#T&mi#M0fJ5df|gEzu8?72L)q}sj1>h2Wal7; zGo3j4b$J_QsO$1!DwDvXlpN1$Ld|seWG(6mCTD0`20)#_0))R1vTS#;gi0G(_$QJS z*EWD5%nC{b%RrZNUD^pPpj1shAa;cz4qLF-hE)g;>1MTuUY>CvUfnrDHk$6DCZpOc zBJACYp~`*YxMC4QMA8pNv5L4jo%RH7`{gw$GHBO9IRAmhqSB(v2C#%Kdd%7Z7$u3} zsCx7qG82M;6*3^n#Rn#{RI^Wk?KqG`u{c-WZdKK2E{^%qLgk}J^TSO9=kKRa1el#6 z5L*8#w4Im{*9>FVl=O&xBkwIdXA|$o5k*ixI(j=DC1voNhw`Opun$vuDp^oDQdrFZGyr^UwedJoB$7M&LeDNxL$5Enz&t4M~c7A#nH72A{7Fb8KcMxwPrPO z%Ls}y$Q^07mfP_9K;^^+CW`-WK)Lt`uMWK1f?(J(&N({jRb0{r1(OY&B;Erl)wK z5o_e%gp0r~ef7Sb?*r1b>=1APxDfRRbjk`3DX<&|t5uSiT?I1qTz~r9! zD{Ia$HG`qC3+<*jrqiob98E%>g!)LTVX|MJ&N~PrSYjDpw2P%GT1flUc>NMR*WCr! zjCRGVpP1R+>WbW_@bAvHg!HIW#9ift<2gskUN|BnbgWn8K3be1GA`3HVYa z+zht4vp9E-qLc}xz(=jXGvS1%cq|K}EP+dU$Ntc`sG&Zi7Z*oG1Zirxx2W`}LP(3S zn{TJ52u_VFD9sT*Z6PWHkFo~+@n};C)vgcGt4w>&dRbDOt+GESt3~n#$@|`pDr6tp3% z)r9*BMAeOqyYZZ|wDQk_Vua4`x;5w%9$ zB&Db+i-D4ug@0*Ef_hOKwXXirJ!>!*$Ajw1Xc_VSpg@RDVjYU^vzMpi!+|_fa%ui} zG~NC-Ge=ZkzdlUwae*aog0`^i_+Eor>Tx=$bM%=0sFaF;26Uvr@QWkhL(l*TnA zb0rUK4bWemg=FxsP0BAKN{ksI4n0RV+&yn*bgyb%9H1sTcGWDZr1WFHY@Kp)U*~(Y z3gfDa#Wk=Dnb<5p<(tJW!-%~B7mG&G%;6ZLY-+B!$f1iwYab)7QHnD0e&%J#B{c-` z+rU!mD_zb}F0yVTtWOS&+Gt>F3E7!l_*D?wIM#I8SakZ1iPP8QZi}m@%mngb!Y8v4 zCoycr{G~+<6VD*%A61kg)ea#GyoqcF_r zC=v!mCsd8d#ondr%%JW&ZRh}a@KhLDhd7w58r1;3;VZYVL*h`96hvAas_56(HD80y zd{fvf$uAGOL9;PE2EwfjpHZXjCrK5@xhRgM@jA84yAePk%3z&CLq{>-pRol_AC93< zGlBXtGo(5EoInY_b758Zk4D4dM2UeEv7yPfrQi<#HeN=JuMi+hs;MTELH$lLLE!0w z$SXq{KU~IP){Y`!8nxrgQ>-o#-@dOdBUS|JtnI?f=zn5O8W1QFo=~vs)3|yFFGQ>b zvo6B@)L(Z6u-)3WQ@?LL4{;ptrkesmrbjt_bh@Ci5 zOgd{)f=C!#YEp=;1Z2#C=q#|R87b{vT`-Zw2R zwWXA*X}e80BxKeE^omBzuu4%EorZO(_89uXB3xmKnP_JpQ|i+PB)3GTr2E7!(=3gN zs7)%cxxPF_*>}n>r-BvRpQ$_;YqFS{Ip`eKt}Nm82JX;eIH+{jZh}fN_5qRlV?77i zOkB>S_hvk@Vq<$ZfPM2bw`u56Or2|V*8#qxY|^I5nX>>npOHN8eJ-Qx4Nd4Wk`LLeL$=- z(^rBJ9D-^;^-rq91V|;%eiDDVWEhH>kjm@2xo9oC0ot}5IY?vs#^?Fzza~M-lmc8VclsVkLyI$y&J7da;vp@TwfYkJ7y+O!|^ zvXQ@?G=SMbWeWGb2bOrrUY#he1SYot#AHEu*>O905G4yAf?fY7vltNn6Raw=X>w}d z5JwqfTsA5Pf}|v;zmp2!k)6ayhtz_5f^(tlA**0rREf@su~0-fjrQY0?4E^>9DKe` z_#%gYi*O~bBiAlMHX^da&}Yf`pHh*Wq3-JrOBT8jvQTQ7z%SWDKYFJ zx8+$=;t|7*CNP9FSA-i0qBIS+N$+BC62~0XVd{a2sdU!G?con1k5i=8gY!X{Rt-9S z?B7E+OyX-zB!2HCnUsH6kATF=g#EGw!`bD|o2hV^SZUgGZNCg$$q=ULMJb~Q#b>1= zD+CrR+wj4&#|R*RkN(9~id<0stL=bl_?}4~=k@p!G1r(rFC6x8m*^Pzp=~3uW^G=vy35HG|_KFae(k#Z|2GRu%l|6cuNTgP2<4s3PvOPD~;f zlg%iKlRA^4=HV8?0vzi&#JFrY7?zbzYL5cd#ylY{k5iVPo0}J9w`WQ1fV%9L4Z)mY zx`*+Wp(=@t$ZXC~wu=+;WKkY-h!~I(Kas#IeIS`we(v^G@e${3s37ZUmxw8~i?_DM)UCy+i(}326$`*nI^O6^gv1#768wI_ZfkJqY25-dmi(Ldcy1i|6 zM7r{%eOpxV^!TN~!`8NJJ9ub+N!Tfp-x-HNyo`EZHU}g<`w-lvMq87+)%GkUGDByj zD=C?eU`o&lAuqH&5`AFg-VE5sZl1I|j+%@uxWAHaA_GIVq%Lk;p*G1zk@OpQZT<9{ z6!-3!fX{w|bhe;ZQN1mB1r2GSsdI>r#eJkxb&&=h)X{+h!n8%W2Ko(Ik#4Kek#mLH z(%{SJCSO~^5npkdQJ9VMQH02bnIxdjgc>d&NAq$?r@bPV)Fu0CU7FBlk3O_030 zHTTYUIaztW$)9DSTu)Z8xgM<}SV%GL1@SBpu(xp-a+6HseqdR3Pp2Eq3U!;U# z4Q$O^rx8^V7eSm)ToUZgzz5`zmW{M68fuS}-scQSPrW5c1@N3o&tdi^!J@jvKJKtf@?P&Wb&d~g2B<+vaS9{9 zPE$!OW}sk{mdF}+2EVzI_Sh9?B3p;D!3JlB+UnYgLt`kzx4xPx215%D(=h>g8Zcbg zm>}4QHxZv~0e`R@hwu(2X(PUkF5fxgh#6uKv`8R4+vuXq4$X^gV2|=kA#@i3{r@d_J~gE`b)DkRLN6C}z^WS`AfFj}}>Y+Rr8&IAy`TOsXz zG)}_qN{F~R3S?DcC}tb`PSBA}Q#d<6@8F9#J^i%$>=qr<5DSQlk`}qw@O^2>z7lKMHK95iQ9m^W z9<12#vTvD-cZVVf=vLFSClmbOQic59H_ zd`OPMmhM_+N6}6l!9ce9l56*g1~aysdrPL6Zm@vZ&1^qMmkJ_iS2mNJwOEBu0{XZm zZabbdpdQdc5(8b8VMig;DXKl&=&gCG(`8VxMHw`wFGz$uef*7d>2AN%lO3#DtI+e! zCk7?_=P0zvQY|Xlq~>3hND6i~l6)Mt?29omu}FG>lyHmVLaAVn5|iFMcK?z++bPS# zqDQI@vCVMO0?#X8{wN+W9JIL8Dtt+lSblPNNv6g@2DHb?0S;U#YkqMuwg;Gh>!lND zN+<;h;%V~5W>FD~luRL%nDsg)a?SL8aKa0Yj&ymcz+HP5%Hxo)kogT@Ss||+5n@oW zTCFBpYWhOTwi9CI+JVT~Z$+!fb9U#SFprV}C2{d71)PDT6dPzD4?RgqXE-B;)10W# zo~7gqErPeX(EDHf(XwfEd4nc2zK0HKf>q7ZgVju-?Q7 zY^R(bZzhR^w;haxaCks_O*Ss3r7tZ)R_2%r$Jh!qly*^ze+ zEIMIQ@H{c5xym-=D4|3vh87=?vE9SjMIFc&GqbU0ZO|!WMN6 zfSAnU;kcN8QwgYl#ia)WqWGW6wU3MiRkiu9?X+sC(@F!;LKBdUVDgnh;+7x z$i_mbu}v^!00N&wlSPMakXw?R*!AdS+>*o;gG1GKH^#&~`tEWnLoi}4eh%0jX({L3aSCa2ST=}A{yfK?LW)(ClGLJUtoLd_70p@EW>?FgHy!A9Ns zV{?aU1M|5UoUs_619$RfAYTR78NZANF2gB3-w?dYzp1OfBS z`4axh&>;-KkE2VFzU1|@N1z!o48eT^ab26|tbyH{l$lHuXVY;$)M&AZ&%msWxW+Pm zc*fXvi&QB?$~$oY2H(;pW>yVCsjNYl#0mz=nkJq_`3gjgrJh5FL;={wrDfJbB}9Zh zRe>d$rW_(2);uZ3djiUn4el8dRbf54Zj~)w(-Xp&w+BZBOdyp6NxL4EfJqt;9pAF5 z2-Bj28w?gL-thJh#=a!(q(4$w>U}0v0GdWXJrG+#xs!VUtA8bH7qd(60`d<*bFM${ zZs_@PTkH&+6~xGdNos?0FU1Vvk-6N~Ys6FMKiYhYnnPG3Cc9 z48&#Lf%BR9u|9`g*YXDM>P*-Uha$T4GlnU`jowO=#D4qi$>Kho|Tb)KqG0wz}VkXFa6(B~TAE zA%`Ps=ROCt1>dE4M*7fNEbDQlldFTW^Q1ep!%>`+lQ|OfY18&|F+xzq)Lu8w)d0g2 z&l9i21@0po?iFKyNsQ*5dGu=wSs%OOdQ&0{7PO5q0IZUeH;@+yg$Lzj56BoM z{q=~2ghz4_hR7KLjMU&B;Lofk{UpW4bnb%0m!HlhMk=vOA4Aqvh3gLNL4aKdF zIIv$iXJ+ARB#8`oCB!%7vIfBYG0vKVn}gw`M~jH7?*XwOwGVcqU+l4Sc{GodDV>?i zn3pQ6j1lW2mVu{m>SlFZdc>ZlXmm+p&V(1>1%dleyM9@)Nh2;d=2oB zbYDhabq#wA_%E(o|3%s!ckzYd1P?8RAKM(TLk?m}hSU`>rAU0BN@xeyZ#OYA4?bp395ewa+gskULXIVLRHBh!g6PBP#H4-mS$WAH zk>^)iHgQA0z#^kMe8gO(|Ij!C2E_{)izzd63s-et=(2PD4ieeNtN?C=rx*mI(r8Q_ zDFA-n!D3UL?Qec@+$HvzwiIcT4#yE}&wy9c2cV+0M0?Yo?-SHv<$|;^L`p{Huep4G zwk*D_r=8&*dhX0J2z_3N`dt`{jp~f%C2H4x^1?oGbs9P_Va2^D!52D_oMZue1ea!R z@Unz89%LcZb1ei=hDo*e_ruSqlMT;Qj=K&o`?W+az{qTT+Z`+h!HLa1WJrl??$A^k zxhOCxs+z_Ycz17ODKrMxJdV4H*gfyd&KrS$YUq@}X52Wa4DqtIDjX{`38 z0lf=xBMlt>vu1z2MaL0*^&19!Y7 z+X=3A+x-qe6A8iN~d8QGL^Rv3F)Ph)(O_o!%Re z18JjX&*qGEl}=7&@a`g28&*FBnTU<6C=imQV%fVy_UFVToW;)#HVV?VD+H#!3{FbWH_rgnP4HeG;N1H9Dl&)?=VHF zt+ZZ5m&7S4e@rxFRw$4FPXFA^dTA*%%V`>vKuL21(5Fq8GetR2+dK63fu1Kxvwa7P zG41M2PX%5brmmnS-5U?3B(fs!8Cmm4N+%w(9`v1|)vyRJ-Q*&Mtdz5d-Qq)E^CK4P zw_S@fVL=c56?5A{!K9XT_AWdwT`8siyo|t|Qn%C2l6Yypvpw1zd`$8uN}O~aW;L}f|Xao$qaCa^Td+whd=0i_btRI=7(gZy<0BH#3 z($fqw(qOrcawiI;ds~}B;6@SOTA2;neZ*5w_Z|5$7-SDl8|c|UEo*If>hL|xg02iU zY3wyxDS?_MT*-mP+WF))%tK)F;=M@X;5 zr#Pw^vm@_U?^-{#X~P_OUhwccrqo1WSg#n~hd6^OncSXL&cOU>`X zWS@R0^>l#{AX^*(xvho&3Lp2p1b**-Y6NKY5a2Y)dz^GQamxLMLjGPP?89-%%wV7l z>D4E3e+>N$qW_Q=+T+vCQhgL~;iuaN`E6uRol!M*!z5GxYU@smXB7}uODq7S z=MGc7(ke3t4i+ezc3Ho)jrcr<)Wc*SC6vEd4Ky{2c@O5W$vtmVT3g!k4WR+g9Le}x zp}8OBAdl1;h0r;d*kDJvc)t`-s`KD5|6_XdxYgz;vOUU{B!9?*TF12c7-LwpAPhcI zij$BJlH<|hG1k6zR1lAS8~hLfHX!YQ7S}NJ?gBFO8z`;Nk(r~r8aN27g;bedLrPB{ ziv+eL$0D3LM3CDx06tbzFn9{+n&|=Ja>Z<#7?;Rf-wATFDhKaV7wEHZ)9QBbicHZX zwnt|-;5<8FPwh4u$Th_gw|hE_$VWiIC&zkugfQDcNa zMdM@gDsMiL?LgBPm00?ew3G2{8-L?zXr8~K;SiFdt*<%L=V2De1Js@+7NS0SOScS_ z%`Kia@!cG`YlUv7y5@{p>l01$YT8Bh=%WLaX~bGThhMbM^`Mr-Ndw(&dgNBudvN^> zp%2)>D5XL3!-1qZi6Q~et$GN*la^L`m14#ds8jp(y7(M2S-VlMFVht zZg{Dq8V)kOn{f6`9m6n(ED&205>OFa@RaQ-$POGX;78YxadHe=YQ-`Cgc0!~!H1gY zK&AY>0zMZUF%-@f^uxNbsN*5oX}0wGbFY=hk>9tRRjD@k}PD#a-&dWNX@P#ktjLaG{f#cHhg*I{&r z!NAF85OWg!WrzgDehnC{P`!Z5BGn$=YeG0fAEr4NJU;0T@hTZbnw2$U5_%O7M8_}Y zZ+er^hph*nnV#i#PXPuL8H9Bl6ZLo`OtI+uCp1U{j}w|SncV0>!Lq0aiE!gWs3;UT z<7@$(J&hvQE3iQtEsZ4IOcI#Nte<81H!ipBqJg5^No)!dOuDW<6gZ1D8tG$n;f+Ap zUxG(CS2z;+9)!@@SL&MgB=HM0Hh>I~pXk&KVK+)Vgy z(0eZl0cjzmN7pDm2MxH;@$OaGzfDg@FyYoG1w%&9jC z+n8=pYD^=lvte>?_K#4;C>SY<%?Uh?`g8KzCg2bkBN0U~wTWQmLWL(d3+v&WNdY}l z&(8=3pOceA;nK~aGjRfppZknQeJ9dAaNq}Pa-gWZX8NcnGrk+-DJJbo_e;iQv>UmH zxuo?9tb0$$Sqm}gTi_pG4pG3v4OQh1M|``Qu8e8&A26XZHv$JEP#iJPfK=KBfI-+Jy2xo7r4EL_8DVJ|t1OEXrbO`hU*=c~d1n0|n>wa};#`75{yrC#PFID4*xZ63^x z_W|fAQ~)48UFY^Vo3nWoHe;zTuID>Dr1eRF*wv5Fq)<^?*%?9x<)h0yE#D>*&3h0jWi6f$-Or+8CZ zvO%7GlB&Z`#xf3XLonKf2Qix#PK&H`8V0(?hpVW+To2D*ojZF0Iz6}w`LwO|j&kx# z0PDNev)SRr6Y{-t7V*s`a-*XCl0URv{ZH_(l5gE^H56}VMiAn>!5=~;=5o7eW5;F9xBZz)yzN>p^b(dY)<{t z??z{2Js>iM%>SHg;hndkC+2ZF;4;!A$+@Aw0Ou>~>y@B`I{bkNL*D6t7ZFcbkB7Y( z+t*v9-?r6bO&guNrDTQeoRPT_(_^m1)-z4yC)C(?6Ey@iGg+a?IFuz%z1R-kUoZ^L zdx_qIBM1!Hoz>NA>0^9~nm3fSqz_AxeXs#Vj~^frZ{ITQF}@E~gYyv;bK^rl;pN;%P(t#RRdsVD(^q1%+*7=LWBI$^tvHO2YD;)_~Y zMiMd5F`VoO@6-R{Dh>6iC}LP|;GETV>ul8GqIZB7P`1@#)!5Cb+a?<>x0foL(&`Hz z@&i02bQz8aG0nALEuL#v`|)h0L%OV;*`8@hLJ@`~XHd%RQB8&nAax_^xrVEFnv5+> zYQ?dS$gNt15dp7!YZc>yAn@^*jNaW?t`baw4Rl=I8bQ?HP0883vE0Z4dlp%j5DC*& zJliI~G$E1jDl{^(V)`w^W-3!S)p@pKqN9I;2e98b?*yj&Q;m7VcUj z+GJluGkUX9vv@|gg2rBi9?>1droRy7sqqc$j*U~*xXp0?aExZOGlqt z6z0N+9AwA!cB=#>$6f`cGyNVq5`daOidfm@cE7p?lixigHR_(>E)*@G3hVr=H%qj| ztMrrzm)kQd=+KPz2{HnZoSBHyjfAI!k-fjkVjPY>K|<_yR^c3W4NvgcUTMYqz^EEf z4kGV(pTDRe&t?tNpu-rGS92~kk%ig0b!3Yy(KllG3Q(rzG@14&Tx@JbKoH)jK}#KF zdQnr#AH#TQfe!F;wSviDqU0&8Gg)55ErAbLri|e?HDyL0*Ku9%Xbo1XhD@IAuLqlJLXEuz&PTs$>de@x9XivOV=cG?ObfGx&{e@3<&eJ zyhQq{Q?``vphe{tFQk7TEY(38qY9Dq+JU*vX|9XuGNOnE7yy(?l%(>(AoHMDh_9{;ypH4b46ojfy}~FZHVBTtEIpL zggVi`Q*GuhZ%?uaM2U&Jj0P|A2NDi)_?x_aS;8Z_q!2@h!=|J3oqAKH$yLnV{Cdq? z4jtJiwx;0CSu0DP)kmtk(*G}BB|1lCA5$OkJ*#Ik#? z{j;tlFulU80UmbR-|&tchmJ=GkhBBOXtz*1HyQjHv<7$5JS@Bb8Df6VordTHZwk2= z@hAl7RJ{zjDX_|7M30a<*$e>e!g(ACYi{%?dM;jQ(4D9qAg#y)EzFe{1=gX|ooEJu zYh9Eq9a(+leIA&(I8YH@rJWDYpI|$PCbV*5_rRdvB<2n5?ZQSq5d4?Z;<_e645 zqo#vSvz~7Bnf6Shw_ZW}Me!RLg(gw}{h5#q1gY4Ip!AaMR~en9r4&dCIuOGtepqgs z2ROd+M~(xpZT+2&H%;FVPQETkhBCN7mLv#JVE-hmr&H4BI(1K*A`6lY8JU*|>05?3 zUm5u}Q)O0eGpemd-`Ph66s0A$U>%Lt5n(s?TEko-^RDD&{a~b6d*okYe)MuNhZqjA8o3cdP8IB7k ztt_A~ch@!&8z4!udY6fgRuJzHxZoiu5CP?Zw0o<=%B=O)47$}vnIRc$02-$Yt%Q@+ zV|W9ww#sM1wZy=dqd+(cN0!@`F7YINuc4U5^E1~laF`&8zR;(s8ljUZ#v8a$=}}<4 zU|x!g9JY%N%?Ifg^y@mx^06|tN}G2nLg0tZ8u4VaHf~^g5uRuXUPqcqs)x15oW&Xx zQ=(SwB*C;Wt^nnNk{L5aALXcJZJlC55rP@rSd=~m*=$^k&>@ZPCGSb0#~Ml(9lYSS zu{u+vZeJWy9M4za$XcTo$}V9dFu}<$XRqt3m&)0%EB=!mOTkPK*?}* z4P3R*mg9=Jx1MB3+acZ;)+kiU2xn+mdp0ZoE@u87%lti_`FkR00dsjao29h`7^)$V zILn}`#C?`EYDFJ+3}O@!=NKb#pc#KpO=-&MQcZv|$`qu7lP&0LFm&&&WfpGQ?KR$? z)YhlOBC1sybwC=ohfekyca6bcw>Nt1}_ZX99n^&VPOWpVcc3-jxaG?<2~ug zXx?Cm*$R|iyW>N$PQN8G2p1dfv>f3inA3|{ornMf(g<);wdXoopyJqoJq?D%GrhUk z=fdMtZyHPQ9PY-^MXX}6)I1;IcG>uqZLXG?g&7=Wy!lmzJ=aoc3`k}^Hfl@r9GJtL zTD=f|p+UqtPXbUQ)tYr_K~9MT^UypK_9X38^)%^)Zc)ISDIeeB+BO=@R+=dnpUNQO z0S_MdPN1`3QH8piEq5K;trTQ9@I1=$9^k^ea>*^AB@_h)SYg!lVJ~DER6rXf2tiZ@ z$bkFBaD$~3m)^J3hSScTrnVuuh3P#_`S;J;?ig24-#6Gxd!k^f)HJm0ULsEp& zXJ|gz3Ui+X7T_dwX3R2Ld-Pj)55&Jl1rYa0W=_Ak&<~IVh0R$oPA94f`jZG)mK=kX zlz($QtT#=l1+?Cr?erI{kg_wub~~Z~g_xP-@_8_`I2T?)_z+&@4n|@qIYT)hXyYBW z(k_vI*V zT_*Jcn3XaU_mIHNFPKxmn}H)BW6%K73J z4(cFFpi^jcBRO3|TUw%*5f_$`S(<<+r-hiSiU2hUpp1+t5m_T1R|PttC3UEWPQXK^ zLs4I;3+y%92g+BsCVo)|TSjFFQW8^K4*e5$%!F;qOUSZ$8nQTBfi)c`nNKIpySXmJhlpGdqa}R@-HyW5J zbR_2Jb?Za6m1+Dt4mOl%?E*^WF*VrWNbzJk$u*OUV%N=410mU{UAean(QN$cp@EQ8 zxM`+Mp2_u#cv_fXr?j$5bgKB$%~LG9Cf~ZfOpPBn3$Y|Ym*y4~+hs(beEU48W0(MR zumn7yX|2!&aW?EQ{vZ_^NZU@CsnRw|4U_ZMC_yFwnqEqEekFE>Z{vn%B4p4D7@!*u zQ70X*H=WoVtt48FL04zlWcUxRrH+aF>qE?74If->!4$cZilIS^lpMihw#FHSybW1< zt<=b!+w2-15GX11mjR!A-fEt-ua)p<{(h!KI$ja0AsY~l>Uif6Y^ zRZ@Bz>@)g|G8%$+_II>}$l+D2Ft<$8XO|yDH)J#x?A&MxH8J4%9JmlAp>C@GqU;#-ElC5dpnO3E^$wC&1 z-0T2Yu+J@EXC7AQht#bqCrVP6>-F?58bjI6#mIgbEGGW7ai)y`>bhz&j|bT`tcUXo z9rTZyH58#BH$W~;pBJGM9Na3IekwrWHpqxKY#jn5k}n~=XFNvd8t!$7p=4j?ixara z^z8|10N_g&6AU}t`Xy9dZucrCMdo}CR224;= z3bQrWSuh4Ojb;JyqpmFHRbxE($mm>`PW@JO+xe_jIwc%W{f0MDowHd z`sVc#J2R{+FH)}z>~@Vxwsgxqrc6K$qKqzAY;eW#G~>*{+AD~fRUe{_P9o-J!YlG- zj%&WMg8DiKxCfjnn1AFEWFF%|mUxWFCsVST7bRkT$5aiS9WHwTHr|S#rr|waTp1!v ztZxX%#>i|)0%Kf5modS~B!b1E6|ASE3F7Dl1V7+VwgETrBjVq>@|}*QGYi`c58KQM zY&&T!c|H>iteK@WLNTSkS-pgt9PcS^#y5KWE^JcOSvs2wXyLJmwACd9KE%)Iwg@6i zz^mRbiGU`hTv;%!7AWX3#coArdKNIS#mCXe@m5uzg%2c*>A~is{!o6zBwDKywXC}(jEAF@N9lRDC83T;zMWI z9fltQ7wJ~}z&s~4n=~C`;AgNk@TuWi_Z&mr4IpB}&m1(=lo}*X4tfLhfus2tup30@ z%Pw^vGh~np>BOlk8=D9NR5*&q3jUJ5H!MqX_=wR0dNEK+X3(mxp5sZfggSRDT2^vZ zhF@;Oq@dgs(kZJPM2?eF`pa$Zuw5R{7}Q*-KCN_)K~}{+**L(FkY&uj?2Ltl!E7<; zk2}|I>e`A=KkfaQi>)5EK{b7go1hhZUe4eE0WEe>mD}BRRICUNvof2dI&!93jXJ&9 zY^J=1JY=p>{xP8;yUDpb=}{bR_h=nkVK`R@FvIA&&0a!ZEhCNur3N^Gb+G|j$@*li z?Z!<4p-Y1klX9xgxEoXr`d&|}r+w$(O2||aeTqVnPYlU?U4GtFA$3NOy`1V(UhCt4 zjZJelQvMsfH>!}$3&{Df;ye3MKRU;=sm#)l&O@D$YXN4yN=7TLKE~SVKg|s*nH|EN z#-Mi_>G||DqtCLFxdmVyP4KcCZ~Tg>{lk_?E}(sYgt;Viv923DG{MbLFY`PRb2kw} zC2c!fk?GLeX%{#giV)l2H#6KM{x7))kfM@KuDVqg(-;@$XUSgh^;!oi^A!}1ZX-7k zK?MzL!ry)K98&Ao!xdVgruhTbLr3SBXn758&@!@436?c~cn5q9e`}={8)60P$O8ou zDKRCh0tG0JCY4$09u*N~{GH@W9gbNAUjmHc5M`j`Abd9@V-BCm}fVye(ZM z!_l65Ni(j!;6R??o24g$bsHkVMN);qhP=GQr;Y=^F?V8Ix({`ejkiif5Va)7mM2>5r(SP z;XTs3?f5WT^Q#3V`G`;4DJI_OQIVyeaHhN3XSth8ayP>hu~+UxpCf$G$<6N0j0iJf zbrb{?lceo}Ss~+AGP{3vLK?uL0wH_R^OKGYjykF0_-T97WY-*UMIM33Iqfa+~5Th7d3YSvR(+v*%ffjXwv%<1 zSA5d;oVS+Oe9_IsHDWPYEo0+0y6ZHWZ5+|~AUGJ^e}+NkTGsH0oYB_7r%4EO7)v<_ z-fVZ(gV5ga^UGu;PC=xyGZL4%tC8q7R*^6;#M(C_*O8 zsOBrt>jvT0s_l>)K?xExEF&25_TCYPGc|_mQRE|aKrUqkN)U8_>^~ia#SO;2p-va4 zD3zh$E@Q3-jHjFj(hiYSx0L8mPq~$Y9S|7U0;AMf8Wq>-09@0};V=bfMb81YsMVWU zMcqJ^M+XQU!9mAZ7WnnIPMJ3mt%z~j=3D36%WdL!>{eO{ETM?Oaf&yAN}S6}brn zlC)(eAh(Kr3|)giHb5UJT-7y6f#jKI(MZMYv4teqOhxL9WbOo>a|p}G5pVl~6)%#N z6RoEYe-Sypn`~<-gEtDu#+tAJ={#9-%HT%wEh7HxVv1^aD{9#VZy;`lpigZ$p$

    pl6NoAIJB1`vlaEX|nV(K4My4y=IamzK`$to_% zxedU<%uK?L>e{&bU>VupWu_^(Z+OEAy-}si6~Ex+uieAVJ3pLqIoIig5*V>dOX`-?+7JW z#p7KCk`v0IT!&_ZJ5K?ZhmCBlsgM-jqof7P5V;hU7^MtskKd`Mvu>TB$(p=D&&My8 z@&@n*#^q5X(HR15CVd@6grIfG4{0ut7BINc&<=2jSrz|Dbo_XK8wu=q(b72h(ERGV zWIRt@+Q~1lnv@|4@e|?)gK>%q-@(|FgmVT4ZBdhm-xRNc=GmS=Oe#a68fC)l%oxQE zj+JONcL;3QrSsaXfZ>*`FUiVPuZe-%V6iA|eE>=yeZW|6%4n`afXXk|a$iIJf{p4j zh29O+*@b9{+=oR!lu%p_xhj5}H4SUOVTGBukJ+4jEa#c+WOET%T``nvhB~;>hAGYW zZd@c7>!8uZP{e3`$G>it$5XVreOD==mkJ7NAPRR`UdHncFS~bUnMNBiU}QcbP~l}T zj+u@+$IKLlY&upYw@O8ycbR8uXq7^S3c>Gb3}!4lF10jX&kH@8p`;jx3MpA^ZxhKt zqI5iZw3bh5Fe#Cg$z61d7($*_2XK&&*AiJ_h9fRg^+lktx38@*78*$9fkwz(Ra+7( zIRWrv2*^+o>P<|SRukc^WzA4BongpEM3(?(M{#@u8|S$wL|UgDN=za*_M1o`gIE_b z#i5P^q415Upmz`5G9W8Jp^`}hI)Dtk zxFUL0l)OL^)g@L8d1(yz*5fFvqPSe*enNSI$)nNyCX7FmoRjvlq%%S}FGnVj^ofy? zfrBPiXqHaA8otqT_41|5SDw8b80tZP0cIP^xS1v45xsR#p!H9qWtbFk1&>6qUcQDi z#FqG3MVq7+)pCo&Jre4>W8Uz4f~XT_w)Di+i^ zOedKM!nhtLqC2LqxeoEnY8wGhpwPLbBqLF0wx1DUzeFv4DQVx&P_G|&TyDE6B&S?b z0?|pr#9J?9Jvv$xh^lkfEWMy(P!w=XD}#y60QA`qbvBTgULLqdm|ze&KxA$MF49~? zvlkvopiUIqkShoEWgc-DFPq6xq1=^~4oc=Vi3OjcDSeKL7UvqU04_yKHe#!@GG7_A zfLh~$eB;z>64DJdp;%p%U}0M^Y-VX-3+NA47gofZVQTLzD)hd$#BP$L1YjAhDMByp zPqRM0JioaL49EThs@9aQC6r(bi-+4t#wo13(C)gX)+jY2Vi@xX&PP@FIJF7tcuMHi zek&6+dfs?W=_$d^-z01&N|nD>d; zmZUR%ts`5fwOl|V<;U>K;JvMm!$s{F;C%)^byM;VXV)TlP}NWrCATnh-Gs2qW_>en z*L)htV{kuVYsKf6WJas;^`_h;*fOQX3vr ziL|Fe&e`~l+^NM!Dbh5vhBtF<>%YAPWTUcdrCGKlq{c(l%F808xG z8k>#=E@ns~_e6~6Mlf;;z}LkGGMF(i*Q(;Vh`^%%g9$lczPeU!gZ#Ie#nP3Nbio$9 zNg8~F0Y{o-(i^D088W8 zQjX0uc*;X=Vm3nZf*BMB3Ffv*y<)p~My3hhNT;JY_BidLL=PPa*gi@I>!s`{Mo%a0 zuz`xTq>|E`Y|56*2+y^)7rviq)vmUxral9UjvP-m^a9sXG$O>|YYG5QC_hG6Nf6 zRe&x@&0A~ms~ojm*S5!+*q}79RH-%EnV23#3~q+0X9+)-nKPaOuhXMhcV$Jxqb>;T zahkzmwgSd_lBBt>uK>MdjHuNI8F@yeB_lr8k^xrN{F-*j%et`}B7Ui%f4FOhh;8zs z%H9aEJ&83!987eO^1Y`9W1SpfZM#+B;ehbw*$(M-#BHQOw~}mH5a2yowQVUy!5=p> z>97Zn8S|kj;Ea_Ig$VwpYJ|xpPCT%a%$K7s4xo3tRCuxZb%%hhQKNXO9l3LaNq)Q} z8geiYv67CFskGEIgOcr%jmkzWER$7|THzGIVqo6iUd-BZiubMXd@6mybP8e4q9Y5r zih#?uR#Fk_5ErPPle9FSXjS@c*m(?DTA92IE->A-xJNaUT^n)w1J@489rU>0hDm+; zO*Ta$1lpYyIh>~TnRs#BDe|A|$G&%An2awe%rg43T0X9{&W*J1i%S+4D&lYhg%uXE>4u z1YYdkCW6RfKHF$Ef%EFUxz>%!rmp9Tv|hysj6l>BzNPc!^2Bwqf??PR9=16KdEg-E zaQ&|9KQ|u`+f%~I=uqS0(hUc61*WQRC-6o0gV7!cc^$M)*JER>mCynZnTB!hMCfbG z0JTfqP?wp$#NgHQvuALc%N@8B*3nK2MM4yV3-PKImAk;JdOaB5JkmH|_>g3H%k5RR zIu`yxK9!RK?rq{I@|_5I!@x@hSRRv->NN8t%RZDuIv@OkRg+~$g`S?3koWKb-qDM+ z%Avejv009IgLzjnJtqJ8u+3bM<$}a)%8ph-Of9ditc=%OmFDrBv|YCb;mxt*n6E-a z0O3qlptO@e2J*G5ByTAp=ZOkg93W=WP6@gM!|>*KG5u&yteS%lctqhzJl^}pyg?s} z*Lq)pAx%*yo;~V6+e}zxxwyMz=r2~DK>Ph?&!8HAZT)4Pl>GvxLXO1irXWm3zWXLY_O?r_qq5(mZ zOK2FMe<97mRD?S77K2JMpQhiP+MuAV=A%F3WF07WoF2_QbZ9brS}==4L(EtghnEY~ zrcKCvKwugB)!!heLGwo|4)F{l;C5pM50VYO!(Q1=6loU4cb+7n%E?TB@B%Y~0S3<9 z*Q>2QQpAfmPp5bikFrc=707UA%TpJFL&Lnpe#m^|7y-Zd$~db>ESiGxFNUd^0tTu+ zEKdceX$vqal@sdTk6WEY$*70i^}+QPDSPgDEZ5jr`cVoH(bt~3p$PG0KPUybaF{SN z?{w?oo@u_&5QRqpZX!xw=~?4$4|Ka&jT)e&JG{qt3kxJ3HtmEY%@qkd(wpqq5o=t1|eNRcsg=PQgHAW;b#x2OH$h!(~p&>`4^n>E>#zm?hCb;jyF%4)Q2Q z=gU7a!ZLd?v}z!8om4=0TZ%n2F)DANv&U0#M9Bu^i`RkRn0v7!D}hRQmIr|_GjA|g z5Zywv6L)7;|KVz5J($7b1H~BlMG{zY_W=X&mv2CQkfAcD%Z&1*j6lYl1%1hSh#VHq zJ0Ub?t48E=OJK?6$s}BcdU}Pt1yRJ8OxF9#kkTA708+3Dk00Q&%q3~Q#SK1+qrh-N z%3SF|L^GD1;=GwRCbLiF3X`tzxGNNM03OH3(%r7@K7=0pnIr_6(d$;G+F zNsVPJh|DFTHyjx}=wZV+E=O@?c9%P^XPe|8i-ck*?{lm^QL-dl%`Pxhg*{UvT9cmD{qLuDQ3ady#wtH083_4>uJu-Rz!xAdwb zakqM;3a68FXXGI45fUjbG6OL}l-!o3IdjEOiEh4k)b1EIp)y?r^Iqd!$TT0xY)0nV zsOKy2%(eNTH*-hSw-eol{1njt*ig2N`mmL?nPqOsszHrNHrLbM-yd_Zu zof)`Cc~0F}Nu9YgJx2^)Abvtk?sC-ju*#HkAGpU?P3m6N3wIK+=6R`jYDyD$6Y(LF z8&uwSKve$5r<6gCK=M{Qg&EvC4j(owab%;bym4f09fvL903AI~HNE2&wwmWU62~tp zjB*z-i?@edlt5md@AZr7N?=&PKqo3 zV!P4evDM|#Q2$ru%`442F?_3dWTo1U*P3CS%?l&_3K^QQJ6n5dYO;!G7#HgLykLptNzQ_VUqr;(Sea{}lE-HTR{<;bBR(>NIl zwroruj`b;RMb&Az2Y%6 zgkXxj8~@y{j>9gM)*Gb;2D-P0G`9GVaBaKO?$s@kgxp=w0S?N=Ztxv@8E2=1SL7|G zeuz!*Hekg@kK_iDV26t(9MHn?wcYk621c%^V^h(5lB734KtZ^K;A(rFedEvpkCg=2 zCZS1G>|$OZ5uR`%EFzC!+A2z+;L&v?44&1&)*|UQ4ebPEL4Q$o1)ijaCo8lFTjrCV#x2JioWy z?lgsDipqDCVW_YmO;>|jyASTe_+>eepl;6pbaH}3?hkAzV=?JUf_S}+5S1fAiuoQ7 z|qNtK2(BgCaEpoI%e!RfN?+8ZDs8 zJLIOD#bai1Q*R5{AV3KuwNxUNx#?jS;*X+mEF}cPN`LDy2|`N7Dhk81!vn{3-B=|` z+hU;xOnR-Wm5DZ+5Uag1ZJCX zzEY@s&izQlaUjY~xHATP_cX+Ag=lH9x*V2|g?L3}t_p?*j*u65XS}0&*vM=SWbslp z=&j0W>~f*uB5tqJQ+kMUi^%Cc$aqqc@nrO~P+(6HAj_$C(xRRd9IP4LSmN3$8CNke0`#Z6+YFRk@A z0-R|W>q%<3peWm_9eBAgAmP4vwkO33Q89cdM-gzVg) zj$>SiO~Q3(bgbQg=={KR&|7ODlpljHaLhf)4ph?>;CgPe=7tc4?K6=gc~145Z9BY@rx1 z?7-XrRX--Wgb=Inj0TKjPguAXVKQ*+#H5JqP@Q=Lo5D&@9(5vZYjC}6hy6lM+5jp- zCN9huIAeieC^dvQ7bWy&ea~R^x-yWr|0xA119u~G3 zKQ>E`CuWy#BY;)WqFIsUCd+de&rw;$1P*b(s@gK1guf?A)9I1&1@Z|?zjJpT; zEbNXqjN1V`$fh*%!>Fg!blg-DfwI@#hPwj}4_LflkryU z>Cs~)9BU-Kb8}Q9G=|EVv*$?@LZXKaldMHOc9Jr3!gAJWnOQa~E)J@s9OXZtZx9I)41j^j?#E+9Mqf{zc!T^DJ4;Y8nDRg$$+~tXjal3VlmS@yG zDK2jY;Yy_w=9;Kt58&trPr!L?VxTd9p1Sa<|uY=&g)ZeWD0tBE zq7yf}X0T%q^<=B;O|0%=w`dpSH8$qaE(r>9Lm0vc;bPJ7J#orhK8ZqzEm)-#kt$V! zdul6B@8zpK@lKEx!ORHSIY*)MH{}z=^scB;s6Yhbqm8Wz{lbtIqIT3QMvE}3fPzRK z>K#h%-RXXYAO>0vpG)h)f0Y5ANj#}L=OT9>?@Q@nw7#`C>wUj6bN)tPr zT?xuFW#rM|tVo3Cf)pGv!drwWt%P03UIgB1`f{S^6s_&F7-OTD1we|3K?jNSVLmDu z8>_(sS&L96#D8Y-f5EXSjIspmR-Oo#Zli8ii)D8f60#eJFv1-}rjc#kNnj{PrYD+D zDZuF5>zJ)@5b4HmCE04kEcg(AhD9?&6#L;2^z^(gmqVlPvUeRt;X2y+V&XPRF`iO< zbBn;C5;228rC`Glyh1=Vd>(4ciYLvMEkn-OV8P&y6$MDn^2AvjQf%N8E;G(m<9Hq- z2sB!nw-4!cb~4=hL;V$%0SHh|t)}kY1DWLE@#}6i!WHoOE(TB>kJlhM5qNCFn5NSL z(A~gZf8%mCTU;FAC}eGcHsA>r34|jC;>s#wOFl=W=+84etfZRo7~7Mz8S};LNRIt- zoSrqjxU>YWfCW}$Vqjvn;1>IS^ul1K6!KxjzhmUg za@(p^w@CTZ8k@kosfq@yA0iRF5mJ=dLqkM{fmH*MBrzcJkv$=juJ@n?mmZ^&GZ6a8 z0+kjGU3-h32a<+32h?Y#Trprl4tc+Dw-6==&nVTf^{`lKa6w42X?rzeusO^!)YyBF z8ORlVYGGw;lK$|aRP*5F6KCnJ z_lzl2lzuy`N(AbbQ}(73d|Gy~$IIb{qU<9GifuLDNe)|At3^LWrSKy}#Zfrdn!n zteLIb?YtB1Co_J~xHf{jo`Dwd{52*nFz2%iK_3rIFnUPsGd7+hVvV7Qb;!70Fa%Q< zJWM`J!{4%k+`Ej;fD9w`)G6TllurJsv&o{+N*c6 zX07#A0&v+!md0T(;VI(gJI4^L?Cqe6n*bwtXp1jS$+Qd!q-Ay1ZJWL|Pe0@{K2SRi zRW7EBb(#t9&I@}?(`FtBI8-t|k`9UQG&<6E0SCnI0x3PL+r!wNgPT+IOjq3*AgWQx z))8Kz$uqz5|8w^)F_L9zn$WH8)=VQIRxC#%kzf`@XJ(kYM}$YII@KN?<{38W;qK+; zky(`^xMOZ+?rs_8W>)s_aIa}aGZL@@X=;IxKqz~GGzfapn#~B!c3_KGumH_sgjld( z&}=|r1>gVw=Rc2o&$$l^j}lGKWQCdAeVp^3|NVT@?LJ44k%)(KGWejI6Fy&VWlwm% zicR7}4i!=1%BPo9!W$YLDK>+48}Pk(63-J7MKlZ7QNlB;wAC!ULtH>SSnM{4nOVMn z><8;0^8wg-0=-YoIx@U>a%kS2XXa0w?@mr^%E~(_pW<#1iy&s(1m;gAK!9wK6Lct{ zC@3BttZKikjZ!>e<;OB8tnq@w8k7jm3#^mP2^9`0xkRH_L=DVeSWgY1Y<}B>voo7| zGbVRHf4mq-7Br3yiOmh($o@R536WV-ch2Fuws1bT@ZUjDBl_X-SYgV>U&!zb#YKqw zN`t&fbT~&kYRSFgX?<4N`?Q<-qt8C=^8vI#-kw7P9521F4S43zL@i%(XoC5k$5C2H z9|`DhFd_!cj7Us~kZ8i{VHBtJYA)P}MDPfuw_PdA=WR)tyestt+}6QEu8xQjDis^G z>;i5AFfBMuijIPUruBI1c1#{CZ)iX~MYpu|gMu%l*MKWWd`pRNgMD`ey{kWUgw(%U zrqw}JZtWY=H;5j8{w=$&FVG(U(BdAB&CALH$9VV(D}pF) z?9N#%6$^NH#mMuiTC+f&RgtrXF&$6Z6PY!&g1tOwGS|A9C zR-h4bFUr_}d#bKn#;Lu~vCRmq0n^X0zbwaOsh7~=8Jy+&snA}LKjhBEJA;=U^mWt;{+yjDBMd zDujk^#zkccwEM()4{_pF;E%9j^f~aUt`=T(d3$&mLuLQSsL{LNq*g0zh-Wqw-b2HI zyKyEGQRNgkW=S*QE>@wPOTZTs!pEzaO`dQ!N!IAfcbn+$O!$50d4;SFc_jJlI9Y}& zB#Sy{K6oT^Kj{b{BO{DL8vYpQ+;yj4nPB64Ia4lfv30D3sC!>SZl48~lG&K=qu$Qd z(JlD3%UMKE;U|R0+ju-x2wt|LD3$3Hd5HR0pA+#K-G<$$$nfw}#jBlEIQJYqA!JFV zl=*^ly4RzvAd~*C0mM3axBF^wdXZ-zI6^|NsBtMJ2o18gnO~Qap|-Q7d^Ic1JtKKA z!G`K2l3ABcQ*b=L4$YnF@3Z3gDy>g`YiOHD7w)GOHjn15IhyCMux?+R?H8)j-5;1b z@aE8g72j-CzM^F!@mqIImZTrn{p9{)1Jh;!LoctjP4$4JifXQie6tB6@|BAN{DX>v z$X6FEG;7b45|`DMZ=46qg2U=E?l!`MQesDH3D%ak3XlL|`{Zk^i&GNbunF+aZNii~*q)$7<8ha0LD?1Mvf$YcShF06n6&M72S zUEHfd0fKlyZlQppYn73U4#VQ-Yg1_5g|!PDY7Q4WfsBFyZ2@(vJo2U;X76#uO%vBk z%!s6fQ`0R0^^s_>vp%2C*KmObp1V~p!3mN3Gr1k=gIhKlm z&mT(yY_SU{VUYw|dt41@j58UTgP1%V^qVQQMiNJQT+p?3oocZ{Lsvr6NOFaE;;O+0 zya!?AQF0cqCa?f#gS|A>czP2p4w%c!07XXMXO{&nX^NidjZ&9*7<#fqN6qUss z6df;5y^aMV-d1ReDu?S!c6A2zCtg6r_=2`z%@U9(pLIyDs%}=4IeuUhKj2@1MiNUG zNtp{|L@Xuo-PdW0>Pfi9Zcy>!F}m=wU@K*>K~TPL6ChkNM)u*H6SUfGRH{Qo-xw?~ zRC7cwV;?oN@I&esIBI7^R=PzgXI+J@6l~`<$s<7g8bg-oO-L`Kuxn9+lFfM8X5`32 zLt|6D9@-Q|_{;gK;pSo`lwYrEM}_6d!R{I*prjnbGS=P~NU7IK#f-Cmm@n7|)?r_D zX_ALObq@m7dF3f|wlM+dC*Q(Y@REa_F%`#D&*t%|p*fdV1Fw|Q0>j5f{L5i^VPKrf zTnJ8-<04PNtmBxdvA=q!@D?uNHr|;Ms@LcX_4;i`8j{!{4o}J z>~SZa0%X{Ni*w`Y>-iiV@~GPh2PwVuVm#ItA$xQs&IJ{MKi{Ak)AejTqCUq>2(r?2 z@<7oXJ2_v2GEhHxqRl6F%rfwq3;E!te&Sp~d4wc8&Y$TPlhu`5qL)J4d}&*f>hVoB zo%98^WpwH_M(EV%EfKN?yX4w6lk<4zwH%giwDI?~waQ2x5*a4)Hz*OQ3k$_nV1(Z~ zep!ix-#~@!R9}(-ej;COOMpm*ODmniS#%!N6&R3_ClLouA&YfS`cybc6dY|tb+e8Q z=u59L(8aK>hSn(iiNh3JS9c?W zKZU6?l^xq!Mw82B{zM_qXQeRM?oR3rTN&{|e&{7h}}tPN&}F z4>CvLOr%y}NFOzdb40aA_Ql5*CkHGkezX;hJengP+3_64adtcTkxlxu2gW$RDO&_y zv22q)kh$bu?fMqk9mMx;^LfOdT z5|h59Lhpk#IFSoVp_v>b1$ZHAjqltE0~X0PE2{HE!W*S!UIR`V7!lCazvBv^w=s^|o^GR}g|-j<#3(}|HMCn(hoX)@mj+eNkQD3d z5y~N9rAV8k`BmE2?ZvZRQjap_&yiI5Rae;97!1-^M*6(}mc%66hawxDrj)i=+ip!IG@g>$3tEuk*%qdAe1Iag1js zCpY5yHSu8ZJZ!ap4+NgjWf-Fi~0Idn?tmons;iJN*nUp zzRh4m`VAWlNaKqJ5PYh&9=xg0D;_6R&7N|>%nFzb(O4xv@MXp{V9^dm9c(Skqo%;> zEqcI)d|^AkDaSwkBaef}guP1f8?*Hkho>!HEGKtpM$Isw#uSa}G;IE!zqDFjWus{g z8`+w}wr%zZvuck$;!7%YG{4p=pn?UD=@gig(F7a!R`1cNR{9HuS)j%0f`U5lTO*Z; zmqJ9Li!X8X(T+teqC@^>3LewFFos-qaTLt!6b1z188&Q?0ZUsY;)p60&Th1-aU2W{ za~aLcDtT?oFzuFDExT^WXX9etqlK7vG2t#U?nR$+;~?#%y)5djuLuVi<)D$D9zzT; zod~7Owd0KvE^;^`x)^}iF_UI@mQdk=j;hC zG@tcBogxv{Nh_LaOO2H%L78@s3lX~R=>^m#vWsK{>6BPMdcyG zAkWl}RLJ~FK;dW&@g3%^q>#OmIArRmRAx6<-1k_TY@xYD0uqz879otc-GX#A7!*-(yl_2=fSpZejP@`|n>j|w zyUT^6frS{Ga1uvijs+EKVd^MXD|gO0_7o)e@CGP|k>xLYm=*Q1$CIL>8g#fK>ltPi z#=KZMQ}L!NKpQ^BcaH&}I2F9RQfF{JR9x%x&CUy`o8a00ERvNdQudK`T-(;V1tpHY z)k2^N{08BERJc^cUi>w43v+(FEY$zaWcP{ZznI{ckSAt@G;4VgTGU>%+M_-0vNh5+ zV#`xt!rAhQwkwKNpsy6h5tWMos(ULH!tdJnays5qa=@a}Iq zJBMh2Nj`BJOxt;GuAf#60L~eXgT8a4o2aV-lkVJ@ zD0uI6oj|t2i}%9i;;ryMV`Mb<<14K4d2hvg!$sb54?zj*@dc(AWiREk*V~hpIfLmV zd?DQPGY6X2lhFuciqJ|Q`|tAzTD#$l_d1-;(J<%o9EnzgDNn-8*%b%SU!L&HhgG)v z%@GABaWt{l?Yh@tfq2&_m$_z`mj$p->F|V>3h*7FcL96~vy3jM*5=tI4~UjkNZLaN zh#%g(!)k7hu;s}6cf9Ss87$w8M~L(u0MZ!fj>WvBygoX8-1>rdOkle&EX8d>AQpK~ zXWw0<7)Q@991Yr<%P@H;766ALV(fw5!ut=a^;r8)g_yMS#KQ@mwniv{H)H5x?D%&& z-u1FLb3+M9_j+j9$E7^kY;#NPCssZJ3cb(?yriZ|7~}YIat#+A9akU3g>GYjE8Rxd zz}W|2C{1GPwB>LsFYIAp`2Z8&3I$^=&-KLe9!Q=v}lFEO*4igXs@_UX~9idn(?ui>QbPVD>ZK#be1L zJvnHl^ed8r_T~SPq8cE|_*ce?LQ@0Jj?LE61pZciF}A0oE1w z=*NJ;%Ew6<4$!>L7kCUpB-gT}i;KK>a@0HNU39ZUG`5*-=y$x51OmPB2>)Uvc}}_@ znpuxW^fzoAm%JnHwCdhFKol2|tYn+G z1~T&eG#bMz*svnzEyJDbZtsxXFW?8LE8OA5WcC1%&S=apWt>CI0RsRfU4GViq3>o) zB!SNFr%m$SaAvD{euJKdI2}cwCb+goSX5fkoAGF}!PHB;WuA*U!@OJGd$zhn*u$a( zVH6$TcY`ImrCd`+tX+8%80#8{f!5&i&a;CRO)fhHQH)+b7``Rgf?Z&6=K_9Pg5n03 zq5U>fi&TWmNj3qBJM{3Njt9%@afbh)2ZN!L5TKPTd#|$ZAo{UuJihb95fdHtMoy9t zuaA%nT|uq=yz{kq3KAWAf5$#pPk=mNet=t_8$N4WQ$n4~2S8Go$psKE*y(0TDofY^7;*WkU%z7a5Y0IN*O9i7WGOt)&o5DLHg@A~ zXnd*W0TryH7xu-GWKT}lyo#3fw|Y$4;YqaCU!$w5teA$aV)W{Zya%0lJy}1{%KPg* z^ut>5N14Rh=^!bOhAE(Iek9rv9)ztYN@b&)WETw0u;^+j6jq|e3Sv6C`#Mhxwx%5b zS8)Ad5q@VNjZ?ZOd0;N||1lOZTZOQSFyvJ*;^k(7+40N$J2I|dZ*{bQ=nBR<8ecf0M>br<4u3%r-^W)D_O9}6l5?mbar3$M&11hr-N~KwL#lEZTtNOBDTfyDmao0I}7TOam^Y4X6t~c3vgsl;$wTH2{DIK9J%WM~|NxDIb5I<6h<=huo+F#Z_P1yrsm}OW_>$f zagXr0AFV*;mH{hoF8t03NW{Pf8(;*KAu}r&^3;-Vx68q1l^qD}q#^z>R0!<%9C0yJ z3jARaj%K+ZU`+%E*4XW8BZ30fA;Hv63?VIMOFoXE<#c?dhXTUGcmy_#(-1K$mm0-Q4MwET54;6@!>B`4 zD@s~KY1Yc8TwvI;rUCD48gZYj^2vDk^yv$zm6Be@+GQ-0vBYo+Y>Xy6)L&CWDivD` zCFlbtU&CBWt0afQ!t{b9CW^V}aQ7-eLfUF_Iu0QyG%}ZAA^SmrJDVN}yGz!?xF-swWL&M_bZ~Sb@qA zsl-C~1sPZgF=_a^r=hX&t3zR2E~?@8Zm9bQBfUjz%tzh?Q8C6_&ZklZA;Ap&mesu)_E>4Gx z0_6Sb!Moh;o(++$$c_T?AV5w(F_xiYAnO4Kv?^@AW{NCcL+lAvf@`FCbJJF;UJ&$c z<

    eY%)v=hDK%aTrHmaa*F5?U{+}9!M($&^8`p4wi_vUW=v#4(387|jsb4Q-;BGb z$JN)&y>V9rioui}1H&n9Vws2M$!?w;# zr4G-sz9=HU1PrTVXzRwd!UG=rJ_z`Ja=W=j5%wAh+Ny#P((>3@Yh;7iK^`ORB5Ig) zv{t&L(daRieyCD{ytq+dlR-TybwR4kvP^)lfGCAp&=Rx@mzTUgbvJ;^(Emfk_1##e zxLd(icPn;$HJuOEx%l8$>j!D-T+-dr^k)2KHuH~UI#O1;=bX31nouP4(&<1lzmm4G zt1$e+GRoo$ncofKS9_*QcUk4ANe6d6xjJv0n7(b4QuQSQ|I_i6g05Im*ze^q3di5h z2sY-Wof&>JKtc;LT|k9U9Zv=)+de$mvXa%j<^r6Zrx38xkq#)03MLssu#Hls(yu9# zWGw)^$s0jjq9V&5e+mNnU|AdYS4i08%Kn&TSlub1H?-G0J(h;{Up%(&{a`sN#>9=C zA9Hwdw-w_y45g&<)&id*W3usNoDv924^vK_7PxlR=}V02-2&IPoAuq^m;i%@NFwt9 z|J=L6XyLO+BuMuz*!*wfGQ!2N{o7;MJ zIRc~6x60k~=8EE@1CJMF|5CJ6b^=+RGz~f(->*T&AQ?51h0K#$6AX&fje@RT2=md- zEn`$eC9JL_g?Ah4Eav%OrJ?hjGSse@FdmuB4rc4#C8vZ8?=IuVTC3N@BY7;*+Uh7S z3>D8OB8V1_lj|FpOu`9L^!^n_w0Pz^MHu2HJIuA5nTv3DfMz{_Nq91TPl--^jzw&* z1&cQdhhY)2f-2XkMg+88HlOVXH)+na_13b*)a1psq+h!8B0|oXZk&VRMrz@}zCq6C z+B*3J^jQ=C+PfM|+(f=`g-v$sdelJ}Ag>547tX;M${Tcq$Ir!*;dnz7A)36#ngBYF zJNl$rkb2R3fTlVRM1n6GtTkgOstia^b+AgD3X#}v){Kn(C{vp}DX!v6WjS@!F}hs3 z#Fsf~YXU5!ScOPY3u7~G!ymO(uc1ljzW!o7gvEYDW+V6Oqdpb>gkX*6fpe(}Bbbo-?S>!>8(oG&ESpBqqs$7*31f_~&dCFlIE$wMY|p)b*)}76nzo74bk_u+~`$Zmdh=r~ zcME2;P8vT0YTZCFCl(ON%bfN^0F%Z=R1E~(X*wA`WSiMw`H)|2W?c7`FqqnUbj_dC!=8==T(JPB0FIW4rFn#?HICVCM&n9qg zoKsbs3|=Qm+WMeqK%SQY|1qvw_0*~;wv`4Y#47STOVw4x+XVHK+FoJu$#z)HBS_#e z%ugsPYZDJ~c)mhsxF5L`W#eCE6f`m^Cg`OA--()fpD4c31XNB>Ehpx83r&%B?UaTP zzmworw-r(kY21`#b+|Z=_)jX`wb3xJB2qzqwib_&^Fhm%#B-VZ6?C`i`KBRvPA6nk z0pFR0P`3z>UKvae*-4xZP*5l=0a11~doPVdYk6LUoGMS!Jn~-dGK3Xi(q$%p37T?r zKwsgc&92&Vxj?Aeo7s`c(A-wabeR8mJ4>%aF;*JZMw_Hau+uyA4saFU z#;g2^<($}S1rE)J#e>KKMJc1O026xQ`pQmTtq+&O``Y7yz zRsXq|;f>gHntNC_704Nx$#3sBP*S6=YEG2MI&c@fs5Jn6EJm6dAZ0WQbY68gAxN0jL_NFVmx z9_$?ECL7xPwxnJ)QP14y4#C*4P#~ehdZcdkb0dVKIpIwf!etw7R1_r4jSA%@{$ zXh9f()G++~VTQ8I{Bn#0tL>8541Rdo%Q1bR38py;WRcWXFY^(#C4Q)e-RO_!V|FCtvO6E>u?9hEy;rs7JnBR_4a_NRSaLS$_Z0IuJBd6~mX zm|Q);c3MCbkIQC5;{pQRX%TOYfHv*vD_ubmG$DK00fjN%$F4NHDT*;UxgJmkm9G3=y*p}Rp^g8o-%vd+JvboU$?5C^B1xj z^U=DSXf14Pb5u@U7ur9diVbx|Og_5W=M#GSJgA~2YXSy92Sh+a>sL2xnjF=dFQjV~ z9S<=y4;_vGZZb0bbcoJXuCC6bj2Jg9hO){c&birq`xU*^&M{+1sFN5&AIE?Ycm}};F?;PY!(4i$Cjg2btil6rrhkejvIy8p@AUxUnolIO zu*)vgBOMEXx3!fJrABtG9{{i}sl`^ZhHgw<;-s@BYY{1p+31WOOZM!DTk4e>IUSEW zQU_FVi4oJymFOKRAVLcLc!>%YKMH-dM9MOST{uyrrLvRAFZ0Vx3%aO@x;p0RLCve$ zq!MG2wC}x=en$J$xWWPq4Sd>eCoEX$_4pjoRqU>*Huq|AdJ#7)+>Rr>$vU!b7u>av z(XHj;nVbN&)p|LcOF!QN!{5Px2ud}0D;Wpf)o`#t^J&b$L8e^5{|jMaufhZDCsE-6 zBM&9*oKuM<$aP$APDapf-a`YQQ}v&>4?Xy%4>0vpi34hA0xtVVt`DO!{?+l)z!^;) zlF2z5^*Pj9$I#nd1_roFDY#$9)3%TVegdwC7X`*s)DV2W6Nz7!A{3RThN#RHdyCl_ z>B|$QM*0S|Hi9s;9?;UdRr=_ofdMHVU_>f6DBVT%IuRP$ zP8GU9IG2OO4L@}l+(gie)5G)zJ z%u0Cb5JQt}VpyXZVRLmO@RB7oKy8Oe;vv{@GYf0MP3V2WTto3?xm(I|BYX(OZWFP+ zXKF8nZ*I32YB1EOEn-q@*8@ym5c8#_soJO{<-A|fAx5Sh(w3%Eq&5;mHy2zdR?u3s zX#drGb2%-jDSl_^%CsR5tBd6EyI{>x?YaqS?L$Qy3=!dy`~i5O!jK$3GrT z({r<_w^|yBaqRq-IxmdgAb>Q$01yeAvj2s+7SchA&yCSC*4R=6igr!Cf-IHip~pm;{e*Q z2wTinD(hn@v2BfL8a9>QslxnlXnO@oqMFJH_k|A}Dj9db5DIQCU$v6h1@~0OqW6r{ zKZmlmtlL!oZa83D*Qww;0!`e3EQ#;F*VFbM3D%wF&DKj@afw-dgtI=Qfh#gNf!&&I zH%QJ>O*-1f7uPlj42}^=hqFUM!Wk_kv?~pJDNJf1xw#b>3Ne^1d^3h2sT)W~x}Vlsq|cZAw3aPgKuexdGXvx%&b!L)bb6c7$#$I{@4I6W6F6> z>H<$kpoe{Cst}Z2dnsL@TA)T{cH{nOkAa(gDvRC{u(1<1J1Tflo#WGJ5g`&ZIYpQ| zUQ#%fWm1M@j1ARr1{>Sbl1K()bH=RN25_k|Bi$+Cq_UMR6){=HJQvJXQxCU?;7WQP zH1pG|^DnE-+`%0KP)T@*pR0{n>OA2=AR-!ht&}i9{Ym=I%fX)$8?3D3|Czt4cgW>QofT6BJ5g7xy;ZoSM#f~JhP{# zg1;pT^8Jk^e?ke93ewX!$31`-yecI+w#&u*E`&R|1FSN)r1s`Gc_jjv49jo;5-XwQ zxmb1`*ur?RnoKc1yCs%uzY^#i!aYLBJ2Eau*p&Z^C&MV~3o;_ePN>KjEWqE@Dbu~| zy>87|zG2Qn15{}OfqGkguq8}QIsBr`YqD+4$)T(pZpLsie|vGXZ@?I_`3p@coIkHw z#!HgS+~R$orz3R#@deC=1S%ILdImFr6?!_?#S(gWH1e2CNfQbR^0H$q>=Cv(M|u-d z#;Lqxg@)cw@~6_?lRm!Sj~5S%F^UXJvBEm~2mZ0kF-R2m1Wy57OQvJp^ErVdOQmlV zo^CYOBp0zw<)8;)sJy|p<|4n?f3*3Xj(?TaOQ4CZjnur);$iXx8{z~%9^kP*U)qT z!~Pl#`Ha3=6B#J?4JfpYQca?=DUye-RwzV*WcD}PT_tv-OFN1EYB2Qi5eLjD;V6w+ z!wG(Fb;H!}sH~kYDzjzmBVxNZjgYX`NX)O}#kQaic#b)C$(5@cH9ilObu%17Il9`Q zFx{IGQ?P6c%p$>x5?d#)Dw_6s^Q3=1;=Bu-XjBz1xCY|jsKPSWHL7(~TWd4{=!8jT z*hOP|jF8BHQ@{?<59cj+zDD zOH6BB?MKE*H>6FKDXXZ}mK8j|Z&s15n);GR;*JqXl}hdmxjtN`dBtUMTY7|Sii)OJ zwHSyK18)^7*Dy?wmYKDhEo_=?ThBO)5Q=U!o|hLt*@B{JBdvD`e2l229Izrm@P6RY z15ttR#5iQ}5@IS#X!BlB#9&5SuyAN%KDX|pw)b-(gK6-vxu;QVPUmHEvejkOW|;yH zs7_!>$<*W2>w1b&lL)o}@LO!E_WtxvdHSUW*=!><;Y*6KhD(KCrAEH}>uGG7DV`zx zvfyUtmNZFPj(->r*RM8yZnjIJ()FSEbjG z+u|O%p<)dr^3W7VigcKUpfMMu<6K0x)ZXb_f9TO|ZA-(xlBU@{I4judE$8DA!dc2` z*bYj#hJ;Ak-(8q?XkYG;E&GP-4-HpkqK;&D%Q=O%Q7tf2h7k*f;|az^RWp#}3%ZOM z$ge|n{bD|2uM>g2l2CDv#^&Pepz?K$;AV6sGP+S+l?Vuvt}Xtw7IxB5(^A$q@PysW zQCw|3@=|lPRV!m?CMfGNG?q}NorUY`)9h43rix_q7d?7P&PB-|wjFG~f1Yz`I&0^Y zc2AR8YFjbcj!!8&p>}I`um~}S!AtN>?2J^Js_AA$KuEXGUvDPVCsfD7CE15iKQdH; zPDp5m$a9DxfRcAQJ(!tY@;a|@1CMKdFjj$N{;_58SYj$fO;wE*VoXj&5#WxtY`mx{ z_MDu`D2%0qfU*IuCvD&3nXCy?F$}_|6YG6eN9H!%+r*nII>q78w&A^{tOz_OMJ!dD zgFNMG`t9!KX$Mri3dPYl-&UCh&owtkT&a2}WqQ(yMdB`2}NI4D805qBvR9$hKFINSddda7v&Z0pBn zk3J!|57%$tCoPU11yYn9V!M+3E`l&&AEf22D(^rV#I+=kTp-k(b*T>6hTR282Z1-c z(*bhm%;jCO5{)j=k}TDg?iaYl;wivW7?EASl|m(QIQG*%v49d@y!myQElXJp{bzY* zItrK(m)j_|+^TGdQ#7+vlO63nuS9XMqeqsGbYhMO?^o5qk`l2Ly={4rrP(8b>TOl* zg5^-~wLRtW=~S?U1M#9Am)Qpklx%)=MfoRCs+ViqgWR|~U8w=OM0)CS=Lv~KRG?r` zEXT0ng+^NpOsX884JM{myg9ACSj-o>X0cMAbJxMqJ6BC=D^6HdrtckJ(r~p-__lz4 z4%Y^?xR;p<_HNHaQfVL|!O~bno;jon?$3S(j~e#$=z^(6+)PLfbY*>(Wn}g?OY!JV8FYnG<2L6j zZCHtPJtW6ssD_GnI%Z`UGbLvvKIOYg1>_~FaKsL>F zE}i#4dS~51R4)3t$6?{-_nwMB5^k+XSY$%#YQo072H{?i7TgZvi^WJNfM&oyF z?|<=vj2}!AVo?B9!B2&)b+M^lov}~%)!Z~2XnwNKN@+wNcfQ843ilF@x6&f7+Gp41 zC%3{z`BiPDf#ItTY@U``9G|o& zExJ=m2;3Er%MfMY^An^z4ls3^LaY(DhheMUyA%i6s0i|hJvGd4VwYs{S{Lv^+gmHb zBwV7=t+VM0F0 zEm@uV2`yl|Lz9>fS&G{~AnF}+$WoS_7KQhq(S5{pct31b7}(p#l#luCWLQquYS0BP zpsR(2&>jcjMXFe8q!C`gn;vHq>34 zoLE>#unncRwNusbuLz7Gq!u;c;A7F^;=v`CD=1mp{F>BBt9IW)ko!}UoM)$A1{wS9 zlei&li3H8imOZ7_3&7B2Ou7D3R%3)GMOjr`T~0G9Q73?S=pc$S;0atg!Xfm$f*Z8M z3FN1jlz9~P-+&X-YnE&joeK7h#Hf;bUeZ1bYAVC1jm{%dSUsW~$~Nq6LGHZyM(cKxN`-CZX_>R+6IEK|V0|B- zR$Dq-YcALfsF;k_Bq&F-i3}yy7=>C(d?fbZ`YhgN>H*G!3=34C^=9kw^?1ogV*9dc zKvP+n-F4EhZoyHyB}Os{9j8DzWYqTI|JMu)xr^E@aKBP=yb?=c6}Oe?D-ILX!2ExB zinva6kqMW5jJ8a19))-WddU!S;aU|<+j%T)k_TAv8WEt(`9jaMZ*Zsd%G~FZ2s;Y(pm|j6Ft}=N6Rtt=caH|+@I|kbJ(v5 zudw39i)x9z-+U*|egH{E6MmZLgq+Yt%H~DrmX+1mbvBHZxunb`+r_zMbYHa=&cMu5 zLQFp`#3&5RLnU?k<2-7G*mA|gDjf*HW6J4g3BG|1IF>8&&)*mh^||eEqe(avdbEWZ zY#7+2wUF?eoV`oDsBQ-Hd34PQpAtLLJb2`9SrYXRh(@nFOhb2emdVs1AHPMpG`s;RRTFQ47dU z|2-FVwekap$0Ht`&En zTC1l~moMS{*$`muLn&OqAvd2z+U%08H@UUnE7dv#xvNdJ!1mn3Q<;p*As9FqOH8YY z>^Y4qsA1u*?uFCW>gJC0ePK!Nc_JS3<>pkvsA$bj3QQPHYeGir!H;#)y-akhg9R%;w-6JuM4gaSpSs%xJ3)x2tLtq-n>{ zY*sr2BAQKXuC7p+N**LJRY)jqbqX$zy!DvkL3(g`*>#w^M0B17`|22 zpWmXpIH4NJhcv=e3Wsv?YWhK@64cXhG-~9nu#mMx#zsKo%xQul%1FbO&Pc5JCv1~S zq*6)rQSOyp@~v29SEw?*uNqCKn5nQUnF?*pP}`rjEEiw_*aktSVlQpgRYFdrhg!Q* ze)&7$AQXjtVA0Wqq0G258|tgE7YXP zcKfsoHL(kwNZI>-XoD{zK6QZwSyV)Y!p~oMimOEKQnF3}NZ>1{5u)saZFIK!)$?e; zl316^B1~OSyK=(T?Kz{%jWiy!?H?705r`S}!4-4As|OdIPps>%E%&eqihxK#*WGyv zd2*!VS{O0S%$AkNmev}-wIDdm|Dk|ThKD4?XHuwlSpq!j+)Ysqn=`YdLDW)3D@*_b zqucSDfAvZ!5T$7l8fr_0T9o~j^yb1@e3gCi#h2@w$#R5Zv-QK5Kdk1n;bQUSYB~IJ zI=Rg0JO2?qeJCmM3;YQBro0Ocb_LwhRe2Sfh$#tMzE{IHSL@~d)$$f?gqHaK*50zt z_X=+y3n}M{Y7WeD>Mdb@`z$<7qZC;gJ=-Lf+k=fMd2J=4r9*MRvgi&`wMymErRXTc zl7(Y)h_(T?jXMKM1%~t#gQJEwRQPD>&f79OO6n#FF6Dk@t^SOfJ>k9Wqpq%y5NBbR z<@^j3%%bugN*-1k6yLk1b8(2scAiSN5fNRhjT+u8|2HkeD#MY10NW!0hA?VmK$8~m4OQoG^4*pY@a8Vs)P`izlV6{)6%X;r zqy2`%yW5kza>D4+p>m>>lU3DnTEh$5_C$1tB5SB+d~WIa-Czh8)&x015|tibbGqsl zj)02z$~Ihpz3Liw<&4@hK&s4Vva9JF{&UkJd$oQ*zFD7G{G~4y-vn5^eEZ z04?=s!+TV{q{?(>;2BM?ExEd!LuH{pjM9=HcAlyHo3HA!3yo~v#xFSWI*o_C-P$$$ zXPfT`C!ynH1|}g*)>4JaU?#if3ajQ;TiP&f1?H#z0xf3|$6UZt`Ex^m1p^1J|9)}$B7IPg1n`oy2Wa1~uO%(opGY z*wUrlfR}~z)a2OxeXwSn+;OK9OT_l2vLLGv#Qx#;a^kj~1F7K%DN=IIle`bRX}IpJ z);$bGqD#o4<<3N;Z{ts0uw@HZX%3Og4+)OVkEtjt!0)DOgs1t$0_@+&Haa_JgY^wY zv-0FOEKy-g+c2JWijGjow(RIhyLtSlI^RzCS8}zwHUa@k6)*IO{VcI`tQNB&y3f5{ zV1W@-bDwH)C7CTq?ypEN+jllaA)I=lgE3;RST%M3>1rb+X8L*v@iW3LK(Mag>LYHu zYEruaSP5mRLzYv)7+4jkW%`v=Jxn^JqMZ=D2IOO!I@`yW>OL%gD&4LN)m6!>OJ%~z zE7_E=cA0+}i?W~nOi7ouF8?qKv7+c91T$eipeI50ZajX-dNYvHin8_JB3=L4-oZ+m zXJ_x=81BtRn)vu}V0LADAN`!W#y+7t3Tqgbkf{o?Q-1sdWpJ`Q7kq=+fF4>=O{mCx z3}P!KUd=aDB!qIf`^j*Ay&NoVCPUy9wIvuV$C^wO>W!?8v8`Hhv*Ud! z!ZjSmB`K@svPS^ubW9EjePK;$k^xZkjnP8PC@oKp>f?E@in=b*tNs08f&58$G&H(z zlM?(hko+((1!W{PI|}lT1Ev{8eqvh0fkNMxzN_*U4G|H;itFPAq>y1h05shZdQNLL zm2#KnFA*k^nkE}z^l>Esq~=tL5HOsB|9Oqpt>YzdhocKOBa?rSd^`3qz8_+w?F23O65`M7+%$EBX+EcE2)BcG=pweh zDfM_vzKgj-oobTWxJ74(Oe;9GYqkbRNuU2%y(A!k)M^YjumV*1P+4F2%8H>axRd$@ z8)Ah`z!6+B17cC{6B`TL-A5Y?t^^`|btmtkLKFXSX;5=TL=jPlwBb5k^@-zBm7F8g z>l)tVC%Tks3@dBFlNkI-^%Wd8r*M~X$OtJGtSoN!i1?^RHaE6;E9Mbo%OK;G+0Xfy zJ4n}%XZ(~LZF+_ScT>1sT^k2{L)1`5Mr}Wc-JETxQx24RX7<3$s860@4KJpM0*v{! zbh0!oeGAexXBH8437*oGl%X&UJdj7Kx%hu9YFy9I{}I|JbgsifQhvUIkxxyW?+Yj#InH)YDOUk+!VWedx=_jZAihSJ%=u6 zc|gf9Q&X#@FQMFM@|+0-^w9$n#yr6A7hHY{kHM{}%<&-D5*x7hkfX(cZB$VWV$eV~ zO6Ue}l%eC+X;x;bq9uDP{Ma+rrg+{X3!6@%ap%csY$9Rkx(xLO#UOzaQn~qp`tD?7 z;&r4uk*fr*Hh@cJQ8>YZr-@d_HViJXtR0U-Nms#Rgl9d&v&xF2&wW*WG~TkJ7T6F< z`xZn$oPCqb!u6RPzbL|gqu{hz!0Gdg-xtJ7y}VHex#)e)j1sHP^z8E99z)2~nc7qG zm19g;Gn0V5W2{_^D`oI~Zk4x0hkt+wF(&qEaxc>sz1OEUV31Nu{#pBUu?2bmWAVwL z!hpQ6Y37)$F?h{228`q0P>BfcsnSykLaVh4`}%OcnXMDp4anA44$SBKlwgy2G`TfS=SVMOz&s#yLyfpJECh>6jzwu14eNGT*xJDIFp3)G-V5>lBDU%QN$~(9%wTnGsS`7KKyLWYh z7MHQ+>^f{dF7FT{@f!q-5K1~9%&x~jpUl>O^cnuAP+s73$FDfNgdU<9hKkMKAJ4BR zL#sN}QC=KQj_y2`Y3QyEawnT?fLGn|Oa(aw@z}PD+gJ+mkG+Om)lLL1M${GOs|uL>FfNsUyTv4jBv{DLb)aG^2$!?tBgX9;{!z0z~`%Xtv?xmQ;2j{2QN zr^~egQK`To44OvJGJ&g~f&p4LeM4}1@veqIl&E)W?Mj3!9Yq=>PX!=FZhb)@QAg~T<~MfP0e8b zD0T{;87-zga8AJjip)I5h1z*&v~s+LwWY}3u}jZrGD&>FE>jOMwv8rwx4EaRS(B%^ zfo5%jc}}ygF)G6Is@X}9vIE`EADZ$p2uOP?gpQ28+YptEx05|1J#T!$Do{2n7hn=2jVX`;|uzZjs$0@k~zXC-HKOHc9QZ@6do62Z6 z8@SiN6{3^vG7%lqakL+NB+SFg&OX!u)3krGMu%u>6=W20({vtQqt}iBZ*q( za~1j!23)C9hY?2=jb&T<*#_^GJ%?_1pY(-hwXtS6iC2>72c(1pRML`U&Qd4NI zEakZn($!$P8W*I03Ly>aZ>#60?dg&l%%CxMZ+omOaj6$ux#;$isb1 zV4`_ivsu$eo01~teixB2lPi$S6G(=_dK?OCPL5Ws`1<(t<-u{DuQr!?kIT7l|w#c{;uVO028{$>-yV z+6p?-bu`Y_h;|#lz=RgqqAaOWk>d*^1e+N(sT+?ZR1iR*lC^LFS~-5@&b9nzP*+T& zsC-S+5nl!f95wtF4u-jj?3Gv19K#!$Vr>r!h(NagBXH!l4k-4Vhdw!uoG=MmJI|6K z|G8ag1&WV!Ven!sp0(H1U2V$dIin4vuH!+rT9BU@tv*y?9$JkMAbkyQwpshZO_eBI z9XbN{Zsn1HO_J7`u_(yrf_YTAxRevR#r9f8VdASNFtCDiGPoTZ@zRJ*x_W^2coyW} zX}=N!!=MPap=cw?wuZ_AT~dTF3n$UFT1dFG_+r89{9BzJzfO!q>k9u_*8osCnRa7&OOK!MedsbqybJdZb zn5OAmP0$u9=V0+i@epCNztd9gI-9D}_vmW5eSbpKyBvq8#UQ_!TMLap(lRa3b`87L zKD9JB$7Oq!g*qdO#{goRZLwGNdFO*GIL0!}pV$nh$K%;GO4ihxOd)MaD97Jxf`Gn} zM76#qoKUOrLk#ecnjnp-3>QRcOMaBp!X=_xhcc-Hb2#HUBo|)sLQ}hV0TUO^=2je= z3L@1tenD`)k4t3a5ClUfAHt`ObvU+B4YW_k8_J~_Z7MUIET}|6=Oz&Sp_vCmf=!Vu zuXr2JBm~K*OaEB$n>9m=>rLQjP!e3cCkh~GCs{}FAe={6qm7mFNJ_cY#tTMAzO5gK zramA!V}(lo?UZtlu-iG=ChKF+Wmc$*)265htF%Em&10O45z z4-0`mIBir}LQ#H_5`;#YdZ^S%QzH{wh1%F-nO}}U593&+RC4JcklXR?<(MX-kUy&= z3KD>lOydopOMCaLNx-a+u4hg9cb1?Iq1-^fsZpCWHcrxa_$g1UShx{ z4bY+jkTXeoWnU4BAjcRkWT*3N!S94fYvA3EBsh5%RRv?TRhs714_wkgOoJB&X3Yzu zEWnXL%;(Sss_HUGb$?kT=45T!Vx<~<<)i^U{;NOHF_+ZZEeIV@L02hu zdgfa8Ri%xW+w7HPK*7=|Utr+jG_vv~9Q_8KTn#o;nUWSV$T%x7t}!KKCjLT9qmCR> z<9?Bh{8tAv+Hk$cY3iuK6fdY=st-xyRfVg@`XOad;^RpO$>Ij>3`k~$Hz zcLfgXqoWlq;nOxt#pGrO)x^{J?D{kQpNg!Z8W8v$OEe$qBdTVpUx4~HP(gvh{8gTP zun3>d7Cb}s(7!@1 zx9N0F+3qa-8`86Nor$yTc`2=z(;Xm+O|DSHn^&#FhX-l*6!SW%$+RV6=d>e)t zIx7ma&*bhgejv$YX1YFc2&%WjKkNfHDn>&Cz*by-@L}nNJ)e}% z8ka}Q;EQzSRO7)N@JE_va9K!8L{9r?)%gPm6zE7D zGzl8cC_5aqNYOhn#sj;G$yf#~0C{>=w1l|L(D=yUtt(}bTG_u^F$Y_Jd@vhH{H9Qd z?9i5M=S1-{4CZPLlJXfab3CVHPA)Qvq>!i1k5xraJCN&qu4&9Ww^WoQ6_v|gDhJD{ zG=AG#&2bL&5=NfJ>HEaB>O(LUe2Qg{TV6s}P>)hejjR76&n7Dk*)?(5#kCLTe)clr zRH^c~$qU0x$Yg5QYb$czbs9&>4k$l^4FEc#xMCLFtW(SK^&GVwd}~8_@2Ym=VZKL_ zw_?yW)fxSEp=~zfrwK!aD`wCpFx7O&4h+aGv;o;-W4b8MYh-cOc+uKQvc*0*TZqbk znuVVd;Bq_k8I$Xv*z}M!(+AtG;gD?tVGI_ksChM>t_MU5H4ksKOYO{tJvKimlL1t- zj+UF`&{EAK+infdv@V|FC`@0j38vS)Jj$s&-0|454m$FkXQ{QDxR>cW7FLq;z|(;k z1fe)A^V!7cMol2`x66IKyyBj;uA0?pvn2tLewN4p2e3FiO(sH_nb177LKdx8QyQ_Z z1VpT#Hp#^GE;pO{U8Ke`i&V*02@xB`vC0lBz*3t(S-nBJ$7D7>SS|+-+4U{8q|Y|1 zaepx$qV>-a4ZKE}=5jNkQD_;AdjMuK`ff>9Co*$6O`Nre&I>4}MCrdCFV+ZbFj;X`v=&Vhp~{jzB|z+u6SvtPB*6<^qFo=gZ0U z&H4>OY_Pww4?Yad!N6W0-ei;r+<&;eoMS9qUpgfTu>3pD(0CAgmqXq!pGs=!eN>+O zuvx9;i4C5>ILHSYZiWCqp8|c3&QZOEIcMyI>_4G$>^`|2)|VTeY9&j2a)gWz0o2Zu z(Q>|^v3qCJ!Ek)T^ZZuQn5E`C_CnGKS2Vls$0zF04N$}9X6=83w~F-6YJqVOx_ zO_&$)nVX)DmKg17J1;;koAJe*hhdxX*j-N7%>nT2LxP&!1H2RK?9X9I!aa)D6G0!1 z$0Itgem>j)4RZoB+*Ne1hYL^NPevHXIicTXnOTn6Lw-I64+7R)O$V6UYVmM4xU4(6 z{DG#P&vfj$;8I9-PZ;`9fKyH|Ji3Su2t9$t+yUHQe8-HEe7$Qlz5~(D*30?y5G{gH z+%R4~aqEdt7I)~>*I_EVuKk%jRai!dnR-bl@;KxbFlPZc^Tm~6h-0c_1?}?`7o{y5 ziult%wl9r6u~SJUb}iod?!etXxSWoEb@1jG*tGyZzMM=a>j#f0JKpu3G|UZ4N)k&7 zdLb`uNK%Fy5K20}o*h~~u=02*#^P*NH+*i{YQ9;ExaqHJWCtNJ65ScMBiPqg_|coQ ztJ}3f`+iP`tKS)2?fFD-rS01UwS?ptq3CU^@%SB@$nwjkfZVZEhv|EhC$~@9tU=YX zq=UB*&+f~!9eM_&8Y2x*sK-=P?5SW2ZcmG})w{{!y`w}QRb%gTf&xku_U-YkJ#eKf z$`ZrmHtgrfoD{@b786?V1zl0gpm9bJv3Te9U*Kn#$zM3NLlCTR5BR5oqwoulyNKTN z!1)t&Sah>dssK!=VY5mhHVeEGv_J{v9;U#^zJ zFQ=1BZWqUY%$e~nc{DYDG=eFn0%kehH|Evwf|FQQuSJ0`A{P;mXU&8)Wo7^tN&(XN zSX&lixk!7bBC2kNaSZdB&^BKX9eX5^VgUBvDwa&1E% z2?yeent4FABz-<#qy8<*>)pZv07jMs_d*TV6pj1NSMOCPqf|ipyurwpCE5fa9Py6r zo52dPNa8mP;9+$GeH5>vxuHUQ!KJR{kk=BkOJKcoU{`mDys~Tsi^C@wSXi8 zJ{!{lkSvUAEWRX9+*6>N7*&X zgS;ZSCQdz%s0o~qQ^>s=OcytUYy-Y^F$al|0auU2+w0dVl{}BjS${5K&d6uaLbXfj z6jTcUMwO1>NCRL;j=b9TU@f7?N~E#Ge5PUTn-2gksonVJcCca>RK1Eu*z!Iri+Hj= z^(nGovG?UHguRjRQC5vY)(3dh6Yx{?^Z*H;QG-HC0?;FWxw%3yDxrk9C4dbv0B8DCDPBlm?a z!k^t8^ne#H5p@}_$Nb|}_a3d%S5m;->AXCLT6D`l;ZLOR!EUe;`VsE6bxxU9uf~^~>pt4e!0m}kpZ8X0^VQ`3j@eSSSpB9y9xR79hCMB> zhc{=-`LK^?Z&tKmvIvTcy}2DN@O<(Z=Zod!4vtw~cK-cNC;H;MY<2YQ9~K~U>FGnccD z^%ANjfduk&cEnDm)g&J;m$P~HQf~TN^T~|i074a=63>l1_No6^_+5J^{rtK48(Q+- zo!yC>qI9wi9nat<#p1Bf;f7FR0KU0`*$!FK*IbJ7-452EoAd98 zaylKbLj22o36GP70E~y5C7L9x&8}agJ3Gkzg8>*&@s7p}L0aL`^TB&YU~UMhI|1d; zbKwuZhc$w^i3cNgWkgn0ja&orD8pD4<}Z)$Psig$M(d|mvoKv}Z(zDiR;ZhwjiC5) zTfqz1faF!f3gs@di3F2S9CCOFc8Hfw=>4jpes(vXjDETu?Tvp;3L=$=Ti#0JN9InmKPy!>z>Bjhv{3rNc84(l{^T1b`@asd=Wh7qz?9h7( zK3?=DT}^K(?+Q{VdN~6l3CU{On2o`BA*NYzkkxzdup0w@$d9xyIkj&i3)FWhDt2}+ zmJdQ?UtmT1YQw?g$0#Sk+?U&5tf;($xT zADf_l-8;5Bn3iNYHZRx@Mk^lrfZ-^o$;0^>Yo-*ZxLwkUbXi0Q*;#j`tmO54OmaloW> zfuqpLUStBsgV}uca68|u9G7H-BgY$HgJe|jUQs4P-9P>IqVS6v1ekFE@5kYCxVw{G z9xmsr)mwC9!QNNsIW!_YbB@qmO2w!?TqtV9*;;U!&hEjAn!#WVq{`z?a1f{hK9ZF; zY}HW9rJtX}?4UR-+=mG7KVuH6!7e*?-;#q(2(r4HCWq-4xA=jc290-FiKg%&o z$CIBHhzAsYo6iU{siWW}y|usLfh=S&8Sb6o_XRt743>>Kz*2sruAU7L#|Khy*2{M~ zQNrcqj!r-oT|*8R<0UfJ0so>Dgc6V1Sc{+_{lFfrSaLxj!w_u^xW^??HHMLENhE(v z+_{sn;%aB_VEF3|4%woLZbC+xmsf6)>jFsXVDesz!2_k#_`fsD=rU7LVDy+Z^+Xw0aJ4K#ojESBM`>unrJL zwb~WGx>luhTyoEGNnPk~1oo`+yqV0zJf~xas3iGB!hjW<_KLQXM)D3ZT7b$Ov{6Nk?v;=)-M6qoohs8_{u9AR_pA&a_Uf|DreSgLF0%_~y;N);luTfhi+K^33|VL@f6C#WQb z<7`_RMvQ|rd+m{{9ijPr(I4E6A<=|O(P_bTc?YGq8ti-Ip27l$tjf#H9wAdQ^ODc| zHXq{e8Cbzcy*o8eCbun)VnJ%FbJ)O^S*?xRW_S&;nE-(v78$=r3n?@H#Jw@_4eutP zS^^Sn=VH$8a@-$b8If1-7zIe(a)}o!M^%e`UvVF=#>Xlri&YpclKAX9vdY*dQ2_y- zeV60Zq}^-7`TWlR@Wzz>jy4e}jDC_$KlGlKriLWHkkQJ^5dy&b2erDoG zCXK?hZ;wfbf($RB1rm0}Eoye+kT-jm58;40AG0fl_28>1lA{(w(TC%h7&~L21xwd5 zNS)#0Xy%!sqB>+ik#b0E!Azmok4FVXRT=kIP$qqe;w&BK%Cx)e+X0nwGzt>&&0vOkIQ)lf(H{^g1@L^>6J4*h!r8ojPW?#M@i1XVV z-YX&z1bC)Y7LKt!~11Wy}YH4vNB$;DD@RuR{ZLe zkPNOa(J7$Fad|?&E&T%=R=YKMkKh*wS5O_jz>f872~#i<-Eb_0H265e>*>C*931Gq zLKI+zve6#o=OUR8R!E4giED^j56x%uA?vVdGV99VAWAJ7u{9 zGzA)9_y<>4UkzV_a%lC$?R(i1zV7j%{}@vGb8?r7=!ly7z_M zm*s9wa;d}{-y)E!>kJ*`v{Q-=Le#JpAu~cElvjGQbxZQ`#uw`W1s^H$;fXu%M=%+1 z3&Y`ioV68MLN$Rt2NaDJ6mT`XCg8>RE|&PE2^`Te#gD(Oaz!@GmaQA>w)@WqIC-!&;mQjXZRm>-EPVB zNcxz`yG^X6Jz_;-DmA~H8QQ3Mmm0+H6t0tZjkOrQDhv1x33Se+`Nw8`fLk#Jw?*#8NQ9KbbktgWsb~@mS!pVEa zR~)%I>XyL}J?kuXUR3KCPH_)?vnOVYdO6x{`oTZvC|5*G08j+I&P@4K| z0?ENaQV<%k!Z~}LAuSqh?U{H|2{pND(AWbMoV|tgpFSOzs?bg%&WI&_-@&EBR+*&;hieKGHOT)UX0Q z(VBn~c@b$fvo|ZkY|6Yry1;Ti7}3l}*76eKI6_bby>+G<+8dMhTP2O17!7kyKzu_) zj>R-N9$x_k#_z>^2Ix2?=QWx_5;V4yh&IdD^ns16Qn6lv+IfN_VlOCjFY(G#s>FyK zIH8{+O9cf1XloZlXj9?KtWwbd*lXMzcvVx(7a7h%`F1tUI2#m;O(2lI*J zDSe5XOIoR;y4lHKHt)mZgygL28E5XmQ*=G!vrJp#Kc&7_&_;P?1}Df8XUq{wgDJ+@ zSdv7hI;ABvItg<`>d&TR2j$P~szyW}3O7Y##I9?i;&?lPpT^MV5n3jIPYS>Q~fgLiCH)0AquHX4Ppl%ceOQh+QS3 zR-t>NB<(nX)@0vghU*g}pD%6|8^tG`Ap`gpF^;j#OhZQnSo0$q(IKC9?5ABXRmLTG z$FM_T;wW_o$#<3jidn*>O%f#yZ_qHH63EZZW&mc1WFd=(4@mfK^j>S{v(V;%26LQT z$^eBLtWHlR4pB&#z^}a<~E=wcm3p7!cyjM44qzDz=RTpA0s-ni^K^fwP8W~4u zi!mH5=<=bop$Lge>eK_G*4w03+g91(dl#@z$_apnZum}SwEMoqIGmM4?WP&l690-& zghdi3U?XOQh0+RpyChZ}$U)${IY`9Qvej=0 ziifvi-R5Z7iD;0Rbx;Ksb3~6;7vuXiHN}FD$+ZhJC1_v2c{`ijlXQ?hWBuQrAJ4Dp zFH&Ge#XUPa_kVdgK5#tS|N9)j58sjY*?H>z&g$b2@Da+JF6OVO zLPx7>cb@2#xDzFqVhTP)Q=ss2oVF>s{OkZAFuUXdv84cdsj+XQT$kh8Y z)i26(@J9z8#t3_vyb$Xps0DAs-}I@YOkV|9a&3$Oy8AN&umJGv3NgkhipljdA1w4b zAW0dJ5828C1#U6l4LHxnOWKrqcDCkIx}6MHh^}x{5P&!5OZR>_G&n$l76%l$25OB( z2&3Pl1b&ol&<%|cB|H-gxd4ASnVtV~i#|J$mCH3B2j#f)hw*f_8bnUV6u7Wk0LkGP&FaT(>^K5+!blsqf#AfQA5!{boc*RioN0YnT`DiqO zN9jA5A9UN>evj+0zPzNKeqRDUgWJy$?OFr*z9jz#%Eac=FDJYE&%XS^T!RKK*TdoG zdtW^JVwYOE;LDdt3#5PK+s+q5ya9cFP?z}i$=lBkKjUj*XlQUFzubS8U%Wl(=5M-hPS1apzv=bg99$f}&ifY!$H(R&=(o|?rO$^)2MC2y z=FHOj>3N1mhF~$%Y%_#hr*f^yJ)TQdxKs}|fvw|SblyF9mA^TC)jRr?zeemKhvI!r zwISDQ$*4rDo-tIO&HMQhIKG*VFL7x2gI#pL-_6es4!`NX%KN>OuaCPq%2`ja?~C4> z16@7NUZ8@S3pT6l?caCLPxJ0CFS;kM^6z>Vuk(YGS9lxNj9pBpNH~Tg^nRUp+#BEG zjV~|U=AXEa9rtm^ePp=dAOJ%`csdh&eCj?vb043(kNfW93p%-+BBA%Uw>UWS3z*=P zB0w-|EnwvNv|(xwmanHP-Z6W--p=0RET~qO_7v{ubq@#9&5wGgXYPlygY%2t!Et_c zeDHOC-u>F3#O?iXwe+rf+kb74C(F${K=~wwEu7z+ehUQaq~GIZ(@EQc$WUL;rGWIBoh^chpXhNkYyU7#pH7bp(UXGH?~tXM#w_cOSp zF%pMBvO>2rtlGf%JE94BFlZbnZGW+OTe>&$@0tDCBOyHQ$4(t*^-J0$7*Bo$-4FCg zFgZB|3LNxLPuy;I6!)>v9dGA5iv9F=MgQB))VtH$`i{5t9dGO4&a%514pl#`;YA!Q zuju5Z%PQs~-DW7)hF@H+xkq9eXhOa$rW-vSR+M*EkbXJD=rxYoT#pP4eDY9FL1i8> z84t(iTI^@n+w*S6tmX=32@p^VDNvC6hz2Q3WimuY@xmnewvZ3hpDZQbHcZK%kKU7n zQ+xo;osX{}>sU?5z~k?+UO7DCZ>L8@zlYxt+QWssLXPLiQRo46BFMk(9$uWD=dZel z;0DMCx}FSqitY+&$p-Bp^U*;KKJ4{Fel%0iISk8JP`U^2^WV5<_h0vpE;__lHw)@` z8)K`)$oprM{So>B=JA@P$(8>uj1?K2G?q1Y8xd7F^J;75BPfxx@pucx| z($C1(kmKkr?jI5IAHF#wcAvjIKR7vj%|9NTL+;`4zdU^X_5Mq_&+t~e60s?BOyh#D z_hvbNFQRU}nT^Y$PQ;UNQDS4wr*ul#VnYUz%0loP}4QGMjRdt8Cnk5 z=mN)$QaRc9+1I@siknG0pm`)2Mx!kdU&SCOimCXR-G6<04gsJ4av!5x`(3*~&Tt|W z7G;QEW-&xz>5D@`nxmuhZuhK=%4T7FoXT+oK|vWPm6CPy&l^@SsF~s9>cKy1CT&v{PyJh^!OM+K0od%i(cIc-K55>N-VkUlEVp7axW`F-6^ zNX+PU=6%Az;iyNKKjPJ@{iNM}$y86EPY zwfHh={R5uq$YpyCWz@md3OA;%#u z7QT*jh66nP`YlL?G+8Lf-*(OFpc2czaTHeO(&t_8G)R-8lWIghQJR8g-4Bk_9uX76-47_#EDzka7p!uh3L5 zD70{7y+G-Fg%@1BJqP2Sp`A3;ShGMZRn-Gpc4seq<8c=nrMZ-USES`H&$C&wvuTglbNb4VVshDGU_G`wd+h0Elx>Erk1rue-0_9(Ub3Ux6(d zQI?;bcVG1cz3m;eQxa=0ttZ*oR)R0&McdFaQOkz$OvN*T^Zo1d>>eiF6)5Er2A-i7 z;mXi+VZpw$x;QD=i{<>9J%?BKE9%aBmyK^2;pK&ND556{nLvG7j@@>;XT1b5(8=$D zoX|~her3%%pUVP~oh@kraCFeWAjll`eo3SUU{lx$>}oP&qQG;Fs%@F38oGKAy;awo z(xDU3V6F>t9Jy_&hRAs5{e8!6&xjW>Ie~8OW+hs>*+*bilIib073}+H0=MA+K@9T1 zus$m6wX-t+Zp?cCAe^y)OoWusxlwByz!2Cdc>>rBFThAfT5k(0HCfB@aT0`_=!hDNq4_-iPIf|XpmbK}uC zgAy{nA5xJq)FY%|K^ZfPQ10t75`8ws2w6RuGVr2Nfm&hnLjDV!H8ub-FCRQar^9=Da(2)=KY(uP(CQardBW2q znm2o(h({R47EdSM;I*yKtYm!p`*c(HMtgdnL!9{81s5QS6Zhw-R5D;@Ihw+FZs6Nq=8)QRl+&uS=4OI z<8!oSNctykOC)eEes$J8?)LklGeafMiCLSc!(Qb@s!d6Ihma+Ain)S12sO)dF}1a>bSH!yCeRhfZ{K{tlZH(@GrUv{-V3!FS-r> z;sFl695S$2L5KHu#;OYGYGp0s^1+BGvsGonSgh#!OrB5%!9!H(6q4QFWN7$vt?ZYr zTrzPDdV*yi!vVe-T+3)AbPy$pZhuE^lZWmCIogNiWBkQKchcIv_3Tgf3D3D(p>+#e zUMhYNPkGE=!$070;Dc{}N#1v7?Z7KY5~FuQM$5@}J@`t=MM;L60ZoB2$Vx!cnbqiN zY?fY1&CG5u;pr5a;tM=x2nIi}T`(o2C&0cG2+&{nAeAo3%RPUelY`4#0!r1_6jo#| zxP;D!Bz7!J&q7+OT6A^X0Nc+GzJ6=G2JY|1gU%AoE=+Ri=G7OD(+(ba&lc%+7+0SGCD?hVi`^8F{faK!*~pmY#|>1z6m3s^lC zcK7ZsBm3dpfMpDs4!v$Qouf=s^bH){*y0o*vg64hxbV;Ozx5WrzT@7T-i3QSm>6kk z$Ub8Y6tSvnT}X*s_vcslin zm^N5NIf63`eleKrhg}4#PEYc~gSTJ5hVJE<0p4xDlB`3bKC9CaP>W5@jECcYFeF*k zMC0l8jr27Zz+RF!nqAtWH@t#D1n-=I%j#yDjivXRT+XgmOVZG+;Zt(w;`v*}cSsF- zLfDa@1ZWLguqzieulId77gNYMKw%;h&qb~VjA%Bd$jr5hn;|pCb0Ge36V~=-ioY`Ff4>FZ5$So9WQ}b;9>%VGC=KtgyPKp`RntS55jUq@#7$! zs20X2hC~t~8Y)+2K_iwZ3?qwy?EK^q3^kD^)0_ZctTT2_o8uxI%Y0OKgrd(8h5A4X zERlc>M=+f(5lmh_AacfWSvagIQjFh#xGUqqyCI`(fbMh|{z%}W))=Teg`zXeM$^S4 zpHW2UK@4w-GK;?e+=hQ$+>kT2JH3LA!2v3i0F6;CD?(?L;mPnF$Q$?ua&{8MG1H=V z+VC|CU(ga-YFx@C@>o&g=+ax7CuMJdROLoe;0Eeqaig_Mksv*P@$QX-(vxGJIY7X?+Fu>$+&VWEFf9%O%LI(o?p5kX&r}XqwX_#hJ`+ zAOwW^2{{nmDi#fc%>ZLF6Tf?$WH5jM>4i8ZS(xnZ^D9T&PIJ9=g)*m`pSF4T|J~qn&pkFotf3qt1)Yo$1s+X zeqMN?p-5$jIy~3y1Xb>G%#h zHfPD0&OUCHU~*EHj_{GI;&OZof<^zZ-i z2Xyb|5Al)zZ-oE7#eYA^&i(@b{3H2@|KGpnv`We>~TFXi2o5-^+e` z_K$D_y^uctL;U;Cu~+_#7s+;hd#3jh7*6ruA7sD%XCHo~PjB(xPqK6Rhc3ns|L&jt zh%fwqbiok+;R5>Sf5h#$;9q?Bkv{!X{D&XtA9E*u;M?#&wU5>v$O{QVe<4rD>j^~v zb7?Vj$KS<&atD3-59J$POP>fH_znB|2_SNf|M2b4|LjNl^uORg0R2yXqz`mV_~|eI z>__@Upu@Mn|7SnaCv#MP@*{otiL8j8h)+HFhPTnD|46=Jwe;yflW(|^KDnLHr~d~3 z@w@3@{!MI)ztD$$*(26SpL+TeefWF!r~d?>{!9DqFYt-5NVcZA#2n@KN`Ok9whkHo1X z;4l6a3x3(+Pk*Ej^sv89==Rt4{)Tr8e$`vfamC-!TlA0rH%{=c<8b)l-{8Zq^vnN% z5C4;X`B!k?-{5<(Aon1A`M>bjKLBv}0q6Mecl3+Cf=*Q6g3H~};ENsx-%HRZ2nXAA z_hKXNUVL%);)}c2+wXs2-urvm;!kxg1bu_qI8?$)hld{K;Ws@%AOpVX{r{f1AIJLd z*xUJw-pyb1X8z*eOO%CkCIa|l{D+TvsdxHH9t;WnJpc<`@kjXY_p!Af=>t6sr~fZL z(CNEdJZQKR^#1tY1Kxz$K8R?E21FphkZ^UA01AH7js3^w4(v9!H}Ds|p1=5)|L6FE z9n;hQPyC0EdZ`BoeK&7ie-Ge5SNyN|kKsTc=wX1vKVvw!Tf8khwD$h^_W?d4Lmv*r z_UQS-8wi2_3I3CB{~VvHcnY0>Ti0hqe2vuj z-eV}g{oa4-_rX(_0#ds3U&EULM_r8vQuo{%;yx2cN&~@AYp7SNt15O6*D>;cf7LxA$X%`g?#g zbOqfHH2F(L6L*!jeibkf`bag>v&7dcpcP^ z5xk*xcQk>Js|<<^Dv*8^kz62%!U&{|7e;614Hp4*MiYahsA!Ojf})A>f*_I*FQASl z0*a2K|L3=N?K*Wj34-IdzHhC6)+(N7@7jCUu3dHNocFxl4XavDto=k0n_d&E?!nK} zkUVSXQkYwA(u^&i<@V$is83uQrm4} zBOUNA=LsCzoe6gnIBa|*fk!y+fb++@O~iY+bdOfk<1lcT(b+Qv^IZ#^;9B5h*8)pj z`%S@jT?^de+K7L)#P_Q0-giRZlqZ$#u~2C&vQ$Po;L*+#_^3TRMexzaM>IMAccA2h zvJRZ=Jb|-~cN4hK^&RjnSr49&^%3udl7~$EOU!#4`P=QIY!`A9Xt=wWl!NCPCSE{Vaim>3+F4ZuZiFwlb>tEK^g z?ARQ$e>O5HlAjHCo5+xd9_+oniPt28`I0b){F4gQhdym8mO_5aFF6X#RiZNF-Sfy$Utw0$}y}e z(Jb(a#(aKlKHtid&F7csn6pwU1hHSDCdyK?6jgbek(FEYx5|UXbJc9J5Q4=Gvhk?O z)6BP0E|V8y@1`n84cdE&UMAw3By2{Ti7zPoNTpd&=8DDDKGz6QP4NB2UlWY})&#M@ zzufv7t1ACk-eMIAo}JUKC$>hqwQ5}G;5z3C+-$s?z&l*u0q@Cr@Hbf>WAr^pi>78T ze1!eZ6F9|qH-XP_eFr==>%qgaKH?2Z9?Cj!rt<`zWW1Ze#jY<0`f|zd$vW^{=LtN| zcsGF`aDDMxE%}11121x(z^jaR6ZlovcfdQd9{gF>NB-L+Z_hgLF6RlH_+aYPP2hgU zM>^nhvmSh2)8kXtOHj$PvBbP-2{Ht z^&Rm0Sr6Wv^$~BgcH`Xy z-s}1fxc}Z>2k?=`tA`!Q2W1^N*?9t|8}BCYrLOOQZ_Ik|xU7%-PLO&IJ zp1`w>cN4hM^&RkztdE?wN&Z9b2mk0ifiHiTj|~nPZ^m9I`S`2@-|RerCmGk-B7D2+ z%Nem;@@ZKIu5g~f3ypUZc#-Ri-x|qZ$U5+g&J*}0UXEBb=Z8 zLVaF^+sppP81E+VK-U*PxxC1r;GbMy{8Z?^acb;O zu-|zC_c7j0;3U@KSZ3B2BTH-R^}zW8mByfN#*P0kbeTjSjX-s}3} z$A!uZVXLRG-+2P}H?Dmxe5C7(-+_`3$~the^8`NEcsGI1bA9m}kUTx>z!}aHc%<=e z0_V8C_$`#YDC@wZohR_^#=8kT#r4H+x#ZKb4qV|pftMQZCh#)X7r!-<*Jd5K&UpgA zXS|!hn_OS~HcQ@;b>LR#3EV?goD*O&-kcK?Bu~sbaFX)`KHGRVfxPQut#s_zzX37c z>Y)Q?I8Wf)jCT`witF`X|F>L>m(ciuE1W0r)5g0A{7={Gzy5E%*i~5vUhO=A-#6Y( zAaA+qJU2_;l6Bx#=LyuyBH8MTUg0?7&HN@vo|tvuBq>V88POKG}FTflqOL@tY!fYSw|%oG0*b`(=*B8Ilk}t?Q@FM34yux@lfuD1I@mnwXs;mRAcAmg* z8Sf@=lk1D$X31N!4&3TIfqUe4Iba&|E@y(|iCG6ua-P6v8`u3v_#D@l@dhMM&pL31 z^8_AgT<5NEj_ZrxLdlD=4m{d<0(pJMx`U^z@NFkjJHkl_N)W%a-P7)*?XaG0v~U@+1I=;o0@gt zH0KGNZCqb~2#;`m8E>KFMOg??F{gIvvcz@*Yl8WC1$rG~z~fwB{7#U3V%C9+ zohR^g6S&d!#qYk} z-Tf~6fxjQ)*Qa+{zA@BZGK{lHaY{8mf8AnU-3oG0*e#=8mpyz9$&>m^^6b>P*` z6L^#HZUVpW`r@})@|LUvw>nSYuZ?#Tc$e#oU!UH!jmz)dz<%cmJkWSIfd{$1_)U>K zHS54>&J*}DK|r3FN&a=XL%5F+Y~~Emz-ZZrcG@I8Wee<2tW} z7r4HRw?^{XtOM6MPvG^&^|@GhgX@dm2FV+<4&3BCfp;3$c`f{z>xxSm6V(_LT28K|r34Eh*oiD=UTwnZ7kbGj+ zfs36d@GRr{ydpf?^~G=FDu5}RJ;QHdX zLGs3|12;KO;5Osk1a5bI@#}l2_O+UQ&Jp%IPvC*ZwXcN-xxV;Kkvui)z-i7CIB2|^ zz#-QczlD+)WgU35^8_w8-c8_Xt}lKoC68tuxXO6~FEidv;746w{MJZbn|0ti=L!6> z@ooaIc75^NAbDffft#Es@Q=pz{!I8M*B8IO396@>)l=B-Jb_O$-c8`sU0?jBNS>N? z;56q6oNrw3X@v`1U;GwIUX*p<(asZil5xF16E1dr@mntWw5$VHI8Wevjdv5c%Js!> zwd4!34!p>D0@oYwCh#iP7rzaXH)b8U$$0{AH{MO)R@WE5ZIZWV9e9`X1U_}5pM&7j zj91TflBZ@JIL&zihm7mHE#a{1%XkYVFUmUbXy*xBZe06Qc$({r-%81&SqH9ip1=!@ z>;10qBG(tcHImn69k|YU0>5lr`%`$e>x%d9Q6L_$3Jr4>eyS|J!Me@|F1E)Dp;ERmwy|8eG>xx}FDyzpq(7rzrEpO|&vV&@4w-MF3yg)3ZN{8maH%{p+E^8{XKT$<;a1ldzipDYXB~K#^JF+F zub;5rc(s0#CuSWu$$0{wZoHeoDXuT$Ay3UZaGLW3&Ni;kN5UgqU;GwIUX*p<(asZi zj&Z#Y5uTg%;CaqVjFpl{vkqM4Jb_ml?N*}UhO=A-!iVx^}mlzu)Z_GMylk)`LXzHWs5#`V3bu;aYMm>_v#)`63pC-B9_y9qor>%qgEml%VRhq4Zw z={$jF81E+Vommf_>Ab{PDS0&Oz*Wu@c#ZLH0%cg5-%=2TpRHz*iXWCh+jA2Vd#D#2A!3ly%@t=L!5LJ%J3B1O*>LI)~ z>%r@smlzu)Z_GMylk)^Vcz>@4xR>#f1n%v;#F!v?V%C9^oG0)V#%nuJml!K0k7gaX%6S66X1trguV+1Yqw^ADgXE1_2X1nn zzz07v*F(6Man(b(xAPKXg5-%=2TpRHz+vOv1kTKQ@HNg$jD?aHWgU35^8}t_T=!Ms zxmgdM=e)#NDS0&Oz*Wu@c%^aOSA}29dhkomON{lBugW^`YUc^uW?Y{)h1;_p{I&BE zqwjC@SxL=4D+&9ZC-89N`mRj)%B%-p<-EiglsuGm;7sQUJlA+Pf#+pCxYBuvfjpXZ z;40?{{EG2z0>7H|;PuW+j17`EW*xZ6c>?!1!1o83jE^L6Pv<4Z1j!S#4xHpXfiE%M zP2fwj9(J%J3H*lfZUVoV_235Q zB?j`wtOGYWPv9Pp%JmQ?nPv<4Z1j!S#4xHpXfdj_%u17dM>%kW}FEIus4`m%V z(|H1qF|P0Pgs*pf@jF5CiCG6OcAmi1#`PXectO^K7dkI7)<|BPb>KSZ3B1R6H-W#& zdhoZ-ON_op>l#tBYed-ZJb}+PuJ4J2&&hi5xz0x&`@`+goE_R;4_ZaUc@Eq3{zm<|lvkqM4Jb@oE zuG$GNaeeVyBYADsf$N+naQB0J-r#uS)#qKw6SEGS=J<9k{}I z0xvS&P2k0@FMewzugyAeo$~}>>JyqmxiTwnZw1GhR) z;2x8G?|}R;EOqS5|0YPDn04SJ=LtO6xZZUMC%eA*O_4k`>%eKw6ZkUY`mRU#a@QBX zLCHf|2hMb!z@^6Zotto(>x1JS*RZhPc>xo8;|T2j1m8fscN??=$c*#+!Y1pyY$H4xH>ffpd*_6FATHWxR!w7iArI zwDSa>Yg}~^p6B}Fw^H(G)`6>>C-5@k`c6vtQP&s0HImn69k|YU0>5WmKl>`Y$@Rr= zv*ayV2X1wqz=u2`Uw^`f8gJ?{LGr|`11C98;1uJ!{)AIqU&b4dJU#2c8O{@Uq;dVM zk#LUdi{C=Yi?R+p+Ia#`Gp^?=;pwg~ek&!9W*xZ7c>+IbT;G`rKj!-4w?^{XtOM6M zPvG^&^^R0{gX@dm2FV+<4&3BCfxk7bpXnCf>-yr?_e5Q{YIfZU`<*9nf8+X@Zs8+c zU;GY~d{EYblbt7Uz_>oo2&cQg_zg-P$~thS^8}t~yqmz2TwnZ_OFk{@z!lCD_|L}m zGjzfaxxVN*}UhO=A_ZZjb9pP_WU;O%>qLR#2~29hzF(2*c&jB}V7ieGc#(7aS<(r6x-B@-_(%fzJ!$3xzQ}l$ zpX8z356*O+z$M1J30&^_4tP=4gO_DJ_=&6sKbiGWhc%MdW*xZBx&7Ypeh>1z!TpVo zB=A7z9q`%4o4f}kPtX0}4Ce{F$+(`2g#L4gBldHMo86`Z{vrSTN#xh3pP3k!e{KTg zXH8Ty`h$~v(AuG7DV z?ArH`XShuQ-<|Ej_Ze^UUM=~8+z(#lJc0KbS6zj_%X+Xce`g0i!gv$!K*hHoDg5q>f2!S&8N;2(^46Zk)_Pv9S&m*M-qsky0=FDu4ifC4X!UU-5_~m)`2%UPvC7Ed}n}n7$50?hi`N}_-f-L z9q^goa(yI4?B80v(Y?Uu$X7e&cEN9*K3-na)T9lk-^*}6_3CewbjFWAzh&v43DD1ceM2>kv`LFY)8vpqm&d!)dNadCgW7^DE zu1xkZPJtb!%IGJmS(PBCs%hf^IhBDjT{9w?U#gh^xyLdX0!YU6q(cTKkV780`QtzA z6d!AdnI7mtqJZq7C2ABkHo|UwQ(FZl^_}iT95r>q?rblSSL}rtk1hOvZxKj17yAg? zPe1oM9#L=NBYIUGk0_Ps$@dd#)nP$6)GGcFJ&14HQM-Z`c%cEdj|ynG!-#Y+-~nnn z1OV0$b^N1VkkDzJ#+r@mn-!{+P4bC-N0!PU#cqd3Rp4X&tODU^ zLU@`Gt|o-<{U}%jp%{OrMx24IrOg-b{aMK@Hvq$hY)#1jV%>M@e@SmJ6dSy#-hrDP0Muazw=m~u>*GZ$VDAH~H z&6)M3WOD^HU(Kw--;L1HE8~-8Rp;d8W8*AYMOXN zu4>SXtQtgrs|HxCRp`A@eR=)!DQB=x@~&i<@xdPd!5j7By`=s`6bg1Lo7Z&>LlSu})Aj z6RlVy9dMHK1gKYO&YLz-r3&hz;5(HPBCF@k_PVKutY% zl}clwz&jnfTH=A;uB#nMU7#G8pB8mNZN8u`adQb_{t-3RkJx=)%E+p!YBRE?68){o zVsVd}RTV<8IGP)es(?++D&=H(v0Lk-c|h`X)9I)Z&TyW<{_ptJ0gg95(gAPI`Y6mz zvi-4|Ha>ufZG6bzs7Vj32>r)J{xgIxid>^6BY@bgt7c5_Uy&Cd4){2`>&{!5!%GNscKq&h9rEo z6X^BSwG*PhwG*&7Sj~0aVr-jv^tZ}@#o;!XCIul_`2(RHwkx)p#KQzRK0WEVcf=w=L^Imbe}`-Sj6d>wQb)kFE#$Z?ef>zHI!| z1A4EOaHg6@16HXi){-7%_wQGR-;r>OnhYb;L1j8qO)B6>HOm8Xtn1$@xYQ}|F{879 z&%2f+$xkuJYqFZ?0u6NZj)VQ9eC#rVoMZupfwMvnS!wz~;CalJ;}|mCMi~Ych92?; z(+>jg2|Z+$>4$+&g&uOf=?8%yg&y*A*8_W76*Vs8VK${<;JKlP448fpSP**1>s=3w zh8}W>>4$+YhaPgh>w$-=WHw*O!>xY9z#*ZB%ryNVa9rpiC%PUuC-ji_xgOZv_v%3J zks^8HHlGxCwH+2|CC2Q5{=T;^>s3o%?zh_a3te>@pxV`ivO{Ir zD-U#Se-~>D;e^y$4fY^^t?QgA*anE{*$5>6|F|IWzX@>>VevpuPi|qBEBCAa(?=jPvcV$bY8p$+<$>~n z92I&WLrgIubn^|)N{C8swEzULIUS;LGI-Ju(4xvR!ngpx0M;@@36GsN>?pWT6fL}xOZc|pf+Dn-)Nf; z#F+2v6`|VSR8tuua#ay}ePrbp{jG{%agCZ)1VXTQFVJ{Y6=^14DW8&`2kQ3%PuEUn z)AGgV?uxoVt^N{}{#|_z!q3Wu<3rUN|jjs7g33R*qNVdZ)22|teYP@p*XE;yb!MC8-uQCZI8`qyP5l(U50iW^%w~0+h zyu}t{bT9D3YI=$XE-*R-e9q|L;}u|$TJ@NJvwHTGN~Ip`(RXJEe-vRf>xtnoA0HMF zd=(DQFN7X)qw9ejaiB-Ujv~q)*wcd#^dLKobZe8?{5rAu7ABiF=L_a{s_D8pQ^WkH z4L|%hIdXM1(d(J&YKs2W)r7^z)$D455G>A@#-qA$R>|Ps!Xrx6C^gWv>ZKN~fvATU zVOOa%78-4*L*J7Zq*~HY)hB+RhGMxYGsL`l4|Ks|ihJe|+9C^j1j$Riz}6_QZ*$^> zxmE+?t!kn%$7+q5P%2FHw@Qb_O=`AA5Q6D{g_SDvYJr;aSITjD57x)s6zQg_ae0E% zoG0+_ZuLtKe5Ub{1P(awfL}7+e3^Ql{63_%N8d?$cs_XQ0SF&e)6cp*OSUgl6Mc=~ zbxxzUZ<5iIOf?I@*ses#J6sQ37<$NOTn~^)>&iV@@y=A+QxEm}={sH)B9f0DwY`Gs0G^l8nC-Yc5kdGZ_6iy!0ZO|$+t!gMl@ zOA!H^-KDMe3objW70x@W6&c@GtqxLuF8G2TL71j(ay)Zsn|+PB4?l$Q`D*%cqcE+0 z{ICh7eI5O+eT~Jt)a?K21|e9#{up;W0NcHLWE5Z*+RRfYGY; zrFXuXUF{G|?P?EW>xsF(TD`Nwd`D$f6=p_o?XY{BkNaq!rB?ks+H#4fsZl;~h4Tcy z_%<&ec&PD_1P(gyfNwP3l4C{C2Z6seIvaSJ zno{d~y6{D=28gE-ny|B@8b4ClyL^1$*)r7aVs2Q%!}J98ooM|d9dNPp1m0>~f7o95 z!>k8yb6$Qx^fJk7)szfylhJY}(0i>K&y_a{@z(t|ji2(gUSzRZx-Duf0Jzn80&m!i zUjN%2;RfR)9q{2>T;G@fO_1&mHO+2ty!yPq`DyJ3sc(NZWeI%M=&TzBSXPTdpeLyD z?agzA18Ul?uN5qC+L!;;mM>73TMix}>Xw6H`8uiAtJyKbm}F`~q-sK6{)hQLs_AsW z_!g&q`CkN6&Jjv90#!2!!|{E;e%w2D(=&?VFmTA>5^@Z{(5Ii^N!2PsDQ5z?_s(X*@DI>%b`x=S#vy!-z)k|NKTQ= zgrDp9S0fj2lJf+<(s(z4ugZFG(0K>^tnubdCEl>Wr$f9N;SF3GCdCzMH^3jE{7{DOnFr%la5& zt^BT4v)_GzY%pPHRR?l=2!z>F&CDQ=H$i3*hy>_RvPE}e4xv5YIeoXV?CTql-E_0n z$7|sX=L!5*C^7fN1aI{iwQ@L1;w{FZV3RLZdr ztEQ~JEBLw7$m(MfuT`tF+9r9s>Gb~y7vAMOf#?3nYXzQfe53=u@~5tkxT~f64>gT? zwcu+`Zxw7))0Od0%l`hy`rm7*$prWxHPcW1iGDFi&4fRSOjT?XBKUwpywM`g0!G#J zIJtUR54OfT07mu>*k^65S-^TV?|>bqF?9O?u2#z)VmErnX2H)($FIbmq>SVNkeqwK zUg#YF74eQpyPYdjY=&!(v2*|9H3?>@TFmc-y9wcKLO7ccW8>RZ(@}=!N;T0itqwSP zKcHrxk)pr#feDLunuR{uLkMOc4I1<6Gyh5IJtfQ|oo}e@x2Rd*2dj5qv(V>+7l^PD z*3D(G!81nag6IT=rJFjfIlJVzQcj*n_Z2txqx(DQ~Ei%X(BIFOsAPrDc^A zDU8{T1n_llhpP4_yOB#lTL`#QO^Y?qgY2)WNDusjnj)=P)`Oj79kYRtshI=hI@bgF z5*p}1xQyI8E-2laVs$;i`ydN_7-waMZ#vV9f(txbl-f%3Oa1|eAaxyZ()+E2}CS1JEaCW~cM z?gL{_0B&2RhwSVGh-==AxPZyUgs4Iles1qLg<&qTnA@v-=k_Y!x#h^i+|Q#S61YoE zA4}tKtv;dB>v8k(?1!&}NCS%>tJ#SRAy|Bo77?v8Jeqq)^;&K}O^?{S^__HT82+0g z5uT$;%fc=aWkSRit0Z zj62C;Y7d;LCciTU|7>*jC4zl^<`(}Z{CMV{6@Df2?+gDs^QiYl%ItbI9elvA)wIxh z+Jqfvqt61!%R69&9qfmuA)s!IcB$Z$Lc%TPiStJbh zAS{fGfFHPipa&skGlI-06NlxJYIxX5Y6?(IN*%GpHfF4`tiC4WTty`b`S$6uO=F%)rA}LwQDu{TNf@C&#+8&8A1rA z`_5{6xM^Ifi}W$FctW^DO0Uzxuy-x^I@SD(wg5Vx?-aQ^gvM7rhbzcyEKqffH?xIH84I- zO-m4_)oL`MG_~k&O%00$YIcl52v#078<%Q&O%W^Qd*#NJU!SAxYbxrdnQQaLR9>kS zAsW4}E&h4&SdrEYvFO?ey5~X&rs<|?xaw})Y^zH74Fx4| zeT)8p!dzmZ^xZ?GQz_Rh`NO&WhnMW!8_M0SjoGl}p@DuRo~tVJV$Xt;Ai-;eylvo-WRjqg$Q+>WZx;G^uQrO@&{ zs%%Vr|3^*BOWNO66J;0<@u;r1=D@3zx8$%PCRp!m70L=ehO{+xgy==O}VOp(SGqTn$`de#< z#W<^xRsuq>_yM5Cqgtls{!}Tq$&2dNYd56Oi_|pJ=7_13YnC0OUaDMW{EDnT zSgxB;)rSJ*9H+*+X0YG6{Y}S?alO_T?(TYM`L`>-zm)}F2Y^pD-u$i0DUzpV9XQQ- z0*^GVzga1q zvRaK#cUpfr>(7$-9#ahh+2ym#BILPJen3sz<_pWluj;_B zQtR*2AOC_}r?z|FTTj*31<*~=M}9Yj5Ye#shMK-e*z3crVE#8@!nnSPYD^xSV3M`l{=J zuc>*62|f5N-UZyQW-gF@GUsU9W_25UVX(-^$rE5YDPUewiRNy%ZNyfTdh<1pY zXjoSlQH*6*di1w0dn~4^*^vz)*q&Y$K7uw*)kS`QY#tv@kyMn%!v8|q{YK4%#$1O_ zm^1Bp5rc^{QOhDMm?7y!;qV}xki+hk*-pE6zEu+=6KabiWu?ln8hfcj zn*)o_so6G$5O+L3d#Ife5nFrwK0PAYLvt?dlx8;irIavWQ7%!dmf&28A84zVE6izX zoSWbZ=Lwv=kDrg=V~vk=z`L_PM!Hb8m#g`Pd{_^@xyTcG@NH_!1h`wx4nbngP?H`w zOf4>B_$==N=Bb$rIgOhn=8QEW^bjVn{f@q&n6Af$8 zFpRNmb)&zv)L8txnyn^;VAZ+VI8~SY2W4|XIK@~|8Vmmh^`2-JIw~9U>fB`7H$@C4 z&O}>#iW!n#6b=v42{{J7GTZ6Gm~Yj@$b{PBdau_!^}S0?MT%-y^`e&{Z4S}jsuvcg znuY2CAy{>8HcnN&nrc+aEpjB&`rIT*M(`cM;EXqMLsFvW5QjKq`w&@vkyBg;vc$f18KJ&l) zLjm|KCmVrW-YUjJR*ey?Su$UEZ&pVn4X*Ei z+kfS`MtP2r?sPSM0C?Lk^%+A=G}9rjYQodw|P9T$kbNn^MK zTc)Pk0vD7H*hSs}TwXe0TfGAyT@Mv0wevVc{mpPY_xM!K-1cxdm=N}@-HrL@)U^9C zeuJ85m{#Xq6G~e;`deEXi@9pHYas;FyVg{hSBKim)H@XBG2c(9pjW6_;9EuR2w{>; zA8qCuzwxbZ6H#;Xy-221*Myy>+n6h<##};UUZp!tiM&8f?^XczfC{O1E+Wj_geInX znwS!X{>Nh&i+u(KsJ;->Uk?dfln2=_-kGZ&3s#60E^dR|4Q-GaZX_n5P zz0h9KWH`58)49E;i?#>nQ)?_eRb2xz%zHt%w^+c?>d7xueaG+AvTu@}Ak?@QgZ<7E_??HL*ULEJ zca4v9z-K(d^${A|C#m`Kz_C5}(jpJ`wu|p0KYcRVs|R_63n%xci3~>%WOnrYTI3=7 zW*^9YE}YzZfylh*St#=M5FjgDIJpP;O7whF!m51|gV#LOGUA);LxB=}WS?KAd7K>g?s!$wm=BYNe7usrEB-39lD9A%rH7 zdLj^hz5r6<=Vg{a@kqE#hYi)54!+mexJnn_X=W|~-%CS?!rQEw;?pfqHO0N8p!D@6 zL&+IF){>>dIb`g~DCC&XGqRr!m7{v$WI}kDP@BKNSC`#$rka*CQm$4v_Lfy3`dj6| z;vH%>PYA($b?tW2I8{?`R;W_`ha8!ET@R9E1fTB{%iaz-rW$h0HsqLaJI=tEI0L0* z?l;hD$7#;#WBy9{wBt+}lh2ef`Aiv;PxIFTPE|e}XL`m1C>5Wm;|PF9iQq9Uc$DT{ z@;hHGNjHA{Ae%7)J5=s#^#9tBLk!Yr#tx;u zc=-4j#eNwk1~DPV(6{L}7UBK2e8>SMdQt2&_;-{(N4qBaQjk+!503!nx)S)pG6-k7 z^xQc()iDQ2N9s7vMLBjj(6InHJ){OWz;($093#>KoYxqGEQ{2!Dx&oiV*+t2QujW} zfn0T0I=LQ6phw2K5XkPv%oP<~&u^tMtD(?c!;#TBV3)<*!c9`~3(XG27RY=FNGb zwOCM&VH4ggE%P=3-z!3Z_|2rOQomFWR@2gO2b$xQ5N|a)L;xN^t5u3ym0dnfa$2$| zDi*I+v$cQ_*H$UQwN`1@<`MAUbyMrnOrl@EGNG6TQ3Xt3a$yRTD2iCjTzU=c-k&Uy0x!7@Lou7fJUGGb`DxmUyX} zXZNtk4$Ddn{j{301FlrlhB&nc@qi`OFeO!Nzo1s9dY$AO)v8qcw&@eTntlEi_B&7D z*6sez8N9=|{-ZIAen!pTxxj8v)5ZaQUOHgEwvIty^MTIA6`mex1k*e;tuw z$Ee8)_~+6AyH3rJyA`;ffuXEYOn`+xth{eqOdt? zvI5?qW{E=Hb)hp41 zoAHjS$2+PX@2Gmbqw4XFs>eI3-bqK*<2667%Xm*y)1F~Nu2&OfJ96b$JE=K7RPg9; z?IbKdt!DcILNM(ld#BoXR0VIgMy2fJvFlYJ!!>F;7Pc+z!9L?T11yhs#3pp9I^*P2 z9b}SXiQF;{AeUm1T#B9IQfy4l={&BE#cEth)wq(XaV1sbN~*?{RE;aC8dp+`J0p*) z-88ohYeI}_LJVp`jA=p)X+n%>LJVj^Jsx)Gzz@?~wOHqQ? zHYJ}|LaRvgN@Novun7^@ga~Uw9d(fx7UNsgRLwB03fqL*)v1TY1~n@zgkUP{aw}|v zY@OE4VOte;pL~C<3rmW*uy-#lvsZy6RfUxl^Y^}(=5g}pxkYoocPWIY7Jb@`B@!hJ zPYj|!J~%fojev69ymTk=?q1q>mgmiCyt{3@f3xvsHRH{SwDoinLx{!z}jm z6DxV(S$$55?CpY#JX=>M7OzpWZ2}=~+%56g<*hU-cb^f$sGB3P$6})T32uI(v6*c3 zBQ+F{{a3Bfg%Us3R$=iYHSIlp{n~!)Z9m&a9@l3Nt;K@kU_#iNP@8|p#vCU4DmB$S zOslIk#$tOKVxPvD60ZUVbm4=#7!0WUJH`3Ns|eF86aUdCA?d2QB#pLU+W zuN&_s@J81czYUT%W*zt)=L!5Tp zgLgRZfc?Mq^dsK2(tTU48e)P>CYqUk*+MwUc>)(1?FH|rvuwf{&J%cnasBV_X3P>pQ14(vP{Wfqf_7}H8X*bSru)GM8>jX zEkc-Zy|i~k55zrZN6L7fuBKBCzb`t)>l;Rg80{{n;nNJDhnC2ubqr#$PR))%2yx?n z6A@d_EcfZL(}6>|({Q(FJhHCOPzuyjtLpY%i63gK`u3BBn!TVB_B&7DA;!B29B_RH z++%<2y9rFjM>^nJvp!OtC)?xIRBYf0);;>-XBN}Z7mqd7lb*hl?5yhG@FBJSzS+&6 zPm6%Ilig;y+2~iO>PUH{PBl{LUm%AQ)bzz((IFFvFZ;kV)bzx1w%~nEBRak3m}(Y4 zuWi!0f2H*g0^VQU?1)U*YEc^1U_^QMj#mF7)o0Z5MGW1jri+-$GhtEYJKZV3dg!WX zer+v+*ah7fmkYYp&k*0WA!ap0%!-m$6Tt9BHv~w_YEpTT&8sZ2S-=sNm|n6%$g+xd zt=t*bF6Rhg!eKHz);#r?198uCZR2@^nzkE$k5v=J>lH?a7;UlBsB|-cuIA+ zCok(kJZ`CN1k+GgmfkXI^eVc(Nl^b+)pVi&1TuY$daD$hO{s$dvQCu-hJh7TNgrX{STZd{dm4g51-cF9xtPZgja-Wl)8vQ zIYm}e)$9>oIL&zie`>s&z&l*u0hd0iz4>NJcea}UEK-N8B7Agd`rI%=eWa}4v~!Q> z8sjm4M~{VnGp_G-YSs5Rr^t#-ssf@q(^Rto?=43-y_?mz&AjCRU59G${}MjRra9V~ zBRnSam_Xwknj%9Cmg2Qj?Z3EI!yE0Nofkh+0H=1<*(j2M~duZGPErnUY!)V(|3GT|Ms0KFF>ICc7*;0t8;#-mUaK*D zqC*Vl6CH}~U*&A{7YA;;QGanDG734e3OO-z;Ccl7{xgR5gYSRP}lLEtTFt*ejzW37J}AgJE+o!TSRde;L)HGRaLE5(?5X`?C+ zBP5sS_h&B)Y%f#WO^|$K5xSvz2&b>Pyz);w-gi6_t zch2@|Th!f{{jGP$Ld!DNxpKnrFT929B-*}tSnak2JqG43WWp^XT#qK;dAOPh5YCh8 zE=ib2si{r`xyC6WHX9ux0H<;FI=>lBr*@>)x`AMEg_>hSVU~?*8B8`t@*;7 zOMUKBdNxp1=%-11R$KKHc|Kc>OYBskpQO#hSlu6^t^BRtN2>8W46bsX!0U{66S%?k z9dOUz`8!DPLB>Zq;F{mJ-%S$xGirKZ1-@i-)>j0Nz8CE*;I(R6w=XRFFOfYIMS6lg z)9H5we^4`%S89Nx)MNrMp6Tn!_<-dSzD=Y3#0DM&JjLc+;;(j*%wL+pZ*x3;7K_<2 zDVBqHd)tf#fk&!g0_K!n9FzD%6QWavIGhmJYZF&)<%jJnx4**37J{YGb#WiLvq(%Y zR!P>eMyO+vs!Nd>P4T#Zuf9HwRuS+z)>e5o@LpSGnLsF3742~)gq|KFgto-|-a;8( zXr2-v?pYp?@O-M}F^u1Dys&s3qo#9!(f-3}tV}b2j)cgjbtFV6yXqrC>j-FBMBsnd z=)TFTC&Y(o@aL%606QHGizk?c9#SFCP}92){j!BVk|N-*o6zCoCnrmo3ANIBzZ59z z!)8}Ybh65Ij+*K_*n6K+CT%VA;UM#}jwq5=DQ1Ap16Wk{#F1(|yMkOpiuMGJ@N64# zN)Kcpsi_-#PV^iBg~BmPO8^olht>qXk|Wb`ykhKhG7%i3IwEDzArvu03E>&d!s+>z zQQ2*E7GIa|w<9B&QpvIL-)!**8`HOTPL|o(X8P9hFxHyTE?1;phM2@s4UpGT{|{J& z&Fi2DF zMG!f+t}ZODRkIxoA#i+RYx2H77emzHK0}7lBa|tX;3A2N*j1&=ENnPl)|$;o2VCbo zfs_9mUws`be4_D@4mfW&?$yl~ZMVqw$AVL{`%`ql-mRue14MC;$b~rl zCC+2Tb{Tb`n88j_)A|ndAZMv*2;i+6#`KUSHuNyCH1t=Ad^3cbMSiH}Nx?|b{3AoM zBQG}@l?f4CA`T&ToYVhu7MnGoWdZrMkN$4`DQ2;`f3WekE$!VYw)g*FsNa!*?CZkG zz2}L{iyp`^(Q~)R2mY9YLwagDkAN?@ez5mrk=->d3k=!Eg_C=)7g=nAD&MX}tF9EL zsq5{M_R%ORlhTI0$R$k)_R7)+JEHW#ma17EXNX)H0_1WRPVPZ&jvmOwakhqoJ;<|M z80bN!M-SxC=s8Ygr3otJ2Sh#{0_4jsoZP!n6FxwP5=GX(zF$)QexrARx`#>{nZnL zv!A%OED*bdU?wyRDRUMPf9q-1VW)vK-zJcRCXfUI9ch6iK>k7P!TQOzCF9@PXTKRo z^!@C3kj0}#o*TjoMdpMM6Zlr1K>fV(*E_j(dRB2-aE0qaTfMZ$^~?q95*HyChfB;h zpT@F`lq-K-nw7t#%3o6DFDd+glE>G^KBBmr5Z)$)vkA2?=bLsqC&VFYqH!Qp`#;VP zTk+^OAwpp>Rn7K4gkakL@3#HlxM&%}rP;QXa!_vUx_SjkF_&0pSyduQ?Q^buvJoej zUzSk;KM^B||8B~6WC^Vz9a$oq5P?mIxF$qc6Y8jY=vJW;lHgtayKN~4OXE`2usIwm<)Lz88S284VlM1gTZNSrlT^7R#VlQlX;%K5TmF(N ze@T_Ur0{?K|8o4we?x10N!9q0s_`Yo_;WP=JA9ddPpN4c&tD4RPOpUmD3R&edfcd` z2mEN3J>&(pPQw5PfZ0b5CPWG*LJq^};#j<+3_bBzZjnN*KS$CvxB^i|qq z%2STC)x*y5QU$TUfg1(k2##FIppm+r+Q2nozr`{s+u?899v4i!Kx>2u==#d zeb(>b($_KHtGKEfOY;m{o?+t6GCIV@z*CR?;e%m$LWzyjI=`@Zf|{LQ5aL$9`;L>R zsKY8!Y&`?iW8GJzuzP8a$VnFg^&U$gotN7 zu@OwDw!+Ews6$NaiHZF&Uu4?uNA;RO5P&R8r{vvr0L*M6uv!dXuwv1{|NI7pfEv{&D-;zO27 z-MU2MIam7l#30(bh$zCCgCL?=k*j!PKHfw`Gpk~r+>4m4ReDuE^0Z2G%K>1*7FFbT zRu%Q&`)W1ofp~Idl?XG(SBcquTTQD(h&$D^Gz8!QxLTzsgDp&xT=ig%#r0~o77*gv zDn+=~D(%`lR_R4Ki+Yvfv#gfjfgYHYhy5bg7$Krrk*jzomjl>(;s`dOI)qQQML55r7Xc)hc1= zAF;JCG2zy=gvFcGY%L(fwN;96tyS8!dDQR^Ig5IgxGgsie_^>)+DmQQl{vmc;^}HC z$Pbp*c0~y}$DC#X?>A%ppd`eDmDLPWzTUw0eQNb@qxU3VqE`JB6A^NvtD9%H_0s;- z3`?R{O1wr*iC$h3#jYqJH>zO;E z@RA{nBK$Sl$-Jtlx5=(vShZgIJWKnlyyuB%7ixqrsHq&YdzJa@>Lq}B#+qxo7(ZAc zMI&-mgeH`V5dEzpV9_Ukze+?17H@(ZkE$X+l83(=sg%!^7qhC%u~66YA~n7c1&?-~ zz_dI1ZUQG5AL)R*@9p}S=^e8DgPOJu@U%Vcuvx!kp~!{@XW@GyII4QdusZ`@B@7;8P`Mjy9edqke8?t4?M}I_=6>oPpHuWeknR26oQV&?WKaN z!Osw$mH8)xU&=hn!y{86yrI>d+!!>zhV6$vYzN?k_&pdm5 z4u-Ko+%mR`B=xmt#%@`!=6$f!wRhYP#!m9S*h((7D-yfO{o3_mL$PhV5B39>lnd;q zr4L3meS~&h*`)b*gh_)5B8|i2YXiOgRw&H*IujGsNVP2Sh;y+Z^77U z`f{MXh>y|#^Jt2iI)LY>>ErULJ^o)v?{+<~GW1^;+3b4Yj?lAtr~2}1E5q_uUbD2f zf#$mUpDTI~|_AuXYYnJt3v()4SR_`T?Aucv zu>bwmy;V`Rt0_G2M>X4F9UZazsYwrTHkrOUq%^rVNc}dq0ywkGs(pBIbaQ|yR&|ca zopYSCSsihtP0p7BEB^oHp&J?M{yS7oSrfPt*ybk0_A()kJQL#NG9eBb6XH}cAu4S` z6x4($q6u~3o@{5xFflK)H64zK)nimMq8_87zx5b}#d~cd=%ENgFx}%<+NcS2m{cJ~HIKjgU9&YgXSKS-K ztvyy4zCI_Vt75nu?k2<#CX6-L1|jbI*j;^tVJaGiF{&+N^qWvyoMqcoiv=NA{GY!Y zkLrKl+U)X5*^?JfL-qgDwf#8Ier{_&jkWJ##A%+YejtfEmfuESqOIFJD^+(J-Jjae zLovZGsI+|KaR2|?S!fxLERV1zL?uj!LYNSBFd@odLR7(oD1r%50~6{JT%!``AjR`E zHPN`rs^gX3cd6M9iT>7h!QvmyLKh%}U>vXZm1*Om-Wa_(?keSzb!GAZP+ytf%PXZT zXhJwwy7Kz~tR@eIT2XysiWAr+K7n%caf#1hT$e7zt=y%!f4dapRk8JntBNhDiY=*% zEvbqvsfsNrVvo}kEqQBgey}7$n-Gyrh`=U9ToWR!33XH+wWYjw3BEknRA(2XmVU?! z)YLyqz@xbQez64d0oQ**z@xbIo0mX->H0`mu92>2Br6)JibkTMk>+3P(?FHR1AYA4 z)dSyOmiV^j*?d=lxhIWzM0}iz$pWal^Li1&gyUt*UNr&FyF-9@nDU~JFi*90879aC zosYVV2{EFk_qGK1lhas%W;ETnBemAWjm7Q?Wv`$h#EpAFL~Omqy-$xA_@_CS`dX(3 z?7(V=yh!59+bYC-rR!}7OV5D1VkN~UbSc)*CH5crx)gaZUhDcJn9BWwB@xSn2xUS< zGNBGsE*(B~bga^4ukY#;?hSbYnlv6e`-l?bRdrdSw7E8w!u(!@Fkw#x@eeoZ!E=+E z^*|^<^_2u+-l?X2LXe-Si4tO8GaMoSk5koK|7J98nMkd*Ww5wS&2|NZxUpp-Vr$FX zr$Zm`l6YZTh1kA1FrYSqZWS!EEtg5L&fXUzGeT>V;BKoQ-X?^z z3AJxIIx**js?y!n8xA%$!^m`3XIhL`Mf;92r#Anbtyitx)gcbS2SJ^<+niF zmfCxtUA^9kk8Fx9OCEB`#HDslJd`!>TjGh2ocytu2QQcIPxjAly+ixo)*_;5gUu{& zU`>cQm=KAX5LGoHib|jt+CmOte3b9GFs-&<6H41J`dix%i$m3Hhd~IY$J90U7NBvd zo=BSy)s^xya^n=M_uETy^~U%0|I45H`^w{8=<5%FyL_WaX_~igQGrd(OPJS`7jvr7 zYsw&4OwtBZH6lb+m|Kd!3KRXU!eGI>&A1fd#8Yk7TWuPzstoZmq*z75&(71R>(hQG z+kQdcekEVM?A)-lS6vN~+HWtbYeRkUzEL|~(mvYzeC%K z8EWlc+lvHEhzgnz1vDY*XF`_f@ z=)v0j6jyhS_~0!XAG<~4Lw9v+2_MBy;RFvac(}o1{6{onh3U=*cvLo2;pgQ6@ z*&K$6``>CRZU*B5-gt7lsFwB|!mA#5{A)kg#L=U0+gfM0Bvzl{yf6G;(t0lX%l)+|v&;8n zCR8Wi>@v9Z)MLNeZ<{3dC?%)cCaaFEMxrgj*xghxKtnwdck0{m~12!-G ztMz({+!(K3ualJ3PQN~kNvVkX!Y|@t&ch`eJ}m0ZzsqkU!?+#pj2uqII-=ZwO^5-p z_?((*6d|f|y{Gu=P>KFl?XX~evAf~KQ~CT4O*dXurQ!>hVioD^uchFJKI#(k)hgRb zQ`6({{eM)Bm|Olz{;JziWq1?fLEQwdRG!mKsK>rjNd%&0mOYktQB0Vw>sdCM&zAKUt{#XpE>F90z%Ol9a#a~-9`dbCV0{_^WjZsyNDKg;O zzA%cx&(3A2s}x`5kNsp2`g-zl{*AQ_y===JjUTq+n;dO$y~T(Omg~=9oMwL-W26JF zaGt)0Q(c%vO~otj41Ukim@sn*}8zXS^TnhE+F zgg+4ZSqQ%s*`4YciXR#;8Fn}HUwYhbOj!KhEGfIVxtFJ;D@(&d1Q8* zbe}GH@oR)_vF{Mr?gnvEv%T9i{q|s(X{Coz*RK-(R zR`^xI*C)DXJIMqJKS$^wCpS`eUt(Pzt`-Wn6a78mA169;sN{)K$U`Yg!CHl@R^h5u zxT?1iT)ExkPPUue$##=F*)IRyM3DlSOtoz4V>+TqChC2*(5_CtSO`VU^Za{;<0W{S zwa*5jqge);BG8l{>OgpadiLf3vkA}@zK9w1K_dnu_jCQF4m;)CTNg-Iq^OU`C{J;n zIv_=Rd{%7pMULwo!+|lPjgnYH^|P9J7d2;}`oJVSNTA8}MWNMB7QUE`54bd{duYyJ zeqAMXettc7jOkX_9!NiTHfQ}gM18%ED%d4D+8ftvG@dQ6EdT;%ab3<9#l?Gq6rL6q zkx>@vU_b>HnueIrX!xQ8cbbMi?f^kO#`P@f;gjmnY+kz5OydV>!ov?F!>~LZoTb8D zF3^;JSR+AiM4l#ej+0@`=J8x<@abXjFO43a8o6rDOvQvWp$X(WX#Pb*c1I%ci-y^5 z=MGzq+wI)Rc01RJXS-qBqNt5x*cO%IS;tbmNV(@X%F%n&M+omx{f)a*Q#QJQ+}_fD z6d45{Sp^@N1s`EfmmjJj`8FHK&mU9N;0wRj{=U@PXfOO)d-#p<7}w*!XqX43?!wno zXceQ1Fwn(7RN)?ZxW?{UL9u^dDz?5rBt2wZYBx%hhQ3uqY!wk(MZ|iW$ByN$W!N(g zA~~5}IGK(Umb@uJq`{qDc&vXO2#@y()UUn4Tga)_^NWODBanD1_&tK+sDtLlCh7$} zSs2^*fD+hDaDvB#VjtH zQA<~si$#7@AWi05y1HPWt}fq5lT8ZDwXUm6;i)h$E>5G^d@+U8Tpp-5J7fMc#WDuV zI|ar-cfXY9I%ht#SC2(8do+n zrkhaL7>I)eagD*k^L`8$phxr=iIFUx`OsbzWMjXw<)R$3L49#xT(1-qv*6n!MLj!6 zL%%K|HF3H1e8eV|ky=oIP$brC{cgN^UI1tLSWcw&u3?}jbTUQHv(JK5IBpkd}WK`Ky!^0ZVZd)Ko%Bfn3JV-fk2yc{SKs%)z_!-`Uv|3 z0iy-p(&-BPeWTkI_yLzg(K)LtLDd2RbMxjXc6=c*K5! ztP|+67OKS+j#iJW!bf{!gwgnwz(yDXXEDOrq8Q=pr9gig8+{fQBTU{C1U7QQTRL5V zzi+fgPWT5&4!+Xq7I^%VyGBm3w+I+Hq2rybM^0>?iTXeoH%CsweXTu@oY*xcngt@J zkDQ1bT@Jb@2wRc@%ZM*9VFR8 zfky5qp|+DTaxWI!Yob07#*LACm4y3Pdp&aJh`q=}vp~eOk%PF#<)GU`{$~+A@~e>p zr4V`KzL=EL9zZJvc#s48w@Uo^ zCetrW3Sa1S1%Aec=(a2Hc1GtvYIl{|e`>muJNF9zO~Bks|4`pPnSdubU4frtbh`rY z>hk)|X{z`=lMK9<(-nAz(d`O6$K@^Xkx342Cwb(tO#BH+20qd03jB4W+ZFhdBnMyW zbe+>$@mD7q_!_4x@Q;mdSKwc}ytZ2>{;nhg-{W)z{*%$|3OsHj%A89(Ui^e418?bc z1^y?a+ZFiPF0bQF7Qb_nfp>Ab0>8v)y^Rpw$K|zMulT+s1J8820?#tKU4du2ytZ2) z{*WXCAL?`kev{Gd3VfK$Yr93_k4!Rf+vy5?jM421e5}iByJg}}NHXwAPFLWQjc!-q z_qe>aTP}V$$-pa|uE1-JZdc%|U0&N=B>tO%VmG*1>@7(Re4Eo1cy}4HTEJ6{)(aou zzKvZD?l*d{1wK|UJ<3D&Yo+^ofx>~_YGl2j=89eDt)O?wfvyLuhrS`=+FSS!nghy5>cD z^QRZYRBDub>|q>rgsxG5H0lGL+;u&z z*hilK)x8gNAO;0W3zVYfGZJoYuw45=zZO_lg~yAB@c3$T(ho{bRt=3>`KVfBh;etA zz)nLD6h%MPr$=Bs@`hs;sM0(XtHv(NnuX>hM{+}qk`fv{DX)*au0BA;T%jy`PEQ|(kQ{1A?! zr*h`L&dzRk{rA)$;0u*{)y3pE%2pJa(VdpSIOQX zP{lw$5UAw(Ow&nvg!6HM8bC+L&KscG0yTh6s~av9g?m>UBfu&Ju!{`DB?7qtrNApk z1pbPGyGN++dq$w&2;`}^1F^N@np=o{JPG-NdSf&}q;9CGs~bz)MjeMbQJ};??-y7Y z2s&$FqOZn8SC2~lkZ`WmFR9P%6zci2M5ue|`ziJ+f$mwzixi6cPg?1`t(9nREF3gG zYZ|)6guq$-Ijn3_+<<;a8VqdX1~dzG(Ys8o6xt%)E8?MGwpV`7wNez{1JY+{M3uMjwk6HIt)3`8z>QJqnijOx&99UE<7#9A<= znEl3#HOHgxU&(cwZ|>=VEa!I$pYuC~&-qr-v{>>n5J$es`zik|0#%Ois1`+})q|*r z(cYNjXk0I_Iziw}MeOB-kS&UO^v8%w!0D&_t^_BK*_-s;iIWN~jc$mysNo5@# zQm^(@RdtO4v8(v!kVN>uwX(R{taR-YzQ*Yayy@nCX#qdc=)np+-su*2FQfB|mR|9F zsU1Ai=?eUDquUjDrOR93FC{s6Rg#1MBgrGzW#Zp2;Pukv=XTB$c~NFVYmG#g3hZnp z{9UIj@b`>vSKupLt^;uXr$<0$2i6TSbOqkm=ynBub&`X*auWx9w9)MfJm~TYe5})T zoM(xDnLuOmTA>4+)c^Kxnf^aPfLHK|PFLXnG`d}Z*BCw60`pvr`*83zM(0N{YhR?V zU>oZJ6ewd5%~}lKJ)&&y*~K2Vf>QhCBic9a z*{F9bo%++i{iNGxX1$<&KC;A0lg;*ug`2xlWe4*17 z_%5T{75MHX2S4C+3;dUC}+zCw^Fd(&U1IO)`Y|yhzz{ziE z2WqD&#;si1fqJQPH!tl#9qHWKr5&hu36$!&ORf@elQ%72+JSoE?(R}w>=$)`bIXT1 zP?tHkZfOVVfR~!)vY`&teCKpIfclVgIx9k*C9rVc7ID2dDNCpaom0=DHhx*Se1oXd zoKqXraNP#=$+`{d8+9Ahp9B^T;&0xhOg4MDUNZ}<31X&z>J4?EKH!`>0QGNm8`ODq z8`N){QyHM1p<$O7l?ZCGb83Uyvu=ZWyK@@z(?xY^t}%I-MNfKVlmTj6=TtDL7u0P~ zuc_OhjuBYzAl~myYnOJQJ{(ODm(@*B>zva>f%;3`1~qOE%S3HZTRFFCNeAjc=aw(+ z%op{3=aePXC+jw-&(&>E*E+XqY3D9c57pdLwCMH{sF<4GP>YbxxX4EN1!CG>U~eBQM?8mrM8c4UP9pOS?;qPH_ZTP}^%OiuT441P$!t z1e=wL^Tpew&@PlBy^x#7ziLfxtkq`BTQ!-Fw%M(~-xYCvFwfRZ+*M#|^FUq(s$1F@1ptZ2tSXIWvf-)u-TQ;#~tR=4mwJ_V6 z$KE1>$!Sc?OJkU9Oe14P=BV+^If}_Sipe>O$vKM2If}_Sipe>OAxBo8T^?fz+EdjS7@>f-(&>h7A0>^>=ri!8hP5g<+w zyBSolmo(eYW+YZ%nDqIbJ>9OKoovh>RmlQ3qPxl`d7$-lzi_ z0|Ki91kO~4b+#L1lcLM{;#&y6Bs20X>(IQ_c#2wyrk-nQH&0*DvAc5}`mGKasO$Z; zzA@eE>M`D5ArKj^i#kMX>w2^|>VU?J1Xc$KoT&~sTOG1V(dB$1DTFI!M%BtXF!8xf z(V{qsU6GrVS7_%9{s7VJ%E8BtO7QHmTtb59BJyO#2tLYD#IeO##4)~zV|)?E_#%$+ zMI7TJ&K9~&{O{-wakwSbW)8~te9-<% z4*!R7bP7H|IAv&m{P-&?AMK5~fW}P%yJ$h+jEk1dg=|s`d%pE9gb&M%u9S13S=eR?n~!*+V|(SU z&$6zQp1MA(ek5c}ss1{dsK-1``no`5xGw4t51Xv((cY*78W&hFbqWG!s)PUFR5mHP zoS#P&!h2*!)yg_Fo^(=%V+88Rxl8grwwUPEJ8}_bTM?4_?BbTZ_#;E1uI}P{kw9d4 zE{c#N>m(QLjUu3NsO6>}LEucE?KyXeeYPjt6dlfwXbRy6Wk*HJDtt%}kIoV(BM^^Z zwKnv)k}KY(I-fWPH9?@e7|<4VLtK?yjSVwBQk4sye55;Maa^U?KU^~&YB(1~CYz56 zkS^^&d2W4WZhke66dKoG8I>t4ZKU8=<4B?Lyi|6P0?)OZRY;GW)rEg-XU|EIH0S16 zxd~)U#4#p1WK5LQn5d{RQBY%|GlbyLyhfLY(c5SUM8>n{Viv}uYMXe`-k61GY%Y7- zk|1!VrRYB*o=uARmLDe;!rf)Yq$npLDW;mQ^U+N;7Z;DM^!Zstb-a8F^!3k#zaJ8BA_v4yvuwzcu;wZKw}V2is6X& z2sQ%I-WU!vt{2#FK;TTn;XiMcO^V9rN4X5#%>7#c-&t7!Gli zhP+f{aZwKEq8`pgLB5v<;GjB?N_J2=00-4!tRmG)6_ z(PM85*Rzs^dV6qfU`*&6Q>ydsO|M>gpYL9N99xi;oF;``7S(Ul9wW>0= zHa4cTJ={yg3&8yas!PNvN))dLtt!#pC=nWa3#>#CI8%xIcfGPnQKI~grVxHuW)!q6 zQRAH{Go^l`Nr8y0Ugd+!CvrvRSw)iiJgZ1jpI2Z1LS5a(_gw;!;khV6j;!?(?TsR! z@oRw<0Rm_F;F4{M4(Hcag>Yi(S6Kz#O{cffx_WcS&2Jpz?T03c+G2QroGetG`L%&D zp>Is7&MR+qc`JFJE)W^2MImStPq|q zGj0US&&4<2%2NlTu|)Di;oEc12kKX~>g+&W8#K1JU9vA+6g^y5+iR$!z0pH7uxE<| z=1y1OEsSng;B8!9e{5(w@!KaEc#_i1zwiq;1is#eJmIM$s_~+o6{BeOrzTs z_*|FQcB{mnpJd<*ovy&YHM(7af9LYrZk_nMk_>#0(-rsyuc8L+3j9K&^M{sJwe^)g zfqfuG_(G>EaO)WVuoHM=qqE(*4L8)^7v0e8zz;iJfj8X0KirI0yFS+h+Rn&c(DMZPz|sXCMu=~x)O2e~hGe7%J&~BC*pru}VM8v@F+ax`-e0sns5wW!JP4VRn42T_ z6_M+2!ba*F_Pn&-NJCZxn<9^|5NJaM(aZAtv{(>O77?T{o~f3D1^lqcQ9V1nqoGaPbrNiRU`9~8!(evm_ad)tu3`eo}nHGfwHtM#R(Ato1EOtuw6Q9dGQq(rf)sR?QI zvPqrdcrnC8T-3KUb!Eulyds!J?l`(2T5!~|susQ4OG4t7=XGWzC5qu77;b|{pNxW! zq^?MII<6kv2_s{|!kAM1dYNeGn5De}kuevF0gX9qwTbpd_0ZTyU;_$)Gapd*M{FIUHMMw%6CdvzEisLol@t!m9{Z;DbXE{$hK|_;9c6%y z5XNFEU7H%_N-|< zeOx%z&wUKmK8*>N{t!Wz^6*#-Ms?U$hHU=&e;Sy5Ul&{uJHLXi9)e)kmz--0`#$Pm zx+O8Y5eZl(u?b0jrh3JGZ*Cwct>m$@i;TjGjJk@9T;sYVQE^o|yuK<)UR;w7?~v0K zo)aitkq)mnM(M}(M`UsJIovihHXO<0+9I;JvK(GtStO6^ipb)sa(F%6B#%DqtJ3|e z*K)3nneW}hb35Zy4W@z0GuOszg5nzkL6M4+9&Y+=6#D7bz1GWqTx?-Q?PI{%o{JlE z6zeNROo+xNhQ=KN+r%L7`vjfjbR^-b6i%%@dbB>H(Cbk)WK`~JV~r@Y=6LJKW2tR; zvx{~yLl)bJETF=Dtm z&qs{j9b>)g$Hi3w4HFKyI2I!oWw1et1<@EWG~Q|*(-i~)zxo_+WqlcOtsPrEM(KAc zi*l6W)Te3OSYK3>MJ@TGSVs{dyjhV8e~UZe&sxHxF~!={fl?{5HXEaKn@Y>Jq_LP^ zI1+QQGGwQ*7HnT+wrYX!MPA<);pUG%N@Vj%>s>!C))?7`15P@{DCM+uJj%%xXC*X- z1-5P=@N1(K?iwp&a?B)XhR_ET~70p5nIZ>ch1bVta zRX)B0;STGIN2qF@u&N2aez^ovy$e zY>K>H88&*bwW09PW-bpWJ4ts>fsfjv4)lj>eokk?6SOY~Y<@$$#F@pN14JAZEfB{> z%MOb3DuLNROm}8+=i?%-5_q&Z9q6Y%F=_4~;$^`=?BmSh4n$iJNq$`P#ooAC2ja4# z@!O(ribjY#oY7TG#0%7a%WJZT*8~G`fHUfth(iRCBs66+v#8sPQ{A*S$?gb&$jGI* zLyFw(>J;sbOBEV#6xbSsz*%w2n~jQ_q5Y+EU>HSG)cGiZxj$RP1;OM(Yxm8zVkpX! zt#`$~OtGn{Iil6eCJl{8BPme~ z2f5)kc=X9A`0(}GWT)Nr;7%AB6Bfpl>a%2`p<|YQS0FOxLNTB*hpjfz-WX6czHXIQ zKOt~d-126lVnFk76~bBS7t^n-2T2ma`#agzP_ED9x~tJnZ;2RuOy}UE08PKsy8KS- z@;j~5^gB&|6}}vYe9OD!zbN0P-zi=BPU*^bN>{#9y7JApyr(N)c0g^uAWE%GcRDMG zGDF8~f{rpkM+u;#te=yQiv{_X7w#7VzsY6Iwgt{X5i#H35{o63CEcDiji-+br*>}{ zK8*>N^&M__tOcVwyiXaj`KvF}!0h|Fw1L?96?F9w1iQZETwB=pQ3sQP#Oy{SV41`w zBsrTt`@Ok=ptO?5&MqCXTGIEXUl0?N->G1lhBzbX7(tWFvc$Mb_B0cTrhu2pi z>Bsd)WO4O5yi?>9*A}T1R~FsRDtop_$>X{rvbd@oUQaj4qYvL!iSH1o2y;7R3q<1LeMa`-fbF?BCgy0`#$!S>HZe2~5!h7; z0>8yAZ#Zq79M@+QJztzMD)+UqMwD4|ui&xOHoVzIyO<%1ZN%}no>M@~xyDt0k|sMV zKtnOFa3toH8hv(IYr*!&U?8|Y6(fe5oowCo)4M-d@A`4EuPOH7fQw@>Vo?Sgq?}xF z6-MJW>zJ+}5csuIezSw&={qKDlOZR#zH>}nG!Q*vQ*h=jKTJtU?6Z*j1q2+@KM6aR@T~& ziz!C-;ou@CqeD5G1|}z0j1n48kdciA1b%Il!d+vO##WDzpOQUUl%q7(ZucnmuW%bK ztg^+HxwsQftfklnyAIglXcu*ueL*!J=v=ErpP^}G4218R^{p1ldkD0Fq55-y*1#P? zPq5|CA7{v7WzbrmPa`VAhXqzl2<)xQ;h|CHvDL%j7P9B?T9%nfwxP1^K1#h$^7Cxw z)E#?|*bfT2Zh6rx#E@qQw2DBV5~#}hhPeoLSYJFsm3v5ZKPf2hAwMVnOM>Da5)V1u ze9L>euBK`^<&@!iMlhPFLWk7~QVG|K#%evmM)s-#*E}lbo)=yBXcCz`MJ=wwo$` z&m;ry<#Yv}Wwd^yS@=Mg*LDlUAChF?g-%!C4;$UCz$;ze0)H;aqqFZ6{{fRNGJLwz zLmv@Fx40)+CH8!4)^G6$U*vQJ{*}?~3cSwcE%3uh4*pw`N9eWUe=N`%8R|gXD$vmU zTIhk0hjPz8Y7_7n0=$va6?neU?Fu}Q^t41~<@-_M9`b`#Uqj^0}@{YSWUx;Li0Iw695*X-&s%>7OY)k}4{Q&dOkMbv- z4Ao-5vMXI0qP=ncLStB9+Y|)O;!nP1i{fVST~c^oSVTrySX_hFNb6DoBL=?A=?eUS z(d`P{v#;xbTSm7l@WvreQLdHlgJzdk>TgDojhEeoWDDNX=?eThquUj@*X1qn{3Hht zBzbghJMlZ1Y`Evy!h0opy0Gi!d=^M{h_w&4z=t|rfj?q&y8^Ftc?-P#tLcBc0`F+_ zU<N05`` z1h4#ZE)LI5H2A9mm2D^4Oc9_0euY3{+`Zq)aCRxi5}}zB>LnqZAjTL==rH@1%zh&9 z%fbT4zX}us%NGblhVp!|Z*$Qip?5mDMCe^kh9X@Z7BC&bE1a&t4;tOBz&+Dk2mA`7 z+ZA|fl7o*(^6>o$+5MZqGoB0iXMxfLZ7A*30{KdTT0r~e7Rb5QG8;7C$X*b^ip?To z>9>F*;~=8l8DPM}TTR-yZyj3jIvKP2gxw~uv9*$2ZSDHm zKH+PeuE4v#hTPf}_{ByKR^X{lx4EhXF9+IQ~kCcHe+;13HlR-iRW4F0Bz zLANI{_)ZstUT8sf?tpg@$O-7}Nen*P#Y=@erTkYSmrFJ*u(>L{!s!b94Wru?c#X?j z;2$J8`06B&F5WEumLvn;=5z(V&**jq?s=WZ1hBrSc&XCFS!*Y8)sL z8oqvJjDvogK-=-BgjNc4#5ep|qmSwVpDU2ce+YTVz6iNiqN@ee27Hav6?o2cLUhn+^Z(?*lru|Iqzc<}QhVONH=ug7v7N?!@VkelnrjPJMrz`M2 zMzNtMp}atXLj;Tuc%jo3_!6Vr75E!T z4qoGQ3%u=qK8E3Mxn!#a+W0}J*zq)UiwnYs)%ICe4eJp3^vlOn)JF4qgXDj67Za2S z$rJ&;pq7-tKqpk~L>kJC<02~Vm_Ez=57I>1=6?l%(T2aCaT;2k|G0DM)CV2$eRs4Y_%a^KG zk0M(n*^#EFOQ`VCPFLVB7~QVGt6bg!Uy|hDZzOrdT_*lrCL8WKS@^6(pDXOTIiEF> zU25$*k_&&!=?eTOqxDCNgnRZ+D^mCbquUkulq3hQOY+ELt?cd+6vtE8`vrEwd_cq- zWMd3OTcFMET|%ov4snOeLBwbrPk$vRc;zI6!%7O!;B5q2o~H?YG>O5Vaxw0H>ttlS zy;u^#K~AWbgm8iwV=SS=>{;Tc2z>Wn069;f&{%%J$xyyT?3FHBEA%rbZx*`M$xx)L zcL~@)!1p*^fzRkg-mbtajUH@)Z%^{@@i*yCkSrZGA-^Kfk^_C$$Ue{&E(KlhQqawU z7(M;1F<2sKj3U5u#lBb&$3p0ry2`7C-sB|cXd`=17W#l749NOS0rdoXdVP_eUQSq= zBqn+(_(x6~CQCi^9?GfJ*W`6-y33kXKjC|vuE5Xk^ZJ1&8?C<_Cp<05!LLd3=qmmm zHXnK9E9q=+dc!@>scrJ|>Xod|+6PIeVXa++yU<=(6k3#lEmOOF8;RA_yh2^a|b+8AZ^f;BnH32#h?XA3_jGwpbL^1 z{2wj`-I>JTKe`z7O6$PR9Wb3y$mmP2*gk94_y`~1bOjzVTHg~CUgq)^_|zl^4<~u} zTPgn2Nd`X4=?Z+2(d`Pn#^o*W8cP~KjUl#dvxu}#v5V>Q|@5NKHE2`vzCtOg%y^ihTn7cG@zg*;@v zp)Hqa*fjM}KzN1I6?p4e-be5@Mh{ltZJn;`w4M0vlMFn`=?eTDqxIJih3C1vwp$?n zkR$^ybh-kcYIM5-f57Fn-E#56Nd{iwbOpYAj^_;imeGSP@L>nKJjP{__#;iGLx}Lv zPFLWY4|ZMfEk+Nvz-P>D`dBIc(lVP`>5Y9L@VzX&{{1h-!FVy{FQ=YQr|507E@Cdg>Q4Z0xx(H=Isi6h|z-;_{~nY zz}Fj{Z-}-MKS`hvpq;FFcLyI* ztn`m|gyn0ko5kN^GEGI{+nlbz2W{?C5qz-GgB5tb(=G5Kqw`dJlK3qJnkS$+M$Sfa zfs>KUc&+paw%T=PF1)4F75GB~z6*fQFnX{BzTpkc-CIe@WtpVX- zf-Rc?#!YJJ`4$aBf~|Wjs)RWO*P!(z!L~ih%G(p}4-@%8V^}aEEre98*^8**2=y40 zx#~PU(hLHTrf#(k?}TA7dry$+dj$Fw2mQ(()R_X!Mi6;<1D0PrB)B!AhBS!Y26eJP zmtoN9b;Bn_G1jgY$q^C9`h|!?f2$us4A;Tq93R1lm*Bhou#bcf=&*+l+j6ftD|c+& z(%Movio^Ce&sf~4qL$ZO_;St20&mv~TnaT`b4;9mdI{<#=k)VIP~&VQ^ruK5raRMX zIb0{kt)M0@FiuubGo6!1s59y|sO#!Bs56wmJxhZ4h%-~ISGS9C|4`$-SMm?FgTSmH zcJn3$gPI>r5O1xUMpou*ZpU;nTVB=v?@7F1#_cX+5Ymg*S0{%f%_|)mGa7ZBm0d(V!;!J|G`ZGo4d3s56{XG^p#GQ(jOL zeP57IsF?!Ap4x#p!x`;QBGTqB|5Wl?fyahQdyAq$J>+fDgc`Zi$WCp=R-;VVYF_IV zRwhts^}wccYIVkT+$ zb`eBrd``7r~v2 z(9T6*=Lq`+p9S&)b%8)t2c;vq8X_CcB`F16B#IQo6)Dh``mZqJiWI~ZDTpJ5d=6mW zPI1*%#(gvgh_oz4(l{Jk&pTtHPu`L`WlZ$SnCO-< z5yO}=1cxk5ete!L5E)04Vk62Cb$N^S#zut3aRS@JA#kRR$bWD(n-qJ_LTUJAxe#uw z>BYn>HzHCTYZtgqPV)JS{u9erI)2iAuLT|D@V2Ojb5W2F=9%66 ziZKzyn22Fa8RElUbLQ!jIEo`iyERv?k$SsTvW-qC=>As zql?2^c@h%!4?a8wA3lQ*ufccw<*7&bgbshu;R`zaK!*>u<@A7JsyR7Roz);ut-Tl% zZj325%lxOy$A0WVYNPMmk*K_O?bStyydU3@>$oWDNV=+v@!>A`NILj%8hq3s{95P8 z_VL!B@wBJW?MUrW_H?{vOB$748e)p3-CrOw zZjy`s((10%-)L{_rfBRgur5L1O#Pk8XF9V*(Y1WTSO^c$MTfhxax-l{pkPiBEN_N* zZ*G5k=Q0df88A@Q2CNL|8xzAG>gq7wpDbmOOf^)CGDK|ad9*jmfX0IYzo>}7nJy~+ zv*6jJ=yJY`E`)oe;AI_{2VBU<_1rzm<*ZwBgNzgf<25%6vwe4Epi z;f2WC)rP_w8(sXWulNZ`2Hw)?3jCo%-41+)(Rw2ze8Zbv9_j8W-B$}nc_Sm~>jh)K zkx}Df!HAa=2z%bx{VoH^{>os4I>LiTYe0CIVDvXKY8Vnc!W$X2o+Mb$8yRT~3r3`c zkcxG^k&%QNj!=(+&Q<5>5pQIK$lu?{B*XHJj8xwv&|=ZuJ=B>3&2JEydjm;)@vz|5 zh#FD?-UfBDfHyKir`HXi5JjG@7RjBE9P9e$Z)B3|;Bk(R;KNJs-F`SnM0(I+4;{AU zS>vqSF+J7^OXVmI+v7ZAai@w}UUT8gH6shWT`zDc)O^h`am(~ZM$}Et={6KQ&K)ck0Icx&A>vNC6Tn>=1DYIUs%^{u)MiWyrP#L>Z=CE~(hZWD1&Fq0H>7mF(g3q>3qOvIxz44Qdml)Pe6&(#()QeEB5 z>SD5bafbb#ywmUU3`@b&&dQ`z_tIn&hi+PW;$qA+g~UY)Pe}F}W4)0{=Ej7zF=1>> zY0L6tz*VCk3Pi@_EC*aIte3hhOxfmutM#j}yl!_%RGG)wiAPwAv9LGLJ;vUPb6^Cnilk@+7g*PByZ z&Mi?A=oliCrvZYF;en1GL&wlS$G||xKTatB=;;t~ysQyvS&F1V(Hohx_Kb->c}wb) zG0`hyqFcs93}ea=9I`a|@p+m+WE@S3jVMRd8i<^1)nly@bg% z7n9mAR`yohwi;KxtfLA2o8d zD3WtgCFi0{#3zg{4*o_a)j#;~7<~8)KD-9s?U$z>F{aSr4?287hac$h!M2tIx%0&v8L4yo zubxem-~9z5<0iT2FRkuM{f+je40_!gX&gwTZb?~BV`G&C&9*{K4&9wP|f?g3U zZ-)8yKFY9nF2jJ80RvS{Z)D^jePg=S)nU9pS;`_qwJ1Zxww_0OqYP*~DDaC)a;A$) zdLvUuFS?xXq6^_3Nwcg2^MDJv-pCyGqVkQ*dgKbU$OyxL!i|>_io`HQyreWqi~K(&T$m;KVg{%mZt6P8H3s0noH%7|`I(v?G4M;Q> zs{_kF2owWEC$-EpUDH3>5tcjs&6?-82<+vc@NG_4;I(h{mwDiy7(LhmZ~k_dhu^ht z(HBAm3btwp;%X_0`Q4I5hwHof0%N}UwhelIE->as5w`~OOA&Vm(%1?pBQ4?8BFx=`hV5_E}{O~N$0J?$0d4+u$Ma@yFynR@V!fFZRbMY zx$wS;GQ+#1A6;5nh$}3_H7sQ17BlIh+v_w8HPV}g>-Hr$8>$1HA?iYbH9^o5d6bWc z^F&FLFZCs)JB%vbBTLt1-6A(hqjriSjs#N7(Je;QudpccDPk!1h+*A&6n*@Zs&~0S z%aXP58-Yj=m6R7B@*~Aa4r268eu)SskK|FC@aA>2#U%yj8kvP{v)~sz{$wJ9!UZe; zAWeCX0maf6r>XQLb#PbjE2x+La%f~_d|Kc(P;|m=9&3GKUAwPX(ayzMc8=}k0k0&8 zMQz!{>h}22#fwvwq%yA)H8!RwaXz+&y7pp}|0)m}s>KeSUFjGX?Tzyb8g~oq`~rcq zIL2j*;-qqu6l^l-n-KL1`WFeQy7^ur!uKLY{gRlkL`$|+OLRU*k&r6-Zak`nLS~I3 z{@Z2ddszN@#siufqfLl0hbAS29kVA7B!lK$Xw)4CpgzdzB~J8v}|4y^dd`g2rFmie#grd@+1s6y3ZpWmuj{NuM?4Gx%0%Fe1(Q zTK{JcMpAd))yJEi4%9d$U zEZQ6M4UOfdq4@-Xv-$=on-sGx?+=CWH=0Du&2p-dVj4zWPm8UatE<-J$ZKt1w$Syo zu;A*NEsASx^CD7Ma5~8r#aU%xF8n|pLggK(^_@wzM*RqZs*3j?2q_&lTA6?j#WgU@%m1@1YbdDNdT*`b2sHgJmAkC|vT2rJdQw*&D_ zmxF#Ba)`gU97F`uj|#nC!pGw8zV-MUR(lFQ&_Ovx)bvRI(C~=;Bz>(w(;!rf89}SN z(rzE^jTwQ)_XIZP5IBpiK3f!H|DRHzK8;zDg~e5Ok!}c&6xdS(;iH|dz-Ny~-mbu_ zj2>)(KedI+!T)CTU<>@vmM)JHtdNg;1pcd1E!|z!)rltmO`Q6M_TQv^sbCE8D2_g# zETV}elKyo!P0D`~;JlGmZ=9e%B`#3Ovff(heO^7*T)KGZ)#~1`z?cYvMxQkFvpuB< zBWbt726|-sEm|Zwga8|H$CT{|0LAo3tm{QucM)=gr>14?v@iY zKKg_F)dGFcG(<)2Rgrtu-ENylC>RqOi&F2`uMy*ajOL8)wLnataw;s9vrk)wvp{L8 z&9P}Q$INDd1_g>Yrvq`S%Ry;2=FcPH4=1XOeuJhmKg89id8yuV_P1Go4SqtiNHNch2`p z=(9cFtKF#L+$k8>v)RmeLNRy74?S&T03ab5s_K3etL1Al<=h` zvU&(LN@olnxhfeGLyGz&+v%ka@eu*ff5HE5^zd}>*9FQ4gnM;p8s3>;(BMWS3PA&S zL{yd~+H{t}_{B2+@_KF`w!(RPetY(P*;70vgn3u3zMj16sMdRc?pGp0@X>c_N*0no ze}CywO(F$f>Xk#4t6p!VG*e2|_Tr(iW4uzWsu&5Cq>6!nE_JuE63+(tkQ}?Xlj|xb z*HTPaZYcG~Z%H8Xh&a#@rp)h!(rZksH1N~uOd9L@?;wV<9JGo_(kgW80|2`0ZmL|* zIEc|^S7A6U`iVy(TPL4h`l!Md=t zzs=hFLHN`kl^X1@1nw|-A84W_e`K~J50WT0xGbuF1$BPXY80S`a)htS%2g|3%mb%^KB>uK`D^PO%WgEUrTnrQfh#t*R*X?u#e$Z(BaU0>DMgF`1{28P3&pGa@_LmAqexDEN zD+FVHpO3~p1p2;Q=hq>Bkgl{*$096+{mSHto?5LZd9YgM^vNa# zb{i=TV<5H==$Zi9FXZ8|F^$L&pPGa{;Sw5;SVD&(bo|5aO#*Xvxd{3(!gHU5+MGdi z1?lNRsCPYVz~$%$WzYrEYQ!Onx+-K*S7qz<_P(&4(`(*Mow4YDHD;m zEAUjK2V3A5{FBSUFEo0v1wM6amq)sjKEW8`Q5@}_ETXA+ zvfABL-1qM>(&}Dy>`#Kmv44T|b~mB!9)GMZZm%wC^zyAF8n+0FDuBR(oUh1rzszzG!4WC^@K~tR5|y zJLm=dM4+(K!KiAVv?r_36os~&e?FEyzTkz``Z^k_O30q1emf`Fc(RK8$AaP#QRH3~ zxz~65(QZ3OC>Rq}?orRvl<2L8Z&VG&92es>XLR=gV)`HsXPe8}&H@b?DEXaZes7nl z=%IHj4nIGcXjY=dCjgiDNa%AsO3fJ3tN{*4w(x^X{ zoN@9Zj-Os$?7%|`fSfnR^P7Tyh9LA zR=H;EDd1t_3#5LXFZHgGa7P#zaL>zffR8 zi05cx@njXeo6*D5!LJu6ACO<>hNt1338qCn4cv%CA!q=Ph|01=o6b@gzgXrctGRvH z3g_+l9^zoxQ#>Vvc~`AopS6d zOQhGBR%zg;)0s5Z^|OdjmV;I?Nm_+&z3ZdP?xxE1jDr|$b`^&8lT{3F5ZKIx_@zLb z3g?zhZL;<=Z)X_UceK#=on*IMDkxSL=6^QxUQkPl+Bfp?k@mk@dp`*G_K=m;aGZMu zeb(f~Lsn8EpJK1eqWU50ACgw%w3UU$L)J&J5JxLjnDLO6l*v=4%JLyADyj189WqKv zJ&OV!l0=P%tmjI|i0VF`nxASl?*%b=G;Ze(MYhJoS_nHHvKBL9dNGwoop#-Jf411O zF(bZ~R-~bcIX&`_II<8KIS`lYtVG4-cCfzON{$1ru_B90?O=V?7{%M;zI;c9<{)zX zweq8nD&9bym@#K6tyJRy%V$8V)LJ0kBG8zCSh*%Ieg4+^-ACPyu>SSo?`$J`LCN)( zZTR+cZ=mEYKV*&4+qFFRp}3l&afrYkvO*BiW)bS^zqF2RA3b_q^20+`{LyWl92yT< zsbZS_^(MA~64^|^TnS&_5&t7guz1MIQIcbW>X;9Pt8{01zJOav@P$rS;Ljh4yj_7; z8LbcL2+ugmJ<-O@w(p55a1u%nU<0wpGIMsLKIN<7-#>h z?m1!x2OopGetGl3>t-ofx!|eFL_yc04YBf48tGp{h|xa_w2?hqXeTE_wP;1@Spv;u zeF!9}Y9R8-8C!}_?1{UGeOXhqT$j&b0ar`#3a2aZeMYw{@ck}tfsft>{rpN2A8V|A zxCQ>EKu0jpokq?A{lTR;m?#HI3-r(CYq$k|jf+7uT|5m;xS|t9grCaStpXiaEAWUA zv-gngp62VA3hb#5*S9j+*({v7gIPt6I5kgd1aGWFrsF zjDgNCQYOY^M{2>*p#p1xSY)a7g6Nvb!zXU2ik3W1wlLNHsEGDWGI0m>-E@wooh@ft zY;$OAVxhE4Lg06t`p<_;vGDxV82LqG?-Bo7~FO83WtVm@D8 zi~4DCi~NOSns<{IEhrpLb29v$uhuUMbZ!8BP0+RHbh*FJlxN{;A9FPej|-d(ujGN^ zMm^QCPISYV(3m>X2ob)tpUefnUZA8wGX=VTI=%yOpv%KksBYMEteMPEv*`Ly3XumX z;5KYRrYm<(`8mqXq(`kR76gV~k7tH0I*8qN>v|fzO|s(zT0(hmUMaz+1q?a(Y^N*m zQBOnOuE0kdJ=g+YpX3qn2hx35Pz?D4wWyyKx5(Y2`AB(D^>BEili}|tYWoJVd}4gBLnofj=;a zyj_7mX!KwUd_j^&2PYq`n?8ZQk9P4;U9*sOcVTyFzFeTYOQx?r?;^CBK5SDVeU(6W zmyH&<@q8MG#;XLnyBtjc;Z`eJXpoNmvh}$`3UIdmi)5FkR#jnIoofiYOP1w#|NI!8 zn&RJoCMW9gmvfIp>Rwv4cjP41HBryZPF7_nA=PY%Xgyy{4jLo(^-;~gl~lDp2>DAv zvGl%~T0N7kqEhmE_E1C%4~5Qk=4CeM7Xq7n5L8)nJ}hyE4ig>xbEoUg>^I{7ASiBH z@bG?3CmjcN?5s?4%b0N5BVp2*Tx#T3wc93*R?jhOdTJHt!ppR*v$m%m7^H&&=}HPk zByqQAozbOhq<5)+Wdpv<=?Z+`F}`fT_ZvOf0zdUwmq$*^+xn3l$(ze2q}|KrW77Vl zVC1qvdZu8^Wkcf&73h(d4H~2~`m(uEK4@($n-F#{n=HTk`|m84%~Ml|=CTQC_p(7w zQeDet!|bG3HX$vS&6ARY#Zipm^3j6k^UY#52&ev$m1pvaOW4c2H9~AH_Gu>S2kju}nvGo% zXPWXXT>Z?+a78|}a>U5J$w!Q@jWj_-LL3ah-xX*Qfz}Fa8-}>nyJYv8tuD-w+;*C^+uKGs*aA;-x&kjd z&NoQ#2}bKyL-_0@4N|pBGyF(uO*?1d_cOKM z@KESnWL{={UFdQrV}9U)R^H=*S36zru2+b^T2Sn+KN7oC)66#152rcT*j;bS8k0MP zM&4cjmNa}n4VC8Z`h2-2j_;$9Fw)tz6e{Ty=aA8*tE79rfPEBvq0<$3w|Dw-0>8xQ z!4|kL$s_t5(!F1xyJ*mh)vR>T+}+7g++6GKWclcTr8P8KJd_EVmG-SD=YT)*q9)K|Y8@XTZczO#IdTh&WoH$is1n zwMmT6*8tgXFJRJwCple#A27OIf&b$27Wl2t@R0_;-RQv<_JL02CI5}9r=c7I@{OLr8EjnTM6}4R~*r-Rp^>&E}lyrTVv7)t&!t5y6 zs7JpR2k}~gH-$BksD@sPkMB?q+!+IbJDmjbs6R^eNJA5-dO?Z{9Z{oQHJHJq3Z39X zk8tS9cJER~WwookU5Mm2R`QzYkZ2eCO%zh|`~zyCj>STz)m_bADiV8*|9J5E0&R+* zuNm13a_{vz345j2ivyaW!Pf{h2_tJn3=CC>-a?n{H<(HNN;iAy`*E_?UXJlA1;w@O zTD9J2w!NVHjhq!xifR-|^hPuJMiRHmG9?+Jo=UOM)qA6!_ZKITnUeXs%#SS=Xx~3X zz&Zynbh-k+@&vy)f%hnv0s=%vToX>;w84%9vZjV0*Bx&i7#*3bu9TQ@-6WDUKbr!NUt zQ2!#3E6`i&2B_n#p%3)sx&i7kYv=|2rEY-Qbg8)ly-J{Ut#qOKtf3F|-ns$mqt?(1 zT3a_j-DC~@pr@!z?h0yqfzk!NzHWe;;|(B&#Vw+k&r`SOTLor;sJs+bE$tj3YDvvO zohZ-@1tmXHEB*Yxkyz5{8i`a-jW+chS^oV~`8U=5;EL9My&2s%ICsF$dWC1$S8}yfH zpg!acpewvVf5!*v25$gO@L9fWr~|c~&GK2GIo_~*r~`GFH-I|cpg$}E^(Air{n{IJ zlLK|1H-Ok%w3STld_cqsWAt|P=OVUUWg;^}NgMK|2X#v36+(YAR;I8;YH5%+7Z|g<2GFT?aVS+#7hx*MTw-@!(xGgrR^p;oaqTNFzijX~ z2uc~&%*j&L?L&J5BbkSA%qzuuhp?0PmYE&g&=2h`GwW^`6B(fHlc+C}*X|NI7aL7> zrIiuwwi3e?8dq5`O=Jivp^avZZ8X_LtznY4kwW-;nNhHEu3w=vi}OT`)Y1-$#U(L@ zDNkuE|F1vDM?IEUJ)#JCuEue!oP!)Do~a$Nl(D&SNGN47R^dZ)m63>$OFLbsl8By% z;CD$~6K|Gjqhd_>M#G1C@5uEa~UsXQN8e?x-%|$K*l@}uXjLpPkuB%XWO}& zei#$oFeWlU-KRufB(LcjITtgRR(GZSGuj(77mfWan5H2FmC(%fKV+Frib=Y=H2knt z2;U|l1uJLn8AnK`FaQ z{GDC0C`e!?7!$tH@WJYfv^0?-n_^DUdXB)RQM5Pa z6dE5h4NVXT`lvbOe|0vS6w~M3((p5TA-q*WN>R?KFDXs#$W;PRDuHhLNQr~K8bCzR zZm0%46t{_~Hfo5T<4a+S3nXq8r9U2B`Z0_eJuWe35f84{3E*oDId$r^Y-)<0=zsQbAA& z%|ril*V&|)a$l7O-E3T{e=h;f%XxU8(kz|>rIFIZ0~Cvg4{4ax5FNzwfAj%to>k;J zavsGau5!-&S(?w(-DN4`){{pir7SubJ~WT0QZ5gU9SzwE+=DJCz#nP&{`^Bcq1sIWGS@9?|C+Lar%6&Q#(?&X;)dShlYWmxk7q?AR^!iQ=?&2q8Ed}O!YVjZ0PXzmIechV(C6IQt_QIr zJ9}nQ*AUOO$F`^#6TZ>#LiR;k8sx~P7;jq75!et%dtT&< z_TAF(=Z%H%RtYIZIo?+&&GIFIZZy@6sU0%n8Kp`CB8bVcFP<@{Zs)(jhQG)D&Mpr& zaS4_lQi&Ql^zmY&9Om<+d4r&ok?Vb3vKXH5q5j#+k?1#m9#6mT$P;3oJ+4m`n`cku zQ<>(~iv@KrdtYR(DG>=5vx8Q5#VI6ps4+XxxJqD03JA)e4=7CKIc&Bl=D}B`Kp&fj z5D6$&IXQT7{r_GzYpDJaFPq~vKcAJEv`inZ7HCO*c}Yyk*?JXsj6fg!0DZ>WS1s9B z&(?WMAmvrHGH>&e#+OTtraLrzC502`x*E-STJ)-6r zuMI2c@3`$1LVs{F!h~nNQX1b0Q*B`W#t~bLtTjwVyqAoI$KWe`Gz!O?&x-{1-NTn} z3wen^AHFCfkdr=75XvG~OR}lTDRP3)mQIee>HUfne{1IT=T-1F_8Zr3A4+%i64ZGw zYfNZFIvRoTlz4=~s69qFcINn@Ri8q(;n3%kU~#RzF(N;)7S){!!!!lzPu5)`)wG|l zT-xDHB5#T~fiAVzLTNu27tSx21+Sge*Uv14;H9$$1Y2G}iUj$~M`amr$t34JQ`%fF zuGdE4Z{^bLr0z_kop=vhyjhzl2=7Xj$I7J;I|)<-79T;1dW`j!{J-Z_>sZkr>1{28 zpbkXAioX0xy{7`|_WaJ-QbX04{1#6w@fJ_p6EE{p)#ulvh?~0vS|B)CW%2qLtDBAN z#~YT#)h$NSE@+Wj1KdQC@VAt6y|fI|T1Cb7zZhCsVJN z>&&1sGD-Fn6cyc2Et`641b`j$Dw2;sp}wcoUoY_O8mjmp(-Cz;sQ*P5ZgzNIWz1Km zy>qtu)HUbAqL}NSvANEt0<@s8J<&-JZZs7xUJ_o68O6!UrAunddZGOtt0CeQReh=g zP;8|z&>>GE8gq(>l<7e6URrALURslu*V9Zfvxpwxa|eMYEgs+DB>t8g*+(8&7LzuI z){!joY)o1-ju64jPuAj|S6q>Y-yfZ`l zt>0SzZ+&0Z+S%poe$G9&%=^9<8E|-@^|byKitQm92f)EZ#B||&41@Tbb`bgU$RG5d z0JVbvup&xU^(Xv4o72x`#d%@;uqZTDVOG^o4W)iYu@{m1b|##jZ;tEBqwB!_0)XuX zhkp9UsqA|RM-8rQEGd4Iyk4YVglu^Lx=554fBkJYYGlj&3kq$Rlc4|};>7DZ-5~y# z(UTj*ZznnNJ5IL}4_ThJ`Kv55Ap14I+p;7{SIJ*zys)>*0}x@cjLRNN^)wzL=Fd+* z3|rduF-IEmcIBe~3-tw%IKEwiHu77PYH%Ai^PvE12k^R1H;5-1J-IJm_OmC3B4ltkb z_(sI^Ro773viXUWP#|%J%9PDN|#bHN2s#)=J`~ zHyfT-lc()K>?|f~ECr#jlXj9cKo6uI4#Rihu1R?XSC%_!P*h|~hxBH`2_QbYxS&3~ z3hKk_GT~@=eax+$y>~|S&ZyqmOC6gheV-2isV;|2Jx9g`gvN^t2x|NQU>6W1=nPXZ zoX>Q!MR=w&846Qmp`K+S0!erUwCJK} zygc~30Ot75Nuh`$4J{@qiI=A}V7!++eGkNOVxq=K2-D&sNdsKjNIhKSv|*%4d7LZD z9W^K_vZX_MGvN#ncZpHn{izSHg8J|(sOQDCU-sS^)jOklUR+c^7=TLX`*tVg8B&#! zBV*1rUMwzZ+yt=2MS{+>xUxl9T$e%NT3IMi7KX+3TWHZm(V4d(_$Ppii+Hxv4dQ)H z^2J4bu+d$u#P^@p>dWR+u!$!w&Q9+8%SG@nR8BgQe@PL~X!2=-?)kjqp3}D*uo^j1D&^ZX~^VAX^Y% z5otuFB7Am_1lbL5L0Cyy0|{h}kd0;tUxlkbKHT2~eO$v|$Hb=D93P_Lv4?7s2D+?l zLc{0O_WjjE4XznAT1WsWm~@R7%bXf4UX!jy=qSrZVO?L+htbvMq&&)~N4Z739jW~m zP=wF!ks#Z_9`vJu1hPiRMspO8vVN!HV_W`XB*B@(jE@iT!f_@I^jZ0YmjA4_@2?_i zaDAxdS}XP6OXamV(Ad6aE4H(?(wZ5J4lZIxLRTyCVoo=RUod)dgZM3%w-Rsr13z+z zJB;pXCEjd$c|`3D-8}%%BH}RmbZU=c?+xK~08B;8i@=M(2Xwas+Q-~ZGJLSn6MKjc z2Vk+`^Cm-=A$dBhe!Wl}lVwf|5tq8NCIl;A9%RtUZngzq01y|!7q`n(w-+hE#Pn|Z* zPWuS^JlJbA{3Xyn@-w$3}Za;%hcT(;DM} z9{||EKR|GbjM*B*9sq7|9An9au56WQF46wZ|MM)KoBUz!iF$&>~$6_Qa6!)wZ z^UO$AD4tj==3*o(6uE}$W!UHXk_LA?DUjCm6uV$PaIif|nj#rHrI}9~wk4?qyVX{(qc%c15N=k2T98o-~;s=h{l5Yd>p1OLDvn&_C zVbTjv5aStwCOj5nzjlFaEMOqcw3G066s56iaus!{$25X_iEu%PXAR+9l{_``Bs@2s z!pdis<&;lKdco&q5M2#uPU)(o8dIVk!vu4QdZk1?p8e-;`D&d~mgSW0O?tuS3lO~q zXin*sq#9GA9>WB4iF&0(y|3Bj!zOh~S(a03K!g?-t7SVruVoyCkdm|lagX^ zdKpAl1DbQXDyc?u>M>3*m#9}x)cX*CoYt;$k}x{GHz@|EFF^DfpgE^kl4>-k9^(Xa ziF)NkJs#i4DIdrZMyCxZQ874O3GC{C=A2ebs?nT!P398y%BkN=OkEK9g`~EK9dO#? zWhl-HyH`>%rdb2md>Rjzf4kN8*qk+9Y|hl+#jb9Ib>WN5{e$A!DqLXc0yYs_b>}zz?owOz(DN96T@!2EM&UQm-&z+3+58_ng#CK+A!yiJMK8WPjfM7y)`>Y}7N(3ia z{JnF@O38>p7VUNd z%!3b#Vzx-`3J4}-*^Z)fz9hYHAz`uvJci z&d?gWQ_mJ*o8A`+2gyPOWMR0$z5`l!0{Eu^;@>*mApX`lzReLIY&8D(2E5VvE|=p0 zXW>Jb=jvGqsV4z=h(tu?^4vDp+4zxRjPT0p1>h^sbNZLSuO<3TU=Ne8zGUa#Wa*r2 zos)InaUs2TN*x(HEj+eYB=&Wtqatw*z%wVssc?_1 zmzfP1&J!&^DWU584)jwpB8W&pCERh&qg%eXB1awNk_G$UpgTU0y2Z^jPFA zp@$N{DV}q39xUL8laegJ1&a{lZp8Q#V18V~;6X8dQFr-jA1s060nHb(v!U0hmlUZb z0618Q@>=71;#xs!m|?Dk!JalaQcD2vFo0<3df=;|zFu?8l?%XKs5-`Hn1L+=2E0C? z#TG6DiDxK!6fd9R3^CM3a%!F1HA8AGpg!x5f4_vf>tPHt#&gTjCMTG=?`m7>PwQM?iruUzHVa{Zqa z{fX*S7FNGf;0D-thx$}MI;)S34INugD!h-a8%K5Ss#vbv3ikwX<)(cqJkiPb(O8*8>3a{XU5KO#@N0I+!jtvt-~zb76@IiP-B$F^sGKEs*kgXNj*QZ zpgPZNXgyCd-P@I6qy^NGD12|@trVCuCGJhRze#~t-zsVeP7|g-R+-F-|+9=z<GdR^w z-DxeY7+c@Q^CODmFg6ts?zYMP5Kuo*S`0Q{0Hg;>B!>Wk3E7phhI*>txr?LZNpN}1&-2%Bjl8XRB2gtI|O&w5h zRj35StKzKJ_j;3_?28IJ5O)NCMMo_J>Xdo@|bg^l8*{9R!8{$BsOGq0A_4m zpk19LIv9XyZL8R*JH(K941mpi&XEIGXsgKl1wd!S%m8!`@#_FMW_ynVm^TvV0^s0Y zbD*pg69$S1lJV-I2|8^mw9yp?#vi_3*H5wgG9 z__UUP0k3T1`E=0**-?OStdTttP@gUaz-9qJI$e+)3VSf)LM0$x z6=%J^*PHZYUsTwRxSIob)DjPKxOC&_U>|F*UQL?DG;4UzSFM%AOK*7?kCCVEfjCY~)Yuxr^ldMaG(Zoe9{%3DGDez| zN4m1yQG=o)TRNmS6V3qf(ZvOIeA_Fl53kFFqx@~J@!31R?UmI#qk8_^lGJg&pz{3y zkm@o>m6BcI##H0Q9St>Z1=t-82|B|R*jEX&MYwml3<}rELV>a{JeBw>wCJK}B)<&2 zoPB2)FHr+t!RZF^>qbv*5WnH_R^p9TD8FMo9kQDNm?t7voi^^hS~Y)p_-Bya1>gq_ zp8{CG(bGuCiJlNG5#yX&%pSKOKO~7PRb!R?7je1i&Sh>^Za)U;$i2tg|9_ z*A)jYPr(ou_S8aIv}0g%fNdJU!<=pqZ@Qwlfwt?|2Hh<4LjJJewnYVPq{wM%u14Ig>1{> z<$%oyzABB8PthM=%YP9t>EdwBfW+{9S-2z4JgznFACaQ4DZC zF+kzz#Xy>23fZ=WZHDP84XA&;Q;wbV8JIQuMO<3t8E{@6a4BWuvSVlapI4547Oxk; zt^(+o`E+$F~xqi2#W(j}v;}#*A zl!5;MuzB)H;sHIqmBPOO7U1040G0v;?*JMt(;HZVkdXU#vl;~-Gz%$cK^6fEK{KHu!8~zdA+j_m zm-1`~SzI{rNCf*qwVs?}3H|dWEHTieJ>S3K#x0H~?0B5^H(Xpr<>02?Gh_ZsXwLVHt$_DT_2TMoOUr71*v zr4T+^#>hY0$*g~KSt?BqtxoppXiE`A%bATVcNIRZ05Il>ALE|>>cp%HqF197!pmE= zP8+qaS}BSKb07>VkOmb?yuyiB<7UUAM%VLzIuy=Q&#^F~Sf8*cg;3}m<$t>~+w}7CZO`uVP1+xp;bDTfpx& z8{=w`#_5!e(YTH^jk7E4fX3AgjdOot4>YcRXq;OPyP$D(MC0ngAoO4r03KYP*)#B9 zd<>Y}S^(_pMB5lSLiOQHr&Pm9j|-a14V%L`^$9>ih5QLx@)$rVDTQ*YXgYAY-Z&FF zHgn(X&?ygOHm$D{MUK$-WHHG936rHGTAONKRBXm)KOaoO)Sc|}O!R=y>@EY~Io!;ifdg0g*MN%bT>zY9Umj4OubiX9vjBLkhwPzD zh7qt9@j?6*V4yHr(i{takwq+p!FJwNM=?f0_zh(F_di?Wt4eZT3;Oo{R}}Ce0F__b zLt+{1s<_uB+T5=VuIVB1ZI{n`1@>fs=e8}Vg8*ht;#2^viGJepYkElh)#aSjaRAdN z!Q~HqF7DSPCou?H0OSV%{Q^4yNTOQ-ELIx=#60%d2avHHY&AOoF{g56Tw#GETFtNJ zF6|+~0}67rhV?JubrP`$_&dymiuHH8oamd9v*HuIG9p%O`mFdtmlHiIIV(O4fRIGK z3&TGvp4%%XV)5qZ2oPtuoM?vRBnEn0<^%eYlSHcl%ydH#JGh)^jN~LzM_&cm;yohr z3pr#HS{m9o5UpCq+eO4yS|GOZYc40+MsgDUv=?@Rs?gx>y1_OQTHIZ!#WoU}++C^3 zHWJ$0U8&7B5*poIH`+!*tGg?;+D1aNyDK%@M$~R&Lc_Z&HQYu*%eyPJ+(y)NV?x`z z>$cm78gGnRZ%k-@cctdrNN9g|rS{v1*7tQ--)RFJ6Sfk(z3D}5j^t#<)lLE9B+>)wKo;dEUB?Rz@Ax>px^m$yL)KM z^87fBoED#V`Z%K)o|}n9Fvo1ZGjrlsWuGAy+)wSQyzOSVCGGq#R6UcJFoA`cK~P*o5cZGwRG|b03=;(0>HJOniehtb2Q9bPA*KMT-gGZhhnuB z8k&o5BP1s%&P9JGoC(M@o$a(KU@pRzFu@Ld28Ub`Bl2iW@adZgeHL@E z6B_7eLcCKcI|8#fRQ>z_hLf_Z*@7YA$<=c~H{*OR=;TzN3%XbefC-=juI4ZoIU3r} zaZfJHgxm3DGA8c7$YPdX11AQ#rZ;H0~D;+@TI z{B%G!MbE!eUp3&9&~vaYcvLXl4K_4&FeJG9V9zFUH{r9>bkhaEqNkG&0O+nZ6p*yq z#~jo@G00JO6xu8k>#U55Hm?pd?ozR%eJUP+HNYFz&^C#1Oi!)vyeOOuFd>O4W;B}U zc#|J?L`C9cmuqUJIycTJ)IAOWy8aQl=kdT}4gj}?d=xee08-ZFbF8-b9P5AS0StS= zL{R6MJ-UfAhL?@JPc=sO(#Gh<*%&Sj&W|ywLtb^4CCB3BTfE$hR|N42B3^M;LFOBH z3mIZxC+YoUTX%J1%Y^)4so$>pJ#d*&TU931R+S00Rb@i?c~*0wKT1th;-%kJoBXcY z9_n^m*vzLc{E088lxPIQOD%S6KbpEOT65Pmq+n(Dn9z<1Do_&36kdn7Uu&i zwwMp_?7`U#JUHXX-GC+Qr*6#}9DNY5M6EHy9^KV0ILId<`N5qj@WCA;aESA(r&m+? z%&sgrQ0DTJiIGLIl@Dtw;kKY`>DR;abz*TqSlQv7s`2g`T4ri za$FP8w`Wa9-=mtG!_kei0r?3PxeEZ;dx&NlIYNs8TQgH;TH$o4hfi2fGwOX(jrR4h zsvS7A6|eNgD`D|U@mXXr$Fm^X%xW0pJ|Wr1rHb9Z47W12DTxfEW8= zqI32*2P;9l#ZYq87zeO(FbVn%H&Jq0oTER^NX{2b8O3wC?$2@B4tM7hD%~hU9&VE- z*v&BSX~JnGtIO(pP*hp~W_tbP#Tpb;bcKS1zX}ecTVAP+6fZ=`JX{HW_gr`tn zgwpajpA6b913=qp)otWR-IImM;Hak%E{J4e{gqMC>_S7GJsQ4v%NIMV=Nsr$c)Bsc zo=5P;6Y>pV!bc4t!xIOnK*q%#nk;YDu;9<1Z}{CXp32ChsRf@lMCzL+!*I(4CbRAJ;_bc^LNr24V~?*z7Hp? z!WgRmQ49$_o4}TnA927!Wzx-u0PH_>a=NLGpbI{TK%;5ZVl~wF06Cw~W|>%LWmL5J zH_2)2XrGFI!y0I_oa(kw#OnnVnE(1h;R^s0l6V7vLW$lsIqm^S{M+TKS*pATpzgl_ z@g86*ZvUnM_)!Dm=}tF@A251ygZRNDCw|oF`c)Ip;L{7w0_cPIIj0-M$F1Za^&&pW z=&n}c!&i2>^85m1y8!3iLfEW&TCzuWmM@Y5r>`smMU# z9P~Ae9P6V*RQ69>F8(A)8U$sAXWTwSxMnC`t|L`^YNvj=4m~!RQ}iEzf3}(L>!@Ve z>`|&IJ*mY2S(bmVkFvEa=la8wBM^|i&9Bl?GqXgElx~VjMK&cyl?p$Jn8$Ml8pi>} z;ZbEW7a);q0Jz#CV!HgK6NC7ib`bgU$S>FV6;y9`E23mof70o*IsI%_oEOFqi$YTs zW>x*vQ0iwCdl9*B&%^O+UZd3h3wD0Q!cmW_*z}K6+4mBT8eG|aVVhsBa{y$M0O&nY zUi|gTb*Pao^Lu8FLJ~&vV&7i&gwkCjN%eT@B(boo*#Q*y#N6?$=?rIAq?I zB}uwU{=n-$daEpJUZ#!99!vE!9wO!seJ%%E+VwF<8uE7KqIZD$SO6}!aRU}#uJa6b zz-QAgNc^1B4dUgl+QLaq`DS280|vIVSNP;ggY zq0YtNE*Qk3Y_GnZGBu`I!yCG4tt4K0m%!8G05g6MM629Jjr%a*>!h6|4N$Ap!(n&@ zMw*l#ab>xq21P}-bVzR|Tm~6@ba6p_coo!#*JZ*{{zUxK*?VVH?~LmC8b#{ZJn4Ho z07!Kiq)N$=abcqI;>L&?n*!{@gan;o3hWc{*#dtsk*iO)!KMf)RkCqZV8PfQ9$6lrKNNlCmsJqb^X%F~xY ztS2UF%ne~$TqJ3LTL`I#yNPF5OsPD`mF12a6cyRhA-$P!IEarfE~pQ$g8J}EWx`Qj zTuWx}ol(6rs^`T;^&tRUPSN*4PRcW+DkVq8oNK&TT-5j`z!nz?I@99H7GZJi0)^dW zp+H#}7T00WqKl%D7eR0_fQyUx5~mx)pTEHu7x56IyIP44|B1^L?IGy?)$H<9(!YaW z7`k|Jf*-tH0@RuS^nz$yJ@7kFZ}@<`HQ;?^02T?+`T%6yQSAX@Z%e}}EgOZObX%bhqt(qx`Pz@0(U)7THwaH7Diz_gduXs5-h!}_vIY{!8X+6a z5H5`Bzl-!YK_A!f8F@CxhiG^jpsAMzx~yzM!>_FE`>TffNkHv$2#30p88Wil8C1n-PIsI$LUt$%Z#4fAimt?4dNS|ZY93y z#`1_f9C{>e!0$ukc|T1f1M}lkzd(e*t637}M8_iKX%KDv(k8SyG zNPshk86O|wh2u;b=(F+(E#IfM@2?_iaDAxdS}S-m?!QDNuf>7J_BC6vowb$L%pDNk z3E+`Ne7DmL;8mfU|+`1VHyapwFAzNrs0QJ+X&)bpRHdy>*wlAicFgf5pa-A8@14|JK2*_+(9N;S8l&G0d63R)ks6oZwol zWgurH&4OXhf~#>3+N~E84etorN7!|C7@aYEdOdPIsMK4-57r}Zf@<-q3@;4Yy{!$Z zJ&h3WSdSb8>ZmkAe0n`{J*Yd<2=RmUh+6Solz$2Ud*Q8E({}?v5epL${^LA zuoG(3wsVaadpk9rw4AY>lVD`5Uc0`_7GbadEfgM>g=X&tbodw6Zfv9H9y0to5;@wE!EVlZ=M>{P!Z(o9r2vqePR=68ZvlPJ zNu@^z_2Q8On|->dXJ3{!-&_W4rZI9vTQ0Wv3Kz-DpA@w!<11VwD-?&qn|sU;79}eb zN7st^UP!V+k>1##_=X$F3dIX+#q3eCLXk~kgJUt06^c5rVra<<#gl7~IkaSjqUJTe zTt~7(QHODy8OaL8*V2r~Vk9dR7s2FnX~beAD-<`V6>~9?6^dNL^)l>peMy5mo)k!H zSrxlrK5)XzbDw`@|MDY7i5G&AW1pN~QG1fV&k z$CGMIiFynZ%q8lT67|-$MUsEsJ0`8k+<0nnV%QjodJY)(DOg1JP!Qlj2L zfa2vk62>|=Op3wjE)b0cH0QKyQjO-+W1L_vQLmh+cRiqZxsHU$wDVLi2q`AS1a+pzjC=MYlrNY zHa@N8N#KQSd|J!Kz*{F;y2CKOBf$TPX)o6yyDOmnal6;R%m$<%w<9?R5KPE^kTv97 ziQpuQzjrQKDH-ufNPM(A81C>*;KmBLwjljO=ienyngwF~#TCKRFOw8cn(4@%G@Ah4 z>=kEA$dez7lk@YqIX~xRC;!F6n$Ma9i;J^G=U8Y~fM!mCsry|(Xg%2z0rijHvDg79 zHhox`B;yDxe1({P$vc0i6u z>mSEw075xre+;NQK)dGvsXmgg0D=iw_PMD83f^A_ViF&<{-mb@iVA7?FaXCF#cIP?Dc$cnnN z0M02h=agJ&aVczn3b0i|;tprpD-sU?V2wXOT!E|}@Fa;I2Vh`oPxUUSc`dzBMC}0c zMdD;<+A9*w&3%1Tmb;?7aaQ6eq5}Ztj>OT9Z~#*0NyjmH4CwUeMToX~%LB)>nKO~R_b1scDR ziBh@;O=jCY5=Iv_4IBd7gBUC3Y!DZU$&SL2l0!nsUb9<8%2@+RWsQ*Gf-vENk5@@+ zVxf!%;D4gLZn!+y1)mX`tpsq6)EWRBIYh$%K0sa*n*;EKnkWVCuwuf&$G)3!$f2XItTTm0*X+GG z>X3NVCtf9rSC!%wM7(NM9II79j8Oz*_lY~~$4(Cu{=}XC zarU@-TvNN(s}ZH{UN1*uR5xw8&0`y5FW1HT0Lk#&VZ-LeQQyqdPT^Z|*h{Ffysa;6 z4kYMIXLNZiE^1q$;5%2?PWDQ%<95OfQ_tEfW|7u$dsUnV`kdLB*>-%i#b+K6DXr=8 zu{-$#5VYla4}D(B;`TICuq+CYt~)CLlqNt^-w z@6_2Ol$_6ELD=v02PgDIK(A{7)qX9ODKA%0?pV8WU{GV4HBcD6aXi%c^V%L$t?{Bp zYVhnl5cl3Zuj>K{W#Z4D5M--Rk6yl6u1lh#^`*a!bB~CYp$KL4|ti*d5 z-PKBbWs=M9v(VkvWYb!{34C^U;M?U~@Pi-Mf=K3J^@l9-lSj zT)}lOqy)rAy@gqTWS0Zfcc!#E1(5DLNlpU<6S6G7 z>CRM%sQbAfzZX|R8do>6op&?aIiKyyZcAR=xoRp|wH(C`aD4r;9I{&g>JHHEJAhOl z$%%l_0kZ6KQwJ1W6)FMosyOTQz22lJ`=Y`d5cekl9<{_bI^7`t?OlG<5@iip_Q2`6GJd}J?kg+<#SC6nE z`vb7?PXs#GNup~3nAWz6jcPH!U`Q+qz#e}Rem$j%R{{(R15zltIL45UZd?69vV02e2 z@th=AbB2OH&t%hDZUTNW(HdV5d^;crwft~0fGtH$Fhc;E4U6v zB_KZPjfXk5_gmM&>45an&R?@Gc+xBa<3C&vJpC{!@uV4E_M}-Tc(YfW4IoQ?EKbhH z<4RBdiqpks4a#ET4A40@NF^CJOX}_o2(2YM5m0ZIw0i=OwnCE60)h!ymfy5lDiL)* z7v!f4C8Tk6Bing5vz_zVuI#qt#b&ChWYuyMJHYW1%5un_38*_jyI%rQeI)M$gbt8p zpPM?M;Hppwh*!l~ukZCHJ=qr(w%mhV0>Gn|c!1Ll;?0eo+#vpXk`r(3bSv?Ozx5-V zcq5~`8pQ2Rw-VoMbpF=X%CK7xfUDtEVs1L7#`tZ6;ILcqFSvGsell$zwGpgtN zIjQ4(LFH2bAk}4_UDCho3imo1FYa}yF$G{>tRX>Xm;(FOR<;PAjrkT74v>WcWnp-r za2~YiqG%+)cR3Njqk{MlryInZtmbn!A)fAZgZKxld3%Vb8jW}50k807mn-T*kWB_OzsH2K69E0Z z$K-m1;4l(sJq_61=C8Dd@s=>Is4e%x{viNn<$0KY00^JV;z+BBI%quINf~pLv9$qH zg-*mTj1rlT_-OYyY}0#8NInhd^&S%n7lOaO-($j&Pth3{^ymWpT+ANuzM4rPrQ)kEMY+rrDZyXNmecob0B94XgJ3=VfzF9~?2cYQ%B^2!hh%YE1zbhcW zV}#u9fbs<;lXdAWn)bjb6pXDE0qZq3Fe721`*RRxs-=Nu%(YTi=dZZP$H-3 z*v=bc?a+pKiI*|U?@!Kp@taYt6$vVZUHT53MD7G|QzX9I=?3w8zw@gk;`fd2Y9*fa zdzTZ>HoB{oc+Wq$oOmyzyIP6A@vzI4>!5q_l??zE2@!{J9?LH%VeBO^;5$-VwJm7I z6;FEk`)Pz1l#n<8K{QDE7=R6upnDA}gEB&UQ-t*JBBl_rPAuveQ~iYQvnY~)!;=Y1gAoc|!cQVOtp>URMj)f7$vJnO9zbJ)J=p5yLyC{#?R)vUdO>Jze zC*RhWN|U9k6JNG5|EZHT-VN~EDf}Sd^g(3jz7Id&g`2j%UOfUK-pfIa#Q`7nf)b7o z0er*@N;teSApg#xy~9K=DB%#7u73Zod_f7@voxUB+eRq-BB1vRN+{(@>1Co-(|05; zqb@)nFDRjyM_ykqDABC+?NoEr_o!y9?@=8FoUHoT&dUXheH~P}Ir6ggy%&gH2d!+e zgP*r4c66DGrw6tL{GD53TrJW#ow6|+*RiH?c7+|#xVoWn?l0_t#?=pvbIV~DG_Hk2a)iDoi$VTRm@FO9-i+QShrCGGoK>s5D4frW zz9(_xzbXBOk&a766#znLX!%xJ8WIjE3E}0N4-pf)cXF0Q@I4 zm7jBTxC;PJtB@^TP(p?guolw`N)#qbnq%S5zKEqT*v`A^v!XEyf z4eqWRY$Kt?-IZEwBcaLNm6~iLq0QZu+H51C(cP6AZ6l%8-IZExBca)N-3dC$X4{C` zZA@r*ccq5gNN9O?rIy=>nr=*Jdw1P-8&TtpQR|Hf&F`+%d>aYv$8Wo)_S=Zo_kmc@ zX#*S+wi3LPWIU#hF>z#!v904OF(h~hg*!63IShcs$z5+QGzTPI>}`r8c;wyWq(WxRdIYRApw5vG+GY-UIV(9e+F+5BM zSO};U&0&ZY?Ks59Dj>ctM(vmZJ5EsiDr0|}pDM?JujK|ZEVc<2;}ak2@@Fek9(ylf z=1rf)0=^%s&Uaql@e+HnNM|}a)$#ejwnl9cqa)g=| zE(3Ek%v(+_Orl)b0+okiwH6whi!UQTPEeeS{!Tb+AiZ?9)27h8AF~Mz4!I)8o3*mo zUFFY4EdxCM`$&NxyaGb{+wKx3%RoP%R@02g@!sc2>J2IiF2W|2^t#CB@-&`z|u8B3k8`jV^ ziBMpEK?#Ll0ho})re-vn=o==-j}w#F#^st?sq)8(sk;Rr{y6caxF4M9w}yNaHUQVS zxJ#6E`5db)KF9iBdH};-SR#DxsGB$xeP$0A0Pj1UZ4Ir2{8O)W)&|FgpRz$SeN zg5+30-!CZP$gzO_Ur@r)(*gaypoD{b5|SU>6)z~^5a(AE|0OHK- zp}k*GgW+{AZ^~^%o{W(jJvRu?Pxu&N7QmmF$e(k%+pnLW@YbIZyi^Vn7nI0-Es*!8au>$gHj%n8t~w!iVVtG+S8vITvFK+?r2rZ|EL@M1qqbj}{gOoD#HO_ZD#=je|!lJh^L zjN-Xm_vcv0;qH7wr5k0)!)@{eyTjr=O*qZVg6A`5H5&hV*Qm- z(d*#U55HXomy#*X%>cmdYHTec4Bdsm8hy?_GqUtcJ^OhOXZ z0#NA9KtFd$v`ZV*3e^yCKdUtHcweE;g@$F{x$*;N4SHID%ez%a-Ifu=fnF3_z`-UIYI zCspPFusPh!N7H<98y!tW1`4O0(=qypD-u!JKRLPh8c?J`P-b|>?L&migyNkfQpG25 zwpLQ~*kn%8wgCULvb~c;mdzfen$nY643K5{2k0m}5)ihEi%}$do8Lg9W@d?UmTrnl zMK&cyl?p%hm&bDk8b<~kzPwE44J7hD02g>fOc&0_Fo@4-2azw2{7#ZVkSz>=6;ZOP zKehDPoPIVd&I{v*MWLw*v#Ne-DD^Xny@=em_26`4b6nqc?*Mi;0FHkAl{Ee1RQA1u zqXt*DU(4oqlH3Z}T>x~EC@=o{og~!AmihG@4r~fVXZ*6}KKlM*#3!Qb*Oh`3_0gq&qr^ z`Y`y=))0H$q54~ek= zh=|4;*+H~8Oig7Nh~vdv1md@1o&rJdrY84)Kq`*|yej))BC^i`>Tjz|hvC_P^lcTA z=L3QXS;k5la{fDb`40ep$)B(bKHNZ>^?=`F6nNDJ{^rr(SrZEp&wgy;yy>epjk8WB zCx4`w26&67@};j1h*zGnE54n=U>)wvlKZ$|a>gR*5Id12!~T<2aMJom-2o^%w36&1 zfcm=`jC&FwJ#-*>8X%aEWyGfMW+)M@%G?d!_Agl}A&tkR=uTbDc0Oy_&Ux9XLB)4B z4n-*^0?b4T?h5NWf{zbw+o>YY)&Gpgs?5~<_jiLGhCB}jP=7j+!<$ha5L zc=0TR8Xo}cUW5dlp&I*6>cwMI(#OFLl`Q!%i zMMihE5`XDWE+-yhG`{r<{N9r;SHO$l<94$fS`oht!0LSqi0UAT);14AE8?LpCfX{A ziMMev(Yr}Z{Jx8ccKItq53Pvz0l+uWkx6_#@NF(8nr4X(tu6z8BGIn^dja`E?obqP z5&&0-M5h37jI>vDJKfxkCZczf)7P^A=o8VU$<>hl{9O*mvjM(B_p6RThfcF*jV3x5 z06!ho76`-&;lIBWK988IcnU-vo$=yC+d;><5E5%*FE0qPQ{L|XqhU^KUG3? z@7PFYc$FnPQmVLeQY$#>uCN$2UaWd*TnMmLPlC?SA^WM4Y!O!dDNx{i6!+{|$ioXc zvn@p+w#NI>Un*Gxzm(Bu=%-RM;*){qSq-zNF8nM_JU2}Z#|@O@cLBnAjO@dJ`qW3e z?EvY-MzRACOvrNCG@bfl@cGg*WAOVy^B5)lA@Cx0$W3e62l(%aUhdC$k^rF2<-m*l z#p$(x&rS5NfLD3k<->t*N%Z5uoLt&+3HZ@CttB6g(`;eAhn`YL|CF!xaWzbQZ@pR9 zjKhU3Yg-e5Q}1iLgD1^H3jANkgIB%aAK3%EY6d@>H!-YxDggWwdx9r@lk>mZ3q0xH zJAd=u;MtoU0MNhfo8U=La{k(HfhW!0Vf>tZz_Wi3Ie+oK;7R|>`KkMXC(Zss|M306 zv&UncKknP$Ngv_-A>RQ{nsWgC@e{yv9$s{Q-vhvto*#37@lgkYC(U^RzxhGnIah}| zzwN=`NuTHZMiar4=3GL5#Yx~fp93(D;MY6^Jn2=OU#1H@Y0eeK=Vd?hy!rfS&&Ig- z8@gN{;BCIRMs9Q7=7;nH&fENve#&|4Kk0usZ}UU?1Ltl2NH6q6&WH4}&Rf2u*L2?M zA-$RNRxjxtoVR|E-rafY7wH3?w|}>d1s}}aIxNLSKR3`JKq&j-LLFNPtw}R?KxGT)Aa8au9;i}$9B|&HC zwcQnFi}2fS`RX?a4}%rcj6dwADa(ZM!XUduc{^>db;Se zi<)fb7pd9KdD$^hrcs=Xc|{w$L8Um~96uKj${~9Npx%(5g3WV)v?-8$1rSWg(sR?c zq2Q{Jl~7H*GS7Om?6NNFIWIjXLi^&d*EPE4n@X`lj^A2VNcR3%Ap<@FNcod|91tob zOV3ReD!3}5BdUp4=2>r+UC3rV=cOlkQDM9z;}svb2Uf^qTX$G;up;g#+5jPSvKs*E z70s){L4dSgNiG5iCS)0p3qy-Le+*t>+x9iiT8*6>|K8 zvO=;8;BiJ>A?@zY`IEd45Go`~&rKC7xGGWt;+1*U^M^56&w1%dUQ`&Lj{N{RP>B`t zZkvlCRy!1BZ3+mflik9qO)L63*xzWi*or1O6A(Q)+Z#{`)RWzhhtdQf!mlcwo9xJ5XbU@0V%USIZ%le-iOu92j#Ka+o5|uAf!(A zkAV8B<4D*aYqi*lCV3Jdn2=?ZrWLJ3RGpF$uY|;_s=E+9J^ZwXaoKK`@!8IK*)dV3 zQLJb_S&iMGQtSZ7-voqm$bJB*SM-6fIRubqljL^+!GtV5H_f+#t3p;nHSx+k>-po~ ztmnM+myRz*W9#R@sT7$Breb~!*@A?@}Cr2I+l4+th?>A9&w1y@B%K)f=~ zdj3E=>p3qy$%_i(Un$L0Fd@q*O)FZ7s5&JhUI~d; zRZk;23&7tB><=>8&iQQTyzH1L(pi-P~jt>Haa>y)9U*8%qN{9NqbO$>HNd+$6?ZEJOBM|@LzrgmsHQ% z_;p8s-wyOo|8D$kM}c1*p*ID<-uOwNuMIruUpQ~}q*)a7%|B_TulWA~JwKWS-t?~p zeVg;<{|?X(1paBz&j$W&&;wq`_CEyubl^V#&54kI_2C<+nUkeFa=*MU(o??0p4Qxi zPg}H{v-u3bV~I^+BSDW_(T184yyb=|!WW_6C@y&&!`?e~wU+1%5=d)kuvtQ@sSF5c!wts_Gya2$_ zyFCuuF#vvK2k2cVx!%_YKq^NEg6(nzSZ# z1K>G05tpBRR&l{+=4u%NaIFhLJq5tf@QMT%37Ge%kl>8C-g}@n#}Wf~Lr=vG`f=w_ z4JqzW7`v#a(gtfDd0cVo+zA&{Pt9@HPa?6(T$1f z7r_LphPiHJVMa(b{6Sci*x!IPUi?9r8Y@_Cxb-AKXZY6lQTDd4Y=TimUl1B!l!=5l zrIlgM=fcD;05IkYn8}p@#{3(^e3({aHbMKh1Q?UO;&0az;r?(70p?;5SBp_RO}p7@ zo{izevMOV80dVv@q&$t<}8n;a_!JbUM}*o zAo|Fo5A(fiB?DumZ%nf~=A6pY03f9rRzh}_8o|&-BdBqL2~iXYI>Sov_rA$x@iEyv zO`#7j!HmvhAGkm8*!M$^I{+`goa4ENXAS3cq&vr5m~-izE{mMgf#jSTqDwzsUFeF2 zwEU9R!A@E}Ny{T?{aX{6Zv+UJ8D!f5_4O{}+yF?|yCiQ01QW8XvFYAc$?D2N35!?K z;+42~B`;nDh*uG9$ktEP>H0LKqwC2W$H#LV=W`tAa~$UtNBI}mnUm_^{z}^%%=sM5 z`5eso9L#wIqu=iWa6AmJNSp+~)e2EM;S4WN9ExNX4D&~TF(e)bz?_KJ-X>RUV-)xl z1egiH!n^3miqsPT9BV`=^7~U%CQRR-5+c7pg^_vEaC?PtPBC~2{e(r(RsYFelO2tX z-548Bd1K>=Y-~J5jjgvgI{GO9mp4S8u+Gbo94v@Zp6^d##Vy!|`N4i5-;vQI)vo^7 z?xgk-{MMS7?NC!Y-9hDnVFWs}ysl++ND1kBc1~ zSNDk;%VC4VdXR^(4bQIau?=gysEr!5#}B(8eSRe=tA$i`ip^?DaZcJZ+QD5*Dwd#Vc{~N?yDQ5U(OeA=^*&tROWAd+8^-*H;|nU+k3=Q*a#59hE9F zM&%fzT8vR4#>l%IaeCy3wA_%E7t(So4{k3lUEqz6^>l z;%TUPp30jC)q-6Vw-Smp7Zx{fFwmOa!?hilsIf6LaEQu9I9eC1?Qyhfyf|8^L3?aA z{uWBnZ%g8_THg7Tw<)rF8X>uWP}pvEooagonW(W6G*FFPgu-5{ z?NOMj1D#mUPCxDe*eC(7)sWME9b z{KrUC9|m=tSg1S>08*+v-K2ln70TCmQ9dDR@h35BzJ{mi02@)5Kg0HA z05-!bdj{I?=aZcu?)>NBrjz6@y>zaw6toat8mQ z2Pa}4CJ)gWa0L%Y#Mq|7=x4b6VxU``B)St|Di48p(d9&MNlv1l#9=q63aNM3soO|M zzPmaXYx-7zpFsDkHbnM2dNHcYj6!AI)w57o!23$XwSZ}8uSS6w=W?QxT;5Tg2jVg@ zB(4Ua<3u;QyuDJpESwr{A`5j-nhkV}G;72yKU2C@|}R*inq)wn3Hsji;6Vj%QVYg{aj6 zGOU#e7UL5iWb$VVOCEc#Kj!TXz)`Ba$6_<_jRrqOogIOB3e~X1Sbt+JpDnCrFeE&= zdi~MOHvt%+lT!g8>EbyfN2qDxYA;8_gyiJH?8ud^FL@{yTcM$vHb8!ypg0%(?V(y; zn1BV5X@7eq<3L3brD z#)~20$<=c~H`n-FFq?M(mA`lX@|MUX`}rd_vFG{$d$EU9*VgrG*r_F_~Ky{ z=R*5C8X9)@36(Zg$itR8!8T6LewYBcu>J)n-L(@N32uDe`Qk#L&8(2+f2(d?SwUwb~gdgP+ASPTt{lt2yN!5rw}?T6Kkf7ip~}q>g-a8 z!aXT=_Et>$+cx#}Ql*HOELb{Idsr#AT4P3m;6;lu@=EpJ08B{Y4*;BK9s_#ZNvUd- zzv4)(M*;Cy99wvH2k_>7e&Ed#E&GN0k$oO=oNA=DbW-c%CR{_!H{l~-vWt5mO6Bid zh4Oc{Ylc+*&h>UkOR6(xX_Hp3;)96hD;OorE17Kp@IU1K6S?L1$>Hef=_9;M}KN^C>zAFMt&< zvf_$-7De$ak7f|1#n)c-cQK{_FTpM;k2mFXxt8xLsj-529zkau4@J+e?NPMGi=wH) zlm@mO+QPeM()6dh%4`%$)J2PolZjm4!Dtj9J>w=h77$FxGFH=5@bAORF93Mje9c+-BpYeg1OB43!K*g# zZ~qWHYhoed*^l>~H+|Knan{M?UqNGo_eS5WtEKxie|hXM5`$ryKQK>C~*$sGW}ge)UAeUeOx=rpKg#4923%>}5d z+0JJz+c_^gHK_O`*!q~htpMT7tyzbt10#F+=y!omb&_3Q8UO{xKF~>pk-2`0@vHcK zMyW+vvp)N-1x8wniL^>2t@23gACItA0HNt**83H=QOq+@{O0)SvbmbEn0#q_bZ?y0lGb^=H36p8YzX{W>qdv||~?JS!MBmoe2Q=!;MKNTRei zjj3qGRbomCXN+PQqd@Y>nV?JhAuTtg<%P7Ikk-HGgRAYc_=xf3moi_Y^|@x*RGrUw z@n<0oHBZr9xjP*d(|^Fb(@{MQB5l_B_Zjca>YY)&Gpgsaq||Z!L*MrTK+1EtD$0>@ z^3r&5mZZk506XWApfglsmx9?MoF%V>!cS$Pu4Q33OTGoIe*$I9w&j)}8(e+78 ze3Ofb9-QUc#E$}?O*Cb;i-}JIKumOD5fW)D%uGpm7_(jsOyLh7Q@EnzBVW0#~sq@ldDU8^zTo12F->g_Xd{mL5V z0KmV00eI4^3H+-Uf>&MOpS=jYY6HL3wcuG_2LSv_7lS9=<@{qm0#Eu>=Wo9RJbN(5 z`OB^VPkI^D5Bup?f+x)$fuC{}c=leGG*-uk0G5xn)|Dfs$_`?G$L{;%_v59x() zctGFsCH+O`tsc^AIdAon-pqOH2kGsdw|ze!JV-sXe!Db8EHq|bHU z`azmI9`dt(k>>gXZ}n&miq|?i4(r4>T<=?RAEhUGai1a~oZ2G%zrE>d)}?h*%kN)g zIlt(af7UN(ffhyiq7?S z6-K9@<`PTEZjaWbOS#TUnc?EBvr>7+M0LLi96{wr0JwvYYPgxmu5kUL@!|@H8g~I~ z8zVty=)K)cWQ*_%e)&Qv2;YX)2Y~pqemcW)dFkvD4^WO@3J7b0EN=_ypY@~NBeqEF zXZ=V%4hSY>IY&)D>!;vaMoK`uTAB6IWk7O=9o$ZX(vyAhvwplr;57iN;`xi`B+_e# zYZ^IN4SHVzgw)Ay0;n(Ec#b;+po=$<-GE?1mQk86-js-{Q!?U}ka#7v2BN2n7(1zE zJHP13cFxOAC*$Je$19}R4JyU?=J>9FP!8FB0rj@Qv;N*zpZ#PM$^8Mrge*NbJz!IC zRme)HCSI9my;*iyk@cLHo-RL%!(P{Xnr|w_3OPQdtdQ&}u|fvi36Sz9xho)4NS2

    0o{-~*@Xf1 zisn_=3_x11BrgU86S9obw4#-Ws#7xJm5_K<^}<&fPJP_JlSm!4+z*@`B4CLoxQrRS#kR&Z6wN~k7YnP_E-wLh@Sqas|EAy=9x6WD5dFe3`+86V!`)pN6rC1@y zS1KzcyKbzI0apN|{7J3`2o;j0=cWo3Tous~)x<0Ftmh8{vYzwOlf0-fK4IYnG?iFk zUr$d)p{%{iYRT?z)ut7_5bPHNr1eU2NkFKUETc57XeFZRl#F;KBwkhRis|K?WrbvC#tLaS8<6rR`ENj| zkSsknRjA;qNC}8n=2_1lS7kltr6+k&p`N|5Dm^lZ75)*o1W%NA3S^(MI|bZ@a9^g~ zu{nQ|Cj&x-WKYW)%1FUgkrEIuJto12pSZHH2WVN(dFe@BRJaE=={@aigHIm-@9lJh z_~dsvpOYKJQ;qIwC4Tiim&@@C=pOMOpZimR=dd9`DHJTGqhm?$XB_uxD{Sg_UgKu4jN0g-BaQ^A*!EZkY_e1}- z@t1A{KL+%#0{>6YOd9q!PMYb-AL*@}H-Gnn{*&{je-IjV5qp3ejg_BVkLQ`| zab9+cU+hO?P{bYp1(A}RHzz4)YzB3??x`~&(We5xl;~H0KWf(L;|V~RLb9&|>b;J> zHvy#MoaEQ(HqSa)wy|j^P=cCOB`IEsidVAYa~I18HQDbho3-rM`Rv#E?AQ71*LgLR zepp6v94`6}-eLg2v;FVm5IY9|a%s%h$^ejDf5QME<>(-cO!iTtqX3ws`W?b2gFoMg zxj_G08lMFAXQhbocSm6TIL%jK?91LCj&j+rfy6b=A|?brH^lXGL!93VOME+9=FW53 z|2gogOL^cMJX3orW#OE1a84OGr})k(deTg>ol|7z6!#v~|FF*i(JTNI@KY*u%wyI$ z9=R{o9K*a`bEMt|;ID>6@6-b^MskeWf@5&OF*rI-_TXgy$4{JC-xk|pemTb|<%XW> zKu}z6-iJp){TG10!xC}v+23K`N$UVid&LF8NpO=;0Q#hT%@jj57~;Xe`FFEDLG24b zBqC0SMdBtn6X4nX9u(Jyb5DZe*~C4ly1%4;zBX*zb(lpp%Z!2uoNE=Zfjp=QRbh9m(YzrpahN_-UapNDA%VqXa)2a+c zpbcD@n67b^42;PcV5C_cQ%2>V0zgVNOk{S|+z7d%#uWgYND_30iS%zj%cYIVB=Q&hi94JL|3BKk1m4Q3YX2y&x2;iL z6Nd~9By-3Ca;nt42qq=!<$|Dw;E-nNM;ARuw15ku=9pe_%CG}YX-*(m<_J=s_T`vX zl$ns3Luw!nrKbPqS!=Jo*Lyja!Tj_4EuOX3UejKCzx#d9IrrR4@tdIZ$Yi#b&+cuO z(`3tQvgJ0}@|$dNha;KZ3iJsl$5lDURXN91ImcDm;@U%r&aL$0P$$Ne*aIW#mQMsr zCW2)W!P1CeIV=!+YH`S081fc{yagd||9CIu{Hgn(F?>FYOP$`B(@%)4jmv3!P=l7( zP}kKd9ndxv^q?hOF7M`M9`29n{A&Yfu^XzvrDGA?RTMD7`OBeU?#n!<8{I{%!arde z@g_dT9qR7e^|a`Pg~zlQj62`W@bAeVN2iUK7M&J+RIo3~lV?1vuY69Io!oTnhG$Mz z?l)oueiJN(ZW%~^><{>c@_~5zd(_tg@eJXs1#yS>RZrYe_-aACc`g0kgym!GP2Qz# zXESkI5T33Htswn&eY;tYLgX`3N&T3IvPEBd3648yG0V3&8;_>ZUr;p!s1 z3Bvdt9aB-_Pe3BvimILjiEuDNd{@KVk;42Oeh-3hOxzK_Qcv+Ekba5Y;;F=dw}J3- zOTSW2ff?`xdhADjrQXtHjg@SmZIwGvs!ewvTKTJTN46Y8wv0@V{(lIU5-1g(R>l0^R=m|l{7Bw-85jyOAj z8Kio`0j4JtC&2>W2cas$y0RbON@mrC%l8&t>8GU9WyBSKO8q$O=MzDCmpQJ^J$}8D zn=y&4L8yel1wad1>o#eL=%#&2o!k0m^&mWL9@Y-=a1A*nHAF^SOHQd*;fm)n1MsQZr*WyE5Z_R=0W1@wgI z99{1TQ@zX~up5VqF9b4L+Nc}`dMl1$27|Dd7-RzwHjp(GEWHkr38iNej%smOgB-QH z1+fUFwznb%m&~`lp<#E2pIww_w7Vqrq+%fG?HY7zVbP?OrSr(*$%u=n7da!!h{Y_e z#WXZfPi1@&dpYK$<`8H;Lwq5S(IY=y%Je)>+fToDLFhRzgKa@r6b9g)h1QmgqnZF6 z&-J+Wo4<72B9z)+varDC#$0|)?6^e_-C^7Py@dNB-b*a3g^-rHAS*k6EljD+$K%Z4 zfrCSGOnna|;zksK=HD}c49^RknE7yVkE0Az1);kP(junA7=p(J8cnYogiTvM*W=o3 zF49?ZDz$lB4C*`D(C|v^f#1nKNXG_M@vb+sgZDN*YhboBJKT+CW_nVi`L!UiAagSa zEg;-3`Uw;3WPYJ~TOBjycjRe159GfizZml0Mb}w*3AhFB(f&2-KfBSr3B7w4`R!=d z;Ps{r>65^w>1Y~&OuK>*g%Eo&Lhkdi7bEJf7x_E#^rSiKw9b(?V_*NOo*3V;X>VTPJPcqFPKwvGhI}$jmp|Cw|ymS+##X}(3 zo@5xzUO;7!_WT9jsI*6pciP+G)uv&GoDv&id4iwi(lA*Q%rSu=I(#!*d%b+hr(y3t}DNIqmE z!(g^<*~9%T>a{Sq**vVjS?SKNDfs62R1jbG5~nF2h~F2!7KrDnJ}uUTkUOJ}I9>Tb z{EhInKzvB`CBNIC!(V>2x*mi0cr+tEp?n~2yrb?N;wHjZ194O33*uLW&#U(i{CYr# zvz^0xDEnmqEupo<9PJO1>wyeS^>8ZqyB5r)be#8v&9>%bk+RaYwsP&-m7XBBmiTey z193CqYk~M_)u$HqfxLax5qDHR5WggREfDusee!EXRl`8cM;xwvAf6_CEfA+gJ@Itq zQ;ZhG92nyg2Pq$j-xaQR5rRPx_l{3idDIG|(cu6Y4pPnbfMl@C0H?>ftcxjnwF#sgz z9~lPI^RXAt$L!>u4tm4pv*u()S!*Qx%c$;6kOU zIVM};1EL+SgfY@h8j0X74uusu!`0}Caj@2H*DqTuDciXy>;YS5J3WOM_^&m{v}@yvuMp-B6^z{V@?8LoDqMeEaNQ_b{L~+fb@Dir^Yt6I!l{_7I%VV8S4w18*AZC$+MZTRyu6CDA$4968r$-rDfF=gqaGG$3WmT4rcjqRjy~tv4;+$w{PjQAU&l*P$mSeIdz9-t@ z!Wbjnq>%{T;@8@*!!h=K5SnD&cKzZgQ_37{ywopROcV?BgA9YYb2B@+e&udBXgF2lLGf2=}A==m^61Tx%RSX%<8E_$08 zW4woEqEM>MU&zTI>pvZA^x7?cB78r9Hk<4=Z*)qOcb3 zlsp@EZgNrj!oV%Tdr&o%RV{e_94ODA)q*%k`9K^dd@T^$RG(ho90B>rs3RV&d?21E zd@T@9QhoB90(olG5vM61h~F0;FV}(Rt3LT%2)Q%rh|`r1#CwIW1>${CPn@rOia~in z)DagdABe9CUkk*4Mm=$<@+k)8Wl=|5u6!W2^w-yK#DT(Bli#M0w-jCf`i{WeL2hL> zi^Fp5PA_Qrc~FlE{$BFVU}!FaEx$RSD=7zcG{lc7&)8}`v#eAsUsruAY=?p5^)_(0 z@_~4i@U=i}SA9XOMLqH4sJBdGAs;8YT$9t8S!D`rrbb`lH01;F65(rsc&X~s{ANPF zDe8!~C?ANo3117ug{n_}k3oJs>WEJ$ABe9AUkk*gsxOFdMLqFfQEwCYE96%}_;|j8 z-_YNj9#tv>u&5w5l-NW0K-@t1S|ENx^{K!WC*PABblNUkk)DRiFGWgxnc*#OcZh;w<57fq0eblizH} zbE1woSNTA^U-()eE>wN;dkpg9QAd12`9OR__*x*osruws`8?JEBjSxO)DinBABdxcuLa`aQBNGBd_k-VpI?Yifjl*i6Q?O3h`$iN7KnF7J@GE( zQ%&>$tPg6FUZ{}_J+*?AY6!nI0b~^y8-{J ztW`)$&DdFR_^%*;w-^n%9fXA@OcQn#fnHJv-R={8D}fR42x$q9KxIeDG_V(dM=KwQ zCkbB*#H#93Kc_&R8g;~J$_L`D!q)bY9OAXd_lZT z_`Hu^gx{MW_fdwaF#Dp3W1kbB&Y=^Ne}0SMJ&gB&9t|XHDr_4qJ5)=!Otsdt`4AU? zc>NF;Dj$e{622CQPpLl5eKF)EQAd1M`9S>W7j*8#X5p&^ar3ArZV~lX2gf%7m9|?S zDEdZ2Vn5{r@o3>|f%uK6Cmy4GDzqK)_^2bEqXYANkROja;uFdT;upWDjUj$X_-Y`wC|?j;g|7wTaMcImA<7rT6NIk?;&)UZ zi0#U!THZ&_-J!!ZvIpQmWv%6FL)=AFBRRUivNrlDhyz5`%F#AuZIqeDgSc&oCn+C@ zw+fF-1~^;w1@ZQ%_c5kGhgUy@%Y+?CxDte?xj>u+iZ39^-VDO=V)5KT#FFTYr4*zy zh6!_{+A^OGnZbDaSR{WEah!g5XQa7qMc4~^IxwINT0}~OgO z7b+i!n|+D?_yi01DdDSu*hl$-xQp<$K-^XJfw-IUY2}w8-n!7acMaBqxW1^;2f-~6 z2ZFeY#6ijj;(o%{0&#!Ur|7MaheaK6xblHGO88nJ9;W)_cLd}kqmFpA@`3nG;cJ07 zPW8#J9rF07Bc7yuAWjgz7Kk0HPkvJ%PmMa_H01;FDdB5@_~)o6E>^xE_S!>Ngt(FL z)j;f{d_mk*_*x+Drusl^QNAFy3Xf|VI860{c!=@^@mS$&f%r|;2jX$cr#Z2%jYXGt z+RIUggWon<0TY@zRXfD-;)!b(c#`sgI7@guECa7neabi+@|>t6&Q(4TpBBCrh<{Oi z@>>jfNz@UaRXz|uy{C4T*hlzkAof*0#pn-tK-3X;Rz48FBYZ6o+oPU1UilPb3goF# zN1Ud7Al@u|Ef8-}ee#CLsumr*c?M+C8l@_~4%@U=j^Eb57uD_;=z+FKiCDfWc!Vi0ag9A2nw z4_Ivrau0L+M?;yEjhAM47%Ywx|5m~zVcTfhB%xXfTL_!pYMu|H+>Ux`;Oi2alg#0A3F0`dN+ zCoWXJARafc+@xcmn*_p5wP?a0?IV952(zL2tIF;OuMr^EGINv%Vwx@z)AaV||3GB0 z^>ddS=14iD<6n&3117ucU7PKDub}GKytDH z*HJzYcN4xAh`UEUu|@fUc>Cb;mi{bsp9A&e&g&O0UQ0Ur1!#tV_}v{*P`G#nv$vr6 zGy;~L4}|7_R?waW%@r$XuZ4ysl_S`N&N3JYOH&Z1f$(rl(0SxHNGHbvr!w z{6B(l@s8%F@GpVq1WY!k)1jlSyrx@Srwib~;P}4M=;?)pR>=a>hVk%iC%)g=b9!1- zH-dAe>j>lG2h>u*;%}=>-|O%X{8dm5ek95Q}1fhs9^)^n%Re7J!UK z!$^(>!J_5l6Pi=KIJ5G5yE!^uq~sV7EXMqp1#h!A4|H$8vlM2BzRBx*V>fUUqS=@M zxj`Vj8^IkjN!c?2+H-KvJ^5FQNGS3$0ZUJw}>v->G$$M7uEWb2NzyR?g)$li|C$}VPlopUOXaX5}U z4t|<;-HX>6uvwjEyhOdu;@Qkm&pgXZdy^a3&Fo?)vbSTC@KP_YQ`=N%y7bCMaq4T8 z7GXYY7l3#Y5*I2Th<_Bm7Kl%)KJC%Pke5Uq@mb{qvG2Z&R|~`~g|7x;KjjPJMZ)I? zHV|E!T-7R%;m#*J2ECW6lbaqh%xl@G)xgs%nSlTlAx zqI>rds3)Eh^~BSno;WS)Ezj2>9|I~a1eGU( zu$o^R>{jza=sH0xia1^QK>VrjwLqM$`hs{*)D!QGdP_bZ@`9)%E>u1c9}vD4h>xm1 zZRp1!KOS|&CzKDw4foT9CiW7(8i<=JUl7j|z7~k*t3D7fRK6gtKSbkLtq(%?4#;hK zhPoWYo3)uaovA8S*h~QRsNgrunbr)kxvrm_ZUsBXkSl7xCIN7Ck-Y0y%_D+F(BgnOTKEwrLhT{*oQ29W7LwJ0s2YgfY zsneCOA`FPTme@o2K-@@pe5eQfr0SDjAIN>9j@VE6K>V}twLpA2>WP0*z91g_wek-7 zIOKsKH>HDN_Nchz2OQJkp(!-s5w&+(R~zyB&2+ea^EZG_j$v0&PRBs$O1}b%c_3_+ z`vCXLICd$S2UKsn>Kcf5fYR>B4sLhQijJk!M_|@RN;mL<5AbN^1Mzy{@w3Um8={{0 zQ{~fYTn71SkUMi{L!1-Mh;x+>#8-sJ$Me8fRi8pV1NjAz3$+yDvS>zJu6!Ui@2~4f z+*tVh3T=JJ8-ZM?J`npxGh#pG197bIwLm-~>WN1xpDJvJJU;4(Cn+C@7Yknt#7k74 z{ANO)6?Md`l@G+92ww}tTUDR@W<#D6b;P;K2jb6#uLa_Ls!x9NAwLv##7C45#J>q& z3&a;xUl3o7dSYd$UY5kog|7wTHc?O9GwO+ZMZN7w`fVw?{3dG)!- z<$%}|;9A1h0

    Tv4CdCy`zq}h4O*8i}3jP0r&;g7sNfIo;W1xiN{1eu|4XECr3ST zLe$&*>Gy5X<=#($JT=-8rzszZGlj1O;`OR8h_j=fcze`aj`@%mL>+OV@`3oU@U=i( zr22yRm#8N`6ZIBvG2|stM|@WKK&%`Xk85BMzFH8Qqn@}?)LXnhko!g*v7hpRxV7-L zK-@|7>AL9;c|g<=cUC?ScNe}EhOP8>0HBKy~X(-%)uGx<^5HYrLqF z`MnCEPG+$RJ?muX3bXvxnWa!H1Mx0ST&{c|?sAYW9dTFTtAV(i@~I6ikOxK`agg$X z_$}dUf%t9JC%<;c??T9(QAeDvd>}q0JU-U~{yFN2i8oB^H*8SViPSerFin{!TvA7Qrf(vL9H;%+GiKdMfK!SMFu zV7?uhJ>1W+{{#ke%)=5{t0eY;7(GNRkTsjTF9WbS%q-?POBag^!~&^v10iH{R}{OU z0o|{AyEQBG-#Mi6F6|xHYa9p-vkb0xc{Nd%jhA{yi=(YZG7N^^$!~tk9<(!p5k8+hF+$JN zK{7&yOW;26Vwk6;`ZiX-wT!kg#FvB}#sJ)N?x)5|``St?Z30^K2H{pXu}+3@?K=P# zQ3kE0EA=p=35dd4{H9>*o1k-z{s&acWlm|umcnA0c;Yq;T&{c|Zq%knF|m*E)q?oB zs3-0i^;XG8A#Wv9r%3!h*2 z_JO>8)Dd@7J`leqd@T_7SAD*dLmn1&#No;Z;-$jl#}t5Vqn`MZ@+rnr$jhRRxLo-_d|mijAikmc{UVABZD`uLa@} zsxOG+qTUvVwws8qvmky2g!d2j101jH2>^PzcNLl;(l~z4gX}h-9u<5RMP^qM7-obC zqrfnbm|1@F#f47K9b_C|z$dc@2ztU$(_0XCFl>b}n&S=PqYuLy#7s(ilP%Tao_M_l zV!MdXDj$ePd`!0&@krsTfq0zq1@ZU7=hq#*Aol~IF@&9DxO4PT!1l;r4qPC7eoJjT z$e#znjWAf)HhLYeS^@*$27Nbx{;u~Qg&0!>mnt+$5TNgS< zws9JC5+^o&hZTu2DEE^=&RHaAr zl8`OjOD}s)Z#dXc+0`Q(xficl>2jIUKhc}c^|OJh{o^gET<P%-{f_!x z7^a!YTOq;rAd@Xo_WLmxYfAQ0Is2*X{T3i!sl!jkB2XgZ3@?|s*}?eje$teiTAz1+` znX^hZ-*K^cO}n7)L7E%aUnOR`MC-;Fxj2h*UW{2@ zcaCuB^Q5hmyBca2Wi7Un*^Z8d;xAx5`0pN-v^z{@c{4yJTPsYqqD<}@7n59Z<1!$& zkHu0Oi{v)0>tYPTF2cZC822E%wubTI{)wvs$wHzSNN!bVnb#kZ6{?mtVOQ%Kt+_y zn9?X-$$W3D(D}O8@yQSCYV3S7MtItx2-sO^Pvp#Fyz`j4%bY&|Fmue5nZ|&?nyI@# z<~s0bXXB-3N?HsD$x8z=3}znyWDoZcxGM|>nTJha45oepNMdIT_duCrL1|qmm69!x zEnB$MXCp1w%s+qbfUNyfy)gdPy`iqP$1koKM2ED+u%C#<+2j2fM>SLjR|w^z#R zZPk`nb>A2SyK}6Ykb5yfi|>O_u7z-`H!S&g*D_krA1`_Jk6c-l(kne%oMdII<}Q95 zyX#?w@rLRScxQu7I2%Y7=P`Ib4&oyf@d@PvartQKYk~N>@YO*4m+}SiSjic=n{c-zz znYUk?p~>_*24u2TVSb1m7bDgU$$WIoJY1#GBUTE@RSKzrN9<unHN!p4|2&WqOiPGEKgK~MOS>AQx|HZuxcRiZB)R5Fhn|NEpa#8_lJ zQ|l&N1(Lh)n$BlW)VU7`^CWx?Byp_jIk9Re$JA|_BG@cN=xUB*l*Y{xxy?-7;hIC? zaJBK${fHLpNIAF#kzp|08s!gSWe<0MdJP_2#M0?I847ktVrL6?Ys|5rWIwbC4K0u@ zTe#GphZ~pN-x^zEX0*1nM6_F3%jw7U)a^rS7F6C$-7WvBmh+ex8;ds9%>;t2AT4Hq zuvRuxw`}8+e|Np21*dC&m5e;&*+Y#5ZMaD0WX0?qC-2+JL*TCI1RA@&)nvqqH8Y{cY6vOUc<%-wWeUifv2%*<_nSX?7^jI6WU9%_8 zRKG%e@_z(sKk^*S51DXdFi(}tS0(dS$twLAddYr5i#_H1Avu3Y&L5KZACdgY#c0@X zjCQX!4HBarg&80dByyaW=C#=FwP-CHxI5l?4YfC9t-GJ@5{tpTy!mb1>uqu-v!HLm z(_|~cWSgSJL8%S55o73>MNrB7T~nfeYzidT6iBP|k4qf=Avu3Y&foRS1ClhQaKCA$z#H_D5mBxtH!mKZuQz*xAB84&+!++HNV8k}Z%e zTe#G_AT5{N-`S3cnY%90;jkMEf__!qX9zB>?j&E*z`=M0##!5Q&Ys_$UI%Y9Y6YiRBhLAWz#?di1LyWl@y1VW6SU;{IJaEOi zXpmeqNG=*A7Y&m2i_uO_(a6QvxHcJkI(7&$LAn|o_lru*^c@fmPQnD80?f$83Aqwr z#{6Fafh8OO(kYPpmJSfO-!zBS$la8CWZFv`YUgGx*57PL$9dt&YXqOvtZOE7HZ0s^ z>zv8fJCnP{MZGKTHU`8#w^)sLzw3C6z>dS#+6~sKTQQjSb0j;+w!y$Eb8+LIiz^Aq zLZfO(7F{K)RwY|Al`M@)4KjVuJ!47ByJVI7;x4S}y&xQbt#vXFf%riR;2G0%dLuz% zMCNE&mNo)+uIQ}*5q3o<*;o;5mdwSNm^)_4pmFz`D{41Ku;%u#FU3r|&r&kq2^(P& z2B;lcIQzL=1Jg{Si0p* zja5U5rwe3>9U3DYifze1)M4hh>CkusiQHxlakruz3b!H~FF#$tze&o$U7QSq+0#Y# zaJTs7@ZchrZdNBl!4666Y~h|Aax5rqx0FiB7RZ(@T?%*@%TzE z$gS)Mgc=Wm>LiSuT^^l?k@XQsHthizqm2l=BJ`f1(snj;d^%P)Yw~7H-fE%kGazgY zELQyYTFi%P=zny%n)Ut%-%^s6wbVJizsgiw>Q};SE17Cboi*vS^IhNku#otPLGwfo zI?mG^1jbMsi{cvPg5W1)EeOmZSph1Uvr0C#F|l|}VE$`Z#B(d@zwaE#Xe<=ZLNoa6 zWNk2+<=q4_*;-+;6=ky3U~w_Y6*n#eV*6MuwXsNU}U0^ofSJ zf$-Hp+*J93_;ca$+wy>Ss6G(qD_;;F6TTLRkE=cq7b#y57oVcJtgf~R`14>OceeJ1 z*({Lzc<%k*Lf-u3vTh;d_2KI6E`fYk7u~Or@*$A7v-FmW4^ftbyu~JOG09sj@?B$K z+f)t?$_-^yC-cC#HCYsORHVm?J$w@kLWO|~AHY+W+hiZr=v z9!#a%Yt3S-jYV#Jfw^ACcl*83*_q$gqs3()Ou{0#B|S3vch^T+(BED=Sdj9Q zC=9q@W@O9cjttx&c&TyWFkg4Oa5lKaoDC$4!-te5AbAi4KC65n{!MuNYGvSys!yL7 zE`_`->WIsg55!%+$9VV~c);C+uLfd^@&$3;B(N2^f)xEL-CT7KtXs8{ZweB%uR4fg*{o)-wM%YwMWO$;la*P+gvK$s_iS8(aJ@nozT$}wr0BG@cNut}OZZXB%SJ*lwG zOx^9oIwlVVHePx{pv7{T7VgAk7|fm!vWL4(FNOgZv2?>Z5DIokVrL6?|Ie|YWIwbC z4K0u@Te#GH;Kn8QPY8WtX0*1nMBI=oYdQV6p1OS+Y~SwIepPF^YYdDP8|$V4!IqB} zCxEa}Hchu?1CxJujiLqTY9G>(XFR*xThN9pWKLF$J0fuI{tjVe)07?woDD8RX9LON z{0t}kFF@!ger+7NM?rWQFdrd*1p;ff9Q~b)j>@CyQ-`0%QT)EfH#_nB8+oT?0Fy0> zvwNwllKurY}Xz5!|_vl`iZrpSv#PfvDzawuZ63hZI9`S1B199MKIuYVN!dC-v zi1G#TY~gExc#i4=@m%E#;_brcoNpucCeUH79G<1D&F~P2$AY9SWKP#{0?kV|x(hL# z&Nw~dbmar_wx4ME#JR#(3*t|Hs(MQ}7q*{(eqCPq{R;eT;k2u5sLOA$ycZrzK;5Vt z1X>t9+|ZEgabpL$Tjf$%-6)lIww!wd-t+)rel6>w;x9_ooh{RVKZv}|fPS0-LJiO>%*25*<#MwuJc=G6nkI{h{RO)xyvOmRmV+BBedo!Me{hvwOI4$ZUa9GYj- zIn=`2449G=*bjt5jKGk-5;H~jb+UuSb|hhi$+~)it0%a6f~zO}QeE>ylGd~==qUX* z2Z1GU!-xrEoUM8SH;?FTerKRK_T|HlhsMZmJ0H6k{UXE-oi-lSHbZw?_@OW8gU+fH zq&IT+*D?sZg7BAdtM&O{{;vAh0PibHU|KQhF8@(5VC``V>?|5jSfRo7JfAV?+CjI+ zq>D!cTMskG%LFFhSt7UPKBXT-;Ha)L9*}Ij^r%9MZ9sBnl3_4=LdzcRRo8|v;O;4% zveqVvoh{sB8M~qL?xLJzu^MJOGrIZLcu%2Q{{o@0-^D`k$^d&UfMvLC@=q8Y0~Pk! z5Dsy&`Rn(#QufMbxGb>;d&$_JDf!8<6is$*)tcqc~mJ0dcyr1aZ2yn<~d6 zhczJk6Meia3cL7wZXUHsO*a1yuhtp$A=MKYRrKb^n)HDv zop4!|-cDehan_|v(9JqM7|`}w5FUXG;=3T6es^@>F^~M}cF*Np*#{JZeQ!^%+o?7epI(uihO)F6L}BVvaNee|88sSNTBfbrWY+3&f3tuNK4`qTY&N zjIlRLLkr?}Kq#na>KDjv2y?6mJ$De#&Vsm;s@nl4DodCG!on2i0W!&2Z9A*#d%Ae zoHyEG(+2BiE!Cf<76eWlhxQ>&Exqfm328E2it0MoKb31{%h)2f6eE1{Mj04_ey9SQ zskwdz_y<6Eeb8LDKsIQ5N(OC)B3K%;v{WWro8Rt|u4{%hjpH^wSn~#J1%S2Oo1@ur zH;fnzKCTou#TqP$k77yKbj!lagO>#oTf4wovs^jul48T-cIp~Nx@&<}?7NvW7$fk( zo7Q^u4X9gQ>hqP8AH2DzS?wC6iN`?WtHE-YuYi@b*e1Yz=PoXG1Tj8vxU1oxw(+Xl zNAr1-vW-Abtmz?^o_y|P=OMY1orl;2R&Pg{bvtem<3YUh5l>P+5L-{Dz7~jw2wyFT zN1ds9i_!ZGd@T%wvr%v$czmpJ9pFY`TbBUdRINGDK@HooVOus#kEfr2A;aKB&DVc| z7d`iYX9Xr(Kxa3si=D{cj>+*DbQa)BWv>Bfu_Ph&&3PPoX07LvlO1dR-c##ehIP5;gdKs#fICFR%@n|K) z*v(ehtJrvNfbhsz)XBW7La38zf-^>X*2#QSh5SdO*Nsa5p%IO?1bw7(V$Y@tl`Ye1 zw4;CHL9+9KCn+C@j|yK4#6_wvh<(4WJD<3X@YRBNMAX|P&VlW8@#_r4M?h%rZvlT% z_FsUt;e`$p`UpGfGk~uvOJGPB3Q;_$@omCTDN%6Ta}-~*cU*2J-8?EV36A#9F9{o zk1G+8xo}0_cLT2Qw_^sA&5ng13F3+ok5)bqX9!;l#JcL!3;Jo0&jYzu&V)ECnh~#7 zJ`fiRUkk)%Ri8rL3i*FQAH(|-O--addpG4hWy84CLi&930oXqVa_N^sTn6Gyh|84^ z#Gz+VUkk(ogs%o-tMaLoO(Aaq!gpgrQ#&>`g{?ryL)adK`01kE0rGA-Yz<||VQN+o zhbte5GlWM&fmcR7ai;RAjERuX2D#bI#(jK_JOki$25_$Of%qTc@vCxym7BE##B+tm z-&F_x!1S@sdtv)aP<)+1_OBr9x#s{cf^axZB)+3+2HX$?3&JNQ-pPUZDd8uaLhJ{^ z^G17}%;!L`C+rNu?hV9ULCAXqUf+<_(mKCk9b_#`fgAI2mI_grsT7@|peKw~^CK+8 zYE;sbez}sK=E`EJW_IG2LGBcHbLkqvta+-_YabA%c^sxm_FxTk2;dxLEu}fibDDYL z;ToRJb-L0=2E9j|bJ~ksAod5vG9ZT$15IvD$MbK|SzTJZ--z+p`4ocVTz>gz+4cb^ z58G9QW>}h`ZB}IELdcz>!*A>XPFFqd!MnlKUXmC%zaZS&8n(=Jd%>nVeC(czq5VyHicNg(w&65`9#fm|&O4IbB6>OV~ zwdOx5%Ft_z5mJ*z>pj8IJCRL z6a5dY`Y`avgRrKAU%H`<;k+HlOoxDHK$9)0g+!}*G8|)&H-GZxOWypRM=3pEs|Av4 z0`;h1xyUq&&^Ep31!hMRjzIz60rjY0gv>-xQK|NvUR(@r#R+a#9H zPt!IImgpcZnf)_8Y}0k>bY@oh9pb+LVoYveZayEM!39}z4n zpJZpnr&;3F$_L^@XEQ-95FZo1S`Z&NNA(tCTj=%x;e`70r0E6OYgJqXk?c)*lZiMo}it*lU3GqwZ&Q#IadB7%$5s}HX~9PSIfU+Eh`(} z7`2ujjShoijI^r9lwRuy%SOWH$w^j(2v#K>qD8|hEFhkx823~VPOuprb#l`{I7$hZ zgK)0*B+dq@5xF}-@Fp;k4zQNXK`N1(1wt&s&(i?8du5=Nz*ScdEB|Cf{IF``zUnsh zf`+L%+fx6z30GtKR{pNqj>2Kzv>JS|Glm`gB!P z&P7{6^dt6AJ`nd7z7~irQBNGGe2UQud05mDhbte5C!fdIwLqLAe6=7>IA8TPfhS=5 z94HVFU7 z0K{=u+}S9KnfMmjzA=q|yNu(Pg51mb?9y3emwb`iI5x?M6w{@=I;LFN_0;+KagH#z4BeKXc!82VPeopJWT)p*vR8oQ0wr^mjLF@49@vE<%I*0qWl(+imL08m8uKOa14@T8-&j`A@<8b&y+jQ~3*NHj>W) z@j@cbRXz}#F4T=rY!<#+5VweWOGVoU#ILg;z6rvzyao6aOu_b!USQ2>K1OMb-Og9# zWEX+t6+4-Km_UZ1*5M}w(+jc%!inKWV%*XP5f%zFXP~D+cw(>C$uJo7gm+DEL0qSP zhcTMtmBvwb;*|!I(%xj7L?7hu3u5<({ge;HGlj1O;`gJTc$V@7@e1Md`+dhio(e)K z1e#zE3`tMb9B-HLR>JARjv~<1b$2GjSs)fhyjuA{{EP6lKzt_ZiHnslhzE7*(%VD> z6;M zvYNj$T~}s;!z|{e1tf&+8U|X_X!XcDELMvSnFAA@2I9$a4)7f5cj*5EXb5Up$I#jzl?40}BOYlq_d z>UuX^$ufEu*J`xF%a^IXG`p4FX=ZK+WC*PABaB^z7~ixRG<82LY@_M z#H*DL#J>xV{RMnJ>WMEXpJLc_*cQj9_xkv%+UcFms`ch)-}c)jf1?n$l>Bw*2IJ<6 zUBE9Rn&|GrT}I4e^<%BX1N+fUI`b~QW4*Nnb;G8DS(=CE^LYPssQK6XHts^YHxL?* zrW+P6zFWU5ZPga;mkTsi+AB@& z3dV;TL-4Z*X$4DlTMqrL1A8YU|2d-ji6b+2+p#fghFI^xtKu7v`)jPT#o09E^LYOJ z)6XG~=l4iao2e7JxjNQ{@yh4E|8<|abd{am%lDVa6x{H%^Lh*AE)G+z zzS){AS;M0esgmB(<7&$f1TaY7_3Dl{M~tU}8eg5TXfbPNkyYt*Xt?>E3qFd=x4Z82 z4dP~1Iz3F~i|dZhwi8m{aNWumzw+1`wJgO!&W60jbvvb-?xgNzmqxQ(g9V*nk@x~6 z@sYuMRY~QBKOk$N*2LX>ux0ZvoLNnwv}v5X#dOzoV;1W*q=B(l+i>Z2Q4+F++s|F^ z45iK9b+GGgW3?ih5q^9<{bHMS^nPSRczns2Zq`&uz4~snWRLNT`3_(=^bzba0QMIwJIhvqT?SxZ!CF>xml;?9 z5iEoV7DNOKBZ3cfz0}c4_&ErT9oz%idx6N02TqTCZv2l{NM?Vz?s$HE=^;F)T6ayh zIq{0pqYyvSM+aV#@>cRbVDu=&NNzF&&QcFN2o{J-M=LB}{++j`#C|oqN^f|l^NC?r zIFddMi`_xoDg3cB91Tv?Jei%V70O-lwCi+%F%=2!#Na=S0NUl0EGeNeo z$umIO*dOdNShF0qA8$osUTM5|?25xjaJ=Hogk8}+nD)paP#qzCORCCTv=PK(kJv-` zK>UvIwLol-dg3X{7sPGn(YF?e+X-I{#Qw?`#6`mAcl(&LpTy`ah#bfJ9;vmVl!OEH3tzslEqdFrpP`c`rh+DS8EA3j{?=aqd&o~;r3+J77 zf_dWvsx&doYNqPaWbYMMtx+c}n>2oU!F&vaosW+K$uW*z2ev3WX2HtW2*c3}tr73H z!LP8Uoduoipe~n^6_chOLyfjV7}m;Q_pJ!(ZFLw#CqJN``^ zuFW5X+W=6P4Pa`Q;0OetDmCS|^BS00i5thjF2Y?4=4e+%&L$Xl|O9J$5$wK%^P=hx!>*hi!z+zi43=HKY(;ubD$;o=r9 zZrV%P4`*tD})`8{L$u@H2qg*Z+Nx}#$fn6p869wWp;@95}eBJ@Ly!QV}8 zqs)zJ^BRs}oqijECKw)Srg$$!exoC^#dRB+XVW<}&!%%|o=twc&t|}soIo9fhd=^D z`bx|c-Pg%pEVd&FD@@ka6I?y3+$H9RB(1V6|CXILlE9rNdYcqF%{k2jfhBO$iHWuE z_b85i`LN@mF=@ACz~|B_MpYv)XO< z*hbciqAmkmqbz}G#kITqY%k9_H=kGXe8!~f2;Cl&E*=qVJh zr)?T}@6pCfZ$#3ffRntnOoqX5J+$&gYxZy-GXE1E+(@N2qq7n(m#sIYM2z(ZOJoz7 z1BD)O?dkoUPuEr;Z&KO+qbM5o$ec`nE`Z8(hX#wd2t5KBp(X3R$3dQIMv(l4Ix zLx`_}_}E8`@dmqigI&DAE?zoZcr#*^e0a-#1M1wrTE~ET_RII#?1$f)1Y2$=)G7Nu z)-TP`dt!bKeqZX!Fs9J1qzB|JV>NihJo;%oa$01QttykPGLx-K+r@4`|HLB1c_3yr z*~OLdW8!RW+{Kk~i#s}ZIamzLI=C(e^QGSVoe5ueOSc&&E zlvSw{W8n5ds;1vW5IP}e0dGg{l=Q97=GMm#@6pyxv%5y)|)R}10^SE}9$dKtD&S4em9nHrcGAmkwYR@hO5H&sjc z$d9B{!X_X*-mFz8bB5?g63!8J6ye9JC0q-_`>gom@nGhvp0G&RQG|bh5U`_8W~u54 zJE3wE#R;6E>{)NZPF3npfK@)n)E#U^k6eB|vB^)wL2ZN}Ya;Y7!PFmJ-iF(Fq#cT-NXKN>j|6kk~9 z*y&_5i`Y^W@l6mU{B>$GFSlek;+>LX+I&o{#`_`2m=vh7jcLckfa>|xhMphp%3J2u zSVl8t7xT8X#nqB+dCPq|J$hhwkExr32xc#WC7}6vAgufP*oJ$9z>bN#608|=l-pL0 zM;kAlmFAD%`ZlqiEg)EoPs0DR62mEfjt#T`B(a_cv&@8S?mlp14Gb=aZo@2`4ts`q zwn_(Bm2WQ zyjo5<5?-8|zqj$;u^6;29!M@;YshDYd^YU~p2i!3@W+Z;-@+d&vfGTwRzHvShUcjn zG-Gji1LEtpd}~Q3PHzl-0fZ+q0+$ne;+hT~Ywa>?2o{URd9i82<4)I*2Odvc+^5UC zpuE%;$_`m|{!l{kyk5y^%;IQb)seT_$lJexu?=0`{waA#AU)l9-b~q5zJl$OF;8eLAWZ|n?J}R4l`4Ctyt&e^04vJwL*)BKys~+ zVK98&IkSUrl4KWmUF37lDTm-f;ics-7Cz6!4Q7?M!(_ae;rEmRPf|V*r~a7kwLm;e z_-aA?VqNtX;}@`<0zLLE;WQAsd0|JL+!G%X&r-Bv<# z_Xzwq*uDe8LSCFMPgZ=L*6+fa)_M1UQJg5A>gW=yfn?RtreQT^?&7Tr+fRVpUZK?^ zAhgT{HLdgQ2P4*knY7gD!BRx9N@&rr60>&EwuSBIL9P;7y$UMDG^KML1e;h$Yn=|U zko=7SS~M)gtX;IP!nO_M3Nb4bl4F|ExgOtL8f(Zn7@P{?kC%Q7-P%+;c468GCprUj z+Mto)R#5g=Z`^6(zik^S7vp8w5_xHckEnppDj$d!{X#D(;&kDwfjCq7g7}K?`6Kex^xWu6!UKcc*R`;_<>) z3*zsip7_V8w|F0eydenpU;bSIvY!HBMubm;@H7&LeMQ|y*hScpy94$B!J;Q|A5ph4 z<#=J!2Cyucq5O6`mxl2e2pP@Mth(07_qVfWYyafgYM!((FIIFcNPe)E42|S5V|sBR z*o$NgKbva~49zK&wty+I2I-w(8ZlT`oo2&NwOKaYqRYSC?%?ccSu4|^V=Z{!diU4y zKDYf_4BZlte0mLhR{21@^e*aafq0ql)j*u7d_jEfZng38{wXm!1Cisnjkw=#w*kCP z2BH7*+wHCZe7)ZUmTdCR~f)w}Rxi+mX2&q`%$nNpLGpcvpDpgkQVx4YZyC=!2yY z*{WfF+Oa~j@zv(~aIEC|@ax@jeGqbe5Ujqgzuj(SU19*{WsRJXufZ*rHP;q{4W_Hf z=5Df0^L|WG7x}f`Z=xO9PGz%u6n4J_$tghxP#!MRQr379hOXB+vm%gEvUQESn{-6rP;i)Nif&r(!;wORBI4i(vIENUj`H zo`~disl+`Xl$0HCxmMg@LFQ!;4st?Fyl66CqA>C1AdC^V2B8KWvvk)X)vrK!WFvIf z1I8^R)TnOSF)s!}hCgH4&Gj4(f8Jys{2v6R(MKV0{-tfn7_`L0(GYP_3w$HqlFA4t z!UYt;CbAg5Y&|AxD}ZBcN=ItHO5U84;!d^&^1GU=%Q(;##BD(cy$4{7RERgX$$T3G zJxkh2N`n3{Fr!U40n9iP+QFP?LKV!(CRklA7gI7HN*F<8DqIj9^$#_fM#V$C>uP?Y zKQ!fy76(Yd5I9NB0Evbj~%%<5)xhLVmm5*(x@kHaj)9j>=?UQ#ybW3fX9MVrWfR9tAt6WQ#h;G&ue z;vOeXQ$7$M7QPmUk3>E3G35*5d&1WO@qN_?V&!U$NgR4jdGFtV@%bS90Uqv{-t|Wz z{LL%q)f<#7CPKKvD{g{tr&sKYButcCY=(Ct@KO+;Oma2($I{)nRISzKj|85N{>}O_ zxfg!}a#O!vDEs%w{~`#7E#YNQ&&qgbK+XH06x^kRR@J^xy z!#Gwo{(E*c#u>Q4-#VIJSc?2DVJ2J$T`OJB7IdA;_yWJB&l1Z|Zu7VP=QG+Yi^_O} zH$#Ny8w$`^neQMCQ=wC)VlB+f_aII8|JZvEFuSVqU3?&iuz`S~Ned7l6cHf-rK=MW zM2R>FFcU&D0TD$(4Q39am`N!1LSpEalNeCMpn(7)q7*CGK=cPvlqMo5grcCd`@Y|| z-nG7cW)9_d{oi~4_qjaJ$5+DX@+xUcTx?3wdolj_1I6WYr5JK0P+n$oJf#T>;XF&!2O5#Ag3$h!;NlM#7DV2uc%qz zk4rM**-lr)pEkN#5r5w0*=|1g1xZG{(CLc!n?^S);)`6K?UsSRILU~YJ6#d4FuGY0 zKbqvkk2#%v+yef7la<{k$kdXq(Z_dnjRCMH#G5%?5pQmEvm)Nv<=OvO+-P?I(2jUV zrz_$;jc!)Nd$~N@b%URjWW)zLT@g<+x>*q)=JITJIQV0ejQ9giSHvGRx>*sQ=<;kg z5By0ZgCOPrxPUrd-?L4AuF@W<_INc!LXcyX+ zJbwY%%>Z1c99{#%AlCw-X1I7c+69q);!A?6`hgE#sK~^})B1iCM*jkI5QeX{FbB`G z^h*~BYYlXMyB6!H>y-Lr7b+Q^lw$2;?iy1x!Ux#if%W)GY1r`>5rz&78!LV;E>}3N zVxM0x$8)|so&V2{*W7Fe529Liufj%H;8wCU408V0J4Jsm@*Ep@>(PR3iNL$l?q4KfXL=fBE%)O5xi`rz;6dJP0S}joG#`EAZ`#NM~^_jI^vbM zFQTzxUnM)VNFR~;?OLQinE7!n(sMFDrbU{i>Pl5(R zt#SSBa+~Cj`B#`V`6Ini=Et;1Z=d;bEz+E2`BN`gXUTiJ7W0g88D}`VLz5jggX!7G z7+DyjFjQv?v7lJly#SC(D(noZ+t!fAYYU1RzXI5TB0*=qptj?JDn?;Jm30t=OsLd8 z&dQ*7@6osxE1@^>D&{?<_8Hj-<<7_!#zb{47gWhvpA7)12@17qO<1`auhmYC833!D z1f6;9<5+t!3T2k7BM3J~U92r$15C2?V~mx?h+hAgA#0TVVML9q;AZJhe|CbF^k)yo z$lRD{%WDa3;U#eq0HjuTXqGM*>yO53&7#Ix0BaTrI`d|YVY7-+=u6o>f^aPq$wFhZ z+AsL_3!K$4f;Xq!+D|FXnHifi(-sdc(2sJnrTS;RAB?aE08Nnd&=1A87HGWI4{GcP zuzrxBGw+8Tc8XCbeIw}jJ{yG3LdZ;GKbT}$Jmt?6Er9%7fZs$%k-P*DZnJfbd?RiX z)9~wN*hh3BfcMUC0bk}~EujvYw4i3~E=$30>gL}Adu?4r_SYuLciC=~Khau%PiKMm zak?V@g3-;2__QP^p6_&n_*$dOq4pT?vjLb<4lj4|av*AkdFJQ^0GmY;RP|YGa8=91 z#?_K@ptD#;LxthU${ak;|95Ctqk!W|m$?1PcE0^EU9S9>J6?~|?zb~9yV^d|nUQ)} zW5bhDtZgbarf7uC!q?{iJG7TS5vVqWJ@7_cb~gcdXeYke>5BMMyHeh)h(B%gK!bS2 zZZ4O*r=dFna?Bowf8gX|Xk7vbbIQ>l0c`FxUYkg2e8V&_ktFEMC(;h>#VAblSAJZbu)+oN(B!A5RnmoQ< zi}X#IAJZazPv*z9NOP9uPrYEBCGYK8%rnMioZ;+NOLo`{re`B#WMPcLP@OHr(qUy^ z0)SLfVL_>Gn@Ww>78Er;4zRlt2|DuyWry}+6c$uj2SLb$O6}vU40_j`uo8L`uVOYR zwa>^#D0fCn7RE$%E*DhES${P=g46_s+O;OET#eUir^foQx7tb2nb&TI_F@#uELTSm z-U36`7Ow#&S^6=?N@GN?f6S0I%4!)=<0^RTK$(3v;O4(-J#^rh?`LHJV`-UNuvYQNyyFK|}J2;Q7> z>)xd_XJ%~9Oj|s(KtIZ%o$7meKN#UrC*?f!L-DNz8n5+(8utTi@sOZ1?}r`Qi%}^3 zCg}J+8-$mo+G0PLWLZ4r&^{6Jw*k_jo#ZvAPZ-8%u8@IzZ9{_4!s7KzcYz{pi|NvsFJCz(Y1NlxM@llQ$B=(8?Av_<0cChs9S z)8$vpC2_ekSIs4HB>+x|9(VZ_b4fg7@;;)qk+P*nVqF0Ai8gcj6>~|v!I`V(l6VsU zN<=5R{EE3GSbTT^$#Pi$K4!dYhx|3_F6#%Y=LggHceL>R6mol+CccT*yRh*_&~6Dn zd`pOBGv#)Vl;2}=7{lcLtmnLDgB89HFtW?#A4o}ym)?BH7XWy^B3|fpMZDv6KEuQl zj4q!|T#E5q0XC;3?f{@uMAS98f>3z`gbKbY=(WY8Xwo}~58u%1hHN5$$r114bVYoO z(fFn>@CRI;UqsIWe_WCg&vv>ZKGSG?c^~*3muI_0;1?$u@e-#i;y3-sn?by<(WM!* zdmdmL6p59ffM%$EvacE{TFpegMB5lyK0O9I8NkAc4|2L9{)Ex^H~WA;?ebi}eDDjB zjCi5b74dCGl$5}Fc$n4Nk+Vt(-rZn zjc!)NJGeZ@8xMX$k`eFXbVavZE`#i10OyW)xziPK?@zpc#C=8&RK!!A zZV(@Bba?@C73@}mOmRt%1%$ihlTcX|qE+#?{6E~a<%Im#Z*RlELx55CG1};ndyg48 zVN8n>s^i{Kz9&i5y&+T>r6NABW#~{3AHBDvLpqMPrN>w_!GUVrrma_@JPNe+-=DYqeVqIR|7|eq1aRAO8@oc9n;-yA6E8>fiocP;L z=XJ6S{KZK|yxi%E_?18P`6u4M=z)rOL#G?WhZ$Yw|54bj0U6F1L{!1%+S4NODwh+z zL2?qkE+?Wp(^p@geVP7xUc}!BjHlo;TU1UF%c+kVUcnS5y%zwBSE^whbJSho6s+;u zsgD}t0e0#mL1$Q^_V?s(F!dwT;0y>EwD5h8HI@;w4U3#J@MXSrOmm@&@sNKlimFAKU#5*9l}c znI!fEpm{{ptxYnOUkkvuTk#t^Qf~m*x8X<}D&}wy4~kh2UUo50I5Q~hb4&>uxSbJs zRtw&&;k_Vx69DIwzwR1NJ`71Y?nejg4}6@_#~WUr?ZX=Z#n=MG*L2} z6wLD9OH;kp1XjqH#+(C!7RKxYVo0w}fX2xHZb1Cw(Zi*}@fV8E@rwXqJ7UmH0GJ{o z7K$}Eklhbg#*5i(og8ta$KNb1xw1;;S6c)W&?El5#z`wRx>~AUyb6^b=HboKA+7P> zCO@59cx%y^nZrQ6>;cqR3%Q^h3K1^+`?5W*M~&Amd}`2M*LqP3*ZRXydI}&V6(D)d zV-LJd2G|)3_#me%;#XZyIsTqI@b*UI@3{kyce+8m%;;uCe6h#*I8vlTKc4=du=KS6W^VcjhUUi8zc3b{(I^=kSH7RiXmQM z?(Z0eEo9BLtfA3d=T!F?y8LkOCZx)L%FJ+Mj;i0f%i{fN4!#G(gmh#j&i59_hv6*t5m*m6`INc!L$<%KwGrCAi6uL z65s1|MLg=4-VEY3jV|vnMuT5F$%xl=x*~qN(fDRG@PRJRX>1MtEr9jPb2c9VHsrHF zc?#%(#^hv4e2~)>@q2#dSrH#?^gx67j3iedzX{!5$Z!!(Z8brBR1Are0O&9g4NWOp zUIJ@ui};ZpsUHIDk$}WLrjLU^oqkx%XF$vsBTxT=`bH48-)Sjd8}hcvV9E?<*)SCK zjA?g7r@1(W9#X{jVR{_^j~nOi6CO9{pVm0G_HP30EnLvgV(5f&rT=s2-VJC=^KZ#T zt!d+6`@$J*TQp|2Le6D7qQ)TrY&;qdd(ckV9($0+YkLqi-UhHehy-c=5>GXHpdvop=?3wEzi}Nk_F>qq0eM?vM?v&j z02J-K>aDPjce3oo*2S!sup2{7aWt#J_Sn-=l5>e^ZhX-|TcnJpM+%l8Gl6 zJx~$v>~!|=1a!AES@{y&laQ?qna@jBT?Znn`c0yIVodqAfN*)=0S^?r>X=q1({AWY z1aQA1-pA>R_%x%N74iHeCtl!mPU~p!Cj;8DT?EnMq)NQR>5BN5MmH*r-ySza> zlSFie1K z4*(Aaj73kR9|ERF(kzS)Nvo8zF@7lKla?)M**%itW0iDgLt|+9K7cVY zHAc42|4-U(fV$fjZO!FJFwR;Kw5OgMoBw*xt*1p|KLFmz6ESbIs1?8-vIraLSk3kx zt-D2{%=eH)DtPjFB*kp3G5?{o>MLZ!l!`^r)EdJAXDIftHEmXGXT%Q9uyv7aXXJ$e zujMr!ZP^AaWES~a07%6Isbx@FfNN3XwJV+)ud+mO36r2R?7a3GuULfZdu=F;k%a<% z8`)eAFyDUy@t~NZ9=3zx7(&iJufAGdMFXLWM#$q3n6ORpyjWiwoDtUNlXe=Yp%?jh z=x{Zmzx_51G%!Z`#;8uIqsR2VGL%6|HFRFFttgGxDx}7f78ym6ptJmHub70AOJjqu zb_KkoWnR1BR2kiT0nm2Up9T>#MHhN(9+;RhGCZSb%#0f4u0)Mr0?;0X4xL(@?bBND z2w}BQgZ5aK_9jhEY6oVmKq)D`Q;{z{#%01~u-IgHlm%YmbVYox(Rf1!d|#3iKj3tO zc$44LU$Y_}V>I570dMMbKJSeMzeAD{@91&Z_!maw;Q{!UNlyGL zryIn7H@e)ZDZA5Tkj{pNd?sP?b-K{<+#6L26ph3LlA6zbXw?p=jjh7yd zht34k8)y*k;&erP%I$7X{3)aHhu?vB`(xej#n8PHfHOVOnYWSbTMW%_10W@O-5n;~ z=1y$404N*{)O4~1wAe`{dlNj};!cU?Vib*kd{C;!oDb=8ja&wTso99!JPO+<-3?K4 z^H_BA*kEw;*kEw;SpMs1YoVs~tgarS9|92OsliiIWyYvBV_02^_Ee1altuf7C;e0{ zz*Km}<8O=j5jcjQCk9EdcN`#Q5F1c54zQyPXakDO0dl9v;?;C^YZCzOnDg;BFhOkzz(OF}GY^p3*9N8#F|u1Iu5*g&oMJksh!bGX zwjq2vN4e>C)Gm~wiA z4mjz&1`;ke%yCa#2|aQ4ds@$^fXbPNW85)l47qgh7{E3JyM~l;IP=}!(#ZuVxteM z*|MWJn6MFt13)UFa9k;E!U;v=wSyfs4guKlgan=GSW+y)5$;V;c$+L#O%Wo{Y>b|0 z8eq-?u~f|OLEI^3Wi)VgfaS9j2+l$+IZgx{ZbByGOD>$YiUu+)8X?`4(Rt2JJW{cD zX_0rgxO(!Ms7*c1(jxE9y?;xwogQtc$9bD>3nJN0ui0|(V}`gA$D$&TiW%mutW(sg z@mg!BvA(qiwUVGSJqi_z*a#?iyMyp>2)V*zcbH+i1aSeeJq+e6TP<-;vwukG$&74( zg*_v-p*#^%omV{y=EZs)0HiLV&<0(~R=LJ&ZJ@??0k(We&{=*iDJG%hvLJ(SG^UzY zZR`V6Ontz08#Wnm^=*ZgL$B~7OIP}{Il9uHt&NefG3qF7xfP-r4D~nwq;`_fA|+y7 z(Ri&z)OY}3Eh0f@XwiK8Rz@)i-6)r75Y~6*&<<>I^$kx&99J4JGd5sm)<@0d$&2bA z@tWy<0RV-{b*NdftxS#AYNo~~09G>zIz!F#tma}8$}5{z5N?KvWryOj;F4Gjz)k$i zJie$}$-@DkYP^L(_483x@^JFjoervd@(YdfDtS;1x519Lu#R^v`P~=|d7X7=!8E%Q za?ikYOtTxFZ@OUG)$wkOG5Y`@8HK7KrN~itg`G>|wYj0jB!JBg2|B~v_`f+-Ou{sj zn?n#D12YDXbJLBvnrQQdk5Pd4ak?U2Vsx`2J}=3M&v&{(e7(`-dGJHv2LSeGbxC~H z7<@ADT@XJLqvAgf0o~w@{8tVSZ{%-;>?Qyo4~cJfx+327Pn6@IHU-|z=z)rOcc&Y~ zhZ_r z<#F@~fXy8Vs`?j$?Pskrv2k@}3UsE)Xs9sU&6$JeSsoqdL3R>=wGyA=bVd9pqnj1+ zT}e)Sx6=*cb@uRnDDbx-yBvV3INZQ6$W?);8EWO|zW`PX395!#Wm2p4LFhduBZVx& zP%CrrJWH)IV6B0E(N_)e6-2Qsf3Xt#U-lQqMWVMua|oTl@Kot`5NjB!`R~0-W-ma> zx9;szHjUL731hmE4&y_DyqF#y3uPY2BFeuP?eNwlTi2$082cj1CPkE^Nc10mIfR8H z&sewN^-s8cNFj(inhm2njA+(ccryp!vL&AFbVa+70UYEkD@GxD;q^@r;`74Qo_UKKp2N&$Y1$%Jq_U)C*wo^6RVj;Z7Rs}xoCb2sJOPA;X$;$$P zl5)ce?rwbw&GHR z2Vm1nVio{OM6)F?@!?7J(>>jA+0hHNNlQ5{$J!#2f`yc~?MhNJLcQUu1k`vR0CO!5 zVcK7t?c3X{2-Kjx-fzlD?M$ahm6D9lLvdWtvA-;y7lf~CUV(I3U**zaGo%q4!)u$@ z8Xg*Vct0K*b%BZ3WQ$im2PHd1!`>+?=VarYERHJ{*aL$FxL^_X$ND}HEU+sCi*P47 zCB?wZ;ydGL4KFogq;HH;qB?J{SZ-9l3; zvNqM_k`31p(@A?@=)}?@4fn6>iganYtMIPK%b|V7u7T`Y0ME(9KXSSvp8pW#&5C$| z(fFe!z}r9Ua`k~e9t5B@L}%YevhOE<#Y^r7jeIkV4go+)`|msXEYK!@Gc%$sjO_aX z(A7@L{~>TV)13AYeGtHOHT)OEoCjZAz;sW)r0LL8EjJ+P;+57JeETJR@v;#gWBfNt z9Hy8jknJpH&c z^p*A>xBoURvb2S0ZW76GRs2N=(@{v8kA|+=L3%>~&IOwQc?$WNGNf`Q%JON>qr1Rh z9{~TwX%@Q>06*s^O>AL`+QkW{Gi()juYDdC5i@j->xfNrjxjjj&arI=0-U=x&A)SU zPTyRiE?wn*d@%q3?twWiQma2;96oZpqQnKqNcVaqXp%~CF~+#B0pRhKLD&AfkwmWq zxNlP1`T)^BJ^*71HY@cF)Ad!ZZgoz) zdM94p6VE#K0*GfZn;?pKMHSy37ume*`C>e`Q#9uk%Q;2j%yDI4wW~Ogstcq_0!e=> zTPyoG6%(9fyAOAgEoFJoRWy(abu~iW0>Isz=o5doNtuG+(=36>M4n48bK!EqtZ|NB zX-@M+cmvG2tX9U;lol0fWunz_C5Np3!V@q-Fu&kSJZ`7*Hmz7P^Qrb&*?EN&)+YYJ~;3kOH`n0yw5H z>~?~&5D8q2^ncIhcy#GBR-bBoN9rcFv`e^Us-NQ3QSs`jculN$&7gR7R(yM0zxou_ zImL8N5uH;!=M>F3#d1!OjzonQ0dP8_mS8^4QjrS_e^dQ!xevxDA!C>i zZ+6Bo9qy>c=-y?FQZq)G850v@JiMvM;YceQX$2##Sfmw-v?7sKAkr}o8-RZUc$7Lo zS}hL*w! zySIpaA6Px?c@6x#Y~{}4oU(OJ={l!;om0ZjDP!l_bHKllIBMi-mu+l`eB6?nmHWu# zC=2hh|99o9RIud^Ne@q6qw+eLn;ZI4ZmYZm$|aeObJ$o)L+Pb7lw4^jIW_c)DK0LK z@nOw@(Uo8$nnhzYiN+|TF^Xu60vZ$J`G(L#zce| z0i}`!n34sUk_DKO1sG+)JL#1Gq&C(H<&oMLu6&-Bjfv`hq0D;5wlmt|{>eOP2~u_- zWz~Yxi&#a~;q#Hk4RGcc+-vb~SE^f$E^_60fSj7-W9$-hbB>kyYN4i@=40xbb84G& z?OEW5CV8=tRtBUMpR}TrR&3IWOj>bCD=O(2^FdU<7N4-MnZut?Zn^sIE9Jj?7@nK3 zu1jaQ%9WR2E6S`~Io=s+Dmx!je$FXF=ai#!$}(hu<5I{1T*v}k$O4=?1aII%7T`h_ z;6fJQLKfhL$pX)5Aq#LJ3vkK;>s2X$Wc*>D6O{^dLLMET1$X%izQ+N;RomSn@n!&S z{6u|{Gj5k%YEUAv8UPPGM4T8iRz}9COuDBVGz}>XpTBhXZ4db@!gh9DQ-3#XTR9FX zzXW;OeP?ThM{@>27xo-ijRRx?-Q2IZSj4{jC_ESXSOe56oWqzJbwFvdlgB7&h+6!u?Vjue*uNt zWuXEF(b`V|%=bFjmbbJ`9f77o^_`{;rr3g6g0e2M(!ksd;!ZL0%6Z{TnAegF)YX0) zVTak%T4BW&xffe7#THDl4JB?4hirO$yM7m{yBFXSPU=wr?vg}hRqX_`*8*IP)LsCn z5v9Wd7L0OmHPy=)$rTm{T_p=}vIsZ1`g)c^-Q`osCDzZ3?86uZrN$fVMmkw8!U}3& zgeh5XHC}5pHE55w+y1w;idJZ;){`H$1Uv=SQL28@;KnJ-CJPrVJg~geI4ZCz3i8deTCUJ>-}oZ53{u}JsBWC1Q% zg!^HA%MLLxrNJUh@C7Lb+B-8RWsLNVQA$+56o9VM`;P!1r5bw8QD$rH)p)Jf)VRVl z&^QuwhF(7~hkui=n1r@2frjs1LHG=W>|N|NQ%t=M-MOhq(Q}pb&ms-4&vd)Pr61lm z%0{D@FDz#%I47L}+%P}tFE5Gs@)E7QbPlz@1wgZic&jwI?9PDVR{-sQvi02Lq#lKu z*|l6qh;HIb-uUy;8dy4t3|Voh<6tS>7TLVvzw z)ctpr!Vk4tse-}}&9zeFs{j-z7a(OnE8C+$jn@jK2JNx=_-`|cR>*%48a(P|Ed}^S zN;?*&52)IglH~Qvu!&<-`G`|~C9SQP@wm%OusaQY#03 z@E@ehH|;-<@uy68LC^P|z>m}c`24)*Q0N_Nx(o7$xMvpKgM;qDLHA%K{AuW(0|@T` z&j9fKr39fJowhCf08 zfD+L;0Mxx=uyrG-Cw+iu-N$tuycyIn09X)x(g$$MzZ%s2K0vfGW)ZHI&25o-9l(m| z2eHVR?iLBoqE*6azX<@xM1KIl9*#-f?gP&Ny#ljg2J3>@#+h3Ow*#>w0M~6=RHMof`K8unEvL z$HRVbb+*TTpz+#%KnP)DexI091~ zfhmr_6h~m>XnG12x54+O%L+RJudb*43cF*FE0hbyAJk=B3&uS2RmDl6cPmX{z}z~> zU2UO8V$_$l5#^m^$W{IlQYaILolGe({61EA{oiMxtaH0KdN{y;jMU%>U)6?-t%!1; zizwfsH$_*tvG8%@`0y`8>NcFWy~h1N)(!)u0AkSTcTmKA4}SJ%;EiLWc-JE%37;tOhDq;$q1qA+qkTxyRxxo(c~$vURGru=7Y>+m;eaXE3K+Fiwz?vV zIaYHq2UE<$I^Q0lKLkL@x~+xkd6Pd3(B3G@I$Lp+8$;+q@txOq5#_6(h_cp5Tmih- zwqFHP;6HCXLu$Ss&9=Qp9*r5c0W5>b;`d&64K8eu{0qQ-{_9!|zH-%o0-~ zVuW4h(ZFoVZh{d_(y{Q!Y;kM9YcS8SbF^l@&M8OdWY4U4lET#Jv=U~i9Jp`|YaE{& zmJ7OQVCsuTSO@3Ad&?qBCQ9eGTcdKhXIu-7p99*L#ZQW5hcL8yVc*gSi$@8EEmR`A zhp0;u2EAoy?Dqf_|LvMv2g7?3wbXu$$CNm~XeyDPQt=}_PBXoRzMH;g9CFQfn2+Kb zCp0dm6#!(~-6HWc0Jnakd>Ssx2}*SSM}S$7__JluLzEVFcQ|c?Q(y>u#~=fz0Cx-s`H}53^LHUR`?X9 z80M9uoESULY1|lXHqXw)5p z)Xg2&VjQ-w`2P7G^YJ~5smVgTjKr%LdQCToId&Uh0l31;%hIBec6!$cS2*{s%K=!Z z++;W&)+|p@UjnpW(v)?!;^>utaIqHOc@Hn5ywev^);c~V)xOhT2>)g8R7aQ-Bcr|d z4U(Wrcsmxx@5+a|nvh06HKX2N0R7%c`46L1x&eTBH%!giPk1Tt@VUM_hl>6U(HK0~ z;O)o!_!6?n{i$0Syal?$J{0pgX4pqYS$2G!?)b1N%jt;8r*Cw1nmyg{q0X47u@D-# z7U_-S;j%nB+v8zMk)-JlkC7|v=OD!@T!nfLAW=)B)1; zmtVXUtI#(+Ov_5y?1ffv8O6Ts4sXN0Qt9|gMBX~SjCoPZw;?9q-JoyNTh!*g&lvfp z#z_D)OXHz$z1bdp(|E0K)L>QW0BQO|-~7+)6syoTy?2n6viWsNG4^daybb%ti4SkX zz6_GLj_;~EzDAPePY{z2J7`sZcs~(7d!@!R05nVQFGAmL%J%4+#%q0}2CGsBNYfws z<{xYqtI#*SqLG#IeKlIa%P;nA5%|R>!(UGYUgC5`yv;wU+pLJUHF}^T-rnhauKqc6 z$3Yf0{zo8M4I*r__U{iW1<8Zzc&JTC9*K8xx+4DQGoAtQJfjC1#5X_ha=9IZ?#BT* z(Gi^ui06YT;NK53WMjXyngjaEXA6HjXu8z6+{zAbpc}FwEq&6`WeSXeM+Us7r1trl zI|u$5&&Oyz3DKOp6x7c%7rk8zkFGQNDZDlRmvQ`T8r0_hHV$vAfA}=M4dIc%g}BfR zaWVEB;;#N2o7B58&}*FB8E9RP4;@k|H`pt;a6&n!w9-DPQb4rMc!dVA&EqW#nX{*FQ;V?-We#5dgf`A>v$zxp)YQTnPNF zh?W6qrER|_L84rGq%{|$)fdw03Tb6YT4^c{`h+hAD3WuE<(#_YoZ>mBh|VddbBgNR zFmdtKgAf;7hzl;n1sCFi3vt1PxZpxuaEdz(%}*ED|I&K@l;X1Ys+P2BC9O(Ht1{B6 zi?pgDt(xQ;9mZEacTN$UQw--6#W}@sPLa4-rS4%136a2sNcHUrT!;iNL;@Eg zfs2v;57`!XD*I;m?##5*3T$TfgB~?QyxJjNtrxGBh-Xta_s!D$sVy2;V-yz?^RgDO z;<=roIj308Dbfk3a3LVPc&3Q+j|bzo<>@y@2enoX|p0JmHsd5$jYQ5RTze$`*hXzpcfPBn)} zLmtyYq?h<$rWj$J?T_cc0|2;mx?3a;1>jMF=vc{j!^|HKFeMUm0l2=1&X!y$(<3cW z2-2b{Rh*N~w07^a<%Q2WLtNI>PlWBI**_^?+WdtIA9c9w5Dm}IkAX^0waezV_QgU! z2!JAbS|r#%D9-aFhtGhi{M^%rds0t1hti$}RoV5x(4^A3!5E)Lr}-HCp9+e-4-aq% zjGXw)ezOm#HHVkhOtkBOtKSdc#s|dILCP;j-4)&wX&mQ*@=Y0P z^a1R9kR<3#AF~vT@Q!FA6ei0;f!4vMyQOXY@I4zno?}f1Q`EtH4R%Y-7R+x!+#%)* zXvo=sT5=^m)Y*CV+BDQ^W7uUjw1X{jFScNcEtp~(N}P{S>|}i1br;svy}rsYhol|_ z;G!Wa3yxR&<^Z2+QriHaM#Lw5AJ9eVoVv&u<&6wo(E=B))WbDgU*}S&`+F++!|I=r zcUNN+ks5EnykX7AMOZ!!j4+?vWiH)Xm#IPf{8~|7Y&|K8R!7#-zz^V$K4YW94i}!- zf)rPp?78KnjR4Z}BBhtJSHEb>Wjc&8_6-@MgW!TaI4vI^lRfvO5?@UQ+AlW-A~ z%QFbqz+|zLal)8l>H}`U>;t2rSKwF|y*sDEzEv!6OAHp^f(1BP)OY+~fh7_w!h-oh zih+*K%pr`CzA*|w_3HuXD!pF^04debYsI$qYP{BKYJ3-9y(U3t=(Yd;rkI4bmVGe@ zyU;iGF7}!!re25c++U>OpuPqkrIT)WMfJij2J81yHRpZUB|Zqi)1;@b6J)+Bjdo0_+|cI~$^lGnAVxiacP-nHM#NM6^b=Ju{#`_+!* zb!}>L&f&ZM%bFywYx7=^J`J%~_F5m3*R_vI+QUon35d+Qz6s6W0C1a>>;bUc^Z7vu zZ`i!Akp4L^@AdHm6zcM9hr46_h^IR}GMG2F#iQA008k^MM<0++=afMgJTe2U^d37i z%re`)aITYKcrj0_U1UWf6=5G$Fay?2+~$p9xg)LrHcBoqLDq7XL{ss~M!bB8Z};=^ zs_9gKqISxf$L?D1STVXJJCI5=^zMLSH8q^l@M|F1A^WNM{A`Tsqb(;NJ2jQRZSkg* zAo*)5#TCw!8n5l&)K~(r{hI`x>8C-(BJ9-V@EU~7hCT3ARbPtA`p~35 zmO|aO{EA1u^@Sw-P(dQ$wm*dPj4>`}wi?%Z(^{~E%C#6`stZPis2$wXT;q70^9d__VgxE}^ zA^hS2r5TT_l8x*d_5AbCzcG8o_ck&eo;Rf)T0cA~Ma<`$UyL4py!_)9;lijrv<5lC z>_5Dl626R=(qfsBF1qDLj~Ei$86h)?2yF_awD5(~%a`X5m%4DfdSO1;OFds%$( zQ=i~rQpBZj)m-Tdqv~+q7@n5y@JnHMschl`39`IFONQjov-Dq_?jXx6ZTRc7!+IHB zS#E<-ZSj@yyn*AxpYpr3;I$?%cEfD9+0`&w!`J-b+$h|2yYU+ySqj5!h%DqLwb~@* zo2N$kx0LlCCSp>a2njnX)coeViOj+%&Kr{ATo?ZN9!bMQynrY!r+B}XNgTfmN2j|1 zJn9hN>vToDF_Pf-vV(o0Hd1~@g$d5#63tS59H01aYOQ0kGA%)- zG@;>o{-dMOc`x1$^0&9yQ?>`d&t3UyodwZxriy=>2za*B74Zfud3nTRjUH$a@0#Sq z-APXT&Z_<|iQNnz{{mnFiAF&Mr|3n4t>vqZ==vT214P#Xd_a|TwEQA`oCkm<(WS}d z+!m=v0a$pS8l186h^~JC;B?vC7O7Q7n9V$(3!NnTDS$fo%k+&AUE2fTmuNo#2Cf-w zeGJsseSqjXAGmR_wdN`#x^@G=g6JRsEbz0UQ$c;p2Z(;=19)(K8r0S!&4Oqm02V6- zTeCo&;ubQU}mp{%5U9*=wSdNb+=Z+ znpqWqGKfY2OuiO~&0S8k7XZz|OV~Go+TRC=-kt|Yy~8;)i_{?i_$8X*1L&!i*d1v_ zBHAIgAeo^tQDY4(DQtvXupAG2;(gg3$1IK4j#t#+y4SaGNz)&m&KB8s?2A=6@IBgQ zrEDa(5MN8{*qAM`Cb?*h`6>u5RAY9+isRxmW(f!`NMkm|%Hkq4<}?soc*fig;vq3N zpk_{&jckA(axRQfT3VDQJP4{sNS*7Di_b=8gE&bH*Bcj^jVuJQSPa({7n6;Y_MpRD zC%!nqa1C&}O^q|n={06(T4-%a3rtB1Oi2q&NefI#3rtB1Oi2q&NefI#3rtB1jMBOs zwQ(KA!}TRt65PG8G0(>@A4z@#JC^;5k;E-xxG$_@&B0F^OW(uq8{2kAZhC&v&~#&% zIwxD_m=7;U=U5Q0J?CEPRhX_jT%M}*Y%X-f$4t*?DZDX?Zj6E(!`QsgjbStC)|lwk zxBtmZ?R5YgQPuZwTIHy_YF{pLMUCwNc3vYvXS_7+U%-{i+G(y_0AWh^g&EgkoYJMK zcrtiEZ5;*>l;2Oa$SC$Io49S~^osmdz-9Smf zK@Rn|;B$jJ!q*<=uZJj2;O7Qa0w&{ggK}bw3NS|b8>94%85#{gi!E7(-^iBwa3e1o zVC3Tlbl^7tOgE7?1ON0}P(C#)(_KCn$O8pW0op(4pzMX+QDZ}N#$Qv7=3f?2*l=%< z2&I=yBn)~#Pt#;Si#;{|ELL5>O2EyG=b3adgQKHPrvgof+i5qhrn+S+ktvZ2s?w{i?13!_PAzl+GUR@BcMu=B0#H$^OgC2cq zkUXo40qNAGxO#rbzDP?_<%*6qI|=ZrIKv%XuP(PsBtI2RuTz1 z(>G>{MOZWCFcgFhZ2df!#D&!HJkR^t3m!_3$BO3cU^=IV69gDFj2agKP^(TDq3n~h zJ#Kp%ua!*=p7nGnB~5?0hWv+k#VS;(6QZn?%@h>GvsbL1OZaVm@(8!Bbs^cn&jY6q zlAua>{T#;U=gqq&q|r8J)cb0n*Ey+7!YGxt2k>P9F*R#13n=jL`7ZeSp`wn@iaZSt z`|zV&J`HDlw8Sj-hO;A>sBsN6Fm*axhFLr#+hZ0rUYkW~TnNy7kfuNGg!X7rtimkn zsXoG}I%H~WIw79MMj!*rkK#|YL*yo7&6ocF8jpcauapb|5 z1Q?qdo+!X59yP84pk#WZi%|W7Y>(EnP;O0;|hyGf4~yGg-rQm~sOySt(L4**`?@omY? zfbbr#%fP=7NaXU@q`JLw;WgN6Z~fJ~TY)g}=^7jkjC4DfC7cVJ^1J_LvKe z*XDv6e85&$Nz)(Z;x3zuVio2>kL9vbzQ?B&;#_omX><^j54C*T-v7v31G_rkF`@ct z;Sm^2)YuCeD4E`lFmL(o^5|@j>NQ@go*I0KpgKs?AFB61B2cVC^?LOnD`nH0Qi#=e ze3y14l;3Ol_7ZVbVeavgOWr<%S>R$q^@oLL{_v*&sBtX-)zceYgt0Y!()5Sw{UiEf6{^=;7+ERbcc&C$^|NqiJtZ zU!3H`S0p*{x~scB@p?uNG>FG1x$-yzzRw2W0wnU`@(+@q57{jMYyo}54+3x(Cwk7v z$waR}KuC!;w;aZ|dVyz{xQA$=i5E;I{*sCNh`wTE578w6Mj^h+#8aLCV$PT*qD?II z@(JLDi2Q9p`ep&il>SszS68X1ay=lNL+Tn0YFus_z267A+DW+!qg1*Qz(WTyHEV~C zUqaxW8{aDRjc=9udY?pnYg>K!TvA5+eudHBStELgo-?v<1oYQ5oBVkU+djcYr+fs6 zElwR{JHi@|^HVf?hwJV8;N*C~DEtk)oyYm#f!nf03Ee|Fw@B3;MwitAGJ2pvy#HD*m+wC4P6uF_5^)$;`UP_}eiDQWZM^TJYvLUV z0F(R=pf0F}`KIDIuJ|XQN1Y^EYYp?+-P#Vs+X4EN<@2B~3H)o2-)w-!F9rRJ!0%QP zxB}$e0I7zARz_aydTvBJ0Z>tQi^S_(PPC`wBv^K+<&(&oMZ<1JOJy6QIL4?)Qpbv* z@?ro;sfKk@TwyQNcx^AF#+d+nm?A-E`mR;62>akEQ24AYlu<7P{U$`9q5)jU*&hsw-;XLv*Mz}WkQ>KwyRU`dk z*fGb{I6qjVUenC`h)xCA_isqhH71X%XAS@)(WwAlFvQ;im^ulrDCqnHXl3LKl8c&) z38d<6Tfz)si-d$6p1&iz7}cFNE+8iKBjzgmpmSW&m5CBxtXPeL1l~b+RnD zuvm766@ACW!s%wYen~fS#o|@8c-1XlrHj{fEnW$6DRCFV+?+S}ogm%^z_KJt?LKd= zwjwAko%>nL^FjcWh|>Hooy&}#2AC(N!(GWNNc`HF^X8J^^0JYkS>TneHbVTEatEuM zyPz@J0*%q8XH2^zFLQMEC0><-Y0H;F0Gi8qB#`OQ7nJtYQqjIP*VD?iq z9&U1P&Gy(gG+w*iP=ofmuN9@RMd%hLB?bRA%I2EJ%iyc|a+zz6C5w-Ge}FDBBch2- zkMxa^@@>$#7r`L}k>A>^NO=^# z{Zr0>v>Sn#kPdS)q|FOgrgD+*Ph!53*YfSbmORq52%055BZCIRrkzG$%ZU#}d|bq4?gME3!F z;6*Ke3m^BnOQI)|%egI5+pcYX@NwBOpq|YfsaLFH;pPEd=p@lk0f@W|?~m5S`$Yg! zBH9mt0etP{W1zn714P&P0N(zsxgOpF0boIN5C9f<6?H18Z}|Yx&wK#yDV_$k_4;N( zG!X!c75Fj`sIz>4Xt@u}$H#u4R`KqjDpG3z5RqtIAAtR~pkCtxM6dG!q(W*hA0XPt z2ax=GK^@~9+Xd=402~v2#0QY^98jnD0MTcC09_%qzz2xV@quN7t@A-$=>tTZX=rwL zo^nq9gKj|dhzy^BKfE9Eum2RQaQ~RlW~FQ- zw-8@TE7zDUu?o3Njrl4FE=^;0!W!dpG-e41Eba!7s$dxw23hs2-6=(@BKmhu*> zAbc&SZKLA$j+NWNws4?37V}3}`87~?8T8>=S z9@Wai3{$#0%s3fwO8=IMM@#18YdNWU=TyFPs^2*_fD6_+dQFXmmz+0z^PXex{77(( zV81F$g=zdWh1T;hQ*R&OSG&q%j$v8&uB5C}m@mu`%t@ zaKid|JYjL6uZM_j$B3c#)U=Fo%TP|}4>%>|oU(FGX*t)P3i9i39apNwS5Qi|{n@dp z$*(bTYmB_o(HsDlAKg3*0Lcw&70hK=lqCojrK~Bu6<{lk1nsd7{fj2@Qd@^*>kRAg zS(q_iT!-ohSfAQ+|(g;nEz=`4Z0g63+P& z&Uu9kM=6>Ncc-W6a5r?h7=fzO(w>=jJj~+EmVz47u8#XKBi;xADb;XyRta_^(Rl5y zLXDpQYz9ft8D1vX-=!}WVJ6GXFbMwwD{c*OdOM!rxNE%Nq2zch7A`y#Jw4p1z^DV% zxCnq+>Fu3>Q1;2$9xGYnwX&(fd%X@Nr0EYU+rR!%tU{GKA;?PE^raMH^_vQoZZNGZfw?Dz=8W7e=w0rIvQPM>^YLiK%iC}S?hM2&7}pk#XE zc&L8;Y>(rENPze>72CegYKlqitePKTfXLj@qYmDKAO+LHv_`QDjgr8dE_7V zfmS)Z5{{T7dVZ)qATUW|qQ=`T+!T7_cX8(PjcmP27I3lzy(O; z!{uup=RtN0fM38Meh`4WHPO>XP9_?SfRGYxX*rB<^#dPe;vS-NO}t<#@z+e;M|7T% zJw#Um7=`%9CZ6&P5OcdKyNP7SyaAGJXkxcW`{G)H%LY>g;_Ub#7#J=5t6H?fX4O z@34mS5REj&zBPc>cT!og{d<_=lzBksI;lyIS2{*CPerqLxE_B9s&fFV>+2r)bcZ~h zL*}pa!@uIyjg%$=xP*!Kak?VD(CB7Gyv*ed;x~_>ezPLp*XV%;@n4c$^}PqW#{#fa zi8zdTD_`|k0O1lF@1yyL0GR480)53vIilh>UGWj3jZKm0A^?1Lw{8XT0AO`}n1LF} zKkKqw_qLnh{sk~260h`7Apzzw4`3=Gn-*k0bZw&Bq;dy{dt6SG$}AtNpM{iJCj8B4 zDULC6Zj6eRI_96s$C~FUQVpx3xWW#o@!AeZjUxc|s6>L!^!Zk?2)o~bQ0SF~GI|Vc z`nUBAfrkl`8d!Q~P6;j7Wz8@MpK zdbl7i2ZZy<8eqo(M%mXs8vNSF$nvERjq;N?YNZvmbS_uQNdPQKqSLGa_$-aY=`Q~e z^59AdlhSE@(i@kWEh^a=Q%c4%W~=@?YwRDWK4sqD3bFcIAy&V&H?7 zUtg1%%kQkZ$(o7q?uDc73UjIP+B%@d^#EIaBct|=ZCOr1$O&R;xYu;4GSVuH zw0cNd|8X)00GPke0xdMMhlt)FrL#i;n1!WtKLFx*0M-prnyRI96$SbVV)}}5Abc?j z-ssrNI5`y`_1*)$^oECOZw0iy@R7BBPWxeuhXu$rSNr@n>|RO@St{Tkpq{Fj87?cl zpotozF(p{N#Xf(<;Lq8<{VJ9{HE6F5MNVq3*0gs>NycA;As0xzj5#mt0D5Piv@?Bf zVd7;=y6E9ru}t<7aIr)+INTXo$KO*B;;X@K`}x*~qW=w?N{!sQL(k(+x(#G{QKXb}H% ztjmeJwje#wAYQt)%a!&8@NqW)i)>>IZ3hVJEsVYsP6q%OB{~&=_igyph}3rh{daIK}M*+OhCa4pAfav5r zKlH4a8YuMxfbi0BmFqh>weT1jLhKwnQg)2AJAEK|CjBB3i_b z+K4ha7^9pi6KZaZ(d-z*>Nr2fa3a`qV@?Ob<{LBAE1FTff+=3X6t7^4S1`pZ7fY z-_bjk;T*H$`gQK5u4HE77E0x4l)?B|u`^leqN}f~j#Zz;4+j=nU^i{4?8P5@xR~zaTsTW}J*Tr5{Vhvn7MM zdgoNWbE@AtHh^o?IZd&1YJoOOoQFQv;;zXxf?cmH70A_a$mIp(P!|inJornvxCMaI zA5ogKFAvHECgaP4O4=CZY>ZMiMzM@(kJf%HWFhAP+U|C>`gkY!@7IUM;iFyNLRgh^ zD$6<5<(vw0PL(;=UJXj@Z#|n_8zaxg$gwfJCn;TXz-5dx2$(@b&p|Gw? z5UguiQ@A_8mNE(2V=4Q`zVcE#o0dH`Eae$6W4ySOH66P7F-vw+yb2YsTE(ke@yeNg zwg7aPeSGY@{BQW!_q92k^Cg_~C7kmmobw9DlLFJmRUi|P(hk?gXOkkPXJ$*P#z@&1 z`IS0uyi{Hf7cWSuhTCy*g^AO6Z9}5QYOuF?B0*=mHy4XAU*+Bygs+Ab_mDV=;goYa zhQ0;}CI1(0yj(&kY{lWN-EwSI7#tLi+cK6x2JJqqQ)#}U}7{L*4)0?9uuSS z+Qd+U_Ud_23KOH#os<;(k13-#G2!g}D-6?Ln1K5biYIf_FxAdc95+Tjsj&$(P(`uN zD{V!#M?o5|6+{i%E7zhF3epKxN(z2s$~YFpCmVlSTCo3H;h0Yoc-68$9|*n$ApL#d zUnE+-g59Jk#cootn-uKw=ZzDgdk6rxV?M3y0toN(!t)G`(^H6I9-rc%qldOMZcNm; z$h=R{cvvqdXM40)*3!5! zQR7S2qbV8>1Z`_9RW<`9f(E|1WE+^<1%1TZ1JGomHyAmY=pdI8%>eM#*k^%%<6@$ljO-zL5P(a$kN61_PuU?Q ziJ4%Ihggo~6TJtK#KQnTz*Hntp7}Gqy2>c3tY*IRNxZIMPW}lke82K(py!=bS7@I` ziT(}X?T46}wcF1q#PJr5ZYO$%V^&!7#U@wJw&@2*|!(azD_DD z_V+mN*rh-}bCMlnJHo{nC!%Qf4%geS!O6vd^26;4pJ`D-_vMG%lq!!|h;|%+>y&u5 z(-rX^ucEwJ5qBFs&>&uYdzTZhVe~+Q7=NqB^yT|3__!E=^+?2FT(srWyelDmVmsPQ zXzdBV?rVID_zd$qp+$V9(fB+S__`$j9q<^7SN?YQbMUtw{Q0kSN7=7+D|~Q6f1?5T z7iRD)-cciGb(IfuWW#k%+xG%+Q4pN~u-E4#=D1w0s7{wm4>c{FtK7oO-NW(#a7V;S zq1v6xGe&mCu&8_7V|R8LkH(exa4SH7^=2C7;_Ww_m*GTD(GvS1P>VCR(Amf_g#p1F%~VrORdM zTwZ3=0hs&QKqng6L&PNpsiJ{YAWVJvS+AmuOdq)I3NtzsAG4W&$m!XdYVQEFJ!;FF z?F=)a9(D|F615N9!ZoMV!VY}s@%A^D}M)gHDrxG%X?_~6&U5V1;@3|@hHCu(B}B%?1svb zHry-QT>U3ES{3HkQ)yfKhTKW-ex&EqFyg12MWs&p%IIBN>cvfcHYmSzs5{2>d9}aLjCECn+(B>1kq!<5Ab}Ui1xNJJEjcho zE{u^AW8}sdttjPTd+VJk6Jv@a?7DPx6u?GE%(B#ah*+A*<&$pM6|6@(S;thTs3SNw zFcWu>|Hwj#h7G%98g9BB4KEk&)z43{<3%f*uBT`7&-bmgus0K8O)w{yB8zTW6&MSMe& z6W{1`gLvc3>X*$z$i4#zuYsn3{S^S$R#GgrW1>6(52Lq5t1An}U_!W^PMF6CIHH#h`(dv9%k~ak$ps62%ZA9$47q)S$~JoKbmb1(Lass zRg};TdQ3_5XqfpbiF?YpL|qkPQ5PRNzP?&Bi@Oei%&*Jx)ylCr8*P!!OvGC`T@hb4 z-p^RXmm59MApXkEE|+Ke_=?#rXb>+4pjIMRE#LEck>P81#AzRZSs-FC>`KqfIR+8G z2rx!rzmY@rFw}_G=<_pDYXPuqi1y0^qzayo+;5g^8l&iY+y3c0+iquq|OE)E21Cg0aCxQfhk06nOmsP$5GulOQM&EU4a7r z8p!>ip2!@je*>_3h>{r$!}ABwWpp{-dT{a{b{TY-g*4>uOBv~UFbu;qlh z?2F(RwaL^L`9R<5?S0XPwpmU`B0e#sjsd_W(Gnk+Ket8d5+5LX&%0IRCIMdFh#C%VbyJ*`c5!bJ?QbM~lFiBDNLwuuy~D8(aM?AA=F8ivjRPbh!_}h}8F;gBq#d z0H8*+!Uxa-QvdV;qOraabhk)s1Aqb1s{sfP15$edtWhN10e}_}w-UÐH_0b~zE( zmdUj&HpDcf4QQJ6EoqcL-AoO?E+=cvVcSzD!fwye?U1>>0@8TxeGoM^FbzCGkl+H& zziulg;puo~XpEAHk}g6#KkSXs{Y(SQu^^5Y^Aiy4vE}e@5DlvyYWsp(4*P|~$QmhXH zM9jel!dirV+geOJ3I^0cM*ctZj#2hPHX#*=osk8mI>MJnv<1bTkv;kxAj;Sf&TW*b z7xICgax%&+{D0H>nJES?!^2t(!5WQGiN+{9s{0z5tio{3sh)88anxO5k!rlQz^QSP z1;e@|!7kzQ^FPN>Ov0)y*HaLF8)j@~T*{wBnqkY=EY7tGhuvhuip91_f12L1OzHK1 z>-j}>3|bv*ATGDG8rd-CV)EgOO{pbu&Fu`E>3}FxBce>R-*zWeIxleVk~e17sjXi} zW^{#xHr?)mEX){L8>6y}QAV`&iJq)tun1)r)+0yVFV>^RYwM93lPxk97YTL->(Rf= zTTH^zE1P`~E`b>*Bd*6^Bh7HqNR7i?lSPI5FE?(q3IlET*|Zojpvvj;f5n+ulRQ|v zD9XChAu6sHo+|zfh%y$$GeVT97Wu%Q$1aujv>i`gMtlCA{9v`ruu~2@XpDkV!{=nO z^2K^lnqld1^dUgL6SIuk(xJv}rh#=pg2iL$_?Ktpvi9=5oCdqX1E+!)lai`s4!@vEW>3+r!37uJpv>WM+#_ z(q%I<@3GYI-cDAsn0DnDRsctj0obH#ytV?UG0ikEpCnj0RzMFw%P1CMvddFJ5SDj2 z|Chgi(OW6L+Fg#P>0jF8b@*2$AHm$L1tDKJ0ln4_5c3A-p|5EP%*$WU=97BTI5ldN zf25M`sNqK_IdM)4P$98PoIc2)8(IAPCNhj)kjMFfA@%r<0Q1dP0u|{#x19!bf|Cj( z&-OM!rnsB<+XULu$VO!{-0%e$*W+q(u$Orx6>@mVgZ5jJll;1zjl%luj_P0 zyq?j`ig<8(!QhSAN6_{=0HKFjIs z<0$aQ0B{5A8o98sup;w8z`8ErcikEb8${K@1_$N?R_8C57ffH+z+aOlzYwsRWbgu( zfhv3eL9K;3+#*O91K3*PB~Dkw*BRZch=1hrYpNW$A7FH|BA(>(Y_}u${Y+Lq7wiE)Iq4A}6;h0bs`>`VIh7G>WS0BOJs;ueJ;ZM#*d$hJOYa*)^*5iIuuqcYwYd5N?G%Fq!OT z4dSUzSHy=J-K>bGxjZL)IQaj;-kE^gRQB(GA2yayR8k_Mxzv%8w}B%>rjBDw)De|R zA!nEB6=|NGOienJCa>N|N~Ka7H7P@y(L^JnROtV?pJzR5KlX1OyYp5*@9(<)&vo7B z{yz72c!st1+QV6ApMIex?r-ft{7+-20`Ul|M|q>@Umj}WE36%eryDyJh-X+mDV`nb z;-^C0E%A2x4;w9gBFv-zd>AL5Z|y*QN(+0y#eIyOJ{gtwC15v2Rd9Px)M;<@n|Vd- zZldxj$oQh|GbWMYS}%9qG$V0&MdkFJJ=DE)wW9){KAW((2KU zj-g*1YT~ih4#d-q&5ptkTRqB~L4RhbiDy|m5HB)zDiANWdX%@E{)$i&e`f7KTtCn5 zu6S=_r*}7(e&bLRH?ejg?r&`V2MRpE>d|;Z=noAw@i1!#;@QSd1>(o8zE$4MMk`K; zrvdMf%%l6faTg`U^Q|3-zcO|z5U;X&RCW#hwV@{d(b|D{y|MW(gzyHdM|p{s3=hnc z7F^!ifjDXGR3NTw^(e18{TiVr-o@I1_()@?0&!ETM|pYlTZWprm9+!$>Bde4;{H~T z@`lhK8fxNU)(*rk7@KDRcz&phU$k~qVU>=5W ze`^Qge;S($8$815(OgE+zdY2$S6Dj`Ut{c4Aimb>QQjE(#i1r1YwbY%wy{%zcwwlE z-?4U7V>$g5p(g&!+JShJu~UI~v(=-#L@V|Vm~#@YVC_I$-`J@@e1O%H;;x}C?iT89 zXOE`e0&qM;ZH*aSEeq-P17>I8{?-n}w-`GWh{sqxnx*otGFonl_R&sZpF1=i%pBrWJIOHC^NZbaRaqJ&zR9?FY;j!u_osi1%z` zCnK(J?4qQ2P^i1I(}{f%c-O)abngaRzX@`xe*@V|M7?Q~3#of9@ahbqJJbxv9{|F` ztR0A_wYAd||I64#N%5|H_tg6_$n)pEg%1*-R%m!3=j1be%DKif#ht4|HU_W_8iqR?jJs@uShZ zh<0IUCM~LCW-%nEq#?$MRu^@$`p6O)qphAfE4{)@Pb&J%Com$!Bxu4L>~ zAl}L9QC@ZWH9}3ii?svsuEyrg8C=uqQC@xedxx6%0BZ;01C5;u#0ObD%FCtSIMl>V ztR0B|X>6|Z@Q6?skFs`B{DZOiE;o3M)dTTHYbV83PqgQ}JBDYY4F;SBmqAxpb39aH z&1a$4thpBY&6+O#1-g>?^z5W@Iqmjow{LU-bS^$0d}T4((e~);{MhS#LpU=&nn>OLR~!1+EI;%=syhDAkmY?j7~{K zKM!AO1E~ zoyLGTku8({TlmA#jC@JpW(dy!X#x6>V@9k`LH#60~n|MyB-%Dgn1*}o@q|y0E>_v<{ zNaii0=wM^!i!K68Zp_G=FgCf4j2$|eI)_3hSW|SDF?&1>y=Ya@2qr~s(P(4lUjvN= zW?C}tGo9?K zW-ifM(^B+!khCvgGFOh2(a59}h?*F)XA7u}RYj_qlID6UeP?jOkA17GGhi?T!voW1=--@BB+k(F`SNb-bMGC2nIf3Pc@@*|R5P>qH}`lX6Sa?r7wNWV{2k z)8a+e4#cDL?M{oYHFi-_T)vCd-QrZ^V&l&(5sw0#KcXv)nJ=1*XCvi7l&2SXQG z^9^W`HC_2r>7H$*{IoaP`2f#hfJ?yo^dFi@RaNgaew^-$Mv8K)vyd8QF+5SiyI4CA zw>New5a(MxDV`GQ;s--rT)FGko1z+Rj6b(T+yQWSMYn~rxWvdkME4joUu27=_i7;8 zP@u#@l^I;}uO2?b-5vQIDp#d$_hC#;_5Mt=tFYmoUuW)vgcWM-A# z3a4epUJ(=Pw9MG*9IG1UcyZj}U92654>EQt5Fc#y=*3Mg{l=jtZer~~e6g`pf%p=u zM|q>@Umj}WE36%eA2c>!#SA|b>f#yJPKv)Zb}A5mXZ1k*y|trp*3e%YYT_TQ9f&)0 zv*)L{qp^zualW;a;(^9azr3nWzm?I76P+S|u{&&uA!tL5pLdJ!Flz_m&E4&I;w{E5 zN{XxZu(~TU8SNF|UHTMK!-R2o;9aa8h%YgADiDvddQyC2sEcn3bvHy0`U8MB#2C88 zVVHQVwFB{+#!dy|w?bXK(Ar6HPEWfE!^SQO%E9HW9UYPC^lOBgco%C2;!BO43dEzV zo)q64>f$k>E`Bi7-LmrOcLyx%pU`M)-U5xYrVE@wcP22;rtmCl2ja!XP6gs+R!@rG z4|VY;q3-G}r@tc9#GhF^5bxj1Zj3nB*hNY4ouMwC9O~kiLS6iFsEa=e^=M4`D?-2c zGiwLp#L3|)1?Lz${feME{TiVr-o@I1_#SPx?>@S>03$}0RpP$7|0SEkKQUnz5$edBNi;wIJ(#NCXY3dG&5 z9*tT^zh9_{`&&B@-(c)iAimM+QQjE(#i1r1YwbXMc^`ZFimx>`FWca^LfxGS3HrMk zt#OHX55ToVbcitv9)@gI`fuM~Vubh2Xz5o6(nb@@jRfEBS|L$#XPD>uZp07%VB9L= zegWPETat$0WnQ9sG=S~7@-Bw0=@W&Rj*I9?g+bm#oi5ETU|pl}$7QypOTdS0m-sLStiAX`|fuYtVlM-h$Vc5?YS*3V_cx`CsrD zI|1@Uy8%tfm36V6yCUw24bv}_6%se2T=d3aIdKzf2jbzzP6gsoR!@p&hPwFCP(h&&tF7t08cmYhm%Ff4!S!8S7qs4h1&LIUyR$}?xRR#hg6H9V9%x6zuUb10 zFETd29)%ZMJ=(S9^jCzMc$KvS@sGylzgxiTtsdniPGw?1>{KAGXZ0wrKK;EzP2AAhfw-};Q-Sz!t4Dcx^jn6SxRtd7aW`Xg zt%AE-J<2Pj-!Ig}{jD8{2N^pRh|jZnlsAO_&`=W(vvwf9+}No=Jlg6}-WdADp(Y+{ z?La)$*j&ls`>Y=2&7eOs)Wox_9f&s=o3Gh{e+qT+&(@A=Bu?X40&^_k^41Q-ZH%1? z#3zKhxUIFL8u|3QgqpakwFB`KW2XY~J)thX*V<8y8T4m{ns}DA1MwB`A`!tuy!DB-p{T@oM&wA1cLKJUEC$qqiY0t zD*#Uz?M5f<&rnU5MvOLWdOl%Hw?R(B3y2MwZo~@bA_p~T~H{$lo7(1<{ zb3HA}JuDm}bL>L&ex@d`A>sbk4#eLXI~9o6SUo9TAL_37CG;m7tvE3c{ywyQ|Fvj* z==BQpnlbZ5%dP4Mx>z_d20va8;s4XDR_+4lj5nN z?rOB5e?8!p`Q*@z>AX85?P|RFq63Xta3eIynl5m6y7hrR@RM7$WM}%>u5D%)C(_yJ zH{N}yCY_I9Ol7->w0{P^na0oOr|>Lm2jZ&zmB&*NT;16Gt0Fir)ZGl9Cw4yIxmL8y zm<82{stdf&HebQ>Hqi3qu5SvZm+JhaY%{w!kcrt4RyD~ z`>62%*!oyWSpjr@s+!G8pP$a}u9_~!^sqq2e%|MfPybbX5R&lz2=DJw4fv&FR zrZF??diqv%o$lB5w5aY8)YL9z*7fwQ>N?%8>uFJ4)$AWr*VDJE>vX@ar$u$gP_r25 zj1iBub|9{Lrad#n)s4+X3!V__ZZ8)Ry9{s!c)tyhQjth@;@3qSxoTmi>$_|(ZimHN z$C5m4SMWSm!CH@&R_c7EdQRfEh8w<_1rptVp?n;pHwWH4?$;A`7i&XNo{~4J$ zn&BtDprrSqdNT>p(ftN+JU&Pu~UJ#fz_kDT>6beP29xVf%rIM zrvmZuR*&-X>30b=aW88J;p?|s(5d|Ufh7v4Mlz>pEvUXV-PyVUuO$BoWC;DCM&soL zJj~jG_#R`Y0`a|}E}m-b=#b2yKQq+Cv#cG6A2W6;5I<@4C~qG9=R-|A-`aurOJk=3 z@mE%l^48E_8*1VotsRJS2HC9_S2VVF3ec|+YT{k29f%vAXY<7S8M`PD=UO`{KFQeJ zj1A{oJrMV@c2ax}A8PAef!p&o)ZX9ti%;tk`HN3;{_gnqM%O>Z9-GwPDxJoyAySmJ zlTnKoUxsEJuEf^iu2}gnjRV~42W&f;^mmnNFqP#c={$XG>Z-ZEt8*c7s^xT7%k^E{ zEm7RMaUb$LpN_MA7pGcU5^n(A%DBOnRk?ub>{?y3bLkU)2>qc()YL+B3;HF3(?f%r9J^VPiY0;_M8_XL`|GXT@Hh5UR6X#V0w z)(*rU7&{e+KeBpMZ#n%Hp(g&!+JU%zj_Psq2Apqf{t6cE73zeTR!F~J=ok05b|7A2 z>{K9L8tUTrteu_*{S~1m{><8exD#LDs(FYz8@nhF=UY1|?q%%sBd?HtztAu4Z|y+5 z+}ONvf>&8RDP9xmZe8lH4gKODtsRJYw_)Za<|P0&Hy6S~LfzF+e`x3z53_b4zR%dH zKzzT|qy3mce`ctO=U6)s*Ck5(A+B$1ezOW666)ecq3-69OTTfbiJMqE5ce{6DiEJ+ zb$;4bh}AFD#Qm)uh~G9gf0h9+40Z7$YxC1Ky}7>|@Vq4YH(zs_4ue}&bO;?Jxd zh{sp3OBGKrc2OXnZ0)4@1!JcV{l4_u0frNGHSVISx5M{aS@c{eyGbsj|Bls?;ziaD z#K-a7%Gz*ob7L0;;uh9Uin|y)J&Qv6{X)OEzqJGL^TtjE;uk_)Jm1<$akWZzOgF!O zp{)k?{dDz`a`+YF`Yvu}7{_a^!BLRu_z_PM#V1J`=u2z5dfrD;@@hzKHTvBv<^9!w zB0e+`e7T4W72~$-1YcOGZzOR=xBAYaH;7s6lH8=yqE}u{9{=XSCFb0h9T+wjh*VGx zE^qAgQ++MsjyJKzgT(r}Zr%upriHTjVI${@)>yev{FAi@L8htNWWe)kRqcuMZzkk@qJ1lz3GK;4n>9I{~UD#a#f0$t#-l ziY8Um&asDRv5gj~I7J3|gYX!$Z8kIq@Td{FQ0ug-(u#0vQ5qXlYtqoVqfTReZ|vfM zVpU+9Hi|etm?9l25)n;1l%FcAPnEQ^lK^g!9iof!ZIYI4nnqOhN{OJpc|&Jq9&e$8 z$3&lsC+#1-z|h(?CGXr$OVM0Zh1oF|J}-m)v#lC}t^i_viGpGjuhs^%2kt3Z1-k_PleHRL{ zY08@nSjqzETWjhv_MlB}4eEhf@l%A~8Zv$_`)YawDlhl2GYw1I} znv5QwkZIC16q;fAsiN;U*%@Hgf%dlMA<&`LYyur=&7+}Xt=SUNV!U~{LA?X$B*u)E z>}h6R`mq|=`Cgc)M^(*&oId-&`S#Kmf<30yO#DJQIhr_5ncJ5KYqTN;51XcC@G$9?Lhpn zu~UJVe~Mss%8jZ%|NOvc;)d1^#CLKX(Zff4m$B2&%E~(gFdI=HV|EeUX4Tsvz3U@D z^ex~BCBB380u#A5w4XJbL9MLGUDgSHiLL;Csj3fqW%A)#;yPlOpZEw>uS6* z`U0MQxkGPEj_k1Z+^BYU>J3s&K7tYJjNsX9q*zm>($i7!B^;vB=4chvW%UP{jVO2! znr6)f&=PB&O!BE_odu$Ef&R>_Ui27olQ(nK`}d=O_qc6E*Pp(76le*PfUY6psn!m} zZFi8)mzBZojGcZIC~p?vc!{jLxT9b8W#cXowISPkHT4nFKjI~>3sI5HgjMF9C}W6} zfjiHQaUh?D9s)S_qC>5_-QjQ;+RlYuRhh>K;NazPi*SkT&j6J_7n!-_iz=8Z+*b_O zva&0pq}4ztj@Y_;iVoU3awy&_K^6XSdc}&M0sm3R#UbV)<{8n|F3o_Cekcu$*4dJZp+x0KC)~SR&&^(;3n(I%!TpP!y+V9T&~1n{>hG z1C(TE7Ci@aLee;P7SSfxVPfGy$ny?Do?D}im;9Uv&h4EO&a34*x4-nm$!-QX+M=V4 z*|QMZ2#9Q5Q^y3zJ`QdX+8yA|q3u;}?dEj?`CUx8e3iS}n%6)Rt$7>tj5VKyKDFj@ zr~zf!bWtu~r}^g`7=>0J4C!1T#0`w;kNX2fbUtYfHnOLSlVXo0dCrzlk+^re8BWYdh8h81?y3?tqJPk zw58vARbjkdMXfKZtV2MQ+aa%yD75n z^nYTM`$gj}5QXmO(Y_MxbD$ICC@QxA-f6WCS6!rlcTuc>i_c#4I+>t?0;rcY-6A$@ z9pABH17$ZgK|MqoBP@o~jfkTEE{);}4IyrrNsCVLQ|Vp|{0Fj@GumiHN%57|4#Yic z*i94nGIn~?ls6Y>)1aS?*|SPjKIZ|vaBmB>t!7QAy)pAe-K}~SG{u?^L9?wXnq$m- z(Q8%}yCqpn)#xmtSV}5%>0&+z|=+88MCM8PQZ=wIVCdgH=QBn zN@RS!lc~J{I=Z?sMJpt6o!^7k@0}hyNEPBy(SqU!;aiT zBX>8o`P%?jTgUW%b0E8jRsk-jxg|21nBDK9!+4Q3uY$%}Q%CesYd!pewDZzk`0UrdFaYHPds`&!?8=$C=(| zC_D`C@@oX7xv~XwM%;`s2Jp0+b33e=8^;t1Yb+*m5yxAHz6$r0==#%Oha+<8tU=I; z!1*Jp$pi=$)dr@7jQUm=?dxeg=D_GrLM+XgRyAW;t~vJPCL~ z^E9M=^j_O|De0YXj}DeSH)iVE&69ziTf~Ld4#XSyluXYp;-8G2zDz3b4#2r0lAGzj z5q%4@{Er%cfhhF982Rh(%n1WXdi63HxqxD)Ln&MA)ypmk2R1?OSX_blBk&eJk`d+t zel5T3vJzSI0M$g5sc0RtcC*8Xx<(FJy^N!a=#j`F>nY>N7p;pNvVJj+0?}r`4jS&k z-0XO=`kI**i24BqiM1a#$SrF#Q`M|^TlgYhj(!^-CD1O$C}w(lsFF7jMy#bKAomTTWRY_rln|RPBJrdt!D+v-vd2YxuQC_KO3zmDc)l3Ks#ij!BGsaForj%C!jirg6 zGG;V?dG|0{(A>noT00QW zs%iI7{Ft%Rd#Jq1Xv|GC)0old^6qY=0@0(!jAp(QUCDe?epRt*v&GY+Ej|e0I6!ex zA7d8W1dX$*+u6Q!FW6ejrJD!zb=qQ^96jb#;10lvKjX3zS(5=zU!waXhZ{iQQoRq7 zHQU)hJ0^a@+JU(9Zg$7SCmB1vW6FCQuqaU{+!y!AmhzH z9%^e%7x*JVyBVp#Ny^PAr>W%wEkRsh?Lgea*nDLf+}rBW390@mp(gHY?Lhp9vH6=a zc!t%ZyzA&s1^@Fc+(Th>B|c%>>I>TL4pU;@rm6Z&pxKLOSvwFvVeC{Oe%k8MEYzPH zYT{?D9f%hiI~9oEv3iuJ{=1j>hYX{;ljm?dV@Yhz4 z^3?w()WqLeI}oomb}A5WuzHlI{!gJM-e~PWyiYBAVv6@ScKXDuNq;}UiRsQ6g&Yuu zi4U@NAU@RCsX%-z3z;M_M}&|HIg+Kzy9lqdfJShnl#JwFB{HW2XY~7OO{j z&(MDrcvDx%?_roYXLoa^1cr^xy&!OTt4F2OPllSfqO}9@zI)i+6CYsgp-J&kp)PJ_ z?DVd7An$a*)J8$Y)|?7GV9n*wT5GCSBj7FL1w4|uF5VSA&HRQa5GQJ2QhK_BCaHo= znLbiRJ>%~o3TN#?&20aHuE&u07;6XO5@V+V@nowf#mhro{F$+bM!PqL{&e82;0e0( ztR(utm_6JKoLATVk@A0R{5?fsaTjX(pQCHC;xDZoh_9(_4~_VGW2Yz8g#M9$NgW5B zV9mBrS8KWv`qC8$6kTr2XsVLV0%oc*t~CChqHsu8$n zIJAqz?e?_G5qB_ldO2J0S3+Z!0ko?%-Ozi{74V9VH)ga3Ne2M41{rOPzo#f1#}zXD zj_6v0xU;nb@tMX>1>&=;9-RZ~4-7T&Io1xuUmBb19sHHmqr4LO_W@=udcv5|)0d{D zS1X#0m|vjC{{QzhXun#s8STOUm3taShX+r5x3N=!STE^yfFaY=pA4jl@3D3u)^FeS z%3gesvA529h8VU+WZlJsFilh08Gx62qR>6i_(GS`cx9gyzX$kWW-kV52rv;$dy=2J zMS=G$B1MFO`&%`PGyiBuULJRa{QAo_je9WA>cow#9f-H}i+<(lwgOfs(r?O{YBYVh zI~aF?D0B~SqqdIR`JOx48|TjWbEXr?>TZhm6xmz4iwvJeUrP`d0`tMA4E=(im$ss7 z0WpSeuy#^>i?svs7+`W`+y%Us#TU?3jGYy~_OMNBD*+l_JjL39_&a0sC-(67R*%jr z<;@1{;0ow7Yr3k6{sE|}c&)Vq@sZ`E^RENorp8X6b;_%NMpeJmVMZ#*g_>B?c~#&j zpn=5yuy!E+#Mr!|gg>=v2~Prgvj*9r3m(AKI6T4<75|N)>ZX$}9X*-!z^7X~v{BfH+A!=vt0_Y*)8!(y7g%?JjS-4QH*p*9MFcFpYjn;{) zY^FO;ey7-hM(QcbHD-QesHHWJhdNrb6U3K+X%2jsQG!3wlqu4m7L-q1FtS8O5#U>i z5)~WQDM?}55u@`~E4vBk%oN{h?La)i*!*)cc#_qlGgEoD0q-y>JF$-98fIeoqA;zaOVgb}1;*VY zJwWtgZxEiVZL(;LF{8)8QgUxMQqOd5bd`{&#CqLe8hkF$IU&|J^mO?;pU z?I8-QMhEgkLhYRLMYU~KAMsu$D_<05MZbFgnoteGqC}xPdi>~RX*j0azVeY2ZSrAA zM*=>Pjh@oF(LWzhSTxj_(Lozd_ZlNbMby1%Ye}=Y8|X-hCtEuZ@4?Ft9Vu~bW2cYQ zJp2Md`r&yoZ5zPDpysNCnHF53T72SAkD~P7m=4 zYX{;ps!C4<;xmn1loSsMbyuSr53&;OXbE3L%2Wt15*{4sVyY7}3Fwp%>joiyv0GKF z1nFYkKEex-&g6GB!{nBTdjjP2=;@n%RC%(gmRlkYD_75~tddM=`pC@MeVik%`Y`6C zdFfAmD>ke;u3X+edFg+1v4vgoXTO|CwtgjafLTbsKUiFS&HfHxUQx*iryq!WQ^Po9 zgj+f}+R{acOYJD4iu|hCY`Kggz(i8erPg!@;yglUnXKpnw1NoDQx|n@hUO{TrDU!$ zoYrky?PT2IN=Y1-HBq~wOSjGn@od0DP|#@)i;BH(%zTlp z+a-J5=*m)`tTW9Nip`eUhefg5H6A#25qy=cD~y}@4>qp z_4f#u=?XtaUpJVsM3GK5j{BJCytt90JHZ^`{5zqk)^yoAJHmtAOOLAXU`MZ*>ftZ_ z>}ifyH$^eFZdU4V&2u50YTl+RP+n#>eWd)uUB^vC11XA|Ond3oavN-0uRx?6=Thxk z09OD%ThpZel_S&s=$yU*-&m83LS3Jzxf%w!K()k)f_%vhlK>&PysQWc8 zC!SG7-ORlrJw%rQv->h`vAXCnr$33&%igXreWZ*t0f*2H;~h=SbfOuhK%_}fdQNo8 zjr;qC)_BuEMgHw~#bfp@kv$#gfiGTU?Bb5%#Xt`)=qlF2QS0ayBirp+y2OQ5RpMon z7QOJBMfX`FMW@Cd+Z!B}n%(@lxp)=pJjjNq8@y+)YpV9j$JD zy4XgFt^|Bu^Uo3)s^X=o;Bb4)(t|qDU!%0Y;$(0O`-plva~PwwP8>}_w)205|95~E zJ#TngzI@7OElOW#O+VYOuCp<-`hUC{H^};Mio8t8=bse28FBpPj`SW2=|4|!34Gy3 z>)rUGj%rL=cPv&mw~AhnXwWcFS2x4)iuMG^&asOgaigr7Ik-++jjTvk*iNi)PFwdl zm8=Kq9aeS~6nPH7ohKe-+&x6fl1LDL@?1TN6upW8@0q#$TLCNVbu3r;Jo9u@+)MYL>MADPEzFDU-Ak$5~{&qVSwqv&LGZav84*Nud{W*8QRdM_W2LsA4sE$J$; zwQlhCxGn0JkU{F@3djer=ut%G>fC#T5X1E(%AD zX7AE?w6^0sRpwh}lrELRXm4L1$CI$NM5?#dY5G){y@S1-*E~>FO{Ki6ikm;H&wA#0 zv02aPw;Aelz!r&C0skzm$t-FC9RTruW>#IALOTDwbvC9e**kyEr#l$v#h!SmwFB{Q z#^(Q5!kes~bVq#-{q=w+p?uy&M6WbHE=5aFJr#&`kEUYWIO^95 zHSr$S4#e$^%@+{C9jqSZHKU&gyrn9nV;CmxZ0$h2$k=>UJ-pcJQ7QG8gqrw0YX{=* zjLmPI;P0&-<*ENesEOBFI}q=|-Gt_2Ik>j5(@WO9mNkGkb%pF1hKcK1I}rb1Z2rS0 zyvFL$6m(zgxqzcIP)AAj)qv91LQ}0d4Vq_7x9u8mJkX;~tPmb)qDMkm{J51xDxhfb z=T;Vd8OpBk@u55Oym4unx>mH-)F?`db!#%`M<8BrZ2pfp{EOA2m8<`2sEIdOI}jhZ ztKEF@LB>vRehvEj8m-t(*~Al*Lo5EVB2r_7tg}62+rU-RPOrC9%(%Q;9Mk z2i{de_kiY*rGM;cZq8Guf+>@~160GBZl;IP)$N+P>gmSH66+S(4N3nJN8hUUG0+2C z{Hw8t8ovG_U361L6=jSuouNe)WfTMcNlX!!aX02(NG*Z))VYpY>j9gz6Q13TH{T`5 zE7?nEOZN&R^>9&DF?evAZ)uwZ&j8;?gC-K^(Z3X&$nR40YqC4RzkzGRFt+7aUSUk0 za&81U_!RRpV}9U`du0~C^6JFosixNPqJBw<-_04xwDJ7hmS1`AgUr0&$lC&P_zief za3XWP0!##t0@rls&bIu@D~!qON8SLS@4e8i0N*k9eTi!Zl;hetS^UaN#^kLePrskn zT(#G(ttv(T7QIqTylRXAI#&L9qTjj4>CMqkj)~W=tn_#Iy@38O+_hX@$~6UD!O79f zI_6%AJ`8;X(BHQ1&gXCA!TrFsi?jHZ_cO@MQ_UNIYIX$|gKNCHS7h-k?~s^0)m#Wv zOJllLT#7y(eOgR>{?&X?dJUgNr}*^`XivX0IC?mrFqgR^!w<1a6T9YE(ETf z$9XUcTm`NLu6@gsm!9U=f!bW9T{{-L1<>Cjoa5;?V&4L81CfPN)-hzFAYsX@@ z0LO#=p8iklkwDKS(>(nRY~8m0F3^4IuGOi$ z?(TH04z_M%)g7;`JiQP0Y2b8lg{R+zt=m`c0rNfmBkWJXN>HBLDP60BT@N$>?LEEE zp411YgR6mSch#XjxCgupTzg|L_5r*LlJ%U*wXXrsI$&qe8n~9nXSe#`S${&e3AlFM z8$1tyiQrB!1-t}YTaEoK_!;~La^B>+2wdxpT?ozulffMD0f^dL-0}-LgHwTPdt>hd z_5<>}_DA%Cz4*_u*MjxnXHVbjZGPDc?gx(p*WSTi3f6!n3wdV)j(>;0p#Vp|>!PfG z9Wg(HUx8~qi603@gE2r~aheNU`y>9|qw3o&`BspF%$Dn@hl zkI$P~{K^|2lXo|Drhuv75ik#|0vkd3MQ+yII!}LFe&xLrlXopOZU8rfJHZp+V{q7F zo*RH`@{a=(!M5U*|0>ALSI&JvwJT7!K2VHnQ?mG#_dUqWdzTtZz%uX!sJMjl8$1i% z0ItdZ30RROPWgMr?dDT0i(h$9#^jBnPR$QF&LAHQ1c!X&s`7~n{`bHKU^TcJ|6H&q zF@D^~S^UboJ0@=fc^knNkihSnuT}JP*_yBBuo`RuRlNCDroSz}^4^TeJC+(PKqrt7 zx`G2gP9*ZcbHKH;(9Z$qfg!-P()5YM%mA~%Z14nl67-_xK(DUTPsz~Za$h6gwQT;q zsHb%d22;Ufz+cba^ta_#-l&+oH_+Y%%fT056{x`r@A}{(;95m&=_h39l}phT*AooN zh`)pWQJ->bz}djHCri<9BIa%IE?DBle}TOU{0!zT=NbWaTj8qlx{>~@P+tXC#P@&A ze--n-Hp@Cj<5%4E;9p=l(0X0V=2wpPDRX~vzu_Y#kPqen*Zw#46ypxh7+>=#0KGw9 z;96Pr!Q>7Dsy`OY0RB4vtbZ!!+XG-4SP3ev`&G*m5@7f>Hr+e|esd+7!44(4p zzk|IL`~r^UO>{muRd1%lCOwCKWl+=8Yh%{~2Z2L8y&v|O;5zUUSPs4iu1PNjw}bmU zeFOGJ@C(=kcKDpz7{G0y(^oE=YXSWfID`mzJE{_zw$1L$x}^@rglpy2cLtl{)ArX3-%CH1A741Waom-pfU4p%>HQ) zU8{rM0PG946{q}~G5G_~F97p^Vs@r>L$CfhS^UcTFedLdv^&AwU>a~u_8g$K=-6s3 zt;w|+S^Ua7AttXoHF|-QK_74yI0u{uz5p9RWv&ITy+;2%u=Ce^{sDdizW?nke&y{S zlc$;*Pc<(9w}88WYaeIvE3aEjUi($N4+pQ~d*7?qsT93C`Z+Q2sxcN!01p7yrei+> z#;oSE1mK#lk43*7-0As!&Ch#}S|5Oq!D`@|?9D*29|5i9Yi~W@;#&tcWQkM$voZO* zqSXSm!GXXv*~b8lsbi-xbp^B-2ei(h3pgFPb{6(IUToW$|qd~h*vtyvbo^7f0#Q_YjX z%CL6-FvivGl*O;SpFn1wYEA$T0mW#}igE39wClH{e+Xlb2*+OrXU^}B_%9&ub?_!| zO?h#83f+yToP{86Tu)X}t8T-3%{H`(c z`y>99|kP|TPx#??PLi(h%GKxUq5o&~h0iWwQ!c6Iw_@hk7in7mzg z$w?dtX784hSOqHA%1P`BT&tVKue{e{@>H`q=!5S@FbycywZpUcl{X|NPc?7ZH7BtY z__h7HAMVXx@ohnS&=vFmCxbrVG;lgN1GrY!_&-v6DD^J{7klIUr+I#@o@LmFzasB7 z=D$0?$ZZZv+waN5Jo8^3H#=i~n>f#O&im($*6~-z-AhgF+xNgVjT5KepE3Sga^mKx z89sh0dI%lh}A9~KY5V&*K&G)bH>*l0Fa4v97b>sB% z#JKq==X?-1FU_|d(0m^OGr?oPwX*6%n9l_u1x9FYVJl6aLCm9IHh9L1FHNtohVQxu zwLx7_A1qnRYf;c(y&H}DQ0dnJwSMIO9B>x60Jv5GUlp)pmN?}f5RKxa(tH*|GuVwKo zZ$wPqkw0;dFgOO}0oNYKeiFDS_L%jSV>`TB1aD6HIDD*3{_^-|IXU^Hp_b%d=g3{Le zcl+lt_JWM@JFwrqGWNYJaW7D>CHbwqkfK@Q-SiX1FrqiIMw3%ySke_@9I7W%h>@!%`q z+V;|KXAbv(`@mD)e0+Td`eRxAb29v^=^qpxW1Wx3hUctX@89jO&X{$>@t4Pp|3~~g zleZKs1Fk7APOpjX##7FRAZ}cp^Zy3gkK;jW&=$B>R{efn13d($gXh3PQ0^D*`2aJ1 zbyc}n82y-y{Jjfk3FNO1js!=6rC<~2O3pBFA-EXa3j8{2sk0vZ{1??zonOEv(2RM- z&1Xo=JpQlb?Z%q+0Chkk;P$yYYdRxlU4JINKK1vF8RrznDJ*3?&1X5#alQ@Q0VV<0 z%BpJ)4S>e%>(wbu?@sI*ka-Te@#ViBOb+APGuH>e4B+-s=d5dr9}b=eFM?Nq>JK7* z9MCzwYexJ9_}>7_z;OIG1J_hb<15!6S2db>brg4L7&kE^KTf|atgF~bU^2J|+y}Nb zj@JDY(D=1M9Z=7kM_KjRX z-4~O$oV>3#^FD72_eF;_KS<;x+T`%w!W&<4>%h+Vjt8AUFW}mjS^Ub|FD6elD{ZoC z@oT%fzh&`j4}Jn}PA*S1AMn ztnq%0GycH({!IL%%yVbJ#zuUit@plNve>7(N zzrz0;V@#m-1Hd)ajnlVy^HI(;5H~OFR}s*D?F04$2YUNfR$a$HkH@#TjxGitfK}kJ z@VcX8^9#_i@vp1@SMu^$TW{dj^9pNO9kZUlBd!DEzR6gh0M|55oZdNRp2}ST;^wRM zJPUMO+JLs8J#ek8x}HZf&jCH=_57o;bPnj;a_zq@UgvDNaK2Mx=KELpe`Jg+sXZRJ zrn+(ZPu_f#a~p`8m-hE`p#A+Fyk@FrN|#h0en zVO;}(doAbcHz-9v6#ayl_z7q_hxFQ}2J3DL^c>>a?f6Q-Jz3(E|2@deKZ89y7mNVE z^5rDeE94|9R7=<2u{`&lfcl^zaIKc79gKZJ72bD)=fHcwHO18h%H39+@^6gE??7H> z&;|4buE`z_3M=!x0bDz?6kTye;I54LX~aJao&E4VYt7Z+(h; z94L2NamqgN@*ZL4M;lDU;ICHxyV}3Q6f95*M5_bvplGLc^?St~;^bs-RE4MO; zn}_y$G0^;80R9SAsmHHtj}iAh(Bu5SF>WDq`#58M-^Z+@ zEOGCuCN(|oGUlKFEa#w=5d1xR14YbdXxD_?rHE* zM*KkH&jsg$OMq*#ZvgMGhdIn^XQ1bD*RIIoSKb#OGj9%gPlIQHj+JZ8IA+a3YtRKlEZ(V~=OP{;_cRsc3IS^Ub|GbT@Kb2ZPvpYme1V7sQcap3d%yeRBIx* z8%zeOxeojSegl5(8@>AX68i+W1#OzAKach@cmuozT=TW1p1utGL+}YWknvpGUi#l^WH%HmIu>*pUr|1fYkxCXekz4WHc;aJcdv;?g|Z{S*-KOcX$KN#05 zBknr-F91DebbjlcagQDU{N7%14>Gse8S|UV9QD}t=U0}vY1Dg|{6~Om%8%0@jv3$O zK1%*<@C0}Y#LY|l+7f8KAA?W9O5j>q^@a^{5*L9npl-u-oo4h0f(03RZ%_Xfdna=I zyuvJg)%zqSuMVHl)C0L-9(WT}-!VNO=WmLBDsb%)>_@?D;PN(LS0LBVpOeL}@ji*k zt3#c7AQ#L7Z-VMOrN?*vrs$^v*B-%s6wC%LZv%D(a{c@{S^OIBlbF0Z)Tsw@!EEpX zsKDP}yXO2yqW1)@O~rlyOam_OYwTZvpZ{lUK<10H{uNpuh7U1p=hN@Yu?HzY$mfTstIS4nTULr!T?&0DKGX-GTc~z!P8|SOZ-94gVHU4sCx= z-=hlmmVm3O@>zQ|7j6GP*_r5PgG)mH+nu_z zfIp8>S^Ub|1TynxkoPRmoE4)v>px7n_INfwIj_g$siyWzb8QO-0PTruFJ|#8@4%S6 z9L7q5ir`@2+F3jD`xP()JONzeQ1YJ|`CBA#EXW6E1J`zH!tXhb$Vr?6rUKVGqZfiq zy;~`|;w}JVGwQra|4XnD{FaxlU++jh7XbT$ie8AGiixk% zl;7ikUBSMfCAH26@3sUl5b8+D*af$M8E3;M$?3=!zQ#iZkM`B>rwN z6+8l5yXz0=)4X`U#w(sKdl?wQF_;7%2lKt-u`r8Yd6&oJspe|X3ZG*B6~?&vugKz8 zUbmP$)%+FghEFk?vueAxE{k7z`^V&|<{?M%-Uy#!Tq{ic4@G?-7lHQ=|5x`$`+D{pa3o@#ag6Y%-9-Mm_5@hk5E;O6A=hLWd!I1%54 z;0B;r*DlH8S6=U!yc_?)XAj_3Fcr8a`%&=KvAhoEdXWos?Qm^c7QgbgfXqDAoDUws z=ht?1pU&b}-pjzv$>pi$J3!Z3cP{8$aqYD%e&u}&+&Sj*z9;YAqwO_OW4qP~Egy6R zr-JVIZUT1$Kdwg>zw!pfO>cPn{X&vRV2e+E^FQLJls zX7MX;X-wW*oPVE!U3qN!*8o@dy)1s^9Sq#H!{w=FF2_KRdBwQ4suX<k^Lw1*a}qPqDqP5YdRNE)--~6$ywr;C=K_h=>3QVPpBw6H3YZPkq<4?l}DfbT^)IDv}d7FYV_iK=UonepUd1x36W@Q;hor&|~qR zU^cbl9w*x??l$K3NXGo$Vvf3I_>beiBW^O|&S9MSz%`8%r{5bhPvyQ0;^wRUE(BV~ z4`3}=4_qs&u4Aaj`vlI7yFdw;0d!1t9n@n_*KpVV+v1lo_aA`fdmnfJ%!`@#-x0T* zai=lXY~Y&4iPJxenWu8+fVlZ;Jy!$m{{i42(8xOuWz}^(&pgJuCg{0Yk6qWcSDend zSHk%WU_L`L=Ji+j=TN^hbx-!ztGaRe)82fP(+9-OOY^)GOazla3AhKiR#v?_v=l!80(s#=Vm>2UE5x9I_Fx1 z^ZAH5t#*T2e_uXae5PPKFV1P;^w7!{s?wr4{L&2ptiT4W!1-Up4JVlWx()|T%k0(*f2z!>0~iyuPVWneV83b^(( z_Osx5kXa{}I(gtauii_}U@Dja zo&wK&Uy;Dx25^${s_Aa0<$n|vD$Af%u${*0r zCT0-02wVb2fKlLTFbm8BbvmcVy`BCfFd5tjT$8Q%_dyQvHGrS@uPlD$eGM}6+ES+n z=m+`(*M?(X21bF=;A(I$m;oLKu04-EAG`_HN0Js$bf;8_D|(b|cU`L!UtZcJKh04W0#6dZhDa@ErOmm<^us zo=;2D%U3Ix$Oi+#QsCPEhJFy^H3Dw@8Q4z&e;!rnR|7S`uE4d@^nHjq0H|&|pmhxa zu4VHpNAr0e`14pz|67pQv0S1PC9}@5^yNjlV$w@1LGN zj?xbTjX*QtT4}l;>*_t+kMkb*b^W+}uWo62A7VO&^NXuD9RFqDa&RA*3FZRVeE+?k zE;}yX*Prm>{n+KD=u16)o$OQXzAj<@+K0u!wT)T)Iv%rP@>H{i>K1Yj0%*W7Yw8`h z%31u%n-!C%nhiireBFWOy2_hx?JR!fHHpbElgza{LMVsx&lwrj1k_?7n~ z$jnpCeqaC?0)~N+z_nAb|BQeC{+vf=a1Md@2d3*vKL|7e&46pA>3*!M_wZR9Z{XMU z-_@`w?X3sb)Vg01N@cz)0ZQDcFC;KbF^S z%fUu)=1%F?fBzf$Q;hkHH+~-Dw+H?_?!-R{OaW7YYo+Or5iEI~HNV{j>OWOs|T`Q%#-ss;RxuvGvdY zHuyS#F5t#(#P!BEcpLuyS^OIR@tE=VXFdmkMqmn<2@-?T``CD!J%LxaBX|(M>2=zpcOdFn~$&Oqj$^VKQ)VgK!$%Z z{d>Xvpr*Hf+e?3tdCUZlfzNm zfhU0G?waN_3TVwAflt8~U={cVxb|oLXE3*O!TI1q;96<=gS+zl0Uid+fNQ(da0)mR zoDUS&=s$?_YZX#Q<2D9O!7;$KOYmId9}Ubo?}kmg!8(Ld0h=2jG5ox5x0zSzl<6G zM#i5A?f{cO3AhKu%}e{)8)!c}gM84{+t;${n$u^%&A}bV()3rjCQly9^91O2LHhbE zeF6By^H;@x0w^tR4Y98I`Mxgu0LE$tMup?X)m7YX_y>7$uVT9jx(cc3f02j9x{#?)mGzG_k79d;xN@{4F((+qUV_V~I z&wRJu%zeq!KW2UYJpbYCPu%*nABk|?r@(zdA#hFmQ5Ice>o{pF9S_$^(=R9HYH&Nq zt<62H;7;J$JLnsL^fUf|-j0~|pcCls#h0e);vST3Pj6a@&Cppb+#2XM@2Y1ug}b0oN4Y1}MG@=n47)KkowiuKkhPcM)F# z{#C}j30dL?;n&so2Lf2@A+;!D#P67w!t z0zUTQOVd^JC-4hsSCpQQuQ&5_#r!|^-UQCZ@{RvLjLMdsB+Fz=)*)FUrew*!XA9Y~ zlMq6-WH;H@LPVBQB$2XYUz$*nV#rQ4vPSfKUpZIj`aZwsnKPrAZ@&Nk?|Qx7o%?*Q z<-YFwdCqg5b7o96p(AvGp708&1@mtvb{l*Lhv6uM^$O$%^V_^olP5JY_U8ABAseX0 zRga*~B3J_JVH0eJuizUv1cyOQ;unC#e+ZwzI71#VQ}!_n*nJGm>j9jQ665BH%k0o3BEU!+b! z@{7RZPzK6@n)p-jJS{u`+2B!-_+p^uR^yc*{ucOKL0gZwQs~mlQ&1UdKs{&-YBI;G zAp0;h7P`dBzDcazH!t1p@m^EkOJ7dRNANMMGx1)!)I113K!Lu2by@u(qf1Otr~$R% zIcNfE!TetmTj)@Dng3izbhC|1c--#?U}sOz{`UxdhiCNq;`;g4&(t<)=m^s1CJEJultH zHYa`n{eJ*Q;4G-s#TS!b^4@gG8$jMfm=3c*%}ckjONh61X;W zjV~s@mwF$-5jYEK!|}!Bm%MQ)OL>Ouo(1ZrNojeU`L+e<&wPg8s``6aIc$Qo?kQ1Yh3EO;B#ymTA;KJilP12_U_ zL2VwsnEaAA&LwXLc~S5aoCGy5-NwrG-1cIx>u2!A52^)%TeB zeqekIPQx!A`ng!>wnhrm?+1)OhR-26*XY^o)k#Rgd%u1E{}TT#__zE~%zeQ>|8n|U z@6l&m;*L@89qKFqHOY6=Pnh{7XA#8IhxE4tWFM15N=OZAan!xa_#yg zXCbTsyUy6g6^Ug%nP-5@JZI6mzrp7NI0kB28RvkU&C@5HZm-b25Jem`;2tBo%(igOZtqj?V=6R0!7ub)Bx9n{8o=u^;_fHQtR zxd;6Q<0QZ1ILP-t_$B^fc+8R4lKH}zD?Ebx9e?dz6L{|h$x)j?+}B{^-Y4c` zka)GY#7(2#OqdI5lJBNRp-Z2CI{G^4q5p=S+$FvWYm`0wfjY8AwVED!6Z9S~@p9aY zF^3*2trJ&07d71K6bYjDWNmVes8!@xRe>h(;3R&w0iS?c1p3<$j#fJX^eGi-aHIt)kQIGlp>5XKs1&(-dhIIn(G_v$|dYmxIy zj@@Wj3idop%k!B0lGn{8Zv)z9*bckkF#H53q46}{=b-e=z&?gd=KGZ?Tytmew}n7W z^oQXQs0$6C1+;?BpcYfihbB(OYheTY3W=C=3aoX^>lT-jIJJw6vrOgZaZnW0GBXaQ zhnjdB+tfp^W^@_XfO^o-=vK3JUL|HM6qwHUY48AhUcl`8;2?g?QnNDpH0In3C*T^WeS&`-dBjFK5&^|=DZ)$Lk`FZk3tbB4QesP$okY|EUz;;<}#-obNhO$5yUTf z{ax}ZQl|S<9f=oJ;Trq6{4YvFU)09)W1$eyd+EpcA`sP5H&E!I*OT0&140qy4TyQ9z* z2Ek=e+l&7I9EVeI7Jde`f9jW7(QpwGn|aeQ&Ip;I5lCO7VH`|=$uJAlax$(95;wx= zl55u|Ip4rpuCL+P&!xOdpzrZ37?vmKAf15Fa{!E zBCGxs!pNqK1fyZDP%!AjL2F}~+#J7Y|FmeI^b_Axw zEcgPX&QnkcszMED1yXM?EQ5{k@O#`x!l}jFCobXI3~uvW^qA+lySQ$<`TVTa-=D5m zkDKnFtSdHgSBSd-x4=i;5J-r;Z2r2=exF6J4z-{OJP$2FP1fPoqxz*+xAR2LhhXP{ zh2O-3q_lt9Nhrv3(X^1bf~2x8i*Cmch|qS(pA2A}%TO zKFVCh;cr88(^I(gDY+%VtzX&ibs+oP1-d~GP>ZWB$55^Z<#`XO2vwjZbY>1Y2jw+u zkFC!0zmivlwKW5~o(EZzo~yc^govxny!SF!T62749yh(7OP`XP0o?kP_4Ec=M=huW z^+7GJy1XAa&jGo=u=f)(r`p{XFXwDef4?`m2a@|A+i!gM+f)B6wJ(F3)OFK4nSLba z8o2c(eHMl=cnm5*ZBTRigXvv3kKFDLG%uLH5BdFI0K5)rUb@`3$~}wQeX88Escoi~ z+!xEetGzFlb8I+_gt0IY^gdbdo%CM9o{P@9UUf9iIj`J@$EN;2$@_-2>O3iV@0E3^ zN!?)nw#0OVF3=5nfSQ{xrh0LWAH!Ty&)N5Cw6*X#Y=>R&6{ty$J-+hUL~1xco7njM zd`^nbxN_8!`TD{-UUzQiO=e<>-Q{ul9sTWLE&AC`_fOUl-*FF7Q}%5WsL4ETdUnVB zTgY+iQ;tU+kp9y^I>>0Qb8*$HGVd6;m-!xtMlcK1658LLxrh1Z&+0ONeE9oNKN+<% zm~}~AH~m%9kK{Z6ZhgrZWB$3R}cdw8AihwtDV%;H#Y1bb}coKpK= z$y?3Zc7a__HP#{Lnq5yq#I0xEQp{7q?3>Kvrf+iTQ*tYTTfefNcR|)M59Y%{P>ZWB z*Kg-JAlH4l2J7C*YgO%Tit6{w(|qmqE=-zrpviiSi`&C4m7j0$$A<_#XCY zo>zfTwAy!pUWZ;9gY@zOw1M8Hue;qZ`zw1XJ==Yrj6MTq!%FxRK7%`rTjj5DgvVQ; z_HXH@SnnA)57{3H^z$p9k$;oV$;)_Og?w-d&cd(Yd!N6b0%|SL+QLiF6JCLSp!QGw zQfmMVg7K!Vj3>Z!I4C+jrGQkB4l+VkPKFN6wI)YtiY~zl^vYyOS z$Yq`xXrUkQc^4*t+Aj33U@xTe`^)fH4xWaJP#x5MATA}(rA{fMORm(H*dFi(*m;8a zGZPH6g{7GW)CndHvv;>=%%0thBUce=OikbUW{A#m2 z^hN0FK<2dZhj>2dBYtliR;~!tDaCWqr=z`R^l~10CG@5)@%70a>91kyH}TNhp}*o1 z{~g-*@FR>~$?uxOIk*5{U&Bw1yfn-g1<{}I^S{-%YxgH+7D$fT)5HvR#5Kp?79?IRE^$?;R}Jcb zn&i9b5$MwA2h3&rn&P3)Lto<(e~mTD9*&`otWoWjhn}3+oG$Tl+~s)cvC=wm)%SVS zITA$A?LS9!-pj1z8YExK_atxtUi>VuzHpw`f@tt1fL_U?ejD@`p(AvG?$8&chg7DI zyCqKd)7g*eUj2_|P2=EAm;_T{7DT~cd+slAx5Vjsoc*Zo)&E-7Bj=YKyE4!W?0L2! zh+pz@xa7Tr)(b{M1WbfI>)1bN{5ikt3~iu0%w8WjuU8P4h?w`k;BR<95_}IB|M?*P z%R&57ce6{~w9J_S3PB4{vwAI~%eW3a2ThD_HCtysF(1KI)*H_JjagF{v#!NK{F0Z> zB~NOu2dOy{q~>5#cXbfI~DmNg)NKg7hFgOaryM zCC;lK)xG-9!&>q|0VoVbp#-!C*>knKCC;lK)xG-P%39WK6|RQKw?7i;MQufjkW48vhH$eyd+EpcA`sP5H&>MgvFKqwT4Dv)<8zi$GC zAsjviwF&sA!F*T@i%Y)GW+|g#$!#W3k{$ds2w9N9nYoz zDn^%FyFSU842!|8Gq!QrV_8q;>EbfaFuqF~1!LjyeEc3Sj0837-(bFX^3uO0<{;DAZGZZ{4Ox$${*-U^i*-sBTf8i^3qVt)(hr85+pyEU;1~O zHywH?}T|S%!w|Q20%=5rqTsQA_J_Gps z)Aj0c)BTfm#U^eQackjoSPz>ZA@Y9o*LC)rjJ2eM)Q|^zYC+?-Ph89$CWw2uan{69`%I&1>9_QVXi%j5bv`fKO0j`)u2#JsX^O&$B?rgtUQ z&flCIw?5@~oC7%yZ^K-e4{CAMXE5&%pvU$kwUTjNdj#xt=iiE3PjCAj{ry3Y&i)c2 zZX5HSVXjMNe`OvweWy#Gl6w{0`j!120J4rkPy~vBT3mHGhH^dlllPN*I6sm?C=_H4 zIS1u6YmcqY^S_dpl(l6AyPkurNzYYXPeR0{Vcspw^);x;JZ^e=mp&zTKe+WP>nQ=U zj?|DAGMMuquDZM*IM0EnI1lXogv_aSx5djjTioC8I{*ET?KeLB`KZ5`+8=|O)OFJf zn0_Q@HMsR9_i4XCG+cyx+2b^3pPhc4*Gn(NdE|C~pn1XkrO1B*o`i~^=B3MhtK74= z-KWYuo7(HtlKW!0ceVG$a*kDkXQ2kv1HDhydndh@u;-$)u2&t6bIvRG;jyXzPx2O9%AxCAt(aHK+Vk;Q@yyxS7$D%=j^)=+N&@SM#2~v4{DNQkFR_- zks8j=CN_Q&*Pi%{yG0K&UuhV?Ys&4sIY7*BcX`}dM}Om3i+;A#{gZXXcibUr%DxQ+ zHJQgvKkS%)I5}>8%JE1G(tjlEg>OJDu6lCLnd-2GnwKFnwVIiF3GEMK?q~e-|KKuz zeE3UIe>=7JgPPQJ)61BCBr3`2CzOL{pb|U_YH`)&7|82)9Ix?7Fcp?SGv*%x z_SncdrS`v)*N3%@0lS_QtV7N0(Wjidw%_>hub_Te>Q*-UAa&jJ zRi+=wsS0j=NuMKN6pV#Auo%>w{$ToS&LjK&t?^#^BH|arGWZzOy!2{(4_pW8!)`bL zI|~H9hn>LlY0w>Q&Rw9-rI+_WdifAm!WPrl-R_tDmA#an?LMDCKMOxY5`4)Z)Iu3|gF!Icp%-`27x0;S5v+k+`?wc}{QCpv`404h zFcEzYsKu8a=~4d|^hra4!xnT(GxS4{gnMn z#d((l>^>$9;+MSNz?oN-I^(|K_&~;Q`OXh+{1E7;H~!Hu@Oyqf3y1KXGyeWT{E|1( zC2u)-D_|9Dget@|0=569|5N5yv-4VA#%_K3*tdHj8Ki^mtU=cNwOYNM1!}@` zaD)D&2epLud(GQ{Ub;aKcok&dq&KyM_Iu4M$1w8&t`YPiJ+)!4oaxB#f z<9ia8`~C5)7x$=N3%vm}f)`*8^GgqE3GMfq_howN3;p4BkbRTh)Dqh7HLo1Qu!H=* zHoZtsJ2{4Ouc`JK{+%$$?~iYNqeuN8(SL%I@GEp@e(6Ciq5WR-CStGdgXECjzi-l; zT0;B1=9Oc(9>VBFj-}k|$gxzbj;|@y_WR>ouj^623;N5@8(xEO=9eDS658)I@0;{8 z6=uLYAp0i0sU@`EYhF2q@|ny>FVd5I=Chv*58^)!p?<&i8(;bnkNVfqee@LqDIpE> zOAl%Z?f05DJH6zFM<5Jj-=sISg!X&Q`#Yb7{(wIr75A_58N0jm=Qrz5k-+}M)K|0f zT3yC&ecbaSI)p-nBfNGY>B&I7^5`{T+fV#F5!B*Kujo;~GkOo`1A}1=b4w3u3GMfq zcQd_&`uC|3k5M4K$=)PC&OH+JgsJfB3GV5@?&l+i`FCC*@z+7)Lx_73)cOkdf3t1dn(7_GRWF>ZO-G+f%tCF1Kt8PtB*FijNgRmVB=-{5y(7Wfpebu_}+!3 zLE4Q9_{m#hkg+~g-d*Gv=$J?F?rG)m-x~fdek3*J_C9%r<@aNBNrwx?pmmOT=;zRrxx^Rdbs*QpV${*s z>g%Sjl0p2ER|({rVDl!CC)WGM7a1-aJPz7ryD4)fm6JefgF=5f>Cap_ZX z9|E_2Wj#?K>!=S6p)sh%RhRco=P{P|QRiz{>)&nha!yY2_q&pP&})tM8z24=)SpZ3 zrDmU{uA4sE^dmVRfLmYE=XJ=$YcwllhlkDUHLm(L&Z8Z$8@>TGFWtvI%Ds>ro`Ap2 z=&6k!%D5mDh2lmp$M_kj3^kz+Gz7I^{!;AMf7}mpZjXW)umIG`#WJoTIUQZ{kCHF% zby8E_L)A`s=oisbxWupLcZ41;l-O4cdVyMc#;P}A+|l8GFo<93RdC5`%Q?{=`oT{> z^D`?r`%9qzQRvg59$L!;&?7wRzmL8W*1#sH$lTI{T0;B1=8dM81ME=^^P_;+MRST=J6t%KKI{=Qf;%YtZ0wpr11M>%m(Wxo3i#mlFBz zH~y!B_$6 z$a|agB-d7Z|56WMD@cP+{A%%~H}Tf~c1$*HT$lR69{0Z&%nm64Q-q-#6G>ym5Yq$4Cdg}^fAU*rn8-6hR z_!4=)fsNZn?6>}S-PiTRY=SMY7t~~Y9HhSHonfqYAc$Y`-UXS@=2c@2vYrw2x*B#l z`mPhiFL|?E@e#tA~lDD5cIo2=WlVhv)y@!4h{T4XmFOYi??)`(`FSy0eOd;o=yf?uk zP#Bga3Vbh=i?~PONvH#AUb@6Y-Mn3AA+@eSKkAJDTUX*bLpSIFy`T>agu$Q|+qjr& z#ipN_^53AJQ4j&sU?!;DX`WlnNwL_s_{_V)ItFumW0(q_M%ex2V-mt!c`hbNdj94bIdkk_o#c3xlaw)j5uJ_e4^?;ntip56LRh`2$_ zdxANmK~3gy(}$WqCFdf<)UT`~y?_75@fZOUK~0WJTy%N=bsl56CfL`mTyxa!ws<)w zd;0qgr%$=o*nZ=~-=6w~s9VbHgVc4?JDGkYrwq9DC4IgGFGFt_2@^rh=?|ta;yhXm z%iv>B^U~!W+#4JL zy@%5}nPM3y`Cqu?f6D9PGuRI)69@L$>Id*0hclp7j@W0RI*f-|a1zvBH~LP-haCRV zLHts0nM+>S(;Of4Xh;#l--Ct%5C%=5C5(m$xGyPwcr7J=rvbi&D0#e}N9dmFHtkaL z2!Euf{|t$JV=|KuFF!~g%*?{y?SO9|A`dcUOY94UEZKR4Q8|c*0uR#%gyy_W>0F6@ z;joYY*I*RL|MzYXbmwnt3-b56BS8M1br{Is)rbW7dlGX%elA>fxX)J;p6KKAl>@c6 z@y&w;um#jEGY%=7*q0fe1+^Ogb8Cx3^(PI~HO16waX z{2QsCjJhdIpHkON-)#DkoK)b}m#q6IkbZMP9>@o3an*~Z;ryjrmx5M-JB<8R`M(14@#4mX-x#UUBd(mYb5+glJZMD7lufxCPk7Dkh z{qxsz=`S|^W8_yNw~ASpiNQWpMt{h7^t;i z`~tLs7mfZt;}78@*yy3JL|+5zjDH{FZ{Z-EhiJG0YSw?q=(&m}_T_~~p(v=WV7v-G zg$+h8|2Ute;Vd*R5r`MhV!R8!h66_bmGM1g6Z?`vYEUcBxB)bR7DgY=coxis zMMjTgd=kz;w9&6Iz6pOq`6t;gxCm;&{JF~UxgW|x1yGamNSFpsmJhC1BIa3W35#Go zWC;)C$@5LH19pR26yqy!0}`9~aK;UxF|;(g)!KUKtzw}|?n>AM?Vk$tj28KkZfm^U-eUxNt0Py2~Ue~8$Jp(v=S_83~vf1p=*HnHz3I1CM{2I@EB zc~fW(t)LzB1U2>bM*H+1=>3>;D$Ia)%=}jvr>@55S;z=~TlK`gtdI@zfm$ENlVCE; zF!}+;S0GUhjt8h!VcZ7VLU*GtV!Q;F!^cKXT9eOPkOne>TBTZCAE7$b1hu&8Q^=hT z%iwcUr$KGrOW;Mg1u5$Aw;pCHpMpLc=DUq9XXddWG^y26>(f%*JDfebj1=NZgZKTm< zJQ1eD2G|Yz;2`*@9|CzmEvESElH<2DLw*{Sbd~{2kB^I`tMDf2aa##f>)7=rW!N(_sVbhJA1leAEwtJfId+{B_CkTN-jQ zK~_h;mtLQ^bs+0q>0hs|&8|BxaV@FW4!S~5h)w+^{aoQ9vF5H;$V zI$2ute$$3{=GX}08`3_IFaBouUqL_X$ZLYHC3FQft1U6Qj6a68a0V_z66z+0XJmfA z#T1v-#1&**49bAb_tJY4cLZde17ML^uddCm`%dDAP=5qOz!Zqfe7pVevd1;d{_pe9 zB`y(hkAsab;$L4^bi1C%J@lv0n}IWa2l>-F^4Y5s-^)TIeAhW}oW!35e`B=mPQ3%i z6*7Zb5~DRXx{O;x2Y3@^!#nUEM8ZC}3~DjO?=W#uj8DROu=!qkZq_o^zusB?_3GN} zy5kZTM!gbH4xWM7)PL0Kptc-I)0kHXAdOPC20@;h%X1%f|yWY6O^`KrK7zD#1Hucx} z;~F#XLbIQnJamcc4pSWQwfyVYg>L(A;Gw^O-XEOt+4^#S(vSV`&$R}=gOvjU$3y(j z;V+8zu2aYNJahuJ=Zv=0=rUdfpTTj6hAZ#~)#?TPCIy`djS-U3jIZJgBF36by(w55jD?r!QG!gm;s z!ml86tvCLxi+EpxJTMg0{w@7cdME}Zp`q!=>fz|m#KK>Nm}*c1)SPvk{xQUkhY9e9 z$@{nTDfI9*%!4haAFD4%Ul|MkYGT&HI#6@gar$o&`-K0Tk@LHi|23fb3GEMM?n3_g z|KQO%e|-3JQujBw1Zq;(P0xd_{YcJLaO+E6V>>|lZ4Vux3#i3a-@-L_JNyJE%=I_v zP=00rwV@TL#Z})*Z^@VPo&@iKn&^3!@VOsKfcT3*PZ$DYVHT*}NqqKL){Sl4K6?HJ z4uG2U<)&Lr>g&2R?|bsR^dIn@f%9fpdaz)0QGC1qVT3TnapRf(++O`xaA>&_6|fd2)B8Nr zf0xm`rp9nA;FYm~es1wRJ28pg#|7p(4H3HT|w(ym%bfC73rpP&YT@(ohD<8hsD(U&DSl3~H)Hp(UYK za!3Pe!Td#uEdx(MQ!a2iTYNbC!TTF@9yfZE&sIMF*BeG&Q+_y|_RTG#|?PM_*&Ci3$$ z2!n%g8g7D`=p~^nR5g08NnDd*4m>$I5Z{||U+515W1+|P_sg`O|F6aCdc4*bTffFR zAHC}S|4r9@@mhBYvgUH8N5F<73LKbW3;3P0z7 zaM(YUdp(Gp9=N{FLH`79z|;8J!bHeQOpQB?`;b~8)W{4k!B~I2f{uC;cMra#(AUJ} zaKz1X#0?}?O?*;EG@Zxh%i1=AtZ6>T`jbsd?7IN6MzuBmxGDIj!CMehywo`dQs*lC z4u61JTy^Pj2SmbNkhzz_N3asqj^R5E)zRu2Jw0=G1vzH+_~t;XpMZKvYFG8wZ_nI4 z9rMS=Uz+@SCKs7FWH`3hrN5 za=!xyKuz>%umo)ttcJDlIcxy6*v3h%888>-gUnY9N<&$2&Y|@e6T1#%&P}idcEE11 z{ca{^E9`(hpcct^FMI<>p*DGgK<)qe|JnY?o*svDa1;K7ME*UNb4Ts}#ob-|67n(c zt8niszH0!r6lkd+17rdN|7i4a@TT!EW4r=Z!6w)OyI>!D z3u-oQy+dElbID(8bkU@)Xf{5kxlWn79=cXU4FG61$3;%LrR=~%g z=B(rNUm*4pT!m&F54C?wzd;{K=pz~AHT_sU4SI%H_%jpp5M%>2XC0@%Ik7W9UYqhd zk#kR9OZIj0Z^aFwx3P}?=F+2FLu`Ku5jTW+r!voUP?LGw^w(Ybl-yb1*01b$4v=+h zgfC$$sKr%3&OL6CS$y{foo5H?h<*yr!g)~h(rxT7#9x3*CNG#j{S4L&pMh^Czpn_l zK>BJ5eP9&KfcM}>s7Sx{!1i61{K4SN*Z!S;)vJ-y$KLI5?cg{!Q-GNdQK<^cjC7>FH%GM(fUrm>JlsKaGq+!9FLgJ7 zp2J$V7ssX#yaD6jO_&F(px;~k3=$rEJFq_*|0(`RP>ZW>=bJ{InIQA3{Zs!wYJCd_ z;ReV$mV=tpulg-weZ+;pL;jpdljrnnUUp(aAs3VZ$%zIvr(gAQ#DqfyXatgz-0Zj0 zuX!iA2A`4Z@TVL*m;*n9T1v((VS60(%*1Aate_@!+;pqSJZb|O4~Ex4`cg}>hQAX6 z$)P!Pf^D!9z5=!Nj5om+aPvR1mSYKvKI8KM?1vMe_Bg&L;VGy9YN}O2t7G()jFXZd z0k)>*ZN$F=cEeYorrKV#!$!|Yod+Q+fg)OpKr+D%$C1*v7T7@cLU)t1|nb~zk|3O?y27Yp(2 zgVXTfVqUGnF`DzJ6*{L@FBSD$-5{?oW%`FHB~%2WLm>+f44#5WS6 zO9uA&XY`A38AAO2O+3ye<|CK58$sfv{(P5wsht)&QB!Ik1KUTkAb!ak;*uvdbHG(7 zivMeWjIR5EAb!b9=aMHi3;Aox-0S@@S~pJ+zw}bwB~NOW0oh}jTlQFLt34LPFL{St z@@k{igND!))Yg2#z1Vv0bzs-;B|_w8GE4)tVE*rkExVb|cF-Qw5;2Ysy|_o6$>`HyCd>!53yd$rHMnVX8K>C7 zafWcH4NXBUgmFxM$$J!>dA-mEz!;beYM(Iv0ye@Ph=Q8i0)Bb^3tWI3a0^1V#@=6r z*f$|FH4B@%an)b%vk~KdJcH#$I-8WGkzBN^I!pd4Qf{3V00O8 zg6*)&=vK3JWPAXQ!buY^<7@EKcD~Es!Sw;&0=4r&{E~MKoOx0+Ir>K+F+=>dweGDT ze#zVFlJ^)|6{rUFK+Q|e?ro)1A2bOMIjuX-y6_J@O(6E zhcloyjqx0K2R<^oj6a6eum(PZFF@@Q<1p&i1v}4G4?Tpq3@-6o(IR0V{0VAS|JCR+ zz5rL@y3ws>>tx=?&#NKne*Qfy)PfeEmOY4H^0K<*NzJmb*I#=)F>_4aupoZPI}6Ud zm(hAdU-5yOj3s9dY3)a(ROQ|5k@ns&ch2k}eZk1lyqQ}$o>Smu^qrMB8j zLHv^Us!Lu5G}(K*x4q2%W(ne#ypkZt#O6ImZ%yENm<$VHJE)yyd=+j&k|TGnYmIc& z$ZYC(>6uG~`0~QD&=1tId*~9^1iFEZpUv}Ka1_#&4%Au1^HnbT`yRUF{|5I_!`AV7 z9miJxx8ig^o%8GSJN0|zsXj3k_x5lNtH9Sx%uv;o|=r)Kqe>$RiQRCgttL0rnpy3+$hEoFa>PB zm;NJh)%@!pb&PvmxC|*+tE{;Vd}!8vC-LW);{yB+f5vgX()1?%Is4LmDIdfyd3()z zG%qJwcbMr|Up^1LIC?FY_fWA^YTNXwctnRSoAHwGq13?yXy8kxhRkE!^U1@XU)-`T%tHc!_tYu*i! za0t}ms-GkGxl{D*Kfh!T<$RR$PnXlQ(y-#-Pl1!(WVQuq+mWb79IiHH6L`hIZM_x(!EXuij} z#On&uGj~2SzxYESCDez6^rxo2+7pb!p#nS$)xmB4=g=F&3(y)mfUM_lV;p_q_S)96 zzC->s${tTN>&!@8X2=bl;SYbD)`?I5Bh*)`%eWCVg%_X=xXmxxi;i`iq{r7B>lj2_ zqgcd^AnrSuLk-y%wYcg#J?i{{p32{c%;D@aF}|4maxM;Z$&)=;408OWrdnL}w>;{s zN8bcnU?-?um+^1B79cgGgHTWl=C4d_HK+;oOrDJAKsDAPuT8aP9(sH90WR@hqHTkn z5D98B&U}&YAE_;KsD109A49(i&iGQ)C=2D`8BmjP1nlHk$!klks)ybXy^~A)3bapP z4SWG=GL~zTT$7|Hwap&-*XSp~8NZI)&9Du=H+8)9s#o|q(jR<=fqj1l=Ix2z4@STw zQ1jBa5mUuqX916MZn8%B5zc|{7S}fFuY_%8o^#}dUgtjV#+~PfUkl8WgW58Wn$%Br zm2(-MfG43c)P^RY7E{c46DQ;8@HXs*Ban~z)!h6(<4?ml6XXD!=cQL5u0Aw@4xl!S z@mQD$GmLJvZ_p3H5s>36$0a>`BYUJa8{b@52nikkRSbPB#kVnteZYX`<-hr==rJVbym*jY2ZAc?<77Y_0vHX2!*)J*Tf%Rl3rehH~f9+dRqqZ zOI{t9yx;t!%vynDi9*Q<-?lSIyS3H7c5Tt3PIRiKz#}ICgrB?fXTwAb!c426FAUc~VneQ*zC2 z0&0yt^tR{&T;lcne|^+C`dlCXEj`%$!Ter*Yo0#dt#Mv`{jcb;-QT#bC%)?5>kIKE zhx;KNsD(1F0QI0LG>5jJ=B4i=CQTxK2m3yL?-J3Gr3Amp=Tp zS|ttC>xln8{HyV2!5;=1SIfjrAZ|XSLbLib4_)GNz|)TS)x>X3{D04<>l6Qde*f3> zq!w5GhDV*}sof2v_WfqPI#25$e#turx=)(dgS^d%(U6FJl08$q z5yUTfdtLIn)0-SiIY#z4_x8|-pigy)52d$UkQWMo+91Y}@D6j!xu!PKL!XSk*d^YV zg!2+6QbTH~CG*fTqUU#s?~k?(hEhXnslD!@zlr{?OT5%*bPsC-d9Bo=R%>_}q_*1q z_$AJ%XY$Zu+Dzi+!UEU~+hG@|iT^DS|3X*{ZgJNC1u<&zr7x%E3RneeO?}%- z6uNW0+Q(UZvLDX%--C7^q=q4&){$`+=ngL%{TcSIGE{|$Fb9548REMERZ<1=2mAf~ z?q~1eG9)(sH-h*jZ?sFEozGd@&i@JZSEu0LEYMe^zrUE`j}U(Wq{k;rpC>$YiAxVf z9PzhY=KYiT6SJ1&Abar>sHLID2Ot}igR!7}KSo{&coM>)4XgxN&)r@pAL}RxHR-i3 zsEJktL~9TWy%@2wFO7(m^*h(Smc85vd*BnVyTq@h=1$lH-<$egy2PA@wDd0LyqcFTvA@D) zxCUyX{pQz_m^xipPcP^LV?oVJpG3^tFb|fPcrU$uYF_U!4Hko1`ZT<+!nc`1e8)j8 ztB0N&y|hdGAc;@MG07O>yN5cJp%W|st=;*7K>fwUrzU>2iLd8~uW#b_5`P>n5%aXs z4|wPjcMoxogN?sN{O+`YdBtbv>4a~9@#}uPbG_QfS$wh|&h_^|>j|$wKTxaB9z6$5;2l^FPiE!cgTpCMd(-b1eF#i|w~c>l z5WnO#bjj2CY)w1wR_Q4V_udbM_(I9|iu;wgM8qv4#^zu4&?WA3_`wl>KQ%Hz4$ygL zF!yYD7u0NAK4NP^dyqb>nz&aO4}`%m)ad&d%X(xFr5Ck>9{LIN>)?$4iaDbo1wNTu zO|%nm8g7AFmTcT#K`|%^YF_#^VjjxQwG)H}?`S6MhD*z0}lyg7~S#XU4DbgB|gcOnfWidqOF+Ax3ZSp-bGe z(901&g7^kzUa4j0xr#rT@#}uv^w6dMVo=||4vl}E8nQmSe(6bVbP&Jf-2yo#HZPL> zl{uwnyPw~B=*Q5nf-`k%jU>i?6mT72oz)Vv5+;D)Jhdk&><=X$k|{P<))oa>*5wg48v`=Dm^C9%+l zv8QjqC@A(QdkrD^IX2L+K%nky{MYjRr$4*#ukrgwkv|3`e;RxVHtra4m*AK~KkcDQ z+(k&sT(-_t;(rI7PuHJ_9+N|67z)E-JZL{|amD=pG|W>1YJ*w}eC?nEbOyE07|VX_ zCsuk?+vuV1KtJLVKa9Q7H5_29X7vd4)nNUiO@Zm~0jPyCmg6XUWshH84_)GlKs87F zM4r!vIj{(pz;aLv=HHl^e}4&A;MoWHTl?@bsO?Ap4!#GC%Z@(`9)l847Rp1g{A1LR zdA#zUqDD;f|C{-`Ugy3z^&eTE?X$GmAGh_%e)#Yl}YuCc+F*i%-2Pb$h`;Q{QT1jV@!ie!TPstfdh&1-njN zN1lS*V?#kG0^zVQjO!81E*7{RsQ(rG1K>3nBC+sBVeYw!??U_puz7CrE6G^{>tP3+ z1+}=wUnDnmA%5ly89~iUx3Rg2zeL}~iqbdC0kzEdV)9E~N|(HF@)|;8Xa;Itx{d8b zd@Fy=B|NS*{j|UrlV9?BgEQ|9@@B&vcn8$HbQ}8-@v=8kTlPk3tG$aaCcorWa>?66 z-f=huXF<(Nx3RwyFMARVp`2$0%=!5cMl+4Ag8~LByi)m^yjv20fq`ya{SnAEP3V@4-@72ge~A{)EIVBnjLH$z@S~v+-Z6 z$m0Vr9Tq`|iI?YR;UfGFYHiE%ITkv>C{XM8B%f#DIGluNC{m8&0+m2*82Whl15y}$ zInQmrGp~F&KbL`u&=l0pKE?QHzMF=MPz9=jTA~Vk9)t(rA;oIf&wH4@Tc;3>Xe}cXnocbHY&8WyJQl4iAtFPqwD%cH?un#uW3e;Es0rdM~p`RtD zZ*6{d3?X#_b*}jJeGdH(^a5x_K=Pda+|(!!6`-Q2SDW!PSOm%H1?KV6KP2u`SPzkK z4QyVT`pf~fp*^UDH4O2+1U;cQ422P(c8KvYI0qKDQ>Qb zYtxvY=R*{vZW72Z$@6ERGBgLZg-v-sZAP!K2h_H-LV< zmq1PDb?PbTEjxrl5z}W}^+DuLf%WjMsS}evg1D_N@oxGY;+8`+TmrQetvL1&0rNpk z^hf>roLK11i0KRxYwN7x`2k4NnmqzFFTFi6OJOy%YZHj?!}v8A0^h@FxDJWh^8Nue zU<9a5Vmt+Az`gDG-5;0&YU-ble<3V~wV)QvKbKkyVH5lSN8lKogJ@7Y$oQZ5i?-+e z2dcwpm-`S}%8f%>5K z1LMk__*pl!1~o7JGV#|S6|reed{}3`+w8)3?eH`-f{tAS^~7HW)UWf5N1FoE;Vqa8 z3qY+gf2+I&w1qC9Hh}R^7!Olpq5HU}8BISCFdgQ=dk{|ULGZc{EW(7v;BjcJlk@l? zEv|yEAX5^bFBI~CS_j6RVGwLI`YpzZ?%_TTM!+1{2x?32<$tLGo8Sy2zR$<+8>^Rj zgZL$Hze`?HN~D0a@JFDW&r2UdjNE%(fomS|axbc8>sWm%0W;w(I0V0d)K#-uOHXT;-B>T_@|XV{t3?CR+9a$1$ChjsP$uy2Eb4l32H|fABPig&gl2E zz%-B^GC@|z4SC^FP_tUgWZeJ5OHeGi&sQ4MVjK4|xqYBN3<9+Wsg)gaLS9pM5#y!s z5o|Sja}It-=mOp4MDSa|`?<}AiclNW%BS)9ETJg+2-#p0oAaj7) zM`$0zMu-G8)ieG)N!_z>KJ_aN{tsCnr-h}jL1un)e4YG$5b{z}5_t{wPq&$fN|Z#$mg>el9ko-gGdzQV10cI)vn4cva{*qU%D@z-oUy8YGJ3tc+2 zCbb*0@SnneO?`WsRxgvadN7t= zE4lR)BIfpq@TOQ@u%DlO+5pz1pUw4vPM;@h* zBcStU_&td)!r7l{;?|paHST8<7yd^QU-2*TtGx${hm|Ht-7~6GlT!vuYWL|r>kyN z-KtZkPMxY-*L-X|u`ul467=Mo_YHpfQ5(yJy(|{*+b`ZPsNUhOw12glc=kTJe!PEh zQ&sL>ewYeNgb*o7{~^9Qmw_#ryH!4-Y>3Lf0TRo(#G!7c8N@j||ST zfrQyV<=b72zB=&8p!Zy4hu>d={*d;SzAn1OPjA1Aj|^V_AU~RqP0zCbEqYo$dfh?m zV$C{d(Ycy+4x(Q*OYT~SYSvRg(UqEY{fJJ~ESgj6KFzwviJsFeccFEeX06afXK9v^ zfEgz`M?S0pt8dXknlZEZh`x~z^LzCzIz_WKp+t9RmYUOgLbEo7L?39@CXV!b&Bnx+ z{>_KyeF?qw;BB-YsK-t)B+gmX3jK{WJvoDi6bz z#vKJJIxVZIdqoD@;&^sw+%@k4OJo)E_{Eu z+2cdtXU=xvN5Ba${H5?r-i03zH+h_f1CKl4V>~_yKDggq-vvM6g|C38&T--5(VF&H zyjwFKpAFA>JOF=v$X$O9eBdU>C5b=kcni#t2mB+S1;Lx(W{=+nZ}s?6`1vC){=4C( zlH(7+H;y^}C_Gnnd?Orq;kUvEdVB}`{ECbJMR?i^zYqT5c`p1LaHq%LfqOmv5j^hk zEIjG)ui(JrKM23cr7x;=)?-vnkT~Ck@4}Ei=kfF5tsd_UPkDSGe3h5p;qbJ_M@#%` zUHZqv6CP(^dGo3MEC^l&%iB;bFNOn;yJ2~YstwOdxcP`a?1ek=nxD>ZqMx_H)2!@& z$nbmMIZq$o3jfv9zyAX_H&QA5C;IOn!q3rj1>qAham4%nev{tooJq(ffBN?(SiBUU zwfV=wFM>;qFCWj3V71vDa6#xW})BCp_K&&v@w#N%)st`A6ZCJg&l%9={%*@^~Dc_W14ajK`P4vmRdo z&v|?m9Ng#f|1jL-@yFn1k8gq#9#6rY9^V0HJ-!R>_4r=6-_p7i*~ z65lJo_&kQfdCr31m++$vQ?jGL^|L@mbeclHD+2hZ`zw-EQ_@^G<2Y=h+ufz9yJOh8hV_998^7yCl zbsqm5{(#3%z?Xac2l%ZX{}tZm@iXwK$1(-(_xL&R86NKeukv^wc(KO^!fhTO1|R3~ zQScESzYIRW;{?3G<5oEE_yqXLuethP4FAUCQ{YEEUJXC&@jCcx9-jr@?Qt)ByT=>h z8$BL|ulBeMU*Yjq_(G501i!)Kx5DRod@;Py;|cgR9={jPdi)`{%j0X{S9*LS{0fh6 zfsgX|)9^tae;$5;$J6jG9^Vf?{eY|Q2jSm){2ln`9{&*jfyY0CAN2Tf_#Tgc1K;8C z9Q+B7pMobn{wMq%j~j8(T){0+zZTxb;|=gXJpDcd|Hb1`*nY&Gdqa#b zj`7too`QRS#~hVJ#NK@dp7@*CSejQjmuevCp8+?&xFNWyL5H6!yemd74iB*(&yU6T zT(au=j}Sh+xFP5?*WV47JbPO7)7Iq#s?UNz^wWXej%9^&daYww>3sTB$3KPtSDY*6 z`p4i0{^(frTd$YC=(nuLqTkv*7X8-jvFNuZk43))9*cgP^U5pw?E#NPzfF29`mN-# z=(k>vMZaY|{tfpt<=y`robdQ5c+%s4!dZ_SacRENEG(yO+3*A`Cx2LOgSQ^$_(V83!f}^e z@9|1lPI<7`_rP-EgXOc}IWN6FSWX+U;X|Q{?qVjZ`mdI0VainKaVA}G=X#@D;_eh7ch<454Xc>HsC z@AF*zU%?AK{vEvD<3GWddi)f8uE+m?Z}3=_G-o{C4PNjDm*4Z@q{n-~Lmux3U*hpW z@P|D<48Fr-mgR$QdwdN1FOQFhPk5utKLx+m<2LwB9-jbz%Hu`w4?JE5KjZNVcu%kW zv+$~mTz>1}Q$2nyyx!vt@L3)Y!5cjug*SOzg~vR8J-p51ark_X-wwac<4fU7JiY?H z+T*L>_j>$c_!Ay~48Gjso8XUmJO$t8vG_j+FLw1I{@8OpzJvHzdo2FgCp;E^Y=bQN znf`JY@$EbS!^lI z8h#Oc6MTx{h47!@j~iYAfAGDWtYi4K@F^@pikg=EN8mGI+0`n1A-v@(p0+UI6B7P@ zo*FZJGyHvzzY6z!U>E)LBiFONBv|`FSDxR&AAqkg`gHdLSU+JAW_Qw)_2_-zk~bb4 z3UBrFV-kJ?Jgwp%6fA;|o8+`7linKmgah1ol!KSTR=;k7vs|y&cMl4-!b4vA7sA6H zUkMkfFa22%h<@qwSoB$k$D+^Hc`W*8$Yar8T^@`6I@9C#li$?e*#D&NZ@=IR@MI59 zyu#8RKZ0l5c+0NgCnf$So?bJ22wN_iJ2@f4v|kbquH!8*E%9j`{3WraZrZC!Pv| zis60P0yFN(M>{-CeIH}OPk~G8cvG+8VR-V^hTtbAzuVy6CmVu`SvQmN{RGak|G?Jg zKj66xZ$C2ek70|=XKvuM0+ZgW;MrGka*N^BaA_S+=9u`ehsP7Vb;*Q(6qcvIn@xRv zRjyyGckW33{{v6o-ViK&t}f3$Y~ks=o;Q@3>t78w4P#H5>-%9pzsuqA?{RXA$^U*h zNV)ufDe>>+Ew?5;=?FJn&j}=kUnm`8--aM%BYPu*YE~do(7EZHY#;OxJ2 z{&K%RmvGwaRVMsja1;IzD-XxLnD9q};7$|X3D16+Q=JT-2{(D`$6Mio-t$z3e9CUL(Cj13Q@ubI-dgqyx?|677&0C^O_y%|!eRzW5^Wbbj z$CvuN7M^+$r$C$VhvDXSx8LaRu$+Eyu?b(uKtDnKViu_KE{A*XMqe2oflFOHnP=|j z?ZU~1V9Q$m3P;%p%@eXX1~-bA;>hdcR--?)2L8R(OK`f*7g$xev~MyCGO=c)?4_f4U*q z-N;V|+)H|Pyjur%di7g`$G!Y6go6`#vz)p9BNE@!7hi`@@yhdSIDx-*jmiIcD9Xv# zHiY+cEF3ItP$w@)`<(>Oh2stT_uvWo%OZ3A2;5tC_Rj@yGx`UyRrh{`h5_dW4yNdaeow3GyUUi6aQuKT-M3w3b@z1p8X-dZ&okk#f}6em zd@9`gnA0aC@GSo7g(m)G@SLabJ_nD#qLDk%<@*`z>&HLA6H9oi)`UNwjxy!7_c3tO zIXvBJ!dJnG6Wn;$3y*vC^CtKQ%)eVq{k{jDIISVL)Lj2n`1|PV?;HLFJnQ8rH&Q}B z9AUzbgvS{_o@;mo+}p~V(hU#7S?rNh4PPMP+>iBtTn$g1&Iv;%{Hy$tSmEr6f51(Q zZ&tq?`U={M>n||zTi_<{Z_scSp8lT}wK?0tlzHc}2*TQ!Ha0BzDAvkexL$G=mqfg)_HqTr87Cx907EOIG!mv)9!c+JrzX`bWBu-{Dd^;R?mS33+jtA6NpCTV#Gg-{4kuQ- z`Ovwr-(N38F&*QEc#cK*21jd$(vH1j{(e@~Zi#`h!Si}Jq# z?tQc|$nC1-=?k#0zrG2V-tNYaC*c>r)5+Ja9n{agoU&;0KMeNer4w$F$&0DKAqhu6 z+W6twh4*R*o-}+ZJV}4C^RKVLz2`Lq_nQ9r54f5B#;~Nya{z|u#67&F)o=pN z(w-kQyb&&~b@RP9!jo@q4E8tmaiy@QzrO;{5&t-I{VY5k>W71Zf5M$V4}!Ow@B>fa zdQLd7FWOyiO=}iX4?BYIPnMGTFw9>_4{4;Y0rN8JzUzI=h#en zk9alp(by1N_k10H4g4znQR61RKDhIP&R)9|_UB8Ja=ka7yBnTFey%gu{}`USoRcmM zKO^DTgBKfpa}*tO=IuOLVaju=F!SF-O#BKwU2O>Ge;2|f&)&WTp2Z%f`09S|mhcyH zs*OqSX;@AOLCjV7!6(5zZvJ&LJar*^d`x&A9^a!eSa0}J38y^{HT*HSb1NqznEL)I zJb9MZA5!1{gqyKn4>$2&*hzU_%85Wmf1M6DF+P3Lgcslm#^Ws}y|=+LR1RjlD(?s3 zrgJ#~!|U9o z%Z6a_b9DX}!~S@50~}o9^w(W*=XcnXXVQBZZl-@)d3_Qd$NskcegDPO$6k$r>^qnG zdKWxPds=()KG?U|IiTRP5B>?>r)M({qbw~ci#HiQ*u4?gO{4?5ACA<(I@*G?u4ga z$>~Ri*TZ-6P{|F3^Ai7Ejlp{wba~zgk6+dp`ggB|C$4w?sV~9)csvXH^|R+P^81Q= zp5}PC z-vmD#SozvBxEG$tb4rql|95!ydz{3ut4@EfZW#UZlu7?sxbzm@Y;5YY6V86QF_2+X z(mzYWIhjeGCl|f~Zb$xiCtT$JHh2godBtCc6O&G#KPlYn<_~)>r@iqf+41}+xVPL8 zFodb}m%%0Uq1Dgl!_8ktC7Ap_4L5x^2v9*P{jeoy`6Uf^F6aNJ( z`D2dfzfAq7;n^}b`y5^V)o>H`%o|Po_rqU9U#1M-2{+$QofzJI71wWd^VwtJxj|0h zGvTKSkGt`40G{yV{S9ylc|6X^c%%g;je*vzeyg3-vCeF;o9d0*zdo0!{gLv!o+_P&OV5L z(A-aZ5ABD%KhK1p3(KjfRv%mpPcvRWLcpQ0nxe0#@+{FABvr*mer{T^YGiI6ceg~exe=%vo{{sIs ze13Hw_28zwQS?9~uPvvM--jAPeZ2`z{HRf#tR?MvH9Y$$YoI3mJB3ej{F748-hE`_4mNzOcty?`X>oT zo^1L}r^7FH>8%xJ{8?zOufmheZyvY#!E?;F8S(?UzaPO(bk=X9Vub$+_oDBtJ+|i= z)Cc4HF($pk;a>c0wm-JOzCC-oF!E~kMHvn}`|}bBKa>;DO?r336QAVm2Bth4&qUSX zzq0!9jquDG-hyPp?}a-*(ipTG{qZ;~=RJr-i9Y%pJjeKafJy)Gv*2}&!MDwL*#>w1 zo;?cYehYAb{jjHr{}u`N^zn7@#Q)$@G~r(oM!!}KKLwxRjcx8j4Z2y^tn>>5uQP}U#Ps7(So>+bLoYx^goX&!8`D|NM~f&ln-?_%+?GoJ?{E|S*UIm~1BA2w^lB5{0?&RP`@2!ce*&Is zboNFA1^4G~hr@H7?*5Z-$+KTifqj4RITC+EV{pZ8I{ml8A11!&Be8!!3=GPd!aoLgdh-4ycxJ}Q&+p&~?4eN;f7b%xCp-B`!g8wnVpi*`JlIuPDe7|AhUxqzy!e0tcd^HFj+f~P30cXGE^z}R7 znNu2q+fDhW;3@RE$eYyf*WfwIYxVCVaMN#P4N-?5Ji`5Y`M(+te&_7n*TS=ezud$x z!A+FMjyJc$&8r)NE))I(x&Fw80GGeY{|E$S!t;N$!jHoQ^Z!A?a<~`ywfba(@Un&= zVXl8OoMrs7^6-9mZ|s?SOn#q${rwByfc^agkHdT5Kly}-|99Bm&u};mHF>YIKYC$b zo-c#PPju^B?}w)^Xbk)70VV4D)P~^QroB4hVe}Kt#r^FWoDOF_|5Fk6{gWS(>%IBR zUGU7=&R+R}T>k=2MmFVdIG5|0f6BQE(!Phn;}_!NH{tEDKR&O6{rPtlZobd0e|=2& zdv1OEOA?>Sifzxw;mKQ_e!r?r`mB!~V)DBao_dC7a-XZq^9WqRIb`>b98)2^l=I&$ zg-cgA246GnyA2-SyCJ9=z7m#GfuC>E{~SE`cJ|~Mei&|g%I%lh1;f$b?{Fv_Fuv|( z;xC7r{^sJ3!3ppFuYs%Rk3EPl_U;$qY2?|;-=pxSY0v#s_@2Sv;PIk9sY&X8zcJGH z`qQa!iR;&x{Lh2uE^G{X4POQO{-{sDQ}=NMiMjt@!_DZoeNFtun|Zzt`*DF`IeEE6 z|9*+#EpRXPY^&jq!xN0pOi7e{JR;$qf9KzD!t<{lNJpO9YnR|I(|)Vrk~dzCNx0`P zx(L48E6+#ZPUZ(vKT;oe!NGpc|NE+~)|O+U*03(gWB>qkgbYPBrPB0{0?6Cm9}s=MYZ1fy(c#@Fe}k_WzsVg|yFl6aIO4${Qaa7G^v+ z!Gu2w`~Ili-a!4({s)-wBs_Pa+h16P_w($NOW|?+6R1^Hp6|l`{Pz!VqLa7em~feB zOk&U4_Iw$fV7#&AUj%18`8*T$_Y)N13Ce${N$)N2+~=u(BTt`#dp&#OK6n=Ay_L^L z;i;E!BEE@#*qbOnliw>$dOdKnHy#cOQ@^%8-V0AJb^hyH`8Tlt(uCg$KjDp!GjQ)x^ouFqV{mDa^RGVzce0<;>Vp@KvtRrM-nL`n z9|OywTh?EFCOom66Z_40ajjx!4}KT+{Ud*XvzIvk{=RSK{>bl%K(}ui4w(Pj_C8(0 zJKTPobKqX|L5qq1PGRPow*GH|k7GSvSjNYDVc&lKi*UcQ$B(*z`tIFDy`@L)x(A-2 zK8U8|ZBW9ydGnj$DR>TjV*AhI@YHJjXAL_3v2Wr281IfZ@mIo4qYdGHtBvpk^Pv+> z{CC5%M|ty0xI}$eeY5LZxqq+y4uxm`-59*hq`w%R`IbInO3Hsa+*EPv=jXx`H@p3F zpMm}L_6Ok0>CaaFeheqx=KO!Vkx?)A-)r*A!ZYu03_i4rzTYe1Y4W%F>jpUSGIu|- zu)iMh4BUw`&Gx64F!nZk_ty@;)zkmW;HgjX#zB++ci>6%)e^%pcFW?$W>cSgW2;ny zUDbR=+CL4K?%^4A6E428@lUz^ogam-^6aNC!0jG?6Q09=lQ#MN37%!V*~O%{$3@h~ zS&hM8Ontlr_V>fA7RK1V-&|jXC%%k*Zup&W!rPDXMYz+mAD(~%Phaiw4$_-w3{dMz zJ`abdzkrL$@N)PRPaki915cm61)gL*c-+Ll8g9OeGaU^77@k1Cy~yyNH_WfPgz)fd6`{+x;IA5$jenhUn&aH1h4bL9p_Wvxsg!s&l4l()X;a?yhR5$-0 z6r2Z7<9uYuRQLZq*!PF;aVhdjf42QI1J8K-B~}Rk7I`q~_raYj8^h-fUk{ICT;5{B zzXZ=6*T6HNI=`R5z1-iPCj6hUINzy4Ri2j1c)lE)LO#+TSHiQOb?X~{f&Kjm&wVHI z?aj9jg@-)(YlVG#b`#u$emdHu|0ZE?{o`hM68X5*gntRP=WWV%H;*EI3%w80z~nTsjl~xvBpf;AwCCyBF@Hd@nZXJqGXU*}sh#UcKnI7nty) z;F}p=o@e+3cmn;JFgyTHVvp`+_>ID&F8(Lr66@V|{C^0xpMCh_XEFX`j2FDi#@26s zTOZ@07@zO)kzD#dk0rl*;ZEvQ`p-VJ|DR&vYsC;SABmqAMuv{zOX9yP7JfV2iwXu@0HP54IxHQ$x+5x9x?N0{*U!}hZee|$n19lD$^iT_1- z^5c3xi|`L)@qZoTf5v#QAU&B5Zug|WAi^R7XLkP_8QK7G4XGe z_&4&*l;KBW@&6d(k#(nVAr(F8)iiKY<;okk; z2Y1ru2a}hSZx`CCm-@AQBy2xYo*uY_4zuCovG6Nmd_#;s=dsA|KVf@5^gehg8mWsc zW7KhkNqLTd?ML$Ogs0Fat^6(FL$UA+Vti$cZ-6J6v)pa2za4Jof7|{u!nBF#R!RRi zu>DB>jntj}2=5Ee(Vn(HoCGIsW{r<9xqf3T{sqG5EZhD!!qXQx`S=t(L;YHP{D{QA z!S&C73BSvQFZ?iUK2n~QG0wqFw687S6|wN^gptn|@g?Pb08Wgv-q4`=XR-MI8{-$C zE9^(|Z-!?)`93)o{#JOJ`VH?t7XAfzit7&|Eh*2>B^>>0+vng(y!!z`sWBFO~-}9sVVLs~qVw{Na8hG5hzbf46 z>F@VQeB|Q@z9ju=xQX_*`~;k!eeM12$-Uc;kM(9}6FZJ11THTowzzCdQwR z@pohV%NXx{Bjvxs>DO1o_9Nw69plj$UjjG1&DGBbB;1q7&%#qTx&HG5xcL)~{|V1{ z_4}NU+uXH$ygbIQj&TkiXM8$}%cT9z_rj$=ehSWd^7<1mT<-55@a#oyd^?P?_MXo* zCcPF|4m%hyd=@M+c(UR1B;0%?y{q7H?&$#jR{F#Xm-2kaV~PK(82??a_xjI^s4M%C z_^*MRk*@@QOZw$l_*>y=`do(zzbh90kc6YtZ2#H~-8aqs+4_^Qa`Ix=KCgl8NAlkq zizj07pNa9o+{?_RPX1e9`;q)klW^+f82*;~Jx`eN(dw(~;YsRy zy$QbuE^&`m-~JY!d$-f4&!O+ykEH)nc-pg9yWk1NyF&<*{D$CJY}6ACzYU&zudAPX z;Owog|NH^AA4$J~uwc@a_oeW(S3j#I+DAR*1^-0PCnlh3x9WvuaEJU;1V|C3euAN{|D}+JO>-z^)~)6AIWbyJW2go z`5J>end4dcxe=bGy)8cq+s{7y@h>=mj<@%B*zNpC{l9`Q$$t@C^3pq3!p%pne;YjG zHRx){obFpsp+?Rz9Pnp;0gMiz5gLET=G9J#t*@>UU~m6 z{C?Me4*Cr3Nq^thl&1rh#cs>J@XQsizAlz<^O5|nj`1hqIb_D_qwm3!?{?Qe3HQ>! zU&OU?|9js-xY>W&g#YSA@GR|Z`{yfR`;q+KAx!${yj)mVX*CUV1P59U0-uJrt zT5u-;<|FAH3s2GBtNB~f>w>fB2YdgcUi`g@b1ghgAGGcH4dHjX^86O=g%2?4J^!<$ zPkS9?xD~b^$^Ue?nf$DL72!GL?Kr}uJeSAf-x}j5;ZAG-TOS91&ZaKcGtR-Yo_@MG z7Je%{b%m>+pTOg^ms~6P{~Ml|aN);(o^a0|SOX`}_pdbZ-w2o9>gxYec=BED`a9t) z`PusW6>L9}=k8yyq|0zD+;p+CH#fp1(zE^dGPs%Y9?WG@-g{!#|0KrGz}fe^>tA#i z<%4Z|cfs}}-NdJV+whmb2~R(r1y3P=De{v1FMyk_ zbnz!)`;qeeT*A?Jw*C+J676%9tIt=$_9O9E#&`feh4Yu>BmKV+3%>>K{IDBuAB5+q z?*#Fse2>B7UjKgXw4|gzlHUub37>S=zZ$lmz4>FyH1+=hSKg1oiCf+Md{@HX5>=!oLyYU&VOOd%51T-(C(kp`VW+ZMomo@T6Cs%iye6 z|F^^Ao_u@*wjU|qBOc5B@9||DD(SN}22atSZF`>Wg-iU8dMxqph3CBb`VBmNts6gI za37Hfx8;8|JV*W5^v@N(#_8XW!ZV(H-Y?gikL35G82=6KMgDDj9Q76MAAM-`Zx?Jo za(zGCbP-$d_*?4pt+DWHWBh5j`GZbh&A`2HbNcNk@a(&sd@Z=&=BDfO@ED%}PrlEU z_iVWLI@jOcBH`Y6cya9d56Acxc#8TdM z*nXt`9)=TdargfVc=iU@-g5SL;*IR@Y|!=V&IZ@@(MkB!`MfiMw50yC@Z5#evEets z_9OXyK=`B1p14n#_GsoyuK$@A|44p&#$&mDkFW8M`3TF|@`>A={GASuf5f%ln`80i zto(5=e|HwYzMsFu;_vo#;$QB@i&w$+Bl%wiPkQx#S1kNtcn*2!Agdsl3$5Cu6OeEPq_JNm;ONy z(m$#HrCclJYk}=Y((8ezJ^df_m#dZP*v5?u`-5C=$+|Ubb1S=h*5z{0(g-bI;sp&9 zbA!Xh4SmBo^%CG*-`LiGclwrw^VR&o!j_g~TOa|s!oXIcjzGUzcwlT~WSh;WYxPo< z&9b$NR(0hpNjCOxmy3Giu*zkO_ZM#)Di$|Y7WS7)LGG-Tsmy8e+bQx}Zq4Z0{OCZw z+_jn43l}6f*-^=<2t8vPMhev|?;0Md1i6z}u35ZjWiD44+mP$d)ux*4=vG&qT<$9k z75Xc=lTYhj8f-2P7YA*|$>hr7VE1S>UmoonZs+fn`OW#^?27)i+5Uy4zH)V8yDC7- zV6H^yU}1D{)fjJHRzD^x>c?dTUZ^akY=@T=M>g<+;{hU@-%nnDR$DiB$1kMYlgM=u zaYK%(wh<*&64=RTE0dYQTz*yGR$JP5MYtP0r&1ivZSET$%bWXMomtLLE0c-tirn;I zxo@~@fUJ9}?YX6S-o{+q)}7UnlBsN8b!bs}a7^Cv+|`rJb!}dk>q+O<_VjhH<1Q8! zD&@X~$z+P_%_S|>p>lBxrG?3sR*5XRt=*8Tmh<^; zePzpfDP;Q+3R0#rx_YXaQeUCmy`m?Tlbn01$waOvKb-HcCM(tMo)-BjGn}tfx{1+6 ziR7oQWG1&NH(cD3FXuKC$3_RbvRp`sbzZsA;y_+s+r?dEa^?;a+(A^7=Bu}sO{>R- zhr5D>D^o4)@^7j&Az$X-r20Fh{!OcYGyI#*w8+0H`8}PI-_t4edrJS_$}eph32klH z|4N+Jc8Sy4F6pTikP z(JG-GbZq%ouIfliE*(jU-;tDDk_lDZjt(hSM~8~qAxU?1sHh#11dXn~5-P!DqD`*n zOEOF*TIC{0vP`Cul29_)qJB)OYJ+qtEh@*Ps=j0@BPHTX^5IK`r84UBR7PE%%1B9) z>6H0Wsie~?_jFq2o=&T5(`l7hI;|2*rzNpeO4SHo5``~`!k0wh%S34n5aN6vs;@X4 z>ZfGeI`w0=TVc0_5dRAMlvFI&}D7}bBF zf9UARc1=A)dBkaJz8{s+l}c~urla%?59bGZ3WMmQQ~E{+hVx~)Vr5Hzxj&s6$*$OZ zPFFjBuj`Z7xD&EE+1gXh_l@Wj*GZ|9ZA(o0rNZdi(^nSzHzkv&jq--|O{bR&WVN}g zeKfyC^|`p{S7SHN*s`&&QXN4TFuYXq)tq2XI4E-Co6EVrQo*X1)aEixhps$jWT0nT zrJ5hzjjq|U~HHZ65O@9A!<8cHg(OL?&ZDnIWK(Ua9>qrFf>9u)QWAE zvr=s*=c`?#gTsZ&kk%Z_ie<7^%13fdrn=Uz73HhdQCE7y*hbX=9bDMGl-OSI_AXF4 zg;}8FOT|io(b479PEN7kyTbg^3GxdsUsvwy-;^I%n%`XL&o3G7t5j6h9bL5nE{Rmy zPh$OAH9D@_R?3IP4uA13N<}YPJXWn1N4p2qHAzZre{h$iW0xTA3=0TldC}HF#b%h2 zi)({iGO5;R&THs1!+qOaeYKE)|D(G!os3?(s8kv*^!HT@#nFnpzJu$%kXQp}A{8Eq zNhOcccBIx*?W?NlOT`k4MR7%oioyD|J^5;t@yaV!E5(ZZ>MoAo*Xm-mu+iLDcweam z3DktRL{hQJSydU7HtC>e>A$qhq0yB7O|^^uOtmQ;*QQiloBl-bQxqm4VY;izg^|7hR1Zf%3ak!x? zBl9Say7!E__l&ytjJo%Xy7!E__l&ytjJo%Xy7!E__l&ytjJo%Xy7!E__l&ytjJo%X zy7!D4_A{!sGbxpCO3Iv321Q006d7euWRyXXNlBe&QmV$(K$%g4bw&-788u2~)F7Er zV`N4Rkr_2YX42|fWin*a(q0*5P-K)rkx|2EMva~sHF##!*qKp7XGV?G88uL6)Ht2V zNNs0YRGC{;nOmfuGc8ijnHG_gj4}Z-*oE@9Dzh>XGRi{8D9a$zs;+HS*S4x_Th+C# z(ngt9b*(ZwGRh#zD61r+jFOC!>Wu0O84lhfzUm7Z)fX~K5;9u4RA0y_>B=bS$|&i| zDCx>5>B=BoB}P7H8(aFDCY+Ym1=ogIPGW?_2O5RIuS-ChO31a)!rnh2y z2_}PqLfI8vrZfqe#Aw4iyP}m~<^qy!M@1Rqiy2O_0X8#H3e6>DJc|XDFI%&~%sNt| z#qvnsaN+g&t~D#=ZZPd7v1AIfr+?GZe5pE=8>Ed|l{~j9SwefLj@qJ4WF_6LO1fK> zbhj$$ZdKCVs-(MBNq4J~?p7t;txCFEm2|f%>26ih-KwO!RY`ZNlI~=?wkF%Pf!nT) z%64s3wriuZT^p6{Dp4*F`QuB3moKGJGfI7=GD?^5B~kd2D14bH(mPTuN|o>>GR~I> zIbTW>X@i;yP}(V>#23=~RS7U8N%JL1^QCpHR*?y>F#l{!=_b||gXq1vrO zwOfa3w+>aq9lE-y6fR40QO@TJPm4$6Ga@SlK-WoH6{``Qs&+HIQ zgtNfl+P*?1-?gZ1Mi1ud5;X*i zII51J#!%HMRF_a4LUjk#8Pw>h22VA1s-aVjoNC}y!GlO7;4b>aZ!*UsEVF zCw#|m9LOKfOl|{XT)^M>^Q^StD#I0*w+_hSmQkjRC4=&3rC6>8O5TbabM`8wpn?rF z8RAqN$rU%8!|1AoIua+hrNFo&5raYIxBZ2@PD8wM@`DscT_8X7%XF=@E{;pS}gcMhaW$LN>)PXc)I)UpZIdpZ+18k}G`wh8%+37s_5Y z8W};)4h@u-;4#?1@F@jAo~3Sah^oJmwvGnMx&FTXp}d-F$A4s2ud*~1M9L$D(LU^u zg>5p}jP#W^q5fMtkQ5yyH=((33V2Tj}Cxvo9l-ri| ziJ7xa`39725Op>#Nh-%7*ZbB==p9^|>=NHg9mj|Dd$gQc$PW+bSSo$(UtE%krkhMS zSLM=_j^43^-$cQdDFwrs=ujM%Ed%*;$MV)Us*_W0N4$?+$y6S_Dcdjj{gf7{;QS_*Hb?|24m8J8n_r1#LBtL)4X0-&z`v zmM)VnyZ#k7@aDjHmh#nXxlqJ1kdetWa$0$mv}hKk{=}wDwuSyzF(X8-xYkiV zI&9o7Jj`95V6>|=mlVN#s-$}6a^o8a8#)Y}u z;MT1eIxmmD94)e__A5pYWlVe z?aZr0D`QOLsh5q#ur8AA{|6c8#zu+*1BJAgY8@dJT~l93jXv;1AcIQ4ORHR5a;J+% z2edgQ8fa~SE+KiXsHy*yc)92s8w-PGE-9^}+TLp3dF#8&^yGC$-RD&nS~S|!{n-8{ zhG_<`EPmtgmc7Ea4IuObc~;uwtEo@mMua209eq9HgDmXT8Ca4j z<55>WR^o9h8#aWOC+k#Lf3dVpL^7e;PSxwYZJ|1*R;<#XV`Z6U%UXjhaH$a}u4z)b z(zV)%)Y;k|nLsdPnH99UL#SHLvqN6(0zx>B;vp?pwJxcR6{{3AT>6#L;dgK8^;CZ{ zNvkZ)Z|oZzu2#CTQT?KYFRIo1dSaEBOm7zDw619G9chYpc|GZ{8pjBky<440VhOGq zt+lN+648#KK&&wh=#R~~XDU6_j$F6sHbw?<)r8BD{Hc96$yTM6E36gC+O(Jt#0!@; z=NTC*T^qWL+2H&)S>v{enn@}n87*1j6#cJqVig|)M1Jksyt;!yY;-KwzjZ64Fw39f zeaVHRaF%Fl+0+>-H0e^7UClV1N*GZTCy*K^#4u9bj&(0JX;l+e+Coh?D`E>I)jEX< z9LbBySl8pMKsQ3DAtk25MKz?<0z{aAjHN0U*>n)?zDl?2DW)18mEf!PHO-gol7+Z> zic`Gk5yiQL^*)C^vHQ+AzU*v6T&` zRZwWe>c%kLqC?p!qA){qHYMW3`d|(hpV$MH9L@}}Y(1l5-h!KMmh6y`C?|cighVN~ z<~C}u!WI>*v{ikZ@}W?PivWEZ-h*zuj*-5tr?E+)HRG%%-(c6~rE79Kmh4C~CX=dU zT`Xo*D^j8`U!0vRZEAan_ExgM8e&Q>TrTaa3~ea(l?PV!jrI+)J0-l%HX*zwK^q zPRSYd>k3^@P{drRV{dyG`4c8%OxBJIcJyd7OXFUznpbQ(N@JBFWpzkDQ*EN}vd+-j zg3pOtRaJo&ZDE$of^kLd9ASO8yPqGE{pfdgnDiB@mF|8K?f$N==nxPcXKaJ(;i2wy zRn0rYQQCCnm57n_9%;3x_Uu@^8b6gtxhiTZqvVe6dU~tF1W{*oL?nf=ftuLWb)teWh&Qw&7ymK-XG57TU|i z;Ky*AcT#VXNYjy5_LT?oQc=}-4vg=9M;T zy(Z2g=NAgiB2SF0F)B9@hSxKsRaN;$={$D6od!I+jdbErP!pJ}cyQ|Mpv(3wHIn_` z+RB$iOt4njtT9NpW!~u5NJR6fs_@6ejzVQMo3YC5LUg*-DLFd~_?NWfGRlu^U|4s( zR!M?2D|X(sGw&FeoW~{NBq^Cd=XrBh8coLJR`V09O8v?rQ+FIGUWd$}my}A%yi#^NF^o;Zu2ZRZ0)$nYLFB~U*uXhwOuz4vzxekLeFnx5kMJ4 zPD^|Ho+?fjbPa``)Qk+>^c=Ou&KxK*wM(`yHgmh~icEvoj1F(Bsq8Q*Gl(B6^meN&^opt0O4d=Ks+;SQnPJ0}OT@*skEyjn z#Y{Ftgp;kx&!Ywe)Z0Nvr`m@1QH{G1qlm~ zId6R^GB($XgTCk#^hhjp?p?Eu!oQ)lj; z-jw&pnR@O9Q}uX1bGeP&Z1)b`m^fo=)KZtoBf6`nL;hR4f+tpbs;O4Y$pQ8P^!1Bt zJ#>ZQLzD+_%!sYKMw=St@jiJXUuX3w*|J5pM=dIs`?gvC1x>2cP?AxnYFo`}f~@%r z%kqj zDbyzBSZeT#`jh6JB-g2zIu4y@=c_UE;s4qcr$sM_o0-LGZ{1(5?xHu>u+$A5l?y4E+Q#)L$&=sEuq)d^u7Yr5qx8BjW!zX1aw|qZHO0m@;uk+MZ z^L8sqd}TW+MyXyPkeQGj+`OTawox)tr)Nb>yB0<~Yu|d8cgT7@U7tB>bOdmAVBLYq zTPkEHf_BO*>aP|y=VhQ%y9V9UMox8^3Ql&Z^{g73v3s;1Lx5pdn?Sw@Mt5bjgiQ7B_huKS|e~!(#QWzn6s@z>!C0nWnP_m2I>P6Fe=|q?K z%vh)%*J)R?TJwm|670TmpY%U}rA1A7Wvi(ea?&U22xp5w_AqRB7rLx@s|T67YDh^^ z?YusL2r#ero8On6w!X?TJjW4p&l|&%2_+VFCBYhYQJ12pa3Z=lnZbX9T`7AfWF(G{ zi>qsjE*=RfHjB_K=3*Qqa_B_muQi%wF)LmyAoNSeir7`#cPU4rs+!fkjr>gen_jD* z?h6x-uWJwRnxxPqQMxcQ!m62guzl-7wV5+el^@7dfw%P{%*D*DL*IIhN8KM7T(ZgJ zV7@BL8PYF3X*J1NF|8FhYh(~no{vV4aN<;cl$xYCe0@^>Y45-rLm@?oZR^j<@({lq$O`t9sU8L}z26T&W_dS!O>X zO0pX$r+hl%Bh%}(x(S@Z2p2t2_$(FnSJ@({cZ=e-pCyvj{IJwZ;BeyKk9|@<*XEo($<=&-?%tEuMT6UY#_GIov=gK zTMIHPvu;)t(Mhb|M0cNt5?s%fqn9jpI0fS|{fzI-sqJ>QW2!BhMiYjcsSH%&ag@zz)v=NjjA++Em6^fQTEF#dbteqABrG_{>VdyF z87oO`m4tm8XAUP+U=)%2@G!-;^Mtx4penjQ%reU`hPT!ts;0DuuUs&@LnL*Y5y8>wP};V(My-&wsD(-Gw2s+f$+WY>xD`Dj zB^Pt#2qu-d)TCd_jv4FMR|A)1=T$4KLGrkP=M@iobvXB7Hzzw0)NvNu+qo2`T-O(3 z=O;DeTpig-YT41{j2ht1X;fqS#}td&vZBr$2rV#g(}(Ld`hJsA5i&npo8QQKjqLc; zYLUCLhaBjUKkmzL5)zXEznYVoO1`>g<3|2nS>WIo)1Y2M$l9RYV;NiFXfaC0x=Hnr z==Yn9j2*7P5%&*=tmLcOEh;`%ExTd2th3zUszw=W$z)+vO<9y}EGorKMcut?KdsRn zZv4=di!x9@%`fH|88$p2G}>{y1JwMfCEFIC(x*2Q87W!nnGq&!<=4?WNc@?+8oSgs z<$B|p9o4)wZEqT&YOc0e&Q5bHD+zsyg{)ZVj;jXRoRZ=GsuV(7YV2(2Mi9Hi0hq%3 zr}qDZJuR$W0=(_HH5RyBuyf_&6d~m_3kw#NVz&cE7MYx+=z_GFoo?>;*eF+LY^gO6 z7V%ip;ArxM1-c==^UxVXxf!kYWrEA^+3(e zBPXi;bSL$?$^6gE_@harH#yr_S3_iTxHI_C`_|5dbeQQGC~&-Q+*t zt~p=Zgbud+xuUc5vaF}duybTK#gvk#G#NLdL$-EuxHV5)EA=#$4-6xdY7GK5#3?Bnrycf{}BdO zWcU|@ZvL#L^F7<6Y~*fP&}hl!hVxr_@`5L4<%~0S%=GJ-LifrIiLR~;;r%>s#hzY! z3Rb^7OBF7Cc+X;avKY#0m)aoC3QAYk26XA7oUEfPmbGBDr(^wE^R%2cbkuMapLRq& zT57T(>%KLU4YeA)6PwnPatK*`-FQcn+|zl)vs*7L(r{{usWpdM<|x}Xu5BYX3WbuN z%B*E)bYI1ZzLR+|-hJI4R-~TWdY#_t`1uS#4U`1zJ`9`R{u>R((W;WRxMR z^@d8a&WtjdW;?i3M_Pf@)|Kr_$s}gHeLPTmkNssFX1P1__(Z}z)LNipAj)m@>@RC%<-Je`KV@=PE%6IA1;Cq{LK7(H#R`@}-Hqeqo1 z9D_+znt=ge{;G90g3i)Cs9AeW9nno@WEc>G)(i!Rlt`?v+tL`mUFTT!X0|QUpz&?X zrXMAD@+hrX$I$)3v%d8Gxc;J6;m%o&R!Fuj9Scu@$`&~b%71dWj@xkOmmBI-TEst| zt(Lpd=T@-MI(AvIvLw}=)dprVG%yEqk<;MBD3sf-lS_1oXvt8Xrz=z+R3hOlpY532 zvSF-J%(2&pL*i5;)(rb<>#bR$c@}%`SnBMO&6lw;F6xT6Hi`BA)!wA7wPZ_oMVpTl zh3y@>OC{A2I5~L|WYGrZkUUZ@5`{rtBaxv{uyKSqqD1w?WI5_fg>OZ~w6ZL7JG{pv>19*!SsAe7(E|!&#jhj!(B)KrU z$@sFQI(+pWI-cvOCEH`oNTg*TYQO1W&GtCYHDooTYRP0Bt!#I!^b~!^fo`pE^!`6S z57xIK)@oC>{%#6RkDb?y=+66{d`uExaqlLw*=rjHz zM&cUf3Zt=Vx0=Rf%$t^Kznu(iMh}ufe3|+`IaN`zRHA0=27D;oR`g*(?@_27KCITd zW>oeC>v~ZM&)b2mAbVS{vOVenu-Yf|)k7%WJ`y#?|EDt~HTLb)*4p?Ssg8)+b;WQG zn(Fj5O}sQ8*%{(hxwhbBDwS##CudGgrSwE_UC|%vjFG7|Lv(2@sl1n=U$yqZB_-!Q z%AXgvw(LlQ0_@Jl<-r~$Ezg(fSyzp)8!ea8K13y#auTmvaNvHNIi^L7=z0PsvaHud zxF&kgNJP^n6N93fm4=^hJ92&X5wQ-bXEm?(J8_$tep%}Sv?%-C$`kGWgx z8i4c7{FB;CF6+_SWTP(Sj_SGg*Y*^=qYBtC5=z^=N@C~dAa#^R2Ep=oRw+^RE3Q>L z?6kJ>=hhLOX!}5T=D@Q(PQCU712c%GbNG$wPRAKYy#ox)u}QjAJFvnqn}>(x5EM?x zk^^kw%OT+`z&UT}`Sxu8rRp$c+GYFWv0F-LSy$d>y!J|Qb#bnCad<#2M!F8;ru>;L zLv|yRZi!@Vr%5J8)I(%4!B!F-%1J$g2!%55E-kA8)Q%6MsOlLSJD9ENK9_D$`q{1G z?#vQy-4Z9~FR`^9-JbAdnl%Ydzc`Ka#pKyrr%-FBBXu6njm^8XqN=xv)6OAk^@c5z zoC>Adgd*e$t?jJ~(agD0f37+-Ho9qHzp~oB%`Qe&)h3vXDWX(Ff@->H%`QPFPS#wm zlSj?StR9e3D=lazJddMeCETvAI*odEi>2PNEm~Gxg=YqfMRT;*e@}1drwqK4Pf!=~ zeunvV#&$i_TpDrYc`Djgqp>ag8L+iav`K@iShSJ#UjM){U2m=WDPLu1)V78dA)Aq} zh1uSyZBA(lyImx@okUVi+U~cthrXMMwrUamH&B1)Ufj(0c9QC~Dz9tR z>$Yz7KQsiaccF!jpuG#*b1y_~ws41xF)Hf%Lgv}88}o;XeypwYaBoAn=M4?G0Rurj zT+&l54bOkZL(hh89#~7{*0ILGjE-fG6+Nx8USZqEf7Dz{P1H__ES}el`q8Nh#@$Z6 z2SBn9Phrr`Wxej8gie>Db~NeWj3>P-+iPDfv&c5pA+@J3_8&(|GmLr{gzn|o?@lEo z+hmK5F;vx2U6sf_CbEgXz((@jPOF78+%~gL(&bh~hDo~C0ibSTUQ;UiOql6Stk!v6 z!+A<%JFgp)>`?0KzMWf-*!~%cJcg_F3?q%1gd1lkb9G9W)KjGHiW_?UWhme3RKr=# zJWMa|o839xlB8++*fA!?Kdr^0&a$*RPfP6FT6q&;3}<4VXGaO?&e=R_OsW+P+YTM! zBf@G`NKKAUUWG4fs~jvf&&73|DH*ZI-*2ZuiViV>GZJ!W_=MODTK>RIRha zZm^)1QVBQVUCddjkHkx73S!efW$PnV+fT#t=?#G?&h`+s(LKsb)l|dKIN^h< z9PuanMkIoJ=Ne7kDvh|K#ugK&r=6Iq*@c~1A=_=j%$=C2jh6NMqo*rcwI?+?7&uR= zN_eNL!&=N<+L1k2b}05mhmA;e9yIqYraI17xz$)A+6zf@cDrDK zOPMbJ%Vl$@%rie!r3G+Vi%U9v^S z7yX|TpvWk`;{|c`lx9>ou|n8d@4ed+k*=v7HGZ2ZZv4DoBVOLNT5AW?d#K17WX>?Q zOG34|ss}b0mv@|FDlx!Y9_1B@>ZGC}+-V%2t)xGk{zNBR_0&}D=whdCe#6O?sdP8< zc|8Tz&swpsMc$yHp7F$NNbT_KfbE(MPIV@g?%d(|N^0v2W&_gW4QAn#O+1=$(;;${ zj~vXWpIE8)ax*7yb?kcW?WpgQwP%1a!sxPuu2g&4x?9_nXP&&Z&4^wN&&aY?MV)cL zImmy0PXbtaHnZ~mt;Sl7ym`CFrJu?$<-2uBN> zWct;!`tqzrGQ%wmi#%fu@V158hXwun;~6S*T#k~{I%-hPT1O4aaNxE7ytb$Akm}T? zlrfd(-{uh;;>`Wj+pi)^GCMk0P|J}qU80*;XxYeqf|x#_(CX|5R7?CE zo$wJbEir1pS^ej?!nTU;BC~^~XC&Hj%lpY5W#)@tof&G>QDjEMI`PcbusSP)zC>7M zt{)&#S$C+XO-I@Ov9(s3>L|m=DvrJ{qiJR3N=|JK{Vg?zv&vMMT2(V(uPRg@Q&WZb z7W254NhQ7AAnJ)>21oMQvFtRfr$mJT)MGUJ;h4 z%H+2BT~_i#H=EsHtRmMuA7?F`HfmZg$Ejp#q;Rq?&l2?wsC5-J=<-@^8A0r0qWWec zr{)>aY&#vr;(IDW;r4X5*-&U^BK~us?iNe~am0U(zc1W(5vDz_rrF_B@+`YNi$ju) z|4hl8b$iUaAZDvsx$^W)$ngeRLHfOE)IBj_POMmq&m-nMbC1Z?9kcZrGiDpVaghAC z=0vqi-+BdW=T^RT<;fl9%Vt4A%_u?(j4d65xl!6**O~FesDm+$Ecow+wm-?M6L_DT z$g_xrU%#PA*TU>ypN?%^Cj5|Fwp59;Dwh+|?d&d|e=mk@ayNHKnRCHvdoz7@cth5$ z@%TtM#aZYS<{uL=6h}CAy#I6u7OB{r>4{_ z)VGPEYAKmntSmW+HmWzt+39@k$SN*aHf{Ckp|4$P!iUZOKed0p9)ibTvvV_6EfM-kLQHF z;GEi8?Ne`%v2&@N%RDKsSqQTahZO|TNnzauOMK*>tCVRgn|@+j5Nb?FEbe|qk zVkVtysCrhNcwq1W*Y1C*+r>rUM@D})wbD}8CN5sPNmTXu=+>y(!`W({#*{HQ#ZF?q zG_$UV9i7)>nL9wq_U3T6_J43vyXm1RIZVsVLc6o}OnqOIZbx11v~;Eu`bl)7cf*Ie zLP>FTsdPiT9J-@ye(e%+YH52OTZ)rR%T=Qsfeg>{K(lR# z?bsZZTm_3oyd+jvMeAEC&|ehw=Mdr8@*i&`OL1fBygfMzom95-I3k-pq%6MRD@)u| zzn%iPRtN_NQR4YBXK6*$Y{cDa7k(rIeJZ^=o`L-j>(?$Gt5%Dn-2=)Jl$YDvAL@;p z&-PUxo|#V{3RmhRX*&T3wdBEMRktu7vM3kYYN@J(1sgQaeM?07?!000{A zCTbjhwE?wT3c{Iqy^*-4h9eW{x~GdMKllHszow=T*erHY%#&$*j1h+}hi&I1GwR3D zEgRidWi3HwHg(Rwbt%m^*2+Gxx-U!g+uf=Qm6K%w(Yeq5*Z1=IqS}O&cRcjT!o7AjtNnc8QSRwFOP`6ubmcK!EwjbXz{Qk;Lg85q0Tx?ubz(9JL}B8piUXHLG$xb+5%5o15vt(lb{tTGhQoQu35IH&8oitIep+ zI((`lb}|JoY-M+2XyK_DNS%}-y~Ju5U-0$89ljH?&O*k#FF33j*uz6t1Drj>Y(X*Z zAQO>OLJOn%Z)rw50M%xx+R`s)Xs@+0E9KQUQt$O&E)mvwvUWQdC)7r^ANo0<0%Vy_ zH)x%zwDU?e+Eejz$mkAzNXi$yk;z}Bv-9MY-HVsxQVSD7-v(ap?f;O&k}QuFb67{} zg{hG+F=C&Evr7!_3Uh$2Z2vjun1s$aBbQ#7;dRy{gZW6toUfx!BCJGzE>(vx=>~H0 zUioNQuyYeR_L%c%E~j)zOGwd+WprvZFHVK*UcXk`4KickfiZat({R4L2;YMo3@)DbM`;J7L#S6KReb;N57yvJCj8Tims>QCYY`Epr851XT))G8clBzSO6fiwj=HpqM_(%8WxC0VaDKgN> z4<-Tg&KpVI{7IzI%0?czj@%myA_yCYEbEd-%Vt(f))xly@>Wu6dYQa>SY94qDh#+g zPjIz*_R+nSCRPlV7xOFf+thmogON=Gg|dHjq0%>uJH`JAo!L{w0xp;zjqutQIEVAW z{OBSFB7y#I`i^Wx$ZP}mi$SF`E4pPUYWy9DsFnV$eY_r$BWS#?l3bXM-B-_0af?YZ z7DAJSshSu){rS=GePcXO(?3%3%PZ3F9rqD#lAdqKjMhx_ZfSN~-3SFXVQ~~2-Ii1a z&u67hqFJee@)85B05+f^`gy#mA}=c>$7DY?n0tF+SM-ud=izic%u;zB z+JKdH87-vTCQ$}Idh?((Ju0A1^7`e7_3{v5kZR%Ol+={%K0R`nBh47;1g2TND`?r3 z+^^~idbXyH6+}U|7m5{iLJMPjtU79%$F#*N-Zqi%Vd`jmp!r?8y!lhq10(3>&~><0 z-h$ITx{6~6Fx7R+(ekOXu_#9M*l@f0!~JT7vXWk(9omK(W!}n5Vh4EUgV#OkEPF=p4H?Hbe#jANZrKpjSC4Hk>bd^qu4s3GVUY}Py z8P_WPL-~Q+wnBb5ruMz@osG7m#Vy16fx-N#V})u?9y_lifVoBGyuLYAiQ5r;<-CX) z2m`~}SkEfww;&RJZH}>%m{+9Pc&dg?JG5q8L_1nXWj!+H;dd)=zN@%5*vTD;WyV?T zBN1~**R3b*k;aL&ENw^c<6k?RM-<$AgSj)HmY#8P_nNUPBboIhv(>hxUtZb7i(u9K zd<#SEC~sJkXZ|C)Z(%ZN1i{~%g{;VnlDwaI4{%{4#!Y}`?H`H^shcaKwHDN1ZDpUe zZk^N9Vx&E5JuMp&3Z}U3_Vq3$1gMY0Vun=TmUn%gBOBA?O}LT!HCIQQm!72!FIk7d z09Ob0slmRi-%=dWLUdI;UQT4_yw&n(f624@#P-Sc42@OMN~0#rT47Ktn>D>~8Ox|A zmkR@7|J%g+dn7m7CSoJh6({b=h!firw@K~vaE7lb%j#lPj{H_Lib_tefBC;jCE}6L zN5=NY<_bDHPc|x|nyArHZBxi%jbx--$mAH0?lCsW;%(isjvK2fr_<~f*_}+xEaI`# zz?z1=F4JXFDsNs zwlMEKtu&zPC&$YO^*f5YIinEe&oS|~yp{a_SK77qG?FXP{GzLQ?5@N|c9;j!urngr zS?PXhHAx3pLOM!^0sj3x^|Gtn?!f4NK_TgfU9KvhI#sq0lwobQZlK@3o2_A1Azs{b zB6j@hB2>8Sej-*;efZGtD60iqOyvZSjYhvTBj&HSV4NAd=o=Jpk90Oqbf5c0PiIMB za-f)`B9)?PxE1ubZ<;)PY%Z)}qgaJsy~VadsvFU=zqdeAE>uYZ=4g$)_UaLl_wzeMWltmlI3jZz+2fwQKRY>HwL3sfZ?`^6ff)oAz2}q# z_E|1Rse<8(S*+q^zP8v+^~QOQ+42V6_1!@*;3k>>BN&K7K|O#u?psx|LWi?|s9=k|&975V^$WUD6@bgKA3wPYCMLbV!V6$@=hb zw#MpTqS~VpPg&wWw<}uN6Jrg-sSrkvB?^DJXs>-h;f8W(kR5UVC%i$9YBSIV9A%v7 zC?6VVj`tSecYdd{ZE79K;+-@2m=drOQhY494Y-R95#3+h60h(NM;$NENy8YkJ`8l0 zc-8;uwOdE^Dz5kuU*1Ihd$tyy2jE0InKQaY$F~zj@%mVaav4R7tN=E zm81$a87*|_&eP%J_8L?74J5nV-|iUWNy}8Mq{aJ~gX z|I{xZEcEiC2KV&-oe1GK_|6^9ez`C6i({z{=PRrXL|T3k z$=m;&=-4>dF;FPw{wJzLrjFTq=(@Z7@;3<%+=B&tY95%N3%Mx>3GR3oD? zGFstRh5p&grqh)t<+go%2Gjio4$fOG+5KlwsyOtB`P{Y8cSK2~p@9cCBGeI}QRVaa z{nde~LSBZXhe`DJJ)+Rn#~0^H zjNJc@s;EGB7^3h`KW@9n9SD?ifSkd-lVj*!_ zSX-IDoPcQ)4fII}SQWoP)&^c+S>+$y1BjPd^un$d_rp>$PSCLVuo*8g!tSZx@(PpQ8mTxVCyAo7?g;9ibi zj)_ixQ+J1U%csAA`xE0HwGdDJ49aDP{Shc+(k{=|k8}Wi)+iVhs)dkK?riV%(#99( zC>I#vQO|Y{n(px5;j!DcP-^xUFC?#jBYVdwyH%%z>XX>I>R4nYsWA6$LdqX0vlfS* zw%!_m@}IwL5tiN^`d!VgAY*4%7Gu!#65u*61NcW;WP9ztpRLDPpL!ZB4nCeHgAeP{ zG8k=JG8Xb(mA)sn2b@T-8V>ae!3S8iG3-c=?9-;b#)zUs=_H*DBwGtLV5zYf<*MD# z`kSi>`Wuzim-85TYMZT1=fjsCbm^kqU#GXu?s<)iS5~*;vg|a5J!S!4Eb1{|A;Bwo z-1w?GPRKP!S%Dg6eJMdL`*NVZf_WV>t{Co7jn{DdnusrsIyM0S!qtKyhTR3Ne71-G z+4G7&r88AP20TDFW70fIqCkXPb};7KOjH=0SK>txL~O%ie|vr1?Z2QYx6AJj8`%-x zm3T~Gj9)BHnVPCh*Cbz;EI_{&{m!|Yq|^;^CbAx7Lc1qa+p7mfUR)Y;_He)BxtgjN zxE#usaXAM(^0v-xaI(<-@7S5b8 zuQOP^Xn~oY-cQu}{kU}g(ik82_Of$uai|m+kch0b8{Koa8rG0fLkuQ>ZJyLBipA0= zdK9UqWygeOWuD7DE8`N#lZyro+p)dI_|!EIVnzi4vc}Ku%UZ8A+v%?Q4lai?H+=9< zg2zaFArG28ma90{X z3RdP7#j3VYDpa5l$zDe5(pvLK4XqzmaaE@|>@C5Yr+|P^0gTfz0PovL^zH;+(Lyd& zWj06K#Wf6#4i-&)3uGKD3}sI{0|iAzAbErm$6+Y~^o~JuO%I}W56~`O9uUMQO)~FB zOh|TVtF|odk*mEOvZEliAg0tY6>$bagCJx+pa2!AllU_mOlGv$^-KY1RzoV{6l#DB zcX;KZ5Z=WRJ8r0mLw3E^j>~@2A)3>E3BlwOuuky-^|2BG<&xV2@pJupO$EBk$Cxc; zAHo%z!F4p?|$6-{P>-vNw-{Gmb+Alo}o ziTfjHC%=gG4j11OyMR6wHLgeag4&=s0pk_Af`O~$I7m@>@;6$5Mo|UHLnF12%ZV9F7aYw{Zlat={+1ayDUN{E+4U(T8J zvU+_3&VBPDg8SIQsiUYzTA9=wA0*p1P>oC|)?nws`9I+7dBY1Z5S{E0-t>DABt`g` zFF(Q6GNB@?bA;l}!XUgc#>r|R7UaUBF>B&4C)Y6|MGn4JOwElFuK8F?M%Ll&f)^CT z!G+Y+cN9DqqSg2;TzTBmvJk?6u_uK|X1`DVR!7ffCzvH}5>^b?>enCoevkFLz%vF4 zC+8=Du@LF*Dta)V{nBMX$8q%eKyiO29yM%A3TI6Q7l4iUd6k9HzVfas6a;T8wx{|k z5CI*As%W4t=$OGNaEcs)H^wOdrEQpJ;z&yPqOF5?%`jBbM|_)Mkhsl;f4|^191Ui6jnn7inBoy7REl5P|Tn2 zuaFRwPEBgK`+>oj#ojqrU2@`%6@fB57*}NqjPH^L>vv(*47CTWTZ%05iv}Q7%=;O_ zO3HBnAFkj?JCj|4!-&!mp>()-mZv#Q7`zmuLw4HMyh)g=eBTg;4 zoLez!P%L{&MFiRqfv$jbvdoMhY5s%?)nXr38`Lm4Q%-S6HHbm+4DiY)L=j|AoY@7G z#Nrr<`mjU^(3mDP)GE;C;Wzf4^&=GqdN&{O-N~|9|}8ob}ynuf6u# zYp?w{`=-D#Ns*KT zFOI*zr-0VC!;va9%jku_=0{a}^P__Vx4x4P7t%5LH1%!e>j9GalAluflAluftnXAZ z;A4F!E7C!3{%vN#-Fz!44u|zkUVe(caZly-J>M%6*}sP$D{Kzy+sbzt@=?$K_G9Te z-YhSkU7Afs>)Wi3)a@t~MlCPAq}Wk4v*!j!cF~>_UaNlP=})K6UAMJxBy~9ge;e>e zGaZD#W=CqlF-6`rZ+MSA>B&LONlbekf1B{P8Grx4-&^?OrxSng;%_Vd{)xZ$@%I7# z`1ufjAIX)&QS#~fx6i#TV?ft?I}U#-@YCVLUn;oxs6B@?est~R6N+xR<(Zeiy6uLd z_4np(-F4z!xxe?kcx?XrKRlRLddam0o!#qM9>?E?p}o4R z?|0CrJN)rDeljqQ{LVP~w8!y>+&FShkK@m`#POdkapXJ@NB=E{bYI`Q;@J7iIQ}*@ zPJOS4!~c66`@a#V+`e(-&y0hQietBH0W^$FaleIQ8|#k@IvMIV0of!?Cctes^#j`vl_Pt#SP4`#Ajf z#ff``&}Sh2?4P^i*!d~M!|vktvN+{F633qJ#%cE(;*>ihjz5o#V~3@2+UtrqapV0s z7>LPjckR9shVKslBaS{j;>aHmM^8^2{=4Jwm&GYJB@X}2IQHKk zr+ou)>^3@%fBqh4{LP9Z|E)N3hR2yFjEp149mfuL#__{v;@IJrIPz}>-d#U>3wG`f zKR%A%2IJJL6hgZ5t5tFISsiDbs*2O@@5PA&wQ=~JarD14jz6r9(~hNa{NdL){k=8L zxc_LJazBb=pOta=FODPs`8ar4oO%_->8I1<*zJorc0MbPKim{Y|CMq4c0BxNpnXsP z-4!Q}T^UD?Gmafr#KA9%(~hsikzW|cK3n3n-gH z#L@Pf!hbXIW_0!x$4}wKD+g)P9gd-5XYiLRc$k^G#N_|*-B|vMP5zxW{_kK&(wbhQ&f{Eiwr&cypPOENoS2j!>H@2p(wsKfQ578!GFeV_ie}w90(NF*ZHF=;Dg;7f&cJ zs4yYPl%7^f-5cEvb@TG$C094r*ELo~lS`+~om*O8+0a-=ZsH~|hZv;j&<)!D(HdD*pm2<153|M&5c&eV? z&`{Tq+c;s~tSNOhEZv@xUpuX)x^a45Wn)D{b-f#kn_Lsz4b`>NE~smO_96v%UU}p6 zDRoe5TzM^;p#jj?x>}gIrl`EOlJX}ulvm8GoI19AR%JtZ#BQaf_3r5nmE}`QXI9QD zt-zI=HEOI!5$>weis>^QQ)|knPHk|IsiwMiCR5!I#kA6@^6DDLv`TlyoT&~pY7M+b zs(v;+s(M;2onV%uV*1qT2I3dPb>M+h^8pGQ+yqY0sEG8D@C}%6X6ba)gQlYq!7?k> zk<3i9Oc`gF*Vk7nDG)wPY44etC|Qo2Yv2QFFzhsd9$ff+Ca{Opn}bhFwfwBp?K zb4p8V>l$X2*OXSn;mhIE1w|DT8uRlfj70Y=!_*qldTLGMyjf^cr5$vw zfv#dAtI13|*3O}QC%DngOW`4PbI>%k)7;ZbE9tjTOHyetl{y73gf3H8VY&PiM3>sq zigI^_)omIoh1Kj5XfrDn?d(2#c4Y<4J)sdXgBDNEf;%9-u-Qtd(BaCP<`!H;_44!c zXXn*lIuT7GPIXR2-K_fZhDy4dRHhqgXF{6t3nfQM`A=;RZPH8g^CN|Ir>9-ArQ!c1 zn;w8>WlMCUeD|iX8Dc^syc~`{8(t1U6DLh@r)NwlZ>+9Bhh@Z=(o|JY0WiG+9jw&d zP+skBM0l1Moqu4C%JNxpa*&yNqP5FwD$Ow0SgXYh@tmyE@l#MtWo5+hX!3^2Ddjcg zwH1|9il9nngr&A_Dx0~naza|^_z7&;nB=LI=rpqsr{m;uz<{&rX0xXuA9}Ruvvt!@ zea&T|c4l>5qm(puqy!lnDofc3DcxB}j5CpPO*Umu{0|#-mmy+O6ldj$Bl;{1>F#{i zD%w^N%ft7qcCp0#FGZUTgn$_hrVJ=n*pXJ$%KcA1at``XX{GrS&VheTDVT6p>4c2ZiLfxP9F2_?<+W9aOezw~xF?=;w&h8TZ-}Mt*^b$k zr$ZAAY3_^)_q=*&lAq2YjY^|W)ZC`-zivC}yJn03_qi^aP*>9!&y^17 z_GTxxTI9bhMp~rNjp-*w^wO%BE!3d|rH^3nJsOAFA?@rNP1l1+uKSUI<%Qf5-7 zM}jRHfvRi&Lx@omJsIR6vNR&h9MJT^4O0P~0TT+uN~OgAXmE61da_jJQp`JMAx=Wj z1b0ni0TOJn9Q`li_H0p!PZQze8Kvgf2#5V2di6~jqC3IcW1m^hDU9jlRU}l^+8z!4@ zW+`WP6JhG8^8ip?t(xW4PidIxaMv|q7TVyLHB+X#9C2#vN;y8tyd7+{oZ#VG^eeBa zpI+Wr*Wh+A?l24DPGhCp(S(_+Ozgnv#25Y)Ls|iaAmcR*lBqT}Ts;a7K zYMgH4Y^oLBis>*iijkRoL**RI#vN4%rj49Y)?-;T2eSfxH_n4IS= zvF1S!vluC?zOtgas=6YAp;FyoHB~wTr?{oH^$}=hHA-)4tf{PwV&?j!v0{4V)Y5s? zl{Hf%>@1cr=7E@sTgtHD15wz#0&5~T)J)dXU5WXUtj}lzR^FWHpM91Cs~C)ITzhf) z%$DLLpWiZr=7m+3v`D$z-5}9F7VZWTPP;uT>M%v(;1S6#2-i{wfQ^_Wy5$Rs(wSsp zL%2>>1YEk-RZT6Q7n_^#RJLm@Y?WQzDDD_ZjMf9zW9W{g99TI)Xk@MkIY853vMB&C zl5a*`HP?j`3#w@~%;cdym2%XU*Vd^PW>={Z4ArWVi<;^w4ek+*btBRpxSYkSvw1bO zhL zG(Y4er%F#mzGNWG)eHY0jKAK%loaAgl2>uC6kg$$ktu=vyjFM;_SMKkN&Hi}60wKZ z6aUDiN+nK2aVV}{$V=UiF?d!TGmN-k5$tq^4u z)`prKjz5;5wC6XktkP8;r=YAuiliw06CD5Rzdx~g%l+F_{5AEf#+?$U<5u(L3S}KE zd!2gv;W6n)9*}-$OnUYK=?81+iH_6F^c<9b+pTwEXTG=NUK49Lj`}1yR+zNXucwy3 zr(=MbR)qY%h1?N7#PPg|mG8X^bh6_$lYZ}+nb<+?<#^Ym-9vA~ouov^r=a;sfKBVn zG}3p7J}C~v#Ez=2#t!>oj-RdkqTfM|KTKNb*CV1|c`Iyqidk;ZhPQv9`r(H*eEZu9H*C1$9fj|;;i)F>SfTdY zt$KBue0^(^D!?&CKE*oyiDYD@?L2OLpGuejMoA_cIZpm-6;b|uSavNS`;+t)F zib;3c@Zdj{J|Eif)PE^_yAALBQsK#u#oBGBX@?XW-nL)0Z(keUY2v9iJoOAEKhuV% ze5l%SvJFo&@iIGZ(sONik;&g|!_!Q9g$*w<=?)v-#v3#Etg_)9CLXlmMc=4;88*D$ zq<7lz98=C-8(wDOj>lu|Z^<8G!_&RVZ-Z9yu*gKne=8mZt{29ag#P|c+lkEX~WAb`iWTkTji$M z@Qy2$pY*li+fCeM!`n^yMK*l-Q>thxPo9at}wE$)EE~YE?ZQYaF-exi)eQdplkq4>$eS&fgvf55~c_$HB|Y`2*!! zX9aNSXpe)Zn(b-lPc{9}j+e#3jW~FYW`}wzVt$60euc?AX3Nn}nugw&(!dG4L?uA=W2MahBs??o`x^h@QXEkxrRs1Od!2o z!>`r&S7`Vm4PT|<%QQTw;rD6yW({xG@J&D(V^lJ*WP9X zlhkAlSCK(wO40D1nw-8Gj)hs|ld9qLA?q_l!&$cVNz-sEW-%>O!?BQzd~!70I^)7b zmxklWTI5rt;no=-CQjCH9HokU$}}8H!^mg4hU@2>>oxqy2sdJvh99Nj%^H5RhA-Ce zV>G-?!_7xEC3U%m_tp5@HT-xDU!mbAXn2Q)_t)@M8a_b7gBpIKhHuvJR1NRc@RKzB zLk%CO;oCL*WDPeoTzRlc+^OM%HU7OCZk>^mr)juL!_zgqNW({J_+$+~Q^U(N{45QhuHhLP zUa#S2YxrCZx6ZUNxmm-rH2%dJK1##eG<>v%FW2yMHN0KJvo(B$hM%wD9U7ja;j1)! zjD`m_e5;0U*6^_!-l^gF8vdb%U!dXJHT*&iH#FR(;X5_FK*RTH_(dA-crNPy`goVD z;e{H1iiTgJ;e9pyQVmbl@PBFe5DhQV@H7p-Ov5uZe7uI|X!ryTcWJn}#U`mm8g6c} z2|iiF%`G;;%QXCQP5yKZpRD2a8h(X_&(-iNHN08FuhQ_v8g3p1mDDy3H;-@%zFfnv z(d4vixOoIvQdekrna1Ct;pG~>O2emUcu>PDG<>s$Pu1{F4X@Pj4>i0>!?$brbPYE& zyjsI|YWNHd->cy>HQe#{sQ=e!c(R7qYIur<^Gvbz>8s%l7Krau4R6%&AsX)1@H7o? z((p_TpRM6J8a_wET^c@5!;3WhIt`z!;n!<;nTFq>;nOvIzJ}Lp_yP@|tKmE=ZGD!xwA#BO2bO;g4$gat&Xh;q4m!n1-*=@Fz69L&Klc@KqZA zl!ga2{Amr}tl`gSc&CPUX!wU3{+xzy*YLk32iM?#=ZQJEA}u3#XnPo+!Ba>l zKvbwx=qpM0ARQEXJn2Nz9YSA3x+m#&p~sL;BHbqRDAK)1Hw!(IG@CP2FZ5}olS!8e zJ&^Rlq>F^^N4huZ9HIM=K7@3d(7j2cqK;6i&^<^WMmk04eU+dOC+!e=7ilNyoqqxt z{5|Ou(%Xgpk~FsxLY+c?Ou7&0pwL@MA4$4H=r>3oMY>(+*GL~tx=rZSq>mxpEcA1v zk0o6%^y8$tB@ikT`T^3%kuDPYZqofo=Lmfp>ElVK34IIc6G*2DeIx1qq*H{xjx@If zLJpxDNS{c0=O3*94AQBjw+lUm^hu;Ug}##XK+-{>$CEypbcfIvk>(&3Y8QG8>A|Gi zgdRou6w=K?k0gC6>3X40BRzz4na~4C4<%hBbU)Ikkq{`Kj|FO+l8J&I+t{(&{vWkLpmt*c+z7@ zcL;qE={(ZyLXRPxPr6O$QKT;*-7NG-(if7h7y2~PF4AQ}4k}>iKN?wevNc7={BKPlb%GnS?K3TUrxGS=*LMXCY>tujigIRrwDx=>1#+kgl-^RN_yvS(*C5&NN*Q<3h8pv zokCwpdJ5^F(Bny0knRxrBGOYyw+lUnbS3FFp+}LfBHb+XNYc|t*9(0bX%0Z4GNA{O zt|nb1bU)HFNaqOMhxAO+X+rlVT|+um=pLkJkxmhM-xScbq#Z)FY@62z?vr>q(~xeGBOuNT&*YBkB31Q-r>b^a9cjp&LjqB)xNw zv_I))(%XfeLV6MDPNA|RZXw+!^eECdk!}`xBBXeWgdRxRN4iMpexz?9og;J~(tgruLiZ-UgmkLVJxB*grwF~T9Q0Ds4xx9E zZY8~Qx3oX$HqzUL{*v^qq&tQFnDlL=gFq&tPalJo;x6+Uh}$5_~^`@AYl`6uSc1 z$=3~Hx)EI51F3krjKHKP-#>60JJ&Q z(x$D=`SjI;eqU5L==Ypv95;P>;-KHxw{dOY@+ZA?1&VJ8x_g8>WsxBIy8=l@si^fa zzKUH#_tG++y@$`~QL-MHo-{M%KqVmC)&WcW;wq zK6;^K-s;{38*dDM$^6aPKIC&Wo$B&rPeU?_^nK$#)aB0}1>7h>O^oSq(~^xzWdIU> zUSGw}2+-cQ5np7+7c(1=V)*d}bJuXxYl7zs>I%#?Tv^+kEqC-_ zEmQ^zyG&ss%fk8)TeN{C=J|}Pa<9%U$-O4GRM`pI7{N>_X601(J+450M`2)oJ6qk? zGK9JWGCKMtItqPZV>#lEE6|byv@p=rrg%~n&mF?E$8dwEFfgkbwkY)dR_NPR==-+N zx5Kz+1eMKii)e3%rupp=;PONVO4(tI6m6W|kD+g2pb}zsL5EC{|DACZb?~pDX6aiB zeP0&(el)fZ6WPItsMAIE{0^hn#Ykxh7WiIQ@*rscaSRfhjQyC3BFX7}OIl*3sz>%t zByW-`0(PKBwFD7I29#ix?R|k7`A$CxM1K0eQJW64ME5yx-*uDVF|NSnDNgT>1c$@3 zIlR-ku18C7VLzC_`2FW_xGN><@40I@wStUhOKa~5Sk^(#yr`Ty)FUFt*}5O=9#^0# zXgmX9p?`zY<;m1+8rud&JRP;mT_dxxi6+!fAeoTmvdui%POBvM9Icdhtx^hD%6d|s z?5~R>mHS?=oU?VQ#omwX&5C`c#qK^$lYFVgx?>kub3yrw_69Br`&@f{on0QC=ydrI zrQnOcZwq{%(nQANJD~~eRp|Ru=(~kByTrZcvr4|tC8b%VsGg*tSqduBxUK|5?;rCU zV!0=~M?~d3P30G$BnmXLsqteV3Va)&1e{VSaWsU4svuQUK9r1x)ab4kApXILrUBiB zn)v+~yQD=w`w4RX4T>JG>fVOBOLd;zAr)`eY;hl;P}o+?(`MeTtxz)b1ycFFMS0c9 zk@B;(@|RfUm$3W=pftThi(^|TbeOHcHCp^;pv^7L_5GSVae~XYA45}L!@xSFC7A2m z;Lb&~{T`!&u?!1FSIZ}eq?c1y%k%xn zNS@LXY&sos+`Tp-YB(JJq#7i8f(gE)3S3ZzDZz@*$X|^VU;d}Y5fL560^tWbxXeqZ z_jxL9S0UQo&?=}UH)Vj0+a7g41t?m{(`>YFPtalv2weiR4=Yu(u1f# zwEUw#LafIK(X!Qj48;8D@_pd)_u$A@lv08~bVm?lVst$8XFn#RV3>pGK`wtzDhFy& zV1jH4-hx?4`c{nlhjP^Sbza4Q&SC9Z=Hqae3c^idQ_>aq;>Wk%=yL(SJ_c57VqLE? zpC>z$^eXgjhdW`tHl9sP-!eg5D^R>0B^Pl3^Y?$5!*ZahQ;lBvaN2xy+WhUtE{s;* zp!)*$tt#xdxctZ#xK52(|A2G=$YlatAOHxOK+||srU-2(rh`4xgI#M~fs$8MzuRtg z@q2%eK7kTd{|+b`S}1xxXev^o^FvN^b}a+9`v$Z^21;iOn6nSGQ2G{W3APMc1M{bm zU^YtNkX{USTu%TSKx_*(%ZRBaNa_tNrmdcdZL6l4Xqp^p8v08hJA{a7xW8vZ^ndEo zK@JY4^-^!lX9C%8Alc_x}}h&cTmAq#)GQmSB0)o*+yB}+ z_67e-@%V=bKbKBXehMxL-PDCSfQmc*q%7p;I-n=x0B6o;<0WtDyTND-K#jQ`ItDCA z&10WS`fY-Ze?Wx)N601rzrYgVf630@Bf`Jd2%HLRU1(L4nlZb?L5bmMQ)`nO&Q_Uu29l~IVVopP5hqLX z0CKh#E8-YQHz=#67?Zq`^`7utr}rEJYJKBe+FNP&3N-PAZ*Y41Ndb2#^c&InI;WRG z1)4kznoHW#2bp>U`(g;SyIhp`3`4iG^+c61$PVZrg?-H7=mG?uC9)b@n3b#o*r;@q8y{lQqS|BLru;Woa<{yD<2L^iMuMC2L zq+c$_PKmNF+e_E$B|Ng>2{)kqWtN!q?O~)Fn;td!6JY5@;Wr`N>7B1wjuD6}s-{I0 zmBae&Jv7nL5_Wp8P&~UqdcsqkEmy;J_3}<>_=aTUN7ME{&woi){I~>G_M5 zrU-_p4@|wVN+LxDtP=+n5>-ln@eQ_} z`*mk4*L{%LJd_4bBiI450OSpi;^HHer2?e0-UB62>D4{~RvF$lHvxkOUO~HmJT_ z35d0P3*S;p=yim!skn5nVmk$fbS`OA#ARY|#-*leyp_4hKGQNH z<4d`y&mU58db1VZ06@+qyg!TdYb9L`;{5?hzp)3I7kZmP=6Fm6jI#~N>BKcP%99rD zbqI})IQ*ds2p^ea*P+0ru4dd&<*7mRDaCrHsBj5-PSZ^kn8WsJL%u~}1|6rjMe$8S zyP88!3+L|G@(d(xkuekTtV}Vz2vrf!oGqEc5gE670cX6*Qf$e>mf&nTLfE2lyMTIY z@n@bbJ{53G)zWXZ@m~f{)YI+pteT!~1?#-}E-yXb)Bo#%~%Q{X)>rifqB2N@f)ej{kS&U$%?}e^HNNG-UFp38SYPz_=Av~ zjW*q5j&GkHEcFRk_4x@bdVLt!Q6G2S!hwkVYT?}Hh7pT)aLTg^(FfM+F=qg?Z>1!0gL*)PESJ?Swh01+(XxP=1%REb7d@CTA+OIkwHKxWSq z`xn4`o^Vh1zmdEI$!h3ve{MIK4{2huz2jiA+rJi*{eWvdUSYi4&*;SQGKEu}rLRH3 zMd3B5m(#ldYZqs0Di{`plLUFQ7m*(Y;R8;H*MfXaBL$LOD}}tYTeQX{iTjQ(MnM4<7C>Cqo{kObLl}y z0{D@Dobb8ZL2egP;%rO487q)!A}rwa{vgtB68m7j38bGOM=ATvfk769alZ%&=6L)) zY~fsDj>q+qjypw2Pls$2$Mi*E%y}>k{TBux%g;Dip?)G=%{Np?{~k4Qw)TVwWPVR{ z9Vx8bDFpN^Am@^QDq^#wtGVPl1$7D})6bSFt-Q&i)IB2o8VH1_3q{+5CBXw$=hAps!$yN!!NW$Sr zfF557@2`Yf{*Dn#>tCurI=#=+ej8Q_HI%GUz@bVYDM(uO?|zR{-}a_ z3RFl8praC7sWCJH1H?+9QT|g;2}mA_{VjkinD-N~iZTHP#I{ zh;lj=aTbWE}@!Z^DqyjSY+ zE7Ab%hh3dZ3`HCwmEw!jo!<8qbfiH0q@LG_IAl6EiE`A2#Zv&COJ7t4jFtp7tG`1D zI8PvMS2$a;L_l=j@R8_xG&`ubQsmsMTq;$V97SE{jI8I|bp?Q>Ne z)rLFk;q9D%&w^7%_(9LH(X(yzbvF728@BQr+psVH0qXipvn z=mDRKht9z@Yn;d90)eD@@OZ)robU8o!1)eqhzXEPczkl5*mMLloomZ~nTt5U2v~<>9asm+ zb$!z~k!!^tESH?#Q$?V}$A#B`_0ho+A>AK4mwv6fVH@gzJx=##q&_RDRqj{lUv{VZ z1*J%R#^#_t*L)=PIS1EfeW-}Y!r(nuP0${LJm->`ir65+XE?oADf(-nXExmx&3_z< zu=Wo#z_nl)gbo)_E#B1;1#^FbyX)9I1|KERg`b6W)Ew2>lC9x)AP!@-NcIoXUi83)9h zpHRAP?}H&%r%$rc+^5phudvb8Hri*SAG6V0Z1fj4`ZpVW9Oemn`B^sl3LAZ`jpjU7 z&%awAk1b!aHm{d}S&Y1X6pZ}&`_iZ{;+hf=PXZU-Q=H9POJZbKPX_g)hn)@ItLS;7 zE8(^9muT?Al35}yc8@eKzC6ghSZ7`Q-AcO4LS|bR^;S}$g$%bYGOVOT3)!D;O8#dr z^WsJ8;x_Bz8H=aVLYgcj(?UjDNFVFsi!@W<-X!zlQ485@A(a+#mUWS6UEE~xY&pZs zKG{O`c#lO)V)V>-P=5q0xh1_pl%(pI@ES@~;V*lx8uGQ8>hQ-`$ zA(vVg$5=?* z>*6biDR858@zh`wxyM4Tw~z)4DY7n3w=Viv7b7fYBaB0`?78c$i>^VYLGzETOU97Y&?zAoz%7r}=eF2Y=Nc2($BGJTmB@#V_YlQpge!nN2 zH0OHg`^))=^I^>MSIIm-vcJcwKoEkL7X!IWK{wgxw`}ykZ1kr#x>TpTAB;~y@55lc z@GNM4cc*CHi0hK|I3Ml%Mh>p=`FkdjvdIwy79`h;2d5dkv9dCm6Y{+!^ zKE#2eXnl)UhgI;!`7fMw-Og1fj)5)uAr+w*C)cLB{5=N`VMTrUhL~^Hd5I3=8xglR z>^|QWShfwBc<9ZyZKF4d5*)^0ru)YkQ(b2sYG(hiX&6qkQmlCvrCHfevLi1}mfVc( z8{_+b;Kb#6`72CfJobR9DV8T3ANo5HKspb0(f0eT{9K)Pa&sojow&75#C#_k3t) zxHn>o)WXwXazHvdKZ4E77Lrrn$GSY%8IGo8p8Y~Yw54xdI|_C%Hb6t@CcDut&%SWe z=Pv(|&KLSL@4MRlUh}>)AlS?jd;VI^7ZvBOIRip+Cl>gAmqTXWt$EJ;?~S_6(A|I3 zApe-XEy1}?o`v}oeqll`-+Nt$Hve|Ddl=GPp7jafIg~uBOdgl7)0H>|2f)_5`#N7Z zr1`fqnmY3q4`cSOH?8?4>QU(1Zl2n!YAaqvO;BZXd>8#L&z+Q8T;O|O6nvEoaM_>X zu9Ll6ocX`G{KvTbCK093giwu|VZC7Hw;Tqkr(|I#*{ulao z^Jw%R!k2<$(Ks54BZ~d+Ic*Tq_PBgJ+BO01lwy3OcnW++4Kg7}MXDUsyGb}( zHnH;21IEsl#RNPXCR;XAC%B{i5A9p%%nye8q0`Fxcyv89yarS{6x?H6jS7aYl*DF; zf^I*uiI&0Lx*o-8t3>FF(7@Bnyn(5m5uJ)mIQw?Lkp-^}O(NyV{^!sL`?Im^Jfjbz z7>AJiBE|iP#qFM~2|mH(`~o_Joa96)>g=mn#aOk0#?NnuI5`NrLeV%Btmx&W5tEwn zNQHK8wd(;k0|a%wW?gL2l0&DWD4o6lw8X#MNd>;QbBptxYYiUPuk6h8g%}fIDEL^a zF&CSufYhOO7Ceo+t9~35V;hdnUNK~lqbUWgl*;I+&e>zo@?<}P1Tn6AWTgHJKR|Wg zF}{8s4e%x}Rn0|~v39+x*&}#6sitbz=E(S=`a^;5o!m*NWJhi>4&4WHCqnlxCgl0P zP)BfG%DtBxYq3iTw9vOt{B?&R_f!4F%LV+Ab@?kdQsIw<{=wT%<@vn1Mq$=>O($Aj zNaAeN%@wU1pCLf)HiKQ&Zb7tmSWq`TWAtL})_~`s2v78M^}=U)c>gOjB0Mlq@{Br# zhlax~Mx6Iv{hBD$VbPC+rpw;;k64?$VCL=Gs#!`7SL)A~D0_|bZPM)3E^!3MF@fLgPsIYDSNr?leTuRo zp4Dg?Zds8;Er@n;84#lm?9?z<6Y`2lo!-~=?zQkm_7US5xJTEM;2Rg^dn$(SF`9NU z+3pA1DHfaisz?htTbrc+{b-bfEi_&FU&;NpM#xwf+X#ad-EK9?(V*EVf8h1Hn)y*` zKxB2jW?jT|!I8Eu$T-o>cqH+j12!W(qVjy)mirR>$-ejUoNK>F5ADeFeb3_0lP9$D zp8@F#%!doDQxTq_eT?Zxcw{4YE#@c~aq|%W{BwITqot-n+Rx+{bvGtZ)zz4pw80IJ90WJ?CGe0ird}AtB14X|Wd$_QJk!}SLji4c zN;80|2ZbEDV$jglXehCtzaA!-pU|>fDf1Shy=j8X5$=KG0&^0_`ThvqiTiNsK5l_$ zV?traD)lKi4qw)~bR+qahme zx;%dl6sb+fwk^dQ*B1s3!u96i@?AE!0?krsdE37JjrO0^b* zt!nMY&?MDj;`0TbKNFl@p35BP+f(4#(Zf9o>We3sZL%@SKg8XCT+6?m-uIwCxqLem zHFGFH;k-mpR1=9mQb>E|+ilTbWr( z=46~o;R8C5vl=bO!@hyTZlNp)>IXs5`2lMYx=SS0Lz3BS$3*nKI`dCw%LPbBK~_0? z5xu4M8+#5BKMC=6qiWCm^l&H(&B+jn8TZjB)a9SwX1IgI`rmufAUrn;ZZ)dG?V7-b zsQ&dU#I_l4zAgvzmw-==9hIvf&3t6a**b?=k;mA8_6}8(@?@7rnDb+pvn=Mj$UH1k zDx$DiYAs3)@z}T?qwdm)7rQ%ekN8vI`xmF2c&sJ&6?4M5--US{mPp<$m>hp$O!*}o z#xeSq2gFhL7~_R@FThazbs@vkZcHkJ9B2cxFm(wV>A!L?#*=G*@=2{D%@G6R?)22? zxVw;P2Psiku@PLp#DYNHAk~T0;OuN^L7C{QnXzNCx<7)6r!0o9E5KstGgzkUee@S} zC7SWgkJy~3+uWU=H7W?WDsI7(nbz>vWnyTDQjTY@pJ<`|7Nkf z&(T<~K_VZZ`kgHxCmXB>yWscmhkvd{W|aKO`q%*kYyGBYl=B3I@d=ah_E^SH4GQ4; z4o}o@;x6mEz`aG(Y0(cs+6U4H;Mp{ne+^d}}4?#kn{}P5>=i*mQaoc1_F`wAn$PmOu0YXrL@0YnpQq~&bkOEzavkjN$ z#{@jA$dr?%gQ%3iGFtLg1QdsH2n^)GLiiGYi`+j@iVSw_bU3mdIT*FDa0@KpG&6Sq zrkP{0%nTx*xdwKedqz`7XoA?H88CJzx;n)VlpK)jByLk1Xc?M819`F!g)G(o3Orlb z`+ED{z@sq_xB@FL1&6QYT>NjG|1x@xTy~)s%k!+#G|B>O#=~BMIMnXfb!f&(@=)I; zd%IRf<4>`yU%8m`QoU$GA^K9zM#O zQH*^PJl!TU5j=8zzOe=Y2DvF`;wpOwD5z_*c>c>?gb z3M{&I7;WUBvutqVp72Mj+5XZmHyQcx0z9Ri;64K(JU{(wV*`2^vkzy_)Yi!M_1`$$ z3H>17cTU$>0BUHzIJTydfvZheRk*_KR zo`53x=r=Gpw;Z^-iP`^Q*E8p9*gZgqoPZt--XDe-9e+ZEX{;}3tSz4T!Gv7dqmV{j zcyiaJrrmP`ISFGHAC>5;*jrc;4CMB3dDbOlSn7?V)X0?!`_g@L(!(Jt;R z1ZcI`H-@2}g`+dR?guxTNQ+;DrWoftcMz&OBzD!!e&u{2F?aC=eWUvq{-no{m4dt0 zu}rid4E@Jg1m7}rj;>X?n=VK}MDR37&A;#*xfe3i+#hLOB9~3~p~5 ztN+f(Eu%##`U@WEJF>uk)*y`XoyGuoquKkchxtZlKXx2UcL;RIG`#~|@kwClig@sD zROA7!g?OH~=^bDGE5>&y)}Q}M*FOlTU~jH}pI1)z2#yXTOJAAwpth3$4W`XX2gk452`w2TJ;txg6z@oK@F2CFScBqo^_=^LJ&?jVwr4K3=Ptvjep_Eoz$1e<;+3qd-M7O$0i;Q! za(emZ5pCRTfXQK%PGddP3QYy2`Zc#D;9hH$dwnt#4V3_=Rx@N{Hp7QM1*M)Kr5;%j zn8+zZ3RDuyaut6t^$T(J2MrFfG;p61DSaUp;7zX@1t_`eJ#CT{sz4r%?)oPdcjl9s za3$ozNRSA(5d)a?&(Bf2?~G4g#)MC?cWuM|o>1*tz zEEIvB5Hk}t*DJNf2V5` zrUV#v5@8QS_^|u*0zZNair?6i)4sC~GFBbT4#?+@Q?2Tu(Y;h3CgHxg@r~r}CSC1s zaIne`@}(2wnz^}w9udfxhg%S^d>cku?pV5fGSa$y%cj!>eCT-4yk)Ww0Zx&OXVCr9 zp|=$ICGG>DL9r&JN0++%%Y-$MaT4YF)v!IE9TrURya$es%wnA_C0LdKZ#JFY*}~(0 z)=MiEZJ<7}>r7U1JNl3}D4Qk}co_s@C0pF=@&`CCaQTif-MYBBYnf^Ph=xw@yEGT} zaXH`aI@V0j_wFW(`$egSyTjV#HO69a;?w*nw=Y8~_Z$6#KRZgR1Yb(TbeHsPF&m$< z#U3%v9&9wqVIYQtp^{wO!AF_V&(xkR!lsv9!+$TWhHQS*?Awf?V%RmbI5>>EIi+Ca zQ1QXpQiXW|b(Z%XLZ<@g6#9i@sV93PuFHylI0mK&mwx{umn$b zs>*{{?8ekb`0*IDv-JulD}HlobSZMFsZogYKNXqVO&;mx{hwhTw0Gd)h2Ws8u=Dp) zaI;14eww+r8K1w1X<_uyXUrl!*|#2PR>3_YM*YvZelykI*a7w50$`Q{O}g&aBhcFr znSkuWegf)XdGx2*Ngw#_^}>xtoXqj2{-h>fw_OV5*rLFmKgOo zx@n6eZDwbFm<`fhe6iw3f$vXiFBv;&&1MKWdvqj($c+e}!~jg53@_{w2^BAX1L^Pz z6)Gko_WXfkjIhaBmLL9FI5<&iFo zc-PK1FsK*j7%O4WeDBvyWhi@5wCvB}mxX?W1pnYflwS~7C_U8MNbmM!_X39AbRl}v zLnvI$R8oAMxRKOaB<}sAF`5lc&r$7#7{(4pp)P+Km-SaZ$!Uhu%d=V$BREwNc&iRH zWW4P<{lJ{5X3k)2&MdGazA~3o)mZ);ft4z3Z!@Y@%MxTeKZhPNHYL(&N( zNW*1~43#GuWFBIf=%F>cWEaEB=Yd0v2wGefbNL5val&%GUa|{;_=ep?Y{#aP|0Voq z=g<1i;#G`%DT=&F)wG`{yAATp71v@C%Y`lKg!OpY$c{KZe^Y! zD$np}o@4BJ_&6`iC?~%kgshi6*?SMS0#kiVD7f6@PbdFHAk-7Zg%JpBk7lU=K@AAE& z;)pIm%RLyH=0R|X#}D<0b3d9vr(dRbkO(xA?8S71`O?ErlWvoOo~Aga#@r4OfnvgVn9vtq^zPw1*)5sONBp$z?0P1KAd z?Yf!oALHatb_irLo9xQk)@OQ>wrJK5#iY^||n-$vG(`F*=Sw(N!XJ%E|4S5ai{)yTmmdG4lsbD3G` zz&dj<)|t;h#p1OHZ0PBDX~a($LByUVp|cUxRJ+l>C80@Z8m&HZxBU;8L2id4g#C*v z(lq1J<^)H9zXZ`>W5MW>WcO)!o`BP#?~Im96A-lV#;-lb>g#!lJE!ZDjS*$YkX4f0 z^dS^ZGebIV9{ScZQwmb)7^|M)aR_Da;wtBkAawfKx$vM8{C8mr|4Ze6Y5XsT{}ruo zi}2I_vj0%v`y&@aPxhu05^+4h^TTu_g{_J?{=vMO6dVc`CY zB$TvEt8BzwRa9!5@gTcrU_N>|Uqf~yaxvHkfO6S~T~n!d$u@RknJ;hU5X*U-zyDpm zRalnSwH>C$IZO}D_qUBuKs)238Zj@zXx1t(HQRx*)}4t#*C)GyMt_tigNncZ7+t7T z#-+$5Y}q;~n@S>%>{?$8twFZ2a|e*5FUJT#Bjz zHtqYrf3Q}A9rU2+y-R0H2LKNK;^3=46BAItJDj7KQ(4~eET`%PzItS%a6n7xXJvEklD`L8|Ar=@x=2%C-lYLb*M=Pu!sim{^SujwW+sG}$zDz>l z&T4Kx<3R}E#LK@@xdVoXNyOj~=RJwVIoRnmrnm5xgT^^r<%TreV?xdo%$z+{&aSVJ zy{laxS*Fu`qC$}CD`xuc0jMU03ywaeRC|XwCtAGY7tsT=Xwz}$8OD=jnFbcUh=*ZC zo#yj{Iz7}zUudIm2i<1Hzd%M2j>sa6$SxAc1?~|%1ZyH@9k3r@&6j1e+@=ndVG$_t zre59BF*|iWTo;wv2G`wzv$NbP3e0acE~a2K2WD^ey|mfe*X(5I(P{_4dQ~G9TJu{G zsbK$o5Y)Rb1$}4qq7Y0jtydw+F*VC>#^#Ud5wh`_t>z}2EB1(%)^w@pW_D>=v+}qB zyEHbc_ZZ)O6cO;d3P3?~+AfC}5FaDkT5a+YCphTpq)2x;CF;^F2d_fB1L_z*p((p= z0c&fNwJX+__oHFRx{|H3l_TcZ!vJto_6%|! zK|-AtLSw)om3N=lE{y|gD|&>Y5u%hM4m!@_VtMPZ&B2L zxf1-@bjoxze&}1}ly644$Ha2G=~-~IL~=85LH2!7?w+ySmhAWMkIJr(a_^3Hcs}k; z*^iRje8J-wi`#v%HYmI=oPQeg$+?+2OXNlSE5|OrS5+Oi#ukQg$taym49-3Dkyz(` zhCYp3tmcb3m4Ks^fJjg23A*bka)uOV(CRba--DFfbvRG%jL!E0 z8SU7R|L^+4=csa!`1(kCTC~8RtX4382?}PhsU5V`oom-r9VuNefM45$n3aJ zSxfrE_u-S-dpNC%(;rSklUx1al_+Eega1W;=&1xm`ok}OiPs-KX3GDM{XwmN;CSsk zu<{3@uv)cYI`cEO{x>6p7?V2HZk+`Eg6~kT00s$cRLCk}h(v&VOjfv`mP!im3w;2l zDh$Yh1({~Zif51U$){o|E^|8mI2j&du4?##5OlTZG6#1F2t@t*4RQqJ#l2i=1u`Z& z*>PBACdxF@Q6RR-dF=|wjz6On?^6WQfTeFScDzfD*tcOHDdnyqhq2=`xnDT}JY}Gx z<3#MsvKu8!e zqMH^6p=oQ`T$M7pxti|{H|4;f(x8Ei8F;3Kz5EUF)L0|#k&#ub6yneky`PR+(X_Ze%oyO-?2iPCA=rf02BK@p;Fq^-8#|Yy^OXUR^GC}r5xKluKH)H|$w!J_ zYpAU`t=(<>`3`dnX7mxqD-K3pA$zwtn7Z#Gl|H5??g#re$t#ed)R3rBe21f^)SG`q zmAZ;by-dK9y?bAz8o9AK29g15Rbx2Wc`^^|o1*ORLl>=pqqPF|-Gv-IRgPuR96Muk z)Mz<2GsjgbM@2NpeX%*@?R=(X?_`eF-$kqRXpYR-$;Js<8B>|#5LHI_w@9@+V#_eJ z93z?I1C`^gXbx9wjw7`k4(8~ga{M)#79=Zcg`u#m3TuY~5o|3nDDcQVYF!?wkm|$8 zbq_gW$_<^_oi?HV3dLy>+!t|rw@W{iU4V#jiXbbri3z^-xv#)i99{2;84T<1NyNBjym9;ZYOfjCg)IRVx(;>KZ!<2BR_LA3L>j`A-7lidxtcO>$&y{dlc~(bQDr)isLw+O zLOH#dwR+-1HfFx{Qcr)umVS^e{hfWW{Lh${2%ycBY9VvXnTxgTZr#spX zI1hyVQjF}3>(p7!PEBw$24`i_G*qI^q- zeLV#3!1ZaevvYJY5{%~*)K@{*5xQSNcsvFBKS$3bv;+`t*kfU`!zg>0V%OxL9N826 z(YOZhA_KyHD*KH_;BzV`fN@#h9uAC#-s5EOTB)+_F&_U|-O=Jpu22u=E%ayf{FQSR z-k{%u7uLvdxr{j?*nPr&^zXlb&+}Re9^k@`S@Eh!I!~RG+_GeyPOQasqM~e{DsJ z$|X!3zY4(@BVD4FG_Q2df^fmgg+W*4O zb@(&B`}t%?*WcASQNQ>FR!YL3t@xjp{{Dd+G+hfVd1Cb1y?9)q^(+uv>G_tW;L6nZ zpj+8Wf+#&hhanNRS%!kp41Blu1JHOiQ1h+q&em+Q1Xj{)rkG%xWeWLeNaQcJ^1Eki zoj9M`#pJvxnsW#fJ=w=cau#SghaHf!Fq-plBx>DVeuYM(ySzH_EXsIsmlf}>*2=h@ zgHw!lMx=>DvnBCfRvI^lu*w_f`@z_I0h_rcjRrAqCO#aXnZGjvcVcAH4piKS8-yzJ zM!3s3->=3YCm@W!;POY^txb2g&=Qu2^Iw*(>gP=~eTN*NZ)Q|qnK49)gpx&?k`5>d zNV=7&_rI4QJWnBym1#rhB#{1V_vQsI!1ES)zTCae))GJmc+tA06sLR9*}9;OSVToF z5z0kcn|8m@+{ktLd%3bMNOm8KyY;DVT3($51K36wWACguN>*BA0qmAnx#xlDP_;-_hhqheB`@?8E4lkp7kvDgoB zWp%n!TthocT=@AWkCA{g*E#6yd^|mdKNI|yrz6)F^z9?FJ!vM1ee`N`O+RT^(JEHP0-V#%> z82drGb-(mi+}P!5L7WHY!>+uEk!koZOu(qxgy+o7^Sst?MtKoNxH#T{(c5TZh~l&H zuN#kNF@v*Z7sHJI$U=W(a$(jkr?&?OOi%U$|3*+m8HN7rW?VYGeB~q7!9g|t6!?4M zFcVM4;!QqjfSH?2iB$_=Cs)Ec(p4{o@?1{ zZ1$nL{;_x_K8XA0__l6Aj?O-eMYbFZxw)PVcobuYaXrN4W^HhKjz_@AQ$JF5EM5l2 z84${NauH+i^~tW$*QdDqU|?>#7tc^U9K9du!Z(1hA(&5pIa@zKiHO6-1+Zx74G?Rg9!KbU8SJ@s z=acY0%zAv|Rv0IW;W-5ww<5#?m1-*5vK7DVwD2wp`UBc@1zb2*Y|iRsMe)H+l(Wrv zwUt|t`9a(XUs2#c6pp|dQn+cfdethk*JZkVO{-k~Ieg%QXLOCt9M-eOCc6(Y z4-22eCiFM0;-PFzUU8n|JD!QF7jvA+Jt90EL)8${7 zCe`{0K8$K*O10>CWykB)YEsqOW&A}f*NC}2o?Y8v^oy<66Cu>=FnGOoyaVU|fgVsZ z9yu_&(Dq%O${SEKbvI$7SJmw4fW2mNztvu!zFK`!QJ=n2pOaL5QX}&; zu&vAAh=qyN=c3cd6=|nWjPC05DbVigb9{I8+3ivF`Fu&Y_2H{hD!22Yg+TG=tP7`h zBSo$2u{in?+7(Hao)+EA-%%Q!eLi(N9&J{{SCw7wV!(RhI4Gv9FHhxiv zTlgk=;5PKK%|;D<$e+Kt>m_aS)b(k+^E5a|ey{ZUML#TNJcnQJ+fE5Bg38hGJS-Lt z+s}1{armhSh5pm;`tD>t#$s_vc;De{NlJtS9Por7>uD8haN+v0UZRT}t9j%fQidQb z1CL1{6BboLc6{6&3>)taK|~1L%d;5N>W&!>$4lTrl*Hq-vL?-aQhwghx54SO*#vPas%j3@O(GMZP_(DPO3qo56y$uMnl68_VY}Dnbp)O2i{HJ$( zdopxd*-jM#%bNM+M=-OhTfyp@o3e#js6Xa~0Ms6pXMK^1Tv*(zoa)SjuVt~4(~N{R zb-5Uq%jMFXZnsF0>Le=CR;aWxL_bg+ikhydRiKP%bR!t4bpRDuBR0cxV+aMZ^NvI6 z5=jH~$pu-T&ptuso&M2sg6q&luv6COb9R{djQ!1wxnW}h&SG|@VvW4Aj0Fa=N8$JM z-~xvX78khV8_NaiC7C1q4yQMyRv!VRN_TR4@56K;68xO4o7L)r6*Pi3VibB20LOXL z&OCOt$M~1QiYyZ|1hU8OVacW@#w~*|sQAT1Xrn_>lGP&KNmK>De;6(O3bdqIy4i%h zD+1Do35tSM$ zhWqIoQ}FS2(skk>!-DR4O+fRB;nzF{v=!dUf<>}zK$S5V1rF{X6X4j)YhwU1zIn5{$QS0 zG@lujWAx*EZ^_TT)}xZ<&%RD(0P-!9p6UxMm*$f0UFBRT0Ri9n&HNANk{0H-^S=)M z7c^#IV-RnKSlq(f=1wmjEQCX^kzO9iDEkGjmFyIc7s%hg-DT!EILG)2Z>WL0nAi;cUT^{CGac zvxb#&xTixY*|7*@eETz$Y7}{D6T{!XF&!35f{>oLkYhYzOp(&Os^fv|ZoIYOm z@vYO#mx;qqj)4{&Mat-X{{B0+V{zbp0>20loj+OY5xJq%3SF$J=(pIYTg8pKBxCRO zuo32!D6?I}e@4S%{|E9k@wbZjKT%P{uNb*^*yOe=x$R0Wj)qk(7P*)WQEq9h+$@nh ztsA-hZE_bYxh|0_=cEe#57R3}`Z-E^Lag*pw$Uih;x3-7hhy~S9VpEnYbZ(;@y&I( zTC{;~9{XFv@QO}xsc(()A8GX#k_0E~6fEp45 z8U25P=e~p$D#Y)kp8o#-_}u2X9gq!mo92Uu9a+4VZ(%XLb|0)Q_sa4AYevmNMDPy~ zZp`!B@IDE4fsEizHGEto#fg_=xG?-O*r-i3T8Y2-oD93?@ab^|8dAAJq$j3a}r~UG_c3iwmIi$B+ghl#DX@J=y$T zVSXpF?twKa(1JSx@BIMMZ{F9|T6aGRlh)-6=b?3~;@33(i{xBsX?zRDJP0D6*}6{e zo%=y}vL}5OY2l|KO>1FiYa?0AR=yeD7@7j03g;)~W&t$hP`yAYS!Bt!LgYZ|h979X z77CUfpr9+Npc#&gZ<<9(@FXmb>h z1*h3%FwH4OF{f}yFWIY&RrHG_?@U6V;BYVy=vg!sQ6)xY>Qv4F@naj-j}gV zhSy(k&luL=b;yZi%^F?z=oNf5l96^{ETn@O58({EoHf@1a?>;`7=ItS<~PhZ&Al|l zjHZfc(ge5-lszt@>@_jU&fcplD@}KyQdXMoawIEd)wa$OI@Bp(=(( zJ`~*kk>xXKF$I4cVxd;Ocok~I_dQNY!KWURk!+~ix{oW4Wm7c zcm*x`MYOm$MvHV>C$_CzN(*VLK1kN>dVJKbf2CzK1)tUJ@geOIMx%ATt!Mv#*n1c7 zD2l9qH~}J&%XYk==z2kgm53-=MH3;KNFqHtqj-tpDu|+pca#~x3otktNZU5VRTOs@ zjCjM_8g;=40tvT(iXggxpn{0d!?1uih^X-Wey6&7dO|?`ukZUk|L6O79x~n4Ri{p! zI#qS*)H$busp2hA9C$sr+NDnKG`ud{xes2|0O#^h7ku{D_X6uL{KYOJGOAjo5V21q7yj_Q4>OXy$e9K0z4zerxv0(8 zHOX1&^0K3!g3j{;39lqNG~*kkf~FO7H@maYKV1{@EY%#Tm=oQBtQLQft1h)6hotGB zxIdG~3=-;cjZm#uAH7GfzK~Mk4}`c%xQUv<5wiZX605s;c^?(}6-uDkJgAWI&ZW0U z;RpB}eg?htDIOfzg2!pzc5U=nXjYclN08A*fDD+=OPA-ZNFrVz@!w=$+ktqOE{APw ztnhIK1@lF*r<>6xoFn9Ot~GuiJ%ao-iH=?>NUXF|_EUG`BPPXh_hC{@oqa)<(?>$@ z=ncklv9VOXT>LBgGo1I!#zY0O!GT6rJ75BzfNlRq^JBF+jCyPK?#xz;Hvmtl1Lg%C zyo3jk5Hjz~37Gw%Bls+g>$(dUqcFtXk;{~UxFeUC&7DG#GpIm7=14MNj>=YYB1J|@ z7&pO_41K0YvNVF_UBBP#CbPEj~HL%pc^@I4}V1d*&e0KK34 zSm-?pKTXklUSoQfH=_4n(5Aj9?9iJAfcwx}6gG|M9lA@=`}PvR_nZrGyD7L;3T_9$Z7*=& zKtAAloeyqLflEK=Cg3I-!ELYL>I!Z);AQ}Bcp%&FgK2-r_Vd!JwDw0vxj1eCj*ySJ z_x!MAsitNRsbe+zr-?f1n7qJcZ0A>(=?slMKE>&Z&GYqwMcO#I*2p{_ z(>*41SOcu)88f~NKLW#E1!!`0?on_H7J<>(h}elpS%JEro9m1~x&+C()#7`8mTg*T zjUBkV81)f@Kqy(Ey~-PeM5S517XV zjb(v?Pr?X#TliPxmO+A&ci~wp{|D*;GjqyAg(hxQmN+UAIPr4*_=M}nx#YgKIKim4 z@4JsFtJfKi6iN`xa+V#|>q;GBr0$Vmm#ki(&N_@LI%BT^y^15&TEFTV}k z=9jUP8;N&{%f#c1j@4i^kS#LJiMV49L)FIx&GS$f`OPTB;VD?JZe&gKU~U7>hHDfL z)&-3BwQ(0=nvu4mFZo&6v$RGV_c!)_Y-CNws8d769*-YH;V;d;8)FXPWV5B|u$wEb z30Xbsg9Rh2RZvGTSNEmTzJAMK)OIMIwequ|JsNi9s)@)5gIl1689dtey+W|Mr_$`GG{R;9FE1?&RX{uQ$4Hy=7=a zKaB2GuvHBA1cg6(PloSJq;NH!p(+G)A3m-)wJQ>48))N*@#`)hvj@p2s|gt+5sjq< z3`k0IWU^;mS<$A5HzwTc-vhD<+9Rk|w3wH;4ln7G{@MJD5K2z~@x&>38C02`;Xcqx zP6NxT?R#V>msP8?2M zD&lEB3CCUkKM7=$4~RD5GGCLP0x;}lsuP7s1e4jLIPYMCFz8OqU0_ z&;3TP+tNH_J@9XAVSs`d?1qSHtS|$GQEl5V7L%PBE+%M|E_3Hy#VC5gGQ<{2@iQX0 zi8%BhNFozv^vq}v05mGxl`Kpi$ zixZ7)M*kI|PH1EU48ax&m0U(`Vr zHM`3ek0gOm;S6z!+Q8<}v>4H}ORS5g)8^9q2pAO$Ha|@HEJ#3ESl_bQeh?J)8KW;wSg2IaZ_ex(wC3>2L8K0W*ncv^=LkE4%r?lQL8^5LnFSE_Y|JI9GI>x=kytf!aAE zkoz&kuOR2<(klC2EF2hcRY6P7hS0g52L*=*Obzh<33wvK;+s?UfZ+6f;DOB*CR<2CK3l9PW8nSGj z&zbL1nfXGs&bc3h%ux`B;YtR+xcelWgZAJEZAaQrdbSh&6@AbR=$hui%-Wy<%#B_- ziJ_cotTs^6Egm+E1P;{K%F3W9oOlx7L&h={jsZKy=ZSdYN=|HzOa`AtC7i4tz8S|` zvBDrQR)XwbMDD??Day)bQXztvmP43Gd`H#q9Iin4cf4NkwKfhKYIG(LF=_*K>svTo zO(`ng24#!iCIeuza2Q_viioMMU~wTdQ@HRRpMwUrf~Au{gDUJGrrC#}O7O`f(4h*u zh-u0r8J4b``*`V*L(j+`Tv~2PyvAxoljrOrFjr1Pn{I6lP(v_f>9?K00}HhN3KJHhP+em6+(VJ3H8A0fI|oWB-Gl`u z1ck2y1>fn$j_|qOeih>oBcSUKwa%aoffN{nkQHRRx}F%V=++hu~z;N z+Y~Fj52ZO4ufeZYeiumw*75XFG7e91#v#f@+;Ny?-*S!69BhMz-;Zu>0l@)-&j4?6 z@PUpl2@4i$W8Y?dsm+2C)i{t7&$EEBDhWs%5~ALV6@EF_9cTq<1MO4+j)C?^WK0|< zCF|`Eu=>JQC436l#s2Uw5Jj#9a{h6|*kAUl>sb-(e+N?XI1gjJR^*JiC?S_3%|$Mk zjqDeZ%G{42w-0gda_D^|W0wY3*y>LsgOH`Z#QPk4fkJJ&OK?IlCe0iv}ci8U^V2FB?k8A$@hKxGeEAv$(pFt4+2azi{_`) z0so*FXqNz&0?#!2$-VytgHJz7Jmvzku;sDEIqdkI{Cx??vVV-E-tI!pHV} zbmR_^vbN%;7IFbrsbIlq8+PYrWHH98{b+xRLcCjovFJLdi3hL;akJg7vQ5&hUYHj4 zpRYvnX>qP6$V-Xe57V39T)2lj`PJIit9^n6Ay*2QJ6bvlcI`y4yHW(ZUi_H2m^DD& z51O5!z_r=19yi>sgQ5tv3vRGhpg)uBy|@{|$}^nL~0yW(O+3Z^C@r3bmq!2RcGj z{}NbyIg|75<%9*aQuw&_IqD4|8#~qvAda`eQSNrR0REKUJ8p7gJ@J;wZRB;xo(8`Y^&CITc;0;$Fp?%-t zkd;j$pA-HL&@a`V#T+i6A5}G+S^T2&9I#Mo4t-o00=w1_=Fl=oJ=C3Ydm5^-55vhD z=2Fb3_#k>zZc{@wiR;NM?$!|(rsaNt{lBJMJwVN=PVY6MCN>pLIq7|L6K01RhAqt9 z09ootSC$$~%vpA0Vk8QwF!R$@=E^inw0!TTDthroE7Ng2G)HZD>xJZ zICiPahusvYUj)HxZ-U|Y=HS6QEqW5(HfqKTft8?;I{_@AW;!HLAqOK6@D!I=54SuI zx5Rb$3Y9_vg4JGKh8-TTDSdbN!;Gg}x2Z*aLGFeZ)!q1Qf)s4Y)r%lOMET6xh@eW9A$Z4kjyg=NIJess0OICZ)FP*qJX^4K@6qm9 z)D^iJM~~q_0prtBZN`}$Ig4Z#NB6W1Kk63p0p>#C0Y2RaxTNAtsESKLKmokq4Ojxb zP+!ylw88HK?DH43=#Y_|2&!U%wSD5GC?p+;nU_9q36U$-*(x>yDg6bYcr8gH>7Z6P3r!Xp!o#h1qZ(Cf|Lupg1H|C3zj@^rm+G6 zA~HX?#A?w>-?b*0Q;8tp!3<1ccIG*44vHLwArsje%KT8U4jK~(i@>2m;g5TMmokOV2w3lQlvM%;BrnTq;%$3^ucJeAL1iUf6KE85$QnVxWu_w6 z=k^(y@JCvNX(JCM&}*;`^aKgp?{NaHr~zzf~te^%F?$pixvKgKu%(a530*| zf&Uh}G}%Gmr{HQcbVO2b6>b~-p>0^h5xidTO=O)=97|8ZqVRX9vsDDAM)RaoavKcAv*pT*PZs1FRDS1bIDNCK7iMVPg4 zxrwdKhpOvU&X&xHp=#Z;9E11Z zVH;u_)(!T>j(Nmk^K}1I zSM6zU+l`@X#)vY{-JtZ4XT3*^+>OILZk+@b;fiSf$l<3*i?a@&2W8U0!z=a7<$Kqo zp5poz9pTu4nRcDsSy()h&9t^mQ&6vA6*+=X@wIM0Fb^tm^LTOkncm8mKF{G>ro-V# z>Zzr)tzajo`o6buz8ArgR+OU-eyvmR5;)D5b1uSb?n}om%u8?KOFz$-PD#pIgI62r|N3vHH!UV%mkdWLF9eFJcH#ErVyqElxe1c}(DOacGWvS~Kf zT1@D#1g)$y5HYj_$0To`flRWD&*2je{)`qK;YfU_T9&zgx5{3y57W`P(A}B+>>Kqn zjuFtf(k`}OfOLWVOn|hn1pOufN|`=$>HF#*DANzYRz}ESpA{_n8CjypqIVfr!5rW@?2qh*lp6Y- z7k;HY_RKDbGL*-jMv48%W9v$qlE>bL5iqCWr!V^d<+0x+kJ(`7|F6qqWktO3&yz*e zs0?GD0xdA(Wk>S^S~o$S)|Q z=6g?W+eEnTj_jU%_q!v%E%tvM+E{)Qpvf0GulwY;b9{L2PkzJl$fZQ+lUIwwxVpq{ ztb7#fAcgK2RGGLR6SQwX`oAsT{g(Pp{@vxt(|$po><>|^kvw^}k|*DJJ6)cP&RP#9 z!{PTeC_-UF!y9L{AE9_ed@T_!bC|Y2;ZpGni&9?9ldx0A`6R}rvJc?*Kcv7U-*Wgm zI_pcMW`rj(gAyD?1V(jA;9HI(rh~Nc5hd`=oz4&%Sl1!*WkTj_c90gwL85H*k?{w} zeAfA}aa1xNojua)(aKLn8td{2z1Y#Egv(4NTtdRQSc~r^&*fjQ#dqRCN&gD+_acUs zD3XD4E_o84$_FL4weY3$Sl5;3vQz14RYR^F&w8x3FW{Q;G`V&d)0>oQZxg`MbqA1Z z&q6LG*YZGI$+ai)iE=IRN*tboa{#$^8#)$nAlGh`C(5;J_>>R1_Cxl%Pp(~#cXz%Z z$^G)}zvP>ulW$*=_=hju-RE@R{$hxHkaqg^Itj+3CjN|^BYgV|h6ea{I4k4^#bGe5 z{0!uD_U?_Dt35wiZEtv!%%$c{AAjve^;9G&{!08EnFm!8JfM61z7d(+{*`@`Bgen* zOLyB-i=maM!Ux~{rQ}mlJyD*g%AzTG{(BUS_0Ss0^XriM|I72gQl209`hn&7^Wi3n z3DA}2d-de&{^j|P3jcTHd9k{KJfE0)NGA2OoM^xDl$F@Gtiy(;o89pX@TArK$!Z2| z*ld>~vmEx-+vjXh1LXX#Gg71F`}LB2gp>VsTq) zjLkdTypvU4-N`#AmG@02?<_Cx-70TaC+}ZVdB-_`Sa(3a*mUIU@CiG zC;I?q&&*KS4^z;$zNQFrW-5EGlReL$eIpL`K))qU_N-L)-2{aCn|X-WsJt&bc|XxS zf_&iQUAY})+@NOx35sOTLmIp0*7I<8d@`9(^G))LOB)M{m59ovc%?2*t#9NT9SOGlzXi@^%d*3An>z?5c4&>S>C zSN9&{bhHwWBSeTRt-?(yuvNyiDj}s3&tt5Lw*!x&ag-QEun}gpj}$Rio*}jhb**;S zy#k++u4kdR33YY%dAJb;CY3l$uNLJ@(CB7Al_y_m_Gtn`qpX&xKlET~X{~pL{{ZSm zLbaEGAmU7@^b$B|Xq^wJxV}FHl_E8!Q7F0!1krod?Vnjj(SZRc?l5*Ho^O>$9T<9^0 zQv-8WxJNi9Cg^rTOTGc6%c+l_ggPY_5;u!ANasPe*hq^(jyYXO(eDh1Onq1(?mwRB zm3g*t8QLk+z^p6tPgVIBr}E#}I6u{?%>VPBk^fMYe^M&{6^-+s%PbB~OIW6>DsyA1 zOt5j8moVH|$CJ!IS;k)BnW_AYHVaZ z#Q^WK0ZB}3^iDOn|2r?qRJGSSSdstiYXCk0r-`(@uQn>Xw9)&22+N|iYsxJ5P=&hJ zv}WqP(rwx|r=g+_s7PiXULof`d;&0ugYcy>$hjy2>UbbuBZ$vbJCca$iSx(AoJOcU zi1)_wKIT);0{17ntoGIGx%q-)T5oO=`I{rZGNtw(5Hv>(fu0%@6wQQ6Ck3q`m;*~; zELvKT?8E&B(SoR$BLM|_@4#z~*jNP7YMKqf>Y^4tAaVxfOocrPCt%^w;xk#HSgEZ; z98b1QCC4S88VJFP3kE;ObcCs% zRz6XhSvZbxgVt?10b^bGdU!p-eHgUNLR~Nu>rvPT-y_{%&539Tdm`&xGp#IpI3QvL zs8q-r zzfLCH1Mt_5@%!PgBLPwP>o`a*{yB9&{BfdA z^Bmth2$Q(e4}%k{eS1uO_It}<5gA8F_lur}%ykaRLmDFj0ApXIV5qz@4Fm+n zPmt6Aqe{WJ(}U5DFm{4~J{T<(43$@4WC@HG3Xf_9gMP4>B7w)JReXY_vt? z6&Q67vn?+x7_|z<5D&(5!niXX#%KjY<4D4onhxVl1w-W( z7_SSA*3inKUotrJTNA?`jCD@|M*nmecPSVuufVuNU>pG$VE7ybBSLg|w?sX<=6Qet zdv-vYo#ThL$38(pQ>6sj@d7PRpkeW}hv>*Ia#Q4K1q8y=NhU@;Ybi`ee8Sd5VfY;}Gtf0M({gaxDw zuAq583>pVyC*j6WB2iM~wIj}h^?Aq~mP4PZo`{mwfj2C}I^4Vqach4LXczq3UJG`J z*G5)^;HEqV0_EP(qu<2?U`I#JMA`Nz8(H8~0wDyJunWRHXf>^Xt;2Q^z@Ku{=LAg|$L9Qr5T0SM+RF&4*b@BJ__O8Q11+si)& zYpI*!;c%f4zcZ=u%{J>)4R|+f3ld zofhMBj*f9c+uaEZ*DyBAnm!!xMTS=Kjwv0z2MNlL$^Fj=X$6z*)VY9|Pn?QD5G%Y2 z6@nXK*?4D~4E7bb^OoAsJWTgj&P>FXLRKmG7Rr3*E|1xP$a6^hRPW6Rq@EH)DD7Ux2}TQWRCI`NVcch=J^YVuc+%4DL>A>RG;~mJxO* zm2jU2uGR(jCxW|@Z?VD;$GQzlr(72wxPu7p=th(?8&mFnucGB{MYB&p!T+ee>|n2= zbi5DpRWup>nfP9j@&OOrdKcWC1UE&2JIVu>j`xqgj<}fMwjjZe>OOeO-dTElhg(q= zE9$N)s*bw^O2>PpucEI=(1j{tl!v#wFxWFN)DxR<}v&sVZtHcktHAO-zMpyz+{#vRqd7cP1F~F)ML3L0D~0PN9OYwDKoV7HGdj zXyLozX$8M;nUBUGB~qe%zrXU&M_M@#h3%)02i&jmgh@%wwe#)&zyK}zH(zfscv@QE zw9)^>?!E(BW

    HNLKkO%wdHPKY5`NDok1ou{gmuw&=pD%9gS0zg>N#@?M28S7qML zRA5eQqDw2$IP9KFX=BCTD(9CQSH3Hm(}}r-_gW`iBu>09cizRW&c5p@7HZBk=-}#m zWy@EbxYYN`Q5k!+cYZrKznz`mZq9GM^IPQn>io5jAYdvS4tU3Y9}$?$%XPeW#(OQw z)#4eh-=&LDb}^pw@r)gNXgQvX@VpvjR>K_xuR8rFxTRMYOHRTz8UNuDj!pV1Xa&&b zKE!=)5&qz10Dky8*!dme{Ekq+u_%A>Pp^+vs3$&FrXDAGkG=Y44(>d_(3+M1Y zbGg5V&&x!xJ_gx_hM?6k$DV*30a)J!je#Q=upnqWLnylSpky~LAB?g?gu{%>2cWuX zUL9gpz&E7UxT%Jqrdt)NxZtdtStG_^PimON6}fBO-1V`=&SQOSwVNn@Be5#H!uVi0 zeq;eQ#P+-xoz!_jQ%;7@MH%$VXXlon3}oNhqFl#l&ncK8DTYO&WGT zd}qGy_>LsI5ECHZvycxw(Z_Csyl&Uvw=XNR$0-1|#?`bY%^n=*1>LhIvND_~!7TDR zy5r=qs`Eb~D)sivAMtB-zvMAyT32i=SX8<`V^QfB_`d=Fzr_EI`2Q9DZ^Hl08TF;o zL_5;~aIXSzi~>+my58OlauM`(>PuVq%NO=i=S!*jlH-2aV87{n>7u^0biaIQKk0lq zM19%&s32NVy3ro(d^x!_4r#3JJJc80ciJ~OUq0I{joaXs`O3b?`7&R9S?PY+Wal|w zUc{HV8Q{l?(#>`okQ8dc^<2-bto|cT$|$KAh(Uw!5BKNbK3H<=0?>0c`neyXs>yvQ zR@V2!$x_Yjen+eRyXhoEvZ7om=l}m(^Vw6FYW_#&vkM6L|DO4*C5E;;Xk=pV%VC2a z?1R(+^87nYZ1w=5N>=Vj^!+c+MNLjLRN7)*sRByQ^ny7hW0A}*m{Y)@P0T5|P=azm zXPzK)1|N?=5~q!A9pK}YX8-Nl6Y$2bDp*KkHt2(#|LxL=^6P;d+U-mZbeR1gVZHYt z&w%x+{7Wg8#eJ4iE{&bBB=TD~I+^;G(poHuwZ5fvF&4qazNHjP=14A?TuN7?>}qEz zU5|3>ou$-98GE0l6bm;3B*8<{T}mIeNC&l){tvR=S3;Gnf8O^SSr7cSNZ1PAF^cU{ ztDeJwi(;7PGr)vv)X!S=BbG~;`})YlN6{1fHU-|dKioYRs(vl%UmwxFxt0g!!bKhP!AyqOR3}bl^!n^pr@%!_pD{WxxYIv z9|X-=gu=RqBMrZS%zE7v838?1Vc*SEv(tU|BJzWQC|=D=D{$&vg%cIXkvwA!Sfks^ zsW7^_21TmvQ8Jxx51MZhw0%75%3K7XlpTWR%TfL?l1R)(5P*f@TNnrLOtNdh8V*<^ zaU@ep_C>rWco{>eW57xK37k{lr4}!c>;ww7@STH(JmL#9pb`l^@+ZW zQ1>|^OiZ=1N(vyP1HxlsB7ub2^;A^LSZE*@MijiLcv^IRHhwVx&&NWE8>I4&qDtR& zn(wzfVE&^cDMza51@ptVA^Mt7tvX;0YmaFf&>*W);)T2_l5VdY`v!y)!3)M}uMQ~) z2)PWzdsK{&Lca1562eF!%f)OyXHiz>Op zXVexFPT<>59;yg8=8ugC=dJg`?>lKu!N`88D-7E=BbU!!&3&q|1`53l?3+LcaL6z? z`;N+%OBbJ#SiXK@_Xvbc=bGK-T5$TvYlr6Udn$Wo-_gIhycM zU7KZQosMEit&vn`GZZujgQi6}LF3f{vLA)rb$mTAf?$g|?%^y+buMMAj}LY+Y!0o) zB}WK0MFeZ%`p5b>RXhs1Xx*L1id1T4>T#0$D2txD_07!sHbNZbx;!Zzt1U`3U=csE zX|O0kY5QCmI9bOt*}A`Py{N}o3`4<}Pq*USzy{2#&?2_aM*HkbvFp~&={5L*!Z~?M zRPk&S$Gta0**0q^j$Q8`U=LzF)^v6che%5f6ATPV0s7-oA`}!iQZeml`w%7AI1}xl1Ip@NVcaVS@i_A(b4#@Ce}9Z5-9@gSL< z+-F*3#1s=|oy&qgCRF8XfvnvNV-piL!k28;;x;KYW&y`nNm?MvO6YG%t8cU%8Eg!5 zWy~PI;KXXPy$3@BNh&z1ov|2iW~ZxBY2qgmBvyDMo`E{=^tuedeZex;GJ^tcKLO5? zJAqN+mK(o4`_!Yy$VOO&fRGEyb}kY3^vX0WF3W$&NC5@MzjEBxRd!HS_Tw}Qgz zE{_~zIkXKEzW3F#S3{YNs+Pa0GHgi&sO4+PHNFx{S>nP}wcOyOxX7N;mQ7F`n0j3kV34yWVv+<(Q;V6UT)-DMFwP@${_l7vp*r;5a7)I?xjV4*)fNWM_ashBct zc1&@k+;$?kDaQA;{+>3ZRaSF_avJZi;=1w_iX}hyxBoey?0>Is^v=smi_P8*Rv(P+ zs~Qq*(NAiBDTlKkVM)%1fnIjBplh-A*a9tno*I7HLpVt5GJ_^UQ_aszxh4h?jLEz+ zN8h!90Z;-3OSQ2hQKUqhb8yfq&MdZy;W4g_TgB03wLnDRPxQ=M-UV+g&Re4F!HQ#v zZuC?iN0p`a;4AnWDp;t+pW(y6B>_gs6OE+R!U$Mxih~880Jnvu9lp}yuOUxq`9?Sx z-~psseivhM-BgWOLtqbmAj5WQ4>B5y9l=!;(7}_NE}YKC&FZp6JGcNv5mCjx_0RK* zwAvV`KU83&)kza%}4TsYdUwJ2be3fIx#o4#ke*7us70 zo=Ua%uARTo-aY7m1Gl%$FSd90Y}MX*b-z=4?z*xpDD@1q+DHJjmU{J~YYSS+ZPOd|X5op_bJOigMV|MRto{=&9dY!TJ zcdJkaS=x9ECCr-ajMmZoYr|JEU@i0s(}4OMAOX~~iTW%w5rNdEL2l#8J9f0jH$tvj zhg|R8%46Oq39WJDs1m6Go37UI{E9>-BW`>x0%0*q9p#(t_8b}T;YGzzrkkPKF&l{K zm@oLZZbK{Uu|qPT_bfIJ@0fhXwa*hQq0jKJJbE0kY$sSU+@6CayKn!(07EKz9@6UJCl03f)*0=z^&%wyl}HvIT?z^J46=E`V|2^;qXaRgfXjH`WM2 zCsYly1-uPWZ%;Xv>{|IVpu5^{GoVOWb%{13zc{-0M6KN5sEh8sHgcwf(fzUorU7e2 zGpH7-wHZa3G5f@xmuutR2dT9gwSj>p@eEuuz*rwq6vT3e9WFym-GdNQLl|OeL_>V< zs6)|lJS}5p@bvw(7w~kzOZCVs9QqRo1|#_9#1y>C1m5F>Hy>!a@GQ*YRv9J;&fu%= z#oYJ<$cyDI%9&T(Qa-mAZIvYClohWfLB;=s%^k<7Pm`CoVh)B7hRrVfQB043Qfu;R zs1a?Lv?E(3l^6}N_26CRrE*US(OD%2H<^@3kQZOG~J=5k96o_R(=^WIb^9!W%3bENL&Kp09>Mg4ff}2lZL0mohn~Z3e!V@ z=?>Ct3yfvFd1nacoo*S4VkAN~sq!y@z4q)8*`!NLD2rl+$s1&v#CqCkCfZAru0!BU zG+`E4kwpzCv^#)x;ir>$0cn0=h8JpqLFXr@CcjU+WH|8zDsFT>p`Iee7t?B_X8rS=nA`6%>_+EeVY|Awyt zGt%Uq;%?b7Op{#)q6E4ye7lb8B*){j{o8Bzhw28rT}hz<3(ITQ!@wkfG1a#u&7}Z* zo!Vze1S{WsJ-L!b3B$tPXRqA*l(bNl8=f{)_nWl*n}!X zA`?V{DTl&{%h2sv)b-7W5aWxTIxD4rPLp5c3I&JOdeD@Rc)>0&Oe6I${;Rn=DOfP{ zk7%LpX|s#3^Xs!YPfSwz?!jjM8J1;Q7-{&$4P`BmO1-dsH>68eMBt6eR4Zp4&?46Y2FgDZ#g97gSP;IO*LOkZQ0km_AWSmtH;{k> z59N!36Awf!v!5k>Fe~w`g9Ale&)amm zg5nyNhj2?T#84RdgPF3tR2spx?n%6u{`-F23k@LK`O>R#qugEc5SF_#5?7rX{ zT?KhEB9n9oA6EZ9P~Z+mI(7`YF}WLa{GSJW8rYyuLNKVgs7pzs?zI!~d;&IR>-?c} z5L`B)A1jj7k(D&;Ey{pU*rRk3Zp6j38?V*MU*n=h@MXz)8Mm~iU4D*`tJV^+d zkF!5R<`gOg#k#gMitj^UZ!0Y_uNK5D6de|V|5IO!Y6n|&F{F3}T1#x5aU0e9KuHiiWL)n4BpOKfS;-Oo1Gi)fSiOb?ckyz`<&P1F{y(CRMXMY?%?ZXV`5)Gpm0;OoGNdY~L!NAkN2| zE1!kpwb+fruL{y}$g&7MXe4o;R(ni2B_t^#jwezP$Dypgkl4o zz$UOl?-7b><=o1H6hiTW>BL7XS3a%s0;XSjEtnpd{1d<6KMcC>5oG=#rioWA0!lja zO3>J%=f10(haW~+M3m)!Mm`=lh7kCBeF*pJbqQG4v=8Bu17j8VWJ@r2OC97Rh%`x*p}##M5|w}BJC)kX<9wIhW1-xh15$CBN^q5Q-K zYDbhtC7ma#@IB@7X2$!n%e|4Pn?ptf%}K0RH!BDrXhs#kGMqH#@F7EV<6Asd;Bf%7 zntHCf*wK0b;ns}B!Q5Ieq?*;UhG8Fa$t^1IT4saCrJFEXhL6Tc0tb8Aj0-wxR)n=qJB60YVo;9OcAgN`c?YrEq52l`Xu(!G__<~a~Iiv9tRCzAw?{w{m`g1pDts> zEW(JvWRna21Y=^5DevJ_6YBNY-qzZ<$zVTBbd}hM!shZv-g(q+>R-qsk=I~v4~}^N zZ@Au4H-x>=;|`zT78~4?s+IptCbAw?qhvLlmpne6r{}JLH+MS#a~LUvF^y3IMqUo@ zxY#08`R(u-xKAnAqhF;~{)tRIure$ttpK2s4Lpl88TdHKnJ*d!gq@?S^RxzsnK!f#gJY|IJdR78p%c4#H8i{bSS zcKAE8`H#c5JNd!Sn0Cp`+UO`*lnE6`sAK|}J3;k6y(P!b#G8NmYLMxR9GjZHAmYgM z1?C1xFh`=_ow*C1*_JzT!9}ITT>NK-Nr_CbBHFK&pG}^M6+Yir5qTVbRSeC89c+HM$~S36Wx|Y9;4U@<%*H78`Wf>U`0a2+pCr5C+SDl6&6~I2@KTYu3suZP zofOpW#YRh9~MA5))&mXWEC#IMKHD7P)# z0%{YUmbpO2Y0#MHG)d+I11CUi;N$`L0ecQsZQ;1FTT5G1b~7&7O_kkL*-e$*6kS)M zCo16@(M5XAH}6LVdbCcoM1#|Ddxz%diq5E?B!$LIk#sUiiaQP}?C7_Y`P5faeKplr zv#cUbar zFpngek|ca7H&&=SC<6_ntDMID3Z}FJ3Sb7Rg3c~mewyIML;zoW1k@&=oUc<f~rsx6s|GIJAf;8d8D%aH>$^65*{T zI6r|wuO{qBMdUM?vEt}3-(20)G(A~5+nJ^lSD?U52ODZSv_f-4t5iVKka(pSI8#a#Iu!6C9P@iRCETfP$O!o9o% zg?>XEqreAUPOfp$x^0KBizJx}yOZ%5YM&D8O1ZN1vWC&mfL+MYpel(A5V`_En9jHl zs$eVj(Ey00D_x5TQOce#6fFWpFH>b*Qg)Eq6b;?D%Cc*_qS$!w%EH#N5D8&peM7a#hitL_~M?lUj#~!dqRv^h&hjRKv{ z+Dj;_+zguV5c!U0z3c=!YN`TyC{T^fW~tU%JWKk?Pyca}!XxdS_C*T_iIxLcSgP!6 z?*u?Vx)BxN{JWdpWxMR7LD#)P9ep2dlQSnx#*J-epxJ_E#jb#0XdN*KA>pho2!HO7u_!SaUH6a16;d zW&wE+I!vF+*pZLiGO-aha+jjUB!XH$mm`F9gd4h+Uwb<=v{xa13YHQQJ#UHAu9H?` zi9@r68V7Bs2?VTVWu0+);!+|~emNn=3a`NnxP!+wJy5C!sg8O~n?MfHp_8;HB=_u1 zoQSuSzRRbFyH&{Yjl&;jY?Q8yABR*Ak5StMkHqK9YKg0;BjyY4;oyj;qf`;N^3e9 z+&+hREJcE&PgrNfKL!N*{M*2g@|aM&W>2v>Mr0N5wTe=*+tbGYDGV%hwtdLc5ctEY zCgB^}xO!x>-`Gs1QCzyI3M6y6bh>PV(IR^Svw+Ko@5ls21zn}mmIm8H@HzR8PZ28N zc>M1?pC;!>DUbK;vso~PM2QAWb?SruQnC!h3Kw7GbYwW)F>@j10J3970+f48qyn*4 z?|@b$c*f`hCbrX~JV@uJb;Es1=;NeozlqV4xP=MUbYU%_7JG=DYnN{V%6>=5 zj}trtq1DW+`>^9J+}u1PV^l9O5wglAphGZJ555H)^$Kw2#Mh#n6fdoIIA`I7oD?RY z6v|YZS=|AI7s1FY4zd;h8Cl07-L82Gfm>&Z!G8Dx-4wSqof8FBwQzEh(3#d`@5 zC@I{PFr~!T$`?5`*s}p#=e4Cx<*IaY!N8;1eug=%vhfO$c7uUPCAxs4%^mmyJ_PY` z8@+SN_H=+WI++u@d&<@i{m!Z1o-WhA=RPA_EQH!sq47e}rE7|%fMz6LuNHM`{N z;zgE4ZsXBfMK@>F0N10$WexbS7$0I?r(oZQaIyjW%35dW6=sO9_(`gWutGr%d0HrNZ~>wb_q*{$XS=uq~H%-2FbAX9@};#aKr z*{S~?X!z6XuXYNs{*nXLf3pku;se#s$O%G>eAd5BW_owk{|bU@;yunzo_$*46U-#o zq+Z&fkC~T&7A7*(L|)YUBmk17u@#b?b0dz^IP7uz$kt<%Jrs7hiC%bd^uj(kV`Xy3 zfX6>Q_Hqq=GE@CR+ybm;D*Lr>UU>ZUNZm&xJk*tSd>?x}F|($Mq7YpBW0k`cCU ziXwkP#>A&U3+?sRk?U3az4tDS-X8)v{Q0XIy%#rnC;9yO-)&UiBaPmBHF|H`=>22h z<3slhPR%Loc^d6|eTT2H!tzq-I~=o?`b^N?k!e0M!H7QqAa>0L%E5e0Om)7 z+kha)Ip%I`YyHQt(|yZ~im9M%I-leSMgC&sXQ0?5CVwcg4Y^k(IjxEFSwxe=`K`=(D#OtWPl2YPDowqZZ z-%l%FiYh(1vsbqg>rPl0IJTn?2xm=4uo*SALCUVQciy0yxTk@jl$0I5o)UI>EoJOT zPV%;tyo}-Jj=RZ^V|5Ny#(to@{6mW(ZQ`QX53RI`^NPw>MuzsxjNFCP@I@uYw!}T@ z{TtycF71ln&MxZ&1Wb9vf!8x)E5N252cZ+v1e_#fRX82B%>oHf`!2f~=Ze_Ys26iZ z>>;rhMIrZ%0#LOQ&AJ{d(Lvw{|4Ov-U5Hp%Vx(W+{*sko@kT)r`?7n%;PD^ewj=N$ zGe!97G&y4=akr+ACgvA`n-Xk;J5PAyEjOKmOZZBT+GY3VxJL7~ZvqGU&Yho0e(r!( z{3;09pL_;U1zuhvPvSlq#{$5)G5d1H_mY-~Jm*|N6fkB?lSFlBXFS0ZW$eQT1JPow zv^H-=#W)Hax+T}GB0Fa>NDyI2?0WsUTDa?-nWBP^qby6`E%sd>$iJcrF`1T{Q!b*HbHXPbrfi6ow zw8H?v-MF~N^~|%?-MBcfySh1$O+T;uaQIt#fhbU6vxQ1=b{EwPLOAA-fK5EfixqZO z^>jKIzd`F3=#k#j$}hkX2dqn3z>(*1qwwzZbCoO#E7V68d=gnF2XrB*p@PO*>d|=v zaiepXiyZ`U?IfcV%E7K2&|NJDbWj5nVGeN4=VrliMb78sfC5zPhSRwLpklzhGRHfi ze3=~{|73FjGU(C)97#G0$e|aQ<$~j5tmqAC&1l9J|{xZ7i zvqp0RiGTK%@5r}Mi|v9yWVe|J28zy6!s?*`bF7G_YF7(+2NsrdxI4lo_)9JR93B`M z2|wN_r8$Hg&cOW4S}@U9!B?;? zscDr>QM-@U{hDQMP)iB)NheIlj_C=Ccxlm?t=wk;&=(kf?SI~`aEQXceYS_^Yhq&Z&ph9zf_FCqJTR z#H7;=Z%~5f%a5FN*zL&Grpm4kYruz{S;|z|O_kl0?1`?d#Pf%h=GgPF&Eq8c(ifQ- z>B>%C>7aWGSyk=iA^^9itRaoWFe7M6Qer4F^Nayj064W_=72R@X_RNP%svxLBKLZHOF zxB;#(xUzdmiE$-#t2}7&pifkESIPjx^3`R({E4uIWN@?v>R1c}U|osR@F(qfVak5V zcb&jWBj4R5pGg7<%l7ABdr1HC&Z{lHzLuft!%&1Exf8V->0d>oX`mn00QE5z9(LfUaeaZcm%v+4_F1cy7ZMK4zVM1m4pId zP^O&yZ!`--@%YcvCF*(V{$j?z{gv?q?sy1O=`Y0-=&LfRcmfwWFaCG}CnF8BWTSWj zCot9QbV>oH?tS73(m}C*VA*r4cHPxOr()BrUWUH+!~`n?1ES?hJ8d zP2ZeW860TC=JV|nK=mM;h(z_j%%1Tfumj1?UsTey%A=tW?;;Efht4Efd?|zkP92m(^1#~F){@r%#X3cLsO-XPDkKoWB?_clD$$TFIFX2pW&h2 zF})-;OR16vr%HBKC8xM0eanzG;T$kbs?RvbkJPemn{__7{H(Tyc@r;_qO~%-TTiJd^|zEBz+@ z#RCQJ4Zll!u##h_V4fBS!j7-_pvvJRVa+C<;^G-T1)qS^4B&)aORe8CeCSYnLYM%OTxlbJbDIE9^R@rRpZf`sTuQ;ga-NY-jLR<;Bn!{S z3mAoJziZKk8l-w^KScXSo0UKJP;^=1Xe20k)*(gEO8GUX`*WYP(4$wnKljXB)(&Yc zTdt@3EpFj8E0_7Ay`HlYE zUD6=>{JH0KX1f{j>o@pwe+C73s+B%}?yx|6h|s13Nl!j&+%Jv%xveyKK7a0x0*@l~ zZ}jKxkp|J{&%NSgw%5jX<~R9sC+GQF?DOY-P~c4>y#4xfx5OohcCL)nG=J_3U?1n3 z!p|nCIAX1G3g3@E_k6BR>HgduWYUEb^8Wp~e|}e$LKdG(a$|q)Rg&wM{JDz-gGT<` z|8R;n?a#fa7uzo*FU_C(0$9~G_UGQP*g+L%?4Cb&VG92=KWUssyZ+oqr;u;bpZg&P zF2K58;+q{>`Ur>74PW_GmIbLSKEf$?`Bbhc{#=bcxh1ZG^5h=okPbfQo+tMXYzyj( z8n8-0Jaj#|1KcaP25f4AwC}A2VIc2azXZF$Sm6ns+?6!lle-RMg+=M^a3z?Q-VU!K z&A0DM?%$JpGAj1#hxY5gZFW@iKa{wY_IO8tPWRu|2XpQ58_8_x9iZ7a+=Nw6Fj6H|Q46f4iNBh~vM#V2do!JzaAn|Lt0tT7Mt^?Tw_5 zsF;5r|Lq$ub^N!Rp*gC@_VM2?f@@`RAOG#6XRDrSwy2T1bU*&vV%Go-+z`kfu)~D@ z)EeH$)u9>_`-+S*ZW1}(m@Znu|H5~Bv5vbNdm1oIkS)Jlk1IwJNZ~2kg;txNIfLkO z(W8~m%5l3Cev*F_`CmC+6s*?Dn_+p0*J|avp<$7Y&@Ow~NbY|lYiR@F*-DIpFZYZn zUXx7T?_7FxWeUmkP1Ipqu;G6#7b?saj2tv^&}_LZ4+&M~e) z;auqF^M}F`yVri3hd*iJ#Aeytia(U(7&m|f+@C+xVkfs1k{!kDLG5lq&#B8oK zsuKSh{!r`jjaDt5Kh$$0l%^2=P`feX$VS@phq94Er95P`k;v!zLutw%>Ro&lf2d0- z-&@_^C~^IvI>2bu=MQx~GtwVw5+0(n){!l6s)83~K>hl)tj0A~kJ-dXEB~PdsWY3c zf$G|R2LUU=1L}2`-4;t8IFPfdv)O*{Xzn$7fF@K*_Pfi=PW0!%YJ)(bG;#c){-DJR zh_|UaXUqsxyZ1b8+_UJs=&TLIG5n|W-eEgjbJ0QwY5*9INSa?HoFY(_QR%Mn#K!Zf z$}Ru^U=xLDs%!13l^;bAKA$Qb032m~OF=t)wBt|pbF87QRz4M|3Ein0Ll1Wl8cfW< z4~{j^5pSQ3&B?^29;6TI;B0@T7EbI#0sb3 zMIimQyiH4G>BRfH(^8p_iIw=^ z`0%0G==+6Taw7{6=X`jgVFG}c1}yefwWdUFIY}THpF9o1Fe|IgeHBws*s73 z@akKLF-DWmU@Q41Do$LBMAUVfSJ$w#x}Kp0A8@n>Nkx2%6=r&wuT0B)nPgVJh-Wc> zaVkMI(w*e&mOw0l!+8*5ega1)X^4&WWBI)AB|)F*6v=XkJBj}GYk)R39ZKRja(1ln zio;zho|1;_-xcE%BilfaB&b&aYK_+#o?r^}V{PqKY`4N8)l<>cw zf_J}t8!p~}G*Btla`d?yw;F?{$GDC7`@p&Q0*^7*>F%*SOb2I!yzJNsL9&=~>ww`z zpToFv+{&ewPIq!|PRiF#UhQMT^tH1AIpbIP+VL7`F1E_oZqE%VU%Lybdz_7N1Yf(h z+BkX`DSx}?PQwb|`r8qEn2%&#`)4&Zyi-Pa{)L*CDy!vulYQJ(eBO_j)<0c2tMfp~ zRpr4+odIj*)7@N$A{XT=*J*4844&MUAJ9$iC~0!aP3~p(MkZY3Jmskz(wCElu7vQM zh!O|%*J~wU;jecuh$!A5T;H7u{VN3Egn4=58Ze}@j>tqm87mgkX^gGX{r-1z_aWvq zr@H{w{!qT|hnVNPWLkUu0f^bw&9xA@5}b1!eB(TNYYn8Lvpy#oe!-t|MswB2_8kYR zt;)$I{*;$9r{_<(5IkiUVQl$jsR64oW>fx@m*#LGxQgQv{@-{(dD;!l0!@5pf@jIV z^_->5S1BYvfTkplVf#FP!W*t2&VEik&czSJ4a?X45SKDFS=t^ofDij|AHCAeH5j=> z1W5BIJW-@2fBi@J>i_O?f!wtF>gQZSS^u8v4p2X>;v|=iT#1jcqB-?*y#50O=M>ZC zGG_8)G0-VS7Q6F6SiIrFA8{ZoM!LCfAQmCPqC{penKzDc@F?Gh8jyK2Bq?fTU491I+^Zal&NoD06N7#Wh_NP1=`it})c+)|ZV7Cfgnskx${3*k3)3(b_ zx5>=nPbu0B@(t}F6LqS+o_y2;eS`LU?~KUnd&N%B|4M%HeeDHczSq|2uK`jr1-WPX z*YRANQ(yJ;*Td3Z*QVF2%nLo72c>^~C%vo$7f4lfUi#OX^j8|_`>=W~{gsE5zON(G zU(e;Mvajla!B2Vc%hw$HD!DP^G^uSCi!fWWs2 z_?C7akQf5Y{qn{E{WD(@p~64n{r;H`fE)L(3i13i4=Xj=NpHWrZrJpas3HaGIm9DK0jpE(Qh3Kl5cU$8Yt|e1Y=>dhQbR zr%!H8HtnBT@GQ10jr}tN#$M;r1NV}bF%(tTQGogY&L{mQm`H*F>Y($}I z#ayZz{h)27=7M@rd>jI$d<_iA`#=Xf$$whWdqfZybOvw-k0ECU0To{t8rsDn>kjDh zc^?H%4e8G*YIS=$_{YhmThz=Zy*Q*J84)hq{%9%{v&rGxsF-!IqpPFB5IG91m&4{yc_&Bbg$!)Lwhh(zN>C z%A#cIIDFROMGe~FHGt@;xHfW4VBqc_zzKmSl_j@&^h`nyr2p`;!Fn9A_;W2kqqImJn2_ba%$8?!Z^ z!k4-k(thz7x?7AIU`L;#_9LsHMf&BBAkZ&g{dgt{HNN^$H+5J573IKDkhn-#(fBl3 zg^O(@R`b#Lm)rn}iwm2+1M(tt4Up;y_(1aaxdU>0b0WK+J0R!rqwnItb3h&-@JA#A zfxeFWTk0xEUtSy+^kG9yc*DuzsNAC%m_h(@4KtR+i$h< zxkSs7+b$)x0 z&ph+&GxH25ng)&E1D0l)LBq_y*wYGf^XBjDKy+^nfqYj=$OsQJnSMxHjg$jayr#uR z_mUXCQBPqZ8wWO5yQZLKQ8vxlsp9-pPD%5o`TndU5tZ9kx=FWozVlA*Ct z*41${7uN0J-j(K-JA-#_I#O}oXXT#|b`QAa{=|Z(H=_q$Y#2Ep)mOCxu#=ZUkCsSG zB}Fyaaf?kyII_$g4Ti%U>@}}0Gh2xuP)=X|v9JIqF!c8-r*G&Z3e=9&6--l}oG-C* ze#UCBW!}FXLB9?-H1Ft!i?j7!>{xGk7F=_$>ghC1P_HUmueD=68k!rq|ofdqCpZ>ArxRh$?LCm+pP zcPqso$x);3z)W-H3c7c?{m8sw7F++;61~|DGDv+cZ?U;@My7mzN;uy-ldk+n@J#C0 zyvXSPw^e3eu6 zNPTWzUjkk=sn+|Q}}lue$(`#?k1$UZ%qEg8vkkg!-DF0V#8cgqF819^+E9bAgA z?H0(r1QzYO{Cot?+({80pEzd0PRV<0LYLAl_ z2LAP;caeS3lqoR{Kpl)0J^^pat@mti>98Flse1yBS%1SO`aQg3zrUtc`nC3@1%yLk z;c%R!PYyaHLX&s*%)Ae~x@$MyCpXpAa%<$|4DtSsLp+cd8d14N^5mA=tnhzI^P{v; zcQccqRgd;!Nqdj=oGt0mhv=+w8uU1iouFQ6Ma&o1Zvq9;j&O14IUn^H#CkC;gZh67 z(B`@Qq7`?G)M9%zRQ$P#P9m+kAQ$&X)EUi7lA6^&s18e%&Gt`8)IX)9KH1VYNb#)p z($f(fmwnlXUaiiEGW9cgpK&BUP%r)r;ley{6T)MWUNl#F**c4XIj;_OBY6DSOjLRP zSNXDR`Sl&kmjvY-RQ_w%zFD7v>6VV=_f?YtOg~kfon0S~Wa}K=u}&q;3Z@inks9Fo zXvvmmn@j!}Tp}5piN(xNog-bHk=Z&N@5!$-pLn49XjSEYFsQck|14apSP; zbcE_?V*+(nt?Luchix=y^|7%|5g_=@kFSK1ko4 zD|*j?hP-f*I%wmN4s9Iho|{5&_Tbq%)sl{CdQte}O`hC&Ejyq#2;ySf0lMMyYwe(j z!?-~%=Q*{TzS07r8DT&bgn5gFIV!M%>Bxn*e}`v#GCG@JEYQg~=Zv7b@o*#fB za=#aL_^unSbH8sv{~Mo=4c2u_%;8^(Smu_XflpAjHuOm7Z`%{JO1ql8<9yNB_PsvM<#h$hrnd~;aF}esB|?RFj{w1B0Ic82&^Ahd-x8p& zDJ!dspZiPzTv*a>%`+F30ZrM0;N&1z6%}iJRC5rp*ZbXsA{?uF|B-HrW0~&Pi1><2 zv!zGU5u#YodaZ4d78lr_p)uiKAI=};jqobgM6Nns^W;CJF`D1+4*tk|pkjgZO2!DD zv{du{&FaOu&r;+=D(_?nY{zpAXrc)=xt_Z>a2Hz9;+j@QGN7>7j zCyG~muTIR6|=Q zu(mb#C}Y*B9@y%Zi|!(x*BJt$r51l!ja0>p&rK3LkbH_f_gZ;2a5AJ zddys!7rAD4D_LyR%UlFOq_)wE=E|+IHGYv_qfSjGXB?(JYEvvxJ5R;YRK% zWlHZw>GbdOm!C8(Iq;-JQyuO1b=AkXBSE^>;2XqX<1}$8cRHGT=^Rlvo)L4p8YXa| zt@>mww9Fx)$MKCgWze5f%owJf2a^+~m+u_)6Sa~QSg=tp6x+>9 z7LQ9=Tq2fhr&FzeER2U#=LMYJeRZFL_>O#DtIx?xiC>^H5=G{p()G=A z%g|n6WF21}Mz+afWC3VcZ3c-9p3a%{^l}HK^j%K>#hvzl6>pgtzxbjK{U4_Ov2FgG z$c5v)&fw6@tTqoY2kA#Ufg{A3)xWHV+G|AX6E0(!GS#jsHK%9-6HDq7^8n?ue~J9o zf(fXuNQ~eWoo~!uK$6|_`5+NIN1f&;4ppFSaUj#c8HX>Dq`ZVkWT_R{x+{&jmP8A| ze-<8hi~CUkfj}R|9bB<0QiH};DraR@5jxoG=P&IRW=ZkU4X)p?G3f1>C&Or>@i z?_Jy{d^IQR%Kpu6$PX=%AZ?TGQ}v*U5^vA$;Smh03Xg=hqRG8Tg<>LCD(>mEx37_S zc*@;xc;9B6X_;v*oC@-k)XD#e#+z8L<2ubt*GCJNa)*bi`SF?18v)X7yykh}iC@R8 z_YxyZ%Hr|~DqiODR{_&p*`MYZ*uf~= z*J-_o$4EtyO1{sL{^vh<&x z2FY^rbivc4-$a3uJJj6zWy3x6iB-=fs82BAQQcd|wr-o(!RLcNYNkEb&GM!>{_5`t zd@qj;lN@Ti^1BVj@Q*h$oW1&rXCqf$NLS&!CZ0|0VWF904nxq1{|>kYJ>?Ha)5l-( z_AIjW;SYV*8eyXB-DolW7cW`+l9$j5*;=pv>*S~%;BwS%h;Ng@S*qPO{ZeW+e`_Fs z+T`&hdE`o>lh#jqQ#8_Xl;%x~+58cvAN&vb=jhhX`DZBa|5x~DKcV_Z^3O_u{`dT| zvlP>RkAG5Vr5yg5!{dL#KXaP@clhU0aQD6ZvmII?!#_I!rMZWHei;93i8dDhtRP z9CxaAe$+qTq<0!S)vH8|HC@)Vwe6Bx*6>T6CDz&&JGeg4-r%2E?)ekvH~7DjZ~0+E z1(D8lePjf=m)|lwBe`1J;?LT<)Qne&2%2>HLo`x`AIpcQt6IoRLf*KqBdt5wp5yZ+ z!?bM1=K;$3)Bh81GEO!XQ7UtRdhx(TIg%FmCTrQK>9X#L`GENLR6C9Vw5CfqE6$kC z?IO16+L_wr1hj)a|0EU+&qLOeAon9LGU638!S)zwT}D&UgsC0)FR%Y%2XN%-XL)JLKQf;p4r^`Du$ebZY{fX1y)yFifyD&|YLswdM^aUgY5Q^@)ik z(&6TO$OJzaZ?3k0>-fBvKZ+*zU)YfB`(8uEhZp`Vn)qz&)MvDB-i)9mR;5nn%82`@ zArbFa-Mn&GJ+@Ku3KgkOjN;DO+Vc8jO<#JDF=&5`!d$5x>?NnD&>_jLd~2xU)c|nj zY(STaN1Fc>v~qpLdlzn1?;nH$E-@!xZeNUFZC3CLsxaq>!obuZ6~&S?Lsg``Rs>qW zUrV{>v7q#@p!DusU>2Y)Yfo}!dz9{4l`yG3#-dRe3~gJiFpIS0ueqH2c#zludHY!i zHif($L7t_fXA~JX-6-4A^?bGz-F;C_b3S(`v_A=t=6ZvneLc>#K_%o#4w)d`I82l+h_sq!F3yn;O3GGzly)ZA&IFX39op)lBCpqSC6YFlxbl&T-ao1ojXChzy(SUF`*7z`w1dNH- zNP!sMZrxvZq8DBibu@pZaF8Hc#O`wL&FxDMu_D{N9SqIe!C+&$foM#@Fw#>p_BcF` z09+W{j~z{(--U~83z?|{bQk)mQV1`nV7r&16>B3`E*390bA!3ufUkLTmYYckzS-{Wi z{Io7;@OO{2%!L*kk~i3eETnHkGS-))=~du#vArL=E6gf?YIUUbSP^Wq?wfyw`{wCK z7g$Ft)=zl2-uH0lxG!4UK^pw?OB?)hL}}~{l+9W6N)MOyMW=iK6vKJuHbAunSXp?& z{<>%SJ6UW(f3T|3+3y?mPvd6r598vNTsJNIDYk+RzkHVt>F6!~I*&H&oxOuxhR~v! z&yFwK-*LJ9b?C$Mw{GwUL@PdxT|pN&sf$R#E zZ2R-oE#vVj-U5I5V|bdm4}HkUHN;FI%YSNntNchjE&Rw)7##So7dle2ekAtrJ@}CL zkqt9br&1~O?CizF@7Mc1BVO_nH+z2wX0HP_BP|aG_3Z33O_&=qWzO|q2KR64QX8+1 zj|*pFc?v0*xy996-?|`jjn;!~cm+TA72>J*xHD5*>81bkquz1YX-Ird@Q}3cOY`v( z-_5PbE{iWu?Ly0LTYc+-#Q61-eEFGXGA*W?d~bd7f(^VsfBhsjR$!UZ+1Q}7^b_G? zEThl>EFEi;Y5x!LZx3+(?dteJ7XL#UXU0EBDaY8;d1$|eHxi3l{}-xDT??fzElODa<^Gv_^iFGk zezVq|GVh<(ga3s4JmwUH;rY=dxw!r7o9vh7Dg250zIF#|=QXx{)Nh_M-vM5u!e~~+X`C}~?Z6GVMrIF<)zy*Tl|b}xZ2djcMTS{o zR=O=%$146Cji`weRJ!^^TB>f;DsU5k6v$_Kz)M#C>9fKD^9CGP-Conz`iBjPz4{(J zuWSDTyS-|Y_Sz)WvP>c3tZQrv8_Xcgi;_c=(On^zu05g^Z5JKk^`BoqYk3iwu3t7S zi|Qk_FGQ1lXGM#4iB^0VxiVs9cRS|DI&ann%p=hBfPhQ(vUUuUZY_qJHBn+y-LFJ! zcV2yD_~+4NY(Sn7G%s?Mp$taQ7yKzmjGC*i#iiz$z>e{GmuOc^Rj~J;55Bk#;N_GB zZ7!f;`3(0O3cta+%{7vGI{Rg%*#bx~j?9f0$iNzc4QFkjXktu10N;Cu-PY=8qYm zXwyI$p!LakS-ni0`b5{hT4}XK_<<7$wV2glfv0jkF~*JT=wP&iLp$11qx@T399~JLGKN0~|=)Jls4-xfvh)x_SB3f-)HDQ$Gq#_yBEY9>4 z!f_XEBP*!?JcH#9`5!eP>O;a5%S;B*-@#Gc7~B7=5VPcw@8varx%q_4@Q(h}ka(_v zO*P4$^FljvP5NNTFTAjydw%b(D9cU8tIEaCc6}u=k~Nk#Oy@T4tJcekS@9>m#GwPc z1OOyXsEXpn1%qs|wOSWkK0Gs@dmsc!sHT5st>-BQIe_-f$d;M9->zarr@3hpL z?Ae|giQvyPai47>C(l&+Y2mZpzo4YPc@|qVuT;I%_S6x@{vRPfN5iN8k^I~Si6g)8 zKbD^_ioubeqki?jC_g=bKz&>PmhVosImwntvn) zwi&O#OU!o{{=X?duhjT9B|od#5o!K3P8bN~=j$+l*SwMZeCd~={2XC+=!V2xtqzsfL>{dxkrDmv9I4vnta$9ncAkY;^>PsE z_LqT=E?#Ngu>yx%tne1up?1d$7}mOotvs`cVV$zudGDOEoGh!0wcKppf=JRY+LdR! zE7Ue+9ywD4v&7tfe*VUq`5XCLDBmCC4;%@_Zpt6{@cB*q1KWwxJMjlTwI)H1KX4a~ z{9AwEhLtc+J924L{y=?#cp_$yH7VFQHF?z<^lS_Mvdcc{?!1ld66tSGFhu%uk!$}^ zQzQKwr$zd+-qrt{wn+c@!bty#OLMN}vUePEd@MO)N6c2jJ*D-{OV_m9Y=-5uAMKCX z?=GxNp4fNW_SU}W*8zO+lJ4HD<`33*$z-`SwOm4*UbcDzrwy0bjg!e6chaXZYrMku z3Jd}97wIiA^VMT$&d zZaWGa@|>kGNMmOSPiad=yYw)`C8BKCKH5D1=^p*mZ0u>Zp4ZjK-muQ{bA+>t3edB zC}Gpp#@}zJQ_lu9vfnYknw*?5`gh7fxOYH=pMPD4TH5H^5}>X!4r%}W6`TAbtQJhS^p^< zpFgsksp|bH3*Q_%jnvMb_z^%P+ka*Q1>aL1#u3%+t9^&TRgF?YN|l?`~QCb z?C+ap>0MqH9s|^#oK#{y8}r=;%O`fX)e^HGTqS|)pN;0shd)EV4~c%+UufIQ&{!V5 zYP^~9mfn-aW&ftU+rs&bq8H{ec*%xr$*VBO9OOE@xlIE=EU>!P`>fN%hl6(EojFW0 zSG&cQm}XmXrFow1%NxO;Y+Q=k=?C%IxlIl#Moexzy-XdkLPEGKTP-n#mQ|LR<17$y zy4RtCrIHgSPE=cE8tHAL@#l``uVZt^bFL&;vbcNhcn&$$j_1N>7|-PlA{fuZw&F_j z^)J;!hTeo<>7#0`y>W02UuE)lY-pV{VK}Si$;*q)Spv=OB8ary07`2T(wXkXadBiH5D4(gH|^Uig53`9*3RAV3K#Ek{QK? zC~)+10A^QwF#UATPe3NopH4i2p3|=usuj%Zk!J4dSug!cVakYloK>Az*^CFolvJMG)A zHEaxWskWvIe3pg!@bO^MiD$yQNs~V|D+OdSUqc1ms#m9Nbj1859~&=y^%y* z8q;T{&=lL;>Tfsi)fMlY5V@|+g$G&ZJz*yDr67AhBrsHXC6t)6vApcCo1IZ4; z|6%!}O_u*OvQ_svq5KjP1UrkG4)0M2U~I>yN*i zF-h5p*HL`n40n(}=4RJYFu5D)tI)m`XaaGQ;Q0sn6O5_fsI?sa7e2pth|d4BzMtaM zIruN$BtEOAWadjcAmh+r-%c5UWZ4EU(n&AO;T{y}(Y&lMF{^p$cRdz1zh5||j&~z^ z=yCp(5j`X^GW7i)w8wFc(y&dBt-fAjG^*wpD1QWhbqHfL+k}pR3r6s_j=!VzyF9P| zaQt$XQ5>Dqg-scerKfPd%rK`>aPD-T*7}p+Mk{SO@d4Yd^)H{#Xq~8H=-RuFA!3x6 zS6lIMO+rcIwW(LC@2TUZa3WI*DOdfBWL2bfAFxP4^_H$zbP?<8L*nZk*4?fVL<{VOut!VA&=eX%#L~g;boXy)nSEV!ca-KZg<=+#A4J z9ZN*>+#VndC-$=($tRT2SwW45gBsVWO_%k4ntc_!Od-X&43K~$XS2-X`dJZg<0N9F zg+=!bUPbNvNDEu&IXQC%yFO2nveW2KwhfTPJ<@VIz*Rp3779}PP>{(A>;bu@@%iTT zQAl_{KA%i@skdERR1_OoE_gU{%F)ci=Ba|A(oC~_xY+=1Fj{LFtOaU zaovSbrXBLUga{@MFlU25y`0WVMUc}+TkDv~G)wtO3s`UQC&KYsGbnW!l^nj|o9^&U zHy}z4=B?wG*d)g*u?gZ6HkH{~U2LvC%FgOyW>x$WuN7@x!pp?$fo(MvA4OU}XWD{^ zxOTMV6&hY*37`oGiFzjpZU76eP&oa zcGEa^D)F_hac+I=E(c~?3vJKOa_lAIf?bKq%^4N=@UkfJE~nCh2IV|k^ZK!}M+Ti| z?{ViocX$c^&bj2yukXrWG}ygXQ!zPX67?0B$Z^ESkFxcDFSf} z$Ik6r5&dZi00}Qa7294zi0$kXO`6lyOYF!BcHta5XyNOr zV%W~diyhO?=fry?u7`Gul@0A4?+KRts(#MS1SJ9e4TJugC-p0c^%|wk8sdk?4#V=K zDCyO}rT)v;ca$NAWUpq^ZD=9;1lp`|=lI|F5K&;YTKycvKO31&*_*&4<*H%J+}ucI zqY%+zg4oaGPFx<+|Z&}UmQV< zaEAwZ5KUH;ctzdWu^qWdAFN&xe-tk#Z_W5caLX3U_{E#~mMd3t~W(UQ5Afc z&kHnI$6wy$VL&-a%~}0w=c7xkl>WER>z`5x-tPJRj$S~Mv&O$gzrDx1eix2^A?UZ< zqhCzL1`Z%XbChW?w!C@|`8~hC9Jt_^b=?1EhPm+va-g`E#<``&xpgqk2|dA4M!x5b zIYPG@^D}RSV`hFwmsoOb`l?Ip)TXbBVmmZ_m4jz->c;)%j`I&RMxzTa>SUb1N22A8 z^RrIr!+G8%M*0*&{fX$q0)>?m?ib?~JjAkt?zqmmmY%d~lnsE6i|wa?IvqWT`_)EBk38E2jhttRGZ^PHVx>gGJM2qz!s60H z$=A#Z6l_wu_vMO^sC0GJ|xb6;*D9$!p_h&1(6#=ezL+Q zM;_(i2N8gW-lh*v}<00 z9QkQsNlYjU{ny~RJo{`d^&ETITIxB^q5VuaI=H3;>^P*2Gw&+Nwa(;`HF&jI@(53U zv3ZcQ0REs^{9%6Z3rHB|v)P;Iag^iStvVXPi|Lsc-?|smJiqZ4uVQiRa5mchj@s;7 zoOn&_SCV5Mhqbwnp88}E=9m=4;%N-ATNG+3HaFHgrB!(xO*hXS7e+8Lho91KJk2C( zXY_a-pMH|_UY^VJW)e^oitu7Sr~j1G4_Oa_e$qDqP!9oQ_X*d`44UeqUBdhFK#1=e zQ%yT5t%K%nEq@}Xqw<`N{+PSGIFsh@dmwCn-@N9ROVg|QWrxuG>w0q0tRvq5Y3>2Cr>p$RvriC5iaJ~O;rivUGQ$ko>6_bK4mp!*Vwt^cX4yQePEIG zVs9-xxWpV$2cZ1@3Xr$X69foEY_Tc-QJ2X zM>_v{Jx)n#bX14pn;47rLt}qqX~k?!`Sf30w5B6`TH4YAiG{IS>=1Ozh@stMrv;X5 zW_@Z)iLvCMB`>&jiaYBzvSWwRwXD%n_G!H+e=n) zCTSLv@iIEI_>;$Iio}%^H?MI=05VL!b6W?`R|U;m91GU_z#urj|M@~2DHsAZ1j|+R z9LkbWVcuX^`nzEn%{c@hbaI`A+8Q_TiO5}*+_gb7HYc49$M5F5b?wDlnUn)6SRk{D zV;W*+(tqjzIt_r-)P3N#gY!}sp!vKkJRO{u8N(eM|AGiL$Qz@rL} zbdR4k@NLj@RJ}j6ua3+mX2@M?x_b)$e#3GVH#+JCJDB{W-m!?)4CZ7On;PCSQC2FL0jGn zyS(iz91-C560VG77Tn6JWOJnN=P1gQLHk@!n=BLqRAzUPWp&UaBg*g1pWf-;0W*xX;et@i>)VaWH^~ zgd}Gdle4U*VtCKkR@OGQM&f7A4OckU7l z@~OQlSna5CVmw%dsrTcky0x(y5!A1Si!n*T!^xa(md>!}kB};if6l)3vUCrpmp#rD z`>f))_xAj6KkD_XPi)^eNW$GDA+1H^)Jo`40tpuE2|^@*dU;x7taAAsnWz`6N=U3r zyl&pK$EOsK^oA7g^>>7Lq;`!x|KTKt*1kIEce~G0dwpPG;<(S5UF{J!+lF|T`Zlp> zxQg4MKJ@a>%%b2otQZ5#D`s+4APEp+NPc%nr&4I7Wg^Y;y9 z!?m`7T$m20f$W&9ePQW$bbaEDAeDlMn4K>QAaO9r^LO-yoFoBqRA66JH?Qv!J3cEw zhSZ36I5`tvQ7zvyeo_shM9D1{{R=v+n0H|V4>d~Eg=jf&zOU5I%c22P!iAhnLe26HdZ zYU6@h_8&O0#yNc}O>+I=(++|>oHP=B$R{Slijzy-Xf0#EW*lNPLD2{UAE!QqAu`|X zejMbL?If^_oH00}WN7zDs}AC!A>)D4cb8H3Mb&F`?^KGPNYC*x*&B)(&pMN!aV`5Z z2G;(x+rYBDqP86u{&rlUR#uwVxvns<46`#5$dy6&%1;F!cR|1DHx-LMm*EA_1p0cV zxlnq9`%mULv#Bd^W%PAmHchJ*Ly@oHO?vB8VQ)FaNrw@Z^_G~AhX)GVPR&ZQx8S6O z*Lk1CpT(KgI$N8+GI%#DiUfr8XY-%Cpgz%z$*b;x7_=Qz=>4Fp&>KIX-mP%g2W}33 zowS@hSEVh(AS7347ZE_t3DpWkdX!6tM-) z8+yLB*6_8ILrN#p2#HVyh?hJV3F4Bg%0x~CZ`oyD@kXRomjMg0$)Pwk72Ml2C(@Fl zLI0?JHm4+8TrMnUFN1k!Fmp&SKur#@yVTe&L3W|5c&Uy#IqCOac}Jgu^eutE^ps$i zt$r73ASgwdIh3&{HvQqbU6?MYxd|I}5^33vaFz^@mT&M8^G10IE&Z@j-l?jL@-L8? z8)bZQAm;+Jv0i(l?da;Y*T{wc`B|F!99fNg(h*H@%p+A$sw+uST3MV86>DObFmr`~ zLty3sI}LvCw{P!LKst8tYw=OfMj288Sfp2K?wjY4OkqtN1V3f%R(#8!Fi}F9S@H{u zF+2G#SFC8v<(?%^AitU@meMVKY%596vGMI7@lWKMz4+$&GXQjhdA5S!$j|r{_3zf) zv3%tD&YG@xCq^Wv@(|zz>=`04rl+q3dom>8u~vaG4a9NcPBsBgJWVrp%TEjo2n!iyRIY=9jPli7NRL->|<-WLkQkXrppW>)3Dj}Q|8nzr7#H?xRnn!%H6vvo1T$Df z#gw~oG0SL|{|+YF+Lp?&*?~mFvTSyuN_>rSmfY?wt>~O6E4Rf9Pgp@c=+&p3cNx_* z1rjFM@|p^S@>Z{^c4cowmib~oItk}l%Vd_?<#Qc6h%dC;e4r>|rP=eKz|({tQf~t4 z#`bz3zx&CC^)F_h`-WIQ|NMRm;p#Ai_PG^)XO5huN!2cF3{4m2#myvSaLKLkze_us z`>_Su&E^jeS9HgbIe}aqdwYpdQ%I9Z(%^=oGtkMkQ&~xkw7e*SPu4!eizfa)#ouZC zeVW5MZT!AvsxC1q7r^e8|Nz)c-DG-xCy&pKb7jMGcrKv_V_JC+P zmHJNn10wO$oK>Q6nWi>P@2Fc)+BzeS^?kWzcmPbSZFkwm+iPDyXcd?k1`jdeHZpl6 zZehGOR!lOOGx*9Cd@i@h*Agg+cN;2JL|Tu6C}qDB><#>c>XWgYITgvc2{;d_E{Pq9 zpVoY7&o1$LUV)X1OQJ(A=9--v+L3RzA-1yxcY~R+f8d+3FIB!-9gB@z;^$YD(BM6C z(Uf9T^0E2Z!qla{taLcaAm<-^ zjaGaRX;}+rMU!V2rrzgApqFy+@OIQEo!G>lg>h`PEFxkf9TIkdn`J0Yhv=*QT0GP` zHon$w5)Em8;3B&OFCb+$Keiv+D3;N+UeK8NvtDrRCp;8~*0lGvO;DRH_I2Fz#euLR z_ut%vP*zMm(sD0j$qRgID+<eyLRyYk`Lv zuSjep8=tX}BDyD_APD?{=tc-ia8Kg5c=${Q&F&#IvHaV3F0%p%NKRI}=kk;jytk*3 zbDniH&32l;wc4*+pB%|PoYCu3jh18r|7mmsCn1k%a88+9Rhh=BKG#nw=WZen$6(8L zXMoxgWn;&oi;w8RQJPA!{^{;>t=&5s=JSW`r9 zdZAWn7k$zbC(kc2e?~P}eUEsSH}-6dG{Y0i!Iw$%3G@0)Obb~IydrtvP1GtWF&k7dJ111rjggfoh9-@V-wo&}RgL2ga9d{{r7)-d^DjsOm| z-XEl>sh#<&f~f;+uPU-7uhJw|nv;GnTyIry(e2+$e4)KB&bi@Yj4Fohg6omilaP~| z({JsZ+D~ToyKHM~{a2zDlb<{$y(v;t@qm4};-@@#$yQ-5uthJL7{q;oOXjj}4+e^? zpqj)37pu6Bn?bxA0p|@FP9lz1(QC2eaC+k1)8%8Qa&Ln~>8`?{mKc|4huTU?H&lEc zhoGz(Q;iZaeHPNF1872m*_IcU!%(5!o;(VAdo}+1aPh+bxh8r{S=Q|xlUcY(-x&&&F)0a@&`ZH;~gRo(U6eV6bS!&o)ZWt1&a(*0ZZ%i`};#M zos!lYd&2Y!?fw%RudrmG5Q1G_=%LU|-ja>o9+j~G9~VI;2VDVR>gEst3!Hm4p;_Wy z8R&tC0PA$YXA}^qvM${a?G6G~yWr#CvGL|)V;l0jO2v-($dUL#Z`;3+!08g8LKb1| z+L@-+v8kzK84Kme0I{lUxkI(Rfi=5@lH~jr=z>9ccnUx4D z&F}D&xJN=05%6@Am3ZIGTH3|GQL>LyF+FA@3KRAzSMELd(kA8JXM95LotG!~PQo|T zP#?9Q*KRpcL`q|~R3)5*W377^;@v39+7wp zbMBV4BCUOM=0EbNT@ob6UOoj7cjTB;^ZYJT?02_tXoHW;zFSh1R~o9nzc4SGP=BlV z1R0FWBZJYmIWpJ>ehSH8IMP2$2DRKtno)m)S>O`pN}qR#Dd8_Qd7Mpc_{cUOEA2b-0s4w3@v2n zKS$oE*k|U6e(EAz-$H>jrgW)lxc(NbZ?P}JF5uZ%N(Xte=09A&OK=`y+eDHlsme#yIp5 zVNSV}uM&qmg-5C&+*`F*-7MG*+G39h+d;GuvZYmYgqg%QjJW|Kk4LR|#p&TZ?msmH ztIfmjxf$_aLm-;MiaCka{izXYR@-!axT+^?0tB8$^28atX}l@prr<`aWPf#05##*8$4(j=;&V%#b{erCT5A*Uvkrbs#NXv<9F&Ou%0sl?7Lq2PPupXQvd8Pn`3syfYZ!; zIS&NC!JG6aVZ1v$&*6+gD5p4bm6j2-d(%r6*F6Ngg`3u$T{ku|x((XuU}TM*`l%P$ zqkDP>-Ctex3fQu9NU(jDLU4E)AWPv-yTMweso*x zkGv>;2$_+-)%oASJ#JiuWybYE8u*nvUlrWd7T}KI4qR(*Yzv&Z`Xq;F+5?9!xRj0i zYN?iS?}Dfar!P2xaXx;9wf@OjWTISzZtdBetJ)4n40(R>^eYum`SDk^C2f+gDkxyS zCe1Hiq6QN;+V1jhZNtvD!DUmso9%fw+cQR%zw5&eh+}iEYqL=m7mOyWxx)8tv~O-z zUCzn~!^njWo z-Xba+zK0;TALOap8_OT2Wqn)sj09>EPjuvNdV7S}?)NqKIcg*Qkc~aq8`%_ErCHN+ zXS!iPH4I4NXH|ccdQPmRF~G&BL@?c4Jlz@Xr~V55#|BI(Auir)+u= z`hoLG>F1;;a`3a-YT>`hcW0`>@8!D}nN=9{!7J3W z<+~vch#$arI}2*=??p!bV`q^%WSXSC`u~XU{71i^QJxpKci_A0=v`be>B)`wZs@;h z?lPL|jPGvPfo>Sk3zEg~U2L~b`K}Tio{*7DD?}XnXR|%;B z&y8k^vpi?@Rj29^e)`Pn$K|>D5!I--ZI@txWc8z7&HhaK@v%@pj*T4OmcG~NU-YEZ z&cg9Zp5#@{Wr~t zA3NjMw_Lj@;x%9ux-*2eF@8$1G zs0aSu(e`Zh@%;{nAHd(&s%~=79(U#N_qWW$rudsM(hsnMzkcxh`Fn_!NcsHj(X#aM z>PI%>@4x<==2k%^o$+_qZ5SMcHB>SmzF5vB7nV-F$X;zJopbI;k)KL~CkK6fr=!Sb z5mR_gt-`qLOgYo6zaC&>E6binE#|7^f%ny*lvY=%b8>i^Ub9%(K$ zB1cg__?sWZ{B`0U2DxDeU~jH`=8{n8Legb9p}Id`Oh+AdS>2vp2pObM5CSl{a*R=m#q9bdRhnh^9o+M8g)Ev2D zH!4X6UBr`>L09zB8_m65k9MzTjlb8^61VC8&R>_^-`v6OU%xfz z_ACE3;YZ1tzfCFToc%>}h@OA%U!Eo-SFlkzQIQ zyC6BJ_9iC%Re|22d=oI93Y+1J-3fZY#P(R9y>B z#Kjfc(RT-RIm&_cXZFFV=!c@feBor}6=2=}(58gbC#49do6@8osX^T4#{=$G-+`U; z9*mzOmktZ$k{CbDw&%)I;+=_?d$Q8R+zfcBo3k%Eh?j8yV)wY`iI?;uigk4V&q1IH zC%dwuYVQya!v{CCb}AXuPj?a@XiQ!7!{m|Tqk#+ajxZgD_@EP#0BmFdNuQYK+nk)z zwo1QfYI?Dgd*)&LekzAZJ51$o96M}xgPY2qG5Z~+a;6>hIra8|4y_*_w0;GxE8jr(R3BzGl;=Tvp!rx+x+RtU$_3+p zl$?8xYClrWt%H7$Hpi-k|E8R~N)3Lmocot}(J%hz1sOSaf&=0Q$hm4kO?-oOrGJ!5 zP{F7V(B7uxT*ap3TwYx9{<|~W*r|+5Go2k}+^+)}cjx^Z*;6O}o91q(xz6mVM|#o? z16n0=g&}WXzk{>;F{j?w3V8=I|06a8*x2@3M~M52mhvUm%MxNptS=Frotsm`=roDL^8b&y{xvRstv5(umYE3nd^r$6mHu=)Pxh@svT$`N+mcnn3%z{#D8n2sXq zIk6ZRxuRF#c_AVz&ksf9t~qg>UuGquiETmW$MV7kW^x7LYnxn;xBEP^A<7=4SIzc)C-UkoN7heX<0kTK=A^?!mROotX9nDxl~*qSPvnYj zNGKUxuk+;Wu+Je)Yi6ZR1l3Od9LcZFR|bmdpppZlZa&mmO%k@9B(#EKMHe9nJa z{&W{e-z$I4fh_3xFx#`Wv)*<<`~dkgOLdcjK1K9r;;TRB-KOLZd38JY=OS0$B=O}e z8!fW!epiM`I+a0ZLI53QP;DTCe)gA6?W`8K24Gu~j;eZZwh>kRT@nNF@YbK9lg#>b zXm8yx?fXG`RW`;r2+P?XBjL1gi6qsXt`TKBgBvmKf>L1UAiY*ZEO__*)`54CC^27p z{UiWy2;g-ty(ZI-?5*@t?1v8WYLNO4?5)><4Ja+N>9uJty0WWCdUdeGQFG z*P;7;jyTyB08`2A3peV_8qV5oeEx#Zxq{}2bRraWBQEKN4=HBS}2#r^~FcB2#*@_@V2B)~|EzD=+Dm`)taQ!?BIb-x(72wX?dir>e9I zTXs8n3<|d8Uefo1I4{p5%Xt2$dq(PXGcWy=7f(5R*XFj1-Qv>N?TuX0K;C1D5}bQa zo)2!^?o@MNG1E3Blt)bmK^wil{*6eac(wjSYN!wZJJ0kK;UylJ4Qlv~R{5S2VIyLyc^6P;T+w;}q)U%aeKXX9*0QprYsFQ<^ zN6}>D*EzITzlrssm#vWMY+d%W9NBgD?cXmb?w4WHVSVTiw5)j4$$!YqYnX#A^^)EE z5=uwY^WQWdl?ijFW5-+}bb1lpB7|;dfTF~jp3a`?ASbo}C!w4;3o6UXhP2j;UOTfh z!B8!!5kz`=Ld~h1b=eMr;oUBL{sT)B~}Cc$pHNaLle zZDL$y6ba6(lp_PeEV)f!y}&#%L-t9$F7oK`lA*=1Vc04+uQA5PUg6gt2MwhfKqDc}EMsApGzmSfbqxym0 zHpKQHY5k0P4u(iecN!VEXlU0+3w!PghIWgzY@xs1X+P4U2$F!D)3PYBICcZOEtkrz zXDfR7*gmAc97WN@;uI)Uyutj;!XIfJqi2n=DAL-C-{Cl}2S*rA?#&i=@Z_Am{dkjF zjhJ$9=8S{fgq@7zLV}cl)%rD6)K7BcH)O|&T=iF;bI#8ywBLMjzXIU55lGSG`ghdJ zKE)*hrR5*0@Tpo++@NU)ul~Z*KvuJT7{Ifr4r^*0P2YGqq>jo)}>#(^9vG z%)IlZXmijxG%Zqj3O3+~&t|r6s!hEB>p#>|>IR-T-?7B*;&DhdKQC}>)4Kd4@j1s zQQggoTcw!86loJSd>d9$`Ldk$o}^$-bF7~xi`O^W{&L&9F|WPdbK7(G`MC{kmTx|b zZ;`GH^^@)i_AewM=Go;kme`hv${E9{f=dUODwfM6#>x<5n%9NjeXGlp;?D=$z+oq? z=PKWEaC)CZA}5m^fdmxnBW5F*+2T)BtOch~R{gt;5Bvk(R}x zP#utXKg6Hcx*%50K{hYJZKlQNp2p1Bqi|jPgG&Q_o)oKmmiD^l(I zhk~McIqoUggn>Pn=kQEDxd?G(_=E{Ef6cL8sAVEmwAfA8i~Y&zM)y z9v{U?$x^B*&)5)muw`#Zl^amIMiaX<6t2=O>}$!u2DRb5j?YNC`%&s?UWmlU( zRJVhdrXPD+*b38--4WFmdJdYA0GBI_XPR#z0VEVB&v?PUa4VKFr>-NMJh|xp5cQll zyvlJB8`a`7b08m>fjnh(4JYqT$JT+irp68zTaW$b+YROu{^7dX)Xo6pk6&MtbjLdn zSwE@Gvv)x|xXdqeU`pSuoq2VEa@?mFE+?f4Qs5JFO8>f59teP zs6OVIV?ne_TkUXq_yyTdnh1cA#u?oOBvC1gBD)WI;$|N!NM$qjKboxjR6*zqa;8p7k zRFJD6OjM94s!uesi|_1`dOyYvI3SGJ6IUC|98E2WsT%y#`P85<}4NYf`9a~!B&jV*O`@p1YylP zd`K^3v=U5{gyO{F^zEATBMVi3G2761sI?DE%+HIU0GQG0f}}y?vuZl@Z!Wa_YTmOyU%u4ifqtkIctG z*8kM`DQL;lrt!=3bm=4bSFg<1I$1`KL>uIFsv4Rx3z{r-oHmAcxqHWoC><>0I z+7|(!+si(MBVS$5gfySsuTTOyBb@{OvDwS3pA~syT5^h}-Y1Pd@w1Xg6 zY}TWMqvD1`*~!N_`1s-|m#EJAk~asD%0p*>3&`gjyVOg7=OI>L_W#lr2)=TyeQ%~_ zL2OIUjNam~ zA_p34Q57EfnmEbxRkS~L-Lf_0jMtU9@tN#$eenbolgMq&aS`Jes!f^lD$C-GTfjQv)BYJs9NETp2%(Q^=&} zBA;e>9&-z>eV=Kn*Fv&>!_0=l?-~*l3mOvf(uPC>{dCZFO|(cKy}0~$;YDZEx6hMd zkeUU$pVq{Ny6#rHqn*>o=sFl^rr8P-LdS6~n-|h`F-q%8CI{!r_`nQoHVzBbq)t$& zkZK}c#d8yWi{_}G^wP}kTvYGNuv=N5SQ6h`N1U$a^T0(d zXs5*(d$YOEU72*9{0LH?VlWD>fo=5_Coz(@VjMtQLIdWsFJS2;=?K_Z|8R!OuzwjH z1}8Gd@&;!t0%eVPH80ZgJd+(wUPQGwFzQTC3t;RNwxE}hlQq(EsEk9JFQR!xZ0JEp zAeY}_-JO=dQoX+U@-iq97olLR7daPZb<%wyRKWkE7BhxCQGz{X<@!2vN6<{Gn&GB% z+vPo?Kf0WT?ve~dORLKZY}r_)*L-PNLG0W-MY1q`eSmkHI-IZ$tKe>`wQS!mTX^-T?SRVs}3S9 z6M@OuHLu75aCXf>flZUFDu<{rWsDm^)tcb%dN&eeUhRBy{0*{fNU0{n=A6IjA=zix(T6LCdtW2#ZSj4fM*^!pG_&7P9E?1j*H(?*a+cL>y$Dk!m zmm4#t%U`}!i%ZNypJ2Ki_$d|&xtX0mW1f)WYz}%go;ho%*on2rRZD*e(1zF020_j@SAi;Q z-?qr3>t!6Juas#wK0wT`X~-0VIcpNGHuo_MOv3crvfC!wxmse*_|jre_)8WaJ5maW z3n#kk{)uFp`W!x|6%G>X&R&V^hU(WXzI{6;-Z%v=%Bx_Hh zi`?Bc6_P4 zmU*>HH^codG3S1!NxHBf_*Ob_bCRBAn#$X564!_xZB;TmobLHu?d7&ixY4Z{#RnV( zW`_(QuM!D&0FN(;2ZhIp!lS#G zINm+Lp*a;8;FmFEbqc4r#1Kvn0#8AHHYI(^e%6||2$fbXjTDfIe&N$7La@KZW$X)} zuw3M5@|tx(!x@Ko;JSp`DY-*hJh08Ihw2DV)=qi6oEny38xrPeJwOdM z!fHMjWhUP8#?1E$-}EZpoDfOxXys4yY!aM47u%}oz`f$1&g-%_29I9ENeVgYPV4uq zH0>~iyhuC=@UXw7r}*ZKV_e{=m{G_VJ0GL|u@&78%o}uB-k>|KMnf;97|3hs)ZW5anALb;{JW|_nq109d^Xj&S z#f7$jxc==Klw)m}H?5Q}-;cvaW0 zy>5S2@_}S<0eL;0ezFsMUU?uFFb3<&qy8yIzUXoO`6TlUTD4+XkKV?J3$o0uXHjsNPu`oS9 zpoix6e!9O1eK)4AC$~C`HzddJKQHxnX|lkcaOX{JmWRY=5V!6grpd_ft#$qr;OiH- zzAgY*RiJ2JxzioVL4UqP(ew@Gnw8c-H7H%oc7}_{Z8Kjg%Hk_|#HFSnzEet>kTU+O zS5#$`C5j+#q~#jEC}(haP2|!292J}e6^vUmp}T+a`qmAX_p(ux4dx~zf0cqNR5N9N z{6sxCa_HZnWsg77R?`s3q_!>oJKIaeoY>Aymlp05zeWLxqkvH#?eW7LeStU(z-d(k zgtdbC7qcKJ5vC#j^+P*TVJJlko0R;kCptLEcQ4A$H!{zEW-p)Ui&eddI1^D3;aCFU@qFGQQh zvjEcOCd;0rH)DDKxQ4`BCwpIVidzh+vMff*p7=uC>1Buomjno5H)zbc+)C8mpB^zqE zQQ1l7f2bw%2+ahN;8sb>0036G4g}8l<;+t#?NHT@({xq++%93Q-6?73hr|f9nX@xW zdral+odjLEkaBb7mxp9ZKbl`U5=@cVN5u>E)Li*oSUgsd)9@LtXq)M(qFSei5ZbUz z!vUDL?Le`IKhB@qS(*k{uno{eZ|0$(?9G%FLFKk{J>Sxca;U@Jb(i~GP4AZ9MJBL# ziL}@fvj;0q&C=%D#fogP_?s$5H9No9lB@8K^X%b(%$!M(%(ExU%#M;( zWFigi$u0Hl?8)4GNTK{)TQ|5%yx3sI!tML_W%Z@ZnxSui%%(AezlENlCH(VeI`>~2$!q(~$wRKP3FYCQ=bO}Bh}Vq%+DH}_*+77c4^*$M={vYfq~#6K zcyc0n@Fd!|q6Bhop_Oy7(=c(`(pz{%s3E#88C0R-mDojARLxb~yxbPHBY#(tK(wEj&0Q{u#Z#-BPVYPT+dvxaeFj<=2on+i1oye+u zn!P=cM|S=K%F!Lm!CC{VDiE0CBIDN4v)XeF!iL{z~U0K-*WhEDrH{Il*wiM(;V8Cn9V7dIy!iANVMZH%iecL zeD0%sB+g2|mczB3?QhEG-?NA<`~dzPZi{WizkBgImw&L;2Fqq-9UWzza}RfF(I@hE z^ewRK%GTDM(gib_8m{y%x@*9$km4%t2bDFAIYqPK+{GYXt_$(5qA84Rll~{|B_~iF z8%6y3H1eP$KWFWi4*dEFypYeYm@PGaT~#eB`VsndHcLncvTGoQA;c0u*HZEDDe&+I zc|6=;BMku$yN{NSdx!pVEHp-wMP< z{4PC>&pi2b6*2rioQz%7|$S z2xO-URDor$n#yGrs9`icws0Jr2FUdK5L!4J=&^u^9KgRty_l zIx}mT?CgoULo3qynx-{lrSRg$Tyb%L?K#qNoCfa?59s%7$?}YlIG8dJDFIup-!oUI z(tg+^cE{|4H5uEgh33i^c(9WZX_-PtITNzh8GkRCE@baa8J?^kDN=0um=i5NwXe?B zek{NCA!=SidoHtKP2j@8~LL-fX;rtfwwx=cx5I zkLOFo%!D$juOr_Lh9|QfW8+|+HA{PZsF5|QXnILUBH2Ne7)mjPayzR66z6}4>q3c9 zVxGFzPPx5T#5(RaNS^HPc5h3P|)^^U&6J2D$n z%Vs!vl^nGBSuXB?TKY!uhBhEZD-AHiT7?7t-&g-^tBSrugZUp?zFL#6@<_ED1ybc4BumGI+9UOq*Oat=0|DJxRT{ zq^6X7;wNSff|%7@l`pZK8|BD!^4+aACnsUpts;X^ojeY>yLi|zs<+qK#R>i{wXfUj zYV;%nmX#k>0CFrPKI2E&<%j@>m6RB%S z5m7^-Rf1{wSPrTW{9fo9r<-uJTk?7jjZ1@I{?2eQjUL6A6$_lAi5^3#kA$AvB z+80aRi)on>XS)|onHL;n$P6-Uh678wD^5f}^wmm*Og=n^#V&S~jcqA~P@LXm%mWt@ ziD88IoGz@pdF=HLDlctIHBkvz2mPAQfi_=fJ_mWJd-A^D%UlO$$2#+>zE8>hPLB2D zD5e1Egsd2JHm#Z8i|U!@wHI2%P{MAseGK-Av}#YTv`ZHB6k7(F)5-_=&L^b-Uq_)F z>)=rp@MmaJ&HHZv!riXMW!V}l@@qVwQ{y4k(EeEZI3!!+kNGuXIW;D##u!(lEL(#^ za=B0)l~dzT)i~JI_^=`~jz59poN;Wh(KI)XpQ^^kdeL0@NVdkGvo(YzmA1~*)reo zI!z+Sx#<+qEpaUt0aBTKc_T0e9G=C%D5+>;lQsGV+Z{;ei!?to|}D<$etRA2l+Ub*vB4)WiY z{Qp6|RHdR#(`I^+^D}b%!xH?%!uXEXDP&a>6WS{O##9*u654AlGnRQnE-jDk#)2WK z(tDWA>~wNtC7YeJLC{qS*Bhm^f@Ur_=etZiOHqcBrb&Yf;@f!1N##L_^I+tA>aUvn#MV_G<0V^VRu9ywzf4&~6Nc6t)F=UJ2}0Rd=J^R^ z(riVDuV-;-&Oq*=kbKpCjp_DpqE%83)iKRW9t(oo`7+;qX`E^IeaSwy*$2%AlC67Rycaqh4nTCUA%&#?nZa?8Q#8uI3u7Z`6$w88oJF@aeLkn#~ zH_ot4FQLh?G-(dB^Z(Q|`}RF^sB6QO{r`A-7x*ZP>)}5ki39TlK=Odd7j;81KRd|fA8N;VPlG>C_yF8*y@zYlAsf2%Oh z=ZC_)q1HWjnpikV2#fDBYZAh)`-NiH_B<~sDGOyJNr8!+F_mct^K-}~`N{p4GlV@A zcxM}gKLqz%2AAn)h=44;o;LL&nNqGgzMLCbUr$eW!J3bz2v_GwS2gfz%oEb59FnOk z`yzA$6YGU1Fcoue^LUa&S7!IW2^yonR4xvqNcdVjD?Cv3Mfg(yt6b=N6agLrWpjh+ zOa;qySE%r_+~-Qo$E(A4e3oA4Y3>u@C;@Qj!1LvC+IXHl+VRAhx%FiLJ}h6+^3n_f*X1CvNQ?xRYvTlgCvAdAq~g)w z=}U96fIHuU+i<)`PcGx0^MN}+!2N{;KdK4;hcHeJR~3e45ARo3QqeUXZ_G4g&xd&4 z)TInq5AP?1(a%Uid}(Sf+QGKrKEHJ-2_k{FNvTnpTs65eQ z3wwYU5Ak$lffawNCjXn-vM-!yOeU}Rc4zL%6_H(sht3Le;A#{XKJKl0tzyutp}|b; z`Oe(p*oyFGwzl(Y%f1Y+a_x}F;6rctDf_KbgwrlgY%t&=gASeeg~f+0f-8<=F`m?S z-;$wy3p7T%p|5gZB0cokKy%LuhD~zdBW#Xl)-WZ@F_PsC!ULe7HmPHX+ag9$r>An* z-g*{qz=KO=y|qabnX2#XDr>%J<<;>}kIFb&-9SieFtFUDv{v2hQ^?{l0CX zX$vm=G?^156B2Y4{=Q^-w9J$a55_x?pueUs6It-7K+c0F2M+cF{}c67XM>YxXC?=B z_vha%`N!wvZ(-9Qvo5_z^2MQ?t-r>fKSc87*kv}q$)A6)BXZ-8&OIW|`a1XOZp3vDS9f1VHSE7;cqxC?j3m$pTfc&x`G>~S zknTz}h!lti!UW^@>~@QH9PI)QpB*Jjl4%uO6(6Cvg{j7>`%^3v_vd}tpR>H5y3waL zFu?8y7=RwlW>z5S%lRZTPtX>E+{?Ttp>;^UKoOV-_R69?UgV8rh@etiMq)ER%}Q$X z>Y3Z4GANHYmt)3CvpH5l>uG%sLeycj7o1@dl|7>C=R}utz^{kc=>?~m>A@a(6-Z>k zuS{j+#oiwZo#9h!60zQde4vfQB+sKY_J+h}Wk%y8GHDPN+Db&!nOku|nU8> z64Uzm@#QzvW<$2nUm1Ysj{8;KwJiyu^0UacOH=m>Yr59 z``n~!O`-P8Liue29TOefhW8I9RFqP}FZLCg_}r&ESTE--5FA$}Y)^zxM0u==Qa8aGRAD^s0^mUf+6%_J z$#Oz|C4Wx0h)&m@5q6ioMp#bvW&^L!V-JX>5H0^bO{z8L#3s`rIkw4UDUz6@Ev|$U zsVhma^MWf=$%(_wc;=K;lg?%KK8)nRnZqG{hv>XPwv`jJtt>-cb6U9swTmSo(q_g= zD=ZTQv$i8Lm=(0g>}+jr&Z$zTztlOE1f+0Lg(ZV@rjs?cG#H*mx9onk`OIFB~w1v zPAd=s-165-`7M<9n`VFae~6tXv|593wEUuL%@HaE?#2JsA+R4w5+HY`Oi0HHBQfnV zPmoDZrqoxOP`jh%5OQ&d4FEnGZKkSJ)XL)A$@JrcqEA1L` zg)a4^MLZQ#SlZ8)4o^hQ#R7blAK+9FHJ2@dh7Ohnwd4III5p;r-?RHO-g_N!LV35d z6*VaspEHU2rjAQ9qC2>P;y0*U9A0&2F*P&?#}wYesk*ieI^LxqTg|hA$#A2&nf*_E z;-iC!aHH()ao%B;jOu<{%+J4(a&jd5Q!`V|DR&2caQR8S56=r7L$6o!!yQy(Ff21W zw9_1*-)W}ONv@q4T{g*Y*ktyrk{owN#|chy@)`Ti3&j<~E{I{bV(I~CH7OyObcR=6 zN#b%ZGL~I!*>^nIrE}IoA(TUrrWhJIvJ+o6ZDjfe*DeV(Y@0gFgHxMy z!#-)Tf)<;7Eq-Bs&ye>@(&8~WP2J4A26oa^HRofZE%~PACTJ1QNQ*fONeJ*z-CbV& z3~g?Jsh_ga+;#{R%aRn6RZ=E)(+wa_$-NXAJ4*#1n52(*a7vh!{570yHAhAFz}k)) z7Cm)8I4Thka~I~2I2opnIJ_NGtD&?uap~;Z!I#c+VxOvf1!j4DXZN^A({B1qvFmHg zE}b2!%#wXQakb+mu2$lsrCog_=(9(9BA!4H73CU z6;WHp1T}*ik;x_bOgEpOp-~*cWYGzAOgsm!W}4|hp4?}&*_`)+(5t;BGIg2u82eY; zPlI;iF-;z}h02DLXg5oPjSv^H9EFgq&2Vqhi#gnz;_tYIBiSc|ZS#VO`q}!H?R#Rz zM9cR+jFCem$}A^V2ilqOz^1uJPCn@@B-mkkU*7xH*Fv4xGhk@Gfq>Mb{EAHO#-_*v z{F0%%K&&jN-%`W0bln2V#K_ToA(vW)xCyd-Bx4)_eL_8rc8ou*CO~G4pVO1=mRPkw z=KT{s+;RRKSY^h!b7wDYnnzFXrY}?7wYh4_`r5mkYZ=}4?tjH1DqOFmz4RR!`L(?v z_+5Ul>^f6J&pw!buV(9Xl_~IidL_%RY`yh=kb(otD%5`)YnIOExAZvU0#U_bshY-| zE#Z3~!`f{6^-7al5P*I`RR_N9EdWQ(`WNA@vNzzU|hkN!{nlmzxC!8$ck^nbLx zZ?^Ku?M;F6?5rr`#atlO10-a|_jrlT?w^<11veK^L}G4agUh+|bBc+3zK_%)z$aVB zi|4*p5%Yv7+{+W7bP93E7WY)hTiDV%=Ki<{dKT_RS0LPv#*EGk0ab(R6rT3aL7M9@06&VeDQer)#qNr9S_P zxK%WAg(;jTb!B~Y2VtB#eK*+Y`$<~&P2VD4$*X6J+4D7H1PtoRRn0MT&r*3mO}{s& zlKUmSNN)yi!B_`o<^WpPnJ2zo0`Y>Iq?~v)&DC!yUTn+AmbVJG z(_lJ)O=3bY6S??VewI+AbIC7Tj*~dpHUn1x(RwV zIN=YVmytQ=&PFM~kTt^?N~v39jH*p4?eu;q)6NC0nRa%4NMHX><~L{VgwZZe)rkpX zE1JLPP#OQm{ERTZ%IGIN3AnL3{zY|si&>kk-Arxw@Hq&H-K$E>Ts~H9;;Z&x6PJIM zY5Nvx`)KTSpwRdV8Veea<-?`11xEX5d|V17dHZ|}+s7%Hw{8Cj?(}`&H0^tq*JARR z2dqw!4%kmfy_0o`WPoj>a6LKjSSpx_*RS47K)X274}1OH1X zM{Agy1p2wk7yl3pAMMS|8&fxv>uW%-R`GqOXWI`uLoXNh^#N$Q$>NIK+T%KTpqu)( z-5hxo-x*d}xe!ji$!JWy(ynX)#z5*&h)PNPhYy2PeLD zh0d)b#=nx=P7>$$NETL94j$IO(z$w&M#ftbNOv`vu_K`3m=uf2;^dd zKhQUt9;$D`$2fBX^8%$G<2qnPURGK5!PEf~*T8#;zlH@eX)ZJGbB`jq2m$A1Ab@qP zGjkbLXpB~3&EeKS>|@@2(=bqFdx;#HJ zWp-ZWZNo-~!lg2wYs2x8^UP%1w)qR)poy_&ggfYf#lD5%YH?5{Jb60xC(`r z#3OyU^kaat&0eV!1qvR7RH(1u(hzjKqMxdY+)0fM7F1LXd4cPQ&LS zvU1=cIdI!xuPr0Y&F!9yyux49PT)~0ETV#}sgeQ0<6hD|+rTW7hIy`uQz45>_n;;R z81naJ2sNaoMNBs+QR{6mNV-=C0gDyQ`3KGsqD})FD){^keZ+Ir6;5PmF1oeZ@*LTd-5il`|XA*ucq3k+VLa= zY1*9qcaf!{Vkg(T2o?W{cd--IcK0sI!@!eDa$atIvB>VYTh~JYygCUc((t|eh`B{T z{r`qb@eBd>LoUT9B-7_d>hq)`u$Lk*q1fk3B!=Ht5F~H1RmG{*EKIwJsx{oDi1-k+ z$s7|TEL*xY{+cOeNcQ}7Gx9adJ{R;>r2usO zar#HY3|MeAXwP+5_2=`~mA}zd#@ZlYWROFx6%8QS^@iF`C_3DxQ~*lc8eNuIB(Ksn79p+=@DXM7npDh5cxlbNi1e~Xz7ITW zuY?a6nx;l!|c_F$RmeeWY@ zSYFmyJINDcWqZKI>R(R@R?E_B_$O5d(SGpz^X=&m8^ijwT+zQniQpthS0H!)# z%s2B_Zs~RA9^5;&)`|U;tqY=UM0jhGr;mb>J%yhcwpzWI8!N*y+0*xtorKGr4~)o8 zqGgWL9|X%3@grH)HslazhU@{e4ic!fadnTIlOLiF6XkvPcJ*SS=#x(J^KWvDsx>eR z(Gbn20lPJcON#kDPt#;rc<~l?c!`Ne(sIp?TSXjS3>C#fMWV_CqH>;hmr)ln({ohfNeE{}@O7b?z^o{I1>?^c zK-k4?(e>16iAvS{7X8QsTx{Ph;Nq445t98eB*V3zvI=~Rii@Yfa{?~bU{k^*Pk(hA zB0X#!#yJ5OT<>7cWkC9dyXSmwxI*ceQ=-!NrKz*U6bV^2d2tyJXtAR6I%_VI|&oxI6YxvV_6_ab{^j7#12BeM0OG-_7xeCodk)EArE1>u|GON z%yiKSZ_W}+Jp(KJoHt)22UbZrfM~hLDFqH)AHJnTu%>BSVykIar#J ziJyV4cEqol^@Hxjlt_BBk~|yWPE5=I8#}0C$gwE4!gx=L+^8~H1wAf|!wkCT5ti4B z?&rhyoZ89mEX^LxN4jL1Mqx49o(ER?8Bml^7F*KxHUKZAOnRB@9&)A+&`aGOL*;E& z_Njf9nq)K6YzprwkfggndBbn)+$`c0Eq@l$w0lC8IXs)h)}D)yF*4>Zvk8iq>~Lix zVCF+*Y9Q_Vz^7jT_W2pugK}V32`D#u>Nf)W1W9O5S?U2W^n+Zcx32=XE#JfWgdDhK zKDYw}ZeJ375Y!*x`%bU)&M)Q0$FN95n+D@^*e`1{M-6j*Y;q`r5Sc5FZs%i*kS_W` zN@wC^&aKtWo7lNJUG5eu(}&$Lcfazz6~YbtraHfscZRr7Kd3y=qtc1JniDG1B`E%Y z5%ehYi>xJR-nWqO#*bnzqWJqx?2NyY(U&$|<37aq78Dv!`lXA5`rcMzIs`R9Lmc3v zl&nAmWwMonwYsk;6~%96j)l$A#zV8AM;{76;chp-!-9pTh}ge*XdWTW=Z?Er=38oA z^0aU);CbR$@3f^ydH7fLw81@DrJjkR&^Au^qqJd5xnVXv?G0-)t+Qt+^=(qqBH zx5n%*1;oKJk*-Z0&X>lY$+(i{Of$zzq%n4n`{-@G>O1@cZp8H6-g?LDWhvh?o+&@_ zG5M+GucUnH5@34sOa^|>a84Y_huJzONu8sq)0lyeTOIeS`O_r9dEhrc6Fz(yYvv?Z zFjC>*G z`eEj#BveP&4I0;)wVzX4$!H%BV;_6s!u8VCa#ioRo_fMu<8KD^LbxAcu#~QDsTzc| zqF@QUk<`0Lb@lJVIqLk+jfJwMCokKMCphg z^!AI`Z*K1|TwE>wLV0YdwI*?1iTVpq&+!+Y^etUv{e}DU(}~@iFDm+n{Dr5G>-nbe z7vj^vUwC@Szx5XyEEpVpyZH;(dH%xIv!%DyU--C|wf@392>9>)g_zZ2wwuDfyV}%6 z*mC-ye0+vOJA@{dt{vBy@e_`qO}Hw`y!gpIxC&3q=8xJYGxO=i?OlcIrag_9u#y(o z`TaHGSXp-79$bZ5ApKDj1+tDpIWN8^N8$JPhf6Vocu>vp%}pXyB(b;QHu1Lod*1hPfko(Zj-rs-9lpR^U6234s8xeNr-FEh!8|k}0u|;^*c9{`(3E(}M zciqi5Lf>2&E7s1sS1zJYOt}vypV@gPzcU`bg>Lh?9zM7`%WNS+2yURtraa1fb>i#% zl;iRUi3_z-q3+2@I{@8DHFWO4&4<9S#K_xBFX>wt`$r2FLjkaN$i(z3WFzBGtL3(4 z-PFN3OZ6wHjt@~dwdD?Gke`X4Rzd~uB*WeOX*2JTC2m>}qpI9iRc?MyV(MAN@BOfo9GFqv3)^DjgHXezG$F)$kZYx zsqXHVotzjb%s#z@LU8MhSs`x>1FCha2kIyvC@~@wRK9=;@a3QI?)HDI^45!b-^Cu{ zF?S7e*NRDO8PxAG$H@u(nWlT1Uy8AmT@A_-DBTkucn`#TGH`WX zHj}f!``bl;_~74Cxx_uF@tE(>svD1Kj{a1*sKJ;O78x~_GE2CvqN{8p<{)<&XMU1x zgeRSSYq+bk>fsqt4+z*93e_Kwxe_?o5vBz8yB+wF>Y>0aWq`NV`Wjy5tkf=1m0f=5 zSM;h~smUw!uD;A&r;XR5?bm5P0a?=tYdj@!q`q}pH;a<4({5yBxM;mPKS!?a+$=`O z>oOoX|HcQMBi_T~z`{3TX4?@n%e|p4TgskHS>=-#?_7vIfZWuVNLPF* zOSM=t3$t_d+r~Rzhn953w1sttZ+y-8Quwe!4D4w6U3|EFcmk&T_#o#gV5C_t4F4k^ z%&+dc?1>&K0_@k02Q#ymHl;)PLYhkTmzwQEGw-I3c^{U#ol~kvdF!&RU+gw~VvB4~ zeMy#L7`n-ao%9P@V3z48=rKE4d0;)}cJMr}ntcn6*0M{l&xCe2E;E&&{<|djmtGOz z!94R1$(+E4Ur$D)T~)@}0K(tKWyZ1LmK(c(FGJ_ry9MvuCDX5^9C;(i^TAAw1G{!> zH12G754)tk6MS=*Om=bhz94xdNT%(3yyz-$np zcD3aNY@RI`$;9dhhtiWJS!UUF6orI=`?6o@E0;QhPD?oZG&-ea5?s`B2E+$SYBi0!tXx{g6!m)OfLr;6=zs;?J* zNq}1U#x$K{ms2nC(}~@cFM70&mt|4$R)0#|B{5=qSVtA_wvIYHeQu-Z@kdYjH|wVv z80zl&=_)O2*H6tH2m7zrPh+;rTJxoYG~Dv^LArFxgj=3IC^SjJEi1C|mYr$aT}MUW z@NOZOX(ZRpuVATLlh|wbWz;j3k#U1;#N}AzoMlwsABea-eNg*|%V&|BJuRf3#s9P0 zLh4ou|M)_RyUhNBh17ZNfTx?h{U$3vyV++FZ&`|uLXLH|gwJr7Q%COSYH6b2#xQJL zp`E9@vw>ziS(o3KlI2F8PPjQSs5*~{oUSusHnN;*m?EZ@2sx$mtckyJU+%fYzF$HE z=|j9YOfhO6BgY!-50hu(FbmYW2SO$c^LFwi43p>>HHD^RYKDvdv1Y^5Os4xk125eJpy>0w}~+dX7(tr*oDguj+ey$)d|QU>amDu_hRTr2LUBdF+t?`foDy}3YkJfqF6O1ye}=flyZlBPVRo7FniC6B z-dktcd4`t51Fd=TPkGmMDvyh{g^JA8*iG=}26$6LV5Ibg{{piw(`&G1)eO^jp%%(c z$Q6iA`dM1+C@re&)#ey$vOx~}UNb`}nL0tfqUG;>>=iyHr?5C`weY@D_(;C|-Rzzm zu~$&70?cnSU~=1(+dve|%k-^Y@I&EonZmhkPVovqAce2x>qpwmGLUAC{+yANk}-cFc0*=|!86 zl_z;XDo38W*b-TJB1Aezp6X#*ZLJ`JR4{iP3hcYVn#~unnLLhJlu7B z%oj_B$F}ueUrR#rlKq0o@|fN!{=wFVoqL;|yBGIc?lj4z$*~PmK3P7N?D^~)PbOHI-f0|ym<(`R62o57-3r>)>mt{*a#dk^^SH0>})P1ZQfU2@g>A@ZAB?HZmSvodmXZ(jD| z-LQOMP2d)Ys{C*#h4Xu|SpzYFyYR!aN}DC;o@RGkx@tS~&M1+dK&yzgg+`lsH)UE( z@8^wU&Nn$tgQdU#b1wy|%S`w)iRh#46E%EB?JC7YlIf;=b>-Q32tBxFpDIyir6x1N zy!Bf46?No_cw1h;y(H0i49wz|JF(I;=PlQ^WI7@I;~iPsOz1X%}d39e}2hG+r9Bm zBBvY|+RMIoyjB2(o{K;joIef z_;>cI09p9S(&tvXlHX?PLi9#rWOFcilh}q2zAqL(TdR4DpziIK5^fw0HtQOCJvk{~ z0@KE{nO{soTx8JHjrmw&_U*m0_b{29nY^e^oB53GK_+dk&zUd|?RE}rFth`Uf}8>i zcT07mHPLU;wBDasReegY@D^}uDPUlKC%ZN8GCBm=*SWL8hwPTM7?vYq&DFQ{3N6m~ zQ)HO%%#q+TG!gh~`VMHggQlV3?2=IB0*0M<5xdFl8ZCBuSOjHesg{3K&*EYjL9Xn|z-e}p z?!AF#VdS)FY{{IlBY9n0{Q4d7mFX8CKE(J^R)n{tP6T#(Ne(mq0q=zw%U;M~#wYK= zj4qZLi}VnPh1;+K$kVv|#S(FxOT^n5eu?b6*GNp?G@HH{+wM{1G57XGuGP94e6J`3 zC#lcKC1!|HVAFEF5SAR7ZO)%XHTKI+$D?Q-eFK&AQ>F{@i zyeiy*G23)J_=@Co7izroQ*?qv0jCGcelzh#@eeHX#v^82MZIsLVHDYY@;D<!5V z7dk2f=M|Ae6iSa^*_sxP5;V`37RJRpr{`LFBMVnim%X#Jw)|dVZ!SVAOipjxwQJY* z*AH9XC&GWBRDAK`RLS2W5yYcR(9bEeOIL92Pxh<}9urIh%`CrzZ~K-@3l-eRr^s8CSx=uT z{VLacgZ^jqIejdOdJ%n>Q_e_b*YBx|d0ASaz=vndua=JaEyMEjLBE)eXtNxjNXIC@ zImSu(|CHl3@j!`LdoAerTM+&K)?t8ASJ;VQ?(UYrji(rrcOFi=FpKl%_nC#)3l~P- zm+C5s(eiV%HD%(9 zoo!3z3pVmVi}(u!o8vuf8ilbsA+7R!2?gV|zi=Da%OJK2-E_y=Nz73}oukI@h%aY> z$aNO%3ekh^jAlvIiLFU0L9TWh=`z{<-34?vfZS^7b-uM=Y8lA*zrSer-34ak%vYE& zC5c;Qh?LzbLuSgpgj$&szQrThyke;xcfmxH)g|E_rdS6}c!wR+t+#p#pjB(b*t}MS zCcmgJ|7Gn>wcpg@lovaO=7pWewEVnqFOf29$I1&~8M|Lt*5e!X4{(G11P+$)(%&#B zK*@f@AVidkOPjOhGqx~xtFEt@kKNYTz}jxQ;7fyRUy73E9&Yhyo8>|eOL}YWy7VRo z)_gCrz0UkCH@h7@dUElT&;dFVoBNT7dc@=&Y;(1@%}*J~Zi?We>j%0K>u~yNY>a%_ zDZGPUD*vHFGBP>sQ&A<-HCQ`sW*NP{B4_9BefPePm9N@%^-Va!kf zP89uw1{lIS^i%IH?r1iEYHL*wSwgl{9nAlKCd_o-MoaL@iu*pA93(yIYO#_wnnP}2 zGRx`DV05U)=;?Aq)=S=6M0R^J5ggMu$pJ+v%R9r^WnPKF`As&P;tpp)&HX{7~13zHflRU5pH45u^R& zUaMfdLFbTP{Y82n1seZCm?a_hgODRim>Er)g)@qcZOQ0MhRI(_s%qS0-(KZu+%KJm z$;5JGl_m*ycjjQ3+juN3vG)>XA>&@X(~3rm`IU^@z4EoaSPb|JXggF^{9NFHeuX4yG{ z5-(da8odPBZxC+hL#qlS%YBMu1k$-vPS$~{U}6R!5w5o)LNXP~r?cB&u7V=5qXME4 z;WiX6|BmcwlIabL307eVWc%fmxosH@r_o7i^AX5^j-$=WeLC4x%a&l4jQIJr0biNl4#|E{P=#-e!~Jh2p; zUFuAiedRl=NMcDl_R=qF2TQb4h`PS9M@I;O(wj<8>OvAS_Js%cT&!Q^hwL1Hz4lge z;9J|IIUPQx5=rKqkN}cll$dG9U7P8vT5{$fGD=sljp}mDY<^IPwMPMzs>ycXG-rBr zh$c*#WnPjMk_Myd;4yua>_A2sVuuJ?(elD9nQ!Kj`7cYRAYo3X?^BzEOy+Z|x^va> z+jLRt!S590(M9ZgTYsiMHkJq0{%!&lU%#q@2pVmqe+~SYZp+QC>}l~kD4w1N3x}-8Fg=;e!o6%is<>XuFiYtbdEEb-t#Ny9 zjb__TTBBTQJmryX$CNuy2)g^wzV0}o$yK-P=(gmsWNl2}QULS~@$K_MKGHjgX@4#WwwuIc% z)|OVUt+RY>J>ug@KWXcCk`OIlmMQIz-@4qERu#WfSS07M{YX9T|9B-UQdYggjXA$k zVV2I$r2Uz+)N)G!Hxow7hh-Y???bhRu*J1nrb^=-N$|CoIxP1)y%JF0w|G>a=>zp5 z2PHgECkm*?Bq3VS>#n z(^L1`v_`$M5Wayt|GX>z@Y-VezzkwzePncGW#^G`m2~yC9VF;D&H-Lwfk)i3I>L@| z8}z63AWfgI@{{yC!GZaEXj$sZs|8L42|hTf(P%^8cY39N{ThsKshpRW*8#aLRR;x@ItC zdFH(6Y;j-n-_~4zOxeU9Qmo#&zZsuMMP6C?X%x&P?SB4c`lcXOy?--wIZN_H`5X9v zrPZRc2|cFtL!~cgr>;=*P5hNw-uz<}nO#CybTB6SNNR9+ zs5UWEGMt8s_>N3In4IhRB@51ZZCF>8y0hBS&`hDdgUN-n`P)PROzfGB{ANOv`dH6W z!hCRw%qW_4W^%}>wTYxuVDtNLUy#wd81-mQzp^@Or1;l+Da-EP20@#k)R)TAS1rNt2ADU{XzoR!zay%WG{I0?_`F<(|QpcTQF; z9U0wK$atybiq!8%#J5g!8n)edV(Ds@F^;Ymb$$1OEb_3$FW4l4xDiQ`sGdr^DiTg4 zdsBJQT?L^p;#<=1D!JM9(@4zIWckDE#E|-=K9!{2kMYBv^88<5%eViYEeHTamG7;% z>AeJ5CYd*}CE2S}ec|h`P!{&qUnu(DTV-E`I-e^7bF0>5AOF_^5Yh<}WcrRNxcH@)5Xf?Rz5-}LXEMevtv_r$fM6~CPKs70BnKa5@9 zo?D!50j9d5UN2Hxw|a+_n7Mc%$2mUq+s;S6h}rdmhFLa>rPEvfnZ`!0A}_nthOqtA zs5;Ib3R+AR_TpNbQDJQjtHYhP1>%vQ69~-8?cX1&Kb`t3+`W81y%G90zjEVfTOS9ebDS>hJEPy$g@ zADbEHWqb%SK75UvtH`3c9&RP&H{i4Oq(v;_!+xB8r2HyrQC76_x39v$XW_N%t1s=D zlP_-9e)4{eQkcG}2gtYRL$Ns~rBRcz86UKml-HXU>Aiz>-!EC-_Y-!&Wd~T?bDNMs zb}I)36W#Bkc$3GCvEaluX81LMtR<) zZuS&9OcjV@2W0#mp1(jlLp z^)NJByD(Ay2Z+;N?skr_Z|Xsb@);zV4tyrcZ{}w(Ilj$I;IpNume2fLdg8klh`|Lx z#9ZLkj&ADfUtNeOAY=Eyu9m>MJkwb^*2Xk73JF~2nptRMbbY5q0G#(LKu|<(ErJ__##|!}5iV{9{@Xru6=5A8M+ZO9D|vgx8gyBBev7rKnVX zU^#q-li55(3m0;KgjkEa*?%M8QE{UDFe;co4Hqu|grC9WsC*d_d;c8RJM&wL)&nSi zDz~Nk{h^C)+Yf|JqWwg<6fhS8prLu%M!A8iI!}Ajy;WZhnGqyGV?BZmt3%;dHZ+ki znfA;aRsB;|!M!*~WxCJQZIs2eajsX6k1jEn(lwR5^~KxjS1%e%jTaucH9yZZF*vN; zR3^IgZdef>t(maG{DrLO&bIKU^tTrtjqKUxPH)%T5!vQ~tra3Zd1ea&Ci|&`G5G2? ztev*0v^o8FCf+YQzB2UIr+x>|EM6l~I0!??slTF4Ixy84ycnnTsq3Xo<4AY7h`{uR zNZUQR_ELRn962sLU-`TrC_h4(Tx=q=P`V=iUc6r?Xt?Q`)r!w?U5 zB^+7E}e<+rc?X6UVt7fm5Q8;|MozhiysLyY;x z-QWY*F1~{CH>^aOpw2&&szdw63%my;y#5xOW764(){eGN;iJ<+j@6KJNK$;9x!;>d z^&=)y#CU+87bf!TGR@V$sZS~4_Gf$t82IByt>Puo>&E$z-LRHv#O<@)#xL@gfrm0` z3-6tsZ$%%$x&~MiU!wifuzJ$o^;=<3MDcq;m>L~aAk$O|d2Dh>mMZ56H(hhX*PnL& zBL8ryNdAL_7Wne1D*8ZqZ5)T3itD_sXN0;o~ z?+x=U8l#lQFgBWXsyl9c*&G3E!RgSvaMOi~wa35q{bA>imW&>d?~K0r9)0r$*86ho ze*YXmxSeRA!*GcAXICL(j66tR5so%_TSE=W6`|`RY?SzZD$!T6lnvSafx5Y!%7 z>ck{chZx0X(m4WY=@8<2o~31+*h>KAs=oc4ri%S|a5EWP75TQ)M76)Fl3nH!ahPA7 z39Mg@~yf45e*Kg=Yg0}JU44kyZRTtN?jN=>{q6z3a% zw}zdXr)y=2p!zO05e!rxI!!YL&(akwfu(uL(^d`X#67GNduI5P>=KvzSd+D9fK5sA z`c)N?U7c=7RhNC`G#mwx$ag(MPO2xrTskStovo7mb>zFgP6JV|LMw?C@=VJiL;8iC zbdL;tk~opEgzOIFd^Mz>)9?lz7P%?Er_->4U(VdqI`D#hhao+~`yl@W+){S0Aw5Ii zL`~(81DzRvmEu$Ldj^xI=Q|C*lPcJ2f;0##9xm1sr<87MOb&p(&=a~|>A4Ad+MtJW z;ft#WKOr4GgsJg19>N*>pTz%WG$G22no}a!GC-^*bFYTvqG2tVx(_Pv0<6KI0hPmzUPlM*mN`z(^E}x+qlu0wHt`gKhA|G7LGs6^h9HWzj z{IwS{$9m?XkH7FlG_106!9H{liXQy1Ad!u!3`JHBGKFv+fM+$D&96zS%wIO?xYBK< z%?pT3%A?$Qsx&7ZB!^=9a75ZONbCZ^%CpANc?m@1gx)FL23uc%jqxR7bKm$6vkN#f zPu$b2K$aY~D*e1}fM(@EuqE`XF5V)`7TK7Hzs!_yABY6w3xjY=?r~#9%x3U#zRY{{ zn+SZY5_3(WU-Q>55P?Mjt|Kzui>rvge!@>=a0VBrik-Quk&$KR%|#FrGbPX5Os`>!#8JavkuT??_L76?&+%c_!K>ChnJD6GytTA&wDMvb z=7xP2;Vv~@Ng}~!9l(NPlA{1@NiKaItV74wBnK4gMVICOgc`MTg7M`iNT@jU8|Ytw zZ|1dN*%m@%{Pd@K0Ls!?9sf?rGb>MbF%F%EGhRBNbTwg8f58MtIrc$lR*R^Z6KXI- zl}N4UUM2DyYR8vi*gFl~sEX#QkR}F2+qyXooguoiWiOeG#BbfM;h%dAJF$l;7>sJ@ zMPB8?u`tMq{fe}4jnZ^&{6jsakDxw*Ffiq#vZplSn~^Ju7ZGNaXR67ljDDUUel<(P z2j+wCm55t~1eN})DYiQitpO^x?3M3!Tn}3I=I2CGgiyzdEJHxyC}}BjDi|I^>x3+w zz@N-~Vs=UkgWUbuXxqV|9>R*4Tw!OPqCZvHrgp(yJr`D+ctTj7?&iv|Tt845{k|=9 zWa(->5C5e(&=T>9?FZ~Kj@+2Pik$5nJN32Qsrk0r6Tt=!A7;BmFR*Ua`-Gt+FZCsG z+w->$u#B}h3~?Eork9klZ>9bR8ZsT6Iu5k0zL!8weWwkd34?b;{0-9w06J(z1PGg~ z%{O|?ho$6EZ_=+BeNcnkvV?8Pud#Aldt%{A#%-<0Z6N+q<@UE2=YyG&&Gj-E#H?ru z6)`r$^_9_owS|TWo4&M?oM#E=pkb)L$gpVF_t{ZIjC)eZmE$WRNG<_lMC;HKTfZWY z#dzlVSNUcfh8~bHcp*S*#=O#Q{0-Sl<2Sq4gIQ+$DIMAI2OVq$LI>fh(2?RsYO%-c zJ+_{FS^L;s@vst)?n3>nqkFFSK$fRmr?g7pS0--mT^!)`JY{3$0{GWCdV%v)ziND9#>8SAfy}`=)@1?x=w5*4F8cY3F zi@v6U*#^-Ry?udvrQcv)HN9Y4A}_k5bLj8U9fhHX(y$GEC5Jf2=V|O<=vm$B1R+Ii zTztxE#o8>Fo@>{RC9ERPrEBdA(jh*A>Q{}6*RM87mB-NUZ}jfZHh+YU=%B(-OKK=J zJbRfbBO6T|-4qN;C~+?%`T=pE@gV){vlKGpRc2z5ld&>vtFB^y>)6O-3>++h%7qZ0 z7v86|nVH#sP(liCq;UH0N_X;xtD(l}S5r9}Y_*QUhuiVP`NFO53?~2tT48eT1WqHbN z-iTlPan|wks>vVuXmIgoor2pp_!1X?);U-(63Co0Ow>IpaglBr$+=>6-pW4=4)%LJ z7_VE-d#&-$WKP9jeK$>W@J`V#3~dxH@H^BsG2$xr)4B*&p&Fqw^i!FQ--flwg$Q&? zf5t!A}XmoW$K)3Z9Rp0nk`Pq{2hKip{Tce_5WPxV%q ztk2`y)!HI3mR*r?@sV3x;R=7v_Q>XO@w(0Cazw)2h;QVvhC(D$_qn`%lK2#33ZV`j zoA?LuC8m{F8x}OoB6=5xYv1&csqR8i_4TR1Y3}}_j8E4(WqZ{T2R`?>p5G-gvDh?1 zBOZR)!Y(pZ3>i#DrZIOr&hmqcn+BPULuedFiaCoxx+)^l!m?kNY9# zRmywUs$whS|4?+MZ;~~SYl8aiW!BO^ZjmmM6_FWGjx`+nSnXtPX6pVELiy%PPAv=K z+GN+OUMA>3j!B7mTocfcmi16PwULxxC4PK z+Wk0Z?uag|eKcaCvni$;{m@d?B`-2zJTGhhx>(n#R5U}Xl;a#U49F_p2CRfju)c(U zu12U|YVN6&D2mHDV6ZHt7ikp;E+BDc04pv#U#Y&f`^Cxn^(vF92TI#2?VO@J4d}l0 zN+w$wOxU8JH;97%*u02fp_}{O_^Oq6^D=^I_3HkjSD#0I*ue%dJ1@znt`0QCoo~;z z5{Zf{xe!65tlqXQa$M``vwNUh6_;o-=#UjffB2c*y>Z8z*yHDpU=g-ncNI&N3SvXt zVHVf`7d1G9-IZ!K7stf|ADeA(3o1^S#6gl={LIdwmY!ZA=;<7Cgs8{TJPl~aL#4t6 zW_+D(ff;Lqd064uRfj!c;+0oLeh@?o&|0xS=uj1ZCCn(0qi$$}L`NRrW3`n@ufDCPo=Ote5W^udpMfhImY*1r>2+eKL}8&evl78I z-A}=40S9W{L`@OoTTYYXGt12F2weJ8kH74P6E7noz;g6ITG58PxCki!RhzJiGan72 zeOYxEST&L?x{K`-?cq4F)_M9gF$=ctEJxNPW(am%5`plke`IzXhY1Y_wLhak^rQD(JuvtCIqzE=q!M=wbY!EhK6sxv=rZe-k*XiP ze6xE#Su;)!j%g9hsx5y2<)vWHV8a3Y>63%^G1oU{ztMiypSzg?!5JN`{s&*J5Tu5d z_kC*(-CptI=SuhHAOy&LjyAqQ8nr3A?Z-%aUY^*~|6Tigi05-xGs#Q(ivBrB1diQy z!OL_-FEJ-_jsHfOwWglLKD+#vL=)9TKLZ-2k>KZ-{ zALy$1iablsIOde}i_#uuY{i9&zxJQRGb{Zw3eqheJ|2h6QyV$Ch&DVX3i-;yYRBOOu5Wy`{!)Y8SZ!c|!`+rIEN z?pVhz>UkD$x^8VW{Z5oM+?V;Gvn`ZOekkiQP~K_>MN9S3wnB%%R1Y5;Q7{($WWjx& z=D`z-iQOqouWfJt=zh$<5R1h5g^9Bq41{USfS($)%gx@-8QMCVssN+{iLUG*6p)ip*PS;RdDljXcTrDA3I;E z>9kDPx!STbQ|Cd%YIT2=0I%W_t?04xEh;K2|KZhfaUz` zwc|LLD7vEAoz`b`+#J2Om~fsP`QrY`Mxs%eqv9R$fmk1rdwWIeu>Fx2+(Q-ozek=M zFRbf}%Q&wru_h&vX+847Cvgo_P5j&WJt@tKZ^j~TS$HT37{si#hY@Ll^RQ6dvnMf6 zv{aoei)(gktOacG9l1biNGEB;b})Gf?QkC~!v&{sWlMGMlk?OyEE+9!&00@i$*1S9 z(*70WP8HYmP2*8V?UvNl;2U5(G#pHxyPYljiJ;iRmgX3K7r^%!LsK0<)XB=Xf!woYgehv3x)-WQ(vQtA~F zXmHDm+Th?lG=MyA0fMJG%Vlh?{a&Bi z7c|GAUbxSV{Q3YFU~$7+CcaRFxF#-2znUn(009vfu$LU)TG@00RD};oAEo?@?mQt7 z|GL^a{UZtR_=3)=?)OosjQi(c=a+56`?4>#wk9#9m?dcAaV#QR1L_1O_^mad?8EBJ z^!m6)-@SOyVC`!=6km{b6T{dAXbW{sU*^)mUi?KmRhqkjUYTI+O95aKBNpC3?x~6L zK~Ew2f9WUJm@Nx+ZGw4fEQx=qrWM@)Tm+9_ijNHBtbJe-Z|mOP{PdfO5B*#78x3IW z$Pk8cNL1(g)JR|{Kd75)e^Q|b6)5SMG3Ys}Qm@DyLN%GT>9z~8ACJNx429Ai=n{pe z^MxuBtrK=s(PZ%>($ECo5fnq8B+Acv5=!UyWx$p#4Zp?c1aNhH%>He|*$5~llU_Io zMl33XWYeE98cYnVxr21P9zA8*e=uU2V?Tq8uE!+kG3myTZ9E3OuQ6o0UoHWW^{Ho6 zo<=rlq^*=@f8`69SMSVi&aTHsHtC>n^IzRVKKDlCaEqemZDidWb-JK(hn|`|x${Y) zyygjIcYSL1k?>QPnfer(U4GgyJxv`A8RT!*!LKR1*ve_&f4+{Bt(YG1s{OrYxnD)# z%X+ZzXf}9#-(S<0`mH_;3Mms=!}_34?eyd;V)CsoMNee2!Yzf#+$ zC$CuIwVxZGuBb-Je=ZG%j|8Ev$AeHyQ3VNtNgv6um~`#RZ_`7h7}B&Uv$w*p+YF63 zC|=h#jxKuhF>uOXHObi$bdG8!I=^T&DJzzW#j-v>_}NGw`Rfgw zNcln%U7Y^dEI2(*g5Y$QWVkrp$Zr!9C3^JF>iI2Tmr9GH`Ea`qVX*pI`Y#J#io5U! zEBsm#1b(SxxbP3;w-JAW0>&zsw68$#K(Y%Rz0Tb}(T||Z1Us#9Nw##Y{kyN2)o*IW zlz&J@Ubqx~cVC40BIhc0v=qHesvt01axDVg@8h@n(x zF^hu*MfK#Y5IGPVP5As-u+tJLx)MIGK&J`)w*6m93%32C+4j#QRod?_xo-PC_-%Tz zWb)cSfP_r@U8VgMiU9J=bz*yHID_KSNO|gSKn^*Ov5H^b{4^5SMbBfBfL}||OXLU^ zf0wcri=w;vZSKeCOwHf%+m3_yjsj!lh(XWnoR&Kuumd3)DRgXhzew%bOIL|Ko1D^2 zZ&dK0S+n0_G}x@?psjGMT#g;0hV0@dv5n1SO&+;OH~!X{tI&Bl2N=R#zy^S8bmB1I zGdZ-^@9tJ4W@s}~UAj%igETRHlPskDc*s45-_i48%Pm3U1!A9vxuNu-;i3UJ><|GX za5R`MQe+)P*y@&R;9T@xIf4{|RdO!o8;$WNEh)>S8>^|Fd_uf8KA@8n=$GbpfN~Ib zIk_B|bsL{AExTK>iiI>kobE{73~FXCq1x(4=lo_7sg8N|Tb*vh3gw?--+Z5=54bI? zI~UTKjo*o^@4I}Q^NST!I8(NKWE;VaPs`{J94NhjY@Vn5R;T35;&IOY*sH&2-s)U* zCQXe(hPs_u?A2EL=0C@$2e+32_3YwMPr%e|GQ({%b(?l;h8B7_eHY7lmG}<4{G}^A zeW!7Rb0@*r@1h%~1>e{ZUEHyz(<<&Up7e3_+o2Qpjc%-9YH3{p+uFz`uQtAyFWy*& z6HFWVk$oh~jg`Ok?y%fG?IEzSBT9weRDJqcwP8Z5X)L$k^jJJCBN zHyK!7n=F580o{k=ATSSvg)h$B{&GMezCF6JnUKbc&=LF_361Ap76WqMG=ZDPJ2O7v zSIw9K&)4SfYWoyD7yWc7@>SzJ^<3}Kv>MERwI=>tZ$Y58Z1aReYZ7ysrAFd6nigFA z#n769IToX@uD?B)yi~?XHi8P>z>}71O1DKf4izS%;hW`#=OD7TyfV6eTFo2l;b3j2 zmOyO9qz&5cC~21mPo;E-`a9*ie&XLvl4!@P|(1+b$FT$g-m|Jt6U4W4hcK z%>TCSLuc-I?rCf8;A81mHF3+nlw6qVJg)@`_Ew8wn8ljL>C{{i+ct^ajWvPN719kA+7FJ(@vi8nl>1cW_$!s;I_Ih1^p;+ziSFp;%&?x< z#cVRs86UP*YG>5OJEcC8XeNQV$MNBZyIJ8{aL-YzX7T#Ms@Cd4+hhOZgOeR!KU6>D zug{fGc_|LZXYly3`g%vWVw<)9?S0Arcl@$+z0Xuim{gWca{5Eqv{dF;R)?{TMIywj zf{D8|Rv_MrQlH$<~+l za_TSq@9InYsW^3N;(zKblbZ)jxM~G1!Y}X;x+jBLR$hXgEFQu9HL249VR>Zj)jjpM z$0t=ftR8o;n~12dZ>=aM$_KXfkOuAi_wU+!n>ocD5I+2VK)w=T)b%<7gC4Do2WFc_ zA}VURn@O~*DnaL|y5$m6WCd(8pli7^3WZmj|7q*#u2S45^(!*|6FI=CJ})Z^((Y_? zFl}N@Ece(eeT}AZ5lC>eA-YOC<9jXXVLaPx!0RYAL2!1aMyB+ul>U$T@PDS4el6_s z54b{bmjQQ9wry8F{xklUh#&Qb`M*=L{rs2qg7JM)!ioQg|1zoN$`=~pzmu;UXzTwm zU-wfw7uRfmH>=A;EQGb&apPpQK(&lNIo~1nP#sU=d$&SIU28*A7W z`iacTwei;pLwh-x|5YH?d}Bc{(J3=8Hc}%{x;k|)s05uwc7jZEahWH6_tnNn&LV*4 zQ6hO}oAU{BB5!#$omWkWU2TF3__&5QeOGXdojlVs+*wrT0B_1oT_Z-Cm?sj>riRHV zx_Di5BQxSgX2f78UV&RX>7$hRE*Scpeg9|&M;h1;@0>b|G>if9-=)3)VSYaINVXF>e_PB6NDb7~*PsOagIq6_|XSYB~U(Fpse&i)x@|5VyPgYBPz_RsP5Pe1#o zm;LiI`{w}rr@!UEZ`25_*v46! zhBKH`E4H2SsZVf&b+S>+P1f#8m+m>_)?ai@=XlsXY z@nO578}f<0>4=RO>n(<14YP=df&3@GXX!6^Biq|ogG)`~p5D!pnS8FdFp%iTp~2+M zC2eNiU@b<7u@gHIRV*Nd-F3-pu=yH-QhChjg*E+Ns!7&&lD*sV9&BPprgXX#00rE+ zK9B*%cX5F;<2y_>>1a=nw<5Ra)BCG3c2clYOKkNd{3vs5--UYjH{atCuHngIHb(oa zm~e1G_yd=3GvlmWJ#2w~f~su)>DiM>DGCwafrXYu->!Nk&OxoD;!iAK}KV@P>#b0(GBA{1m(p3 zNTbfJay?Y!J1pYA@)`LK%Xb3(5&5pa({K)1(lKHb2gOwcnBjGD!Yek6!i3pI*E>VH zI5YZDkiE>BF@@3E{55Us)sC-gAnb@I!yF_GKO#zojfYfCGE`J(R^iQd<~9i8HOcde zhk#rq5Tolm4(Z^;-hdM4)@J@4QsBf6A!A74xJIX833$9vBFN;wfvY02P%f~_3-!^y zZ?yCGh&^=EC$-6APGo7aPs&Sn2b|c2 zBzx3PJf8D;qX<8O0l_ha(}VeoSsK9i7PdWedZDryAn zV=HPrqoAg`TkueyR8fI_zt_xt?p{ zRL`Sht*7j&&YMeIwpLN)U5{+tEH5D02D(ZvqrZPB+H>2rx8vn%zgOtDwoV}_ks2Fl zqR7#6*e_H1#@4ct60o&QbOP%8G1r(aTgxV>2RXwWl0=rzDAIBKavW`FQA&)Vj^=@gEE|626^O)^{Y5GG-t*FJS|C!?h!>QyLTc`r2 z$N)EVxvh0G(-tQv8D2S@y;XJwR}0l|@YdrCofk{Ht#u0AU^Q`V6pcA$Y;m<;mBSlH z_g<~0l< zTV8B9tybE-j66!BGV;W(fqR1d>6C0#*KT9+YtvHQT1Ay}h-TjN! zAPc&`lXOtiZznx=GfUeBmAAgnD9VAuU5uxgSQ$?TS)FUtas6&2Hht$j!+2Ik%M+zL#=XQ&zn9kY?93JG57n3)sT-B1i zH8zRgZThDiytO^3a*d7Vx6EQQX;HDkQcaAxme>>?J&~<7>tnZ3(c$NLEsz1S^mc(0qQLt(8kd;>}m*@InZ$c9X!?+}Phx)>7@c zr3+dAnc7j`{0cGRGAfIGj_NP6wald%p}lf0+>>`o5lc-re6c6a1ueQS4Q zlEWCsnNT2Kom1LAcOQN2spii=uwDOaxRQ4wt1E9|mik-#?c{tfdU9#xRm89BwN#9X zmzTC*#OI}+o*4-~Q{*Yx+4LK>lYQ*ax~gBN#ceMV129~sRI91)wZ!JOe0KQN6G}h1 zek-{$mJNLMCU#J&pLVwuKg-AB@`AR~=1n#kACb#@bl;Xeyen`U)gb*VdMrIn#+}HX zU9EyB)SAD6G4&2%^6>(ya=p^lHNgP&Mvx%~QMpa;LaBd4A9dLtF#~dAHWkpUSix+j z>2qUys9BSqiyp#qlEc|P3q^0w@$Ty9XmdS9oS_nqudC#L{7(^PD+24015v^DT#?T7ZWUA4NO$=pCH zb3N^IQB7J71=72dr>W{%b!%SYw=ZD+AUq!OXY8{cgUaIwZs`X{t1H%sw4x?I+Qq>w7 z-trl(e;o9#wsTwqf(|>Pjs2WHz~RU}m;`0e42#%}^;{!-e4MavyN0~1_>dPTzrTxE z$y|?I_kGC~m7|y<7EDyRo^R&*Ik`S8J+18=$&igrI`s$iqr7Nml;MCMEwM)0r|tV4 z>B*k0k~P|B!O*ledLH%ELek+g`4PQhh-#lLU*y_utOJvx^!Cpz;7#47OMeh*uCBR{0G+8%X@DR_XZ`UO|Z+MXf{ zMIgwP^Hl5;oJ4*y&uRNb|NR_K&X(9(B8gn7fI+-9th@Qqw$@&i81HjqEd2a@*SMEl zV_u5Q!IQ0r;80;fD^GH(>pN0r26WM1Tx~`C%!}=&1m$f%Q}fdk5-tM=@{*O!KTxr3 z*S*01lTeF37NjFJNse^i$hO#fs731Mp4fKz`RSWd*U!n%$X{Hx-+v^Jj~kCec)o6O*!p{D*pq8c*xg(;nmLDtRKwaf-5$Ctm(5d5UOLY#m!-i;dtD zRPY7z^kdhjpBa%$<#`OmD)cOg{JiVazZ03SL&Z*#=R{&Z-4gpon#a$!#MnJap}1{J z>?5o}$tWAP#CD{4+_EM17sFm84Z^DTCrsUqyI`G+JOxhLA*Lr8PVI8!Pnx@EaCuHt zmV75;Qi14iBV%{cY?$pNsX?)y@u1t;pxDj)W;)Y(T*re4osK@D`We*y+LPHoVi!R? zi6z&sVbk`2ROR~EvBGlXsaT2lJ*cWTkDt1t_iODW*fE$e=B_>>HE(hp&lAJWyOP8w*C~x4m{+>xx*d2h2GB*_ zTc=NuhqmS^(6;Ph8Gi?=Mav!xLeH8+$`aDHQI>ti{Ejk3xwG3-knTuV&VD}eaT|s@ zHy4+;53GzZZ%`G5DpODU>C^BiZ~r032rcE2KDIP}@k{x2+j>0Q?RUwP;-Pd@9p6fH zwO^Q59{GSHz2%V}J#L;iaMirF0T>sq_vGx6vCtf^);d$>>o=mXx&}orV@O`QtZO5A$lulO6Rz8gx4A8!RJIvU+pbUpYLdT$$c_0?rh5@yw3?4Bz~Vd(EhJ_oIr)bt0CzLec|orOeVy`r-)?z!43_PDAa zZ{B1bDJ2ap&g6l~D9Omv#ELa(CJgy2mX&amd?V%r??03%=O_49nvLvgs*Z_DF~}vG z)$&I+T@JN6mOO2(Vt;KG6=Q-Tx5Osnq3T9H>I=8Bd-?ri2{gNbtNpm`*U|27rH9Lz zjzx|_au^Ui(JUU{fs{Vr8E|VM@ncJ*r|b8%MB!+Cmgn-eV|TrlqOZ$*B!A8BA=hmN zV}nvNq=gp+^R|R_#}jif>VwmNxO_ zX7$K{|K`c9_@kGtBbDeo@x2rfdv~LFHcze<*fQ{94f8e3(csoFO~Ygj=V}`HNnsX8YeMDRC(*-g>F^gki5JZHZ}vg?xlV&jamO^*SD1<+mklN8y6JH{m>k+7Q+n3z<5Ex+Oqb@yg|WvwCt;wSy-vBG_$X|DrCB`on*&;ry`9XW+19yZgi{EPbORgIufI80@-`28caBvBW z%Fxu-_t%GNwbY|WP%-)^r`>DRE5N$>wcV_Se9pRf#ysvWVfaJWc=EBo=90rr45`Ax zMn-P43XJj22#~5X>L$8m-`=>o+e#nA)}qyA@U*SsW#p?lmEWu5tMgSKM&EcB)p^gr z$P=NOmM;d{!dH@9dE_%U2c@t|x6QYx;MjH7X zNpslMM*pBtKa_DmmB=Vv$})a^dgjN#PD}Ofg`r!e7&^n`63~G&P_##FiJ_B zQ;4(cPpbd1_;u(aZ%srnn6o`F@Qr3VOxyekn3evhs6vN{)uZ(o5^%NU?&93{Huq^^ zWj%KdP`j9kROC2fvcGb8E01$XSKE{Jl{J!h^(T~xrJD6qR^N2OqoU7$zL)h>^QLpP zjQ=LxjQa}PRDVnC&$-&J7fB|c`=@`jnZC6sln>kV`%i<%N1M{qf7cZ$_*CVg$D_#M z>Vfp7pC{9AyM8mza%!Z4Xs?djRYrFpLwD@h;%bF;`AK#02NA@V4S4^eGFtnQf@8X1I`<;%Dpk_nT#it;J z5&4@UL7ZXP%x@1U1&9vdZA^J#h&>of3+G`-fu+{%Jn=ocym8MP?~QUkE;o1zR`wU{ z1W`BK;MMXN%zyrk;3;h-1m{e-Vbc*^goR#kwUzEsp%KV6>F3`Fy(&Y(NW~#H5%Am2 z@0v)9lv5rr)Q|TXkJ|(z)6hJ^j^#R59s_|c;wy3lQ9r1!rmokoMT9O`;DUTjJ5r8b1s7m;0KI9gmb zGFn59Oe-O5)_f@W)94^p(4MwmMM;9|#v~=|;II@`?*c_$^+deK(ND^raAtl#SS>u#P>Kr4@Be?DA z6XJ%b-z=9!48msalQXu9bV>NkY8Hl`rVM=HbVu}L6amU7hEK{Tc2}c(@2jHzUzbm} zALE53T8$hXmR6IsfNoX_?v^X_EviTqf=W;Y;@YAQLq|lPreVpP&uijSEYa8bURzX7 zt?Xhif>kRa&)qRW~hH=Uaj<3a6R}JwOU=)RELgQy)@I zsVlhE)g(OMZZ4aRBt^6&sx@EiT+g^rr6(k4^#T4&HRpn zv5)>g=Kboby}BcDb;MXVSqeFq3KfC0|8$86`I_Boco88`xYe9-*yS+wAdCk)O5-mx z5S+%vcLRfyjW)QHYBzp9_=f7`T&fa$7GC}vzEpoUMyiw(!0XjGuAMS^C7kZ&7PqxCVm~CZF2Ae#33vP0ZZRIC?YZQZxAOK$&$!#pRr=l z_PXJFWGj)WA!JdB%2r`MZq%9^X0?yy?xru)se3(dGi#>mgQW}Ia<`g0vcHrU2QJMw z%0zjXKoA8R@~kiOcyT83MC8v{fma`=(uurUDmpBei|v;I^RKiA0@p+_b>%4&^AoMF zyW8uYv|M$T&R5DP({?Glf*jG1Sgw}$^W3uSNy+m_EBZ5?O6Ym!_K_)Eri`DWA2Dgh zg9}>T8>}YR$t#Zq2Lwm+zjb}+h>dwtbD|8%ctOPn-;e(1-_e!yJYh9Mjb~;^O|740 zIYm?+bbAtcJTqTk4Q?j~&S88;jF$IoJg^tj%L6YsUvd*_g6#pi;6E@KZFJ{sHtgq~ zHf|T5npaM<{$}J=4uxaMb=k^ZbmwdfzrJQbc^k_CtAjl4N(WuW#vPjDr0BqEjciy4^Uk%?UwUYmj}6aPuH^US7KLczB+DM%~!L7*is#EqR&Kq zj~L1MQ<{JCYE5^^Q0!lcXWIkwhcZ|-e?BjC{4SSSf6bqJLbr%gZ+qYfMf>@@;AtE< z3cbq#B^PI0#GJtzArfO(I(irl5JE}ASl7sQt7?qKcqnPau0bwr0B?-LnyvM0dBSvJ zYdwu$VjPKy-fz^O*R3Wz*HK=Gz{eVXt{CI)DbWQ(g~V44ZNi z$`yHwM`c)lGCGt2-S*%Wc0M%DlqM!UZlHYZ!vWH~qwlL(N(O`yt1=`pq|xJ#W=Cd} z!#4eKcu|Wfd1FKMztV+#bS`0CR^z3t{M%Qd0`GPSL+lKSnR%ozW_uv&YM+rOpXSEM z&u9^q3$xpfkkjr{8Ik4WTst-|^e@Iy`L;XOHSw7szY2FvMgNn-lofJgmv~_vt8`2V z9?eDxtv4a%jv3C*QC5x`pI;=HFySB&~P5GyS(JR z;EBxYT2#|LGRp6Kso zV}_tY_3d%Ska3?xWxq`7;v|sL887;v?{Ko$80PhbRxiBml8Y(mokgzJ$B~DT55=X3 zM%h~AUPdax#o>$80W_h1N?6)?4V0Z!eaCpsoMSfD(#rC7A6Duo^Y!|ltNrC7sOkk) z*O-^1N6-=|;YVr?c-P4saJa}t8cpOas!x0#Ma>j>y4tTG4)+~XMygmxiF_E{A*~4s zsb;1sJ-SY!P{u=SU>0Nk67>w5Qp@fMZRg0oU4>}Rw2MMsndb(4Zc&qiP9v#!^;#2y zR=d0{F8R>jKZ=`$FcYPvH1{bWLET0F|``X(R5` z%2M|r@&1d8i%+B=g|5hJuGTFFvm7vWz*RD1BEA(aL&`Na5)R2$z$s96Tzs zM;@=a=IuR$Yp(fx&tO}toR1*Ao|@5v_dNFYfFavzN+V_V*ok=4Uu3jz>7J0%TGYIN zmrGwQl@h{g`-P15!nqfx@oxm4Lq25cAAwrE?v*@4fKi(19B@1emF zKltt^Wpv;(r305s2YxqrlIpC|Zad9#X^jh1{HGzk_|WW=eYpr>R%d*liC^v)BAaYTIQ+25r+uj{Bq> zS$Rrc3b@?u1>#42w-wHLY{8SkfxHBTOoo&5e)pKLxLwm5oa@~L(RxDV#XEA3?8|f)I z$#%VbKbu2{B97L-GX_hxV=x7H$kwg1wT0!dy(wRPCt=hlO+d^yGG(jHID^L>v7_)o z>+(dNmww>Mc@|08t_=-@h4w}^@t)Uj*%|W(^UX+4+iEq0j4YQnC>Nu+IABMwka30S z39Ai13Z;2ZaYbb8G1__lu47#T@Z<=V?fRWkZ|#Ac@{;|wmLEtW(luwbkNURjxm~Wd zx>p!_%NR7%{!E=`W}xSt^8m~*tkv&tNzF7L2~FEok)3uB+mS1swo=$iNT>WjYB^gYEEmJ8PT43y~Y zw15wz7it2@&BbM{M#v}A>{Ra0mAOgU6ssvw3kHyDLb9?ST8uVL+oB~cVMH|OLhp$* zk-k(2%-Q90eE2W~$ok{FxfpAoAZao|#HY&#u|p$kKAmRYGnmKs{!T*e18*0Z+sZIK z)j3>h0O4GuEnKcxVy&cAj*+(TT=Ag^wNHNIQf#;85nFUeT7uQVC`~5_OL6HRG6yj= zw!ljrlOd88*jqJ7|xNyA;jD+?2NE{}Y=>rB?ip2%me(}q*jxAwT(og--Q z+|_D)N{cu?6=$n0Y$cAnZ6%x3tS@)OU*tl9ZZ@9tc3o%mL#o*56BkJFTDnvFH=2~v z%Utb&JQ^3LgCbiIA=?};sRaY$W4>xX)ywa#WDy9gM&)S*ohV%MjSa!Etx0dsPKapmhtZ(WZ`AU&s zba`KLlP1D297r zBb#U0b7Bn)5h7>akl1y*u5d-MgLyvsGQ&~q3K`cU(bz*W^zydpJz!gf{jr_Hu6bL= zj3JLlD(tbxrQ)@?sy@Vw^aDA|avh{7jjFDs;$m&oppGSRK32hX4ts12c|;$2OD*<| z{`F6+zgClg*+0MX`b(}M)XJ#RmoId-RTN@mqi&AkN~a*-@Q~N!M@y?{*?+X{x)T{I zWU4R+3EP8n(8pr5!q1pY+Mz>vMXDV9;+??v^#{{;oo4b^dd;4>e+_zV;hSj*rJSna z6*%?~B>v_Jl16Z{ldqw1?k3dZjy&fX;9{S0KzYeyt6nRQ{K+$5Zee-JwsPClw{bDt zj?}oJ?)Bwz&`-|%2;ZwpT{7V9AuDd6&u^ZH8up?sEPLJBUY0(3C_OUrWUQX4#N<~7 z-#kljh>R1hxhM*rwzIeS=$MfO^sNR)maFXLku%C8HF>*!pzM=#?5^`h969R*C}$Mf z!YhQA$Ox-=LJGf`m#9Y@Jr92+fKhlXD@8t)Q(X*WWTgrmdfh{Fs58u*+5FdD>TSrU=vZ-(&@J zrCJl|IoOJa^oHMXY~J?3mAOmsJmq&lWyO3Z_=CtSaU76~odI(k!N!Y}w@p zH{MO*Wi`_RTt53wZ1ZV)?+RNQUT zDGNp)S44gce5_ik_Uu0ZZhT^IL8FdB#WwH@LCaWxh*?BLkCSpp89b~uWYHOq&Qz}r zu+6X3120kT7+`Bv-!`evlWUT5Vy=>BZP(5uL{`+EcE>h%HB+hb4_u+5^}z4APj;O! zyV}WaG?RimC+aELYP{4qDifgASx!WrT=4l(kLIN;5QUp}0sHl{7SIK|?SK_X)yCN$_#=a|J zLW938x`As2QrG*kb-uc7FzclzPUZ}pN_QxISoG}**VgHFDUz6Lwhp2TGcJp%Xf}=R zs*$MS-?ax%Gs^3Yi5hS z)-w6qr4)k#7+n8PD&vahcaePbf?k=+1`btB9XCLreeyGe(1qanZ5_Nzd7Rw~7(A!h zOZxE-_nPM)An8<|r&c0ywM4dsWq=aV+rnG;#>m9}7 zGU0(La=1#Cj|?3dlap`eI9IY_Wbkt4Q&-!Cbgb7yAGq3%J5$lW9y||C@FafkIzC0; zWZo`0HMopr37zd?i4!~mwKpf!>mn^tl$o$1`6eF^SHZ_i!Uu$N46{podomZCm(9P@C!fMACbJ^pxhij}RHe-4S{tL@;lo@ zwlcqxt1BWE_AOg$t@P2h<4OpU%325m1PJ$BXm^tEc^4`bU)r|un}RUX1-p3j+*L9( zFx>dw4ZoXy$9sshjd`?<=R+SPa|r$-COwL|GPa)@P_Ig3CzSbRAg^D<#z_9{lRuMn zglx@@btJSJ`625+wHQ)nIPtNI4_L_5XNlfKCuez5BomNb7U$u?szB^SxFe{rqO{6( z5ra6RyV^L4$-WcsZ@meuM_1m>Sk3N@By0TD)i#7ypHpmETH9b**;HLu>uU&}5%60U z%$ufuPxCkVrdL%5{Y`5u?o`jkMMdMq$5|CvzSLjU3n>WDChwG9wb)A0(85>1xQ9DpB1HG@`UH zYGE-&ZtztHv+yIKS-hwD>l^)nTKaA>H0hU8U1pV5CnA`QPuK1|UxU}zRPOis>XNZk zS2cRH)3>s=+BdDPDiBy~bSq1iAev@2Zwe+uMV+rHTj-qNaso^iNkU~~FVw7+tz^J5 z8=Zbg%XogHw<_rKB1|3VZuCxDUe&NH#j8v@Tt%>|!Mk*glrcf;@l~z#Web=}_w_f- zZSn;I31aOxzo9XUZ>2v}E$vjZU{VIte9QfzfUn%YGMT;d(Zo)=cOrg@|NO>;?{t54 zD4>dx?xhNm@T#a5K_?y+V{@y#Y5BSv8bkC-lABi57z{B8Bm!*-W{9iS>q}{iN#R#4_piztFo#jIu4;{hCk1GDlA70- z^i51;rPaaOm1&J85#;nS6&@&Xp6{}dkMTVzu6e$IFPMm&kcsBB(qEM#CwD!QXJSw= z+N$^^`nC3xlFah0Q8R8LL6J*8PX?LVn%ZhLi!M$VKw40S7%m9aCTnkQlfRlqp5`YH zrPVSAFcqctBR%vbq>vVgUK9)kbZ1PkJ-xQ6eif69_J*V>Rd_U2pRXaX+#jrLs$GU= zktSFr>Lf`b&7@al)ryqbP5K)GH3yV3qgz(4Y4qtqWyRt$-Rl-tsOj30^eAm?tTRMf z?rR98gv@BFZA^J|(y11Ed^N#LKYDC3IYl+EcG>cNWU9j_2}@HVm9DN06lFY*%Xl82 z@qAXsb8%ukrTDtAZqy1HQdcbYCC6jQOAoI7z11*FF|)*&=|^z2)hn_D8Ffj08NDz$ zp=A0QHDu6bh8ok1i($J?#>}+j=nR#9w19?XnIW^$Jr58>By-|TORTi1sY;Tos7EQy zOwVZUiC&r()8Mhvw_1kL%&4>dvwhV4Qh#!Gqc&0#FekZ`W|t4fR=!=ZO)?=KBb-p(lSf;Oie32WMNZnFga?aht2aF6D_qxY6IB^eOR`VaXWQjJh+((*n|>sFBHtV-Tl$ zWn@5c${E>xO<7`;hJyaOs!&7qa-*7M3KOnU22|l=aoK7rM73TCo$FuaYnoG2lcw1u zN?Ffz?Q_-!(DS4c4gVQFDQ2UuDY&M;PX^0Ir*tvh*H+IB)g^>wC;-VB*+|Nm{rmZo zsh$Pg4K=cc6z0?XGBTF1+CU>SbVh`vXGV;)2C#U314@&3oRL$uu<=>L${MPcs!>B2 zOsd3&hHXSi`ctJwef0~P+C()~`lmOc!}bfD;ji>hWy#wwz?d7;bDz$_tdfOI9Rq^d zf=vZp!kA)2wMdU76ML$Lksd0F!GS}aq54LpcbKhE*PYY1G_)+eZ=?mJ^$lt;WhhCh z#Zs>~B_L&35)M7852S<}jImArHCe-;lFl1Ie`u&qa-Z~DoYANg5s>Cozh5R9 zky65&AKAR2rbuU*O+1x6t3UM9>-<$_5mM>1`a@q4l=hv4A0xojq7=hP6)J7=S*%xZ z>3(WmK)NY4wm8|xQhlWZEo%}BPzL$@U~OHk8r@RK;lz)1fj*@EOq-V7FlTsbm!=zc zu#U)|VdJt-XK?OscftZ={AufsGCtUywN0$Yv5aBm(WWE}Nat$OG#geUW(s??KUC+n zH(;$<>a*ARQOv~*Gj1HF7XBD|uxHp0N{MmDf@S02L`He$s}ar~^xId-e5~U%`Ia$F zXiF8=ANfOcSe$D7_Iho;;{k(JjbUdRH_j}1DU7oYw^u>Gsw!Zws-tgs*Vy%JMjMf$ zP63^^s5c6=MQ9ISEL@*?R8Kh>Bgmp18^HC}9)X81HCKrE`NAVzx~Z?;#- z*Xs*X1++@P*c#_oOdV@q3X?{EQW?}}OYHa}vmT8pQ_7z-CTbPWUU-(+BlTa3H4)v3 zB4-#Jjb@u_bxh8`nZ!smCB1UgpVgTpX1h&E#AwuTDs5a_a_xo1V(XOtmuL=2x|&*A zhV#O4FHZRie!s;hlI zY_nSGQU~Zo>HV>|$mq7L-^^xLt<8c`19PfFb)kTLp3%s}V6I0O_7$jKRe3t~>Z%4+ zpD2h8)Vo;k)L4|LuMGN7B0Hm#(SOu{B?FigErY(nPw!>xz?(`Zyl2oEvet=(Xt~lr ztC#z#R|q@f%+mIYXXGAa6j{o!DO~6p&qzOoE+ES{MM<~Gz;Jz^z0SzcgXa{{Br2@x(OUQy>8ga_NY2dMbKAO zPupb(H#c%*)52_x7N&9;0Q3q@eqlCF(lYq#U4bv5Gq!(39{tiY_o|#8PfBwA>5Pd# zl_qO?N_mtiC7rTgzJ@B0AeY4W>qkd2Qf^~Iseia^ZOk*~>y#|}rISG?t8cZo(b@J- zmkD3Abje!})0(hfx=he0?Q7=fX}Nzov;BJKXu7{CsiBehf%2sc6`{sP)~G)3LMGwl zK&WE$%U>8YchRP<5w$BjouQbJvsUs&UFEM|dgNbf&eoNFLw6)rKqcFs-c)2V1eKbu zp3@f_!|j|EoOs=x#WFl3vIRL$B zGB!v}i*mYrQqnh;6e)~kk^2I+xBN{NjlOCzm}69s4kRmawcl3h*VC#|&0ij$dQqd- zVw!Jo4il`_(R9Sra%JS3h-We&g=CotA1n>1nxM9F=MndkuoQ8#1`TKmP=n+<6enY^V`j{^3vA|?WUyr~>EX9)akeOjFW(fJ;TP8|nGtnsqs%P_RO zs*!aOshP_=%F!>q@=#r{wz1Baq(<$}LT6|sv<tS;i=or z3BI$?NrzMlr|eGq8`M~2s2Ew(&7d!%C7B9IR{DAVI-j{0pTS3F$1%ywbTY#$eARwd z$xUl?bs?ryZlxY|`4U#^%H^T@r4^hu5X(d|+?d#Bu$|Y)o|2qaFb)`K2F-M`(50PE zFv8P1pIL^~dQ0##BZN&o|-L09Rk zZ_G$5m98}8tz|`^4c{_4n;B-vC%INIh!2#nIwN@C1kG~H^RW~c%b~P;oqbx0CY>6s zDpu5*M1c$*O}es%m9>bio>N6xGdJl>MO2?%m|ojZ8(5xNKPhtwUEbJVO=;?8I$7zA zicOPma&AhdH`}+0_$jF-+fPcm9&Emv&6NIA5n5Vb%e0p`W8qJA7jHuc^K^AljGH*HDW9(>K7)Edft0 z%$BXz_OWc~s2O=dZJ>6k+7pmW6PvRyjC4$uQ08hm7b)p5(P048axzc%lxnlPKBpihOxr=xv{XIh z1|=KGfgo$#EOfK|DUC!+D=VE*Mx}3LOUIZZ(-X^*UkZW297`%Ou^*ruM!r}f^oa(= zVwQ9bx|HOz%SGD<45LSubW##9_*0EsGnj?m+*D-fT_$?;f%uzKm%0-w1Gn1RSLE5` zne5+b<3I{~x}K+oYEUrHic*$M+0uhQbqqk%T=p*yn6FWfCiwyB`n7qXH1(u3Iq3r= z`bdXPE}g$*Nf&D&iEvm|sd+4=yeV{g$kU>i@z%_jlQUT(P=&I;A}5>F--3CmGpiP) zQJ~ZS_LUDzpGtT^$QSZW4{-P@_qlmClgs43Dv9P^S^H zE z5;+Q;*aFfHPbD%m!u0{@H-!e zSpB5gnihssd8DVGjXsfqAs}7;^my?9mGa3(e<=Cr(^=`1+4xb@a|%bo`k~OJrktJL z-4FPzsyno=eNqgV!i$#f`_p%-z4vR*BH6lrF9Y3CdhxtjHmOfT)k<3Z^9=bJ(d z2ifv3ua!6Q7IG-Wzv@8ck^B#Zj+ciTIZvXDKfFOmyO9?y7zYef!GY5MvUusG=wA-4 zcIX!yv=vL|lv&>Xbm=K;dRk1%EGzrU=~QO^*$;!J((3f)q0+7Nr6ieH{C!DyA}LL$ z*9R%-WQ0@uDS^g0(*%u3M5mKZXH=5gn?kASFk^^4Atg=fsjf;6dK+74henr7Skvnb z@RVeA!IESKpV~X4F{MzM<X06ZL_s!>z@w z!)?IbiQ9yG2Dcrz8@CrXoVpu@8;hHS8}XODaVzeNKktoyjEmuR;$Fu61@|Ow6Yf6T zZ*f1zeG~ex-M>Z#w<6!~!xL(}rxaVbC0Y%@3W`+F(R z*YJBa&X21}@xO%MmAF~BsVV+uIwklOW$`z|Pa*7E2MIUn{?&LSJPgMTzY%=7A%LWCW{ENYyMh(|7+UMD(a#E=li-&{#Vq=BI=<6HxpNin}9nLcQWocTmfzv zE*JON)7T+!@8RCWHEzcKfh)pI!Og`j!JXNNMfA*oude1y-)f(wX{luu|14(&>l-c0 zgTcm$XP&7rAU|q2F(Y`PbH?Inb7oI>&sgl5Q(k5{gR_PlowvwaZY!G%z}~(*aK_3e zK}(%~S-{ey-6Lwhfws4|a-%saNcdrF3E3tR`n7~+XNu*Nhbd!bPD3~0T5V7zkt?{C;H}Q(I zl#IV5y?(Elmp;>D@EW2Pf?XBFe1(a(4ZR{F^G#LWKdh2_RgB`Lq$_Wsawx39XD99S zG^Cyz*tjNAk`LJSW+7!aK{4Wylt%MXB^N7%>KpiJp-srk4HjNa^RHs-K=!r+7G8|5 zWkbX759$CX$7ULR-r1b(m|MqtU(5Y<9Eb?$z}akILC!fV!=r+O1$Dj)LjEAlClKVQ zhB~umso{8nyQXY)u&IjnC3{HDkQ~o4qsdDrRdvb+8L(8#C1};MDWq9C)o!udd8OJ1 zN@XJ&lA}qSk`SZ4f#b2hrZX&4k%BK!&8bg&K;9eS+%fOp@fN0ffj=oO-ByEsE=RH> z&1H0g6}~n4m;Kw5?c=|DR*?lB)k%1tov?}aQ!MJdiM>XID)ROH)k(rV}}2>tFzOY zJl&8HZa3l=;=kmoeeo-QvM)a6wtewNFrWL|1=oYOp&-yo{Gg%<@Kto z-UtuWuI8!*POg(lQ!+cbNJ1+KCchji;)t_W4r@_0t z?ozwIk03bUeRd~bot^2->SvD4x}`s#Z|$@avu!W zjmujEaC6F)r`XYy^ldWsdY>pqcF`FX*C})pPqA0kQ1AngCejo>?IN(%}3#+u2(x6+AI>nxLxOB5fP zER~H?-P-IkE9T7RTIp(aVAEb73aIObe7tZ^QB9>=B*br{G>Qq$9UuA-O_kQ$aQdp{ z+#3{Vl$*1)pj6Un#1wvZ@yvj~VO$Zf`!vl{n&G*|jS6K-H2uT1zbQ8({M=;xsi9g? zv<)&N{H!^lrX)!si9J{AbUrdM&JD!8A85Z6ri@#REEk_)@%lq@Nsn>m4krW7DYkRe zhSy%xL*}Ojd8(S0@%lAhDG`lmMwrm|4@^%}NOWHP6IAij0#j2=2~AHjC4eEv$09?n z>{EZ7%YtRvwOm9aT`}>Sn^e^WR6bt!k}Igx>c<#eEEd|TROG~os=rvaWr43%r zveeYBu23rp6%$1XF_;f{@g1YhPOf8**@Rd=#Lu98PKfGzDQxbOMt{inU5HkZ}QL-}_ z$&^pEoR>?BQ_a!9IxaR+J+5Cq@=AwP@x_-Es{2XR+c{&@B$Se`8Yfb-Jy<%mG*r&E z`BsmSOM3#riTa64r5a>5qscV*m<4!UFiZW)tuKWv7RTCoQFg4pYA96#daO~b$mk<; zs?&cWzvL} zI-2s!%SVD{@eazDq-PSU*Cn%yRSzOs{E7eP9J@d6%5Y0~ZZur;@%!U9;BLj;f!mCm zV8;pK?mlsUyvT5y!EN&Ur2X+Jptz^z?vL-peS{l%0da74-0I5x@e2*t4Bm=ckK4GA zG;lj{d3@fo2saY9`r`fZOK@{>&A2_dC~oIs;^3adMRBer#4X{AUh8qUM0n3St z@`eu`F~qXyM9ZQ@mPJb~i)t*38Z3*NEQ^AcMIp--S6Z&HjI~^RiDj(aaNc|2Y2hsw2@b6Ke#2hJ9>x@PI!?xI6Gh1S&!R@+ljmT?fvomcWImN5RNnJ6QzK6 zbJX3~O{p4kw(u*EVF$~=L+gne_h`ReSN&DS#LH9lTxEjZ~R%3 zr*013R94tyIm2@58K+uC2S!(qmaBT%?!fMD4@dFB{!R4|zQ#Y})7DkogV+$t?wNxta z!lKoq8_zWVTRp~dCL2#@o)M61?M@H)>Q9#?r5M09xp`qKT*}shaku1n_9+e)KF-|y zNEdn5rymv#R_`2)tvc)jA^5`uLw+oHba(w=!SDB7s;*u;`&ZR5dH&@s-rEGn-|+fj zf}I<;uMzxK?8TjeH@y11e5K2Bn&*Kbf`43l&sBnhPv7{S;7!Lpx?a$m|KM?gAKUM~ zRM2(VL;oZAX6Ykg!7F=SJ4SFXq8dKU*r_ z0JH3V+V?%dIg4@%1YfNiR4rIN+4i~MKSt!qw_7bw*&EIi{BC}&N3gea$%}$bmo58+ z;B&nLCJD~yvCb0Q*E-^P!4>xp{gvS7ciexrVBM|vP8EFV>4#qzobuVGI|bjVdu6;} zXweSUfu0@l(sp^iX!3Kv6TGwN)sqD$THd@su=#?QpA!6L)wV|k@9*n6LGYyR`xXfP z_?ACBD`@-GA2$l#wlPu0%P*AY-yK)Q z*ln>)KD|ahrD$1Sx_zbKpvzv*5!_^d{#LFw%O@WrD}w|G*%@U-drvGr_ZZ zHbw=1@$}%;g2kU%Y=Sr5G31AWBX2$IEy0IJTza+O>67d81b16!6!}^OXIqwjEcpH{gVd|fSNtmHSb2V|FYj8xh26G)2yS`xZlB=X*n{5? z{M*Jy+633$@X%ht9ml<)?(K4){@Ri9{6A}7SSRT7^n4+BVb#6mf`7T-{)vJ?%cfrn zzFqWik6`JqcFYuf`Ic8E3)Xi(*D3f#-%BqDUK*=abKKrn8;a$5`VGteOK{u9C9eqv zPPaM*|9aejvji7=hW=LY>9r%?5S(<`z`26IEzMQ)Nq+vYN96fB`|zg)N8i7Eq2PV3 ze!Jk1o*Mc3pyg-1ReupY?6Wt&D|qYEuc|lDPrP;8-SXUZ$IDvw1!3XYp^gjfLzx}`f!T)&vo}ggKj2HhV`1@7Q|5WhElV7(A zwtRDYK=2#Gs^1X|pXcom{Pv~wBLwgG&ZUKN^3SP2s>8FDKz0B7vc-c91M+?3;XhnnI%42)>3+_Da zg^1vHE`Kdw@R^x!EEDwac<3|1&pv$QM!{*1Jb0Agi#OiAL@@fxmtGRQ>gMNuF4+C} zD-#6geY|6i;NO=${G8yjg`56U@Qp$DpD#G;oO@k@ubnpH6+zFjLw_&$$;<)g2rjwY zS}OR&hf8({&fl@@4#5v^Y#1lF=8@Xzg6r<9`ftHwT52{4-u}FQwBR{!FP|rP%c|ke z2o9Jr>|w!&zL|TX;F%{6oG0g{*Nzwb^EV&4M)2a3ANoY_tyOpX1y{{@aHQb7-^sf{ zu<=q`T<}ll4XP1bG%V+E!T4>y?+e!6wRDf*3-J|If@ROveN%At+e2>`{NVW!FAG+- zSZ519e&2u+!K#y&{aWzTZ!Xy;SU#iHE%^GXhHneby!5%d1h;?ZrB?-OhV7Ul_|bW< zoGVyy*QVbHK6%^2Zwg-h?7cGtWAXco1V?@R$3F^w@9{tUNwDbV`zi$g^Os!?!GY&& z`-9-kgI@l#;FyJPRti44?A4P5&$ztiKEaJMtGWeqk6nI=V8?0xQw7g`WLTHr&u<+5 zgy69|27X7d{lnbT1vCFBg>6~yFU1cA=6ott? z`Xc*i*Tm7~6GvB^F?w{-IiZvw!yg(lx#gvkqr=WP{M)mq$KwldkKx|N4VV#+pM<*| z7sVC2;_(Y`TXB1Ec6U79j{7q%XC|K?#&zKeXT{?;;x^$Xc=*OJ&P{s%3MV|@Tpo`X z;PP<4z}Dle``O-9Q8BU(98E!rP*W#Wv!e0ZYEr`eO z#{CK>&)Y6YcTM=0;C^g`cPxy@9T#fXW#9%djH|;{;+(i*oX{%zMeu{$eQ`YAgX`e; zB3uE#pZQKQtquvxaFT~O(?9jM>F3ReWBLnL;++3x*NYtfoi2!s|DDci)N%NtWL--e z8jCaA(%1N}m4y}A55=vcFI?kS#c1vfS@9^(rAjJG&> zZU$4`g*->`cNyV1#|}8J5N)d$O`?}ipgZ~9UCTQaXinR~JH6=t;JRw`hf8_)WEJ`# z==>gff#9u#ui!mG;#upU1B2i*f|v1*AR0hr6YmUy9iSKN2E$-+fb_whAnzK2;g!4- zax{7|SPb@pi@-i`E$CRqJ2PMZ7V!oSD+sK=2{8}F8Yj&;1}2zIs;56!mn`#ghP;BYh?$9nhyJHSO?-%WetePH;9 zJTt=={|NrTAh-c6xRrFlF0c>m0SnL+ihqn8z;3V(>;cz_{|4y6UT`m1a2xrdVRruv zI?&n48Gf+uSCkj*_%(c;48P!5(0K>-0v7xRxq?CPPO$5@(2M`?sE1QXA1nqt|BHG6 z3+|%4U=Z95_JN}ciFYsQfyMWc9_V}!d4oM*FBsg&v&4T0KE@y)a4c91dO#;w2X=#d z!9H*lnojW}qzih%AlSnh-#fwHCrB6U})2JA8qaC+v%lI+u8$6D&Rvda&SR=s_>o4R(OL!EUf%0_mMX`d|;} z1&a&!#lzwccFOaq@C8bv(}#Nw*j}u=^bHJ&$;$@CAmQlpidZj{GN) zFK6M_f(5gvKUNw&9{2;TvpFjS1}n)&Z~^C1&nMl5@C8<02p!mc5p?2zF?3+pQuv>O ze7vL&cKaw77!Du@R;pc~6D+u#e8Ec2k#&jxwb04)_h>g$kt650LdI@kXa;moQE#C4S<(Z;;BLVl@^z6O=c}HPeg^IayTIYJ z>mG0{*avn?dw+>=(E2j@QEwgK2C2VSh!6I>hMcKC=j+HBEO>KYe7ijFM84FY<1OR| zR=&+M_1E>zzWAM>wU_vy<6X)l_&3s-41c>w2khNVK491T(1Dd7LI*lOLQd3E@bB~! zuw<+(b^GRpjy+>j zeJ~7$!A`J4!oe=E7wiG8GvRwL@&cV;CFli%U>NKGyTC562kZfR!9K8HAM%(*zF;v} z308t$FbH;l9bgyO1@?ixpkqJzdY}g#U>E2C9dYCahQSW7)3QI_E#Y7<*aHqPCtmLU zxD)h(Ua$iUgW&=D<6U4U*aP-}d%*(h{X#xk52-_;3BXKTnqMq8^B(06Brz^KfW961PkWD7g!ATfR$h$7zBeh z;(=js6Ih&&Ji$(Icm;IeSkQ4e@xWp*2nN9pumkJ@JHZ~X3+w}nzd^p0_=Ck@!4bp< zJHQ~=18xBOz;3X(fP6tGXq`{_K?mpsonRkW2NoYmz7h_0fnjhv*b7=0KnFTN>oG-y%KG32p$pz;3Vy>;Z(s3YP&;{Klg8ymo33h{{zDqi1?vH!G zo+6$XLq8tA!LH){@pYi{Y|@cuaJPh?OZk@Y3_1l%C?D7hc7oQ4ln)GoW2*?C1mB={ z3Vee-(+CH{GvEX4n?-s{iRU3bFg%xXfE{25=$sEd*mn{1p!K`ZSHs5=mYuo&D8I>F&y;)7$sFz5k0!8))PTn9QX zBOd4lH~2`uiE@L^0O^2UaCi;z!LeXvkoGFi;99U7+yM50n?P%b_6in&dqD>{Y8mwc zP6CTpl0WDLJ3#9y@&g@UFW9@9_P3n)SHLeA1bM~B(gk*aec&buUrRn4H7$2(N>WcG3fT!5~<9BkdFH275rq5233kz1yJ!yM7HF=(qzquoAF%kpk*}ZhK@VvC3*`p8otVE8S{2ll?hGv(^+rJO?lF8qT%p!G7sK?mq~k9@&O zunr7@>%b21POuAn2J8WMgT3JJCdvtp1+7uyg9Tt6=mgh+!N0*j*t?5(V9)!MGl2gG z(1VV@Q%wOO*rTTy~DA=fXu@dKl%poOD1Z*ay~uJ+^qf6YK@M z#UJbi3-U?-3giHe1)ZP=^n!I@2e=OG0`CO-z-K_~;qV6*fWy}k9~=u-f*vpk)`1;h z2Wb5U`GN&tFX#ZRS3(auKriS7JHa5>4R(ONU>8_<1o1#GXuXPb3y=p`a1`|oI>9hl z33h^Bup115yJgk;39cGn(~3pLNHhJUaV>;-#3>$Uiw0v})>SO+=^;RAGzAziQo z>;t>NQ7y;;bb@`L7qp&A`d|Ur2^NFhU?tcKdO>TL@_`O83_8IM&;n5F94xqj^v{MK>;;2h!8y=_PH>ZigWJI# z&>BH*paZm?OFYm4dO;@`2E$+{*a3EfonSB61zNvHI-mpW11qJUO(0*e0QBPT1jAq$ zyc6sIp8>nU-C$)2e7BJvI0-DCNIZE4*U9sFv=cB4_JEE_^k?x0N3DYnbb_6e$rtPf zJHS4$3oQON@xV&359|O7+K~@9R*=23MWEMBd@wwZ^g#!Ijh zI?&lbIl&+{>Fr>+k#csx4>$=7Uq*Uhae(>Px8)`1=1I;Ty7c8*oznshGS#nnA=NvnH zaNhbH^1*u)?$#OHfj5*NhviQ{Y~)PauvK}@mh+D}@6@v#CrV7AapIaQu?LDr>0$ZT z<+?`mXK(ymiD&XVN9bk`n{CiZxh6qZ2;Ip-H%H3l88OJYMNtUP ziwK`Uc)f&QWR$zCWx%|lPm~Ik6K2N}WQDF7x|=}jb4&^s7&0tdH=xCu>mT~W)Mr$L z8N(EPF?1hY%zaxz|9j|_%qiOpMSqQODrw7~@X-rh<0S^4W_e}{)r?_AH7UB`xtvS* z5;`e&F?7w)NwY}gol@VGgiC&>Nw_Kta+$8>BJqPp`~!t|5WfBZ@i!5_i}2eCkI)_x z?JakiE>NyhuyR=LV!_g3`q?uqD36|D4FdCq<(3OhGaoOMr@5NOIjm8hT*EFFC?A%4 zi6(VvU*oA-p2~(T(Vj-wK>>Q$75;+*kWba#_(NIw_v!4+Y;$MI^8%AoT^y%TfLUg- zGFVPs1XMb#O2TG*70xAsYnY4wb-yZx??xZ|Qx+}%=_3Z^syt^5Q@OZ@ zc_fn4hyPx8c#IP?Z^ci&z_fnxqBBD9uvWln*7aO@>L+YT zT*lLG(p}QXT}6_SSLTjcBL-cZoQHY|zn$=d$x-Az9A2YeLe~LZF?2=jgI}Clj(=f$ zIGDUI6(LBm8B?F(*B5Zx%)oMon~$|X{wP)sc862Bq2;SPc;*jBt+4J z5JD3AFg>Vfs*$9W3OykjdJqN^$wU|=A%r9(`AEXd-0yp>z0bMlj+yfLeZQ~YU!VJW z&Fp>ldat$jUVH7eAI?7KU?gH$F7_JTvq^|vXKV$21MrP0fw7pEn3)0PyU)=3x%3>Y zQzqFLlc4V5oA96Wodetf$ieay=b4>+_1Yo7*q4vR!)=76AJsRz0iFZ674L$h1gDH< zKHLdOyCE+N^ud_7`i}R=%hl_boML}ZEMTgs7zHdu&zI65cjRqV(G`&4OZM<}pK0gJ z@Z}b({7HU2kLYIDc%IcCe7nF$a~$8^TVid{eU_aw)0aC#kji2C1CI;M*~- zD*71ly;%=m0r;lH^KGK~-%%C434Yi2l!vdkvp$;?u9p z@MRNU&I|>`GEmM=Nm!rZT-03R8}0D9c5%R)5w*{5;EQm6id&4^huR%7 zK_k2HC1XAdI@y`qeikqIy6Fjaw=m_K0o-2T-f(eb6SM4#^db}`y^pfyCM3CofS-nQ zS_9(nGwedPp*y(%BzH1!<-nbe`sn;2H{a3S1&~|mYJlXf1-=sJzAmg&?l@O2$O~ymzC3H*zgGx)~c6w^x|N9SbZ%cxYY zy;43I4e{I#&e_$K53hH+$LF&X`K$y!k@`ihCm+YYdlmaBrwMNBYCX+CK1DON|8eaB zda`&Smmj_y1tU8s18y&H54-i&`m}hF+bujCIJSS_1oVmKjoG(nz3yuSe}{8{^{waI zfWE69I_n?uD?uLz@xF&f$Ml&!)1KkWFII)H8=l1Jel!O1M&p|uqrCRcIw_>h9BAZ0 z(g^!BlD`!A(#<$uS1e@yC6+ z48O#+KgrE#4FC9m*+*eN(u?i)5{M?bTOoHZ=r@p`|LpH_^H?q~V7hz#wGVRB=fXdc zJ-*}cK{o58C;P!ZaG?z(6)BflDZj4ZJB)Lf%vbr(`Nn{+azRzJH5B6e(BXsaaDEsb z@{9dB$S;TUqtRIFZ58+`9(s=yWRYah~#Gj?&AWqpbOx zekOyj^uwy?V&eO2RIIF~o|uNAo)$CqGLDPtR|dXRoI9>Y-1oDGkNtj*o-eR^a(TY6 z5BPaFzfJQe-}@eXPcyc22jS}I`F|?<2hMlDNBA`!d;yIs#R?X}rbrxAo#mZ*d6SIFb=P=@P+%)qQQ+=KVAIj}}+~I>S)awR4A;+y2`=I6KN#)CK zj`_;xcn5Y|`DiYcKSOE9)0R62h7!UbL_VSn`%%FAW;^-N_(Sd5vzV7PyzQM6P6Ko) z2)XT1?mJw$dfc>n zxaw!zCg6&In^+rH5W`V9_W?KU%c>~ceyj{0JthJ~bTq%AV?OWEQwHecjzBL2eI)4l z#LxGc&`xHfmih}lX+ID2K}6?q0{4aftc(&pNI8`{eF-At)l!ukF8VSn>_TbppOH+KKrBRpH_lCh{|yU`=jTjb^%ugn6Eur z%PBL)?z-$R`#8*hzB{`8jRI~ZaP`?=G3a|i|8MM%+GrE_BHvd5Kx+9dafqo&x9rhvXLnU-1aufll}i4&E7;&3umUigyc>zbrHIa}@AFFP_H! z-g+%>r|@I}E{lJZ&zR#eA3{F=WL`}9&`FcbMb*(QRPP_5Cufb()7h`VoMaSNKJNSn zUcDs_|Bm}q#P^}2U(_cyuce89bLKP!r1GV-#&!vw5BjI&+k|{7f#>qw`OnK&1-=b` znDPz%XXPV(tVQ`UG2UmQUb??wKG`>>3+oN)bQr64Q5b9Aec)@qtUCGu*xY{V(V@lj zTaBlD=(*2vc+T(NaJaq?pbf_l7I@qDE)~l~&p)?;Zwc}_QG)Mmr(R^IX1>##C!j06 ze5CipHt_GNI(nK7z77r_+DrT0yh+Ml=gd3_PtTps3sy&`Q$D9Tc#Qo#2e$`%x&zN| z>G{+y%d4XU3Evd>^PN2bst=~O=X1F>*Dlvm@Rj4a#hb~F0!}`0jK^`z%yGeK|Ywm0&2*REKa@f@lL z_pq+OZv#I4iR%B)>y4DQ82?t`J>t-lE)R5?=dQW7*49rp@R4V#qnFf;-&Pwx2KcPi z`0fJ4yY+SES-iiCHBc^b<@366DU}EK#jgBX^|vqLrlyT|(ic59+y~F?eT}$p`c<(! zU`P7w*HdnhNMH1P@h-I28nTN!J$PrIRxf~W)+MrSucx8>Hi3T#o@31*{tLYPq%(7y zW;Jmau-`mL_+-5M-VgjKUOd?$uRYPI_MJAdnEev!j~Up|oYw@;wNXCjdH9U(?4a>v zW^Vy3tPgrFdPvji=+C(Jb@lLJucap~q;s&6o==(eV13i`)9I-O-}31AO~CI0ek7Gk zc<{N}X6Uv7--gF(lj?Dho%C9>F>4_=Y(K&ZjQO)s;GcJVwO)6=Tbm#Ita@SmGHJqD7*oDW!B^S3I=X=B z_e5eD@@r&2Hun*|xP2xgP2|wpV;7jp5 zC-Ay|z`yG;o_hrjBe7?9?vri;zOoIT(`*2|Bip@~0ZaNLrUyt{yZdxb$t(RTiOfQo#|a-z?xZ19z5;rUXsi=e{?f6I1pftiOq z<#oF}53T}V`~2!?PpYuvcilO@Ubs@ZmIBuYxK|MOy*$K&Wqa+#n{$P**KVc}funXD z)B*ZKJN{F@l?eO}$8Qbw=2N%d>I(cgl#Bh=g&w@qACBU;#)JPbz8%AUtDTp>ZojpP z@V%;|=lh@szZXw_3wu4h$9xwzkaL5B^tT&)kqfG$vtiFZpNCKHmHj|k%hLyOb!P<+ z=`Ric#`Q6N=+Iz~-s|>Tg}`^|Yw$acj;Hr390s2K){7o|J$`Ey$-mI}ttUKq@BUaF zerq@Qmf*Shu4JFHJbX?&X}{IPSoYui7QN?T$z{fGO{>jczuy`Jz8!;%-x^w*@92JO zA^5w%e%WuG0e;7~IQ_Af-zq!>c-Zeh^;_eC-*I_$G)bYcUD;+Xrgd_PbKEi{oR24DVl)zNE+Z-_C2)jV}HUE0Jsyo341JkB819E@6#9v z{XUDh?Q5_gcs; z9akM)L3+B)TMlZw0`dbmwqd{Ob-2X04}9$>zz@*4u*Acs>mBc?%|Vzn@GV8TN~Tsv zv3(h9OU#ey#v#egHuS^fmzH_ta{qGtQUbTPzI&?MZ#?)07FS1ufF@agg}BX#Fl zF}Ke1b$V|~ALuE;El+G+Pvz|odRD8dC~hy9@?!k%qeoWK^BB<6!GE<&$NU=g@!am> zeCWL_BY`{4#bMrS>P`8Sfxe+Bp3`*cBuD2%^qq!|;nfp&rz7q=4kdTOz-arqJJDu_3_xp zAY;BK<5Ar4cpCQY)|B{$~J@c!@)T-FJp!|v^ZouNTT;VZ2uq z;6Duh0mSdr%U!SVTFRMrvp#nM-~RdPXfMKFN%^5Xp69TtKpzNt$dwmgpETUi%s&FX zE9hN7PbB_2{M{hXDS!6wj$bwH$@&L974#Ku{(5|~cn_!`%tvtY!egn?NdK#Vp9ehg z>iT0m>#duV=vzTw2|AV=hK~Ar==(t506N=`Qy$NFlz1lW?+Ek^(0722<7R7$y2z&_{#L zdKhNx$m7SifnEf9ef2yDdI{*+B%k#VKTf2a1%Cnhn0n})Ku^c}u;TRK$-h77nV{D- zU*q~4dR_A;s?!`JzXbaLt{%PTC3wu#TP&paO~4nug#Bix|nC>Vv#-9QD2GDPcldt)?{XtKCwfb+*J@75F{4iS@;l==$2^`y@ zQ;Z%o+Qc4YOaqSI%hnz^m~EWC#u$B-fu0X~efru7dY2>6tBm}*_^F&}=j!@QtCjza zR8(_^pK#g06(JwEl~_65dp1`AtnHBABRCJZSpSKgFCjU_hE8$!d;$*w@#hZK0=EQm zE+U-M-(g35>^Ub)(?31_0k;FVn4h8k!Np;E73dX5pr>I1u_2Bg?uFM_Gx4Ij&wWB7o&Qr|+y&U`}6TgQ}=cy?FwV+pmj%@@F9YkD`Ubban{KR|eu0UM#qrRBy=9@!< zg@BT;s{(Ew|zUu4luA;kf?${{?;n@P`P$+kUsp`vHbCw~lH1D+H)gy)AMb4F z{*HcYL!v)2NlmeeeKTw;KbB5hypQOEoKo1wuhiZTdGg0T)cN|{F5M68$ptViPIg84 zS0MjY#JAeZH`C5@p4a(CE0pxL5BU7e)ln?VVs+Gdzt+(g;Zjh!AxFV+{=kg`t}sp> zKbwX%W!@w|4OB$KkK~R5ejf1g;{><+4Gxmz&H=6zxOa)s>HpA$b5@cbU0Y)q2)_yV z(RknFcV0ZV9iC<2ePsQ*2ij7kavTIcGmQ6zdGXHu=k8iC$z2HCVU*)l#C=17cFN-J zBcoaPy#m>MzOOI`{o~DAvko1n}9E^sC%D`?0cA@&sLDP)ho|?Enq61zx6*RqPoP(ca=3LjYj?D+enQF| z2q(Q30^bFCJr{9z{JxaLp06iANT&LY0j>{lA@ny_uG81_zJF)7b!^U)+@-*0HmK3- zUT40<=QaynxrEya+{kxuz5{VrF2U#e{FeZ?%7#8@b?mgOca2d^Ox^i@ zJ>{SNel?%V^Zn+*>wRK0{woBv8wO)#WABcKB z?&=%!4Zhc6&R+3pNqta>+O;dmPpXMFAUnCvQ?B^=#Y4I#q!jIM#(=LB_1QvvmwEWS zc5S^wZ2C}%;adg1{12<6Ve*p~c=$|y`dH6b#OK^rVSVogU;0O8TGYeQw6?pAJ^JnGxHRZ zOYbWl3Hom&_wD-R?jyPG{b;ho{(xqFQXOrNxNBRw?EFj*B~$+6f$IWX3MDw>l4rkb zp`nlR(rb;AT|uMwi|&HmoK5At02huuyY`8PM|#6Pr%+LI!aRTX=x;JuvQUn5sa?c(@ohV>9W z4NV{Xx;pv<;k(z3A7`{r_(I^PeT(}lKHvv<@ZK|Sg~X7@`|VZ0SA1VCCTgA z&g-bGGS7t_kx=dHo459$36BpG9<&?T`LIIFC;WJS4C2~0v2W*DFH9yn{3PF3VA}=V zvtC#VdY>cEH-VmY1p02!GeM8_GrA9kvZ6RtJ|Ct|N20em3O(D%F#`7FD)o+r09hti6=Y-n_ z+&tiT|H4zwTRgZ7;8L&@H~?IsJ3do;(7j#f`P_1sgYenFNASK~dheIpzH#^p7fN`2egF2zRwBj@xe&aDCwaS`v=yrEzqB znDj?W8=@cU(y=cGIYg)O`>@0!`r9tOAL>hIq%+gq9pp(2#z#jnqco(nr?c~=V zbb)ah+v}!0eX$QX$-c~#XAJ1+pm!j;^PGccUt$jEnV=`Q{PFu1YYl&W^lhL=j=+Bq zbSfXrA(p?{2j%wfqw{~+n?LIVXT~k#p?Emx#`E56;L9N|rVn==eIcq$Qndd^z7@bN zz_srsOiH<}=v*+b0a&mxSJv}F$nApn!N=MadNz8Za&|RzeqX_OM;`L_j{AHUCx_>8 zqkyl7)I|RUJM|6r;63MAR%jD+UyVU_*allS<&9w9i0d+Id*v;eg79FfBiThEaEF1b zub++rJ+*O76t|^ga&+Cv6;LY6nFCxVaE&N|b%gghdHmH{LqE=?$LpoPp`T0hfrqnW zd2t)kYajMgEqN(RdYlY=R!U8@AK}M)@F*L-LxHEA=43tTgWlgiy2+9CLAXJ{tptwS z&zZO9Q`YhK>m~!Y1UNEFuYUPNr8!AS`dtNF1#pdAT)bYk8hU+t8D;2vAGEYbEHBmz zo~7hXdRHx^mOnKp!Pb>DHmjDTe4evHVOzo4ER3yKEUOO`%ZW8 z^*;xa0z+Sd_pPsW^M}31`SaMEo#bya^6w(~-*%7bRo_SL=XIc+fT8a)EJ1m)sQeo} zcs*amAfpd1>KDIgk3f7GDA&psHPHfE$F6kvP;a-t;|XcI5g$8pCaT0Y41DG3HT<3o z-v)<|e3Y|SK`*G_iJ{|u^!y7O%CnEZqh>`@FRi0x)z?_ zFI4z<{CMD30)Im-e7t<^n7RJI?*;zS0P5e)TaQ_GKfO;x=dP~vc@)m|2VdmGnrLSX z7`{OsKF_?^PG_~b>piN^Lhz-YRuk<-`Q2MLpY;M|){D=L7Y=~G#&;Hmd+P%oV=oE| zSUP0x>^AFlXcgp-1O9D4_@51jcmRC{)L3&JTnqnDU2$6<+jI*74$tsh;69%oZ7jvjX+pK`@yi=U2g>a`Yp2d=G& z{scbX74?;iy*^lHQU%>}8I$Xjco zlMs*9%e+rQ-w!A-?uh3RJAtnNp2v|~vp;R-5j0*^fxZEBDwE!?!(5Ed58=J4Mo%;z zwYe1b3|wo%IsFLpXL=72(X&C{1$slGJL9}(zCz!TITC&HQRqtz{g`^>Z!&bAL2>zL z+|?DJ^6dtl%3mMdcNxZqBhcG`UU~$2Ht0)0Z%gIl{Gms_3#t1L(L4&Z~#P?UO^5(<0t@6URn+ymy8Ms}*QMb_L(etJ&No0O_BtfYiR{@ub z@3_EC8yxECvFELz2SLYlHdaR1=_rzur{6|K`5go<3pmn+&JS(D=cWte&O4-G!junO z0pUiO{&PMb7ht{9_l(AYely6vH_tV)oc$BayG_aE9|d_8z&9XywfYH_g}#Th0rZa& zA#ai+4|VkTan=c@sA<5L0Y7rOcin}&J$Ann^l_lKqx?Mm_DZOO_^Uvl20Hg^=eUID zd>DO?X&&e(4mx?f{~-RZpc8*G(evWzRG&ehQ~o!>ZruDmb+P!2iJothykg)hX4LTg zOBZiVr{?Eze--FmW_sHf?WXOP&6ehTBxf6Nqk(ITxRw*ImxG4B$fcuSS@Ss`;!hcj z{sjKXadiELc%pX#eaNg@{l}W+^3(UKc7gst9REz0K8E;9YNC(E(HFY(Ig~%>Q{(6p zUHV$$zrQB_y))Kqrjy<|f6&Ju?mN&mrhC)J+0@O1h5H}mWzMeQb2C0VMB}j){Q|vi zykD9z1oru#zdYybF!wh1V@WTCppS%{GZ5D@Fs@z8#nSc<`ZUmEeiC$Zhn>n%4Ej9K zZ$w=4>wO%)quw)o1xccO)&jQ+xQL5G`+4pQZv(v&^sBve_yO)ay<+DHtAI;=pnf@N zSHhowPWM;hbaJ2ebtIn3lMUPf;Og>AM5phK?K%Q|GU%0{W18d1C#JWhpqEoQTsrjb z>F1k3F9rQLmkxbgs`*K;yA8dEmu~J;JM$qbXCfT+4#R=&7LB)gIKYWuON^Z|UZX{=(!|v#Wm3<8~W*9I{0ri z{7XSkNBQgO@5H|e^a$wn^`G5FetqTl(SjBHE!_O$_0z`CQ|q9&L0Yz<$K*ThfD_!t zp2#oL_tOqTkE2{U(3AGbyphx^tltSsWU3c^cdrY|RbRW5fll^Q-@JAw=wv^w-TcUJ z#Lin*8UDKDQ+d-yX#R7FpZgK!WqoP>(-U`i@HRy~6(TB^w-9(LPZLVuet@})XM7lS z1UltcZ0K=*+l*O!%s+NKlJhGAeq=rRA$dDN9|-!tq*ET!xBCvC_sEMo9g^^g$ao;W z!*{3U!F%qV**Uyo=aG}zhrV05a-P}8cly2OzSbbnH-KK(e2@6Y8-73HuHW$Z+l8Rd z1AkrP3YE7E^l6}%d--`y5j&E=lTb{ID8GHcr_QhOod1cPJ0Uwx90_{^y}MT)^q(`y z$7k>=(QmBg5DhGLmq@52K+AI-?ee!=qY|LB)}^a>`2pEl)mR! z^a$n=-ga}=8g%evHMLw$m|t&Z_N9q$EBK}@!ahYDpYxtP-o?iEJcbdovpvZ5@m+)c zg2gp_9>Oi3caLENvFL*?q{mLcXFlp32jkb9{XtI$J?0Owe|sfFfS2?!#_;pHqNg)& zo@5Vq&u#a7J;(GdYL}(J_klc2*JJuaKQ{a0ywW7xR^X-q$9~9JUzl^njvpdDQT|21 z-2*-OzBx4})7=ln8yoC?+$3h2$mPzs7W0G0YNB^}%VGMbS(msQd{oatz_))K`-fgU zuV48AkDg)o)S%W&G4T1o&-)u*zYPR$w8_(2)c&Rn_zl3HKzQf;U4d4dlYa&1?Wvw& zPd)X%G`~Z^c~JxDh4QahS`+;iaUY#xXImv-PUk!MbTM{ixTbkwzOSU`#o5nb!?hmknsT77`{VALANmPnUiUA`$PWd1@_Xc0fu0X~ z>^=+hU@VO5e?9ym=*g~p&^`QJL2nOwqDzOZc<$p20zEZOKIoqEjR!plI`5k~wr1|b zQvM4KJvQ%&A5Y6bKMcEy%{$`fEjtZ8R=@cCt3cli{`$(Fb_4o5==Je;1-%0Fy2?-X zILOe^^J49z{e?aZiR29YO$Kfk4m68 zWXWb&VEk_2OMx%;;W5!I!zRCfX-%oHEbw!}EsN^Y#pz+mY_M#Z}y2e@-6f#pCCx}Et}R)Oa|l!QNse1`x(74t0L8l*4}>JqyTZ=Y#&K;>8p`Q@vQ zd>@(WyA`+%z(o*u{ht~5DBpdcuLONM(VcR}^3?n7J@gJb;THlQd|KmuZ9U~QV;-Nc zF((SCoP{^Rp8rOaGpT)q91Fn#8{Jl)H*VTGHM{-tyz7q7=MCbm6@tFJX#rzH}XTM<^ zh&WX4Er}}!+9Qr%3lb4`)6zP z`wiHh(cYfYM{C2E7aT*nk^EJl4?KeWt%jaeOFlhUoPxA{ zppOH89?{K@>ggMc@e%1&z>pekAx&;PVr|ab(s{%PAZc2Pck8?OSh!VZb|Kd>7JAd zp6*E)y6t=)D7k;5bPL;ah^I##6jKngoo!UUO|TQ{AY6`|_;O@ZIl56f@{$httmSnU zL$3@-UYpy{Keyt0^|XGC)hoxX7wQm`XW0+eT`#_6-xVV0JMMidYoZF{AIY0xvZj+JN#cwXI3WHrJDFUO2B-3atrAUe|GG zZ^+wiL}ML zr0+#K`9hQ{^HQ!4UFiC3tw-MOI^=Z%PnD6E?9M}BGL!6HNhQkq28M*H!;re6=BYh6 zYVzrH2gW1RpV*uq*>xe(Hz2*gD-ZsQ&#vGdWq1Suj-=0oU{T2NoYuU}iI%B6@fU-C z$M%}&HWC`=hx9ja@U+#1%+H&FXmRXCI{Z|ht>7Q`aZPlim%kUCTjmpG$X>J0im~xL z-ghU)gB>_$;^p()r!3@5uhH(_WJ>MS6?_}O*PQswF9TtJq?aT8Axd-Vf&CUCh7bCk?Tl zsLRQcoGQpU3^~hOIqWA{PA>J|n4IjSKGxlJ$)WmYkH>ueQ**x!MuUzCCw>Y3=iwb5 z^goyT9A!i8JO=nBz|(sNJ^dX0cakqRDGMiAJRQ4x*m~Y`N$tEA{3V}ZUg+8x`@j68 z%%QIP! z@d9bJ#z8Eb>Kf{(P`aFD$S41cn&{J%z~w|SOgVc}IU!S*b5fns~NU6w|b zge?56g}hz6usivLyNS}xFlPC>-X%gNyMcnWbh=W!k9M|qlp5glLYbK~xLKFW6~_;*3R zLfrXLdRY<13#6YwiT#rzJ&|iRqT7&u0O^04{ASX;WCqPc@$nG1Uu45IzLoH|j$t;u zNq*V{%tt=>OP?dbweyQcSu+T%FtO6H838^;PIXb*GqPNWL_k*y;*|W7T?}SR~ccKJl7VyKV8R zMe*&{Tc{VLHlXkObW(ST2Mu@QlaX+)nr?|c>OCp`Fv+QzNbaWou*5~`fF(w#rIz@@ zLK0qtd#VB zim6ItO7Ey%l%lIzB*i+Df0MoiLfmJmb+&lWQd4YEYVfBP0)L76Qi;1>l`H+?bxZB^ ziEpel#3$NnWU+OE5!HM zsyrZ~9G^fH!VipzX~&TshKpOYpe_Ru-k_@d;x6@?U)(Fz=79J@UN|8j$}RPPU%YLp zX98k^t&mb|tGNNO#in<5LRQ-r;LYl_#3vq?>LH(aMyj`Mv0Eyn{4CWnpSZ`Tb2)=F zoZE1+5|^tApLkd*L;-(Bi5H~0R}ma3e@eAR!G@Y5{vY4}HS1+3K*Xu)Kr;0Ed9oO- zio@b9sir21eNufI7RA=he~l-m%pqiQ+3;y^$!sx7DAC;#uFh_a=xfNt22f8SWy&h z7`Y4Vi>1PALnm6Zsa+SGDAVu4Y!0378zrVtA9=)54=cG^sf|i(Ri}CLOFA3$o@$#E zMRGJ-MN(@l?JrR{*Sp5pe$q)uxl*l=;^lf%x{xx@={-4ty3@{}cwVX>gV5u}55W+9 zl(I}I#5XFnFesk$cR+k<5Im^Eg;$PR(nNeL)ygJfp7p*D7r*+|2NCf>U<~4wLG^nR zQ4&&!FAk|klf|~sEr`FLpk7Q8PlwM&{7_g;Z!9VkTOj@=y^0rNlUrYiFQCBnSYi`t zffK{0JT7Nj;tAtAlA42%dCmh;Jn2;JZz)5Y0@F5vPLqqsMG-i$n-Q5HBVXI3WdYNP zY`4iYh4@59w%OWiO|v2&*kUE+^t=^$%N8F~bdMFOu(jiyZAUiSTJj#0mb#7wF7g~TeDQi%Nb zlOb_0>@h?ZwLC$ru~c=4x&%^Yz*8lNr);$gjcltgf?_^3FWY<*a#9!`_S&Q81qeoWZ8<)w6w)lyP_21&bK3~$<@T^od4Mdq#s~d=4I9_C_&%$DzMd>hrEs5d} zj!(1Ivq|D*o6@)1swi1Z@KLc>xf=ZCQhkiU+EzdK z#J5Dy?UT}_F%EvH4N}4wKad!{fQ|XE$SGF}xQZ3>K3hC$Y%Sd5VL8bX4^#eVvz+b- zcS^M*K|Bn@NfaAwbucX6u+=MJvCaP1%CK1MQ*R`oII28BOjfEQBpwSWq(2={Q^Mk@ z1TCl|G%BdU|6_~StR6y4x7AO!SV7rh;Qi4SWfXnWRy%AOQ#tpfmIyPh-6_Qn#@hd$ z(&9NHy)MSZBSnk06F7RqHwVs;qvmW9=p2I7VAca*ZL0a73~`Q#ScEOBMeQcJvNWJNmk zhj{s@{EsE>r3z3RoFH2~PUVBK?3404iq5sv0!u6>F4GhwFt59MJS>L&C>Mmq4lC{3 zu&A-rbBW?jkY9+pF;`^n~bXS{sqxzsAY-b zmd}yHXO{XfjA_$Th`;6Q`)HzgfsFHG)ps$Xev110KAtGn2TFkWGI&{WqWB?vI#;t@ zE0E92c*Q4{%T;m_jc*DU584XxWp<--pIBw)4-F^Fhp|L@I;j2(iTh1a61p^fP?B3B zU0_W8zqZFyue$)FxKzu7G#!2+Km){mK^k#+oPR1PmQZ<0eKdxx4cvzsLAhoZL-7&Egpog_KTO*IYQjySI-8-Y$^c^CaER1!Om0DBu&{k zSzR!UXXK+Lw)&IYuun8l;hW2nYLEKJLl zufo**)`i7fn^K;!)use;n2Qp`6d$F)^x+IP`_%4`_|m8LgvER#ycI9;sDrTEqWk1^A`W`9Wmm-4>R1gh7l z(Fs`YrB0V(kh)S#aq#mfvO=cfqraGyy(wuy#Nz^dA*z$L&*4pwOOC7fC4H!pkiAmjuHd(}G+g@#}Z{XF)mF=g0 z=x%yNg91iwnvY8;ZN3?Fk(Mx4;cad&n!+AOOWl47&s{w!Ta&kJ_LwDp#fn8@7I`dd z`8Lg^{ZcCS%mn;H!jA|W?cZeNga~%E=*%=%py=I zHWjyuB)k0#sW#cvtk0v8$ify;c{XlYTewjqzO>YC8kzOB!Z91I>#^Zxr((MCp{+c# z?Yf&Xu?dRMPW5r@xji~678vMPSR1~I^|Xzh8RWIwO2reXQEb)N;t7*idklaFY_S2e zb6dbrU$rs(XJOmON`29$iBO3x)-jgqdIB=K6mRg8!!b{=Fy?iGZ_uO>iiiu<{ELcF3< z-wlXQkPr~xDS}MJZUU{5o8bnXKNb5q2mI{v4o1+L{2(Kd}tM4Eph)*zZ%n21Kb+bAqB0n+GVVQp^1!$|;Ne>i!U%b6X*P z_osfx0~RJa+XDpur0yJF4~T>4_VDaJ%H|bb zRc3ww`x$DkU;L~TQfB$p3~W7+oxJO(gh{68SiE0}9TC_SRx@PIEWW|N9K5v&q!M`W6ee1P={m4B^_ylIK|DY{EW-mtKJ zgy<|Qg3Mnrnb%(N2lLgXEC+>dah-ZyiaXWwmY9m2Jxe@*O(-c27~NzakDc*eDbEDO z$n|m)w#Y115~3Z>Eg{-hoRUBbt*=AkJ4_a^r>sr@6>DZ7Kf<He@-8i-6x6o&%}@yTXdbLI2$Y2T-f#KeHw)mUr{sy8Cy zi{MhZC`D{ZP%9dXJqc=likQKhPTwU`%H#%WNh9%4gQmdjpegG92I}?3Vs(<*+gQAm zOpp(gF^Ld!QWPN2cmI}sX?y&Bs>FH=UENnIKW-qV`_;n@#2fw#5q~lWL-;hPHYABP zAsi5UE2N%I65oWduU`{V>yyNSgntRz2m3Km+|yvCwv;=L?MI4Soq%aex)2NC3c|E3 zd?YMButp#bxBFIt*liaej*Xai62q>gfawzD=>54yfe~#Nz=- z+7eKYHlT$V{2o+-b$XCQe;HK2C5n{^z1Wu9H^+VN9Uu^5q17CO{|Bup_< zCMJn0YmvmoBfiKh4aEDt%MpK8MX=gOG020fc@41Efm$~P)ZAq88AX2ysQZ(}bUM+r zEU1c;#jA7}?fanGnk3#K@3$kQ-c1z0hbWtg3F-?NXW}=|EDCc%3wV%h^_^ebb}H_t z$8PnTigTi?bN_2Qkw#bwVh1iaf|j?p5bk=Pp!)kf5}#_g~hja0pja@ zYJZ}5jmAp!TPzb+kSV3aAGfh;?KY!P%6jxzU9)07yy8U=-Yysuy%a}nQ%Nrn=C@IC@+ciah(bh3gA zzF+3T`Y|0QZ`?(Q?`(%4)c{O`IbJHS z>Pr4my`M~*v?Yzje5^^Eil;3#p{aP+QdP%@Lza5}7#jXxq(y2+Y#b}~OR^~Ts}-;Y zzdDdaqwot6@dnKxwgps4gtkhM@Lf>NN)`8o)P1Q~z^WITioKy;1WZtC8qqRrZ$nX& zpr$qwtHVuxjEIL4+k^UHqB@u&eoR!GQpDT_O`dBk?n$CDElXYxolpf%IB6hO6C4-# zAt~YF%lE;p(-a)n3tGvhlcoKel&fV!bh;^)T4Yhp;`VcmxxcK=0{eP!~cH&)4=~U@IMXwPXqtc!2dMxKMnl9*Fc{ET4o9E zaM7>Sgu6^Q8u!@f7cn?}75l#gdt`O}cJV{n9?E<1xO8(}xdM~!I(}J(zN;R3Z5BsP z7WQ=MH`;`?arIq0`D7ZtKK~_uWTmc0IgWAAFMYcXD`|(~AN&rOdY1g9!IdUV=a&xr zT|fkzn@9R(8hYjvb?dj!QRua0_c3xx3b2~MuhfKnzWrzQ8*TWr4BwFdlHaMv5R+e} z3G2-t+eO}Adadg$bKU33y7hB;E&OP6T~ZIeRO@$_3B7eVQhbTw z--Qzf^y{<5gg9yQPk!Z2{-0=c`e!<E?R$VV$07 zuAN>~gH=BLoa<1-`0K{Cu3Of+KDpNQIkm2DG}nn*tQgr-M;e&x;+u8(u_?^IBIB1@ zm}_h|@DIDI{99@0bncgaK^=(S%7<|MtJKp7D1_J?Td)SjAEJs*XahEx+g~-Cn_`>-MvA zjr}b*;d&EpHsN*??lIvZ6Z)~&Nxx%E*w%!dO_*!K0VW(_!m%ctV#2v5TyDbkCfsbo z?Izq~!b2wX<2D87Z^E`F>}|jHQ{m-t~cRk6K*%*9upoip&vIv zIDZqiHDPBH=9+MT2}hW4tO=)>aIOiLn{d4eH=A&~3HO-rkO}?0P5vfqYr@VZ%r)Tv z6OJ(9SQAb$;an3gH{p5{ZZ_d|6YeqLArty>;EU^T!nP*tY{Fa<4lv;e6OJ|E6cf%h z;c^qMH{oUzZa3i`6CN_5ABUAVe-pMfVP_NOns9&#N0@M|38$EFt_hc$aJ>mPn{c}c z_n7dI3H^Oc{w8c|!pM5C>I@~g5_?6e+Jm%C6x7<9Y4$C&FS zJ2mcoGk+=iQeUq%^sKM+^(q~R1Lpb{-CE+nx0*26@b}rPuZJ3Zxw&p_GmaOa191I=}xcXcF(Q}KA6 zxo&9WmD5=R`WbyY+X;P5va_vliMcNNSVt-~m*|7DRrFhI=m$R0k*^JX*QffrgP})o z0Goc}&2;Bv%Abbjk`Xk3r?MF%zi=vw-9xHLY?-_YO>{HF0O z>cI~Jqb0^CJ9uaNWV|U*$?GGEv{vu~TqE7s= z-5MFZvmM^J7S6d0rc0EcenHs{W4rHOtQYRY9 z8l|eSHw)FU1-g;{Ox)7QRPD-Of`RLWI*}5s)*#3NDY8@s4wWPY8% z0%L_b?IMRT1TCAY&JLi-iEz$vhY%=%1*oiaL+C!5rKMY_tloCvoGm3ONq1jf1X zVBmH)9tqsx##4ng2koO~%tv*C0koG-HL@RupwJU*kQC~D8@3HYRp=U4=zLV)4s|$) z>W3aKL-j@QAYG`=_CO!7n=T=aHOCOg@GP8d7NNvfalS}|TE2(_!y;6P5&Jt4>hdJs zNFYKLsOR@0G$Ij4@I|QUb2!y4Liy-S`$WiIfCFYCGzbl_UxfO?W`7o;+n&G~Xb~Ei zf^$|Plz`IwM}+cDk>Xbo`T~1_2L+v=6TgX2J4`(fiO_85;dkWMQi{VObR(qvAwu0= z5#mn~x_q4we~HkKC`6SAt@sUZ3zMNX8B%PKp&yTvI8YQ?4dZ%Sh9*qIi7^>E@B$7{ z$F-JW=A$qMc6jH7T?XwfM++H8fM{ssrzt621EaDCdK=~(1^L1BnCr|OvaPN!BD~m9AFBDR(y=ZTfxxkMtG<{ z7-~8INArWB^~XxFBN)2j0G?zGhCYWPE0cw_u#FV{i~B-n2_FTekl|OqL#zI3Jw+*# z!$?Ueu<8Hxr=m?0zC_=~LjY(*nXsS_rJsEP{ZB$^WWww-D4kwMB@?BMy36CqsAL1V z?;HdLGD#jk0g=IDR|z~Xh?rF}1piweMApf&V={!C$Q<-sT_hzWMPwvkptXiI$i>BI zO-YZoM;0Q+0MLr|A@!-5M59M;m?jeCzYCGDj*}B*a#LKqYc9g)BcuH!LN=5mpgQT7 ze03ACQ^7<-`2|%eqSNp7q@RPG5}BscA9d3c7Qj+uBe{@**76&4Bbl&~YTZb_M!_jE zBbCzDp2lhGC^%EzN@WNUjDZP0<{Id^>AVw> z^s24#&HjYkz%laEp8#m?hffP0uj4bWK-bRTc;gZ1)CngsM^W>qf562n8YHd~BHUNU zdwhy_c3h?zUdH&^pdB;F#vOX#qCH<&&5Pf|#h)5A2PIER)?yp4gOw#UG8eg6sU$Vw zi}YrPKLVxL6me-jEI3K$_&Vl~{$w5R2gCG7bo?uHRewVrFDpR25yzX1s7Cyfp#fC& z?o@JM&0C?u{w+*Rc@AAV`Fze3s(3jHI~>83#%DE#Wv1$)HGiWej3!eH4|PTSbRGY2 z4dR`3{Mz%taE6Y*bQ99M==f!5^T?Sx-fslrXX*G~P+jC~9UqB~8|kX!i_mD1b96k? z6PR;#yygs~pQq!A@L-WF9seW*Og9~$0^c0zuH#!VEi$W*G5)I=$Ui#4ptG94cFX9Y2kDFVgYPha-J}j_+)O z_{BQj0$nsRP{+Fy=5ihP{f_t*IzASS9T}|SQ?cld4AJpZIw1Wj9iOoY@u522Y6s%O zbiCPzh!5BCWDNZgZ8Xj2e~$F)bo#9ch>tS7qY=Me#}8!!e}j&HMD2B>j;Fqh_-Gyf zA`kJKbbQ!Y#BbK|;#~0FqT}zwQ$)t-_%UB2eyfg;KMV1(I{woch~J^(!-pV#r;a~z zGUSZc@vW%T^**gC0I>aB)@c|Wx&(ZOi8@0*O8}m zyybetSLyg2k0JiFj(6`2{4+ZKHMPZR9iKQ5m^C^chNq9LHSuQU!hDKwP^jU&NrhQNNU5Li%8uP;)c+JyH9WQPs zL=)qe(ojd4%0qbbNO!p0W_QA~$rh{7FJ$w_(6T&g$`-9ABB8}I=tewb$`<|LDP&q3 zICmZ|W%IK}AR&Fez<-g}1><-}{2fdGEdFoP(qrRqv?lSL29-00X4jf(Fq}$LYt4!G zsUl8)=GqSWzHDxoso0z>Ma!Tqt=^|Vxb$y_@Z*AyftdOr{;6BW3=_wQN=(YqFMj|- zYv&osLbMu;Xs~Gko-h!{7oZiJ_9k&y8`!NS(VAXhOZg*`e#c)M;+7FYh!fv}?WfEL%)Bcl=!J-|aY*_$eKLTtg`J$c9 z`BFI)Y1hUWP5K~tC(@?6>5-k_a+n6oc_1u}5$B+04sobl2g1e}@jK#dF9qhUO-Iw? zr9V*tJ_TS;48-CMXw1T$1{4J#4B18}EUBFwm<369$}|v8bct;SAs2}a(&qoMMAN(O zEXUQkp!RYR5y}?@$vy>&x$l$Hgy8AmPyntakk-pd@+S0;rVq405BQY|dUuQ_QeUQ4 z>Cp5n3aw}Ug=XLIH9!e3tpqX^&%X=*G?<-icBU19`Mv=+)9mcWpFxVW&fbHIu9Rnc z*?{8bmYt5*P=H5%hkyI=*JdR_#mR&FkLJRiGI;P9z+anZ>Jg54AU(M9uM9X*c|u|4>{ddYmD!w zEC;jZa8U9(2lwydV0Q31LOyT;2XlIG@Zgmk%)On1ho*8cZ#4(=w{!6D9~>-byN1{o z_TXUAWgINIi-SiOa`4y-94!5cgBA8#VtDc-4ptR%@XR$FluqH`*_9kTw~2!_yEs@| z#lgDNb;Q2D69>;HuBWRFZ8&%#mxC9t=HMk->vw2gwvL0B-{;`fgB)yZ_&m{GJB@?a zFXCX+Z5+HYkAuyn9K87f2Nl0^uq9;!@x66A2XCLx!PcuecxNgH@2=$Fy$TL0zemuq zc~B<5Kw(H`aF`&^=P*@Lc{(<4AxSwMo41stmX6I^Nm5A1<|i1wwuY}A^Z8#IhemJl zeb*Ei^xk1YwD^%6nU#!*U5kCxr%sh~VHYj_bIeZwKGXi7-UgnA7B_F`~tvJ_zCdhKKLGuc0Zndgh)xRLywFncK$~N z6Q|1?uL8)D%ZK325J-_N8XEv;`>=>=;g^ek#r+2G$!-oULQq|b(`7rVMS@)24KH^g z)YXKdSX@5u+zwQd{OU}Dno%c;HPT4lhw+PLt#MJDBWVTY`j*srjLgHFj#A`%gqnsN zMe1l=pDq(g$!T&MCJU4x4-kMAd%Da&1m<*kESOns4XG-`tR-}o!*3iRTC|Z*VD`ey zSOJuQrM)auCPgEK_5S_n;cHI;V4R2HlJ4 zkk$n=4FqSs%#gF8L|k?Kkb`r+;NZMT49U8lgYLI-VvngDWY6ay=P3^Ix-lfbkb|BV zbI|K54hp|#NbiFjoR0}OGP)pvX?j}(rQ`g-9x)tgIH=0AvtJRFwm`fZx zXhjpeqx`OiKx>WNg?X5+A3K=Z#Coz7qC+2t0cg#5jf z6aRRJgFoB7N{N4c%U4x?zN+p)LHgjW7+yN053$QBxGIT*q3t;sb{+@AFXmvxjT~G( zg@cicIJjmb2iJbh!3|LkZfv`egx!?S!OholaLa5CZhex2v9ED(+j|_0+rz=X|K#AV zhOZI(-6wM}p&JJiFXiB#2^>tB$-&fR2wF8Ch5=DQM-~w zojvMYM4HIv+QPa@f?18Ed;+K!@z>@x2$B(^Yil`2P6I^B%`VX~7Pe07_RbJ}?z4j+ z=2-a?KvJesmgkkDt68n&O^DM>(R%M%M8-KS@jN9Eo(Gr@BQ&UXjdWq2A3A0 zdL!ePv8J`Y$l8S+p@#sP3cySk1o}>7VSRmKV?$p7+6I@-4X<1ObeU8Hb+oeXZYKqo z>yY11hapw|3P3bomgp{1FsEx(CNsW8X_`R!t?;L-sx#^#^Ph$Y zOJ0lB0GIh}AiBFKku4KG0o#q%EuWe~4|IvTz+82aBey&NL2cykSe}v~ygUZLVggsN zY7L^j{59P{tN?WlA>JhfTR#MSIR=6<OkD{$vo3w{dVvN{-0 zh(DhN_7b`NM{UQp{1~`zVpz^UPrh|KU{}etCJ+2vN0N=KUYi-a9^u;{W5n z_g-?j0Lq1WG(*A>5-t#`1d;%kPy?a&UPJF4L7F06L=aF!s#Iyxl&T`20s<=4LXqA? zlw!f(>pe3&yBGL=e!s`#_s8z-&igs?QMOSmMs;U5MYS>X%Hb85s%T(C{IVl-`4NH$o~3#jN0B|S#8ACgnSQd`~>cbe!r80SkmTdc+6f|9&U zloz1if_41};%*Y9fN7A06YY&k_dZc4h=*H01gOBlIkg0r;aHL>U zl|a-aMO8E!;1MOLWDs>MO4NNt)iC~xP`bK+=xox2>-JKgW1T>jc6zmHWY|*IErG^P$a8{tUNsaCZ4%A!juFOW0ISQ|W04fFjOL zeq^F31o14C4_?t?qO}{@>BbF#OKRF{)G56~f*O$U2!u^}`Xn ziu0>~P}8`=yawTH4akO8QT3cN(06-*skI=sGi9@+9(BgNl1|Q!)0L`k0i4gGNL+KqQ&H_e3=XEOXATNf@K>F~;*^Cmz`k$s`mtl8cbzG?I3hDUfPE2+n$*9}_Hz~W z6NtMOr5`>f>Iym0NuloIaD8L5=R1`)^A#-|vKO5cDhcV!7NN?I9W{nOWFDGSVOS#& z?JP=_jG!uo_`+09hl7}CQRsQMvGQx&xc#1@MRer6*Nf^Qe{V+ob^5wJg5yuJJc z+B0O;Vud~e=EM!Eva70$phku?#MKs=DFULjMcK4G)sHit+CkCT* zmWK3Sh5NTRq~k3@^aU-Airo{k<~^|QfLoP?RaH@_JQ4C08X1xBXTVNcsL-fNU7*)O zvhP(k-Ub$i!cv*mXi%jTk)DS1HZN5aB2>x}$zHO8_k`ZT^F`Rx7;Km4@VH(AEfG5T zm_o+@o0A2#N<{IMLsy|47SHbWVE0(OC_z;XU;Q2h-6ZtZB>^u7I$%?!!eJ&gJhU}@W`c?ZQ8}2BJ^57HnSiv%h0fiB3)c`x3ynd~PSiMK zUT7MegQ9o_LO59iR>_-fo8Z@lb{nbqC1CgeU%VCFOzA*q%lazjImG(&c`@x*Pb7CH zbP~q2!n~YucqfLnFOoLY%+n;- zMf7Y$LH~pZ{2lBwd9p^C%DhFc*Kh}kNV#yk#bSFVl4yWxQY%ztV}t8PHpx3F4R8l5 zf+#O*CvMQ1bQzCfV~gw6E@rGzh%xthv8;<)hw{CGw7zz6h2au)(k{f1wVw6LF;E=} z!(-97?Bc%}mDr`{U}?m!9*jR+eQ}4dee@5gT=B@M=)g!{fHoYxNPf|2Jaw&)#?vnr zTm@!j_2801fwvEbMt4{fbO+gNY5=0S)(GIp+W>NfZA0z_FaW~gcHmujRg3~*^ZJ0} zUfyg7=i32(_hQ6_y@*bgFnTkDhcqCk=~+gniFY-|%V9}*6n_!y?-s8gqA*UVt{Juo zy&9o9M=5ySv8nQ~E`&l`gk4ym&`QASSg5!dtOHtavB6!#_`?99wF|Hz7HT&@phLqx z{ac|kfi1UCZGgDqrs@e{zoI$_)qB7mdk$}+bHX;@<%&SB1AAhjc7uuA?q+~JMK9=3>N5#uoIstbRn>{7HT*6 z*ew`*A?(oxg&qL*gN51+7U=!3cTxXDG28lHc-*klW}8!XT=?t4{~!ApQ`x6o%wSnyTdU0W&D z$H88F4iAF`+R*(Uh7H2tzk%f_qszi>aGvZa;STQdQOb%KV3jP?Zm>WHxJzJ!DYP~Q z*26-dF<9_p-5(ZIswaS*^Bf)q3v`w{^1M>L9@riWwHtf|?UAwA?b?F>O5vvMG_dOy z%9fdznBN8)o84`@s@K5=dQ4YRnS z6MS&}h_^%0FLUzIHL7A)C4l6_izR+Z8eNfJl1AU;T~b>iaXZCpr07Z6**Fe0fm*^KCRMETu!(dHBc__4^KGv6MxZ zSj0yVC00bNp?R-4WUPN#Bw{s^qF1)hRk36YhnF+uGGM!>c&7@89TNJje8Yh8t8NiKkoq8Oj1Kp_0;$-U#5kG>=|YQ`48jzS zr?n7lw}dlT7%Tj{#TS>|hem```xd}?3lbU>^x?Q>3i<$r3gJkp3P4?$`_!i44+GM2Z2wu!1L!3T!Fe^ z9NrlSRq;QgJTIf-Vw3Sb4Vh5FBUBcG6ie9LCOk(CAn0ZZ2c;tcD;0SmVs1Rayxq2J z+E}1dEnFm|pvV1d;%;VW8GsEIBoaikgV&WYFVOhE6?GWI_ZGz|qt$GKJ0zw6jX;Yv z966-BApT^kGiwIWXEjQ%2<1MD6`C2yiMpPT?^P4v{%K4URmLkKE+Z-fVI@1jZA(l^ za;Bl*%0OcXTUmf~u*a0Ahw$nMU@(NEEI|6tW0GmgAbi-v8s3KRT|2<;@tB%)e7XX* zLb%HguzNhFA<5{zQl4C2YDJ z*gYQ8n_}?pLl~I|VKqCzUf-C3m#|)#Hf8b3vXLB@!6YK!H$74p* z)Snf=AG|EH0689snMzZ(A@)uP4zN(vaSzuNTu%0|;E$F5De7>HKnwpuf9_X9|H?VFIQz(WJG9{&i$C7#(y8fx=0`~8bgxX&LLo;@!dd`WOWGZGazml zk4RDumty7`d1k28GC>SxN?t8HwZQ0p2iF-!(hLv_p3$}VF;ZM(U@9n&f;wg7!TU!+4FoZUDVwhPxzKv^q(>?- zSd?QmJR(KO)-(^MAC|AB9IgSF&`2e&CBeQ#wunnMmd1R8lDL`vl6rYn6w^w> zqPH)*{9+2V$henNa!vUc-4WlUeyokVO{^`D(HAi%Gi4MjT7MZH)iMT`iI+>L`Jr~G zTfPiRLlvshFE5|$AcG(0i7aO=Nn>%@eV-5~gY%>}@%Z$8N-`05QsXm_?jnw26pKx! zgOd!0Zx7Kqq;V0O@17`5CHS1^0RlrnOM!eo|ILM}5d76-K8Q7g!eC?e&HHiO zo<2dAvajRg4z!PtxmV@uOk5GO^HerpqQRw}o#(RoDjRkAm^)U!B%>i8^Tak^ve6vJ zX|$4!?nVQ8;@ut+p+wXtu3Wy{d}abY={G3m!lc#^c4DA_0=OsP>r0K=Ivkf^GL43C zf(6v1ZwdhzL<^r_MSTDUErN786Eclj)C_$H-!Qt|ilv`Ia!^Y>90ix>(RA?3DO+uL z9Ox&AZ)8DgQiY2^*3subndyX7$5RZOOviJIHNnrx*X<|ja}OV&APWZhft1sjNnE7d zU%-kz~ZY8qzhcni`6b{&Q1L&qI5T&9kX zA^p^@LlF1ra4AxD`~c~Xb{!vNgN{Gx*866bA3^%mu0s${$h`pbCq!Nf;Ne^po6bx3 zE;w-*`3c``3nB^9R3_x*sY!weF&=g@b+m`Ho28=;eZC90+o)C)k1(NQ0;ICQ>(H>b zA#$unC2=J|kaa)7ttrp%|aW8b#dXU=t1M z#X@DR5XKvExURC=Ot!@oW7IOn!#nskNW@%jiz$Q^3~?&o?-t~QGZ2eh2hUsSzSC}#% zLOfdatu^Y^kd=e}gV0q=XI0KP^KCXhDj*Auib7a|0jWU_XMH=3L3mj4g{A<6bu0}E z*lirntu%Cju$QGlj(2@u7+*I>(s(%0BnYQj8WeEI_yw&8yEteCgzM}YctGs?#t6mB z4WZ#n2#?q`2;f`eZhgGqVhvXzykpnEqgCH`#fH!rLf1XJa@ZAuk9?do z72K|xpwH+0qOZI;=rpj)!KfN9`bs+szyl(#-M=8h z@wicDahOS6cE!L*k@aFA5-dvGjw;2P&Ij))U3EdUu_(4n8kZ`DslI!zl1)((1A$Di zFn-14;T_LF{{)t_bPh&WkmdtftT7nH@9KPixgHl%$?b&jfCfx2yr9CuI-#G$2GGwS zZZaj?6lFS(VSTy77QUe}7=jj)*E$HMctq*zhK$AByH4m=(dQtJ zS-Mmn1$8WB10K&}+<6_uAC@jfg`!jLiw@h{Q{4tHLSbHP>Nc) zZ2!eb+6csBAT^M?`PLB2)vX@l#lGjlkHI6}*u`SRo3{%Nmu1h(-tC;QEcPS(r>SEt z7t49pF)6^l?z4~Vi6d_l_*1QTS6?i8!1qo$mOA5>n-3~$h zDCp&b7AtDXk&UB8SxtnG6<8fQR!93NG&hdxzW~$v|G&qNSJqh>QbHcV+U_56w7)`6bF?(J_V3VX_Gk`Q=wCqMnm2BM9P_9t zuFV%oa8z$b8OC+ni9@F-&$vE!5wG#Lj}ScRDvHi&oZ#abq4g2`jvt2$KN2(#=i-(X zMsOPn!P~L8ZU-r8Qrw70fZ`GEd5A1}ViD5> z`q6KgHY9*1L4YTMsdh9F-KMyabmRrrAshXG}%Pj!*LA zFibmu@eoR$)@zx+Ddn7***LPI= zw^A`_MYIBrDl1Ph?j~mxB3I>4%HwiVmI#h2?|#Ho6gg{a%CD&Ut?HpMLLu86SH|&o z@sW5P{-`|aSZ>@Naq&|SF@6{dHLkMMuH9VPE{Ci4LQbZ}7OA5 zwl+pTA{zdAufO56hVYwkX$kL3PPF{~CLD&-z+eoC{Y~YWJ5UFg-rr1~c}ft+_qU)I z!RE#0b032h@Q8`K$F?a0J*};$N}1fyj~gV9(#5vl~l8aYOqD zty|!56oq;^jfg+9>KHyV<-_uYqnpDak05)>@^~d@?}UHUcbDL1Mlj`X1phxaB`-mP z(J=bQPy)hU=5VQ3g^#1!2y3dtJ>{U);bl#Vm`J@K9cB^i4l;$4X)*-!gN0IuiawoI zL%P)>L?J8TEcz0H6P7TMQ&++{bP0k7!9r8_AkNeW6oMKQflX#gU58k@fL6f2su4PP zTurDXh?g}bzWl~z?uUEazi!QS0QDejX8{~ZQpKsxf1o}-UW6N^!9ZTMFi{YG|4B9g zKb!)7Rw6Qf_!8oWuav$;^sV6V@=X%eU<2O=4GKI`;f%EO233-e#T&4=s?^I!R$583DB;-%1F6Oc_n!|H0;~iYq{lbQz9XPCXDhL`yt1_zHQ;B0w=OfSHcdMHUl-LkT8J zJq3t1AnZUEBptex!eb~r1;0#m9^f?#Zp3LSX>Fn>kc6U7B5n1wuu1C?<%cBJl5*T2 zTbdD7fw-Q9u!10@FHw7lx!UR)NElRv_N)>a-{l8G5RY)xlZj0jB zl-c4!a4DmY&eOjAIgEj)fh7T{ZDH!o6^}6e1&v{Q@a)9ppw1wAY6?Ah0TeSntBmr; zHK2(QPGz7A=hPtwkp6fh1M^RWhUE~hwKOQ8qHzhmNTJ~Xgx^>i-AH-2d=TGnQjuAb=NJ;Q5D587V(C@-Hw3 zqv0Sw1eI7Q%D}@BP$T%8CI5QE@hyl9NIL`*9#wJpizNRMqx@oELxH@aF;ofuBFX=Q z5q(mbF%QB;49F@WKPmG6Z2bI0b%M7;xW@wG#3xJffm5aNNIi-0pIK%zQ+`e4H=GO6 zSN)Z%_{hj|{z|6xWst92+ z1LoZzfZ@(}Fi7G76}5n{y`@2ZNaKIq`Di1ALm(KZW1AI(Keh4CcW$@@VjiSREuyDv zd-yv8{~G7f61d1aAl<78^l$jhe|(>+SOHA58K)t;uH_yMlL^W9^!^{6Cp)SJ%4iMO zFE({;1gcVGrT#n4eWhSi9FQtmFx7Sn>^~=as;Lo>%q$q+DKhm~;R}hMd?33@d>qi} z!8kI*FYDvyJb6K7W(9z4!H~!i?mnKP?Qa%RY6Ft~2FPg(;|B)__Nw^1hfK+VQo94` zADV!BsXC^a`ge!aTEjItdmDWEh0Rt;rPZ~lOD%8*L)LuCTzN3nf;lV|_SIe3e6GrS zOf-iy(;~RLU~0<2*Xa|Qk4Kk5W5K*_aiZw0!m33*M+44dY#PH#*8<#b!J_%8N%zpM z#Md%j!hJpK1;$PQIioT7jXR^s@h67fLyhM+20ef@1hvg}Q_FAeYtb)w=J;!cHbk3j zP$4iSn3Ff{S=1pE*{FY^u1V-G-*8{9D#Q&fMDzjj<+ZpDp;KRFE)&d%EF2F}pVzC) zHV(@mQnq26a7n$NAknBH=$qrMd1^cK@E$LNY0sSk@cvOqc!*!5`(w1p`nCEcqGH~gF&x^sN)T2c&1 zZ2z8!t2{X@6`fasxzOWdPtI`$q$fuh{;VhGBRsH&f})k!c^0#I|I?GxAB6Daus(;Y z#YIGoYyNEqRVs094#Ga=_}GO*)A4Z)>XqYT6An$s$5RfLj*m@(mX43S?JdX0BRp>vCYkRwdmPP$lDP z6o&@oa)^hiTA7VB^6^-!PPQ(V%i#iIC9*=B%YnlzmxDYrT@Lchayd)@I|Z9>H;UQj za#)D4l{(z>Ii$Efg+HPrZHM4dUip_V9&rJESu&%I%Loy(1#_|hFF1-q0 zA9Ogv5lsEC8*0hb5Pb~2j<6XVF7>MLar8dI*6480RcLj1S(73r(mtGgV-dk#g&!ff z6D*WERP^ce6w++y1IvUxq8ycQ78Qb^geAPqsVm_eN`#NJN3fzuMC)F>aGE1+*MAR(hRhY?#(yP!N z^-Fmb`tYIjDzH}NRk+HB&v+HM_Gz!ea@=ievH5<-6$tVw>_O;PTH<*u>c<-huz3|O z;`Dcm8G}O!T3&?^)Zc>GWC9+6JcTZ$(1$3NSD`Gx6blad7PZ3iDl~+IzbsLzve~5Y zD)fWoRZGfogKU9UVK&4|Erb;WA@C}E4DkUAxsMVw5!0)13gXKe(RELH6*{BS=Yd}O z2ZXzuHdbUsdlg=HD=Hd9X^RqB(q4rQ_y+)?s}6`}7R5%H?t)(^09Q8khV&JS(4}l* zIgB3tVHA7m-?uQKNI4A(8YyU(8{u-$4iI}ag+Y$;Ds(%7@@L=-gugJ5k8^5y6=r;( zG(3UO(cR3v2~;%7gBKbKLKww>)S$fz4Q62-A5J0(LSEim)l2PF*o+=`CIjst>}uDb zyb7)G8c=8$3*l>a4FYIww0oj7EQWBUU4!x}w0Tn*xevmFc0hR*_IVU=0m5r`KzS9S zvtdFi8%dd{1lV*ol~-Z;L}f!XgmHF2c@@%bVu>kE= zcsUNSCqOWhh2riOHy>(*@+!QL9TjIeq+5dt58s}^lvm*fI#%>GkP{k1l~7)VPc|zv zZbA4v1Lg(gNdWLFY^AI}E3M1z#n`0qNV8ARq28Y&9~43 zVO?~%r#@F2?OPZE!FVk+eG4Dr8e6`FN641&EpT$^iSoItVKE@F{SP3n@-47bbYTVN zy8Iyn@5T26AbktM@MnDsDaG&?M^J+<8E)YwY~KI$EkuJ5z6I9jaCM%DsBz8x0}xG4 zs)&X%7d0>V8VkVVf} zoLatxcs#iTuqp`fWHP0F3t@OL(N~(_2&Nw8TlfT{de%%=m=aY``xfrQgU?lp2$xXG z;7wqQ@Wbiihm|YeLRV1YR^m90s7KQfGcLX*LZ9_5Fk-8cm#Q&aV**&^TbP1U*UD_< zq*xwt)yaf|)SS+cJP>y!E429*ILz`b$TQQoAkQq{!cR!`S8Tq4-@*#qfoeL#p9mx9 zk>Q@{lfDH%R*dDEKtF=GuBl+(!loAh z{0rfWsBf}tJRB+5w{Z3~ZXtX?%Gj_xFc$s;HUK}I0)AQ|GJg0H;)k!4uG_k{JG^`! zL`~<4;y;-@2DMw<7?y8=+i~Sv5S3Z_7XC&A{hZu%vr!Qur3Wf`tD(N9M%Caf57uZ{aq?|5^wu z2twdn$T`&ED2h#K$v_F3i0NA>2XQrx=(;C;3t!^Ph6B(`tw8X4L^g9UBvUgM7Bqkd zgQ-_ROtUDFB}E;jbMP7nY6XZ*7R5%P3o51}{6Y;@K+i!)Pg{hz5M0V8mc!V*1K1rP zPb^F*(!PZxysTZ1%R#x(LoSF-)d}reI8qYj&p-tTlNk7#^I*CT;*HJlW(y6?A#7)9 z&@&diB1h zR6(VY@-6Ja)L&u4s}R0!2b6E&+kAM5$JzV0 zAu`L_x3IGj8bo>k@qbwm)3kIx>f@~`4+~!uQaTLaJ^lF@-4hrN*Qtx!lQN#%C}Gq z{tfQ3(=`b1+BGQO!me|u<9rvp@xCZ0Hgy5DZ-H>rQ*j8&vQQR=svyd@@O=!3+K@K2 zh~u*DQND#=mV@X8=|D}Of5YSZ_&!apsa9tyWbbOZhuaZZ6SZ&QETp1&*@}ZNv!E(P zLxDc{1la*1HnA5(6!vmNILxFj*sX`FG1#y|RZ(-Iv<`Tfvw74vVrF{!+(fu)~9l)Lz zESewfTbO#*^es#RGEHNaZ{Z$n=QswfgmgO-)_s=6w{UzLb4S6P)tWrh5!v!Bd@!H; za-wG70je@8`T)Vcg@)z%eUcYUTo%sqEpRu@>eXdicMq2;+eUm1K;Aw`G#me^6(#($ z7yD8rI?ZZ_-_kFIM3wfSBbm_Y492Qrshos2UY`u3#8Np4(*`0r3=*6Mf9ajjHRc3P z=cnSZTR}eLfp$Xokk@g@tL7wRmOxzbwlbkdPK0LT1$0RC4HMqxsY;@6m@wBp1&7=V zOqkb$L-`Z$g!y?mlzWT`3yR{f3H9qd(2=l&JY(_SY}kD9cc2Yx=ZNq%L~#hLq6MCx z(NKEIfpK_uz-|?PD>VYr&cYIzP{MuG4}wvau&PaXjHW@b#1a-meY2$^dqoLux|WGm z)Y-OA!5*}Dk&>c#et@DbfVgc@B1uKX(*O))g)Y~t_)rd;%(aKpMl;MKtb~_oP(yNX z9w{C~d8X1ieE|H@C80Vk!+m?0feZ+nX*DKLmsUg3cMSB0aG0e*c8n65(EG(mYIqaE zcPtGGXiE!T#?(gEunEE)mIm1|O6W%S(51Y=zzGP?SQ-@2kE(x-xlauI4&f8K2JRRo z45z>!N<;2(=>K6;RY1=5Oc+OF-c}kaK$ygUSq|KDN|;Ks(asAan?u;n4sg#YVGfPO zx8njB4&hikz&)pg_ox?q7Q)E+5H7X@+;d7;LG`XE8+Jmt&kpd*jD(Nq(E`=sI1Awg zJHTD5ge}x<2c}1IIs647jko23yH*K1XfM916hI*eqwN5%+n#Wk686J`%rzhx!a59y zd&Sd&tFw1Hbj!|5!jF^$FOxuf02^YV?HCo^iG)8XM@jh1S>Fr*3oJ+j}8s(>u30sVaGU_&H2CP#siX!1jeF-~^kuw!F8pLFa;v2}M zelW)NP*-UQi1ijF%0%h9VVtg^bR7h7+M1;pYj@4Lf_*= z+5}s*9$`CmxTjN)RbOg>wu&u@`n?-cii_ud!?RW~A*?EK4OX=p5DnJLXq5X!VcOjC zpD$t5%caB>{13;8Ve7M)vLB&`u=$Pzn{ozWzv^($Nj60KA# z*R|n#Ri7745(n0zNjYvZcWof-OJs|$Mq|hmbDs^58{ehkeiI?)sT9oaG$w8n5LSOt0A$O z|JQ0rBf*-hA&o=!^lC_R5D9tx|F9Yom!-KH64zVrF6cB@L;4LinyVo#g?k!lWJ$_GiGrGlv20TVgdN_5%F|lW7WsZ(4v}4XNL|=*|Ja{BKA%Ga=K^t0BFS z#L~l%e6OV*j)KdhRzv!%I3u?pev}2#t07IVZl;rKD&Bu!lj(SVWlefDqy-q*xRC{e zDg&vmF_XAR%^qUaIAL&GNcoSzRG#%}NPnRzlsd*j`kGybS`BH@FjL0|kbY>_p;kkh zT7#61&mcW)*P&KJTKJ}^<1(Z-?K;$INH5_fm@L}RX?RJ9O%*LH&4!aFG$9Wf5s{Y? zkd|gbUO%oS3^3u46ApDRNjPC7Pwvw z>0DV%ghBgZ(0ZG2M=2!aF+NW=bMO@l=kcY|t0DcW6TZqqz9!acNX2TKb~~qAG1Y2F zHw&947iFP}sa8XJxZAWg#U@m%A&qQkTHD4ZRI4G?&W#xkBA+8{X$oPyu?xK~S#9Rp zVye}Uj`lEPZnni#t0A33Z%4*Freo^WkOp8rid^C7284fNQ`P!KRAPsBBh1mOA&nVl zE_0N31|B=u?5ti5>9?*XmJB4r!g!$V5qfKyt06_>0?Fiif*bXGR;`9Kqbxai*pB%R z;MQ6!mzlV>@~+maAuakEf8{13dc&2 zF^IsXihygd*{G=1kls7VTy-$@El#OZt0Cn^*H>ED1IXB5OsJEOMZFqQ??PxAP>fDm z0C)pO5I3B-DddiC23#|>8dBARX1=}x{LBAHL9K@LbcLD1Uw}Qc{;w3Q)sUjW#4#st zY-=^7Bm~yi0{P_3bBC)Hx9HYtNL|4Uu(*PZSgRpTfMlj6Eh?qvYDgbIvR+G7Z$f1Ud-hq{ciV3B4N9=MT^e!xNQmgLuG{`4D3N1y)09@sBJ-dI4=_9&9SB z(!qh%kjlOy3yn%cSdjs#LAocf8d6S-&iO)9LkL?~8WgbG$eExt41{n51Evl9_j*_j zY2_XyjVn)YLAZbc^HC~*Lq@M64hMUxXbXg&*fp^K0;?fKATvV4cMzVlYY@P<#==DRE}*FFZ^8A4O_{~l)1)rDoS;P3%YsO;C~-Tg6l*%~eXDe} z1kux?MAImY)2kundI2TzDv&oVY#Z)v5AW2d9IGMq?hR}uko6jaQED|LBSIy25W!os|DRNcD`;xSXQO;M(+)sPyLQW?xO2mK#x!4!{{u^Q5YnyR8Ff~diiyoRFL z*Q+7@R~@|*uB#nD^tN;HsykR&zZS%Hrlj>smssa$W5^JU zRK%G2IEWval6I*)3hG!$esmSZnED|IUPUlCk7_lfn62tIC=8;QrmXR{Sjd%o+hR4O zuin7{FWk#*j5Y9f<;8V$``+h{v|R9i6|c1)$c+J???QX1dyxVa>NR zlMkmv;P6B4jvJfz<8U?i-b>KW^>DnFK1TSb*nItQxu+d$fDtZEKUJ*DIw$d+lj zsU!juN_}VfpUA{0a~FU^42hh0#=|-+WDgr+spT#N|J3?~BCmkDpM?~|e!hr~R-fRj zVak@L0<6#W;5znRel5`|geT~>I-kJ--NxVr!+TqB*s5k;0QT=nhDp#VCl-tUG@+7KGxoyioL8a@7$$1>+a4oyf(LViGN84*f z+sFU2A*1bIV@BgJM^5U|0j~W7@o{$%)MrsRyn2X7{LxcanvLsMwjEUtk}>Y+N)^yF zlpRfN_&#_}Ub@n8ygMvAm!{eQD+QfvvBHw0+mkDpc++q`V0g>D-8`5=&@~1o#jRCA zO>r%{??XmQ$As)vVQmrC>R^AwX|)>9K}i86v1*I>0Sw; zaS-=bg*dLK#;u~{s4x>+97aXdwF?}6l zMuf6YPlPw7n+SWT!#&#|g|HDvYC&O0I1e@%N%ga0>CMHEwm$k0!wasLcF9_rLN^CDorB*OkqeE>6r$|!>h7kMIBx>t5QGj zM^N=Xhz%CSHV71na)+bRps~1HIW8Rnb&N@2nXJEjnH=6%A$En<29sE+#6ma$OJ+v{ zR;4b-qWHhl$&r|(PAcw&q}p;^G)VTN>=LU>N&U7Vc%cJr4u9lVuHF1|b`xNKTW8`Kuj758$79;6W%$R-~0@ZiOL6zooM^2 zZNjHnl@A%>g5&9so$vh0-x}}XcFxX^ips~0&3w$yipnR94{@AK=iNB@&Y*9g`6M=9 zJQ;)4ajyqO*|YbKQwlt zJrru@f_P6;u#}%3mH#zr0T61oLHL;lOf~#^sT*9OfPV790YfOp!c=~g$z4IVR zBmURh$}VS~UsQ@N6n-vj(r}5UksB{PDra+caH?eEK_oI|Q;7e-I|p4aI_v+ebTt9d z;Tc`ISXVCR&7(@!ND!|*qw8RH!%;b(bE}ISe357|h?SbM8v6RB4U$XAH|PK4=KAya zeXIV6R>D?)PTK0vbzA-UDX9KrUxY%y<|{9*zpefhM`&3s@l@uL)b*!yM|^Ao8>t?M zCQMZm@pb)aS`uF%G0+#nA$CC3pJQ_{qUAUg3DJv?wkA_!(WQ{zSlcD6+5<#DQmYsru9H zB~(c+(4RqE(Uhz|Tsf@z<7&_oTw=G>#b_FLwM7N*VQ&q4tJd&8%+*Tlqa^Eg0qbjP z8WXvtbrp%hGc2*&jQ>BHh6zn?oe?&j`v0SepS=!ON?q1eiT^l5HT>PsQ`Zf@I{DuX zKX(Egu31IJ6MFQL=RKjh4`awDG_QXnI$4zh+;>t>=nFX1Pw1hr<`rzdc}HN28Qz%q z+tdX*-18o!))RUS1lzSR%M-fhSUe3Oq;Ii1&(u;@?a9EQenQ_WhH)iBe{d-Bp`cb0 zl27Qzvy`R+07^0>jP%3<3VuRQ#AAo5foNn=Y=c1c6Z*_ulsrPI7pQ?u3d^h>ro+n@ z$93Wwm`YX7;z{vr2Z;a5K^5;lKIBJXrNEbbxPlK;zrmp{-tUmgIZo*WLT$x+3t^9R zxaTyaR`I%#a9(UOQkLTV_$g+kASRUtQH80WShZ(8!gTSbZNYPgp{4*jTF?#&$>J>> zP?|;pn97ha(lZ@UaPeN83ss9jY_ur0L7=*L4`bNIap^FqZJ6Nyy6`Pv8%if zwYTIbUgR&4SBvF0X<|lI$qASFlsgn9C-TyyqHs&T@edwUqHs%2F^-|#djQ=PD95M3 zKK!!{>S+=Ztp;^+xzcjf=q^NSwxuGSwj3;$OXZ#8McRv*+$Gmfd!&YA2*8l1s^axWDX5A!ln-Ua z8;wI<@#-(f`#)^H@d&k5ylw~^sKY&zA+;*r1PEqnVU~(lW*i1*5Yj5_K4xkLtM(Mf zp{{rv_rf91&=Ks;SWp=W$%;20@r0)P2sMydX{09vr@JLr<-DhsgxQHexm=7{@#>)-(DxiHmaE~Nu6U8jy3)vsclWpskQMLLe>y-` zyan}jfUI~|Fb_!8L|O5khAF}&Rz)iLMO$Q1RlH9-sEQ{FLimJuMGHr^U;c%a*`k|Z z@4A87kBaxrhluvfkdG%VtBS|dlU2owytay9y%7MQdqOwpYzZWzs-j+DD z9~m6n0kOnRSG+#cbuE$=FTAL(MY7_RETIWm@d{e?Ojf*me`-QjytWt|$QDn0GF$SC z?~%Bwc=-mXiYE%fHbZy#IvAfV?pN$x6?jHar7AVnAlfq(@9$d(l|7lT+c=bu+FX1n zE1nmJy5dz`jSet2-%AL!RlF7m>!QOwK1i*KHw1$5T9~EcZHf(JL zsjT3X>LAosyxS1=nGW|ffYd79lMwu(g;|RC(mqU0gpeL%7XlM~%~-W(I8Jr(-W!4S zIv6SfAkKm&NJtj%Y5WD8(3A?GDMP|YPjf)Q#XB++s(OMLWl zGBCp%QyzpB)#0AkAhn9OECf}xFiY`<567%rXr-1Qx-vD5ReOFwm@Zzz9sM;!V*pIC zpbHX`#rxpA(zF!77KVh8o~?j_i+9~SP<05z8H-{Y1geX-J#KoAOZP!NW>Q!ti#OzT zE?%DI<|@aN%_>#t{L%A@mtRAu#)0P$sp8$hhq8FL;!qcF+x2J!u=zeksI7R1AZ(lt z_w0w%D&E-;ysw2>ig#K(UQIzr+p+tcDR$nHrveUj@$TA+N{awGkKHwF3aTa{S-da5 zp)@&=(FknPNKbA+!NuFD9ttD|L?w%28w9G0H&7W%#~_p%fojR5uuK-On9S$pse7)P z++|9vvsr_96>8K!Drw6q|=d{i`Wiy2aF!$pzG@ zH)-GRI4!77izeL~gVRFlG&ZR*$}qXGIxUkFh9)n$h&oM7DuD+~@=NNpdeU+jkX%%q z)=7HU45v}*v{BNVU*j}dowiC^cm=0EI)R4UDAp+{FFeG_F?3p-_Ds6l8q!#mqk%~o zqi`CpPKPE{{t~C9DP%s!9htNQz1-w-GzZyt78_4VCDCDT#d?F>CUJ7{y`U$$7 z#U@cwvHd8nM7kr+r%=+m?S>;cKslk#S!^~X{fn+xayrexWpNf;KuIA^oYzz5ODHKj zpVwFCt0}1R^nfxbUq)j$_iI`b?fFgl54Y@$)j9hhM|^Ek5K&%isK z&creMxKo;)Z-JrAX8b#PNJ>jTe*3jujCcL5S=_HmWgNEm!&FD$<8wG}u4++W7)mXr zLk{ppu@Hyx6O^QMbnxjfeAt^cMo@Si98Vy&mxd!m-V70R>$xFtPLSk%($?yAj|F39WXD@v?Z4nevBJc7aKjN-~0SA+ssjoNPAz%i&_D zl5=js?Zk8hJ&c1zbqv83N3e)*n%fYqVbwO`5)nH*q>weWMbwDXh&ob6?fi`NDrfbY zv~H9sb>yPoaQRa1$nXgI{2x#=M5UlLOtHVx!*#^Nrzo1H!p!N3h}Bzir>75&)MB#!LKvg!yb$3^_7G&YT4dl5G}fyDln z!nURmksLda!b{SKSFIE{PiE0=My66G%A#Auh`vNzumzhyn#(C_$tNu3BlE&G;A_%P zYCq3HQIAA?K1F6Xipu2StFu8S;lx8SD;GikZHJx7Qd3DLM45_0u+&A+Cbsocsi;0< z+E$N9FoO2VJJKcV zEF{prI?krbGk2g(KAcUHXE_3k;Wwx@U7mRY>+r~|Hbb7}3A~HzU2Ud3^9IJF&8fy8 zUm}IV0XmDbH|1H;z!7} zPHx#A)#7kn_~H)56)3tFG5G<9Ip1bPS!7%)0JibnwqF$Wl;>!OpmdaX)qiE$8<`L_ zKpcsJRjmMDhMcsjF_QaNl>dpKJc$a`rM6MXN(_U&-0rliX7lUlW?og!vVx{NowRbxd_KX{JnoOJv)in^u% z^6U)CpwiGE1BI#+1yE4~qQz6jHR86XnKXhY&x%XUEmp46uzH-l$$MCW3UqcF1V8bf zO{F(XnYhQX3RG^4p;MgVM*yoez^CxYJi_`=Dc5)}4!TqB+) zLIZ=MOCr+RKn{bK{9_c=~_E4|Y%gqCA&n88i&Y6cbT0-Q2a0bo0E1 zOgB#$iB$Wjyd1I$d)Gf64D+kMToPTOfCtN0R9IU0TJc|u1W-aORtW2OXYpEyC5(C2svikB2x)0ziL!Q+M z+^Y_<0S`NjVvPb1_^hEkYaAGa-eL8|@~lZL_CwHpWHc@Q?Zdp|5LE6>oYtP3hNa~QZjp42|> zzL@EuCgD&N3zb1vaVw_gc5=Z} zRSxHp7CTrwl?$$&>|M7tBbg7yg6M>%4Q4B749moWgtbZ_g4}hGWJei$@pFiwG?xA_QHkE?i2YEd1;PR=Y<2_j@7IjI1~ajCnvGtl-qKm;8q1S^ip+A+i= zpm`;_GHGv#a+%A)oStk-ISjzAe*iS&yb#Z~vO0q(@hf~e3OKn=6VJl3O{$8Z-MC1p zC1nH6bF<_%%t@W_p!09Nl7w%fDX?|QWZT&%L1|ztmBOF|ET)Wx%%}Zps|=We9>v|&` zI_o*QLYDoH6#Ebac3eLt?bejk+Wd_SAL+Ruw$o?=WzyeV;Xn+1eSO!rW zGfbu#L9X!-G?tCfgdm}~>trLCgSMd=NjkvFC?^%fjM}7=!u*vSMVKE!6){jt+NHA2 z;cT8XAksZ3KNnz`a=hos%b5M^Bv&P|Sl zzM9LvQf~(hk0H3@U`{h9(|v_n?EqIxD!HKr%CYVk(R~@puWnAxM^jkZ@W(NDFH|>Q z%mIfZoLAIxgx`As`3Y}46!~+E>6P$Oz=6i>8##f2G!Ff?qa?mUJgff632WeN4lG!sztie2NFG3$Ry)(Zs4!k=ATKkuVee9Ch zS`En!kZ10|5|$0j%egFup+aYz4cY*0Mlo+-A}T`q;BiO!tY~2KB%BSIF3w^DCzjxB z=zMWjCJ=@XLeqyW5b+WNd)<%?=lj7Z)-#a1IAkN_S+B~(hNX9<_hFci=i%Vgbr$zl zne@?%4#C*apD->M| zL#_1X>Iyld*P(8wuTYoB8GR0|M*2$r&oEpgXY{)lkm4#{>>EBFXS4$&!}Qg>K9^Cf zy0Zjv^++#G#$i+jY`#-?aB*I}9G*Z05mrKntD7p0?%}J9^zy4}flY?AjwU=$KNn@t zeF2iG)C?!o9>QMF0JnMps8TBmz^f2W%L2rbldF94d5rKyQ@I?#S`DF;FK{WRG{Ja@ z_96VBC5xq*^&zYE*{@hk&w%_F$o|uEdBJ|+tHzo=KO)DTOW5H(UL1ys>9t!RccMS) zMZ+42&39dtN-S--0mXHCq~p6p#HU2aYOq|Cn#_AFRVfCj?$=Pl*M!;w=w(415h;BS zd(zWGa^nLQh9&}-^$fI_FJ%VB;g7i3fK>oKeg^7-2Yz~k(W6ynj{x{77!tLU-%`Q} zo!)Tdc-8zq1Z8|}=FTIU-B|Kqz?k0Xq)S1C07PpDN>bVI#-*yO>yiXnZI;U-5V?z^ zUrz&Sau@w#E3}lm7ZkBQLQII#Q0!J<1RI~`P<@WeF;j~O| zK4*=}?{3IWYPs!hd?GJt>`ka^(KTEpcMIqv#zk_T_NX7QDS8EKWV>21 z6jc|7FIjnBmZ+0*;#pA~n~jnUoG8*5>N5vQm%7TDd^NDmpT~Jlx>(vyJBlXSzo(;bXby8JwB!PRSgSl)`(S<{Ihl zhkd3v&J@Ry?s15f={~!ZrE=dLu`=C*1^=4hSp&L*Re9fA>_5@Rk?s+KY@5!~H$?cg zR6ed+llL;5nM_6UQ##ZARP6hTSTcn7k!~4s6VJ*_cOSu=t&BN=Nho~yibf&F*=Bff z+eErw=i}*XMfh7dj&$=AAksYyl_Oh@$s&9WGwZ$LcpD%0j16?+-N$C2(WkVd+<;t`YS zZrX_VGK3#GneHJ?c+daPo#}q3E$?MG?;}+R|4DbGn;+qsB3qf_7+FN>nQoqki!PGb z^PI^{cWOJ{H^n~E%~M7*-7=gfhQfY9mhH&Lx5WN8v6mry9O>r&FN<{ZpY~sdtLA5_5I&A{Pk=PiojI7pd6{~25=96NW29KS6?#Qp=Z zUx~fHp8GEGPxx~2ldY)Xa1`CPn;i9rzI6+|%d>wQj*yH7qmQF25i<_@!mqYO4Gh16 zJ^YZnaCe8FeF;6#@JN(KXt-}bI&H17#KlkQ=XdB#{CyrP@x>`W}n7*2Eq8qQ$zu}v6x06+sj>^@d0 z85vg`e<_Usx)0znL-QGOl%)1}K4gqO0mVZ80uGeS;bohm+MxtuGnRdL+2I&Z+uZ0f zWE^$&`VQHyeTpsrwke{7kHw{RgdgezrQscF!Zb(q;!y$q%t0Jqn&8$x%R?UO2 z62h>I@98)Ke#GW`Uz7nWK$niK&iH}uK;S&7g{(%n0X-EUFtJmV2S`y16W`D)9cQR4 z1Sytq4U$33t(?F)Y5+l7Ez|=sUiLlX{F8DR!m(9DL5$awCx#P`rHA-JF5}0A>s9Y# zA%K+(@p=ey4KYCc33$d&)zG^TUBkTqzJ3<^*6GOj`2{~ZU&uaP25?hDP{M0JXI$V( z%i@YV0cFD`Q-XW|?)Hp}C2L^vB`l+2kd?H{D{_6i^d2sYFd_}IbW1)?EODH1XM_+`7 zG(?nohCCU}C-seXLeld$oMag6C7w*I;JiSk#5a$P1h=_2`odSr$P`)sGO9ZgPck z4>glJH6t~{tc~u(av5$7FEt}ZOI zt(2$gB1tEGo@AND$3m{wd;E8ssc-xRd*rjnsq5B!k2xxF-<6t+=o-wrg(LY3_HZN{ z;z+}YLeP)p!J(z>G)J17=y6EOx>9zOBaI-c2T7_cWluTMNTTkL3~;6F9Y-2PG#-*! zu9TaXBaJ3n4#_%K%GatR%}cZkl8>`XRgbR=olNu<#6P-_uTgYI!4pJ(L*o4+P-t1b z>a@kt>_iffa$|SWmL#eIX?-{C@gU7*h}uBX!k<&_8iIAnQE(KOD)wbG~@HReIvuH2bFR;F2LM7XU;`X&X>6Y!jr`p^HCi zR5KvjJ%nn_=A_6U*hyzO1c-4Dp+b3ps7rrgC>GQrAl5vDlFq*#6@H*mdx1Fm5Q@M3 zky@X=z(iGaeG9~I523y*22=xTj|Db7Zjk>1K7fEjIl(DoBP^{`8&Nu(DMLjWASwq? zaMi-M0ccF8u?Q%GidT2~sZOYJ}vp2Zz5Tvap$fLXyB3cLgj9f>d!N(HWka6>TQ$SMFjQ~u@} z@F9es1Orau*}&8;)Dby}hVLQ#B^b~HTf3=UX-G+}!F$m#a^nbG0*A{Zi*EEEMjFvj z6v8sWfPeo2pgUdItpQCSY!wW67tJcQ2OXQK0Z&6XBpAToRZHzjhmtj5HiYwo0a>MC zWG~u@nV{IP5yE$Z0o!oTIkh)EiSbwf$00lu3}}}NS@fYI*jN?7uMqwj45*kFfWEZS z$s+tKyakIR;0LoMvdE;3YjhT6A*>P%s0ZDt{m91TUb0AouuA}-1{(Az%Yhm|d%Ei> z*(e~!2T*8t`~|Yq!8E>{R=YE7vMC>XD5XFU4Z)6h}37P^z&#^XCe5C zg)-WqQ;ax_a!#O6Izadb1pfwvkupP8A1qIuPESD~-EZvINX~~EFoRJqQ5y$U2Z&}a zstbA&6ox+}kh+jw^5U&L?o#^zF@#Za31rK02|eeaW&^RvMTxHF^i*F=Y+j-C)p$Dz zLjY|7;-HISyPVFd*gj;tir)N9yXYcd*Rn%l-0M(w8`x@o)i1Mvx?R5i&Eubp;`cnTy=`yPlpjB@Q#PSem6^wLin8hHsF9*$rr zmm?egG~NAK2ZCDeHtAZ~Nb2AtK*f&qbwtLq9%F3c3ie zbqrO-3WnyJ4CoKkttdYE#0}ygU?;LeQOkn*nab_bW?lp0mW$Hf6x6Tu1}+P^sB&M% zTQN9-vt@f^DjU!Ybmysw=GRShDNX_Q6+@LrG-_xkpbD9O z7+C{5B`*CXWV>oBq}s6%WMY0Tdj|-^)yW!kmEK^keozZ3r8>0QI%Y)FNgS zW<>(%24PDeM&wF8%mo4@+0;8 z5F85#)pG>(sc|D9%9vR^x4i`E^&E%>l#3@)Wz8#740W?71k0u{9Li}Z=#Mm)b3!=XI$p zQCm#mN10-|r%;RJ79)9JkyUVuQLLx!^C)X%YLvyjWwi&_AjB*B^0led{1zJ{UzM2rfPf_O5adp}M2p5l zGRu{|#?slOQYTwTz7oO>E?@}*^irvamDL;5f6nkjAWpfcPZsu&XE8)&!z{0Oe#>-HKYH z?dk$y?_dCbaVxcsHE9|iGhu7SLpY5ApK~#chVsR&)VfyNR_KZtu*?-2ZTVI9$kfXw zzYLqBqOO@dZmWv=(d0{CRn$+W+6LgHsn<>V4f<}g&Xtm3EfT>m`2VXP@ctqWC5Uut zLc}*s)I>1|E4hH+nz&`w!_~ThHMRtzlZ)EIHK8lvw)rd8ou`mFjR0bjiwdrU`{wnb z8nq0FHy({5s~DQ0y9reu{9>#Y2!$KH@FgV zTTjR13rh@0bcIISe71#3=waSPW-Oe5t0&$b4e z-0AX8P>O8p4l#N6Pj-BopkbyCH7g;x`FNOBi&%eZACs0KW)+TPeq)^X`$W*!q^*d2 zKOl%?O^!6vq?3?bbfwb0yg(}PQzrfFiewbTWrCQt`&VMM{7UI}j>$n}6&@3qY*>i;4@F;vO}4|761Jtz23 z1RIC&u`Xe`uURuc-2nmGD$m0r2J

    @WSRaZlbFsC{(a$p1jWl03z?RcwEWHDOh13h7?p_1&-8P*nds+hCDXqd ze#RR>-!nf@q&$cM10Hvvh4KZJDLm@pJLY*lghvh_jpg=bUf7QhwN-u>4a>ZjivL^N zbNg2Y+y{;QYY{&_JqO!OX?~Hot zw48c0E~BA3ZDNJf5{x@y2}rzq`HWRdbgck`-Ib6Jb|1MeHb2;B~vA8jeAfT zd4I>kTOw-x?vx5In=v+DY`#F^dPtTLvv{nIC`w$2jQlhhiALc_=F;E`!*pskfC5HxL z;yW&|mwH3iKUn@zQ^am&lLVl%!t^*@j^GkC;YhluVtc^Zx*{ zlL5K&Fk7d>P*Q3O)@f2(KLYUQLm;CLK&7XlQ3)tFT2y`<$`eXcaVk(0pmM`;=bg$x zSc3sleX30tr-N7pW|SY?o38)}J3j;a%c4-}h*KsYW3pcu7AK{G1vc}08VWdK$% z$f>b-Tud2NRys{@2V@5Wa>q`7t}>%)2<8rS4#IC45M*a}YBB(TYVnxn(5)OobOp?cgB28qPebr$I2X}}v5@}`*R#`!ZQB_tM{s7Agimr@j63Vb5;1!ZT&tjGMGk{D{sRWtANX~60TDVn@ z6R`4WoTR0jq(xAY7NR_h4x+}buE0EvL)8p(s2Tp^cNX!N$gS~+$;vJdc7GPVfF9La z3&idKin;7QIw%VHljqi_5MByECBsNQH)8p7=UFtE_1!{5uG@}PqVE+nj-E!saE>-& zj|g^DDPR*3Q8Iw#Rz^^>jhkH!L^sYMT1mSf!*CQyRtHE12c*npH~J9TXBNFz5Q?Tk zxGVr=E<2PzE}KQ|^8vaU!rcL=m~O11MhOsQ(V+YYPC@!r0Kptw{<&ya4AZO|h>5x5 z6khCFO^=1a=qUN*%&X!FoG{37MF-BH1R|;gQi_={s}g&u5u(!rBF9T5RzuVS(c=Rm z=7^m=1fO_!KNcIyuP9_um2@PS56F%{0_Jprk{f5Y!ndK2c#u(YBYz$r576Mk$Rhq` zu5}E^%Yk%~QTDcE)dK2wAiQ^-;xm`s*Xv-&8XAI(O184%A+8tzGnXCgNA8P=|7*eO z2w~ta4cNwE_&WuTG-CNHz>6qh5l|C@Q7dTcP%NvuaP;)jZZ@7(bhvax5J89$U0ycl;Xw_=h(Gh5l)EYyiTf&N&HUH@+V?EU2X?bvO z(!p~W5qt8;XU#t_;Z3UaoqK)?=hJVx=a(mJpbRt;>diMG@ORBfU-J!|4_E1L0KW$P zBu!N3t0!)tUy9*;DtFTTf!{z?dg6Tcd6;)W(m%ksO!L`7YyOrA8>zq@Y^!U-+v$*c zUik}u0z`ZjMws{@KV89Xb=367yDOkJC+d-E8IDKYXap=DuGP&$4E4NrpDpFy(jQ_NTZsE* z2l1Rnngz^%BTTX{o+El@R2U%qwv}o`qp$qucybAJDNk1Fz@EUJ5FNq;cg0fnB*T;^AA&iaWQgO*T3SaWddh$&o#!Ot&!TD`E$7SoPgP__rYzWoH*syiut)baBC%yY`>s@fl zt?e~15|bnIPKcPrZY>?hSa$1E;M67mw8jq6p_R5<>|?hc5j@0TjE`GUq?F)c}5^v3rUu%v+`yj8Fvi3sDq9ktiyeQ zWWywx6CX%6PLes%&fs__knCkiHYG=Hs$zH3)9sZNyeVG+Z)Bj>+M453<&C;L0jKHK zs2dz+P&v>JLOW79V>g}BX^&%V+QLn1?4f&FGRBFWC>m{R^)L*K__1Ek{3R2-0LOPw zCcNQ*Cus2cY~XnS?99Ua$JulzGiA4J z?bMmUpdU4Elg8NAao3VIp83iPYxQNyy8<7%+R&2U4U$NK#>2Tg$Z5Spk-aV_Z-M@e zwDReUaJ;6V?#40)Nf#u;o;W6->*y+mSM?AOo+D%deml{sXe+RL=@@P$QSrRs`z07S z-+Kq5;{A}+TM*A`P#XHXebjf@FoR06!q*V{hP>#(ica6-vzl5h7ibUq6_((SFrZU= z7Z`q|gnzOX0<->uS&lhHyDC}BMC6?tUr60cnWbRXD!y-Y4w2f-RcvPEBs^S4(K-on z4%RJdi!dEw8!mDIbmrwWpq&o0kc`q?-5Xi=pNKp_Ej7eZh1(NU0V;av_!By;TL}F% zG`vq+T&L`3r)-C00~Klnn?K;4m7j6`22I!Ll#}-9Gsgib$l;WZ>)Bm7AgM5ntd@s2 zcrGK0Lg4fU&v~^Wvt^>*;E{84eqFu4qfgWH_Rg1VL>832E!#2wIt9SGmd^LXV|r>U z=3^kX%2rG;;*lF0Z69X~)iz9?ZpzwxI;8Xa11gUJr?z2oq8_Q1l3lfqy8HpPF?i8I zS=s_Pr8Xz(k!l(4%qL1{bwi}^Pv>^Vj%mQC`GkWgqmh_TOp}~>KEW_GpLhu7%qJM) z%qJ>n9b1rFV4AiM05zW&`Ghl{@aihR!N5CdViwOQ_5q>h6ZgQW`9xlgEucdyEmZJ4 zpXgA8@jRax4^Gb~+Gt=`Cqecl#A+b7QBIIvLS#V84l1itx>Jd_Cqkg6Xf<^q%V8UY z&L6~wCDhFKJoGA;I*1h4rC*52>{5m)mp%k@T*?r~r46)>A;>M@(xOEjmwp0HP0`Le zzGvW_^e*G~&cIcE}MNcf{{1jE>`3{!r6 z2f)8@l+sjBT2kgtId{pHx<;; zJhKbMFo3binckq+=fTdLpN1gkylw|M-4sukbSgH|u^`(VVjZ=>C^SU7K3`99rZE79 z(a(6?Z#`{6m7f8pN1>ZM3fb1>9n#|=R&F-@!LjaGq)(l(=uaMtEelIy{%9WMsJsE38Z>gE9;ue$e4X)a!joFv zIY%wgV$sVt3;F3>b)DsenYK^u%rnI4Egc<^*!`qGe#Ub+>Z+aqjJm2F#FsiZT-6~0 zqtXxf!^|40Mu2zysUFoFY3XGaA%8wcTP)w+*^JJgu1E= zmUFJ^*Ln!l*r-D*ZI0mis-6Ipx~kWL(^s`$H>Er}%&~{{5s=#`Cn(zhbU(ENOB=)gS&kCM< z%D=&BpWf3z3iwowKnb||)FwfFaM&8mfm1!@bCBV;gI?6)9FA32XP6ewLjmaK0x1CB zw0i}q)l4xM@yN@Fp-$gw(f6>RI(!ql!qucx*}E4ze(yF zT5q=0yJ?%QFYY{BA_;ecZm)&2Hs&bqJk!llJrLyVLwC~=t$_Q`!4E0Gg3$58OsvS} z1pqg6zX(7D$1(u6J`C7FEi_=KTGO?0?fU?Rv1^=i=jgFJqQ_3sO`x$3qbs4h@EL03 zLpuGAX^@wARk9qhhbcv4r~>3%c3v$RACZ%mF2DjTnubDen#PXOVPs|KUFPbI6unCj zdzc10dS_?X>!hVWmEKvo9i}=)LOdjTgPoAod737%30zZ7cR-Ir}OUt)q3I z^R${hI(&oGmBJ&FJLnx9#fw``Y+K(1t-!IghoT*#Xb;0!_16od-rh%B0W%NuI-r(5A58*AN)^J)zD6h+x(WDaKb1D8gY#n5TF@Kth6(jZ0 zQlii3Yj{5C4E>A%pX8x?9DYV2UTk=LPEiOZd`^i7CZ3^E2pCfnVaR9HlutjSE*zYt z{s_*}vqGnWenxXaC!M7g6186Fb`cx^Mb0M>m}luriTeQ*s&A>l@WH6FlpDcWiW6Ey zXa%8lgf;{HoZ5j-JWKr$oS_k*2A!oT2tT8jKw-dg1ZQcT&}~BZ3;jgs7ecQJ{axsN zp+2l1&Qi3{M4=^xRu$SnXe*(eg+3*8xX_70=LlUabgj_0h3*l0MCcizmxNvydRM50 zncZ265L!TJQK1!urU-2=l)o8qmiQBgXKAp|u|j7E7gyzD;;4D2R^l_nOh1L}Mq|nwvy9*s4^jV=(h0YbaT)F1p>GS_BlL*SGeR#3y)N{w zP%Dgcj}TfwXi=dRg{BB?F0{SS-a-cp9V>K((1k)*3Ee34JdqhI9wK;ZlzIo}dE569(=x5sq)vovcFmtuv`w?V(aU&i45 zE^G^aLD7-8dvb{5ep-TkF4XuJbO+pqmzXQL67Q7XXKp08!QV2spW~iq?pttqzGUuq zaO;ON*RLf$1zVFfU+jj>yeN*VIv9VYwwk$?)9?!XVdlOAS7H@&OW#6Ac96Ma;I96_ zoOd(c2VKuxG`Mc{n7fdQCkU!BXCsd_$C)b&t_(W$3bZd1pC9r6hpUEorV+{CC&p7* z|DD5atOi@#>L=iNvs`_mwG#0cCEJxhiFCZ?qC6O4MHEC{h9jXwkmaVoqmjIi{V?c< z{xHD17-J=8P3a8ceirG6qceWe_v=rF>TY=wBK9fyd7`0f@n!4_NJTseQvVTh0WT+g zhNtPEfoK&+Gr^F{Z})yl66B&(6D@Rk`#XLEF>>z6JKirpN6X( zKfncTMJPU_75GTSUuldA%%k|d&A~?rADa0O_>K)t6m_C^9o!R92nDu|iPYwKQSO$K zCtUIVfB5W3rbzrXuo4cBRi;H8E{N9=%PHk{E%22Ue`Xu_DvIx)f&^6+zX$anUQO|x ze*<4#@fo`82Zcbx{AMG z15;1&(=p);udn#ysQ2&&if_ucHB|i5c@W=7@uP8{C%m!ZC*TSXe^T*3qOpcIQG7+* z;|_1C_{Zu1(@gPAaFK*JSA6W7;9Dqu7p{u%RK-8D0(?uw4_XPnmEt>;ht4#`cf5>v z-JHth0-vGci=tNzZ>{)7Y+D<}SLC#975{Z##J5xYSNXuVS9}5V&EXvsU!O5u74NwV zzMJAlp|ZofD}F|C=L7lG;{DvNW-5N#Vqj(|J`NXS_-w`3Z2^9c;>Yr}@Pgtkbb;aX6u+C> z;e5pxtPXyG;8yC#Xq+O{9B5zkL6(aX2pNYb@8_1r*r^j zo8oh!rw`w*`OV;WD1Q1l@b4=AR4n-S6hDpYWvAlLVSEVRrTF`7&-;r15_6{r)h01$ zdMctgmfv$J4gr~|WiVLGKrb5k4oFfSj1gGSM4sRv5*?Zm8FdYGLKG^m%+7{%snR;QL5seGSi0;6o4@l$?kV(}2vG6Mob)`YR?sGWnB-M3MT8B zY-e(S$#Ev)tEG7!q5Ii^A|Ov`!N~8WD=7Xm@HxP z8j~$d_A)ujF$@5CHIIeQ5NHdNxWr}I?G}0>C z1u-5qOEqIKLR!TKF-FZl%>%5b{3MQ1lUB1B>#4ASW7PcBGr%_Htj+&g0FXL~*?Ej@$(fm58QY3; zF)uPUozTU5Hh^HvOsO@{k@D%4rylriG z2|Y?(PpPw7P-coF_!MOg^OWbF!Z*tBR9xZ+dSC$&>#4~d2McPicLct9XaSzONm@{U zzayB4r$LfDjrflme9s!5CwD4=Z*+k7`^E(LNZ)e-KGyKBMjz+#WX(cidoFi+_WJ|y zaEaZcJu1&0iV3jCJ`eh%&j?-BgR$L+A1JZMwPWymBgy#Aupc}_#`j1%l#Cw?`<3U& zxMtWzha;I`PXpv9!%i4P#?OYm2|BJD_5#R$G3;-r;v+$15AH(7F|uRY5H<$wZaoRR zhxX@yY%=Y}ID5;q?apLuHtqjl*4w7-d76wZrX4p8d)}tqtScGsnD#z&-198^FW5id zvPU4@0?SV8O~yjY?u(4FEIS`^f7!CH_rmL5mK`>ZjKzSAAY++jzt^3N<(9qRSu*~# z>|5ydZ(H`#{$$*-?4c;wUCUkxE%z+DBvk)p*}hCN{=MXmmdAb%SNd#^T?z)y@z@2C-+7OH4EbH~*lBRqmmZtokc%FB7z({N#C{BZc|XK1 z)QOCJA$DB^`$Oz9P<&C^BC4+KbZ3SmU+xA&0eIyE{Din%Ay`df4u@ z+rq7%dF=^Mea36Q4xOKS?E^6Wtk*VBqH{pPJ=1*l40!iPpS>H(j{EJdXc8y<_D`^L zi)}YXF}K?G7ieJb*!DFPGb_}dGZ7UKYX1jii$d*DD8u4V+lTVq3$;H$y1zp0G01&N zF8dZ5Lc}1@E;x zq6&O=aU@Q%tAiG@n}Qa$JAyuLKMk5}+Y?xN1uiLMUqQa6y@^f2wV#D<&-3C^^b(;1 z;XjXOgZVw@|1yeW*iBFjvJap_O#3)|U>Tv`qeJ(2?wNftKG>&mV%Sf^EuppzR4#iN z8cUe{De}v0uS0!?+wIX(BJ3gXXQcfY%9F=lh1!did z5_2ezy=*V~J|omX79LM=>j=myXmRKy8-gQ930=nXDU=H9>v{gV@Ws#wpX zTeUyLGQ+U9#c&RN>*8LpVTWPnhExT28=UGC*5T+ws%^k$sqnu`=oHb1WQIu}^4L50 zTn)Tf3Y&A-%3E$2zZ!NIsQnGQ09fz*j=x60^6!RWcgSlPHw`-!*8gGHPnN;o1R3@> zsE9ue8zSR2ti)>k4mu=k+ zVkei9KI?j-^jU9XBtoAxc_!Zyv2X0cCLq~7A^DW-DvdEllfCgEzp`b2+Elu=@2cR& zuxYO>gQtK@`>m_Ev1{7LzQRpq(_U3sx;6e3C;GE;$Q}LJwM2aT$+Ab@!i!#(-2_u& z^k=^ng?oJViJr*MZ@*jw`QiG5mXm(_30QW@Z;!{FnbUqda}hTC{q`%ZpLp9!Xo2>-~JkoJQZPtK833Fc;;HRje47i z-o~)+;Q~j!l|=hSy_H3CK)r>a(ot^*21?)m31q0ZV~9lGKMlMf=talIW!fO_kS0QFWJJpziIYg#T`Ho5SxjG)g{K-0-}3G)rgH41Ho zaxG8e_?oSlhUaIxpeo|S^gh%^RJZ@-!6-#Y{uNw^PT&nY1Dy`)1{WNP@)xc+6lFLr zViaW*IusOTlq$*}umwfwjY|+kIgS4BIu!24smB{p2`g*6DdG%!`8ZM41Q#q+CE;p> zssqRis&1knXwBo$VL;VL^hHor89gJsQWTN!%3X92@Jj3$@ydE+3a>Q76%VgG4!6TA zBX9<!zu7I#?Ex~1fTFCY)iIUWVQX!}KdC+BVZ(it=tZZU0mrv<;ItDgEu! zQAxSgCgqtwP3PcL06W6wf<=zUqqS9Y9|V#q$oJ zucqR82hdkb@w@}*tF3t60rb^TJnsPdQWVcSfWEql=N&*_J;n15ps&8-kE8wg8YrH3 z0DTP=&pUv=MvCVhKwo3U^A4czNyYOHps$JIc?ZzfRPnq6=xe5UUa0w+E1q`%eJvEv zJAl4a#q$oJuchL72hi6_@w@}*OH+Ku%ZN``JnsPdG8E4{fWFp>=N&*_8^!Yups%gs zc?ZzfPVu}0=xeWd-U0M=P(1Gd`noEfcL06e6wf<=zV3?W9Y9|X#q$oJub1L^2hi7B z@w@}*>!Wzy0rd4%JnsPdRBMXn9YEgz70)|>zJWUJ5b)0^o_7F!gA~s@fWE6wf<=zSWB79YEi!isv0b-x|g9 z4xn$X;&}(qw@&fA1L#|?c-{f@y{UNK0rYK9JnsPdHY%QX0DYSj&pUv=w-nDifWFO& z=N&-b+luEMK;JgS^A4bIyXH58-=TQk0rb7Ac-{f@y{CBI0rc%uJnsPdb}62B0DbQ( zo^QAK!xhiBTl^7<=i4p*NX7H*7JnYa^X(RYl<*OJyT#wJ1$r2o7{$X_G~aIV9}}sO zZ!82OaKtb%g<8COA-C<+W}{$ufv%()BeA?XS1FBryzb^hpX)73ft_@sF$eeSO-p@? zFJ$QvxH5g0%W2h|{MA|5r@xCwQ97utrn{ek#|yh!CF>Q1L1_{tR?N68#vZ~7I2zg%G= zrz|9Y_7XP47>_?&WCNm*q#zDmTv4w-82LPb0n1jo>F0M;-_`Q>pMinblLumDrDQmOv*% zWY+uvC$%`wLX?~NI(sW)ErK+Z2yhV`@nsom6zSe(h!|J2d-qYoV5j+8Rz78fC|~@4 zD({|%HD#U23-H7|a5N5NDvtQd|3f)XmLM-y3LPL7XixJiPnk0p5dM+p`gSVtvCEDo1oNfil}c9me+ zBng(kCBcf1C0O~b1gk@^hD?rl^>GQ-)Ro}1eiE#kEy0GZ5^Opn!R8whY{?DZCr4~8 zE5SR>CD`_q1ly-duw#`3@9vS{y@h)@!Oo2m>^dRA?%yQX6Y)OF_STZ%{SFfBA1lGZ zB@!IkEx`w0N$}yn5*$w4$LT(*D#4MC5*&R_f@8}i_;{}bpPZH8_-_)N2*<23IpWi@ z5}a%$!Kon#N<{c+k%TsFlQ5LdN*GIQPl<>E#Lg)ZQIOazB_awDJETO!6FOZHovx^) z^X?gqN{{?$L@XNgk9~0K;`(`R+Yy+QMgGzSt-T~ILc56kBL>4DokVw%a2NR{`~zY{ zy@K;n)OV;6dFNDhtWA-W_!W5(D@-XGIKqhh+XE#cj(RMcxHNrN4C?>=e7=4Hq$f$Z)z+U84>^5+xpqqS=^Li>~Vdl;p@>fnDFTJ7efc%*Qx}d~8hw zax|jWRlPCd+#cfTU#7aY1>N_~oh)kw83*vbsP7EO0 zYGg6m8=_+r(lAfY$4=Ascad*$o^qun;H`65;R;YL8FZlJXud5O}{wG1JP?4p-BtZr*e$6*AN6o!s5agy^4c%xX?!5B9_&8R(QC%+O z$0x%=Rzij^`kPBI)sE`Ubz*KP1h#jH17Kfcwof^*Nwl>)_@T5K$=2bBZ-Q7J93_4@ z?L^#%f%t@$km3ofz9@dw7&;vg=)uQ`>WHZ1=*n$?OOCFx^&kgTPjHZTRNg}zJljNq zvD+k=@RT^!`=-WtP8a=sp8KH{L)GzogIl%UTJ3HqLpAoF_(o_Zibzr05{!P8YG z=-)wtK_ev?yh4JZ`y?24S%TqyG{WS3BaX1I`h|vtcSBDm(hap z?~F$E+^N`dj#+N4L9bJOhDt$COzny9^i)vBKe1>7PO82D2M|3mw-F}E^`B#(P)%x- z31vH)|ASWsIHnNYe-aV<%UF77D3X9LW8jE?p2e6ZUBZ|X^Fb%{1=0sLhAh>U7p5jx zAV0D(9G8AC#6QilW|ForEkb3+d{XRfXqtfd=YwT+v0RQh`PXU4mLdL)fGmN_jf~$% zlaBeO?qxhe&IQ>Iz()ZPy)P2PeEllo&d zAT|#N;<*6Is6(L_V98)}_?Oz~c>$p^Sc-0>(6NP3luUQAv}8pVy$|4r46Y-t)rewr zE6G7zg7i8g8Zts!KNMXW0Y#-~4EA`r=vX5qV#16gpy)BKhYB>~vSD9TbQII5OEdGLQk&AvQEbUOz#PqiV+{!cPNA*$pg5h5#$zoaimw9v=OYrph`+Z2 z+mYVAuG%sFay|(!{^HO^h{}5O@fg5*(RP?&Q5}d?H^NfYF6&V;cM1b2z92(-J`%E! zAtPutTChda0uZsCr*=j?de)DE&Y-U_-dnUT0AU9wFmWJrs30bF7JVFmWHN+_1DQ*; zu+p>W*8oJiJ|+%iAz3CvA`4|JkrcW3}v+uUV=GvZykJ0vWS|Xbo_0 zy4Z$FaDa&RBKBxNqAp0C?g-JBko@3E+o7QwTKXx`JxIa}2h3$@P}wx@3nKo6L(Tt% z%a-L;qErBTyWl|k$cFowXe2PxbKs=E(fQsaS_1KA7ZPYB*;L&pIsnXZ7uO}Il%Xbl z1Ih2Ml;6m56xi(EIFsmcI0A>NH$4Q_mQ8_}!lo~sj9$=5#Q>=kfF+1GHL8SpYn!1^ zErICdqNF8hRAsXzhA7cB0*Fa2O4`0gH8lUjl_02PK)m6iq+}YEW|khPQ3rrH?xMJa zMs4|Tu$Zpqc1)l6vY{V<_%(oX0R7CHd+A_^IS8u;1BS7Yhs?rIB!F}XI|Kvx?>1vTF(=nj9X$<$ za7-{@a4%$W+8p|W1}ubdSukLFPXNxD7p7{!b_n;lfLij8nlay*J1b(8J`KUQEL0<2 z;KITG5=9(_o||SeZgCKQjl)wU8w`j)n!?t*=351Th=a6H0D(6149~y(*05Y^V4<22 z)@OhkeQVLb9sm-o9wkwk9U$lvNUb_SOcr(l@woLV`geK`(#Zh?^z+}2#+0n3^hIQ-#S{gT)y$~J^08}0t)!cf)GK@xy`WA@a809(y{{`1`gb~xj z>OM!S@)gC7Ee@5JQl&t{tqbTtL{ljMsxc@?Q*HV+pJ~KQwwAu2Q5isV44_ah0nD=2 zp!&q@;SfH@0H<8_-tzid*dxJGBJ_`-6Ssyw5&^ZXd z4QOzBD?zF`1O7~WR`oL=Qf!5Uoh&C=t z_e1>urZFe19T9bRYD{v>0%AjURM6N|TmCgQ<_BwJac$v;z@ByS zfnf)}7uCO6wNW{u`gg$YXNNkdf2^)q8kMg&c0F+fRdj+bw_PWRBzx`4HCp;GQz zw3TZ#-m?#r6zT=(AQz$a@J3BcNzcoemx*CBfyi=E+B1Tx>PhzLl5PfKw~Nwaf}mP> zUahZDp9Ar;i^?&!*OqOwm@b~LQ2mm(rv(0Z0Y^|fa4sfM-OsabrG}OTtY&s7{3oc< zo>r)BQP>uUOc&+$K^i*OQw>+9K>5Yk7hI_JU*2Kx&a0k5>u~+9fpn*fkh!3%5q%0{ z-}k(Ui5-0k+@%~?-4q3O+H(w@jAZ;5V4>)#g6mj&U7*)Ix%O!rlL1S41T-A-iz{9-)EgCZYQw`k?*vC1bu17S!ddNCJWbFP9 z%xxDh9@Ncn!sl>aM#y#aP2!b^Qij1_feH2stA-T^pOlz$HSYsE;S{>A=kd8lT zR1YAAW=E-+d@b5p7I{w$$$B3ZHv^ED0x;;=i53_0a!7-BwPEWa+!p}2o_G2-!EX%d zGg{-%1AFg(;oam;P9KJ}Z=q90mBv~hM@|>W`pUU3B)jt=Q?aHMzdeZrUH?}iCzBf? zH?bis_-BD#@F;w6JxV5~cL;V7B+(`$IOHahdK9ADt>E){*W#)X{8zxp9ZI4S z-u>U}M0v{Ke>ZXH;=7sX;X&{z-n{cPz8EWnH01mZ83$OW20S1}C7yyKmKIU?s` z(N?55{-{)LrPimIvB>LV?+6S6YNzBDQm9tXdes`JKKWh%?5elV2nQBd?qOJM`TN0` zKfMESg|K~838-c`^khluEMPchk#T=uM)a?DQ(=sLJ%Ag?ST$$jGQir9%lEx{!fE6vhd(k#7rTHKMv9U~OHfTM-)C&Ubl< zh7Ja7k_(l}U>(qUoel2oD?La99zzyPOgf}iaB4$VOf zz74FmLZEB`yko@z-)7ug5oi)%q@kk# zd%=YU3~&q<{61fvjT-+3ud@MYiK%^Lauu-sUE zKB9^RdegTI?N7>96tLPZ^dW-<|F5r84XwI8u>Br^hrt5P<6n&Vhp3(c*g_W?Z1DTl z&?FN5?KWxXTY&9zp}`&&XgUAyHMGI!0ppJf>9Rd!u;AIiB z|9@CEh`|*BYv@9Q4bGbj9`5F^i035)+6}P5E;QI+fe!W;#XgikX92d#g+64k;K%#l zh|{Wf0sHYI@Gw}QFZmNMYSrHXcH4yp8~ptt7`)Q&eFxu!Du8YzqB7<`IJ6tsGN(=Q z-Qbw5{?5Ji?cf@KHFlv~Hsmd+)BZv5Ko>+%4YSUB9q8DT&;A_y7lOJ0gtyAW1ysAo+WvBO9C~KKCjndYf8muW zQGBna@!5R%5@sGS@t6V6j{)=2IV^wTQjjwu7LsuQW(sM#t}b=H9)=wV|8rv*Jt7( zdX|@htfDJ#BAaBft;*Hc@)nS_cI8F7HxiE+Q9J{P;%_LKkzpu(9rl6$3YNQ`xQ??C zZ7=EsJMFfOI9qQoOo)@>I;U2{&{h-DxE@0}>Eni3^Fy3O+{R(;uW3fOK$SlNq6f$LVPZM!LcoLBcO-Is_|R;hQayft!n}i1?rW!ZWuoA|34j z^q>ouj5O%pAY4QO`VxR2T##g__Rr&U)1>H7ohgf<7?5(p?IT-HGBf$XTbp89*=KCr{-wDFA&}e z2JrTHd@IU=%Os23weWRe9D!o;_IP{;s)+7d0A(Po91P&?@%Wy!GY#*dunnysY!?jR z?eX~jR0Q`v1TX}`XM+K}>l;6WyrzDfXg-8Xf&tt~$B(2J|HPea&f*;icLf7@dp!O* zn)QtaoPqF57ogT7@v~^=4y3*T!2=db8&BYtg6iZQmiXiJAPFx>p#@M3ruKz#Xw*_h zMXg2d8hVxr4$#ngfTg<7RY3}GQs?g4vrhpr+C_Z{RSBY1E4)J|G077jF92+94yb5V zTV3&a%+t8+X%`@eU6^jTyh#&Z#Jq{QiYU7T#B~?N`JxPh!lz*xYLA7W%gMvtj&jQD zQrsm{T!D5pkDbv9%K=u;g-St0tJ>U;A7TEt4c4^>q+0-nEO&ef^;66-(OMBFp@q5;?zUBR^Eg5H_hl+t?OqX?mVPR zP;Z$PMr&P>=se^3$Y$48TmbRA%%s&?R}~=YGb+eowMkI#n|{-dDQ1F=1auEtR)4i5*7j~>Qi6|F+%T-^T~`4=Q% z^&Qn^NnNbp*1e7nKgVNd+lHb^_vBT%j4M%nSyAAzv&WFEAddJ87@5e4A5LWvS2GZw za0yZf^RYMap1YtSs^4=En5XdsLDbW1VB-_;5@%_oemzS7TKEcZA{>qK zz(fY;Ka05s3S%OwJb%oH3lp&Q1ElyEM|?iC+aOynBJNrsKA`}&>cAs%e+C53Q%~M~ zc<7N5hKV0jkgIsMk;BY6s%}de-oaHFcWpQu!xphIg=pL-xTJq>R#4x(>HxvhIO4x& z2g+<;P5I>!YAJXW=j5IF4<2xioBBHV@;q%~Z8cH{V#YO{QRd@Gjn`nPRw>vgQS70X zN4jA45SL10(S#~KgSmIPxcA89;k-P{SxcqytDt2UaW*)wG#A5X+-_2t_$#HKhjb5d z67%t5mFc6YrV;l(9`Zs&ejM?I#GP7jh^QnYYXt;qd@jvS)sUk^Eg|ln15%M8b*VdS zj5|eh;^p}VV8#b3`H3VAD2sM?@M;LGi3=Ee_%2 z0_|00Gt*>h+?r%gnI==-HpFvYGmIxtaqWp67{*V!$8``s>U-!6ox$ zTtEtaQUHLVwDd2O7V##14tkLhDv!F<26KqGk#w~KOaFl6-+(lMlc0L;&Vl;16#67y z%A|Z47z*J~3KS%TDqR6&BOUtM$)^?|O$<+n0I%Q<~2XN>SP?*7((_1gzd0G zii0CYdunajbnRNGR4On=$E*wftt5lc%gtiCx=@A+bC>M@0KkGN$`q?A7ocKBm-Q7 z6Ff49$}|FN|G1eZwE(7dKrx0z5zIEJFCs?;1Zw2$D$R;}bd7t-q!)o%>f(AcL`(Nu zv=Nf`TlBhGB|9 z$D4pdcZBMJvbYUq^MkHPXa%8dJy6hE`(dG13Bl-f1j_A?;yUN9g-k8wGxa=wm!goQ)(pwB`<(O zXBdnsW96@+QI&zH=b|{JURB0j^%gmyOV$~Pr(BfYAm;^TTqEn&a;=-3gRQBgTl-8PvRqvn#Vg9V;nthjJ(23!48-n-bP4KNYt3}6>vJG3KctIS zlyPr+#^c$$C77Dh-#~c5XuEV71@)` zuxlEivnovyu&m%)H!R#Xgc^zlG$H;ov@ElKC!k)JH=-5$_<=wyx4p*aP236NMwn5h z4U&d03K@yiVQfkG;*fVCXj}+-nQ8S}Bek+IT9wC>;HUE-&S=>W%N+_|AF?Bm?5&XI z;2Y=0YH85_KYfu+ob8t(zXZ}>37G<3JizH&^}M00sMXA(ii5R%-{53_heV{o+6HXx z{g6Y!$qaAE-+&~xot1$S^QtMa(|xRenr(#-6Z_l%Yl%M-2NZ#hW+(3=dTK$au*}oU zzfhZ_7nKCN^m{?`axQUA8$`Dz4{z4?`4H>T!f-U+07q;a#IL*#%rh$s8%A+fMay-3 znem7pJv$e+rzL)yj{hCow24#4jz%>}{3klT+a%y$s&*3(J)=r3x~k&`7eoBg7FYxP zCHVU~e)Va@zcv-|Twcro)0I76)I$80`F))Dk~)584aDzlSPY*}6MO@SFGE+85#Np0 zzlsYHs;Lj+6N;gT2|aL%_bLVO4BfzELjstc4Uo{3QEh1my2!-Qbo@M2YziPafun~9 zk;GNh6`Q84nT|3_He*pBmC#xgyRr!_j#AwQqz^J(FEk+e0 zYhnOZQllDoXpYVZ`3G%WnWvWFCGjTwQhEMQqj7m8mO8-ZjD%AYt1In+ZLWY_hPVGx z&Zgndz)Dw;*tjngKMGk29basrCcj`F;Vq2)`Pf3O4xy7N&)$;Vmk3M{3uSN|PHPOq zlDJT7b>^?p1XW+CjXJ|yu$;b7J8BGUDvtOXpTP=4$9JM`i0dDSPpAv2BkWFNA(-I` z8?&%56&QvL`ewk*v;xBQE}#Vis!$fD9YBXGi!7F=9yo(;x z7Z!;Z_PpKLTrc%b$3A_9sdE!mSPH-I-nK}&Wz;(6y%d7y9G z3{?(Zx`d(O1aMZ(% z(sEEXJ2a6I`Mt+k0sL_a_&blt_~RnPAD5JUiP)Ed=H`ney7p?m432-(3RPcRHF&@* zntJaA;dtck())|3>C3%1{Ph#mEb&^W_tGprWM7!~w_d1U;t`|w_x^my-Y@SJmMUKB z^!{;x54rXCUS*wS?YqvkFP6HLM({s0sxkaO*kXF11W0>JhHHe6E+BM;jd=QU3AsBV zKyk8y^DRzKIGmO^l*A+{Cz|LA!X9U!41z2rFanSwCllqs;3F?Ksf}j@r>W3tLT^UbUECLSq3E?ofQy3LZN$Y-G5E#$)BL9oJ_;6Xh$Ww0d@4aE53pB=GOasjlL7b zK{LRZXR|Pp7lb%{H^zV!nD7UOY z12mf2666h}_f7q+Q5d9f5*~p0nIP+>B2?3hPQbvQ32y?d5-fplAiZ_K6(M*t5R3LsP>usYq$7ooXIUnHCU;;mr^>)z*ZdZhF0Dc!t;AgVl zK6>_?Dv93!UJoYlGgow3 zmzo3GN>Db~G*k(GBguPG=Ru^<^Dw{@Ot3POA1-?@=ocQTLGUer_Z>n$@yb%ZN~f^6 z6=lZ#(JR=3lt2R(8Y0wemW%8iUcASwazMatdY34sBjF zT)0uysXyRR87Sh7BX412;7LSfIdec*&ZMBMlce&-n!+lvZ$UVcL6Usy$Xm@=jk+vE zT?6BeEee+LYf0WZ#(7EXf4xY7m50Mjy2J!s?m; z8w5+>S-jqE#^cfQHi^0d>>VsY5c(RQ;UU>|4n<`B7G7%+DbF8A|eSY&AvO+c2ys#sFlr#D@>C zDVw=VP+k>pyRb1?kZbWki`Wdfmr{JF$=k!Ka)(cTAPsF)RCbwXDb%_uc>BVZeZ{=a z;JhEo!%|`2-Ga_%eY2RspW&I~FnG9NNy>sO&G#iuL;t4JCUCxYc%qb?%u1n-13=EH zuN}lfFM)W=A&cgxBHc#2lCP?s2iG; zI2W~?HJL)cpwIDE4X?AEc@4m6WlQp8=NwO={!bvTe)uon^H{Dg;L#36i~(v#JG_?R zV}~$r4mfKv@c5SVMWedNp;*F@BKxdGk-G0rA4h>|T zI;to9Kf)mKgrAc`vV0yfFAkJE-R2>#^5ifo2Csq^p6<3r&>c<0?|J z93ROXEFB+L1zS2kY9ZKid^|*Va|)>%Gzg)Ncj&gjoLlei6X*aV(6|@~6)ll`hO3`^6gR6rz!XKxLKNhYW9~Dv1;?{`c zXwe<}BWB(rr4ahO%Yi9DRnnD+Dw+4K7F<=>=a;u?TjaVeEQqPUB3urY+dD3YT<|I- zu)rXf1BW>-2YF_>9ORkfa`+Od?!p#x3)vjxayW*t^LDuBZ=kq5g`c7o-2(8h1OCfk z6XkMv3HNjq2@Rw~kM<)#d98VCJzb6qwIHh}y$Xj{*j|NBkO!reSAi|Eyb8Ne-y$G| z+96^WmYjvpEW8h2W2_&I0`?K(ZiP#)!ohu-Rtdqh7`v4YuI}Fl(bovu!{Jh{3Li=* z5%#Mc?#acLxLJ~7jG%`&F)+lIG3D*H0zagj0OCVIDMK;FQ!>!X4nyRl0w+)d0IeJ_ z52voc$39`J1NqcJ#WHpZg;!xQkj)OtaYJ;0SK$EQGY*9XgizpBxB>XFLn(wD zv?!KW;iZmv{D)0unO*m!S0N39zRHkGiD0DIERQh7_9~2WDONKu+B+;^lI>M!=~k>^ zV0`4TSSib0@C#LfE1MPo-QX}pL2xcxv@CjuZcyqwP)<5DAxJq5a_bc^= z;wZ1eH4Lms?+hm}HdUauSK-TbN{u*xg_$6$gq#Ebufm$r%B%1ez#0z0@+!0{3nc;w z@4{G+nzmQrsTcQ#oE0B}G5N);?8dy_m@LVxm0)aTmQX~RYuAI^1{Jj3CgRG`Vl;cJiNFJ z@CFlP0oq=LV~{|EhtFBDsRB|JM0pj~qU}|!5>Nz7UAmS7r)_Eh~ivp z3Q9YN#vKP3JXZr=g%+#87zlKP&2YR56LB-G(+nWXZB$ftnP;|Fp(maW>a-i2!=XIe zt8n;Vz9xPH`nSUnUIkIiDWtp#9~Wdvk+|*fVhgf9Bw6KEXgi99mI3iChb)>O+pAFS zp==p+Y6VJrn}!*L%BxVJscc+y8V+|{?o?+ zsiz<&;hz;y@P)pGNL+r(w{RL_ZQnv)L>tT+^b@_T3hzY|5H`~e_YC1mWBV3X0N84S zmT%z;l(FMmC=Ois7C1Q!`uRMfP8=wCx;@6R@+~kbhOmMb@!JB+@%C}Glhn8<)AjB)* z!dp1Bd<&B~So#*;5^U*PScYKBw_w7{IS#2B^b0207&6*_9QH9G% z70a_(K7?T^T>2J%e%lJ4F2Zf!LUdlZ%#bjBiEz&+FwwIKr;cx-2zo9-_$7qknZqpG zw~z@P6A_G)A~=F2NBI`M#9cj0CJ(bj6|{W|cj3Y3Dn(^&4BiCR2!EU|{#dy3EzH89 zxRf}K7X5G>V&*L}5uwlf7MK!LB`;NE?pt57FzH*^1%fRsh&i&L@GZ>g>-ZLWW5kfa z0{N=+$>|InhEp}2L7rK@1$pN97G4H7hPMSjLJM4h!hO(;iXyD69qw5Q)B;=4I{+Fx z;A#df-@;_InT7X>K8?p_9P%r$tBmhcxb!V-d=u}~AQ+2L;$3WP3RgGkgD4tdu^cYts_>zd zfUpX7xaSb0;*}goQj8JQ0B9?R!TpT|en>q43=ajR3>AGmO$Iv0VTgQG-~?I&V4DLT z=hPKAnGOLs9|~Hsm2cq|(En_PeSar?3vXb>Sgr|_6ICe|n>0Ptx3D%V2uT2|1`!Y` z)VFZv18!+jLFpJoSljLi}+_*>&5l?V6jfgXr;Srr}%YJq)#5 zTo{gTf!lHATM(65`W8l@W+~so$9yP#3++(9ly9LkA4=Z>OI5yw0etwJZ-Hx{?OP~~ zA=8`KVtx{}D#*7`51}n=#B)K^kJk_ocP@hwb8*y;?F%aEl6Zbjxf zzJQjySK!7bE%9*N5MAI~$PYNlp|F4u3VaLI05@?c zqmY9Z#quq@2l#!PV%I(CTiA;?8y-L|eFDa8nB-^)e z7G49v`WcL?4vUqtoCd#8?L|oKDbQ^FZR15ja4uW4Ec&`Fpv8ld;LwC1+qY2eq^4a) zaZn8~>f0>Gw{WO1@}CJ^0QO?SW46@sEv$n#TS)jA;1oxK?OVtN&4q;305>@jY~RAN z!x+(_i0KHxQ;r1Nw~%W;9KWo?9e@vmB`Dv*)JaN0_5rxau&J6|LClHwHr4l6$9HI1 zLP>ySnINsOXDpPOuas;6uvsuc`4+xtsR+FR4h$x!84EeLDJ7=@oE=P1zJ;$#D;+ii z{5qJRd<*;)5H3VI4e&xRLHQQ8?^1++06udFwr?Q@P7!(;&#S!H)HT5pQ6rRZ;lLa) zN&~GP%J8U)qkIc3SWrt)+SxQz2{mJ3KbCY8dJYBnArq|3R5KP@+)%!Sc>tF<1k1Nj z1Ve7xj_?DFiAKmH)Uvz!im|C86cSb2seB79dA^Jfl)4#cTm@z7mT#dG{DmU%PN4P)rNbEMTc{VWNE1Mq z8%h!u;p$Vqg`p*(;U-XaJ2Y;lnWX2b(JKZ&8OF z-@@E!JeDg6xU54FV}MZKLY-3lJgF`?X&HEqZ-Iwt&ZsVO#cdQ-RsTa=5cGbbix2 zzD*PK$NIF&IBZ*!4|!@se7o{vamcIY#J6vSxZ;i?zC$&HM)CqWB*upEpC*0;jGsHj zPf6iJ9tFlvojV?f{EBz{w3-~sBgXjYO>kI)x~BEe;^$HI;dt2sTTHXNkcPE$MEEkI zGz9jv0Z$gdo&a{5`!@7e@i)>KP^LJv_RLV=PFf6Lodb3W0)L=y0Q}^D&1WD1Clxs= zig(c;?V$%E(mimWI((6mV&Qr1ZpF$4S4Dno(jJdUQn89qcjTau^(GkaI4n*ZjVRw? z#V1pG9eh?8Hd0$KIy0*urw;;8<&00E1xG-KCNv7*N46M?@HQ=lphzZs0dSQgK@N=K z>(l4(#|R1g0si1fP=w|*JsAbe60QQg?MRRVqxiOT8$(Jj6HGWlqOhp~RD`aSau9Q$ zm{1sC0uwANc;pn{mn!|OB-8*{KUjhw45dMzDhXWx_6nB3Pi5lA(kBa*k{<({5=`Kc zQ~YEaOe!B%1Kbo$;E_}OEb0WGg;4Scz*E5l9y!G?q8h&|9qs^p7);;+NBk;!I9&}m zvg6h*7dG2W9$Lk(r?y)#J(BaGB*3!4gb&l8!xq|+jKvC>&;VewU;@vfj6XodcWK%X zt^vIP4r7A2Ry-ddOmlyWnj!};@jp{J$Pv`JpsjGI2-%IFai<;$1x>-FpwNt(FBi2E)Rok9RYS{f_3$DMmHUw-#Gmm zhV)Dr3-FU*0>6_PpJ?=lS3=~@a)6te5L9dA`vzU zYn3|>z|coq+E^@pCo{gK;niUtmq!d31(_9+qF{A3K5wQ{tPDo&=Vb9anep!%2b(Kd z9l_}RoGif_ZnVy?WK95L=5w<6oy_z+kc;o&?+9IXAMR?rsyjIK*S~a=>t?G5p z$67Hp+Vzr9@GvV_d|d_wyCSqVwwN8E3XVe9Bs<)*hZVFRdn^F3#s-y=wGNfxbgU_r z$AOE-9;;A@XiT{Xqmzq@5-g3NgbC|2sPYdO&sgfep{hiI9mAUl_h@{n+lwX@vH>fv zBEGHyJv=={<*8T^P9UyMyl9d*a28FC8t0tC7!fHrm5%`V`$Pt&DbIVx`DHU+n43u0iwE#5K%X4T*EzS`DcbnjUL4q_TX>V`Z#{R1wGaYDja3 zVQ|U$IRr!KQP^S%^O;5HNYQWya%R$8fL}17gd*_R600G7gMPRm!f6+F`yGP48dBGp z7|tOa^S`mb#tfN;y&BT!a*S%|R2e^0!ioF`r_!KLhcR*?E z&|+AUy&BSV+}I?;1f9}B;l5m{qZq$Z!v|P34uzo8r$A>iL)vVwhV(CnZBoW2pxc9G zsMU~W_pxN02Fh#T+cMN@NMqk3CF2oLZ9P66Z&=wj9O#%}8G;d}=jL`<$XEz;xg*0~ z4Qby3tll9Q`+<5yhTE$lolQWSg7!nF%R!)6@F+_Ero3eV!CKE@WV^E(689D|;XDj- znK-K<#Z|NPE*BJ2t%h_x#){b_D5hEs>A`kO+de^{S`DdR9ZTEEL7-XpgS_C7I;lFaP8HQ?zFLJy+Ik}(D+8%BjnnvA>~5>Ns;rw zTlZqFS`F!=1k(7n9rGW+yX0^=qeO1Ws~UCJtXT{IaJ9AfFUWU z)sUVd?_>%kL9WgbUYLTj8d5WG(rm%#7OmBgdLi%w8<0I`<-1(1xJ7qXLz)H75{Flv zDb8w0Ujo_dptU7xt%h_O$YmQnLo9S7fINwA${`~p5vlN zrTk#L!7SMjO8*5`Lu&k3W+GJqSd$4>H^vSQtcH{@P-Ysn2iVn-Al(yK4JjM$&bgpz zG{6at1Vz}cXDhBGECsm6ks#d@SPg0M*GQTr@W)Y)IuaCNzs{eYWlt4d2Y5GF0=p-$ z8d7%XDkMZsK@niHtq_DG`ix9ULJ@$am|*1t`wp-g((yZL{8kHK!(amY4zLA9X55TcEI$}^92S?S#riG6 z085zO35-4tOI(gB#VW?_BTCjpFy=WdM>%^nBzIQi#AZ?=HVsOt)sXb;D!HcsGk<31g;GkbhLo$is(bmtD8Vdw#VeLt4XJifW#BttG=7f7 zcgt7}>8~oPqW1t}5VK?%ie}$l4e415iAIJ#17m?BOR>~yNF(|x?YDz*fLS53)M`j? z_f*d_ZK`I*VpaB;Zh#G$I^uwI9^US5PlC^%xrG@ zv}Q7VHBs1f^j_E`;5h;g9?d-U;M!f^#Ep3f2%thBlwi^V5!*{0@dzyU<}C2~f64gU z!0HC$txo{o_SO%0e8n+30qeoIOx;TY|E9xXyvM@v#{!#b;~u#FS&0ZvD_He?tIf@ zis?Za6v7tF6u13ch+4fbU%_2yWX?orANki+?A`oWqFxwJ(5-i_76;582G7o{^*F58 zC4mFDaPk+ZpX(m~HOMOd8V=mTXQ{=+S-W?{U&r?1uhU@sMRb1!abFMYhc3-&$`#y_ zwxz0PJ7M(w9j<(P2WB6%Bvf$CQ?5Ncf3e^Of3&J31vm1SnncwpxT)|iRJx9soX25W zgvg45UnSwLNk-e@MBB;V*^tq8m9V05n3hT%S|W#vvjWrzaYg3v>LDKSp{Ew~3Ci#F zR7wxQ#FAMpDDfX)186d^7unK+j^f$j>r-fVFu_T|wpy&Pq_uqXJKkNXa|C2~%iXhc z;S0;roM1zaBicQY~k?Ye%gNTws7Yg(Hh>R{SwQQvG} z9cSaast0gh;~|8@uhEVeCHfBFQEV|B1Fv;a&D|KdSI&vi@iB-aJxb&FbQimSn3oCx z%u9lTMg80Ga?cUTBf*PCLb2Fv-iLW1ugU@xwUVa`UL|msktYYf#?GL zK-J@1Mmu6zSpNm*N3g}TW{W%>v4>fcjvHE0_w_Tjx+3f74v3E(GA|rWt*3}Cxha-gZDmIM@j{wjm^TRYFOW*u{!lZ zAWu?Ivh&dQIsotMn6j_aWB_w)(8H3n_h=>>{G#~>qr_Axg|U`8ZMT`IH(VfY4o5}e z<6JlY#01%aahp)*v;FhgPE^=zL>t7vPABo7zj%?}x%jUrU+>Xl@jQ)+`&!L~Xnyor zyaJ=5iz!}Fv>vrFx+$Jww+O{6aYG{J*cGqLjYBNeYYavmYB~p6V2epcD7%P7cs)u- z*kC){QywV5x*Vx7O#m><2JL*Eh@j$44?lo39MMMXb}_3mi}sYnA=++1YLWK>8WjZ4 z8SH+?rbrcV2-0u)A*oHN5lYfigl2=WQb|vCoOD7pBX$O#sa;3BQUC6r)o|D7p-0Yv_sm;K`J_vYg7${_J~ z^>gue?MwU>p|+j+YB^8cs*IY4nDh)fcm^PKvD0c_M{D6q*rQimfY;mBqA^I=uZsf5 zU?U56Bne0KA91y0;gLteQT-Yp^IZ9aWBLUgC($_{yaDVu*G=za>TSp0i4o_ zx*)WljdwnA#f#aM2c#a8Dg9>7(k#JWZ3q6QH8AqoENIGu zk%T9DRS<-j@&K#b1WOD*?M%>(N|(_2ayqTS=*BEzkH^PWyJLVA>-L9IY8JVQ&!Y_v2~vKzqInL!{vsmRK`WYoN%WSs%y_vd7}S(e+leptzR21X=` zJXpC3v@cTE5?(PjMv%sZMDbu0v02Wzp=vQWP`SI;YQKecg6q%FMNa(@twd1$$&60d zsz0%Otm@CpICkpKWF$0$6MKg1J*57uMCeu<@q}|u+V!VcD>UQ)={R<0m=(#YgTMn- z)Sm{0@$iKSe_{7;FhSLyA131}<~TVQVkCi0X<*l%Vj%GKK}i5B*#xWLMfG@~H$A1q zGzX)#&2s8b4iJQxK>)|t1WSynKlzX;!kz_StY((5$MY&%?M{UncKs@z;j2g@eQqHbFZS!Cl z!x`ERj4n1y)*r4MPW_3f-4VPJZNCF6ep_=ifE|Kc!}nBc_zYA3N_1Apify2E32GV# za!VWGDS$q#MB5yT|34&c6_O_XBy?)=|09X}UM-@++bpRxe}_di{Npi>vKxMN^1mB? z9#d)&6JlXqaUU&tQ4h^SVqNyoZ}K6x)x|6EP+axUyl|)8L;nYD^e<3$`;S5wE4&`% zKv-To+;bQxK-EK+08qgOGxX3^24iXhq*7xrS~KfM7VSBKFuRAo5r_54m^2WC(GKYs zNs>MEKNFOsc_6G~l2FpK0i@6#dIY*1+6TsIhs8Pws@+5XbPF$$bE0>^ddN(nnRCOU zxw&v6j{N~nabI95vgWw~5Pum&WiNjiL}l+oK3v2(UHJ(P?d)xaB1*#+V;qA_E4&`{ zMA#5J++zZDvUehY**2IVdpA6VSpaDhcDtFCjYWG(;n2=r|9bR0Ogf9*6^HbuB+2ZJ zsiY)5LueF?l}dWtI1SC-U#CD+JQ&Fii**oGJ9`hn3&3%y4p@zuDKwMW+YgCpZvJdf zM5+9wQEdNS%g`e8;=_CcBPQs@4u6eLxkHE@!7JU0%#9sg?6}I@*fEJXbPs^+qLk$; z(7xb>+>Ta6qWcgiSHFFO>Y|`ymu;$ybS`mlLBx_bh~;QUHWb6kacGgm9Sj0GfxO1> z*#TwXrixvk{-zx;6>W9wre6-(0iLx8*qXDy9grsq0o$H@r~>5Yj$*&<1QW%2N3nYz z)eE{YmYyC~TZ?sCLZ2y}pQ1M)8$U>*$<>XUY@!sG=ZZu;@UxI<+ zs*W9V6^HJ>Als^V+2CpY5yK6t2yt@tA*|6|Wf|$`&txL%ZVDT#5HkvBk7UXi&v# zi?AMcxTgzHr{WC?N=TBd zcrCAMQqo<7>M&L+=?TMWXvI767@}SUqoBiL9R$^`c>Q#^Ef7kTz^cwnp_#0B;;mvg zzZM;_RJM5h&RIfRv~EEauLqyXipQ^^s*3j+3{(|wHV)lgAls^VUt>}kzlKIz5h!0x zwJP5FLWCP14*mqO#LljGoyXg?NLD;E)~-de;uU_~X2^<{+o@-=;@!S)Gi1eUj++Bf z6C=bM*shl#4<)$XM#p2&!x3EzE@B@|icGWHRPJi)BE@B1}~_FTm)bO)ib;wAB+ z9Lc2cp{#gSacEb(y-4~HwwRg-4XSwO5q8ZE_tXdKRJ?xyWJ2OHQih7R5sknY5GWRm zBFt*SqCImEW>>r+U9eaRld6DF&mk?7Bw6vgbXStz17RSOgp!`YAca=EQd1%76ENmG zEY?9#?TWYhBlu4^(XYVT%}k-0taxIQoSUcXMfgz-kiCW1y(oL*V2sLMj-s;nJwBA# z+XIJo_U2!!X>VYQ>5I^y>@AP5>UOwi5Kt$3n*wNWgBh~-(oTGu54zJ(Fvc@$#2uV@ zo*>N5-rMivc?FXefw0ygxo`-Q%-+-ZqM(rU9YW7CNhs<084*LXw_kgRy3KKsC5pu{ z1=Y^pc(j=um!iRnWv0+fX0Mp-=jM5b5n(TZQ`|Rp{fn|!JdBaGcjg^Cd&SclnY~{i z)Xv_KNM#(Sv=X5~**gniOYCsZdZ14BZUwN{1~X)@*%$X#0OuU3W89UNkU0aIgmoLcg1HARU3>}4vS+7s-3+paM5#I z>Ic?PW(v(@_KK$}Zk{z6QIh8_7WZA<@S^PHr&_A^@{}}Hdw=FbnZ1{AXlL&wq;ic@ zx{A=C?EM#E5s)v#J-2{5+50Mh{5F^&d&d>gw8e-`6~K6#S%0%=&o+eF*}H8cDlL;* zgV4<(?UN*#y~(4Mq|qQuXOd9TGZUoH>g0dlk8XysTEr)ngrwn)Bz}TnOHwEQ zTaxgQMzq4<3p#!8NSbmlNRm4F-;&;8o!snPakGc6^FCA4N*24g8*=VIuBYEW*rhV5 zb0*Zpk`)CM3EMqOZK%sc15ix?1qEwHRM^?vkj%Yaz~#%y`)Sy_IVWLNK1eR>4E>gq8@ZzY2#xC1s~Kw!l5t2#+R`+{AidIFOhP?Of8UB)zS!#6|Fa zB;``4QHfR9xf-obb0zLXo+RZ~r?H7Q2I2HIby_g79`Z0LMxB;O%!DQ{$)iroB)&cs zr+L(AO5#E&kQA#aXBFrw?|1u)M@X;vU_n_jLM^8=yClL=V6qaRFdZ%X-3>IN-T__OHwH+ zBhE)q;_3Oo6R81Y8*w8kF>V*Ks|>Xf=VK^w#b#YgszlWw&WQVj5}#lwmh=uCL9rNd z(F>cKn(VlvNUX%=8WDqh$Q7ya16<#uYIsXWg9D38)z^9(2HNT@%r~GMW2_>c zT=_l+^xmSrV_{O=1OjOt}$+9Ah3H_^1JKt-=p~)+Xg58q>n>10;N@o-{&=?Ql7Vo0ao^C0|+ zF2Y~lig4bcesg_IrwMuS=I?N-fH1N1@R5jW@%#ud!on+_VtN9eizojrg>_&iqmr3U zZWx=K*bl^qwBlRp)myMqs06dvU+LjG;^9+d%~_E(%DQ#y5Osvix;UoTMZ_7KyFO62A!L3N(u^B3QI6N-Nn`QK@+pOpc?2BPw=`Uqr6laiIXPL>O z_*1DhCMT4BC@zT_Ob|M<2ACDmZ#p!aC#r4-Te8AR)&Takz(!`oJXw(H3?XxFMwz!+ z<|EDo+7=owozBbz*3b~(B|D;%VH}41zluNipV;;4-Bl}7X4I$K(Tcn~3=eEZvp(Ev z6+u%|W{f-w^R-C9*;skz@-=$}XXE5q7T+8n&c@5LDBlWnnPonbXE}W{G4d$$u{_J= z8-_Ng%mjIc_VNtQCd#u|-yyt7US=|i38@$K&3F~qr(DDJxDu#uPddS_7+DG{wyPpS z_|9v{CzouG4s*Dj`Qi#i3B>L|Ozz+`x@AR_^@DQ-giU<4?Gjm??d#_yq|-ad@6u0X z+R4liH9#DRj8&}wmuf04sfXmAi2QHDT)QSh*@}3glDw1nkpl78O(e)iC=ym6ovJcr zAMx`GnjT6?C;!io{i-zfD+V27g^+X_%+Ze#=OXrP9pcYahCAhEp}UvJ7v^;kNBoS^S14yQK??tRCBMa6Q!U7d_C!QoF3irWM}g-7OLP1yYh?*(4R#+3jsDqr$T#D9X& z!zKs;#mJ9KCb_Km69k@~Au})7vRR)&%mL!ZNMhnfQ0+;lg$!OKevB_>b2y+?@LPWZ z;}7ClNA%E6KvY90#`Bs!$5ox?;)PQJYA-`F+$XG@3(x!9L<~6oShpufzD;7lm0dWqoQ&fo}oY?y}|7kk?lM zkCDq(l4nuA-&q(>d3QtzI2QZ%hr=;^?m%jp=<+r*1%WkD$W|o zvxdG+O>y?FJZt33JP>Cs)HeF{{;2Ou;Fa-Qawuq0D8itShw(I;3)?#he?O7L>phTzTbk7@YC6 zk;6Hs#SYqz<%~;}gXv>dB&*%cjWK8Wo}x*=$C&6h*i1=CCs%bO*-FOFi3=nnqd!gQ z1;!(tN;AqfN_&K5!l?d~g)_OJPBoaq25CJh@?)qqNM>Sxs{AV$L$J^;GZrx;l?Hu+ zu*D+x$8xYxi;qxxT%%K|aS9k)MW41dgdr12rDy|$?VAyWj=g}8PJ3R17Kdf+xMndR zc`-&Vp063_?RuWq5j(GxkG{|IWn`ZE&3?o^%y7hbo=6Z-YvO zWqZt1v1Fx6r2yVMDR*2n(>yiHvDUK1g&w@zY0*maq^;)(BRRiTi2(vn=W+y;{WagO^Fi1lZ~a}qQ4pK-4QG}f7lqP`LWF>eZ;r)$ zSH5c(^IbXA#EA&)Z-wU2^p;3Eu{*2Sp9W!^l33cH>A*d_LnL;oq|)+#fZP&gvdIS1 zDI9%8Vp&;*4+n*>fOjXcoDBcn4o{`A3&H*5mmo0THz+l;3HA2QvYAmddjV@HS#E0yj?z_>0gxX28Vg`%xsYf*DMi~}Q9+VaF^@DXe=4&c^+ z4ML-ewe}Kk>*C6bMX;4Z8s|}NnL-&mybtYv1xq0o6T(QKd`@b+QNXy8ni!;5mt-ns1+vD zOs9xp0P4v`=wS#bi-#Kktq*NNGm^N6g;6Ty#(eC=<3jz{zO&R%rzG5$C2muub2zIf z6$rSNy~Y{XF`4%~7Y=jBV|WB4_Z*Hv7Q*E|;OZ)vsiiq24f~fjL)a)t9f+vq0J=Hr z^=TMbRSe_m5O9qHE#RtEhWGqhWSVOO`0iQQrMbG4<-H8%yn`?vS#Tw-? zIpTr6FV8xaBvve?4IP1EF+61grx9l`Ile^7fFHhxvMcedC}rA7AxiVT1*KD_pA^Zs ze0RFyY{swREXwz2E6!&ADb8~Frrg5WtViN3*0=H*&Sr-nXB7&@5+{%{h^ixjI@n^w zvT=BjAi_sb0AYRYa1ST$;WRzjApp~iua1MX@jd>9w&OvYY*Vq&*y|qxn|OIRM&Ps* zz#0b}MDIl--N~2pF}T|Xq*%?(rRL@m%3T$s;*^D|gpAxPFn~^3q>9MMeHH_)l*RnD zFqDyzd*(%?xP+JahHXY}?PZ)U<(0YgxD+FnxO$`%qr^k#jIhPHPH-m2QZ5cJPBjtM z)DBkp8-WP9XTIdO=tVaC-&< zzAepFzWh1djEP6mCqekxCLx83oXZvJW2{Se5&n;ZdFkVtz^d-Pj5q2cfM-99C-vB* zak9X&BO^U5+4B-C_TYxluR(D24)5T*B(Rg- z1J>6OENu6ZFAk))4?+l+2~7lHmP6u*Na+NcuatMfa^Q(7lQx2|>p9XKF3MU|20CqAsem3}*QW{NOrtG~1EDSwmkOJ~*d_xv#!Rrv$ zxQ(fj^MG22>C)(p;lk*Ai$Hq!Tnx!HD}zw`InvthAT_D1>uL7eB1vC4bc&bzmnUCB06|gw+qbOW90oN8j9=}|Ke~aUQi+cc!xKWiOvwSGR z&oO6ZE^+(^A9u_vj{oB0KU<6AXCf|l9BHms(L=ep<4tqzhH3#9Pti^y zaQaP>&%5E;(XzfgGvpI5_Aa}7n!Pjm5l z`Drd0!p8yEmp}uqIej_2LLc7C5bnOyTrJ+`{c5ovHjIyDIPU{48N!Q-!=ooEPBv7W zfa_(kk3E5kAcJ2M0W&lPz2f+Fu`eq2rNq80_W3KhZV~^P3&mgNSRJ>Mo3`VtU%hwU z#_00Qf4Uatue}nY%>qLq&%E+3YM}W$_V6KX!_{q`L9ZTW=Ix4cs+oTm26N`{E10vT zxm?Kr{7sK>a3MLyIn55HC&odsjP&LC|f?2lfxLs09r44>*QPMc@@343h&O zF*-F2vj_bPPW*wXTAN&$VeLO`Ogjy$tDR!Sk9>d_=HM?_@%;g|x@8q;rj?EN65v0K zjlhTS9hm>>B9OxLJWzYcp#uoGCIa%X9oo<^|DVPQaC=PK3FsCl(WBH&9Ny*>wA?w~ zgqb%jvxgDO7@&pJ%L8Bai(c{KzC;1wpPH1`@yc?LS`;BMUJ+xe3BQ&y$WAn*T!9H#CjS7Y~nf z;Xq1)5MC16f3XTmOO$p3urk4TceI@TUkksbiHH4E4_K369P=VH|D{V?I^7a=oU@={gzq8jlTT{u;{?+24o+(6?A;ql!wTS}w$8SXq<<&lq>j*cB%SSz zle+qCHdMcuj+52Dz)t-NH1@B#&xaqzBlQ04VVI^AABn^D_t_qbpE(jI8#JVYlk*&P z(|#mPje)>Crzq}%0R`3IQyIXI~zbxu1s7pQqx;^ZShSduh@cuiHlMc$)s)gnx`UA*6p{Q)_mC^Z$ zGM|H|5}Q&y5~f=M;)x0ZNpw(g_om_&BB~0czJqdQx8lA*)D}n&2mO~Tyoy_lXatZ6 z4w_x2Tb`To5=8TWtg=yc!Ji|7#79TbK5;#u1Te}l%fsp7B}CB@SDa-tdR2gV1_u^O;C73qskiZus}<--z}U!dQfLs0FZLFyS&c<&Ejxe=x(D3Ecqp z2_|IW?0=U|!`UDnZcGIDSumk4wDUKil4yLz)1tKiw*(V-l|p}0T!Jdgjsg5Bn6Q5? z2+b)PO`a&>djKB=6OLdCmp_%7A|*k{@e77d*z9}=WC5WC^>{-`NCa3en6NhiNwlPA z=xKz6MgUWT2~Qt^(2CA{r3ifi4h|-4Mz!(>=({nBFb&|GU;;11=ue|>@+-ntfIEW; zQ;I^#*0gn}BAfwuF_^Fc&kFr*s2ciXq2#{+>0*$Xjk$+yO9kLm6@=FS<_jj2$_YX{ znqwtV9-u#%pw~tc?Pef9eS}OCrd$E|r$dn6itxWrMMohIj9)Pb#wOc6 zG>ZJ87yl6Yz6ros07Y!jBSy$_nR5S!)B(+jXnw1LQUArP3DnSHbpfNF!$Ohsh0O1J z`#+@#5qK+|M>mtfn8PgD0tKfyod#H}tzhhNSVC46>d+1Yo6o71|AE5Sg|gj2|6Y!K|Hh zrKOVfCm4?$S)z+qnf4tm_+4ch&z;DREl4k!X^MK7CR|h0H$iKdfy#D-@Q=~M>x$nE z+@TJi)wIfk7hU6fqGSYd&pHFNW5rpiJIroKEJ)GO5T zb$pV7E5vQk{tKm|3JTVBG0#=7UcQX+A2uaW<)&c$NnhZy5EoTBFlst1kt}Oq3H+PB zN9!)A?Lm9rp$fZ$sSl_P8eu`51lkgZY8&HGe4{$@=?RV9twgiq{b(=udb5O8 z05>v0WEMUI(XLxt&0k1A2~ZGz0C>_Nl&AbhphHo;b2MV#0PxTTRB`>+5xB8OmQyJ(e9RKn2!>vT0sazt6?FfC&=6pAhmb8&sXGN>nzk&Ma`=Rvi2wuHr5n_-~tPty0I(dE|GpgG_zceq^3v=2%0lJ&V5 zu}I!Gp&WT@Bb^6t$B>4{`JfziWeS&5Z3+-Rf(VI06o!317_(f_8wUrOOgg0uqQ zdM4=iIN#nB3)}cpj7D|P6fxm|18TJ|Ea8H>sPj9E84BtTo%>8#P*-)X#j>ET>Cz3r zQT;b`ib1y(hb`t1=Nn2w05^3?LSQ8u@K_}w;JZ3XqA|eM4k5TC{?aSqYW;~N4gzD0 z!@9sFp$g%?{wMA`pTZzo0LE&EB}O``5dPC|q$}0|FiyOfMMgnXLy_VwFz(wdE3pWp zelbPJhTM7un=)ChF656ivS2KFg|#UGurw1ci#$<e|2^IK0335K9&u@Aj|jvucLLG1GP`)R)m`UC7nhY$M!0o*=hhI+pn?GgLaRYZzw;mG2(I`3d3fW0l3yVg7|; z>Wr*pi*#-^DoEe#7kbgPsw*0c(5al@M$TBzSJ-RrHi9bd(U<-?bA4IRqZa?w@EEr6P z-3G!|{lQ!6k$q)=ZwC{4p~Lg<&?ki}H$WSJ?>$HOMjwJj-?&Am4*-5*6U1FUI)gHJ z#mB!_{|)^Ex2rm>0A;;R(^6>1BxtfX-beE`@DfHoTUGsmZf4Y&;KY-kF z(2BI=B9#1I|96tiEuBo1=F8ZE^S>gEL_YZs>q~pctk;NwhoaiiNAxZ3Ze3NPXa}Gav~F#`Mt}vk6EM-A0RQGh1|S|j{XjGpms%D0 z7C9PaLA+>e5>~#p2}JLG4ALu9Bn;2+Iien=3w{~q4iloZc0xCzx(Iuh!vzz|M*j9b zBL7RQGIa$ozy?(U6N$2w#@Ar8Q1y6K!I6OAe-7?en=ifbVx-BPtEV?o*4(TKKaJxD zPXQM{?FzW~NdcZtpXR+h=6yhf;0Zax1FoqUjJUZUNOMJU2J>OS#a%xhXNtW%=6yg= z0xrJ%11?@MAmHLA4fEA-?B)PGuM~R@2)K9!f;1N|?GRA=s4*PEUlU3bV$zfVewiLm zb=NUd?)lp~&}l4(@EhTH4vT%7I8GDCPyzfj7r%TTP<#F!37$a<{!%mn0oN+A-++CZ zIL4$o5yCG(r@8pea=Z~G_QyrstpepwsHC}A0-jBe=RJRICC&BBJ`T8emEVAiU(7{{ zBAh>vfM>Fkc`w76lct!nhw*VwG?8hp#v+ys;e9}b{2(~o*QdF@703LsvNRWehYU7O z<9!Damscu=KGQjbo8UATH=D>k?9*KQ#ixLaua-2|Oo4JI3J#6~uDN2*7gU-!Mp=ks z9uEZs-_7+)KLZy})uhcD4*#h|TGefF_n1%!dv^i|sWcw$rmAbXGbUcISiT9E6-U5U z`w;uWz%9Ud5o3w*ipRj#GIownXfR`9NSjI@v$&NUpZG;@8SH)sQSw)dT!@Y`f3+-l zc#OZSC&k}O;_-5|Y?*WpjEcpdm|6TIVvG64Lp3+DOLL9yj%TXX!~VeoE^~K(e2q*q z|LsKD@0yvr4{294b5tr;kkHH%oeAS$bMRo&u4!iTVWeHx%#H7nc0)7WO-Q?`nVs4Y zx(oBa4y4`E%(-3gc|*+%K;|9I%+{5(17z+RPTF^5{sCbJ$?V;lwC~A`t54b?GT{K! zeju|Nm`BKboJQJFGS5KtF*4t3OWI1^EYOp*Rl0e%9%-v}b3$Lz*68M~j-;*C&5KBH zoo?oY%teNo20a%W=1NFeYMAE`Z<%54hAGPpvkI6i46`I`SZSE$k@_mb{Q3jPG|YTM zArogKA=5CIBiVI^`2c6@4YT_o(l!|8k1%?pVNQT%n+&s157M?8=1u&4X_%cGkha}0 z?;$6?Hp~%CN!wwVRhyHx(=d;=AnhB&tPb11HB5rFdknKrfV91aSqpi#59#6I)_%jB z0m=cx{08ZLXP5_J=0U@J6KCHW=2|Ft$S@lr@UUTy?u|S%%;~W9h+%Go5=Ra5R7>QU zVID%h95>8A-zV)y!_16$e;elO$ld#f`78b&7-kzV9~$N(nDVb--fc+Qe};Jjnmsnm zS5YyZ80K~4*;B(D-i)+ohFKd`V_2A37{xd|%;j=KaQ!mn{ zg_#4P()2KM7_wkSm{}RcKQqky2}S%|}Nckb$96AC;6>i2MlaGd*SCD7N!p#`yIWNMDK>5v& zFh4=oeUQnl2g62XGV3B=KFnkmM&Vq|WTv1>UCU%{fSK1bnJuCGjZ9_2=RxM5 zhzIOeCUYyQ#_ddIayMLmnanRB>~1ErH>%>jOy&ff{gufq3yc2FWbPe^I+4j7gM+7c23X6c@=++2*8=~P5`MtQ_#yWZ zMlVpN&{Xl+zn?xokXr0yb{NB+KU#wWHDZ_V>;zX!h#&d zSP=M<$;){dzdFo{GL~RgWG1IJ<|oLg#1UBd;}}GFj3`rR2DNI{Lwn^b)_@^i0mO)X zWT#s*NLo#i?o6UZxS;e{KEs!ez?}sly%53`VmejE1*XSxch(TOGjCNq?e zLUSp37iZ|6Xi!H3oMTh@D3n@VPJs1@|6&p_w&2<}iEeO3%!A;<8KBv8?=|$XQDl?{(!fUfC{*b(qQ>6N z2SFVG4za0x6iVflOD7R8^l3~6xW=aP5wYq$uo}0suBV${QJ6&C8X>~Bp!{J+;3E~m zyW$%-CpmIA&AWnEGRGvE;~bBdH#PnP)BT@iw@4`XDw;&)Qo!oO-KW4x>_QZ!2I8bx*g00iU_Y{nE!K~@DE}cK8 zz?lWYvKbI_0R;Q&3DfEPVi4LgVLGKYv5rAb=QOiEex5uah%Aohpo0+~WiYA-(`{W< zB2$9miDM7b@eL=D!4HrhMk)e2Vv`k16b$nI4KB0y5j-Ij3eNkvcw2A?GB5K!w10d} z#kPiQ{Fb$s|NBYH9uL9N&zPYN64dQVak)W0%l zxilyx#2|}XSaE5EG-wbcNrRT+Xfav1V~{21|J|T-=xb^H1@ymMLOqlrg}O*>Paqwl zXSPA>YnYn0vJxA#Qc-_W|H`0mR0(YlE+LEigW}S+(xAx7mO-U)w3sa1F=&^P^8$kw z_kCdrHNj|@4(@qZ8dO3V@<{!+K{|BYG3els%y<^+XM_4F%2M^O3_7byD8wL(J5zD# zoHS@AB*_xmhoi-0;f_Hm|969SO?#n1|6=?~mp7n<>T#iTl_m48`oD*CD658%nY@NB zbCp~07D%YAm5>YcZ!SOh->z=y)*$f%9pFqMT6wOXTHe zk}BP8vUHb<>(3$|R%FUd%ftnk*{J@$G->WKaUEthcBzA#-(vPBSv6`QRarIq<7hEi1jl?U$q@5dNf=rg z!(JLrRdJ`mhL%tU*61sZSPYT$mClCd#O(l>6~i?xYaKQ;R&m}||H{zMtg_@)jqsD| zTja`$Oz5FhSxz66u`E?gl%+*?jM=5Y5MywHrqvRZp)9Z9j(|R=Cb)5B6YDAsHmm=p zFor%i*u)}yiGNNzVdAgC#PN!=QT;0ums({RVxmP}rN}VQGV$u{3?`;HCR%jIL<@X@ ziI$)YCLYDT53QxnxZ2pnT}p#;{bVT?tqT)}g|UhEaBB$W?=W!`dg1vLr8s5PzcTTl zRf=B*m!d^3smS!bZDN5T8BE-zVxkl+x?`dRzQ9CFPzDoyxW}Yplv%YoDN2KD{iTV= zU<@@1XA_UD*O@sRJxV&d*ZFi&aZSZlCf>A4F~mfRtSd78sjjo5kR`9P$2eL{7Qrzp zMG1O=QCH{5+{s|n5x9rwFDlhXmfIbbrhkAms$gRnl{2*vfKL~d69MUW6Z5k`oT$)q=h5gQRYpT;ZBM)j`@a_g#ZRJzC}#3HX!WXhpi z*H`q=43#fM#YE+^=#GgN_yQ9xK^e+v9y}tHThEVPL0n%-g8~C(IcZH`;>Ao{PH%E| zkXxUI&TMMZ2VcCmt@*b5fK7tsIn?3p?DCgFX5YkgnV zx@XFMX3w5IGkeOJGl>?_5zkRX$EZjVH(}FCx`oETlCX#itpw$#+un8qiufST7(Xmu zU}Fl%!&nq_8pR@hKh0puTC6SN2d)-(#@3<(m$YE{Feu`YyNVQXpG}D(I(W2*j(CnD zIz~l`*am}~d=@%@O*a;?mX+X;b(f+rGO+}U_!&O20&*xC>K}-GOfq06Y_Yy~HD`r0 z24%fvGMWbEhoDGDA1_j*jA)S#*d);+IpR5r%vO&muduQ>w+-Z34l(CKQ zzd<)JG;O;))&Qi(l@#}s3~dNfhA?<3CXl-%_gh4C3@PI`4jz1Vmwb;GFw7? z?UF4QBc^i@({7oJT#DAWgL{s<M#nk=NinEg$0P$sYL{ z?ru4O=d?ZYj|NJh6(CR%&K^nCXJdU{qR)={?4{3v`pnhm?fRUd&jtFtSD%~oxkI1N z>GO4ceyGo5`us(or}dd|9`h}$&zkydpwE{2%+zO=KKto&m_EnqGf$s$^?8pzH|X&#wBsPM?GIIZB_C^f_CfOZ2%` zpAYNvDSf`E&qMnBM4#X2^LKsztIwp;l%b+NQ}x+cpO@&fqdt4-bD%zR^?AEKXXtZ* zKJV4%CVlSE=X3geU7sK7^O!z=(dTJ>CM2u=^;uJ&4fNSkpPBm1(q}(?4%6pYedg(N zu0HS4=LUT~uFq%m`LaIW)#nj?{-Dpl^y#C!LjU@#s?U1*Y>wwM(hkqOJ<>y?`2Ruo z$b0(y2G70nb6I?$)DZ7Iq-#0P`|$+tx$IzAnlg+V11Iu~6;`0AQ4kcT!20Z?yXK*&`lCRq`&+sLXz2v3eBak5H(SO+*P%m*{@6jHCB?b;0uO571emUrIcaBr$f5ZRZnGdWfU_N~@>=SVEIUZl* z7y0YIFvr!(>p}M$z5;ZqtNdE`p(LfRkK12BcVKOSteBnhfD*=u+&{pvQ0#e&&&NrQCZ&=yUe55mQpt1ss59?Nb>{y^oduQJleVyIU+07O_ZJLmXO2hRualn zI=QM)Ii-_p2-Q+L`Fx>5N+;K`>FU~a^)y}FGZWB!;=ZdDk1x%?9fHRCL)>NXmX1TC z`SBUFy<}Pb3Zj3j@DqTOd{~G7Aior^vxny08R0TAbc`2w@~zf*dC9iAmKc%^ri_dj z=f(Xe4osB%Y+-U);b&%X|Gc*dCXUIEksfApeNZs3obY?&xR5-UjZqvi@~=aI#*YZ% z!m{Rf$c=PTCoVRzk)oW`V<}3=<7kE@iRwxeeTDMjnXb4}@Qs5%}0P^Z(s>U1ul3A&V5=c?5j*=>_LS8rD*Yp*&z+AE}I12`4? zFY&yxEnZ8&)d~aQjg;-WAO6Z+??-gEt{G~@{3=3P*(@B(tslnR8ox+iq?QySysEMe zV`14Ica`P`=v_eV5gvJJh1X5AH)R&WRt&F z-Q?U?)*)_FG@*^ZL3SZ-e-NK?6H>WE1Lb`XzK9avM#&s;u>1zXKT+Zsro`$T14r4> z-V}UnLIElwNh*G}xXRvw#;yL;f-VK1Qxv3}s!N{?aGE67gK$$ojA*aK#avZ>3wdRy zPTGe&CV@ITK%_8V2y%HND5l_}=C-4+17H(DMlUsG%w*7)RBa{R6bia0O7oKbgGTF> zD%*x`__4<52fIc9RO^||Kqh?(sK0m?hOly(;fJn7bAIv#H0Mh5QV~`DhG`M>*4Hqc zbNmYP-zt?K$c`A^az4C+3&1G6k=`K-;jJ#)2Eso^+9O#f{34qvj*A~F*CTFd5TEiG zsJIbf=(|WXQEm+gRxywr(v_-k@e{z6s?Z|kDmpFG=~Ntlem6R|U!%^Xm(-d1l{(YC zt4X`Fk~%Y*sB>2*b!LrIXU-yZ=02p(`~&JNIHu0RxGW}LTvwfCoz+>fD>B z&g%8*-1mYyYmTY2?zB4Vt92)r6LVCglN(War7Hf_N+bWiMxFmWuFmO^>YSOc&e_-L zR2rCy!J<^9?72PY3|g+v;H~Nmd0CyIN7T9LFLj2M!tAb8rQvne$?2@l%{Qxa%WQQ< zy{^ufpVYavbT1|t+ftp|veX$rOr6`usWV}&I#brFGj*prdAx_GRHf<1)w%Oub!OJZ ze6dueSFi=I+72F$OaI%1_0Y&>S}tCJpm!5KN=+3C|j;Su{2s(y=^zZ zTV1{cMkI;i)Zh0CqRy8t@Ixv;eCTF`Cs0Uj=l-NBNT}`HpInDt-gn^V?Qah6O;?6I ze|lUCc$|K90<$N(p2fO`F$r?IBO;z_gz-!Vy<=ebJ${iVNQQ|y@)PJU_Wjq={gRk% z<7eqLq|+Cmzx*&}xKb1GbxE73X=})GRJ8wk{l~$HYxxebw2aZ99pYt&avkCa2ecHH z8yW9?34qTtj^evm)Ur$lfQx<0JV8E%c>b3cmbLWNpgkJUwNaRsQBF!tgF4O+<<%2U zC3_bz&BZ*_+SHJOT;%uDDR7l<0r;aZFZ^foaOl58Y1h)~a%#EZ37EXzyLSsL+LU#*@Mqn+v*H~U%0!FpvFRUiW$d@|+oKEma zRjozTm)~nS#A;AC6ET(u?HOQnWE@gAl!W_Z{tmi%&H(OFK6Cyu)uGmGHJAw|KBW!ovBddMr)aAr^$uLF47ITApK z|7-*HdfEAdX~(`C1nzJYt1O$!YnY7sgX9T{A*Vq$CWchgE}Kei8iib`R)dflrOyRf zLdZB-#}+K@1BlAbxxUv_ZpQ|=KU+SWcO8~>j7W5JrnI9sFt|OkYS@7Lwock zoQ%aPezv7)se%W<-%&H09S3_|Jej_1|!XvOI=M zTv9x*7JfF%pnVj=eJ|1sn9L$LwKq236FB4pa&8n7G?GHBPK!(dW=<40H>Q*&LUJ!C zk3^~GVT5rE5~t7H`=z*ib;3;1Naw34Gs5UJsE%f^i9BU&g z2~DmdelZHbKda!x*uOY*HHIifH3gz=6s2w7qAm~pi%b-C9T0<~C@q;qbq}SFu&60O z%!#5{LgaWqJAVJr6Z?&Ek_|v?2~Z9&Jahu1Ejx|u2k~_Rj3vETzwPx$haSzf9KHte z$0!F2m=tP^IOPz=kaHe>mP5K+gQ4HQD-?eb{uctXs0U&r0*nQ;fO(;z%@I#PClIp; zFfyde*iO*f^3WSiEr%QsM-$*UC}3^q&q|g<0f>uYIb4gR{^n2|*sG8agSb5w&~yv{ zTSIMUS-?RM-;D+IW+`@uzQa(VLjDBeAF+U2DdY>G3&2PLrOIJ?j$cp;-lyTe9-4ls zG4#?H#1^ptZYlV0hsGSYfbJk(7Ymq$F~VHnJR!z&p7uh64af%p*A&jSS7%t+3^BL1yOW?+$1 zApT2$sjr6ePaFW%{p<#)%<|y3o}BU zboBvoAOWsDT$PB_ZTwfyprx_FOayUe05Bs_y58vFclGba+$}`ZS|A=KDyk5Cgn8pQ z&(HP;&b6%e1MpT6Rt7ZI|L6kC={o@aEW#;Wek#u?t-tbaiz&=DYhh@z~uQq+rn?-wnvcx;rX;AgdL z?GP_8@!#;Xu|`&24S;AFMOiDVsL%W^s4+$L0Ag5SRLs}}yFjkT{o5|I5>5wpaTL#T zxW=H+pZ&I|9A*6oV7m%K(ee~^*6+X6qTT`GSQHfuJ`Ng=dpp}g&jOYR`x9I4hO&({ zS}pEbOj4vKs12eBt3U4C`3>Th)wF!B0HQ|}Wi_LymT|SQZ=&Mo0&#m3Wyb_XT@|;! zgGDU@Vp9}FUWN3h_#5Irt!MLo9@uxH_*nfZba>pRH5U3KV5bU0p%g_;h|5B~sF-Cc z!<^z5)8$fP%e^43RW%E33s~nURND>g#I4ZI`nX#*q5lp9^|mNN=Yr81vDm$F58Vsw zT;Nt0!P=&%EZ>fM6-Gv7+zHsrQK)jXT36^daY@fw8NUGR%sHTil&XpTiM!cVRRvhf zhWN$mAXc-APmccyHGqN7F0?p*S$yVBE7(vFCk240=ACU*{KN4>CRqG3 zV4wVN_-JyM)BgDDuCgf)A=UTiN*P;wn%&{}8CcV*-r~@ntKb(~+p0V!a+&-Ze*$j^ z6n_!0S?9vX)}v+;3XjGvf+pfE2YJy%T95j$?N;&S!yC|R6u%PKC(ea0R+6;vb6CG? zqBoJ?tN)hBm84y`+(L{02iVHhgOW#uDpryq;l|h5M9q=l>T@NEuF-50xFx*4qfIm% z31*xtkrpRb(G$a;&$Ef{LxNrBN)!m{$}}VV1!gv?gLjbNr*kFZB+{%ht$3@$ccBMq zqJ$dQ(#6j zOdz@h90B09zkZp7CsBF@3;{7W7O;xDDwPwK<$B&`lTQpgM_zD2?%}!8Y1zI4>_1UxF@Y8TPeR`|mUTI-8S3D7jwYedl*m147TON5?onv0zEk_{$=L`&ia50sFx@@X)YAvm*a4x6oe! zlhmMWu>zNaee?%JnxAi_s0vuaC^S}Jg^r5UgHl!CD*?M93N0qE;-^F&tYTS@2X^*3 z@DNy`^CLAsv8>kvwmk}s75M8HAn=+UmAMh7o ze(gXFEF1Dx)Z39;paFefSsjSxQB=Ut&07@zL*(V}EZ1(pj{I-(?BL*W{;U7}(CBN1MYUbY6W9FEC! zpza~E*8-E!jxoU;!VPn~=BrQx<~jZc9e=)vN{K#Vh1#@Eh595Y$(jF=2tv)Bt3p-4 z?nOiVR48(`LKV)$YpI1!oU{^$q|6AN%|wTBLLw@DR8g1#V&N>5DRI)gFS7qybSbZu ziO2t-OhaUgfROSY#CNG?NJkKQMTxH=E#7w>ND6u3#SJ!yN3@IpU@SpzDeDB`HErQ_ ztM9=b1Ek*#+LBoM@Q)$VBb8D0-;@3bXggx*gWd!E$aVG&VJIcv|%8=99JJ3v2=5+u(QiKzxV3avQmf^IX zvN{07J4INT&9rb?>4A2s`u!1zQ$={S7~T=bhgv|sTKiswj*@6eD^<%BFS&B#GiY4; z0=RMuTA0e0qb*i$QyH;nUcSC*u6!}iNL2nFGq1{*G*?Q**EhwLTQW^+sTv2;Wxm`D z;w1bc_rTanN;h~@m;jAPAsysygq8#dD2%(Wl{?-K1_a6@c(Oc}bk)Cxz2cSbh&wc`YCa_RS=RsYI{Mu+P4fkCbQ zwGG!>O$NtpsO=n>gX%|x2de7LA>|t>fCP9?KN?QG+erS_CB1^7?<}BRe}=wyv~-4k zaI_qTesr|f4E^M2JsA4g(ZY)n`o+;MVnKejq55-S*{bJ;%Ax$M>H0joP<=#*Rqdxv ztLI-N-O(Sa|AF^d?HfS5_(kfl3#L$btRgNYyZF%2Iaoyu26a>sM0pvRbBkBKbf_+> zm}vwtH%{=XR|wUDTpH6*29rzm(26DC@(?&Y8RhaIJ8!y7ejS3<3jG5UplJ>P@j-y% zYd#o{>N%l4cVj@1pFsH|N^S8YdIl>1XKim+Pp!*%;Q^yYhu|Hl-gyH0t?I4Wju%0Y zeq?K8C8BTBKoX*dsPA9=A$qI^5)eH|ebcUOcpsw2X`nQs2dmHX4*Y`X5gI6i=$q6x zbWXwuFNw;olnmR2vq`7X)=ExjZLEB7^k@%aU&Jrcm#RlU(j!S@L5&_g z;^mMgL2&eFIif1nLmQMD4I8H8c=2uPagT3nb9PyW93u2&@`qG=r6H`=@;593w&aJH zHFN9+y>$D=gK`h#Mcor`%gesu=+xkcyI2s=QLAdIA38QW2q2t)Nu?nP;Je zn)Nc~-vGB(jkvh`Pry_9>GB-umZ9yJ-h<)M427ki{Urfj4uz$kqn*;Bu=GA2?NXD- zI4`atCLdCI8OK+{;hytbI1Ve*=~WJ^uArBLY3X}g!y7fKaSbrDkkaEfgF_wRSsKxg zW9~pWlF%1Huf;#;Y!pn3qQiYp%#nCBt;I!Xpp>LV0!9|f<|T1dh`a3&OZNCLfn3|7 zCEF1#*%O?E7`dM0`8Ab`abEl5l&j>R_(ZG&+h(GAOAd~w+4DL`(^cY~KlJQCWN{&= zDi)XiDZ2j8lnc-%{i%sM<-QSs|1nKT;U>44EoaKHg&5gVMPCoiW;!?Yq;R^R59Izk zdTRNZ3VOulu9JS97x4kme^{HZo{!?oL2`N$jaMg6Wo}gZO4x(aukI%OM@QEQ*_X%( z=_f+vCHn3sy+RYDe+11;>Cp!j3gjdrZ&lHkir zYd-A?m;e1WPRL|6LIS}@1OGtKD-xl#a#zIRdAUX>eS+AYTd5ucWXV<~Ok$v}+6pY9@F?MrOnVi@Dv?aUAozYn^rona^~ z`o)>mDUOJ~Y7UHkWKN2HWloBIZH|Z@H%COjHRndZ<4MsnG9+ibSMh_NF`;8h;i<%w zSJ5!^;dS}`c}N}JA7VeMzZG3B{BnpD&c#q$T>%{mu`9RLb?D58F~uafImSfxekZ{ME#`c z)AhpX@bOR{_7eXlU;>DFu>f7Gd>{H|J?5xPvl7I01Q-d@&0^+6XbJ!%BvfdF6@ zBI#x|b27B+xMgz`h;ITEW=y)AIUBkX0A(W=qj%wF@^NggN`xLle)})6m(I-U0nwZ& zElUEj#7EoG;1-^DGk%fv6eG4R zO+oCOfReHabSP9;#b1URVF2c2LN?&Bg{bYI3jn$-J|60o1{+Mkemq`}1=zOq=3=}) zVVbW&{E+}7LC}^O0l>Z@;g;xK_!)p}1lm+ihOYm>vS|oJ^8giXOJxC2Hr+tHJ^(m2 zwk=(-%9dv=5P3vtc~YLemTifXsh}-2Lzh;;*8sL9%21&}Tk3<&GtG8C5N{P>7__Bd zuyvxmz6auDFtZ~sJ>;wZKb&;l z9=GVQ%G3x8iT}?sy`?g>?MzNBxg@cJz~9#(#ti~C@V^HE&TzfBl3d}Wws{B3h~lGl z11Q^$)=lYUUrTL&DZLx%?a%>UJ1S?%K}hp1evwXyjTx=KLfo%Ge9G0JMn`Kw#-;Ex ziHeNY%Q5Xn~AurAU8iM^>h_bT(!=!h+R=!K=x9d*!`qHgLeS9;@sei`VT zP$9eF*Z>Mo^J%wb00CU2{I~3`lHsTzSD60^^}0#qjg8n-3MEWh1}83IM@8|vMG_t} z&O>x0d`Kbj)jq>ngt+(|{8!R$k$B8T>4fPd$9-Idp|~S-;^LYkK@yA8O+wu;R%b<4 z1C|x}Thk;w|0gNo4~XLaPQ}|_!9dWGUnX_0)~dSz72bA*cy*gLLR9-l;XPb0MNYSa z6}sjf->X+fSlO5Mhl*#;}6KKC1fRcx?U>JO6< ztZIYxQ+uGo>Q%GBCaDQGAz0l8Tcy^6e(Ke*!Hm=mHy~Kc20Nvm?2X|0HrPFN!D|R! zV1s>9S7JF=ueMy@gED8Qmd9kdUR@ce!QrVtUk_@1TcXja-6kT~&<4k)wtfl0Msg?G zdMI^5>bidsY$l6Pd~6O%YTAY1)m$Fc@ST$S;d;<7lA+-3r_PYn)O}D_E4fX>`I7qZ z&X8BHz03nUKXsv`o(%!tMY?7%yh2jrFlVgS)rQweY7)a&+3;pbt%AC!*Ug5vN@^L> zua<6_ewU>7J_`QbReC>lpQQfwH}dZ(lQjSRXqG7t;Uk~+tk<||&;xe=nRnXXXwdaN zc6QWi+Ms7JC$yosv^y>#jWGPHjmG)*!3vN$%aIHN5>v_0o2HjK?*$Nu_Z^E^WYQP(rD3-Zk70*@M8f zXOYbJ!k>X@+Q1=*2_K>NW)hQ_I4klQy-biPiJd^3jt?}^W&eYRF;AKDbq&NH4{3av z_B0WAASoMnrp&L2BaqXj4dV2XLZ2pexC}&ei;Hjf0pU$6h?n+L0_#;c{w1G({)Ii@*$E=FiF2I zMm^4=eq*FN>!@BI`4x4Y_LGUvlo!qbb+@)4NylQ-95`WvN?{PHc^UppncE7fZZf(g+5oYSF=t=8twy0)ON(ADGZ{pVHG`@wey(Cg7+>I#bwIBJ0a(#h7<1|C?cm} zmnmB*>(hqOTZCy|(F`+X?=4_7%rN5R1qPwgWJ-J!sBouA&O06o5yuZg%H5_iXvNK5 zpSELL{p?R2WKand`Y-JmycxnsN)bStumbX}(+14zBBJ7f)(qRgX?vB%J0uFxs+UCG zE0rfNmMFyY7xMg@RVKV`A|_p?e6$L*-o6sQ4iW~{o5DEM!Vhqge#PVZaU;D}4QKMY zinQyd;g!v7%0olfa1BEFCKQ*}AGtN0V?vR%z7-HEFrkuZYuX?**MySO9`><^dbbIc zOIx)Aw0R~}DQy}oPs8~pR4q+DLTG^r)k-_q2kjhPk5Kg$3RrVaz%360aHj%z*NNevUD68IoffFK5#q2Df&)Ssnw&h-)p;?B zN_U-CRz4~K;WIv2gTmWVjO1jCi#5t_0^L_f0nGvcgJAF%zAjArhEJvU4Ct1@`IwNU zl@dA%;MFTp-5`fd9}HTnqX2GhM@2Bo%anVUgUu_#g|}{d8-%U+4I~~FZi4Dwc$DZW ze%E0jz7f7K6}@zYS*0+!LG+FAUXi{L-pZ0?pC*P^jf9_vIY_U=$z1qCj63OdpP=^@ z)K_{vcCK)RTzD^J%M0%#wrK&q^@(l9IbpaCx^((QoZ*Da6WfaOqA+ILUU~=RyXazg zGnMavrT|>7d_SEH@0H5;U#K{}oAO;q?A6M*Ke1WL_Y-1!DBt=E;O(b;n_>Qv-d{O9 zkDadc0qQ*p%aJ}%z4eG4u6&ykd$V%bM{KToj}SXTz3)WeouJ9yrgxIY*24&!K3ik! z(wooNZlUB`UgeZ1`IcG&o$@-0tO)NH>8sCvKg^<+(dL;I`4Yse$eb=XM%OpO(WS3W z+_ECva_<|djTL5=ee(EE-w1E3h&z*vHw}&SvWT?g*7(S+jahVfY4>l#$^A?05+to{ z2(EKSOp2sUj(nfFfyrx4KjWh#p9Xir$I@E;X zyl`irn%;B@40|Rw&5ew}zwivwj4+&Snvp?1i9j{Ir6F)gbNlNscYJSS@|i%J734F~ zgdp2Npqk#14P5vG6s_4UyOCwvURanlJsx@((OHpgcn+jsyb49Pcg!A7rqqO0X&N@h z{xcH!K#F5C z>I*F4-7PMI<7g*M%lg#5@G_Sas#_mOG>6)|!K|=&#fv5~BS{CTQX9LNw{pM~-uq$( z(O|iP)R9iea-d1gD`AQv2FcQ~K>QsN-V~#^AQdgtASp>D*AEGAkugI|A4x*vZ#vm1 zagcQQ0tg%_;~v?4+}BGEfKYV$p3QBgZc1Qwv_ zhdOBU4QO$|jD_I*sLmJpZZryjxc_25qUlzhFnm*()-(B{ihVJSOYVVgc-LRJ)2fo$ z#_`gUK0v7Q9u!zjL_eS|s>0-huOE*Mm7Q_j%JG=c9&Q<>ZQqYQl)Yy6$V>ZTJpj*| z&7(-#Ot7u@0+q$fU9utRg$E$(x}zxKAesC) z{4H@41VSl%AQ3m^I>?q&p!}?L@^V1L$_}Gj-PWcF^U@%bC{rHBCT!hHO#EL#d*^l5L0(*3Hr;EurYP_vmpxXDfXi4zN6yv7AVK+;*!8TV~fssif07K zitwm?RwQyEpM2|_72yf|zV^xZz8Y_ySrML1&5Cev>Kl_5PUB=JCLaCL~-h+K^ zk&e5X%wHm6GHgOh0nJhynwRYM<98PL+g~_3Q+F{H?T68fcq)A#YwA27X3|Vcv>=Lx%oR32fNE& z&sr_}wnr|Xvv?PwKrQ>Rr?7ZS<{)%KR}DqdE+ehKp(UsN1x2(RU}%-Ra0hT`Igl#4 zhAoxvC)L`7yd;LhS31IUzw_w987$s&ki%P;{04|d=+8>6< z5hM8z$o!{S72w3Hv;Er;Kg}he2l=o`=hQ6;>Jmh(aa4Lhua6pR^UMGhh`niJsM3>4AltF|%xe|YhY_(EFY{8Tif`rKpW(FBny8Lm&| z^{8GhZ$9-0B6{c#uq(Ljly{g8{nhvh(eVlKJbdTn@?I)`zTq;&!+lh2ho-E9w5$q8 zJaypZ@T*gQHQ<}@iz>>?;iV%!SBCqF5C)R)CL+HsL@=twy(45hR#w64$%A|iD51Vk z%f=rVrq@f_fEvn*@T~8+!FZG&?^j2Bef(4adQgu%w3~At`iFlBd{;UuJ)rUkUJg$N z`qv}kmO|8<`EMrQ$sjIgXao@6z`w{r=#dym67Q3|P5y;34Bfr78{qO9AY-y%^g?&D zb&QGNbaLo!DsoINY;@>u9iwuZkoRF=j}_vL(!Y*bLQLM7)q%`H#ChGkL z);}rD@VXhs#jg$QCHSct=n+&_4wh%33| z_LIb;JUKj$ZdknPx4a8!D1HI(sBBH$(QBwrFw)aCH(oS)bqd!G2I1{Ch) z@aU_50V10@f;RIM2E8Pndd=b0r~VZP_j3?!$k6|dUiq<%^pbdJJBJ^D`?nxG(E*MA zZ|B{Yye+c;@oOE8o;KwXUinkbyCCA_TDOn(u8L)o7Z!A>}IF0zE5@vuZsqsTeD0L^~@5lQVR|3H6N245!X-^BWT$p;Ct&O{Hc!?=%dK{2T5x~9Nul^?*ZUt2eP%m3uOHF5qZiHOf4khyp)d{ zWFW#&A9Vmf5nd9Hxc7~mfx*w^w-EjX*)g9ypc#+Dw-Ai;lKA;U4zIQIFGlz({G!D* zJWmT_u`&WOm)}nK3lRPv2lKVT;advAw88m#iAw_(Dq9Y3R`E9>@&o*0a@0A)vUodZ zxP=$4L`%0Uo@i6L9G++NzeD&B$H5w%UNl^x8*u;_KV?l1tUo_n?5p$3T%J7gyCJ&x zsU6c@8YtCtmxg{%AiX3WG}1>dKM?U}xa6Fxq9S3MQ-zW6PxQjIC0|p~%Brc&<-L#o z9s@wFFVR{bdM&yN{MuFeMg3kbzb5fN20ZwLCWWDtBg&TMM{Q6pk45=s5n1H4Q!c+W z@hc1hA^4JnAzKE1V&Y%qsO%Cc3>j0L%MVQa;iS5+NXGDA$>Mtu0LSn@$r^78b}-Q_ zc-YFHO}L)8x(paD@arrm+{@+XDE>B*-IpeY+pSS<>P4YT19=ok(=!&t=*aq2N5+py z3GKkofX5BCb*=L|v~V=po$e<98QW<2rH_9Jle0?MXl<3M*HkIJwn};Y%^&?g za%-tnH=^8DBsYFC*exNRsUTeO_k4$sq(qP>urW=l^eg8%kS&` zl%ZhEZ}`d0Rj2xGb<*#uli)(t$&c;*tl}&Vg`+Ht-&H5Ut~%>nfYgH!F%v(nMYYm^ z4u)X*p34l6DG_aeIs8mtRs;MBet|lQ)j#tdW9pw?SN}+3hc#Z%>3@RoZ}>%%8!LTz zh_S{>kCo#%UYb;2=fpK{0$ZIE*QbpcqjO^QdO5uO(oYAV6@Jm8csXNfL$5^S07p<8 zYUh3TQ$7qEy!p}}0mSVNWyY&qeg)=lK%}-*qM;qw$Hu})_+cNL$Y%JBX;k|-SrTC~ zWRRT4FU8Vu`h7Zc!RE!C#^p`al0MAyrmRD^pSo`|g5!l-D4|6ec|Tfo)x$XT570FI zx6F03^0rvHBI6?Y0Y)cELo0qON!;h`=+J!Z;*1f zJd5~${e0O0x7--dn7Lccb=gI^yZ+{GVNySbs7}Y559S#YuIjt zp9Oio`L~xnot|gm-}rdmHp^%q)!8dGhw5y|`A=NFoDaAEt)5pPzgSeR)t*28=- zU&4#Szo(Fsm^i*~F~_Vc-R=OleBmVW1#np?`_6&#pOQuL6$p#uFrN9snJVF|Z%!{= z)*ki=q*r|uEMK}KzQ$PkIKLbQ-(sOoW3hgNP`*q+qybXF1TGP7V>nn=Puo3-)p3`WoA5(Tl z zV2D~M+z~8_@*AR;a#xTL-18z^Z1QKUJ0-|!^lbnX$ZAU{Q_H9>6luf0C9sY;yxQ2` zj1)WYi}oD$mPVM>%fV?FHq{DRCIjwbuK17l;4SS(1}Zy9f8uzCC!>SOK`tcuPn4&u zQx&$y#)rI3P7@G0LyjW04w9^p9Q^xo-U+uK@v~%Gf2^`>Udb4e<()$#s5&l2(_jl0 z3wH=(5&l55Qtk?pyi%$|HIDqJW#nHfPbn8}vl6yY{=N1buyn~6?$Z)N&BfWmR!g?6 zm5tb2rL|ej(wbXW-dQA6MF1txgPtIw=NmIw1sqD>X02;CIJpUgGf}zcCQW zEg`p7rwx9E>5?0W%0Z zBW(f9m#HAE1SDU$kFy6p7`!>~R<~?N6a6p7`}K%iB;3kjNx4(A#X|O3*I$?zr}gs# zh`pwf=@IzGtB<=ltKeHGr%*M;lD>nf%SGr=dlg(CK9j5(e1=tW5Xb&aRt55e&6!sM zYipXSt%(B-sII^%6)n}aHPzlM>5=Vu6)b~wD5ab_tpQsED40xH}kxXdLuBil7WVWl$x)Iy~@WRQhZe7-6^L8mwc;ur@7 zGsO2H;C#o8?h0S1%0Q`8u&l0|zr=IYehCT-8txCMCuW5N1ZKVldYR31M5g z5|z=-@~D-9wo(=SW&k2*0gx}Wo)s}D&Jw5lDY>{h~puc~Wm7+MK*U)U12YSu2$(>$9wi~j! z4u*96%ZB`N>dbhj);dUR)anq!ED~z1q%f+LFr(IDFsD{RoLX}&k9E|RYp%BgVAQ$~ zKBLw%7I;+E`jzHKwI=2hOSNXgXVhBC7O%W@Jk`2E@l@+8@L9D!XMwM{1U>K5 z=9*{P>JLCJm7<_E+E%3pxD-eoo3gM*7pMW~ZE3@;E2rAr?zEaZhp8Qf9XQ&~O=?G* z5Tw36NPVTIb`+OdYttllB-b9~)DuDC98H{W*%nGXSKMskFyOJ)yeR@b{qbw^Fn4&} zR*BNhlvT}MLD2kyg&3@bnaAp6*3Hq*9J%)?F{{X0mC{+ zJCl#_r5gT%ON%q}5WY>rI%hk>nb>;>8%vRB+14rxw*S0^8Jn>bwdT4e?GWc#B%0z6 z69{9ICd@SHVldaF32{w2#q!8TZb6e?0)T1K=iTj^beaXOBk<%?Di)jcwLq9Ay%0WY zDJ-^~b>q8_Q9PUUuZm}rEKevQ<3_P5m+?iD^7s?;zL%ZVxsyHl{qMa^gog zyl$Df?IbjJhb{<8^j}(@HowVcg&^`VRvcU+OtYeHq(#8r5)?o_hfQ2-mI$JOg!zon z_9t=-)C`T#1}O3^A|`6YaPG#5{Dg?Z8lg>6gl)3U0?q(wX5Y7Y9%Y;KWvEV}x!*Ac z5MyT@zI#~lY?LE_GQ-y*_-vzGYJvB;1ce*r6F@GNqM$;JGR>xp zHcFil7@dA+6}1(zL#KPueoTw}5sZya9ptB|PTy0RsZ+v?PK&{uP6=^3Jz;tL8mrSA z7dxH451$#k8d{;7l&4M~P_d}f8cUo``@m;9dK-&v?^M*iui~lGU5aN%{|r8>)2S9X z+a<750&gjqb4pMLzNJzWXQl-F=PvjwkZv})Q>A0(F@8VhsKs zho8b^y-l(nAzgL!o(;6vO`$q=iXoMMqst@jQu6UMR|Auf#PkgZscE6GH^0K- zn?aB;(>IF2T;CwX^$o{kE3yj)!Jhyy_Gb7!u5a|SnRyl1H=b9q*f+KTVeHKh@R`0b z(qhM1H@^FL#j|g8T|qqi#%TC#-)LqPeu;J6GGvK@**A8t;UI}q}z1;H1Kz4y%{{X<~wbyE=*BKT#jlh#5RV?atH4vu3 zegL1*>oSX7ZQc0p^%PINwz!XY>a`zyR<9kbKD!2bEwm7s3gl8L3Mw=}Znjw!R;jVX z?^)Up)b7${^GuZqcc!#;y}z!WM`8-*EVI zjv7Q)jX|Gv=wR(*xc?gEj*Tx{sQ+`+(4ixT|6<9%1eW|}{+@4UjysFl$3JY&Aw9(t zI>v8aavqNVFau3!vdjWS%F2cI<#o2r`|bIl;_rer=t|FH2D4WFT%kw?mLqnp88gc2 zm~jdbGh`py_ZE<+>RZrC!hy_Rv@UOIbG{+3Y{Ogg*7F@sJ3U=IZ!Hsgl`ykMB`Beq z62`8hwdAJwJ}XiNK!W>suo^Hs;z{cv;7Z}yzgI2hQ|n3%S)sV=L0ke{zVI|)_oQEk-Crj&RUF0(yQ&}_iLRp!O&zvkR-{n;c zZ?#?pp~42{xEH=l)wd14Z1rt|Zw7p3%iJ*-ZW;K?<13>w%@#eGm@V^SFt=rHAlx!9 z261MW5d0O$WSa;7Bbj#7LLEt(1B7D^Q1*QEy8C6s&|5rds13?g-dS6*US(8Xy6jdt zsniFxU~DA6z-KDYftvsvD3s&^N!Hc7`A5Z84rFaAZ#S3J_0YHpiKY`EGp9B9ITYn@MNR@Mzb%~_U#O}MLWmG{PJ>`_<(I14A2bo6? z_}Z$EyX(W$NAp_%UxDK&&vc!l z34*)`DUdhLnU^WghnDsh%X6jd5Ax{~x0zORHqo8-$s8aWR-P(1cJbPQ>ds`Xns`cLqHg% z9)r&)wWr1Qb2{q2RPj`5=A%xj!{M_^eaZs&xde9SXs&`o$Yv{iOQk5zEaJW;BX*e) zHhEFa8Y3`jp2EDltc#&$sBR^4oKAX-V$rBIhR+y*q6vZyN=SiBvwVsg9NPMMmga_F zX)Rx9UbOc;H80xxsp_M>zh8Z{_Xm{ugO))Nd#^_!dPuW#8+x-kYB1lF)72PS(fOD? zo38nta=+9<-1^2gL6d&HB|2rJYu^~8FZno&zWvHg|`CTq;FDh0I+Eo6>bkfBfTl;JHBRWy2&}Ii^@w_E*7QJo0 zeBrrrXnY22*~b>Dd7KkQh30W+<{yhT-*KJ7v*|Bd%EK-;*z@=DoZ@N!_DAVZywhxP z%V@X!|NQ{XH&3=*$ZpHYcdL2>;i|qE#92{7_-BUw1D3<*PNuu$h82{F!~Q}*&9Hw2 zJ~QkWO%M$GgcQh!mQOJ3k7Zs<^f2y^me!;ubUaI*)_iyxx5qBW-9aK49{Gn8xn_rm zkOC1KeJ<`vmNwdOFSnAillyEWHS393NWhuo0!ck5=as^*iyK*5GwVY3%fKDS`9WMH z{LC2Iya@`s+#;@V$h&2p%5fKndyx@N>ce-zZf5B~?;kcj(G2ze_@h(Z5@MWXvyMet zEX!7r0cX3{gMqQR6D;H?Ac4(&6J%p^2R`j=?tTlbRf{%vva+Jh-3)}WxnII(Z0+uSapB^-^aJmz8lI!p@Z4az4YscAl$_P9 zMjD&Rs@9kEPUS3@b zYS|0_+aL<^@-B`^-6=|7UN&_TFE7J_F8Bx+96Hbxevvf7Qrd!2AY6;^Z!7d>#bC5= zqj_^087KN3?bm(4Wb z1KnR_#M#xFl=U=6BmUviF+H>beBMXIl%uY88*A;Jzn@jO7oR-JC82H^xNaU1dGEvs z+y}gk&|RF+c|TctZBiX1T>gJ*`41Qc z|8LrS6g@fmQM7u^N3oNMOerNWDx(fynwB{G%Mw^w@&B177VuIf?rwD9OSwP!Db?kn z-|@)^SGLJkfmdK&&A*)}tMq>$P~_zy2GU-FnvySoDdxZGmCo9-{Y8A;Ht05Vi!Ry= z#sjrM#=yu+mLk4J#Qk#X&~cvh2{E^O7_+< zN47}5awEIN9uQs!CSSI}cje34Rp48yzSZ!32HykH5x!UkiC^c-t%x&eZ-URH?F%2% zPGK&Kh2PA_CiCA3=S$-tU22f7V&Qa~*A+>(H@rwbMP$Cbji<@=0DLCbXW$ERT`gZC z*!~rMoAMKU1@J8p-W>3#)xcKkCg#U&Aj=0p`x~fySq0xkuhQw1rgm;!f+swMHCApsCe;Au{cd%kfoX#FCX-i@jqQ;K;Bp0O@Pf1^XZNOb0dUc7_cUm<#+d? zpy<;y#uzqvWC7oSXLxyz743F&3*c}vU7FaUGKn2@3NMEJMY^A37oRI=Vg`f~))`yf z-KO4P-J_64(jE*<%zzLB83!5hIVXw(^fsA^h?wG~(mcSzWUFa@332OXR4)FS^TxOX6an+xJRR8CPiGvae zGan`nPW&(frubI9fo7=w57rTjbfSiuFxR~-t_a4~WG=yDOrQ(xlHHc<^S zt_fHojUmA^mh&`#Ks&UFpWSDJP{Pl$np}$+BqGRt3Ske*NCa0(KA!K`{L*tIP% zgTRx#!Zcr}*!_Sov+QN?nOSx-i*0S)`0o2vKF+fLR6J+dRo;daW(RPD1#+*Ne??~5 zZGl`WML~9!jh=!E=xkF)XW43w%xd&%OLQEd*Fk|^Zv%6jske~mYLw~oPS`du2z~KR zB#EuGDV!jNY&zcW3N|;};JMbF5pLG64*d>?^M`2`df5t=7@B|_^4C^2cirY+9b%x= zJB-kM{?(x~hMEzq*(H)Pfn4>scAvI9WD_o`Njq1x1zj z=({)@^8xsl=<5cTU@N=*zmgBI`AF7$tCvvbdt}sWz1O+lZQ1wHkKC@%k82w@R`Q)uElU7JvQ0hEqUk)rnVUa?ILOb=;%I{%67sK}KbXj0apeWNe68%^! z>W_amk1vfrSgvLEjyjh1rO{-T<6YneEvW?1|~)*XTJ zNb~I+LKC^`yEVkXABZ(WXnTvBhPEKvL;Mdk|9hB7|Ab-ukmTcx6LVH>G zwbn&WKO-kIgboHr)69#)f+3U;s%o-LUm0aky}C(e?A1=8@uQ&r`z$mD7Mh%3bvId# z^4gw#q3qX@96Zq_NSN?y<+i;uEs?(R+vP8 zf*nyI>8BRJ7w=IKa1$40`?t7k(G?g3*euz|HF<-PX!psoPgZ7^N`ISs%a zLol1Rxi_$GV*a-~SaT~tdj+U`nFrrb@U4=P=fHE@A}zqy46ttuF3!6|cE0?H_)CwF z?|1Os1t0!q32)lF*ou%*k9!=6DAXc3fcSiQ8qb58=rQ=J9;Hc~cVpoc{@vJ2cpQ=W zvH{OY0AU1&&%n7Q5}Sd))NYCFS0J}UOcHL1Fv^shQo|W4VRpIC4H$ z4+%%k8ANgrkf6YkRdUX72uf74WB~y|Ndf{QNLD})5JWNpB1lp|BnSxaQ`J2)dw2N# z{onh1X1k~Bsp{(LT+=hBTq0GqPK|X4m&n=mESX&*fr}htmq=lWu}h>eV&kcyhC42i zVVTiNnkcWXdW54~B7HP)ge^a*OJoA1@t^XE*h-9G15F(X1C1s2iL92~*(dTFV#+5n zTMPWe7W{K_F=&`inONY-CDV~kKXDoVF>H56!{2wt}ZO1zag=F^SO;B@*G zzuf79vsnTjcIxm=NTf$!aXXghPMtV@35ohxkNiKV=9jorqJZ6SV7m){C1(;f>4+o$ zCY+&2AA-Wc8H(6Bi7iDe`)`~!53wqUji!u<+5Ex0sOZbXg}(~Y6@LlD6#vVJG5;_I zPNkpFIl@`RA^H@F1Av)Ae<3!7uHaYj zJ7@Wuaod?JHN5u6j6uaCKWem_XTKMD?|DOR?jm&o!sg>L_7R0^nOU-VtImwtO#2p_NKi? zwjqTy6c)+9nPI#}W|-=9DPZ;*nIX1ii)k4>*To)8u*^gpe>u>PZrLWEsNN6N{&;O z?F}0K;A+wA$t|mPNIi8?C+iT_T_V=4)CMD}&m-rttsh;7v#dX8`dm9o&M|QqcrpUazx5<^6 zY}YN5@i&_eVx&8$6+da0_#QQrd@h6d3y^5yh}FBz#8{UVt7?N8BX>0dn|~X>_wela?7gL&o4#u zUsD~@BWfnr<<_71zNm#*BgDp&4YFImXUYzFv6NS!cKf$6MgdgSBl=( zvLSEiJYnKJk|$Rc!&FtJfZ0{W5WA{cYZ;Z1ol{k308mvGdSF-8L2acG47@*6)Z(h@ z2861rWr(S&I-{|_*_LluSMXd_zK3EH#0ns$t16vt_gS6xuiO_61k6>{7qRJ-9H**k zB@1Hv{;l(~tBTLcv(fnZ#x2`e8iTRr)(+dYhamyyDKyFUKj=AA@!Q0#HvgYgaHq}x zm+;#pn_t#UirXgHZ4J{x7l%9ZKb(8MWVwfNKhY$+_-GfOJKPn7J4##5$(xI=^3J14 z_V|GT;F`nTPPj`XgVh6Ye_E7t}PhkbMuk$_T81L%} zNR0P&uOT)`_I0+5g<3|c%L7FQ@9mTf-rFe|ytiW+(aW5 z_7i5u`8|lCQAeE(-C?=eh*Z6yJ4|CiZSpT~=yDgtQ+wR04c(Ds8@i*(H+08kL-z?- zhgbdpTAa{;$#{yz8@w#@l@2*{NI%h}JzSf-!5i}wM76}Jpy?x!JsqXr_cDg(&2rD| zdDDhe(NN5HPel~Zn+#KpGX>0^HyL8jo7J_99mvj^H+KV|=FQp$=`GF4h0KJ%c%C;8 zi&{KyP6I;Cn+Fk7^X8R>f;4XF(A)4m!SlRXkQmQPoJNT0d9$gmpadP-OPqcJ=6Q1t zV$&%(PR*M~SrCt4&vbrC=S^kT`nsT%p+EgbWxu!WdJo)cJz_%|xpr;3k6~$7FZr7o= z;aSm-?Yds@Y}ZqWX}kXL2^7NL&pJ%D9)AMlbV?3NvK~LYPy`syGwD`cMxzi+dV*fv zZ=1BZhp;Q-DSW4G20$D$%mP`N;cvv08TM=7Z3f69F&n%5*2#LerT&M&zw9$+jr z7BB`L9XPk>B#oB>r0;~cQY4Q^#7-hMo-%6SnNxZ`N(7gB&f(Lf)H;Nm<040n3i#~y zmmKCi=STwx4l~dCS-b~n0HE4|??Y@n z*&urlqSt30UhCLnsg2pe1w2Q^4%!X0R4TjA+mH!5Pc+inKiGYqVXDukfZ2VXA$Fg) zWf(=m8v9%TRAYaDm}=~m7lH?W4H>e77m}=~e77EmOQ-|J$KZ<_b z*iQ?d8~ZcFbe~`OiDKBGLwhWZP0hl2EUkgqbV`m>jXe=G{EeqBI=`fiT~*XdZLBSJ zMg2nWNg=qR7D+zrDhWk#McE*`qC9v{g;%3|R^6^B8#5UOp z6H^s6Qe!9R(A#j3;JKoP0i`CrMf?m+9gO%!SI~Dlv@7a60dqxNM{GJJ$Ek{nP0Qth zeHZBb?26Jo0DU~JjbU8XMQw-@&?#zjm@QiggzDf|rySl!Or3JD!IQbTPpFK5hbP!z z_TMoWV>|orZfnsy7@hQ#!vs-IX^>g#XB2}57wL+l!D>f?BaQ|(xG=!bV2h)H0<#7T zMrE@GFKN+*beK$wzeNkRdGu)`XVM{tgV2w5E6Wt*hH8_Zv-Pw|@izAfYUgm57jB#6 zaAR+VrpsG)n^e)}K1vH6?zX~hlb*wElkBw*7B9az++&2hz83r(ZhOkJdpmkp&LeiY zR|)sBWZb#|O`xdxC<6X!gMnAvR)5(ECi_qfcjH8Rb;~>Eo*Mp~9dk)7ajp$fUq4H_ z2^WDQG?KTe>uoelnmAVzT4L{dRukMIMYgQ`g4+aIr-8nsdZPW$yzF_0H{gXdT8tp0 zlp`|H9`-ov*KMgucG}2zJRQ^hf>qZW74D~Y{W%-vp)jpHh>{;{m{;?L`Q3QEVZNZN zrTZeO1mj0k7Ck)XY?$BWc=L3Gtx6m8mdm)4e_AstJ~iCzNS{QxFoWOJV(#mZM%Dj` z>!1IxSwb`qo4n0UjCC4tM7NE_c*yqTJ_!bkR=0s-dL1;sr$z+tD#%zZL)P^}-dd`R+ zg!YjbZeD&EWR7 z4e6@A4b@^s+xpDd_OspI>SwguTXK}s-V}t}n+-|Sf}Hlo5d5k3wq8@eaRoU`Nh zHU>b|-c}$soswh2+goy)-QJiJe{;l1b6aO(XcN&K)!t4>M%>;)nK(;sZ?z=G?X5dv z%0XlE|EuMsx|{`89828hlnicjN(Q$%mNA`@b14T+@>Hi0vY_xrm{P!avK4Sz>TV_FE&^{T)so+q_+3Q}kwK*bgxD&?Ztmi=5@?CjQ*o>+V#_CT zY*cAH%zMnSgNXI`m1CL8AnkpQ)j;gCJ{)@`AGS$&Sig#*3gXDaXpSvHtOvf5UX?Cm zFfP@e|3@U1I*B1+RBill3_B72r;6$6V<5~C{Lk9?Ul>w5MxCgPAATz@T|LB%)kIwu zp&Q}Lm&Yapy@UV5GLwn_|6CaG3!;MXU6sPMfU_i?B}AIBhNu_X+hFV$iTFRerK`iD zt5F|x-?D$nzm+C_O<2LJQG4X*o2JtF^-%c-;Yzb9s463dwxFz$UV4}Zk24{Q_`OY$ zDq5=_ezz5cY>9IYF|Fbtl5-_~A1GaJFGxW;h=C)f?YgNbAHV2ms};A$GG5vzFG~_1 zP*RrTe8L2;CHgJ1mP!0Fj>=w){4WfE;$=e4FRhk00f`R^suGA=)hKZS8RfDoBJWBS zQLHb9uS?@*1EF5KC6|h0s%WUDu``6%K&Z-j{4>Nki^+&>OvW1BsZZ;0XmJ2%&c`~` zQyL0ck)BB3YBX~MJMV$d^bPq4z6X!@o$h^&h)9e#hOaGtJQQ(!34%y3#zn*9@qG!V zNV?J)<_pYBMFyIfli7Bi*^4j+?FS*%5U4`|jDN=aNb}nO8VtQt%UfEnr^dUtSaU~G zpHh&S@sDfx52e8G(6aXHa2v}k1h%NI@3aGs^UawBC;mop78yB0#aQO!Ohj7?*Ht4Af zz}-jb>!!}lAG(ccVSURpcuYceuH>fxm@hy#tIJqUZC{jA;d9cdxnLoRd8;O;GJ{|P zQ}e(jTR2UW55%ZfX(tG2De@8-QMIWO8YE%ZLTPK&GRojCGNC~&gOh`Nr+)a>NJlfa zx;%pCbQdp7&JQYlti?IDpl6V;xm&3m|6jPP-9izga+?)Q=Kk&`@(!6So}w>jHAThf z>pBv2vXvM{wG5SOe8s_plN&ksu$|mZ94x`4SrSa%E5VfCB$yhtiILM@mSB1f2|ns5 z!Hi)N%$y*>tS=>)eOiJ!|4J}7ADU(Q4D)J8Fh4{?Hs0}k`nravdI`%Ts-v6--Nf)R08N+0S$w*!M8fhPSAcThkT9TBU ziGIrq@lTIU!BZKgf6w&M%q~Byn30)!v;)YbrEM_kAcZd5D9~Nz(=Vu z^SaDRi_8?qrSQ`iRd8y8QAHTVF&7G12L}O_hAx)TsAkVaiAADmd=65whB+u!F347a ztjirBD38 z8kxDya>R4gS%l7*oCufiG`K0q2qPCQ#40%RYwyANWl>>J zOF0M-m(>QbQ7$Y)EUE`W6PK8q(!hI@xyh)E_(}mpS=1fGehj$4@{K$y=Qn6H(mr$< zb$UyhkF@1ZdhiOkY^DU-0>WOG_!UZK6Wh~C5PoxscbF4X7pBR~J&j@bm!L?Xe*s7Z zHeK8+VW7VA&T3FB0P!wJB;}#zl_6;eRRW=|L-a|nG-4_1U#5|H_z=#cEvVfbM3D1^ zBCo{5Fyl`Z(;a;@03R|)+2sZ5H5Bw|*-Ddq{e>2}G{b)Z{l-Y2xh#j?)rBysY`O`l zp)H>wJO3^~Q%}WuoU&B&e*P+&^MmmlvsIr}v@SNNeh(2jf9CUZjpc zfoTx6cL>@>hW`c>O`okqap2NtD>-Es2c=eVkiCC~-5d<4CBcx@5)3~m!MoQa7)jqU zWK?eOrQg z<0bfbg#`0|kYM3&5`5y_!|Zp4i7xl~zrm!>{veMe{!>wcN3$e&+*E=m10?u&JqI}w z7V`j;qfOtv9JEW6p#5wKI;@eP<30&GU6A0d2NJxUb{{jmQ&fV^jV0*bQ-U5dCFu3F z1ijBl(8v0o8Tw_Dpnow522_?{U^5AZb&+8BNC^_>OYrVG2}T}};QhZO82wCwF&VKc z%AU13h7(WEv@cqPf^Af{6(L{ZKdJmVc z7%#7aOjoVtWf}_z(R2_$aR9o(s)L@i$?ireqqrcZdYT{f}skhUsrr~+_%q&EU z^g-%KF0Qu}M@MBqwBRf(hcbJnTiv2CMs&rz>zTosBBS`uS#dX0-9^R+tKe?dMYL}7 zg`iO|P!FSrXRg&S4GdNS%xo~vsJ7To6;;Z6W-P}|sa9WcNj#IPlaaG(KeiV(VAVT8 z*oHd);y(d#N(4QwfrRbxmL5%xLEsr&z7b5uXmcLx5zp>7o@qKi*m>;IW2xpv(D$yu z!yyU=@Q+h*`Kk+VEX_bgdk*CN0+I?Ky;wM{a!=3>|8oSinn-Wr(1KiUWV{u<#q&$$ z3-G+4mZ=*6eH{?!XQ7_w*O$|4`iG#+cj(e6RLjUrX-2>tdCbH(GDNd)0h3(RkBm04 zG`$LOVBYGGjmS%PbK8gyL7mMA z*?36L0PK8U2r58>ELC)i)&sI7Tu>&ihoUqFc20$Qwdgpg=fV+v%K}l7Dx-xd#6wV@ zxrpMlt~L;5DS$|dHe?c&kLHZ#IuIEa`NxJ#BW!R1 z+2%l`L{jLIbTKc~ok?HUg_8=}S#*J6qAmZRT0C&1c$Uy5v`32`fEq|=SFnpy1}aY1 zU>VOcx&jp~3IUkk0UM>%0JNOijZ-6#MR~~&q-O(BL*SaZ*wTuygNQmKwZB7A-A(iD zB^nFLbeH-Xx(KEWk$MQuOHjT^N_BO%aVLll0dwuYa7nVfMD!TIbg;VaZBF}0g1b)i z0x-ps;bgqg`rRRV737vK#Azf+L_H?z4$NQ|*DS1*ev>``#b*2fej zs8}H4U6izaje5m=1{(^hCJ;?rl$1=P8kz;WYE*Y12D>OOA#z;gN8wtT>#;K9a?*4l z<~k@F@V0pevn_WT+5qA=3{WF!8S2=*gW>6EuIi#C90&27D?tN>n1xVck?;V-r>=w| z^g0#R|_gHq$LDa*4Ehr&bdST?6qp15|w#rl%eNa#(HhqcS5hVsnHm zObuQvd=114)*+1Vlo!-O4g&K3;-yP|Yc!g$I2~$%*pLBsd#H=Wq^GR){S&k_)F^cZ zvA+XQ18or!R2}OBtljQ1YBCV>808woC_`=g8lE;*!UQd90{}adiBh0G)~Q%6=`;XW zl1VB;e`Me#tu^}tjWRMJFTNx{luH2PtVO6kQ9BQac^P1rYvY?J*A%Pg0xh8`h_%8c z2w=9A`Jk529>mV!5@!Ak2}`U!U+PieJrE~56711RP^&EO42@b2#6}k-^Ij1W)J7|7 zIXzna2*gb4gC|aM=n&#U6|H#jb`_3!y<)(S+Kdor7ffF$4)#?e$Pj_w49Pa zRCQ6>GJ-1Q3E_yRDAp2)w_TK;69iS)^GQ{W8VSTK7saxY*iY~+J!j)|-s^zf?c&4j zC(yS&%jRq7Il!(Zg~EP<8t7?&dJ#1(j1)1r!n#~AyxfyKrL${jJYZ#AsJ35BZ&>FO zPxoc$zYRg{8Z46B=>z>avn#~>p*E(2_n3l)jl>H_`U zlNugxfgT0ykLN&>7*&{_dOF)x<;#WzKdx{agj-hdLGK@!UnG-Kz}9>Y9_AHjoOkpg z4Q&V5z+_O@A{t-DyA0#7%>Gk>UF_n;g1S0}AA|84d2e8B5-qj@cF2W_RQ`b$0&VA= zfvH-gUIpxL7s_cis=v3zHH}Jxiq3^gn?dpxXkpq^2ze)Zr*B2Yl>nr?1B0ARXmOs8 zywx^p#hQZH)d9Gcx5qZYukdylsPUtLUHV^mm)*|kTW_GSX@N|G;PJNECwv>gmT{}+>Ou1XOxlQsSpu>PD*$z7#Vl%zvMp=O#X z1cpk_V{-Rs+GgD&KB=LZT7aSN^O&SK{9~&(DB_n7HPb{e@KcK9?N7FoYEP+i8WnL7 zD;u%FZZQ1vJSJX5s$HgLniugNdXO+Z1Vb7O=P7cM0jL-?M^pB!j<|-UIpZyQ8Q@o3 z2Di<)mMcb=Fb#XwMGVIpQE?@JWAO91+)6D;8HXUR{Skd%Rvs0LJ^_bn_1y8*9;hVw zJ^<`eM2EgMY~OQWMdY!R=kJKF=pn2c{R-4WRzVgp$`{~hk5wM~>OD^*R>orXOOqSk zYFyeXTn5xqD_+S(`Wk(Wtu5+}iUU!OQTCGPhiL#r`!=BT0(c$7mf?Uo@Tz#S_&(}_ z^V6(Te-MX-1Nga|=Vf1-1zPEuAg*!%(l3(?1A;H*_+o6&7gW$XjK#!lMD3=RzF?>?R@jijnP` zYtb8l-TNFo6c%WM$Y(P&^dew?xzKQhW6+d6ts{%&(ON`>un5BSoF*aA9+7cqG-BaW zfYo!MDHIm`u*ju&(k%G5fF1Z8JQNn_#K>G{wCJgTEq0;d3SZs@h37{`tixUuy3gmT>+XITfW8&Vk^1&*fwT+WKTjbqxLsLCptZy^C`73C9;sl@%ki z;12XV1e2-s0+d6yp zYGed+6-tY3h&&?7Rg!hc@k&Lk7|Rxb7eJma@w2F0CHN_7j_VkkbCr8lD3O*tOUhM> zdCF2YGtAgpqT+TmHgEh?O{zU@5%AAi<&LZC+k9nCFmdhnU_DhrPx+^J0Tt&K&#~^`u_+2ODj3s(_SB@QN@4J z`!V>%0?c2r?QQM4syG&0%{h5Sene-N5j1z2*hM{%T!rwc z7E->gM8+4eo<;MKS{3Q@ZvfM6ek>NDEQ&Vj^!Q;&A2>cW7Alf{NT=VzWE4AU2sT)f zHC@r^tw#VqvGg4nLhw&@dJo*i&aV3kTmeYI6R>+}=lk-lb1 z2Rr>$oxTZkYV0?!3%Aeh0H!|vDE1;lTLvt+u&DCtv~DK(Dp#IB%S-(rA+ z<>{G2OaHe{UeC$oDKI%%2p~gPwh(<)@^r%;+U{I+p z6N~ZErx-{nHj=Eqz~|>Pv9akX8G})9#cH&12wnVt2vz<1r8%ouXdbe@cZBBGLZh44 zA%n*y<5kLmW16x5TJ#JkN4pxV-7Taj4VCG+gQ}^mCZ+xsw#iHu#iG$WY%b2IMQIo^ zo#>VSK-8vEw}B`^SH^Ht>BPOq)=O2vs}zUhsjS?*a2cZ92S}+dC3Q0miqEVT<>n%d zAv&6ZYZr5g(Zjgpz82-&c|H8kykrXG#$kAWoP$PO6Ybo{ehBX&!7#NT z$kPu^IJS(cO9$}RHxt3n(1FQ_Zv9E4`xaT1Y)I-Df*6ddp){4c`$;{pcb>cC# zaQ1v4B0gzKO>{JG6LlBNL(K1ON{5l_aa_K=s9Fr(D*X-m z9cg!+^x#2IZDIm>kUvf)0p9RJR zEc!Cv+4O#VLWPy5O`vUO`VCFzEv9$SPrt(JfMhy}pYtv~5A|*W`9tY8(jIWSlB?4b zDH7YG7+fkncn4AqKTFbxk(3YAk}iVRI5u%K)c~P+QlgTf*(cCDp!RbSVq{I6NTWfR z>JlGt?wUB27K5-pDbbeQiwm`Yz615BgV6O5LHs3q@3Mw};VCr=LN|bT;Glw1fLQ8= z5!Jim^Q!)*2AmAJjbOJL1u0jM{ zQ%)Cgx`N^7PLjR;YVHO{HmQ%$r1)CV2i2a#T^fut64(1k#l# zC&-0d$N^Z;hICR(t7yMt_yOK$TcwOFoEUjnh+MX^$FWARfB?|I6$47vRb>J=9u6~R`vVNqt!6M#JdBofPJ zRog)kq@Komvzq<3!rg%CpjaSYc2L-)@fO4Tg1NH{?9YH|Al7C;9xf@KR`Sz$ZvnF& zc2y#w1BhK*2^vts{I!IZ@IHtixDwREc5g-VmG|*5kF!_`;wo2y2GlSMPQ>f`4A=|e zp>PTOu-)6x9Fj>(xC-K}a0vovVWJR9LaO4ZTU@#nMTnoqd)u3DcGODd1F=XrfS<;D zyP8A3(SSN2HVOyu(|B(`GhK|%qAQ4f!U6m=-aFi^hxNad;zJOphXZ)G=Y8KSKFKh+ z5@|Jv8^Qs++VhS#7uV8&!yq1a0qQBbcb3^Z54dlF@Q{hpyMrtdErOr3dsmvqVIb0= zMsnc_Lj-lh;fL+sAIxGHaHs?zor)-L^f%xwEsB~5;^p!P?IuFDR zMu{S-$i*pbI+P`o6$zK9NoGmjq$P#O!*p*xYsk-dCc$#z04TZorNugX$dlS)}(5YddCDx(>+WWH3E;3hbG+ zxGG@jO5?x_E?qdu*d0J4Z#=Jl&Mo-|P|i72Y3#~o z#i`w^!0qvTzL{}<17l#|3vbN1==(pR^Xam48IcjxI2Xao1zS=SOzQudW@3IbsUk2< zTwF3^6{oic0~}+n8OlPt064$}%kWc-Zed*UziQ@0zh)PNNmBut?Z9yCvn{W2N_%fL zQ-h01>p}gF5pJhePcDlSe_qP_s<#2gWRuPUbJdX)oP#z5lMVV8;u?9+!@Afbf*iz7 zLYqR?02eT9+ql-=al;uG2TbW?INsnJb?DPQ$g+orrJK|onC`fuPrrj>tXPJH**M7e z@&m4(d&9UUf@6uzb#zoxF1`=)kKt#N6{mY(^-rRi2Hseu!(cmuOSW}^h6n2Wd=Z%YT}yx-^irY&O10l990K+;*N3 z{c0R#wjMwZvDx@0Np6x6JU;(`<4u|i@-iFCHz~2tSwx2t^Py*i`mI3^@(+fEvS%nI zuG-Dmx@uP~k7?RfdjfK?!nR~3oWxaoM<|Y~mU&!PZC(f~gUk2yA@T{PMl{F_SUYQ1 zZEYmI<{&T#C|B*(2-9F7bq1{$(>?#-4s_+JoqB}~mPX_8GsUIbuG&^XQ_+`$w$`Py ztF{nEA*1d^4BDPhi=RNNH{%VY)O)=;=U}zN5-xY>%^8^H;>%&=3$xvow^IgCk)12dv%xDTY{Nd9|Th-nv7jTsM9n!*_cW-kwuVW zHmTcB9_*o!O6{4%F_21QCJyz@@H-BuFxPO0tG*%)**INuDGtNWg|bZO9!%e60~XWq zBmN*GeMif5K6hk>r9N0qqphj7uk-}g`8VM09v{rk)T0K6PsvIKLFl! zK_W@LG?sqXFies(1H?rxfF<+(v53J%MWm=i4F6n|CiRnT;CL~v!NisbU&`sp9v{TK z5!a^DtC*(8|A>)%%*~oGV~#H%F>d?`{7MIS|2S^jU&p%7I}St_O(Idw`Ag`_uwe+F5^Brgw?3*Ipbyy;Z%Ni zCT`XkL>p4Kwmprwg*2cN)_=Hs<~>L=UQ_9x6HP|qCk`RF{%_P#BrrI&fmF@Ep1#7( zZWoq@5t_K2j)8E&CB}pi578YaRJL;tj>oJLmW$eL#YNKZozN0kw>-cWbn%jtM&UCI zJ2k2X5RF}wWT{aFsKITFh7sYvFdB>icxRTVX0bWgkax@KyIgHB9`2)ZMMOOA{@Qy5Q98F%VmHY<8-QfV5WWf5Nm`3c+`(uM;*Sx^u=~) z3*y`10N%32eMQ@FWF>gH;}>D?nSJW(mN^-SPh1o? z#-K=4NBZK{ndvaaOC#O_*xsa2n1q+!abKAOKh&s;K>XpNnA1l6Yz})%*OKoQ_~~$k z+gQuGW}W~+ax92QMHeN?@sD1|$EC8iyoj|(6F}OyFdjzqIzBGFl@JR=e^7@x2qIs(US_~15VwZ|_?S;zacfX^ZOBs~US>d8 zt5Ju6;;LCY3+XQO42aa#?R-=<7oiQOky!(4UOR1_7l9~}0yQ5ip}5vo9#dPV4iL>4 zl_W<&b+bOk!bC=vUO)^>A!{w3uE!0q_P?oR%>-g`3R!}B*J>BivbF;8eF|B#AS7Rs(%`w)qodL4d6ty5C(n`5`@X|-drXVs z$>mAW$X*)T7(5zZ0tr!nE|wXVoG0HMk=m7IM_};d1&O>$-G_!DZJd)Hi~`ktWqO7~ zupcb=c}B!ag;t z7*^DE#{GT*5~5fmEZFd#?@;Vn^IosCOwT>vfN&6(uQw|d9E2*DA7yKnX!tp&M*H%k zXnroNpNn3pCahjKRF5{jj(OwNFZkvwGI`k+#dOXrZrB1$0ACaH<34T@_UEC^#OrbM zg~+(qPJ+6Hn8kb{Z(iCn$}~b-iSRWaqbV-mYO#|h>>_#_iGv)1T5)Y=YiYl3InHb4P{ia=@5uNGvK5K z@Y*uem3CpuZiaNag`fK_pcoy%gc9mS-R7WKAl;;NP%<+vokwwMQWc1PG^QL=3xQJ3 zp$3@+)$?Ei^ju6kUt~xlkXt8%6r?2qWHw(wvsY#B9L6cc?B@0Cw#s9|I7Qps=KXJMZI^@*Mca@$uz{`Z&M>0* zB=VXy(&HaSLq(H*3CmN61e>X9*@s zIg8P~&ahA}Z;vWu@Lt@ah9I`YrP@jGH#B0ypAkkWMmy0ULzTQk6Ag_W3f$Oa*kV-X zWteV+_jY?5wiuB0E{r$YN^UWV=cazd8;c53*&hb(!t=2kF-U}RM0|j4DR0{?dJJ4T zSW>IXHj^@|UJXT-KzPB3dHW5`Pyk^5XkIvji~z-GESN(TB2s;6W19ol!NqDAznUK^ z?Ww;>H4BRp0h#Q=xKY}J%8+Bgw)D(B%DOHC=1Ui+#mz;Xgt~dsW9h4kbO?~&lEOrs znih+ZFbwl_&W4Y2iVdCtoS`9#B!h=^3iZRC0d=+->(bDN9{!|@%Aqj8uQG#-14=k+ zW9J|YAA6p{b}EOq01x=j9P(1%LMX#nlg0rv*%6FsQ3&HrT7<+e9fF!UuS>Jy5nbaZ znzSF7<1UW>Kb%e7ZqZdx{&uPN6}1m%KHsE>*RcJ;rAnn&E6RTnI%)02*{UaCpn`yu zabQ8oLhW5bOU+%d7_SznF%WMs%ASPSe-T=4HhrRuNPR&Z;)uaCCV;hOks-=x^bv^j zTnWlO5!z&?#qOM|fi{A;)s>(D-Yb$P{_KHRo81> zz?vt8qH=jd9*VbaX3?nLKn! zd9|kw`Fxqt_NDDL1|oq`YE03p^PW1C-dDe%F5n;_-cNzz-Eydlb+@{1=nH^Y!6;RS zGMyA5LG`enRVJ0=cR(C*WoZ=emP384k^QyyH-LDMLYANgShad}1AWUYhu|G$ zj#;2BV7kgZf`q>7t%Eqn$o!i?`_`cc`RxZN5y6@4{|GBi5poWI-yD!lKl0XGE#zO& zQo(R46I)0+A4+m6Z(dzJu>iy~NJkvWBwjjH6EskhpU7(sLL&~G5l-OBN&j-AJ;*fu%Z;~4 z(B$MszH50_?m9k{;O&_EocK)N`s;DF?n% zoAvFnAn3OjRv;?Qh{nub{)KN?J^R%LDFk~eR`GCU`1wA2Vie10S+WI6kZO%8furjY zh&##I*7+xiuGf%u&q)uy2CA!T1Vp9BrI@s?FA|$7>i~Kg6w#2CP!LsCqf)Ma(bNK8 z(c_lzBz*RaZ*G$5eFK`Ys^UpFdXX;POIumB!X~{0N->A3 z%~ed!EC+n%Pmjqs4hECz1M|9r!}^&|H3w3gc^{F%HDgjwPzNwVmA)7aJ&!EXn&ofe z7tH!sSW;pbHUE{DUluVz3GfH*>CG+$3NYJ`WcYIBl{n9CBV9 zvOo^mS{$-XIONiE$i?H3YlOoWU|$)JxgU$~n)|3>Eqh8v?m%a5yYYvhZeWPm8PC^; z;c0tdsJe@c&;2#-hN-)t_wlc|8_0!_$u=;&NGnv%3z_B7aG)!X2r}6Q`Z9-%uz`Lu z!tyItfdTxAl}y2bL5wX#(=I_^k1GdoHUgDFdFUbc{SmYna@XVXO@|zk3Jr2z7`_DY z9({+q9~^|8K8DUA?V6JwoWln9*G7Vxt^*%zLyKvHd-Ao$AwXQdg`5ZIJY5GS*V{r9UWEk2yi({W&Wr?q4(WsVx4)n~fs2!5e2thR}a{>=XtXnh>IJ=5}Z9r$blln@~w z05Ht~L5R@THwRsWtORY7L$`(Sw`~I7Og^H890A~*3+jU0At@3MmI8{U zw<>N>gIcjV$6H?0lCl91#~@{Q4T@$-r*Gkf6p>UJfVwFp)lCIS7hgjU5bJgXpjR?b zEY(;KN!Jf;z*syQ#HkEWSxN1>Ej1yVX>h}lm+H7N8I4M&#T4l0cH`%15TD^SG4-4_ z*I^wW#VImCv&S}Y+2rP4VL6<&fve_Iw0Lpc2CkW@FhHvz|GG?BY7oC+Rzg1!M{MAx z2owix;16>Xgo|f6@TbX5R80W4P3}ddRP()O?m@R;qKS{|%Xd~< zS7}AaXb~kMb%H|){>p{(7e|7|!~(Mzw_o5=+`+tvVrUlG@fPjG?TMt+;8lpxvW~&3 z8eGewKLLE?g8$^~G_{#UQP^E(#-%g*JB-@VqI{r~bE&&w43$S-8pGxM2;YAO`3(o6 zr-=wTA`@(R4sTCAf=KEEM52QViV{Tx6j))Mx~fsLf%w!#i830s!`gO3qqYNaz(uiA z*wpb^_`p$X4i47RMNt285o|rNj}3cjeR=^cFcM=@3@%-E5v1pCk0;+5GPqJG9*7c* zG9KVgdoBV2&y{mzJcOmG0f^%we_hjBo2G=s3 z0rA&x0DDgYLp=L&qD}x$K(snIrBFxV1LHi!K1YMd0>X<-ls>C^oklG1+{SQ2WdmxW@2D*!gY6V0GM-+-KfS0|W@6cj~gUJ7^ z+$lPrWDgYaX2QlpBrE`t|M`{E5(QAf+x0UoVF!qNT?vKhD(ld|y9kR3ItRivhuf|k zLA3PdxeCNHP*ZoZfMJ$Jyip>fs4>G zDxswZKJ>Q7dWt%N+SNgToln9C7I}w7q8W_@VVp};C*gzBe_gHzghilz>Cl5b%&3y6 zlkkCK-X0iPW%M}+*e}VTS{*)T6S(NT|0C4-8xZeXPLV{S9ytYe%iHQZz_I~SBpJ*d zKGh-j;LZ`~O_F(SK$|9oW8uNxzu?I`XzK#%0l>N5uc zem?#l*dOsO21%TMe;Z35Tw#4c2`Nr5VdW8gNS8ikDHVaK?%*J$F02vsnN5FTYD-Ys zhg13Nd@z#YFjAW|7?jBlRn@C&-s1EkMxkIIvlABGCM^SS>;C{ZTLN$%Ya%9Mla2v+ zIT@I(5B+Z5L8~m|yNCKU=?O5=?>MEDb|63E$iV6SuK=#<+lx`(q?Z9KkrWJheBM4# z*EcmITdgk0%~L@59e`jlI)|MVj)Q|d#D#Equ}kE40D^Vs&wKVe05bsj*nt7@H}ALF z_`X25XAMo-1nRdALJdI0XxIk8I{PBARaCI^fZRw1D^5>fg}BUiFbmc6uNB6={Du>A@zfpW~!_20|3_Q%qVx%fFiydAlG8+DX|E zQE>sXB1ZXqrv#vhqaZ|xeXoOP`1wBj*XZvk%o#4s+iO)}99{b(br>$+h<}pkIuU7e zob=#mP+eVDfUwCSYF%F>wi=w2hd^ZBWp+|7#2VCfQZDZf%~(}*4vN!G z$~Ryg-2aD@l3Bu>l zC||qOd2A@xNqGR2lMYpz%W+cfHcev@7)-hg%p(WqIw=pVA%kniqzpaLfN|;4J5I{M zmuS;fP)0e_p!6!oNx2&1xHLqX z56E&C#(o9NP1;FW1&d^pc7lA=g)m<-C*>?WE->jDF!x-X7Nwn(Bkr@PDD;mUxRlC4 z5yd~qQadTfpI}^ZV5&b4$4*Apg+tDZLl(#(TZ==s35Q&I4!L+7a*c4f5B8N2k_QuU zQgYKZtlem+7J-_?44# z0_gm)6N>5s{|_!*hOlRffzR?|=O;q=fMRI}1R=^v`41MpBIGsDS~>KjPReUo+l!F? z0E~1&LF5ie%1QYlW^a)+7l369lHvw6NI5AlVsRjnb^!203Q5XIx#ce{=`sL!Qbc;IqJehkmJ29i7hc#3f%V*8>2L`GsN;z|t|j~p;^S}$+Iu+;08ui-K+ONR z97AdEW#>m4P!hxn;Q;Nu%z(|9DA^3e*5Lr{y_|ymqyPqjm>3Sw-peU?e89C#vq4-K z4j8Sxmxp3Z1=tMYP8Z;KFB?JvodDqy6Q$1vrPn#$%Tbsx=pRu1gOVWZmZiOyP2tR? z+A!|XCc ziuPU}U&T_gf|4hks=b#vu}8$`AV8__P*uIU=5@T6*DkQAjsOn%A7JghG_jM%`40dW zCj(1$INr40GGt1{-BO@5NZH&yq80d*|3iR z`8*lS@m_8hkKqoGe@Fq*-b=iph0HF2d@BV+doPP%I>GsGtURJ|>9R|~ij($UCcqI5 z|1ZcTQb4r#@_@9bx*)eo3JLRGCf(143S)6jp%*d!lfONT5^9HyF?m~_HI4l5|IiEx z8R6`um;wP$u7~KG1=4t85C%q!CL_LT^P2O>7@IzRCuJUq4~$M3i^NM3Cu(sWwD{lj zT~9NA^F_G7tnc&BV*yw6U4?NAad&}ot%sCxO!=MCjlk?cem?q@zaNvY+N{<2?wSVV zZ^d`lZCXLTyJ6Gb;k%nQtqkA&VbfmYyFYDO#8lkfvT4P+Ah-2hfeGVr*Tu|-a$~Dt z72yA<8sAmU9#}7oh_gyl!|6cacpUA6(#LT5$^%S6Rvu$cc^2n2FN}jFuY-C&86pdH zd#Ae*pVoW{&rX?#kkWRb5uee_4ZS3#FtukXIm}tpAf@oTaR1@b`S2lLOnm%eVtj7% z=_Jk56o^(13O&v9Aw;}mHvfQM;Oh&@5SJQ#a|+ha5R@t*VSq$(zmbs8U1B{=M7v4! zLjt|GM035FkkD3Q=hsBeMsh#7NsZ(V5_^U}B=?aUAClWiY(&!nA0xT1+@wWvdx;sw zo?A%nDmT$c?j*5}<9uBWKktUJ2WOz@SzC@oTZ@WVCAC40GqV~}Yvc0uV$)+|uix%{ z6KQWb>A?Y@x^MUPbqKa!&z}QH+2ha#DYn3uh^KsymJzb!Y{q8K-hrz%Ys<`|pjF4! z$+S8J>;+uDrAf8AgS3C0^x(=QTKOSLF*sVWCfT#h7OiT5oKh=Bh*p_dE34IYU}H9q z0M^S+l$dRD(u=pYG28j0I^t!C*}-26ihjEWJ{X9IVSR*$KNR!DL1z01JtSsrQ9_h= z$1&^pLpMs;m#(n&{P|ubY(pzs7^fM2{;pT0U$8TZG#6RfN8=I38ay5}Ked=FyY42R z;C{K>%Zr`nN^2&vuD}|btK{FG$!^^ILSc9}ZmzNX|L~Uclh44s&Y}wM;d9iud_g1= zcD+K_h%-CQklNm%1aCn!y2&1%i?&${vBKmO8V1CBjLIndMdT26mvdAD)+qtj$2|Ng<2fL*@hPC=O_- z@&j=*g)H8qm`|;3cyKOujzANM#ucuYv`y8VIKMPqF_}_yJ8wDQ)R)oQd$Ya7P4~;s zx#@oN76_{8&g`?mZm+Ww5fxFj5i!zSnV_V+8zx0Q<7AD+^D>G#vX`ZB>x}t{IWp01 zG@6)W<*=vt5G48%KS7b@NUeAp3nzI@Xr$S{ndP_kUUcLqc$NGbK9L_c#*x416IcGf z$mI`~pB{Aekus6bm@xU)K0L~Vmfc(_Y$99B65DXd86;}KQp9+U8N;RY$OueCn^Qow zr0G|%)b2oYa3h~hV>aPc0$S3Dqi{-fpe;6lOD`r+c4$Qj*w6wX-0XT&?pJZb8EHDQ zU88SA@W&5Tz1@u9*+zyeju?JEg74=?T-E{)8|hTtv9^)UyyaHH*%$BQi`XDhY5e?G zC18e&-OffjHPw}}-8J>u6WDe&XDP#33L988kR+ytloIH}l)7@&ad0KjKs=I5{R*3g zj({z?F{WB>mafJ4PQDYT%+{KwV?nA}JdhzQoQKQ8cj~KjQdO;quou%TrEC@^xh%;l zr{aB>UNt?d-(e^h^Ti-ArW~tRZbm8(qA?r%J0Xw!EN?O)^!7BPH7qWp9$TDyqE4>kWy@-?2$K70kdx#Gb}2FkcI!AY z3SH!o4dSu~#QoUDwrwEGAELr6?m@B<8TQ*LUHR%Al0T4I#Q z1boiIEv^#-cN+NdqH>dr$o0XULVV4?0k}k*BaH+=gz}vTbrcC3#?sQrugFOARyyI? z$U=_%0|vYz%N0T_JXmnWHJV#SY=(TmLBe%cL;C283JE_lKMR zhLrg;)Xm>vRAXFPnz~c+7xBlRC;o?J0DPvZIc8#t;{8wYt!d6u?w#DEs5qFVDM~B* zIvuRrlKR0%A5oh+C|VJzBl)go3#3$+rl@8ziMFPUSR1GA!kN-cAY@49yXW*nyM%jA zfyGb-IQ3i}w<{$zj|@ksqmdXwqAHq_Yo;RZbaj(o)6jDB>>FSK}wMrWgPi>h@Kak^3VQU5Dotg$nT!gX#+l`W<^Xg8U2+ zE#oFuix_}AC!xuT1OqUh5@Eoc0Gd>MvL#DPnu^-MfVnvwAcc?|T=>Dv(#IQN>tqHz zGKpPa9v?VeIxHc{pv-HLut9k$wp_@y_%0cA zWFQ|0o@8^28qzVha3qXdnpRrcg-4ATvV?nYIQRcU!%Ryd3^8cTTn>5+?*Dr>%S116 z8E37EHbo;UH4VjFIXi6bc}_8dygf%*-`$A(CaLkE3p4&dj45|Nz^ZF&s(-(Lj#HS& zUUjK8mW&0NXarA(v-ZK=ET%Y^LMvJDxHeSFCe|w9pUZfkwZR#15WXyoPHMDCh4N&n z?!oUJN%sGLti1=66h#*{+;@7H9Y%0x$qLBIqJY9mM)HEPk|jyb$yFq+AgCZ1Q49om zbzKAz17JW97fIrRfB_LPBL-9i6%`C1D(L?_x2k$(XL;Z6JLmi7obIl=_o-V|_g38s z-P6504B*HMu_seIX`umb#QxgwSAW4%VizV=vb1fW^*n(cDj87)bB=n4{I=kX99rM2 z_oIL8A@LYxE>&^uxgvr{c{zJCZm)Lu1Y@6!1li0QM@cFs%k>-W$Do1-6Mp>3^BS~| zyo8dLKY7lpm>HKBX`)xWM;h0%DRnsSE1Oc6dmdHp$w0D{=70YOGh*J;PiaN2KE0CC zMyJ=Dh@@l%Q|6Smk*xqcc|NG^ID0-{dh|i~N;!@)ox+h)0aWf-DZPi3hU{~27<#k{ zxL|f?qCRpF7)=9aaC?025^($PhK|=mqI3sh5K+}BI{FT1xR0Ws!PUONog0Ft0B~yz zw9kO}1+0{j4Y8Y~lJWs~mLM%;^m%}yK1)X$sicIesj>MB@ ze1|_zGt(b{`h`d>8Tti0_8l)lUgUAG{p2fvY1p*WL)hZF=qx;y+`K3Hwn)<7ov@~D zVIz&VfYZi&{3xjqx@(waIAsPVnQst!Wvje7<29JA%D(e=@^X+bk11Q_+dg_ZG*vI( z<>}@7mvE^dqprEZtMbv$?Ql~FDPB(#J18N-(Z4d3wa~oN&hiGu!$kGj~ zJ)v$`;^-qIp?5>080LOkXm6-L!nI^S8c^u{ko*kE$8n@QV>hgn@ey7M9)1`N5QpJJ zSJRQ%{iv@)FJqk9j%1PvL}Q{hY5My51XAcwXeLVbE&*49*(V;L`%yoH4nK~Y)l4%H z%&7#J64?EyUqUkgV7+BNn2Q5|+ep&wrW2v{hpd>Ff!GqD+JxpPwT`R@$8JiM@XLK^bF2+mV?wpy23lVqSqeq`A->J_ zN+1R%2*d}3u^J1V?RP=@S0zjV;?`oabc3sm|HE!8YY`C3i^%F>7pi z2JNQUR0l)r z(;9(JL}`7ZPyWgFa}vb}+E0U4HpgoKn?k4-+(3i&({I1cb}kT$5(EbA=V*!;B@_U$ zwU{j1e$p^2(kko+;&3rpw*8Dc5C6DDaYfK5!Z@r+be6})5o;`*K)R05O_!W$gyw`S*^JO!K?4}XWYoCXeoX; z6^>Q(&Q->(O%T;NTE=Z%8RQmd#_UbVU(KFz_f`ZWJ&;#LDYX&2r;iUXyNR+GM6*v> zUb;g^87m9gA)gH-b8%u;Lzl>wRD8YoIX%12>mZ z@a5Y9q3UW7)|b06AesZ(DL^SU<4D2#Jd+vIgZmQqJGr$!7%hO)=m!-P+=*agvSv8 z>@ajTR@%QZO;a#i6JSaZ3`5>?X4NG9z#J6--1uRKp?9#EuVQWi;?4jS8-`i{po^Zz zzifj>iByMW`0sK!af@2M_*ewiRHy z>Nw&B2E)+bSlnpoTLRI6s3NlLFf{iUD{BN0Ta!VMW@KEQ3@WDeGB`__kCT)S3Y&x`kQ| z+ES;F#QPZKm9{{1AnHv`AGD=<+r|5afDvF`6A!R$sXVsj_At%uV9p`HlpttJH{b>b z`;a^d=IQ|88i8#~=~yMJn74q~8=zusDHRKJ6>|j4KLUUgW82ac><(#t(xBa{I81$_ zAF|ewT_{G-mVWru=GYRj4uopK4K!#=)v+_H*^U5We1gEBEuHt7m321|3yaCJZD|w! zl&i8<0kN@|EZdg6C-HAOD)a*&_6I1_me??2ZOL!cQHSadPr;oPTTJi$4OBB!f6gHN zQA*qI7<`h!c0VH+4At$P#6$2nQhoPdpMkkP-OouWf^L#&LY zG}Lh(4vS(L6dDZGtFXhsw9*u))AOiJ_RPb2$c>fHrRSoJcA zRc{$o(W0DTG4LPq-oR8+mw#z53{K+K4t zSO$d#>b+nD{zSw~9|CGIky+huM3%)hsvhzZXoUeidIPwz# zpz+*v3OB+Dsscc*7-*IOnZ}cWy=|4$7J!}vX(6M%0V>*fdhUcmt_EUS48@cR4I0mS z{C$pTWj;`OL~6-QIOi=G-xO1}wQl$?NBZ%ri(a{e;3)DMxqj+x; zbTa_6W1ue$$f(yVz+8r)r2woUNDCQV3tCb2UW6ypWhW3H$52eE&_KN<@%K!om198t zL8O+g~XwaeciQH0te-VBq=&z(m7wqznZ$ zPQAIH-4f8Fqrr`-cPeUUa2p=2vhux#b$U?!;dl^4aE38qv; z@iK6v+(gmQ|9}>#_pO8C%^|2I03BkWr3PfwdoP}ZRY}7E$R$V%8J!GJQT4v~2NW_J zh`bnzDHR&1*M||9R@MNuo=7d3Q7^|mFT%I1ME2+5#5-W4cb3HJCiAOpNb@7`(Qp33 zN&nM7It3Hqa2sW%tOd2~-vMi`4^|gtRWHg)l{+!!hno7j%h&@zCns`i7%G!$JjR~i$GMAOSNQpfPNv`ra);LMY*NmSGNb*^z zH!dZ3i6(t|E@Mew@{*L)5D6kw-53dV&BQk$!wUh+3IC#LQnq421hF3x#mQ~usc&Ek z-}DItuc>=!2LUR1O?&Yg*IxzF+0P^RNs~0Wd7bCgyy`vQYf?sNTkM6^Or46+s-l=X z#NnDx4n(w)jYey>e+1EUY_w9%SARwHTpLZVd1N}Gm2I?E%^sK*H>qNy^=hV!LA0uk zURtvz^wZ=#8_lZu#2`e|ZL~wp6TJ~V-$uLFoC`}fscxhFYCeM1Y?B(&?sb-VSk3ay z#cOh*bkJx{&7b>&Tg%pHV$H5MB3j2rC)aGY1JO*`g{B?Km{xNsT1Arvl7{NzUr|!? zqS}zvQ0i*@HmUhBMujGgq#I=W8MjN#j6$gEQW>K0yQSu{>q1_Ww(=3g`5E)1=IIdd zon#kO>u2Oi%_JZ3&NjYOYM#Y-7aLz8HP3}Dnsl}C)l#zz`Q2o=GuYVg1s$E$!-8fgUO~^_X|&pI3<2)Z_35t7eYCDCS~GnK!i{ zk1)JLJ@dY}Sk${VoV*v$t6cg4+fl1ux*|ASC}wQ9S?~RQuzC8j=Utc7tZyo=;|Ah( zLbLv4k89ox!NKHunQK2q_$u3^GN(X=&4wJ)?2^3kTr;%AlS)Y zGI%YS5hl(Fa}gF{f>bGqHDI$_&a%90z!o7 zR5?)_CF&4TTy5gCSd4;sC04`D2dF*eihxN;?Z8d@7)hs@q@#;*53#C;P3dMht~XJR z!Pd=wGITrvb_%Hbv<1oYMDd1flnpA%C{%NW7W3Xqk?LB5`;<6UO#(PoHr9Z+F{Z%3 z62=pRoWvz!Bt3*K)qKB^RAYmaq@nn1DH;#`QpLwjVXq)KUd7$_BD22@bEsn?k%y$s z&ohO%EyzKIJJqeh0M_g_qq?Pp1SX(n!iALUkIHGpgcJWi`vX(Fp2JSWs4ncx5~UU2O!7 z3lKJWay_VUok>0?k$J-iq}*VPK`$QFlPcMopZ#fwjEJDpe`v>ehcGQE%K_fBJd|&# zHsBuu`Igt9GkC8kuLQhGtmsHrwG{GxL}gYdFJ9(R%KVe6kk&=hrOLj1@Ot~o933Q# zsf{#PVJt3@i8xJ~JkGnc#hn#4!`Jkkg`K6@EDs%B9XO;GcbiyJ=HM*E?lG}&=70)_ z%`vf3nM;}@cCU#=GoQuGrNwjHS@1k99x$;gnX(VDxh9sL`F1AK zEoi5?*UEgPB6tt7orf~&q1Bzf2KB09Y>|n=s*_~GX?=O-a z3fm?Ht?gCeLR3x$Oom_*79dr!3E3%pOhYQaV(S@INUB`+8Dv*9m2E|4tg;p{gUR;_ zwJ1Z2BzI2!Q7pxpeWZW1mRrw&7$V~y1Y)b!U|G>jRAH&oo9%D5=}{Yrpa($N*TK6q zYiH=61){Y>YRVzPXAnI^-u)4(Zm)pzV7IsmS_$K^JJS3%1+)nO+9hq_ zy3+&oHihU%1oNlgDnpku({%MoF-Aq%HwTQ*c_vimJD$2zuacBq4!*A!1-uvl7{&7f ze{?~;5A&@2_X0l41p(&|f`GI2qJZB5fC{K2m!ZovYo-?k@F`T&MB{75)kL#5gip)p z^Qi`54gUn02ZT>6>O-qBrZfEdPk=Zq{HM6w6lB2U29X=SBneBT@Nk@S?AcHrNyda? z>k`a0F5qM?xi-d~mKSoHHTezLt7T1guH*`15vjRNS(w%AH4SH*eg}; zeqwv5+*)%H9H?>|v_WvNO4zyp!66zv0MF5Ks0M2io1=2;6ML;nC?s~Q2EQcsIt{)T zMsS)Y+sok1O0C%r!P!c^kiol29TSRqm<4jc4_7m0k4aRWo4eb9kH$^)**#u|An6Fs8N|YGQpe$5G}86YH0G z17(gfvHqE@D07U74ai(WnK>plFtY?@PB5`SnZHuzL=zhfkKPMAhOK6>PVzi7Y^J;% znY<}d_8ahKZ3J0z!i`|I*4XfMxYHe^xsFnUG~-Mx z>?M~3Dryqn`-U+-PD*^EOafH}wXtRWGc7vJQn7BAgS>$9XDC zvkC#-HZglAsZtHyH>-s4syoT#2`S#jWm+XE*$0Iv9pZ(_<@*4VDyPumvMQRke|rY@j6%+Aa%F{vK(qsry~1AL`PY8JrI9}qyf3Cqp6S9Oe@t5~P-dRA7R zErKwa43Tqu05;Rr$=hcDq{{ZnD8+8mIu1GnBtO+0dYP|!N#2RPnV%W4NCRNgDFAwF zli}0*v6(k?_ASkEj<1jC^O^p*NAy!=Gv>5e7nyO8Px_liHAIHBLZbI{c;u7+vD&)2 zgwaE@KGxBZ{|P7#xSjfXUMFV!w?GVl;{J<;f7WUpncpqS8yjs`aX=p4c?fbQ-zeO! zlG!iuGSB)5v2(aY$KHXLJP@dM=Q8k@ zlE;VoDERB2oam`%3oq_cRY06F0nXHkKC2}n+uf3?U7j{`i{o=L~# z7IbsY38yPEwI(U$a2`(=HVaa3M$+#ufE}p%oG>3M&JFW9@*I2S9~5)LyY&1S&N*Q| zSezR+bUr?u8=j%~nROZNgB|AF@IXBq3d1?!>%q+lPpL<4xl4F96h2{@8*YRdZEpBZ zJ@0J6u%Yvu6E>8&2v<3Yf3OZKdG_je;F>C&k58(%B*d?}^B26usZFz8I>`G~|LB2e zmWfvKt1ibXtYljgt>;($6eE4f%T2U{e~IMbX{wTGS2w}`^iV^&MA9*FD_Le;AI}ly z!bT;_?)bqHDoU@iAe1{=(5Pd5(nM z1|3HVYa>`zy*mels^hlUN1t1P7hMNl+$reC(bKRVZqoeI0J&8wH^!#vgEWI*mxKhQ`;mIZWs!xG)GE*g7Im`chCZv#JK2=BKf;h|PM zFTy!D{3V&M()GfbFj&_^eNpbN z-{KtVdL8CBe%F2H;eLA8YU8lp=vt!?Htl-rAymoh5^e%UcK?w~d|a4#DrQU4b$LT3 z_Q3VMDotzQ-eUITeE?NGioY^s&tN~oa=`B`N7oVT`TiLc@B(iF{U~pW*+?mRdleAdP_!Rt6yC^!9@&?1A<$mNtfM z;Jq2opD+UauP(YAlUVxNufh91p5K^F?dwIbiWVY-OiJP~CG}>BzRNZH+r#*;nlDwz zF~(r!(eS^(8X|i&TT+BozmTh+aQ3Ake=VRjKgkBSwflQ+EnORBW9K3V%n6h=pZdUm zS=u96cJq+j3gQC+!|ME2kv~s>-!e294niIe_}U@N{KdOXM)zjcokD)v`*@sGuD=pV zI)_Xomys@^D$2<@hDg^C7hSi@tP2t87GmXZm%kPua;28{cKLKNBHcp|v!cldCLywF z66%?J2qn&bVK#$zp$}#s=Xbi3E;tLp7Zc0HNLqd$xSJm`+!;*#=X6lE7)o-9o`|eiMP!w! z2o@F^&kb`2E=hBTgR;|5l3ykA*#$&~;M%g^NcliZdlbkz zO?QIQBSeGJJKaf#=4JN`3GAH|uEZXDr`*A|+$*HLUn-JT=i8?MyDCHzV@2fGd9NYj z{X<+^;+qqGovX8uWPpvQ`^mL28OeT%Qz!jsZuZj~P@d#5*``G|x3#}oZl_E{p! zQM$D_QurvOL|G8WEhVx8oV_tFmFBpmMZN*&XpBomIc}Vs~!%w>GXJ?E%ffF&CwzkM8;2ex`+1MTTVv!Tzgy8vYrI*D?&J-yJPI`>H!EjsBjn@-t z01j_8o3ysW*4HlpWH*vpgYaECBoO}9cys`ZenE?w*F%)hax=KIV+f`KVhGkt z*_X=K`9LfNcVz;izFbxZ1!*qt!auPc$ZJ5nMbr-Fi~s4UD{duoez6|zAehGjKvZj6 zUuq>Gqt>$jJBx~Zj8_rhFk&347mL$Ip2kE*y=6ThS{6e^I6`E}pBRP})dz?X#Zc<~ z+e&rJbrm%oh`WoS`m#H=laISu)G{De6+<1Y1=MBIw>ECx!M5@S5FZpnwZ93d_R<5& z)Uo1cAdUwpsOrHN0LYfTm<#E2GZpj33OE8?F3bd=lMK4f)gR2Z0U)Y($a#XSzMO_ISW!SRiHhl-JJ^kNr>UuZ<6y5%49LhvEST>B{>^-;E zD<7wcr+ZH4gIOyc&>f}A?k5eVLZ{SxJ1{%O11diN3H?Pd5~`U;f_ZH`;PuA<7%1m- zwtzdpyf+@O2hTNR50d`KNhLf5=5z6YVWj{VEE6$DP{2+wcgF*E)JGQBAHztafWu(^ z91r;CPXLC>zKs?T{uGM<9DyFzp(AGxlQ-|SfZAZziw9I^HHXW#8WzwA%pUQ8g;*hE zkC64432GU}f|(l+Sc@&(?2&Q>#$yHC2j+wEfIb{yN6Cd3SUo%s=1cK_hUEYlElXS$ z?|}JXJRsB!S&Wfqm)R_if_Wky&=#_@bEG6D_F9JMel!dm)(hxB1CO!@sIjtXsGXBF z0isoaLeu6qZL=rH3=Cx|rZ1R7;sMWLftZ~u_d#h2m#BQR@%)mN#t-=bKQQD#o z1Myo7MQ7+L`mFSAU@KbsbGShqwxaQcDH2_M&veT_#mpe;`K3 zWW}Ril|w_UteHUE88m9W&qYK1`R3`wRpb+^mJP8*=j}i0(MjkuT9)S zC&3S8OX!#77J3U{a|ks(%W6|mNuiH^x2Pw9SRF&z$}6fw=(-*j^%fBOW2m5*sQmaW zlrSxH6FR`;4`80-fSn4U@GrX9IyaPu6@rvGfJeV^#M_RWA`Vt1)bluC%>cPF0j4*{ z;<4w2_C5&gXy9&$VO7}*t1q+RfwHTGKJQ>_F%Pgu2{jtAs7V8WIzJS~v{k1m>wwr+ z4E0MnpfWRGD2jH1-_eXMk}} zz%{7^M;69sxs4r)6B6UgVtJ~oE)&aExh_{JSrJ^0R%M;?SRvzxAmnSa4ln4 zZL#=FuHu@69>a{q;CdIun5B)`Jh3)TMU&JGm~^C2ITI zcxN#31&U-A$?d0bV9`}@`x_{y&7G)gG`oz?1!Jkrhjhs*`VNikb9@#?-=UFxu1^!S z+K`J1Rra~itR+mEUDcQ5Z;%v6$^y1*yaPcQ=ixo})j+*C;6(Glcj>C({rBK>jB#%w zcQ)QAPq8(8Bp(9iwK2eW0_vNk(uMxQk$A@qGrR+cc`?+JL`4pxgyvNU*|q$4*W*=2 zAjk`VZHhtdfX!DSWM}%#Pg&H5Kzwy(R3pD9w)8aHzkvurX|~ojvu1voWwu;Zz|4pT z@I4~gt^HYdc-|hCrWKf%6YvbH;Wg0Lp=D?JS6vBLM8JR;6W=3%*NbK!2pz_-mSCvE zA&!~GP~U~vijASZ51DNMCe1z)l2wpbK$(*@!&;(@A4Bpwi0=oCsI!E!e+j`7-+}pi z3=nUL-$HHCTW3+?*(ln%IE?)0U9^PN%kj`pSa;5Y2x$aFRtyzygug>aCRx+~AjX^- zC4Mb5L(Op(5VHf6%dCXoGt&Yd2XjR{K#g#gUuq~G^k8YWf%zr@_r)8bw0}(%^ce!a zj4{17yf!iBi*NK?WN!M4w33+u2(ebkiT9ndhdCxw1T7NLw%el4N=>`{1uBLoh`k;1nfaKBF(qeC(Y#2Eo2 zN=c48CM0vgSrp@{d$~tU;;TdQOpK+YAi4>1Zu9C=wyeiOH8BgS^AMf8-`%pz~&rR1p zyYYhNuJd=|4Paf5;VxLX>wdg#tYp`Je#N_7yKVsHtgfA&#Jg>~4nW${-t;zOa6=(& zwcj5(z&T;r@ZuH}hjryXZ`xWi(8Dqx`BA*ImrN|`CGRK~^3rNtaRMs428iShN5IbD zV}8?1t%PStd)fbtB0J;0S=t7cpCY#&L~Nt+JC!o~;lsIUn~ccx+QM`qn*iO0BZYte z!x!)6EG54aklek(2>;-n^`DB6@f|-j?^j)a4AQ^<3S@evOk&lYQ*V%(tbAa^@w+aDbkLbcp>7S zmq+?zoQn7vZyHN?qc13d>fU~fjYZ6CwKF%I(W_=bubSgg6 z!;GZ{plxFCU}X_4mS#-%pKKQWfFB=A^8?CJ1m1=g&3)`I>#}A8`T*g_v^piE;fpBo z^fyX}j7wV%-l}+h8=CCSd6h%nf|)4d>)^c;&u>im_g}fz7UwW{C&^cJ=?Yh?4c#d6 zp|9|-XRU17Pw@IU5|L(ATtfat|44hZ%x_k37NA!UZVH|*YsfF`46~`xWH^}PV)9PV zAl2mkSAg0&1wG!E+rga^AiQ+R1UYTnBdeW=C&4TT08ut3^YmQ0{EolHroC2gkAv<3 z?4tk*SuNTAwwFR5G{rdv<{$BZSK*7&c2r#BB&1>cr4kO?u+k;+JODeVqIVhz4Zv&` z15}gy*kfM*8-FMFBxXLyqUnYV%H6GB2m3?#X7AJl_n2Q5IRP~iE zLtX~ztw(}Vz6```#Zaw20&3ScXd0%dp9AsznNe?#4Ako%^}KR8ti_q5HdSbEJ$={i zu4s!!U?yPAi$Wdho!4J?sNO(~E{cktqTSQwrwu6Ko}CyejKGrhVt zv92h}m2d|A=MIyvU|{-~x0`4n@BF17xgJ=c66CFbfl zH@ukBP6l(r+z`oCDY-UGN{&Ku!dw*Pg!yv0oG=%9IpJ>*j*yV6g!!_%+%Vq) zm}AdvvPpST&lHnu1@OIVx#8tc6KT#LDyI1rr10foIpIk-=V~}t!+4$@_}p-b737-p z4T?FX_>Vh~&NpM_guli)SHrm)#?#bDl^fJi?xO0$KnMKfodv4;W@`rPAlexcEtRu;To4Q zd?n5~;q_PX{E(*o4dL8yCc-&kE=+U7TukPKxq`?ImxuOp!dye-hU+MoTMNJ-oD;6E zXD%~xHJlsf?oV!*yF@vP#{;myMA&wd_q~d3sK$JjHu+>%@j7nWixmRwk8`AO8=us^ zw=T%5xlth}K{bCJ-h>c%tC}PA7yK)sl*2^Y@OB#BYV!6oA{UdV>+vCSKgB)A^ujlT z8FGYwAj=7lf@8%4;(BJM$_WnzB*I{B*qli~dwYfyz9%flp1)VUaW_9F%r~asA6M9g z$PIr#nBkX(GJJ!EFYC{6+5ny_;G7fQ04{W*^!Jr+!iKv=)80Fb_>c9xe8psL_{dnEzgE1VbGd@{qi2TEBT$RnusqMOIp3~nJC7rU>yw=D(n-WT zkjrrY$qZN4@OQxEhS!bfc@xe#;UVDWg!e0b+62-~*l_PuE*C4g;f_;y{*Rug&t%xp zdCmzN%8eSP)6Wfat(Y604J4e8hPmF#)u$+P!yIIC!`xKO4YREzXV1nvY^(7$cyeh> zSvsZjhPOVn&9Ce}Bz*nBgb-xCpc2W=33mf4!eDOLoJm0UhjMbme6d!JJy*Srl-qF5 z(M)r~_b{o+pF#9{z;nZVT~v-euhm4AZYP~@%0t_EoZ;Z;h#~J?N(#T2niJlwa{tCTC(O_2cP{2lL`s?%x2`{Xr^*!A9$U0mvd*A{(Cr=}*R>C+3d77$EYP@Z~=FviC(``Qo3YvLl44 zP$u6Gv{cGA#=Iw!f`B*3ABpS|L$)!g6xoJI=63fdkkOV2C_H5?l1z*x=@OTuiwe(| zH!=J1?*ZmG`{;(;bb$KMu;-r;6}di1Bz8i+{Kt3XvxV7XnumnA!o3 zA;_t)m3)3C$8QBn@1p#8Gv-O3l0c0F;-&z_P*DrkQi10a`T&^uMWM*6CCj`LXawpWngUw`SXCqkgz(};1Rdb*NEYhCTPtOz8g7DYBxlR6QG7p7f}FMH7P6&VWyT<}Ht!k10?>%c7j zQmLn;H2g5$^+fhla>ZgqF7-Dd;zcM>m;FA`4I8 zl#f%Me4B#=-aoj(g~KFZNS>0I-*U&9gK!t> z@)yNe=ca@86UcuCEa&3*CVfBrujieQ!w6(3)`l)b3~v@=8{)g#b9MO0m(}+mU1#uO zpI&9mi(HIzo{Yx;<7egBhc1Y zv!<#sHr3L%azS~SWr4%u)x#sQ@wlhNUxxodTpl7FlN%K}i1ld$LccSD{}$36_>u|$ zUkAdp0Bp3lLKeU;%hi%6n<)@WXm4eJ(NfyntA|L(w=y*M%kKdA6%alOzzn%YyUss~ z>5CVM>Ojhml=we@of2~OVn}=GL@#Ar?3*MJe(EDn{5)g=v$=Ams#xH(}67hiaG1WW+~hD?pys^fi)e*_L}{VLBfAPeH=%8ugRC= z>~CLF_=n|jYZC)+nJOvx_Y20+G7o%&ZLcuh6@4YXXiS{RCFzrrx@@tEtGX0YPJoNM z!Zri#?I?ZSIbdA~vWnwh3!{uhFXl!*+Xq4DUa@K!JV-Z809$s}xg z;^W7o5bYCU(S;)!wZY+sjgdcLw6MommzZ1dbij4n|4XNfsHbxooO>-*e>(5Ba z)F{(I8s%f|bTOp;s*>;(JO0H~KZ&y^kYqer_0z;KJkhIu+K8%tI{JqZrM5J^sqh)d zJ1ZH+!(mFnP|-^B1z8S6{`6)-;tpbQm-c2g+dzUhAlW^xHvIfjB_#9p=;;X69> z^+Vi#bwHNN?~B~$w?WT?z5V7&e+`?#Y8>>ro zMpa@I0ZVm4Wx^=S_muY38NfHifi?WB0M3t=`v>CTL0N4k3**vhI7+y2KzT9~{oDVY zgs^K1>eyk$m+13TLB6mktEey8(F~}@Ky(XG3}Mp9mn> z;h?FqgGuc?VB>~^e95OSw^72U*WgogXm3uJCd|ociBZ}P^Yw%6{x4?$-xLSduGCc*-z*Ti;D~GO(B%Mn+<_op9kA5ng0-bCST}%tTfkEP z3f7l2&U}y;2P|it)6lB_9LVbfmZ}}8u4nIi9pv`|7DJf)Jgi2zoIU3+P|Eb{EFS+t zZ+lyPA=M3MuU`aMrHJW%=!=gDBW_yx7>ia1giCRlx-x`Jjv$jfDd4iR3n={pzFGR@ z>u2x%J3&_Ma+lIL=Te`L$nXe!?tTu!xHW+Zp`P-DUtjZ=fVv4soOYRDyq7YPUraME z!^xBP*mU0l?&|;>Ojj^PS#C#5zNX**1(37Paw65sQzWNBvA6PLWE}`>Rp6QgScY_d zHPI`5PKf(JUSzvE`e}nOh3f?NtfJtjrwhvIxxyQ@U7E+F9^6c5TZj(d>!(oD)zYi+kmkC_cQIk z*iqH_#42{nmEdZ7q0eRAFrOGrqVvMPM@bAD`&v0UrPbV5Zw+t12bj?+!)G+y-*>IeAhb3u*Jk))$kWcAAQmVXYiSy+s5f1{9@P+F$ zmFMR8^0fQ(O1!pKgx+y@ObZQ91b|BuxVXS8SLcZ`j z5Ptcyt%g|O;B)R)L*J+rt05QB5}61L8m9aj5K<3EQTew~{uGdlei59LF(co8HQdM# zBHT7RJ130^&1^0={DIni9pya^a^Qun-Mf(JMQ*}5Pxv)Me>Z|h6&XK|B-MPdFu`4* zZ^!15Ob2OP!{y7EI*`^pH7-w`M^*&INMaG-3{Mkdx>(#ivJHq3rSnK5ZzNmxAdp?l zUiP>eau9%iA?Vs#xlNteT004;))p?Jw&whoL&GF@Nk^kLV8{ZG{BOyMq0O?{2Fpp|@9f<$hX-#DVHJI*v zMl}@av|VK-q^hd>uoU0BQWyc8{h`w`0!2+FqC;9SHT?h7X$vU+T8IxOJ=PBCt^gkq zvEl!&04w6XhKr~|Oa#j?<2K7Z0HFsUG|_E#Ara3k;+!vyh^kgbQT1aBr!Xk(>1u5w zFVTt0ct%QeiV}?EX6`$R$#Xy{(`zm^2Y^YKAVV3r+>qvi=MR=GpHl0yM z(DRK0Im?Tyd=OD_qMRtjxan9Ij-Pu#*pI__03AQ!G_K-c{sYJ-0v1DF;sNn_ncO%Ao*kIs&XyAcxDj;_KcoSdGc52y#X-R*T_aH2}F|QC88KJ<| z4AO|qlYC113gnXkONA6I?lTmSQXU%~IE;Y!SyD!blbb|C%o}eE(FSSy1nC$mYKUn_ zn=g2_(DPS=S>{_jW2@cf2OF?MaSi<I+aW2FU`M(q2Jzl(vsCW}WX|JNVJcvUdk8?b?f@1c5%;*~D zcnF4-%?8aiy!G-NDC=<;Bk8RdNWPPjPl2pHi6c!hpG2bbNhYjLB<7RWQ^u8eV^(n) z#eEVb7)!w?nTU$BK8a$SPr9@@#7b_5|MD=1i%=C$qy=}IrTrrn&5w+1aGnrf|+tAnW zGe#iQIli7q?xWfRx- zO8`*Ckm%O-CT!OB7JMzG?LGterZ}*MG05bG`S?Y?+{;8~ZwJ>|(A z6yFKdJ~)h?jQD&xK$-JEF52&J1SK}Zp6JE(dx9a}++^8F$xni^8i$drw>eABOxa-e6%CcVO&n4br?3RJ-j_#H}Cd8coct+ zxPmb@vnDLbE&og4*f@bUtO8>m=o-q{dqx?>JrJb@9>_#gob^By<2=xKdZ3>{s9(i) z1LBP)|Az;P6i`;!G{`<ccJ_&P`U(scT4$e z-pU&Y^5lRO+;F_!OS&kecck*=J(l|wV2YOeVNgu(2+B>+8Ops4WLIvp1pQ(yME(nM z%qp3<+r^hG*;{ZID?7Nso^&4d$a~g$%9n}@AfX$mMHlugvawOHmZygfB6eZVgkEF; z+)AEgHHD-RAl!^2q0LS6k{|X-_aZf+>KEj#r=i=@a^MMeD$ncpq`B5c_mzEk+;+7T z;E8e|7+DPJY8iMjY*bpl0O6Dp+JB%37PSM~{2J-r2>%fR`$c*A5Ll`54I;NHYbjXE z5L+wPU|y-C<6B_7B-KyjsTZ4jU3&$f1+WFu63lvNRt3TbL3*gXva%qNrcq$19t)5x)0x-$(!MF$T)<(wzmOT&t_z|0Du zdUxIIjU@d47ufhg$4H+8}o%L{LO+o7a*aOx{w-X z@qPzsvkddFb8W%z!fyVDzn@P8A1COAw*HEogJceojweKtDuE(Z4+JMT^~Jui@?;6kh_UmlgjPP@f^> zy(;H`c+vu8zsV%rvq0*B{;z^-AXEc|DU?LqR%s31An@?pC~sRa-@*cF==rbCM0*xK zrnk?k<8ymOg$sla>QNutppzyJ9ex9U*vJM{V@0m2u42s6c3+zi}A*{0O}o`%L{*^YZF7p?w-^ zv1p&hnltS)0U=|bJ1zDBdkuI0PEoYa9u3hxzawPrbHoCFcL}V0Drz>gPfLUfB@t)r zGZ{SmHp*i*c~SeI0_|BTThocCfdAp27qE)#84n}%EAmtdo<_0B3xP;}OojonT|Nb) zK;FT*Yz>CCAv6J@9l~3R@kvTNyj>mwZM)3Dd8bg!4&j~2BB)!o%Qc`C$Y7kGQc1NC zirUPh@X;l%hGPRwP=X!W*@|!nn~p}V>1d8S3~A9A&eginkh3+!j`j^g#*jl@EeSsH zy;h2bY@>aghP)9WV@QX+#-<5(U!!;$a;@TN$WIVLIoZ*Y_nTJoE`*1BzOJ2YW`WRx zr-9ljWEiVeuc=mBFH@{=TFpl>*|S3ER~zMAE6v%HRJ2=mw{)AxyHu-e+CDY%nsznE zu1B_O_hh@@HjMFjKZuobnY|`2MUUh?*Y+sftJo(v6J)#aNt^;{fb(s@7087Mt zD}*g;Ky7BomNoez*RrbEQq^n5meohGY+0`WVO;nh2$`03k;OK&*Kqf<6wj8`SBuJ) zH60=ABKV>z{%&*$tc!R|!E9jL5h~OdTE*i`V>?AbY*Lro2eoVvR|t9aUH0#F4) z`z%Dr+GnH%Ugr{6`@F1R+UGNb3MCO|>{IR%YoCf|w2yV+V{M`8HK$%TtL5p!n*GXRNq;cEdjEpMfQdAT(qzpo}4>A!J?n3~PaTEsDAD#X#*8GK|%>F%{?3KUv}IRXZU*=E4^w*fY+B z&$EdNAus4^)QEB6j(v=5*Y3%7zisNmS6V4+?KN=W-=c8Fg%^j!yYT7_sRX+4ZV0_9 zbm6NKg%)w)lQacg_+o_K5SMk#g>SOy0~fwgUb7^E0`ewF#nkWD72*xEYl+$RS_sLd z(TC-FoZi%BuUxf5_$1133rTP3VMY9=@G%tf_y9{hFZs_mg-@>}O?kt6Y=`jCmm=&L zZwjA#Q8snDSROtCNtN|4lS`2;cUFE}1X4XN;Fic1{QFHsMm%qHk4gSqyKLyO8xlh{YS`s^h8(-Z9_{gpUdjZH)DWILygvW@(0{pSH>ANN;?! zL!`Gt{#mQkOVLOBO`MN*i0U>!w9z*;Lr${^Gd{W)%(YcQoR4-gh9S4WM-K(S_~>H@ znXY}=a#j)Vmm~1Rf3#Ta+Rd60%dUMrLS_uT%3=rEYq^3+N@&3=f9kx7?n1$iaMq$O-5I>D?-RMD;I}o9#d%* zb;-I=0?eqi7|f}(7a&fht*wlDt>aYsC;&#K-y&pGI>nZGB7rA<()_5>Otej-(j0`0 zN@rW_1A$7HDV{2QL-ADUPY79+RFsWS$h5_>#eu61}7{Ui^ z*1y}UWIYjBZXa+P#c{Z%XD>>c|J^MmTyn>B6_mCIg5;+(d6HF)ORjTTlXoA>y3t-G ztC|jB?1&5w{zVPfHJ9x0;q&Q97Q|dwRkf%)ne|JdT zdeU4s$X%An%0M_Sy-WJF_L(}VByAU_yWL`oxEk$RM%L0niHd6v#hJzZZ5DAXzKd)G z+jNo4madDGx3;g>hFv78qS!^I0%5wy8iY(2scEs9_8RWK1J2t_DAHOn#4geVA=^cq zac{Gxbek{z70j98EeI7#BF=P?breL`)7s|eT#xG_92!2f6+K|DGUx`a1BZrvnhl4B z#;w_+93~hV?A{;OmPWA-F%jC3LA!Nmpq)DuERk$4Hj5P;E7UNEUH!7IkmPx z$f$Lf#lB~+;qF_td{pZq#k1`fB4pM2h*jsZ1hsynV5&8I8P%GIGiuEO55JA_waxEL zZNGx$oo}x)B3J9cwm%XA%(UoLgf@!9B)0w7w8$a6w$Q+cH+2?4BUQfK8Ob3ou=zo` z2Q)*reZq{9iou+b2ysTLZDnL3x4=lF05EO;d4!CS=33w^0#B^bV$n!^$DV2X_1Zfl zJ#Mip>^0ndjN)mec|aKlRe+E+(mmEV3lfaKsbiqjL=IuhC6%{i^mv#u_oX+ZW3@DX9DPZKY|YF za!C4Dw##ua3WWc(TcV{jqwdqTldiK@8T6park%F}w^1A?7_!+wOk&4!(*_y&UXb{( zCVtC`b%~2i7iwD_x3yOpk*d=w<{i0$c{j5hmt0qjCU2L>O&erTmmqOnP23|fF$=y< zuD1?lD&RV{&iF55>pIzLp-(!fSvi#S?~EJxO_kP*8+SPLzvmK|nSvRZUgN3a00H6`?{L@=2L;iz*V_C7&w+U*`x~b= zD{MvAI;}q3L)Ag|er{)$iBp@BUD$OTCUEbjnd^kxjKL1^E*1Om3Y{8JvD1*=jKL1^ zvds_5eN{80dne4e_hK;T-U)H;-N}ev7H6b3U7eBqZq7&*tOAA+cw(Lwi$>}KgfY@x z2pJ>Qve<@!k=iSsMmnT;8tJSn10!{_#_5}2q)b4}60H|Pg_4LfM!J`RXrwl0G?G#4 zE~~7iD8D@XuTI{m)>TMs)anp>Vrs3RFshX>qt;?Dr&dCoTHm)a4#caqPIsr)MF^Qu z^Ko0`^vkK%!Z~G204BC)I zk7qGGjr0%F8zVWyNh=F&f0JfNBN1kdR1D^fM2IueDJx?sb?>J2SM+j5dI%w7qzP65 z2h>QjwOBOLmx|TR+}_Sew_5DofsxuOo<_P6C}X502w5WyvBtSNFjA3wa$A8cltfUG z9iK-N>|;lBbVkl=#ByB+mPa$&vKXA#{HX=vyr#-kZeHW?VVe%~8ebD|USkq)Uc&@X zHs>`C>2gSz*R&xLg&79uE-UnFdzFXBs%#p01aO!~TTU>yprbX39qZR1@roevY)$Mq zXGrW=uC2?X-v)`F(ZnHZfFLm^hbHG*mgNQsSyTgKtZAFOHF3*?#K9(r8%()d+Zu^< zgrC6~PkY<^u5na1jVZF5fa%BjEA$Z_2LF2&UdysxLrT%Si^k` z6vE7RT=xy;J4KM3?`#abLy=j{Tf#5r%F>Cp-qTh=S@<1;Hlz`J{2EDbk4HlgvQv>| zW-4;*md!dLnq(6$1xl7p!`f$q@XcoYsg7I~6SV=8a4O@lPun!|#A~{e;#6i-A2*dr zLR{@9KToJRK(RVRnMZwqgbvhlpmQVo&Gj0)@@{ z7Nj>m%ppFq`N8+h)C}pv2s1vc7|i)FLYxnCGP)zTz=ypKfSF`P`#B%>(Q`4yO-6X38AZGj? zhESm-;>N3a`tZUJay`M6A3(#rNyGXbAT}RUWSmd_vIGb* zf!*jWBsSg1Av(p>x>Ku3wGw93S`6mYN{CZyH!I^`0(V;_f@2t`Q2mAaauecnTQV;_gO zK4zaWx}u|f2s8F626Ofy#Mx)6m9d&?cT=^>!<~IbA!O|HfK|XTwNFzm7VY!AVmVbi zjF7RN^54(n2uHl7BIS>rFX*-iu^u**+i8+SB(l(S2ct@COEPwY`q zw97L<7+_7E^81flti4d z%l8ySyVOmzi(TUnLzOpK-Y$EUr)yvpZ9ILcG3+vq6HFgt6IaJ_?LyX#2ohhSiNCaB zU1ER!Q6x8$&r_CH%GOTSJQk$xsi_^urPkd9li0B?3=)49B%Y#)t60t%61zlh*p`BG zbZ3BVV38(nl9-rHdA)41gY=`Agf>SKPUuSd>DzoNngBQD;;gv01#telPEu`)n(3%+ zR{U78sjeHxIn{mM!R^+bPRru9_STDYf1K)m;LvuuYtWePu9qz~e-{0?g_ZO>xT0^6 zcP+q9df4iV!!A`q+y2+KDRc zfE^Gsjamqt8BdNOgjJozB#tMsX|qEdV8sd_)9nwovo1MqJaLFaRu=rtI?a&d31MbD zDF$=n2_bGgaWc|7$N8=Q0AT#q7YLd0gBXIfRg#Mp^6kuva&2E_p45({E)WglSX)&iJh{;NiDXQdgTY2IGnK zTbwrkWtH`hGt$-{v`n=3JrH1~&55YM-h?=NH?-AiZLhNHQr$=5{NYvLjJCODXA==seVDG0jL)x1#WA9=xXKzBBy`79>@%A2j9W$+! zj(>Y2WbEC}>N2Yf?LAeCMSC|HM=b3<5g}vm-WEI1Uc=q%D4zCySMjv>afIABW$idT z!QPd|Q#kG23L%VB2{>c#Dd6F^QO2Ip-ey|X$0} zyJl?m-)V6;ZN7XGo4vy%HhXqRV;_gef+A$kUDz!#&3-A;8~ZrK?J@f-)(mMM!i;^2 z!JK^varT*QWz3@5oqfIsz%=^?xz0XItO5$vKI64mw9m~zm}XyqkZJbMS?t=tJ{gLq zeac_&?9&_}Yo9+X&oK9=Fc@7PMf{SR5BmHa`-%_i;Sl-6RPiAbP zw*m8|)j-RaE}%4Dc%V8zcZKrh3J+$!3^3*iSnsb-xBBBiI_G`{Z5)$M=r$Yc z#6Y;UpZ8)mp6P`etNz$+Zj5fJ?_{QSo8Q&&8THNz%Sszi-)*i@ zfR}G@ZC|?0mf4|h^Ssq4OX~~OZf`80>){eVSks+|`s`iz$~=(k{f~qn@C)H6F&W^j zb`Q)2XM=R3<3m=vr61$_M)_VnWRAV*{|l59_#YJe zvpzFpvpk*!{;I)N;D>?I0)M2M?L>WAfAeJzW`TbjRNRGeQsAQxX@O5Kl{i{O%pK!+ zgP{u|-Pg}A(vk-QFP3bl7VJ=O$pL-Ml7xvRQ($IELd=o}tB%}Qf+bfyY?i!ih*|P> zjpYCW>rVI4q9u!g5KC?VC6*kj*x~xjjMe%0(UM(YNy|WO`8{x9w^>a+D^u1SxPE=3%;0`U=qkGpr$wtvBo{pHTJ{2ouAm zz|63Om|;&;9kq#uUHga`_JLt$*es27ZciF^qK_60yA%j9>>r@Su=^>tV_?{eJ)VZ` z`=}YV0F)ZGwv3j+ne+NI7oF!sYJ7e=zJEHvqBTjp21!krs#7y~=>L{UwtlL!!fRy%%$IX<}wdB@%Q*QO)(Ugsb zn-*_-h$%DV+E{qdXo(-NiDz2Ql-|QN-YMbU%nZ+KU9g4JH0`jIE6)@FwTS55Jn>t zCPq$ynUM)GBOj$YY7kano7Ur=J?y%f8@ zJ~Lyxef((Tg&t2M*ML$ZU!}&qF=XVlC#al8J`_~kg>ho!eDLrocexr~*vK+y7^z9k zM+)2*71vTVYuHC2E`~M4(~5*aIDIaLB}@#P0yD!BVumeJ9mNPOFl?JAsf}ahmqCeP zZ_-HD5Lh?WM~jC2(PKHNJM<|t?1PFe2n^fD<7wCtK*^x)zo68xyA&A3@0$3rilEwq zY1m&t#a$RDhCT9WHS9Q5)39MDYEpB0(XcJAH^astE`~M46h*=yM_?Xb3`>|8HU(ye zCBzK-lIqAuXn|q303e3Fdz2aW1dVhtfpx$7@MzeDKu8Vy3n=l}a}|4$KJoi+kEdaK zk0zcTI|!5-cB*>ntiWTFM$40djJq%>X|#OZKiG7Rt3iaX?8iXqo@=2>thiEBzNX%a zcX?y8+!H2NOo5pd2{9|auR3yiCs^^ILbKvMpu|1j*ES%Zz`8Shv}nae9!vME10`1c zQnBCZGc)$9j~}ggX^~lRFetU+She1yz=|@ao#MfC&*h-vE{qfR{DX>E?*G>C!tS}) zJ>u|_IZf(reY&l)d@7y??|?Ck74N?21qy5DirK%d?4L+4Djw1Zo$X!;TMG?S42!t$ zGH$et8U+oKQHE$VkMZ*c-q$apFrx^Qj7ou7MiF8em909e5nABxRRD;)N5@)5wN_x{ zQfAcmK0IdBNkE9Z-wjGK>R`oo)+hFVdOS1g1COV>{|ZVo>O#$+OG6p8?>H)FMx6#K z?!q|9sQbagr`+Xfc;Sqa3VMig^N<4f<<&QtVJAXd3~PvCiiAP#@%E=-2@}Jnz|63O zm|=&jjsn`tx)-gVF~dFuN=m?C+KGyL!=B}%MZ>Q3SeAh1&zfPoDE3tAc*S=4_|dR; z0wwjxI8bWX2?~741nk%39!$e-1cl#Cgm7ZmJ)cv<_EC1dVaF$Qfk$gnBbU*zZ~6&( zRxMp1E`~M4*m}dh;}c555+;UCftg_mF~dHmI`R-&VAuix#ADwBC5D}^kuD&xZnBRS z4ZF{HVrke*K#9jzDt5I#Gh>%{JPkY7Zw^FkNw?)Y1sA?XxK1L40{=P z-eb3>7*@s>vMxAjK2bO#M4#@vy1=-DpaQGZ%CQNK^dg@zBECpl<@Ne>Uz~6=lg_+( z!HZWbCnWwJa#2EVs`0xc5UliqzorQKcuTmgRmeQseevHw{97-6h$2GaN;$nzneof$ zPTvHg%_lO&1r3Wz$i_5xc3&QHi>3H@FFvke@%gTqR?WR2!08WfNmk8SY18kPB~g6y zzc0kuR|@9r%9dQg`WX$s`$ir1+`X@DLf=w$WjMFl8WWo}?X09#cAb4ZL2nhH@b z3aGx!4KekI(C&IXmTIlJ?u;=2YZGYdagbAv&qQyfHq&^D?qcNZSGlulvlIf1iH=cZ1MJH>8e6DOx9#ZLm~)&Pz5+QXTPlWvlDT2S zmna?^VAH(-=Y~aqbHfxs<-)mPLs|%-x#5?HM9q;8s6lG!fg4Z0-CXD`U}SE1i3Xe7 zC!rGR{XBu}et!u{Dxq%LcNjomT}Q8ql~CtN#Ih2)5tLLy7b>=wJ~LzMe3DoRt@LeFFMmF)b~dKliEE6X0ZnaLY}ynv>`kD=urFw&b1$c1 z2m5Hzuq7T#!+r-!3_C}$Wr1OHJ)VX={{`x%VebT`hW%En)t~ffCw$^uA-gNQen^PJG zRxXkE-2Pg7ch%w zMbHFF6!2>xxWWrQmLlkVx6GB#VIE+O7qv~x0b2K=9>TU3S` zo9r@Y(^#xwe+UFhl3N*7AUnlhRP{j>I}m89GAH4LefzsKmiN#{Z&3p#P32d+tKLCr zKf}efW|_QLtoa>`ekJ5x!4Mq5Bs?;_&KwR1$gH$UNhV67O zVKgjZV%QXz8I}+;>_@7j8o>o4i{>-Tumv;Cu!9##yjt|7VSn}E(Xgw45W}XuW`-T9 z*g}0`{m0{J*z19kwr2z=HSBH!h79|f2h*_CpyDo!6T@cCQp3(vH7SPWA*G*bN@GX> z3gP5Ij0aD>I|Aa;2l_!FaX`}6J~@yG4jke@i0KVct4NsaMV~`7Jz-+{6quQw5HtNw z)e*Te!SuKMmx0o!=gv0Mmuj-|2&}u?M~kNa0|+tw39p;!mn-&deP+fE@pzj48KA`U z<)GB`P1NLjg-rjM2h;S?5}H1Y6VrDE51(?kMZ*i3UhMjprnCSFNL%~){btvzAT4$^ zgj*1^gD-lV^2P$?$m ziKNXmk$H%F+S(_)GxIpRW8Sdi?DkefArLsu?w1FXkF%Qqpd4rS9w<4HG*KjcoE_E3 zadt_lq~q)|=1~)mvpYlsuYr^uXLqgV=A%3%arHPma^*NXa+GV^+J9LWTY*0{gqFsJi zsh((8=?^6>bv(`PQlP8c4T`Kk&F(>c> zMV=Ee1R^>Jz$hZCT+%bq-pWA3PulFKyn+L8G@_zXQ!{#35aOxIUtnTxbK1ai;UV~=01OF0+Q*9RFFcP;^QR_5p zJ6H{;j4W^)l}XFipKZplCNr#ou2umjE)frW5IWloMOatiUqV=J5yNVws58N2qLRYu ztjyG~Dj3!&?&g(D^9CT9q8u_dcxa6!m&TVLkMZVSUE1M!7--%+u$E6}U8! zVI5L{yJG8yq^|dJw-R+yvEpj4f%sS);kOnq*FvbCqSgMQ_GevO(OdNS8-N!=v3tB> z?e8ltCm-U^tM-D$rkxbEw_5}D6j!V0J>z(b&&y!HM(tlVtlh;uEE3Cy_*B(?`T86n(lfcQS+}S@!}~ zPiX?DD)Lp6SnTfb5=`LdUV;hSZ@Ew4EJZyANPPmU_3b|<@IOr8GFPLxu1h2Sb0w6n zh9)=s(WC@!!Fx^MGM~V6DlLIOtBSw%=_*}22uret0#;9H0@F0GJ@o0`b{BgICh%J? z!31_%;S<gr09?4z1^|l`Q3C`90CkTi4*=ExC_{d z%0TG=V3PtP*VPXIKJ!37Fn*f@0P>`_cL=`YQ|4||G4}Q*AOw1dtOxB(;MiLo0Mw|( za-lC60MIBh05Enw*){+m+de3jnK+O}wPb!K?=x%wa6Td@1AtUW;s9XzYTAthfOFol z0YI863zQ}uX?-(rG6;AMRFyN74Fbep?QJ3ApVjQ-k(8momP1C)UvHtI)B*v2ojM}f zUwf>f2(Qp62PFg6M3Jz+QjPd)5-Q1GYrQ7=YX=QHc746SUh^))p}!_^)nCaKe>H9~ zWRY`MA>!h%TLBS&J^elN*CWlP`q5uIdo2BRG7#dg>p+RW8n%ndWX5*>hba1M%W6{e z*Aqdhzh0p=M++zqO*r%gYNaDXoV9>bbk=hdT=E=5$J`RXwO4I6Xh|Hcs=4x*3J%UV zTBSvFw5sd@WSg^+Z69&gOBI%{&%jxyB68xasgOixo&7$IKxb|JfjMj6u+k)FJrOu@ z*6Tr4ISV@3S?z5x;-A&*hbJjRXB`e1an}ACO5_Ibtp5fi@v?x&XYZ5BSS>N}X=&TP~5+P-?D|sK8vnFxXS;-Y=HEs!Hk#kLb+IU&ONukEgT#_lfjl% z+-pItbmWP@4yPdfby|YI)**y?e{KBF{#vLOi!mYQuQZC@7oh9{vdv$~wvYJhY=xES zGw|0Lh@ALqDkRZgd#q#f=&xfz$?VD-VWmm_I^RohhUE)TRnCGoe_i44C$hICh<{cy z@zo40M~Sb-HG~#7d0*ZAbh58L0igKmE>PmDi6UWNr5f?oBvg{G9{mY5`Hp}FJ^)hY zt5ZCe73-QruKFsu+7VE09J0u@1&Fv*tOso%#g0G$DCr2?YVOpZzB8l$(mK}k; zKQ&)9?0tc+Ug+`k)fiAxvEBy?so>p2XR2%ELb>_sL=R*~Uo1>3AUS9{n)>@h^HuK~`aJbBT%a==`ai+Hgi+y2yw@>BpD0I#hkkBj zin~?xVSTzQqIW@9MiSQoR!`}eqF9mBOrmdes+ZuHVvU#Jn4<9}$5G)JMZF6M+(IWG z5~elq(hmhcax)YfS?h+JfSdKyb&lUGMm!%1|AZDd{uxW0zo+jjy#E;2W8M+TK7&^h zkE@~kPec@Es)ka1W}kCGArmwMy!M+DDgJf}HXj7dQ{05@IA^!}w646*VuZSXVgF!{eBTy7x;zon|T4VQzJ~O75 zx+!>n9@Le(Qcy!ZH3QUCQ02~$*JAdK*@VptLmR>F%N#F>HSWErB}MuV3fMW z_|I6Dx;daWdTJUdw}p#Yys|bd+&GHKjyqMX(p?X#(p`rC@gNo!&Jy?Sz6~h2uhbn7 z$hQK8t|Gr9$W$FmU1#v}!CUNj*Kek#p`$(<_xNHAHH-xBS)fWCFZz8K)DnMuW7816 zQ4iU<)@UoS{8jT|pep>YnhjfsOv0|Ua<6y>>VE-q*BZg7;kaw9g=&ryoqQDa1w?Uf z{u#u@V%kaZjn6N2)A0UI0TBpijj$`9y2lu-)_#r3^wgpsT;!H{XsrAt@8`b&t6p>Q zdDxj}7xOlm?yqu}tD%E0ygXUIpfxz;BuucVDSyysZ^SG6S=2L6Pe^JFR^k1-ZaAvK z?Efr8wSDM!^o0StBaxmasn6_@S3w>(QG&P14aNWLpPI}{kH}}St8R)p55u8@A&^q@PC;*zJUOm%tGaO9~hm! zr{4acuJlx2P(wk*U0C~4_ZWC@g15}gZju`3Cc~j}D;S@8Me9L{%GID^KQyGWp+KSt zWH!*t9gp08NDWc||7>y{0^n&JyTF!1XwKTkMrDM8g3~ze8Q{ytJrAgnS?Z=Va*>G& zEP=M{r%K&iyeoo=Qnv)uXP}n5TSB;w&mhzx0r1HH*fk7n3*aRI@G1q$j7MU~dpsm- zvkXtRYZ!Nm#t(JV^zn=qrvV6)?HVaCE3kyvc8!-*M~xMD4o18ENNw!kPX;CR+d>7l zxQ+GOU2yNW{9qJ!gtBt`3P7pcRw=MrpP8{E0G4T!bI^y8-uBR=_sOQUK$1AuSpCz=vCH)`n zs2|B%c3uL*cJ;$Kw4mcV$B=SYeI@>vG$X;JrE^<3EQ86lT05j^X7B4W4owBHG zU;N+WS5nPD-2-ZcTNaXN^jxX?0`CO(F(~3zI%-?to(ZGT*(=36H~{{S2Xc|0?U<@@ zh(oH;P1~jr!P}TS{bn7$B!qVO$dwMCaa-Ksdq1yv1*{Nf0U{M*<}Rxchi(x!9zby2 zAdh8-uOARnCr$w+b)sQMs!V3=G>>P8Z@tH}!}k{`?eHC~Wv&3qZN{VH?^Mhgk8?q- zbmU2&?>2nLr_4=I{j3PbAp~jHxCQ1cRTxx}+`=MzpUTu~C6a1sMrai2^BKE_Y->Wu z=4XZb8vU{=)zAVLJ$TP91Pw3WKo@KQvkfD(}+P$Kdz3QuA{zT0wmAkr=nX`v!39pkgq{R`h0`cSVA zt6-^{h?htI$>==|Nq%>5UW_fIxy0Hta7dVhLLVs@%0# zP*B43M^{NDtbZ#GlSNxGP55rNmsr9|@xIhe$N!AKNj(qhB2SG1RRL*j9%iRyejwNrD*RzKVAm6etO5G^n2ul*lc0rTBjGZu$9F&yj5h9uN9NcAFrWqXGDa4lljIMxIPDD~I24}z>+ z-AfNYl z`p`z*_qQVF^Qy|VRMbP5!KiXQ^xIhf?Iry-3E%u@rOQVobb4nYr*{^)UTttJnVKaI zZuX*eFEin{;r(rhNTn+RRp}nX|5A59{^y~+#U1v*E_KEDJ`LYxw#M}2+~sF$I!>hs zXKScPW@{+C!q3)B&_MGE)|r|}8gZPdxzbadsTl{V%vC6wGc~QCmpSMya@;{k_jg(^ zU5{}YHzEGHH<~P!D5U=T(%U0dmF_&Bijy_grS51@wLYkhpiWDV!k^1R!rq^^;UyDV z={AF^bZhY+7al|R3O^Q046QNzc-aKQ&j(fNX5xQ8s27=~I8)3;-oW?8?rLbN*0|Q_ zvvH4orctU0yyh9S$s?ey0JXpwChWtD-DF^lyTvq}f11}c3%oMOtE-!%R3ib6W3?Xg zELyTHKCmZ1?c0cvC12b#_(%qA|>h9#0yStO!y%&Df zDW58LMUs!dp5)_ihJAdVYl7BciN1bEpBaPGUw{Lw^3w$AKfB&9RJvnX+jAiGGvfDN|X$ zXtw3Sdf64LU!|*UfPG8dyZC=J!j-A4OF+p~R-#0BDvMeq_mWUaQ(5$h4vdms*UMwsv-#Fz zIodlgizQ<_`YeW>sWO?dwjR%(%~e3jXm1!Oq?Dt*d)2DBP;Nb&S3QtDn|DBArWrix z+3cVoGi|ZzXaD66gn&%z#ow%zyCPK>^lb1JwFGx{=crIV6Jl#QG>Y_Wj9o~!^=!zt zkIZKMOSPP-&+H{Ko3&>)lSeP@;;Bxct_LN)dTL0@X0wKSEN8Q3c#5-GYe7{x({Bql zWp1V>jr%*VpI+~&<<7=r!Ol-4A(GvEHMYFF3ID=ia1`K`_>*l%+eB9PJ8d>kM3tih8xWmXAaZYaV@|4L#}3nkfO-LFty>0SY21Mc8Nq)Hvr%)l`n3Jm%o z_6ebBNQavzg8C1aI)0F3OP`YlP9*i^dP z@B*KCem$hCLVM~H$+~4G17RzBd~;S)ToaM?kTBR<*;jy*RyLyrDYmjbK~=faR4rRs zwxf&ocah%uF85y8WxQ+m8iV^AjEP?O2T-kBQq3k%Oy_bpD?M4P<49QVd%P5pPeF;u zd!Vj`@CtWzSmf_gR~$$b1`>~}!~%DV#)~D@)@@*=D-nx(lr>kM*^}I^SB9Kp4-K-)vmJ4ZyD(B#dH&s+wIx@1MreXx)Mw)!)kwFj@+<>NR(XC0 zC96D7hw!$_bLF1Ia+PN&C^?_NuwzvQD?QV^a<24_Zp|4EN}9+-k#G}9HPS>Tp^}=& zFTEx3hUo*v# zNdA2Q*WK%}Y$AsPA%p)oC}|=Md!x$W{CAIM6ZyNxbMW7OA6Q$O$b+@M9RTH_)t<9} z!mJ1w(mviyDYlP8R5@G0La47Vb>;4C)n_fFmPTnKYt3X#iM5fminNi&t|r^sNV4rC z{kbd+zO_EHXS)Hf(}4S-p?eXLl!kJHr#j(Xqqf#iHVcVbLwOhwrT#Zg7kG*d6nE==rEo{I0~&Xfl|O5X>r z@XgCQ4LC9oe*cPVU&7RLTJu_n)>CjcE-h?SbgrO3_Gqpz2%75)k3mk>7ZSn2`hozt zz92xZFC+nNeL;X+Um#FQLL$)C7sxGlyEJ0K&y5CN>~p%xJ*ONQ$zxl3m zxiecN_fFVP81Keo)hw+uIsqr)PkJZ5*8tW5UBEgQuk({x?5jKw$#^`C?<3h+=;eIs zURs1Ue`kED_~G(OdCo;5+}1KKw#~!bg4_8Q0=;OzD8BbS0-cYYMIBN32GhlP(cOSZ)p&i5RgK%1i>0aw zt{d&KtQwa9AywlpP*OD-c9+Uz#xC=CR*lDXAf8oYA5dB~zNq5_t9Rk)a$u#LOrUCRB~Iid2op&Li8ZMzZTaIG_T| zId9_kN621E_LVXz9o`atevPPc<7hRTmL|D&Pj4}!-va+6AFbpA;5?v9o( z2B`)F`O?=zm@f+fk$g!%(DJ2PZJall`Et0&GGFq6kbId4O7g|98-jeo214j0FsGJbT0GZb0;XG zr#|73P2sxYkhdd3TmcmIdLah66{>OnPjQA~y&U3rlM0Zd5uw0VZAJQR!fBE90zmjV zhBDV!HU5m4{M-;=Zv|Wp#ZA$0m~xz}mJpdkk~js*;jYNjje~(}nd_j@b;keo+N1NtOo?i}S%_hjRE-Geooya|j0nR55Iawy~D4?JF5mM1snFa3;` znE%GR1(A|}4m{Mi(=GB{@Jo$7 z_Cj0W#oL4W-czkWbvle=+fOnY5IYEAe*;FT+l~Js@-rxkeCDR9cBg@V?*14P!LBOg z2|izbE6?+Qb@x?ZgTO3IY|DnHUIQZR{k-cp2s9hdmrW06Pl-Dr-6I8h~%+&{Ld1jp> zYMQ9{{-$PnRiNgpKuy+BRAZP1)a0mmuBn;T934-I&8-lY*o^XO4AX#`Q&s$YQ&W6t zpr$fV^Nm+ym_QB7p(N@R6`yNr=1mUN^gY^QGZa+0GfYSg*K6mic)6*WU+L9w-S#C2 zYiPz^X|S@!@BvBtyFq9_`Opm0Kxl8P_`9a2{8+Dsq3xB6(3bdoH}(dDEs~H<2V|Ac zbNBCZXWXQ4P!)~Yg}UB#8H*9b61w?T3Yf~n6> zyJG57BQbcJIO`3F#180n!&d9mC%>J2bYrk(N4p=yd;(aBZ1d~txX)bE~p4pi<5v`_QBlf{}mk4iU&mm+c|C=odkl!%m|`b`X}NiT@(z)KO? z0!l>IfuaZ&C=j8gE&>%peW-oIDtbW0m_WtjpjHD|>K+KGcoE;bp2(`7+ZX$5dhgLE zS}fVZxEK)G!pJz4I|Bq;81*ng_J8D4;dhBYsEYDwz@DxN;w-ti(<@{yp3=o~(ZGcO zBNsP&Ycm%G%v>Z`Cl5!c>e2cP<>Wjfk&S*=rb6Npi_3j1xHI!FfFxPhoWx{}Q=laa zCms%!!^#KdQ5k!phN%^0bC)qm92PBw3fUiNknt9^{i0PqOzw{)O!h~nz-+KUi0zM@ zq&jlZviQLUhgU8B#dvdnl6FG zJ)Xm>JAjg5?^sYMj9fJPL4m)RfS!Xh--9{C`V>^$g>f?6YTb?LfqiGGxJ?A64P3$o zbB-&)qciFzU6{F47iRXx`bc&k|K&vJ(3P6YWnsp@@GCV}_!m`pAuBa+sm*GkHTyF6 z%yLcvbET%#uhd*{GE>OKn(?5pSOb_W)@;UiS*$S?@2e^-*4*sXa7GPlDEN1h3=}gkjyQ!=c)B`M;d>>9$t^&{`nV-tBfBM~zArKw5=a7n*Ydq;DMp-;A9PFl$YQdPPzM4QCz=a7dw4mvHv~GJl`CoeUDV(v%fyG zuXXt=7%-cJxn3cggu_pxYBmYagIeaBgs^DPEQlDJ1rcMjK(QshSx6Dnra`3GG>8gx|m@+wjI|IMo;aKm}UNJw5Kfg8xHw-E=7 zae$Y+Iva&n@~S`+G{I8dV>Hqvc{K_s$*Yy1q%ZY&2yc1yx5u);bU54c%CI%G{+~_` z-C$k`n0ZC8=G6$*++tWtUY$jh<(0*Bvc*{Q>Lvk6UU7bUsRHt#FuTCbew%q!zkD|q zc$uT#2ukLt6Gg&v)KnvL)JdqMIqHMYp(f5zZ_>aEAZ2sZcX%#a{v@u>QIjik)W(fN z77cZOL|o>mcLE}f^_k~dW4%io!kk9|t~<_S*;u~-gv^D00!rpW4V$Jzfy~$+*smbJ zXK3A>c+Q2M1PZBOWBqRh=0bUBj`}K~(0c?!TIOMt;(Seem0`<#F`~mc9^d;xqj6UP zul_w8fOFK}sLAq~5?j8bRb(>M*o9aFOENVjez zA93U6G@(&y6kOkVQJM3^XqE6_B$lOv!QJPbi1}2bR5TTDO*@No*x>= zwd$ecxNU%c;-yDj04vHkZn}mNhm|po+iMLY&qlldg){^k?Uy{oMteOd8OJ4x1r4@{ zu)!7)HrN!Aaa@v!Hr67+##$uUSW`mko;ez~)%vu?`o@bGHP$^(f|4x+hAmSp>YuOQ zVOm)Khyd#!3ZUP?v78}Id#JsbO(Z`uo?EASYiXw*?$URuo8!3;ePlSE%et7+;&|>f zP%@rN6br_4BEs>Uh;Te7A{@^piP(5fL^z%k5sv35f-Wc`wA7F1X8TY%o=Z|;<2h0B zIM~f%j3~!*i7GgrD+EWzbH8bN(|!~y1mn3+y)Z9`rowV(02}z&uPoR*m(M&ulG;ZV z9jH%~l$X5`IhtzOlQE*wVW7&LfdZvENaS>qjHL{b^BD4@r~CUoD|DYjfsCaLa)^eA zI%ZD~<5-F?8B3+Wtga!%#!^S9j(h|cjHM2_gt0y}2i^-x#!}n1OQMSjtlR3tWA*&K z$8s!n@V~8k{zI|pwIY)lo9OWzOFa&hRL?U(p+K;DK3;*Rn1GI@)_5?-Qa^!;yD&~_ z?8AF`k1lt6sd&m*ss@pM>XZL9mbwr+lEzYx`WFdfsh{vd#!`LMX1R|ei!O7UtCPo4 z&-Z2uIhOhZ6q**mWGq#1sg0#f#dWF*W2sWFCS@#Th+7S5W2w)eEHsufOd%uI$2ESR z5vw0dU3D4kBx9-Js;!#H%iSO#Wh}J|n8f{X1{`I<>sYF&4-?5<=kq+pvDA7{Rqjbe zay-Q?c-#*+M&G@pPmH3D{eVGo(e5vZRr*Cc*$+43a(XZq?80KcLgt=05#gd;spEnj zMV9#ea490Fkhv#LB)Di->bPJ>i3QH${zq?FHpQg~G}L2`yD&^P#f9HCv?=Zf#4S}`dehzdT5q~c z6a2nD8~6C^Lz<2wpT~fb-t;0+(xO#_@Yb8&>9K6l+FWV9X~RaaI)T=#)GKCdCSbN^ z1f!v0YZh0{xkM+Ae7X{4y=jZ-T8pvvrmqqZfigpv+T{Ek3B2Uz-=1QA z9)FdMd=iEKM_$S(H3{5MKCX0(gp7QWzzvLih9VAvm%REC-(}>}LTlT@^x3$_NTf;f zs`J&BSN%XqUhNgaTV74_SmxCdP%=t2Y@y`UwO%pvO2Eu3f;F%9QO)txy!wJD%PWiN zkrrdktBh+rNb-s!p9>XG%e*RZ)7LSt>PJ4u052n-L7-&hlPD4%`B06Fe3DQ}BcJ77 z6GuL`YT&v5sUP_?$!9q1ASZEkw4QP;v20rJ2PGpP!SohA$KyHj`4|-9$)@!$1=c`$Xyo$;P}rRV zhP0zO*Lm}oxityx=y`~ajBq$DR_@wruie^Moi3A+&j2-9ixEEA^0P%+MMgfx&Li7; zBV^l0_64Qkh#>K&&>V$W%f|AkCn2@NAe%|(2j()azild*l z*R#2@KxFhI5jaHCf3!ZcA9gc?2%HSD#Epy3**q!csQWQrOe2 z_98DGwK*5UpJcyBm8EFBGZnX{;K@EOH;QUOqBAtet>xdC#m8`>oj z$x+8{_mfXiBp;DD9U9!)&ys#x{}JBnu_3o{Iq}LHqW(}R{M7z7LeIUC8_5R1#TVmS zjT|?12Y*%Z2RO16f24+00#x=L{BWd^de&-_iI}y2C-> zF+R)OuD>zg5kh5f?xFQ=takuX=`ulaVW9?r)@|fn;N9`#k?cW7H|ExXyhT1=?ob^$ zBN4N~0|ApE|1me&=)(|qD-zY)7#|sqJ_wW1M+(f!J0Uju7^ph(5n3?%7zBV+kvl+1 z75TOTiwUf|+DD63WY_*yMcxZas>t<<-K5XV*ghWbH_Cau-zWzP?#?Q*h30r$eTJ&Z z{cmQEDGW+F?BWLv$|}XE-=VwMTXd)LOhNYGHv+5nf@6V?7~c_T|cYaw)*Kp4>wQ)3NV8Ue(kvNAG?WJ}KSq`w_P6mHWg~+$-1o7FN~l zdM8Q+-EI+Kw_8Nm^`?mIl}i%QZnsFV+bt68dQ$?s;xt-8k`Uo?SEX#N72nS7@O1&+m$_2p(VdKRNhzKQsLUZ4Qi@YxR*DI+QhcK7 zh$Fb56t}zGN^ub=DaGe2F!Cfz@j*UXEX5li;EgDG$qT2n)varb&tKvIX zN?B-gXEf4eGyM3cFO$l`lXzd^7QF(_CSMi~8NjlThwS+jNM9B<`?4?s3@r;^Czplk z8df2M+-5fw!AM#7FGP~d!g~t+A7x>&LRRV%8h`N`Sr-0;MkxznSWp(Oxhq^28mSH9 zjNdn|JJKa(VI`na77UWDQ221aFRUyOCS@T7W@Uj8D+|q3N93u5vhc6Ftt|W(l$3>o z6qrX~U9OK7%R-&UvMl7@V`br3#r{j5nX&JD{8$zWfs(RN3QEhubqc)I1d_|bdLVId zR|u3;7S2{?P!_aznjgVdMdg_Sn00ty))x1&EL@?Gpe#_l%++YNvMdxs#FquQ`+WDS zaw_btmIcU_JF|RH7V7Vi0oS4tDhq2^7QS}_G$yCLC1v3_#BZN1@c6&KN-7Jl;(dwh z;IJq2dtVmLypLs}0NL|3kiINz^JQTg7+My7PA&@%Xjs({a@*YN2u8}nDu^VPg%=e1 zKgz-=g*>ZIXmnetk!4|@fmRm6u%Ijq2E=-O(k^_gnj%jlemh++q)W=e7l2AxFvtdl zqAU#XfwEm7Ov*wE%*p~GRu(>29eD^YXcv0lZ)IT>C@Bj&6<9!E-N`;$EDNn3AeLp} z0#MSsi)ub*=`%A{=i|q+Fw5iFyL%s$mW5*#*v$lz%fe0|<1P$JDhqq5WJ6_PU*(ws zm~~8G*3J*IEF7+oP+2I^M6)c+f=GQ?cuP5}>}_IMFv~Yw7AzV`WnrSbm3uIc{2F^O z*X|XGJT{N#m^J+me!pFj#kViJb0_1=;;duw1*;Bk>%Y%k5d?Fzd)jiRl%R`|D%WFs zc;7OI5sCYjTMtU!w|vk;_4}47-R$9{eams=ed505JHVE~($N}z-YD){{s~dEean6S zN|z|vxan4V0a2Fk0V-NR(P>|OLw|1%1*Z<7W3>YH0H}HXvRK0oQknE6S);r_9{h>0 zWqxrt1!fn<3WOKNra-K45Q5J#_gES_ks8hx3vX!_j`9KHsG*G9^PqZqYBZ>Upm3$6 zLSH`1PZ{(|FT&BgzE|KEr6kP-3Myfmr*HVy(mcT{W12q%C22P7;}(Y{S;M>l(@dD8 zIR$2E76{Xv0OS3?j<`jsfnGk#=pK~>>Cx_GAA1KM^Cq2b9 zmw+mF2K|RLFZRAYUE{x0pUsL_d~fOg&?{uR@ly)TYs0@*pYA)n0MkvFq&o#>=@tmn zodU6R6B49*j)qfV;aOf+110JH*;7n+n@5>$gIc=N26j(z??=>(Ek+}&%ijFKlH3&< zq)6WjO5EG9kD2M0WL@h8m}J5v$tf^PvOt*R6o@66kRZvm8qQx9o+Y`$M~+3h##2mk z+G9-e9}2Z3qw^nh^U>n*mjO>GWRyOem4EIN!M*yOphW9BW5;NiMb+EPFqZ%#hPfY< z7{;(g7SSbHgS-F@LzoyQ1!jg32n~}0F~blN80I+*XPSj)hMDLiN5fQjiiW8HRqpsZ zCVm<;jMQ`$3MpWU=XFAxBDH(kK~?zL-LP?BQM2d&NH9}NuuNVXq?Qm%sj!*S zB(|lJY<$G3OEo@~mdYhr)j>FnidZ!TW?>10VWmJUJVNl1nq{4av&F(Qs}2WBO4tlf z(W>u&DtBKfv_Y#b@$UA%LQH$J`Eq#Rb_v?|4yxUK@1hGiAeyIrn|1o!Z+J8^5E

    e1e#DEFE~hXeJ?p!p{HfC+|6z9JVp8)u)i(eDcX#wRpSL%G z@iZWn?g~(q?n3;>Ay^9Sg4#}tPH2MV21VSgPbfUUmif<)^foAzL1h>gbfixo5$;G^ zn8gykiAbz;q~m}}N7^6*HBfYb7x+NgktR$!(kU>@X+o?cJxFy_BeiUK1=0M-pdw2}@4UJao1qGu`a4SnML3!et|qK|ljirI^ffzn>|+Y0>91d@Bv z_W&7pVUYHsFF``eU8PC}z38Hg@qWI$THh~01biP@w!~nXvzO1#fmcKL83nPkOc3uR z#b>P>jL~C`c1&}A<2(GI9Fh40+T6t7%?a;pi?4S+Nhkd5Wz6_?Oq+2p8Z!TaKRePF zoACnkAF$q)JNf(Yo8$Ol!9i&|fZg{g))OD@gCD$UaD{-i=#+*b7L=E|Kf!t(pi);0 zD(`7di%to_xgfb1?<(C~{KvU=P_e?@6-Hq}vIy_6Qvv@cc}=kdOf96i6|*1S9WaXF zM8jMxNVX2R`H}iaQ?})s;;hpkE6bIZq}UkmV0$9*vRrxWXmhd&pv1|x{~~5CA-HbS z&%|=H_KU}Iw03l%`I%vNsZ3@}4hg284FO90Y$_ByZ0VR%+C=zxIsu9OXLM1uI z(_^TKj`5`i9*2}U#(`taF_O6I7{aAvBy!C$W$$r8utGR_=h5-4$u z8`aPS1lRrYi#f(`9!tkK_8D^w!wyiH%vgoT(=l!XN*tpIlsd+*3M_>3&;reTpiq{; z5U==@Qk-rYk&yE(5%ol`Xrq-yy;sm%v@1}zQ}Q>?l-LelT1C9V*tKMvSCAci#3|aS z*XKL~r#LcgQGD{d@I`8`Y+@OpN&j4I_SG?40Kk{DSP@BQ3}?swM_pi(`^nkU2iG zY(c&TB|eb|5BmgFh)*P;l6>Oq=glYPYrut&GM{+MbLkUFT=faz(kBwR<`WlAGM_MR z4U@iK^b)kZ;uD_&B0h29Wb=s^>ck+i@$`uf9!sB?0fhL(m!PDlV%QlflNtMJ7j?6u zXg9@j_6$(41D&YlucAC3%B=;t$ph&?Pk~zL$P)*eLqXOR6{?^0K{v#Rc`t`q9 zUH4(F{$nt=1yJ9$Nj%qKyxX%c0{9b%)_<776B~yVF7&;lB@0}{x=sJVz=NNUV3Mv7 z#O`LAml5m!0<(@@ko%i}YLTRt9iIP_S-~wEuL2<*Uqf_JBZr! zTpv`kUaZE7PoP=1 z{bgpo62f9uLtIvG)+`U>c!Dr7YYNQFN{E@Yuj+_QOfc(P07yaYHr32}rbaoBz`C_Q zJeu_}Af%u!1|Wx<&OwH59`blDA20z}hi(=Pv;kP%=IvfQ2UH|`BkB_7f~ zz0_Tdm)pUvbZ3F$meO$$xJzL*qG_tvG&M<65~P`GI`id3O(#I$N!66|ypPi*h<2sB z8H`GIrT>31{+GJ5@c&r|SNK?(P(FoD*(2(O7*hc8|7!ph`JAdR7G&oT@`6`@#39X! z;us#)U~u%1OiiWX_pwBMq$r*+qbTO=>xi1MvNeBNcEHIjcs~*Pm$(D>Ohp`?k3D^O zPsB3E$}Ow|IfOA57=+Ao-B6!>uQABbU~m%6$OtWZKA5HMI{g0-;8NEcR2`_e3yUmu zcY)XTRc3fIP_?SEh6ds(H0|&br2_x^dC(Ww=bi-ODKtCq5=Z6(^gKX_CcYD1<^EKC z`r9g`?atOX(^n&G_G#J$N``=ev-9yk?v;!LwFT5NcS%MAB0PcSS}^c?7yK8I+dxsI z%9&;hmm6hHc?T8MzOF`x(rIhxz>&xv)1#5Y9F}yJH;d}I8GfV8V7$k^m`PYx1LFg? zV?COL{r!SxT2b{wAGnhi;l+Xaq6RPgX?};h&)>tWT2aZvAGpTY!+n zde|IAU$c7CAjc^b&C%&m!dPz-CiP|t%<4@-tlsRRItme-Z|>O~-2#Brn}2|k=IHFz zv@DEHU|lO8t?U25d1|wWWpgwHl+>G-DfVi8X2#y~@ngODxyN%VChfn7h8{eiz+X&2 zo1;#E$k}c^K;htl5Kfw-N2!SA_ikld<(XDg$OcI==@w1tUHWtfx%+)8m`Sfdg=A6~ z7Gx43%p}gh9I%Q3qNh6_{hq*|-)6Y5ok+QI)~` znI6V$Buug~1!mbuh-G6Z)lq=Zf^2O0Is@f&+Et(=8^@r;@DnGn?h_v#v+)&=Wj5A; zl58wi?5q0BjE(YmW@BCnbu$}p0HxWuPJuNhpxHRWgW0S2FQ~W+<0KomQW3Lpv5H$Z z`kjB;t2kN{8ks_~c5h^6&75OqHN4CU%u0xvwTtS=Lui3nuK+;I zx&V}z^$Lx00fBY7K3X(ubS|+p>&c+Rto;>xr&%es)yI!!o#gQ}>rzl^*0&Y-p$Vv2 zw|Fqkn)L?F8perPPY2JNb-0Qrn{}~c*CJ07x>TPnI~>0UW6thHKPZ^z*pwS;fuhiW zwFB&*nsW+Db8dohm;=??|4Xa{sg0lApVX-9#YlwEQnL~*d0Qb5MAyp65%F& zh)=8~q=BZ~SQ*$8z>hWM-$Ji6MI^Z?7ZEn)6sdBi*}}E9?`Snu4i-+(40p_CNUSukfS6R8 z202loD3zyV5ysL@n3is32QVw$gjnhBs-PHx3rhF10BG9>N=o;c3M?S7F3U%YrTduq z#IkhX3Q9_MZ^d4z&&=3zA3v7v)gI5%T?LGG`so zySrlb1VT2(DRUjQQ^cb{Z&yxM+M&zSXb8?FS-0rzv!anvCMwHXoIINEo>mPrjVZr9 z#h&o_Zj$oi#)CwedtKjd{2ptk^&Fk0!lNfnC@H{5*JR2^tR zJqAfRSl`mv8jzo)FsSy7~h{hNs~veG`afXiGP^^!Fk z(L+~&SQD4e2NA4t?G-m~19RjQ{YD!PQ>nCvt0Z8vS|B~&jaB>v!(v2)-$BgK*NAU# zf1q-C&~Z=N#5dk8Z;N5T2ax_Ae=<$@HHMe|4w-u*>HX8Wt{&O!vf$C~PuD`ncgL;w zUK#lT?(Y6Lo=c!{{A3V_`B=lxFXxNnxFJ?v?6HV19_R9@yqLC_FDh627Yt&De=+Z^ z;Kid$iD>z%f5F4utMLLqfhvwfwjjI@+!@or`r93eq+%R6WUl*qZ^UJ{<8{v$E$0vK zt3CoE677Z;EAXPiHE)N*6Ep?YPz3Q~TCn8ifH7qU=p!?!%>SpmJ$0Y#Kp0<23@27ZHK<=wu&(JTQ7giEQRD$O{Th{{X+rU{fFv zZstgVSW`fV4=W#OHwC#8*36bxO`TrF9u2D}gA@P~G{Hx%B9P;j=Bur_xM&^qA|D8> zEApz?T=W4#n&2^@q`A0Ku{Y>5Gj@*0v$^=mLzo}(f*7X>PA%?0KZ*cp{GH9k{o{-96SDEfzw70=Wt_W|)tjjT0nHw+Y?ttIO+u_;|5bIw z5L}Q`Zvr4Wb?m#AQ|r_Ug#^}}=%dA)8VrQwR4FLQsjZ6r(F`A}_3>j)?e!k<%&D%R zv|;b0CI4uBhL%mQ0y6Hxprp=HR3$^1B&Fj>R3H3QBku0-=t3WPmX2qjSW1UMj#p?< zIt0SfkpeM$5`vH9pDBn;^g%L`$)Bw4uix132c7*`)2d5ADYeITuZ&UCXK+l z*S#v*{81pp<`tmC<|`EYu0Atk{XCvFZ}*Ye{0vZP^8-H?<(>6uD^NFhFgsIEfQq{? zPD;lzDq`vQR>KP!exADk_Ps%^IZU7KnCRnsF)lZPxzz{M7u0@hnGKxP3k#$lflBH# zFa*pth2VK^0ODuh0hVXCruXyO2ZKq0a%Zfq=->Eu3tbevw)l)kL&euPEbC!8DwKTW zfc-=4AKi4LOYXb715l28-O;sK^XbI1PjKW_|V{q8Hxp{V`hxo(nKXm9)TK zo{SgVk~SPF)}IUT1AuZaK;Lz&?FWWLxQNP|8|{Kps*!U65*0VXBI?aR$>pR)UK7s+ zSf+swfD{)|d7E)$J;TX|Lnd*th)O3VSN2mFHx5}i>4S*4ERzlgL@I|bKuNE^;6s`% z63Kamj@sR0>8PiELM%s84}cO!HS7~AlNoF3@pRO=9?!~Q9Vo<;%cQ@khvh=KIq9Ds zNGI*Efy<=iiDRCF@A#CtiK?HDc^yLV-K?R^{cQDkbJ>L3A!^iO`Amo{lhP=%Ols^x zvaR@&ZJ%X0-x7!Isg_L4FY}X8j04e{gK;w=C)Wa|LMr{C0dio#_D^ZIPS`d(aHIWZ zKTVYdN@rKP@6fc!QE3x^li%#G1Xbk>Wn*#iS9=>r{Ii;6?nfE=>$i{*e{G?mxZ68e@)`5zmhBd zYTRnbBIgc6#Km7P-$aVtj#5zKub-)JeuQNfZzdog{ULKU2zrN>z^w*uBaNjd{;;(HttH1u5;IFL^`+9$UQ581euP3R+ z1~4J!uQZDItFep8Hh(4CKH{&Js+N3x2L5_7A}9Wu3Q6?WUSH5|^w-6pwB(Z+|2|)4JYqyxc zCW?gpm1@LalTbIwBX1`Cb-KsWU(foASo-S_P~xwKtqT10c8{mOmU%q=^)pcFuluWe#h~2$ zHTpFb(_aq(h1++)6Mww`-|;DP>l6HS8A7P{*JJ+KUklY@1x$$fD~%%lYU~oS&0op3 zkNE3s)l#O7^Pd(Hdm>h{ULdi%GG6zkTFprkL5C=&Knsu5pJLM8cXtM90Z zzPe5WFNT!)>LZ@Zx;2TbzDln6s&Q)}i(Gpg5f@+G<9kx9TdxNtzWRdtMQj#*wU@`z zSC@D!eRUTo@m0gl2z<4z$J1Aj`+>UYt9?MJuQt)9J0Hr;S0DC3`sz!dRyy*;SKp!_ zeRV;Cuik+W>V37tKlcS{)nbKAi1{jwBED+uIN9c_WZOr4wPm$@-%p=`uYQNfiLa(Y z5`DGPHrj!{+6$EU>fT|cNxpi&m!Pk{464dm(B`YiRW5Izrb=p&0GAcrk;8DfYFY)U z<$h^95fZGJk}ZQKW1pj%g5RPDgoCCOh*^pdeq_{S8gl;Y6v-Nw=B2U3Oa?*C+S3I-Xi>R{o;K1|Lj zL;#aHg%p@&Cm}YcFjjTs%udLut^i0*y#Pw8it!4J5m-0cM~gYN)?=Ad&40F>nyJ_~ z^qCnu%j20-cLF6<#W+x!Q-if+Kc-KsF5dKD=F~<|aTmr(PVKoaIj_KzkabIVvrWE zCm6n4of-bP-^}pytr{h;F4L=`;U5A*ipYFWQbZ~hyTB zd;V?{3t@p^VnM*1SRhy?77W};wWr^jUg5QKVu1qX&RC&|h2vGiCKhyZ-fzU!8N*8z za)U*^bM(kgG$TuQ7sNqI_gGNn&OlbW(~HLILKKM8MrOLs(cy>oYUf(c|f4Q#_tdwj7i?*%}3YYyw&jf91h+vc`YW$-+2s zvNOTM2X~sNc#4zp=9!l@rSmMO+CS2Q{tk0=)4ke5^MVRDN3e0kf5X-40s-u`0zzz&s%=-Y4oT>#SIkiEp zP~&r|jgJ;{>R-EwWlr4#N^ zsXS0|7sg3WJpi81sf>SWF*(n;UQ_y`$(}qR3x$!Ls&*eRx^VhA$l?Q{=NwK8vQzaP)Jdl*5fXH& z$d(4f*axYmpi?CfHW(=o%Y8!lsc`ub7cmVniOau_U|d)+T;doPcB(pSAccSgE`k%q z0c2sG98FUf$<^98PGDVEuZk}66%gVgjnmT9MNU=hxj~Du-J5|faw|~MVibZ>7r8@$ z_nUwg<~KZ;F0vj}+=X%CA}!L@MXpov1`G3Ln$jEf>2jjed@5L&kAn&+%(sIocLw@j zh1oEXxyb39=wF@9x>KP-7HSM~yM_r1xArg=X2PT}r@$;b39-U_m+Htxa6wLe27u($ z85x#SgA|xgVBHoU9&_peAS9>ef|A1glwzOJXJ%}I$1|r|HL{%Q0!nkLtCspRt@LY7 zUE#sZsiC0aE{v0$dXtJ+?at8fLOCTxXqhsL=fbeZMMoZKMQ8)Wr3fWLf+9q=6d_}; zQcXb-5(tY>3dC$q2tQJUOhdKA<=LYwlTX~kiqQKSNX{Dx88ZfK$(a01%a}iP5SmY5 z-NRlLGiC-5k}+R`l8nh#`?fYa$By-QX3UvcmNET7X~x{Ez=ushGv-MTX2z6&!sVtR zoMg;5RK$!qO4*@|k+sg>G^LF-A?}3ew?0-ZLXEQ-E3S2(4XWH3$cj+Vb4h9u4OI-A zKpk&ulqzZ{lt>{mNGlB$&fn)~!dQq1lR}gNvkWD~3en!GqZ+{lg=hf)l2_Y7NsHKC zfsuL4tHXS>m{$ikw!FFql;qVhitVaTod4(J$GlqN@oW*dfYQ8rQtPR4q3UjrCREP6 z>I^FG!Z^vRe&G4MI$y)HyzMYY>BcZJL(37lO;(;80w& z&(&Z|*dU&--rY~1sJ5T=F=3;4h*xPW+hipJ^Lf5Kougvbr$iTSZ6JPu7hkQAhQzPa z9?T>9#7KP4W6j_1^5PFEt0D0z>Mb^QLvgtz5P#N-&ryhpdykN~m+4^4mhrK*peT@D z=%qhUh)E|VeGgq;w>5Z-GpYme8ZX{KA<5#n!g>we75iyiH1Zu}&|&H=cX!)%lgQc8 zNbBQ-lQyvAVb0EFrTtvL?a4M-5O|6L{icZ&q^;2td1JlGAp&fscVJ^iaNN5RtK}1M z!-4|kM4Mh|4^?r_&}Ob4AL1f2O;u6c$4=sJ^E5=Pv1oDLg`o+=hW3n4U7(~!leoJ+ zi8d-E@POmhO1AYZA>KA7A+EdPe2pq8OweeZ#2tv;Es9JlD)6R|$XS<&h^NE41Y*tP zRYP55c5<`?U~K{c?>D4lfxAu11Y+nj9tGE0p`?9dYu$O>a7rW^XMRSa8ssOfSz6@C z6R-)Z)ydJwxkYDS9|pdq+?{(rVC!9Wp^Jh0i3c}tj*4=n%bOR8=*^U4^k&MsRk)dQ zoWFN+J3w=tzdYp`|Kgq&X=wY0PRHWD#-soWvd6kkCvv);7g28T7g1tKmp7*{;FXRT zxjALGm*?G*CSMI+#wi(fh}bHBw`BHD&-KWV)akV-%iKyNccunds!v|E;xDT_p(Psz zUbsREpLzb8$;FD>q)#MiG9oG0ql^PG@p_anI76>TAx^GG`PobGdKBz%Rh4$tr2JMx zE}HyOc}>u&@smB?t?I&Hd1uvWt*DN7R*mu$@2p~^<)X>3s6Vfn_YaF0@2wIs-dnW_ z3gn{66fwQKN~Cyql}PdKDv{zvli!EpX?Is0+L}@1?GYD(lG`H;8!1J5|EGJwr)LIQ z1p)K+2!hf5Ma@EJ#doi64?&~5CgOaO0*qP(U@OIV5CXZ!iMfbMMGHkwN)&*WMGfTkCEP^$& z4pq&CshM>!QS6mHgSc48r&^5ls*mmhB2bp`u2Dc73bSXqvE7oF@n!)p%Xq(ll4ZO^ zk?=Ae)yOhl5-MpK@6?>Ok0^g)ywd;kRj=MgZr`@wxK9O{-L0|)cb6=mH^kdr7_e;YTX@CCN_5S>`Rd_MS z<-t1DK>E{#Z}4ZJ9lAdqi)WzSrn-v(ayLZ(gxXTaGtfo>l6(f*Lkj)pGtll-#69|i z!i!F!LY{&4BNWORXkl1z2HJpj3{$RLg5|j)w zyDRo$eP+ha^mrDr?>(M_%oaI_hAdQ$RNxpB&`V-W0*9IPu2+kOfpGcpDmja|G z6S&A;phsqZzgI{u zAi;FVGO(pFIOIU{)SU{0$(tJJHfN$2@d`|Zj!M~9<68Q9`}C@*)9D5QSqN++N1 z`fIXZ2cBkzdA*hOGzO2?8r!@dpBw> zJqM?Xtl+yI=SCujzd&j-cChtYN@@+LFOiZhE*l%5Mq<<67S{&U)u)qM4VxY?o?6BZ z!v?hBqz-!&F~AUfi|c#@t`R$lxD8lXd|=Ngs4MaArFZ!55m0Yn)V9UV0d-Ux?C*B& zuBnm8AY`3$Y%5!=M*AMw%Z*)&p7b?OeukgvT=svYop*Q@#ryX6**!T~ki&rkArJ^8 z5C|YGlmH=t0HK6{^d5Tez4s!$_a;qx6=@7j%Wk z&V~hs_;*--`aPoBeY$9Ma-Dk#<9k`;Ul~ht0q{ zGnLI?>IL()gKk@qP(q4Gf@wd>sCNEzC?AoC0=6!at5W(U_A+^=e%>eew&w^dGbDah z6--Mw6Ac4bD~UhhWG0k;{tPU)Joy3st`bU&_|ITva$~KCcAsbr_UjeC#D5P<7U=_` zYxvV@L^$b|1w96ONVEsRKf%GjgCgRe4`wn@2jqWwWNALkRrMEV4y-U+IUupCgsq#&FkLr8Fqm*@E~31GYNqL~z}*mBu7Ga62WkOkScjVV z&{u@w?u%*Au#U|b%BKbP@6<~R>m;vSnvn=9taBTP0hz*jm_4yCk{zZepW0!1$tx3) z2fPKrNC!BqH=bAyI^-<2x_w~>9m=P6&|&gQ1m!zpoC6#-oX4z?p-<5O=z8FYg(wV8 zS2{BdT_)jPI*Z3`hPUd;xxG%D!2jsc|Bc~o~T6iH2VLS@Mdg_^+K%)%4D#B;+ zX?ioAFk*a)AEM_yUIzAzLfJ^mdm@%kPa}BVlOlMw9ymS4Vcz0cF$|(*z;DttgOj%z z#p-Dog9P8x55hB@`6>R-$N}+aYF_(4DBr;&ld-EB-iT56ah`cQPQQuBOnVH>KsCN> zXc0c*kSH3TcZjA%1XE{ldOp*)t|czBtIJHjYD;mMLtSR~9r+EHA?h;B_h=+8bE?aN zzWVKOnM+-k@CA0pWvIF==Zi$iM&wqP@xJ$yaT%sAYx@3Zgv)SsSr8tA2IAZ#1?CXg@RQ507>nkcTPkZy8eKC7?05+-l6Ka z9Y(&7$k*rx*smv2Z{#~lzTf^r{0(TDi2no<@w z%j&}O_E!zk@@w_wU3RxWh-nse<#G?lYbU?PNyaUA&+xm-gq3!6@HDq04jEt;X!KnZ z{QM0Dv$_g2O@bTL67{%1bC!c*%Hy;ZT2{oj8?Uzlja9934_bq();K=Em_Tb2w(sNdKq0OEmoH_f2Gxv&c=DiZm z{2b`821hO^E1ZRmg|n!aa2Agc&XV_qv-FH`mi;W8eg|oW9aMsKb z&f4w5S@)H2Hog$fmfU$b+_re(>}VyN4~7e8*9zf$_>pjSUlGopUxl+b0~&|m$bCE> z5FEK*3uot}?7}$^Bb<+03g_TR;T+m5oWm!DbL4?=KFxqeDLC?2G2tAqC!7=gg>!Pg za87L%&S&R^bNUzIeD2N1;m(v0&e=raoNF(f^W%kc;eFv;JT9CseuR@f(xi-u?53lV z!c9+&gqxi>J=r635*JSP$lS!ml07nbGO?X<8=RU2 zlM-;AGifcn>&WV;8M%nHf_1T2XcL<0Jvc%KBUbV9jHHq(T+HqL!tyxSOxoPqcm+1Ctxvv_Z>)>SJ1!} z*A;XKz-b2(mcpo6JS>f%YY^_)Vkke2c+*hGZ@N}+^oXOl`WtE>lBSB3<3&OeilJbp zT`Q$&?{PxH07Nn*%OxN6LqlJ1e$H~Ftz$jb(KK^7N>~dn7{jiyqqwFO`e-Vkh=ZFD zotX?Y|Al1;^mfB6Q}B+Z!sS1MUxAZokqTGX!sf`Ra1R%;9CtW*_`KqwGUzveqiy(a zH;&MqjB1f>8ub;4EZC;aU~z(a)CYQ&@dJhN2z1Q<+jtw4c;SlU=Ao<0#?t}Lgd=qC ze;CIv&&~nN&-;T>k=psg-a{gaHqUZm8oO=kB5a{3{D(Iww%hD6g?&48V&C$%Z=Uq% z-WBaKf_*uFU<=O+$B*AjWH~q#hFuRkp)X@R=!h=ZBYyWAUKe^%kNN(+O^Xn>>$hw_ z13Zf0-YZC}_dEQjnX_R33E`Ab#=%^s;w>h}@j}xX9qdx5c>9nCOmOa9U5-bYZ)D&YCNNHs{u4V1S1Zq#zv%P(G5B-Qz-g${|g`#Y*%<^ufiVh6tzRc;S@7XAC^c z3`0VKi$zZqPTASQDYr~GG2z0gP((PfWrY)0ML3o23n%`PaH>2!bvNFG1I~{~mx3_TW|0bLU*V!pv=B*@lqPx~+r|d*H z`RC!oib_;9HdiOD&|VY-I_Ai6;cEQ!gv`XtgrbuF%z!5#CW8BL*j;wX+t?JS4c{;$ z2(>G!ZGFhbmT;VQcpo;6b$r@!3r@pm7rqUm`q2R(M{$InfUoU8fG)xBhVAb?167L> zt16;~(NDIZ8br6HlH>CWXF{BCCN>t% zq;bNTx=J|H_X}s%72(Y0?o)8dIX?6^gG2p{({cZ}UKQ^2} zxB-QPGpMp~1~(VZkS@X*I$AiR<_Tx?X5oxEDV%ZFgfsp(;k=szU!K9GCPfNoaz!{H zA!w6Kqi;Ucm6B8OpJ`+wqlg#vh;Jd+BVW&oT!Yl7f>w$cGq7apZbtkyMI50mVTio^ zfg>wMX_^9r$PF`Da7aMajWQxUQ65|H_TPx0ny9bFu#t#1dRH>8L#Y}VB9oI-_9&V+ zBb>G)LZr$tE_TQDP)?+%-Nx|Ae9E=k7%`7expo^P-{aH!N%(I}Y200-b9G%a#tkfp z)2IRP9nU#8%JS)iLO3nA1h38P#scFfMC$H|=f+sX@gq)mcm5V%EU!#=rpmZlvILb` z&zDIn$JIHzvD`SH8D;mO3_%4Zw8IB#NturVi?-mREc%PcRDs#}Oi5p5Ef*b?r)r&H zY;V#(ShLJN;q-S6cpNE)Zx7Kr*3X2u2aeDkEaN496K^Zycnf@M3B4b*p^l!HYTknW z+18ApXTpC0YrRC+ytD}S+&EisC(^MQ{vY^j@qM9P{Oc05lkmS}YhKPbB0h|-J>&cM zA2f|`IQ<0RsSQEDj^r7)3uRGydK5=a95QlIKV&5-Mj6MVIKuTYcprE&sfY?xb307v)IA+W<2lVML9Dka zEtb+>LrVJS1Mr0#nI>UVJL!LxTPV39sqp8a63`7iYQ3W!Ym@a58q)p zLc1^_9ugS3iLR7UgoYV1>jp&uDaV*)D7Y_(k~A6RJP8GFP(!FK{E2}v@Q$YVb`~)R z>PUyENFUY$5ksC5xFa+l$}(0(LXd{gDo`ua_#^1yh#2-lJ!OZNHvyl3_`w5B!Pdb> zB0U|D9mYXI^{-p(4glwGM5ql&q8KXEDFh>>{+ekiZt_o7BZg< zoskMQ!ugfu7*DqfLR(A+(8Az>1=fl&ky`!_x5bqMX;?>hP#+B%2z43`Rnu%v7Encc z$R)Fp?s0=iYXEMtVXd-kfVNQksj>w!s1&7Vaxc+&a913*iWH6#(S7(nvlaPVt8kwY z1q5Ma42Me4a6ABbdkCu+i1I-xpHlV9o8qn#C4uSuUtEeP?+^_IILm=WX^Mgnjfpaf z?I%`)*_Dd(N1hTLhkVUJgcYtNDWd$F=n;b~@Kmoz1z0mikw%2HDR z9a34UKtBg@m)2N1Ls6qZOtdNFO8`@iwYYsE*()KgXTZwWzLv<>T%+$QW#I_KQ~nkN zu++$YURn47;(dP$i@$<}b;c>H9ip751UUTL{t6_h?MA>N)pkUJDCJP9wGz}mBLr=Y zXou>6Xzoy|wGz~EqtS6?YXFEb4yD?m0mG55^G4e^MJ)xf-l0@0DySPqE!;5?;}H;F zrKDs%=EnmCD)@WGph7BzPrz!q?A+R~9Si-%h{MehrbB=gNQqk1KSrwsii!tO-=XZ6 zkA=Ejm)a_{2e2UyD)JpeyILaOxm=&1lR`70E_Dc1emuluyzN?;N7>m8;)p}3k`Yu{ zS45!7=`|2{9cmoE?J9@?G^4g_O%+AG1`!l$mj~NQQGUW|vg>-Jin}=2c!&2dKY@02 zZN!|2D8ClKI;TXf1Ppc6#oZRvSP*j^%D?=C!P%~INTNWu0^9GPs{FF{N9n9__1=i* z_dL`)4k7x2jzzR7%pP`aUJmvzaOp8(rRu$4RaF$&CD-R@WJJUfz{)tNu&7F1p!Z#G zeWKD>7g+Zj5w_)GymK;HyR zz&EWZxBdt)<-Y=1+4(i#DTa~-zZUG_H}U@WQADD<`(hM91iFdP%Hv8_^&`#PAa*x&QW|%u#?}!r^!i2ck!kw z&>93d^rk@kc_zQoRTb#%UQz&|egnl* zAYO~c9e2lp7FO*ISOwxq3*&cpPdp)4(gv^;`V!W;4qi6IvChw2lY>|Kz9XR zpQX?>!1g<+U1HYF5d0^BnYSwb64={s;E`Z~UJAVQsX|`?^WYOg-Dm#4*2^Rdnfh}T`>G5Fazkx@B1)AAhTv(yofqmkj z{s}%@4pkzL*<_nSzXA5pLH!df&=TeotdJ22Hqg1_rEvdM-34FK?9fb^E(JE>4LlMo z(7NX9MG9>VtdE2GCpha{DB;#-Da`7NR7?f7%t8GVEYLn?WVo`r2iO@0O;f^xA7yR` zQKo+c`}_?&5-iYJW}feqX>URFe{j5^O58n$1g|vRA8Oi~jA%w;fF(I7XTqwJJdbSb zGFx^~6Um)$-OoWeZ-`q^m(1QM0TeCTKM-pi$~I{ATLk~e{OqB!dJyb)|HaEU1KY4- z`p2AyT#A^UBNX8Y_q*d36_oA@#xDew6GW6lIqBg7xA+q2LeMe`J_&5+|KerQm^@cw z^2|^?`Ie#SKj7|_^~-NUw7fxh}5 zfi$xdqKl{awRkoTxL0B6g^bCI2TH`mmvVqwocYJ}d7XaU~`< z?oe}3eVA-GTLx5bGbbi7dKpIEIy&=H!LG7+&aUD`&h6}L)kMzIk9fVy%J`QY=$pB3 zE-hYhfiRqh^dpu|v$7EQwhH5<#>uw`lkgP=Nck~M$Q6jc9{@86v%c0ep1i|S!Fs4R z5l27A|0X{IA-SsJkHVKOp05aQAJ5#Cj^-5SOsI&{n0Q1c=KpwhyL1_z-Ol+FUYVsU zv=EAE7(B&Sx-5sOPC4;zC|%K@xe(Xl2%U|mguDZB>g50^Vu4hl-MISLCNPo3!)B#x ztc3vv=}Y|gE$a)}0(2hYESqaQen==?4lg-+G-vDf7ptHAK1^qznjm&FCvJ5 zd(Yxn_BLX8_c(_Cy}si!3otVj<@W$<#a6?OC}J&6Lt*e-H1!fXmS(h zugl>ysSyev znuVJgU0z+*s*@ErH9A&Zx+rNc?nLxEw6&Nln${?qq(itb(e;&|p7cF#P;?V@=}Nke zl8;;!?ctALf#8TF>$=`~rPJale ztFI9w-3q~}HRUvFN=ON;1Ec6Ux)$1sMzj5u_-_}E(4C9%D9ag_(B6Em)uplwj>S(L zPk^}kW-4ua7ETjTVap9!Jy_S`5jE+EH6soghqnQK2%s57R={?(TkzIuefcLSK7EH8 zqgrI|A`(h5@TtS$x~556IDL#bvVZ#?ejpHa3!yuM>u(_f&L}RGQ4)G41Tngf(C`9THVGN617a%S*i&mFTF>(=ia~`y%wyvekwN~rs0c6D} z$(@ijBk-q;+8L{B>)Le$qA&0tpM-AQ4C`Lbg684u}oIk}YHN+2w8EDeM())A|-h)yuxh(%UL9l=w@u`LC#-hqS#1#KA9NI{*2y_$TBL`s1NXLv%bgjr7%7}8vgCnvHDr}4SyrQ;oNpT`G>}5akAHuYbLYQ}{ zJos8xn0C+=%BQjnuq-!9EUaa@ z$ZyJ+>Z@@cMSKxcofhLFv=Ns@Lo8J4jw{?LayP}RKBoF;d0B>p6*|sr3uf_Kxmn4G zs6uX6NU=Be~Q7o!st z+wl;e@p#Juw;O zn-2_rhXh|0eh(eR#W@En%!Cq;&ZLbRD5g$dM_XL5MbanL^oOm zRs0HQNlV}_EQCRfWWY)T&(+6vq$lrSs*f#HhFH_FAm{31dr|xu{Ir09_7J=ITi~hq z*uhl!cV%G$#A*H(1Tcn1&Q})JLEP$Zf#>RDr_!AFRU%J9Jm(MaTz%|38bzuc?m_(7 zAK^e%itI|*qVsU?fr=VlE(~Bi)3OW&DJ%50| zN@72xj{DJZ;3&F7?B@^gTz%|*`UK-=0+hqZwB|gM&b-BT(d$+PHUP*N2UC?lYky>R zqCNnNenrh(3Sx^xab@%hi*kAie-}A3`Z@wV0ql#EC{o9hP_g^Mmu%uv{)2{$;FeJ=CuzC|l7WYB-cg9RH_Av}4m52lJ!sS^??iVBCywSsXyZ zvKVc6%zF&fNj8D>v_MZFHkZ*1OTco$AgzYDkpb)Z>#+%;BaEv#@mES1_!Q!4e}G4) zV@n&u@L4TN=QhM&81Sn#atu4Rs_`jalHxfxE8ur+IQ(yO1={;9BCBhxXs=4A7>JlO z)XG0WwKl@>9VlXK1fnfdDPj~@!W~7j8lH0dhW*ZDZe^B_lBT35-(KG{ZV|% zuUXFn9$FDEX3tM$j%!*N^+Z$W`ID|A7k4-(W9Oi%X;q{@f3^JqUmbH2Qt?iLu9-*S zsTdEK5a@3^%wDJxEG6yaAc}+BFcmTrwv@qE2%_LitGra)QXsLTD- zB%%#a_B$$vO_7#HM4vgxn=p4mBh$9>e3aFtMorSSb1{OkG;ctO^1fF_2FB%jU_CY-CZ$SXfb!0+XxC-%m ze+%4Y@O02yc2bG_6XI)sfV&Kyp8AMG3dj+UCkclthYG}92G1Zpb5<2a48+R*0CyQY zqxCw~@b^hM7cC*S_XoH~;CWXsJsW?1nt_oJC-?*0Bk)Yq-$#ogfcGG-a{#$4&$C4D zACAx;Lpa5vxDQ?qfEvN;`#czILKl&)L;X1=;Z+rfSMPbw>7`ZzGb&>x3=VZer^La)q9!hOq;6S(u6kQNuQc=ZTl_dFmQBbY-R; z#I6ijg~u!OJWY+$8I*{yVC&OGlLFLt6F^s4Ck;!rn8RS;g5=2>j)xD6r#Y6*wf zDcc@iljGTJoX4mNRfk%~Ch#%Oy}1lMDq?d7(du-DHpJGw>?doY>_mF58<*Rt25K&_ zwW&}QBOCSnY#hNTBz*+r^Hi8>I|cUI;9{ejK%S?}Gk6-gilPrdEr4`(FmCKYaOcm{$u%VdN^K<6 z2{wUW3B+Sc)^o^JeKXhOWl*--s;KO;%qmj*>flbfHh;|AF)$ZWa$0Ws{1>G8+nD7{ z{0Q~ALvVM&vXp`E(*atHZ(W@-RKp@59Dcb^5pCDufV1i!jAWzb0akNh(fq{G6SONC zs_VJ&T=TD;bZQHvi;ZD8u^pNmPq~06O=aVv(|D-!nQ)#n`MZjWbQA9!PxXMhhd9D5 zVD{OTyj}U;RHR}5z+8iXn`hAlqVtfycM#DBNXBz!ajgTUj%MyT7&kg-Dx-pHR0Evo z*>N{bbm+J#E}3EKoTnAeP#Q5<5HCPZCkKQ zoKq6=TSvqcSA++-(x!?Dk*d=@kg67a@`5!P4KYzekiZXdUTA3XR0(VV-{v?%`=v}^ zclZsq{k=mtfnnAUb0JMQ8$1$1{q8@YSK-O*E}!b-cPt`1X^|V~mAZ=g54cR$*ZL0C9L+`(~pZ z@_kG^_{}@|)c*$RLE<2KzJjIb)C6q#bQr&Xf=31%p`VCyQo=E!-0&=J3vzhyESHu- zP7_sz+#nTlnURXr2G5`G3+ft&?>FiOrmxLu2?bB!ZX%h@(&O0{gv+F3%ThT;5-^%B$X&RsND6g*_aSikE_o%O&&ZX|*4^m%w zJ$o~p^SG|Bf}Wet`Rf$>XGh??0l%ovx0%Na< z5T`TnvjTV^)Yp@a@%tYBv>yL$bAUKHn-f4k>a`3nHsndC&!AplLdH>%8dU)?h$dHH z^)8gBw(8{|xIHhXBc1Qlr}-H%Yh(NahcqCOI4XS$$X1#jZ^cs_NCgKY7{xoS+1tQw z(2{-lkqNS(QxhPqY|J8VQKLVwbYCQRDAX}b$UMi}((ygiyZ$x=@syU%wrps1un7tdCmrcw<2mIGVvFU!-o*(U#A49N&YrEwFjZ;-=SEfjm}Ve`P&eLOAnc1*_Z-#wqqlnjva&z zQ$K}bc_>P38&t0-@OT3^W7B2(MKPZX(*(1+Hw zQai*?6cd02^%`05*U3db7x={~#3K4Z3>C_1v&%0ek4gDT=;ymwAusra6k=)p+dr)v z{m2d(N6)(>WS)RN7+B(&DTCZdnh%Gn{V!38HS-*j6Gxw-Li#ENj2wekiC{~DtC)(7 zqwRxdMiyB3M+kl^?3Lsj5IGTc{)EDPYx7%Vf*260mN6J=! zf79$M=X&QOSuG4I1Ejixaiz2xl@a(>@FlyJU*@#70@KamRIJN!Pkg;xSujp3Q#cXG zvXq!GCtr(kBm#_bbr%GU|GbbAdB}~()89ck$f_!rlkAIuoqAPBe zPGiB$a5$3@r5-V8C6q0W>XqsMj(nv~hoF3JtE#smN7#Jd7@sAPmJI>u4v;4{<`q%M zfp*^p{n#`48m4p&Fdc|PHH30t%(q2v@=6vW6^0nafXu1_cIi{BW_;Oo$5{3vyu0cU)hO(L0_%r5zCWIu;c0ncgiFx1E8D z5Wn`fzyo8xvwG(A%EGS@U-(-Pz(sv&pt6v;A;$l3*yX?zUA`~%%fG7rTS$PZE?Uct$^9AAWSFGSr}9ba7;ai|FWsba?C z9EvIkqO?QtgNvRFj|}+kxD8Mu>+gVQ;ZWjnR8%$N$wg&rAc%Jzier?Ci;)JOxP2a! z<8mO|9BeY4Z7=_)MiG2Xjqcrn9Ru>YjUiDy0pxq>)-$W*Z-6m=uuA(e2JVg&<`eDz|vU`@eZ`ctjpNL zN$AJAoX20G;e8ac@0eq7k*qoExxP69#7Ym1_~{tZEmB;-b##7F`sL~EJv5U11{W~dKNh+DX=(M-M$8Iyr+ByZ--)Ihh9 zKep|(CcrldN9e?PDbkt@zpl2wcN$bDt-~NpvPG5FDB@DXmT)Ve*olyKWnQ)BdH%tl zpELKM+hrEk_0Iq&zQ}{6&05J#uUUOe`qUOkDyLnH3tWDH?F*k!aTFJi3-IDV z^H=eq&Eo=I+-dVEaS-efTl|@L@8pM=I=yBpqIiCT36f?CHzHH4W9LF!P}T` zic((_b%4^xQIlCMLmOd~XoT%=4Yr8yZS$zep1BNi@(Xmm&7a6XE_E>oU=|TsMn-h; zrEY#qoKf+0j=hjewnd;yyOHJxbdL)_t}HSSlL62DFiC&lzkfLD4k{;~d<^_J=0DM5 zX2TKM&0oM4F$LjS+7`rihRC7_c9y6*l%|f_2Z1GGa&(HjNYoq5@RXdTULl$Rg&SiT zxpy!ZR4F>lNh^WzUnu)+RTUSOr}jhX1nOV@jlcGT06JX;bIs<^8y3V{dcl{Z@tx7> zcc_0eA#)!`BX1%KuO9oDw2MfuPT7*7@?jCf&x6RKp9t19er9wk2elFtvY;x`#it;0 z=)aw2wF#8=w(1p+Sscy7b7tnz&u=45R74sDWU7PlxDPrq%}~M3eEK{0*wSjqyBvhW z$&#%|IW~Z+rtf>j+-WdZ98Q^f|8pQc^x_Soe+!tO?tuV`JlbrFNVTy?c98~;Tk zXLjeh>%M^Gnj=IxV`=IrEL1f|$}7_yb^uqS0Qyw9RJMC`N3FI00Fv*l_29T@C$?<~o^J;Ufve)h*wWNVDT z;|MK-xJcYkFUN)UOb`<(5o$e~u>2=eJNWgo{k;{qz|9K?Dqp_lj89Nwe#A9R2Q`n$ zDjWxNe)*bn>g*%!8tYr3edw?A%hg=ac^7FlImB6LmsuBSM0laEuKE#aFFE`pXfJHt zdT;W}*W5H6i4aCIVel>(hiydYdzwKPMoK`7wROt~Z}DLsnsZ4RX$+v913f|PNREjq z3-jUt+-PBGIDknEiR^k6)QXeyb@D@HX%zq-1Xbm(ARk-$_DP5?Eu8@HMH)-Idd|F6 z|8rHk4*@(+1?8n0dtm9O3wu#~=~4Bv;ZRYDyX(}{HaYPEL@6hHqidoG&{{-$;bn5Y zG5NjN9J}e`)$^_XVGq1{*he(bJpO9l)w#NRcLR9`Lq5JA`)Z9<}W%w@bYEwtIkhUvUoI}=@XG= zy|S#=&-GJyUYOLeY1ou+k@bxDtC{UIEgg=~X+U|EkPxzA&*@z7Eodv=InXup1d2#8 zdBMa(ukA1&K}DM_OcXPyHI#uVRqtY$QMQ_aR&b(0(*Z7a;FTPmQkxpI8OmNqUGJxM zGUziX-#F@Vl#Gm{6iw!QE;Q&T$S-U}y+6XmGT)%&8z)HH29uNt?LsabvNXIR5$MO~ zfsL)kwFiod22sVKL}CwiF^)&tq)V8W1ksk>Z-zax!r3Y`UUnW^2J5qt>p(jL>}x_1M66)^A^;xpTf1q8Vg zzanh`10IatWyPT^$N>s7x9jnBWuX|vG7QMNqJT(O5FTn_p)SNGjs-bDVU}> z{MO$Bul+F_x&Ho3CGvNOfBOTx_Q!1HGOTh4!n9y69CjLb?T^{nwQ0MGA{t_xKfr5$ z%s#Gk8C5QtLTv31@F0mf*p(ff8NSOj6yg|vfCov;5w0_tbO|hlxY_~a${us7tJG%P z+Hi{u&@>q%y=hwgs6KxxUAIV$n2CPLdgN8$xWQVqHjv$f)!XJQG0dJ#>KTXNrqv=w z2AoE3pMHS)*ddgSN~r1P%zzH)XpxTjgLF95^CUOhG1mr+GEt54Kq%mda$!%Tp(*xVXEa6*pq-( zCxLwgKMD(>uCNJ&=hZys8TU9ek~-~%a>7={vm}jFqyp%Y1pP^O*0YuGz}&Vu zSgDQD2ny7je9!7%P_%AVW})&@pdgbX(NgOa45g^8%KPdRZ$-+#85tU&cSdg<^M3$a z{13S4I>6z^EWC(y>IZOqDp(XU26>;NR+bNZj{B?AQZPH;z{z2Niqv&K;3|Qiq1D&v z6u`?VVdRLH51F+C=VjwkdkFb?8ibcL1(l*3_~gR+Ck&@%$Kl_&$R$ldN%YHeYe`cn zATc(E56s{BL#%D!PCWLU6P+4EZD$j*wTq)sdx3QiH1Q27v5`Qgq{1rFE0jV|Sz|AH zraG;HyfqEd9$%wD^^AW+yLk-qg*3=)w9n?mz&ZHV#QZnpr)iMwkAchxoOY2Bvj<-N zIQ;Wok2DpCvC+jlCnAj zH%l|Q9_6KWlMrM=tuA<6=7U>h1>%deft-#wZ$}_L86&nmLpu;L54{^QtH5T6iHd{m z2tMqIuRiWZmyZ5p3R&9`T!dY8$PKY(KE-wf4~1fHN5Em6?FhnPEDA^H>A8rmd_zp0LHZAXxQ zn$p)o+wADP9f2s*kjZy3)K#f%m)@vs9kfcrxD5D{L;TvHQom-n6koiR`t#dL3^G<4 zz;9zw1eFHzeP~5P@Oh0NS5mrOcoJ}g9z}abvg51NX+)7wN;#_N@P>=dLZx{{Nc9zJ z18B(5DK?=>qSE4{uSt813{X#K101~u4eZlbtF&q>UNm2`J_Fi()gM>Dx{hV;b4 ziP6;3eej|9ycC`-jHarg;h#|Z)X?yKM4*O-f5E9e+`1d_e9Uo~(_qH(A3$f}ch&ay zW`qi{)0bjs_yL6Hwx|-ACH-+&i0YaR2~k7C<#8$oUO6FJ%fi;x{xbFa3sw zYe0VoM`#&wPn@CQw(#s}3*HKRQ=FmU(NLy2Y86(kq2WcgzbXMWHgHsA&)f^y8XC@x zT-rm!oMmnXtf67fs5La)V6ZbZjK5IqH#9sxovvMmNy?0Gq3k$96ID*Eq2a>t{Q#fKg7BgflnsZP z7??_L;&^D6)50#t#V#9UmrILXE)#Y+_v~`^*yTII?lF|FXfnBV5ktdVb+s(VF#w98 zVXnJsXjqi9Jv1z@tf66fWep8;Ce+aI7f6mXG|Wwe8XD#hYG_zAxoL)mnYD(7YoYhX zB}n$raFv00>){B^iMUAIP%p=&*+av;X<`qXu>2>}Ncc^${k`E_;O0XFwT6b1(Xo7u zYuW&6JCg-D4(M`dINYOazq5V{+IfFn4h>&IdsvJ^+=KQr>mrQ^FNcPwLl1&Cxd&lN z6o<+K#t%6Wa%lK%d{zr1Zv!Z4LzcehFaD}vBT3Mj+Iq^N;fMHe5=Qz080kRi5fGN- z(C|#W&V{9g0M;-hvg=il92&lb-h#07F@RHPEXkqagTEdNE8Tzka$FxMz8%j}1u-UbZ&zt!6*i1>~5 z_7?XK#4z$8?jMLhu9IR)gP$0y-Woen*V~s+-x`8Uy_$|J%6iLjX?DHM1vQ^dSpJi# zH2mUif3H4+>+Ko@wd!r#jre=kxTe;iIx(3J3_+Lm_NPc)+s686Xz%*#vfkEftZQBl zu@c&P)yg$Ds;B zRem|8aRxi(h?EorP}+fxA$C}j^)@{=?-9wV1E4uWBD-D%$$DFLy0X+C!00rVWW8;T z4TFTG#Q@$Wr?67qYBGZxXlpWK9Ct57EqtKQ;PZ9i+=}Uo`JBJPFqy&KC2KO{ zdp_s&;+V`}tF({EzqIeZCU{!;M{hOU|K!P9SIBM0>S4)ZQl^f;`Ejj~Ycq*T45U`E->589d7 z=m@Z{15f1WoQaL`P-Z#mbUzgn8>^x0a@4*kB^ie^v2h&o7dE1LKjCU(Bcq{f^I(!5 zf_QFIUXh3j*2IQ}PbfioM_`ve9I9kQVia}M7>)r&L6ref*`YX57y(lg8@F?y<~4=d z)gid_MEO|Qzedf&NYrQ`(;Q3~vL`m8FKgZQ&!!JgO{13*{^9En9hI8kp`jjk%av zLr$GU60XH#_D{>tTF^&QG zG}sdx>yRC42%(J~+PXPvVxu5NjA;>4BBmPGai=n>n5Zts{#K?fAJbiKi z>Pd%CHq^w%G#-Wj4(e^2Kyd!WGA1@=oJH_IA-r}(Yhq)=R@ES6AB*=M4s}1ck&rpD zCpPwDU4>{nssd}23RTHb6B`{LAja-MMx?@2%c&+d8s7po7s$p`nA3b(6C3yOIVK`M z3iMn`9Q_hGvGEx81aud`A1NU(3n&vcu`!z0GGrKs4>24n&)n35P!k(IykV&r)G{`K zufupbv61x^SM=IYn%Sx>E^A`rD^xz6dP5y#69}&+Hg4b>L#G)~-m_KlEJ-8w#6~tT zb+HG`L7RgWHL>yacD8aE$~AvgO>E@G2!~F;LUE6`^T?%;A|f@h@$d&W6$-G_|A5uR zhJJ?OS^!(7f<+ zsELhJUovtR@>2&9t*Sk-k@Sl-v5{c{zFKgo$KIaUIEdLo&I!K%p~l#RZ0+ocjgeO@ ztTB*wsW5wD zG>DqmI4kOt3;mZM9ID=nr%g<3n0#81eCWDkcH>DUjxru#Z5(2TgD={0AKD5l&Ydnc zPgaOQjEEBWBBhA@cx{mBh1H1mk8o-vX ze0}hFCpQjqFUGh9ceg#aHkXC(IzGLZlwxMOv_N zkUj~u9*4}Vmkp#quyIg+$k7f`9VKWX*2Y0KAvd;>6rJ!4tC!8hUd^yey+I7ODX++i z>|SHzpjr6V6x0F`s~t*YNm1vi*$YK|4C0hSaiY*#b0-`d2Yr4P?fG@6KRblD5nRd^ zmO;N%2ADA!*} z0P!n-3*3dq#zF7Btt>o&_=mp*0W{YueW)yCnu3u~94Z$Ti2K;sIH>&ymB=WF<@^Ee zV`Jl>tG5-<0Ah20fcx0kIH*Jw6~zFE!~Fs7V`Jl>fL|1_0OE3gfcx0kILK8**Z3yV zUWkYMfl2KU#WekJH3fVP@rDD)9yB%%iuwxo`x%7SEQ+Vw%N9{1)W$)_9)bv(imopX zKf%EEPscl<4=je}O#(zWlW;3547 zqHDU99Ymov4%%>8*Rt_boEu_(2ILL2Hx4@a1#VCU2sP}`Rs~TT2VI^8q7~F`4slhs zJ!<2il9xb?fjY@1&~xRkaE2ZSuv@)obyh+9z}CI&CnK^q4my^k&@;fkONFW!*(f#+ zniz!`p90ZmSb3HfRof}B*GA{Rfn^6$EEVQ7pt6UZVbU_IZL0yaVM<(e!!yjwcSWVJ zCxB5YArU{GKDBYs@g<0QK9E%o#;*hrYU3b{AC0|G57`8IDDmiqW8YXBZSj3RyfJch0|)da9S@DPMd?mY5N@WZARF+rZcn68aU?6W|}`9a)KO8gFk33_5{43QgJ&3lktRky}4`tTb@bN|k$ zu^OmmvI+B7ZDBpri^s;%8y648#}k3%2hK0yz6FiL=^OcK?=WlweK zO*)LWt!i&|nK`NKC%EiqhrK@yruwT(EomR##Z?E`mw#Ts(Z38234@?I6Ll#=-*TwZ(r_ShRX@|<#kTV zL^l@=XEI?cE+^S3TZl5Qy3mHlR>tLG`?3yp?XSAThF6Wm_C{V?qBcNK5=Lust$3t*kb#* zZ^CD|yMJ@r=KnBxvPWczH*2cP-wT?LenX7cP) z$g!VLBchW3L4_!E1l10+2qZo}qS|mpRf}HuWh6dzqB`-zV6Pr|55d;q2#w>Hk>x*t z_QLN|+uvK2A1iyM%Vh{RZBg~aTMi%039)|T$WNMBL&DLa_VRU>%}s$M^v*XA>8e}= zKwnnvM-&s$9T`|YodNzDOIRrq9@HMEYk8icD0$IOPuQOKrLGkRMQ!n)w-zVQ=-vX< z`i{=&SI#NFYsD-K+tacvE`fOB8h^78!Fa|cuEjW{ukkKK8P{wnt!(WU*tOmV?Z$tR6d<3Rf z!wtGNm`zdeeCb~dm6U+Zm$#S6_nvx@~wCxFI!Yw(`Fk3;z$OxaGf5`F|7x|3jP5Y)k%# z@GnMpBH-Ve;<2^=4n#~pz~9>xS@d4VrKW&hvm>Ei5Jl9mv zCOCj)hx^)btLW(u_=^)9Q36w<3KpZcyeO2d^a!<{s}!}hwcu*QI7M(cUN~&rNQ{TA zGnw$UUvB?!zUhyRo$xPk5^Yl43)ytq6|gg}sg&;!tz=fTG!$o&@fG-J!DpdV0ko1i z#xfO7#@{yewxSZ6C6UI@rPhVspM#;}e+-I3jkBW@udQ(S$S7r5as~B@S65f^tVF2n zWKbjjU=F8sqfCq}AR7E1M0afU3L=WS{mb`$2{1cdvP`?t22R{$q6_{uMB+Yy&zlqH zyiP+p_2wcd;zAjx-QtaJlAU2K%V9Lo6qmrGFQNsAt9~DVZOo7SVi5jbi>GD@d~|2Y zn}Y{#>hj1;AvVZuoST1A>}kM$xODR`iaibGmFcdDD(q<_uQG)Zhxat0X^3?$j?kW{ zwA|PU{}!|semiV`Z-1zk*oKZkIO~YRSj_L*a;$=ug{U zwUTO(sm@9aCz;uhc7uO=>`Cf{XWd=<7*5y4APjOOx0~+G*$o#zu=Vu2@IcolbJ80k zU<(|fv-rx=2W1(eYn*r*0Btzy3zWXB1PWkSR=lQ)!<**gzh#adM*SNh=8?1&ejl>G zw5$Bb&~f-(wEexyU{y2Ok|M^_U0ghM2!8We;v~|S;2z?TX2l9BX+s5{P7zQ`ID{x< zCC;MC5b8MM8jf9w^Qbk1J}E`Zc0bP4DjExQrcK!6Mn9l6^K2|P4u2B|>81@JKC~&h z$}2DRx&mnH+j~3 z2#4>KUGeQlK{NRwi8z;xxFdqz!T;ts^ngRo<;I^DD_y+IGSr>>NxTG`-)-tI!ZpCt z!gVL@66~Hrv6ol-38D){q4_!6)Q)Ht~W`z?It zFi3at-(%K)WDC&c66{QUb&ai20Fs*lhtjPj*yGS47J7bYMI4=%V2h4}$sdj(@#ur0 zkE1Wg^S=a73P1m%IPnKlUS>429j`ZzyAPz!bgktWg4;e=={AM>b<-3f{TC&awNA!;UHhh#y+ zhRn?4%mgIJ%-Cry3g6N=LW|5#k=APPt8e>zOG0(h+8#n5TU2R{A}%$o=6x56od{`H z=2dHcZxJs+*-u?pS*v+J0GwtuZ~qlYDyN;x-CE6C0>y>v|5(k-LHt(p%1gi1yg|@& z;RvlK?uoOSw-`KQY{A=vZ;G>;w>Fe!j@pVhc`tGxd!vWut?@fVn53Kd?;c0pQRT#1&HE=jU$fBNU%+bK z%pp0|WAzV<-YTo%!R@i3_uB#djb8~$lC65hV`i`BZ97WWL`9^|K>9nFXm{<^yqWRc zq0>~z%N&Hm$&$4RjiNO*45jezob~$_O@*QD!4$4=&H@I~X?+vcHT9$=Z zbzaTObyuzC73FNN=9O30YF>F|t>)zvs@1$Jk#1*IBtJu<$u$RZ2(>CwG`akBmSR;T zv(~D}Wf+6x5+t?eaV%w8jUEk-&}hU(;)Z%TF0^NAqlc1E%iDzIKbdO5uZivNjpYJ2 z_amsaD)Psom?6M54FolU$*LR&bh#?>`D~06vc3S?a(`W}icFZHYl$3U543}s< zTopOH3nn=@{1s?F*m}xUkpocmg^|AiXlwk8$W@VR(PI}zazM*(>y{C@D)KGNw+JH@ z0n~D!ZxB0@BUeRs$Ebm@)B!*rhD3I~3X-cLM;um`rT|!w#*$nWS!m{KG?wJ5 z$R;IJ>0So#eJaRW6}k8r-fqtzzGgt)VsUp(PL)$#c{MNB9`RAmHA>5}XpN}1U#|PV z)!Qbh_iwDXubg_D4l$=)&C5@WRc~t|A1UkYX{gt5gg)dNBI_;3rP=lNCtN+X3Cn*n z>F;Cd8x9rn3Bu#2>;SELo4FZQZsD4WfGWl09~=jCS#Nzm>e_JDYeQ@3ugiM70pVY9 zh@Q{}urAVw@Uq^vhQ6G`&w#eX)~zZh>gA>ndMP8j0DNRaFe2-10qDZWC1^Kn-7+HU z?PUxCiIn^SK*ya_d7gvVVM*58dUKVfoB$#j64~`CNY>k{GnJ)y0JYOtlJ$1tdS$5- zfPQH#$$I+{fV{=x?xw7=TyaE|<;tX)qG!Q9x#m^y zjlf%z6#W2wCH4_r3bmS-8)$1aZ(Z(QYzar;2YL%W=N>Co^LFC%`{>YPH7|FUtkt~R z_*|{#W#iUr-co$d!%qKWH7~yptkt~lBIUZhnz!S4S-t(YDcQUpGeI~)r;Ezxx0?4j zd@tIHcP@0z>;VtI)x7s{`OIM&;uJj&Yc+4c2CRC;A#HnE^)7)KW$PIV-C50B5@1CK zUd7Qlt9k1|Np{o?ekxY;_J%UXQ7fX9WE{?F-no!h+KB4?V9YKLe$kK|_CnXT!zAqo zaonc7A`uvR1cYr$dgW2n4G<36M~#0wE6Ui2RNzp#=R|4tYTlDOQS?a9`K*F)$zEGTV#= z1i3DJgaHBu_CP%7Sg=>~hWAkxzJhq&v0$&}eRWM)_ygiUjs>+?w}fjxme$wcD1tZP zkAUG&was45yJ@ekRbZeT#7YcUxlpTluYRa3G>6#M--24r`~G}oVK~Hb{ub0~-bT|@ zB9}v4>kmZrLqWB2xsNO05X9sDfLhJFAg_wz2E-rz0kxX9EC#YgF8+lWu-PvcYBle^ z$GXOMnesp^;1BTVCsy-b3Rgfp#2OA@ujXwy8x^7zgl;T~XI4B{s4~3Lz+C0J@g;~c zQ0Js1#FGb1t>#USmXceILZ z1c1q@EZM7h4`A#tV4I`*HRDK1jk|UPs-U@h?8!?sxl9&opEvLYq1UxMc ztPPMssW7Mcv{v)3`d&po3+S?xIQk`WHShNr%NHr!4d6sdNaP4*qE_>sdW5LI1#-{9 z__YB-t>&G%9KKY8e5xDakdDD|!f&0=6oP%UaF*MMWlJp;omCgjcJ1Z=;da zsRfiCw(7i8!KrOZl1DN(9?VpmgQ`~ZZW_w!YA751RbF_2ZAy~x34-;XP_Edjysu92 z+S`=mk7M`|K-yttH!ZAI^F9@pvjZ%Y3g*&B`qVZhJD#x7crZ=gz{x=@do{0dg5h2O zhoyvJPp#&S#FK)*{|G@!uiGE2mj?IY*TXQD{BG8w?J;$7znjZ z$!>fBa!&C557pdh7l<;XwkZjD*TV7vDV_?mSMyE~jUxXwmIi4MwVJm*2KII826<2# zM6Kp+Eo#gR$V<{7YBg`jS+=qh^1(ESTFv`QA|sa}-${wcZAwheU_~m`P^{*yfG0qw zjOgry;1Kgke9@Ns(AL8*&YdncujUnl7!fb=$wLus@kEk&1HHqD+jwLsBpOXFmhjg8 z7}~?p>!?!doBF+Dmx9L0)d+2wgafds%)0m*PXk>YGPEM-WuKPYEze=p zyP$j=(o|6p!uv%}JYk|bs3G)Chiq~L6c#qGr z8rA}QBVL0I;a!9Kt!nrL;OFrgYzVKnz#91rz(3;&99ScSHxC@8ez=&r9Lvw`i-toEBFbUxFcnuty=jj#M zF~w?l8sPGH4K{@L?d7iXJtlc%E5M!c8f*yfq}F)f%d7YZz>}edAcVKhR#ed60CK+W zm%wizHiUONU+$&=Egv$ro4&_}@OH*9P#OVk9xyOm<@h)E&?$3lpV1fCm;m?KkC=>t z5Z<~+EcF4<7H6T_9H|r`yp`%8$916W$U?Jyr_%n3ynYjCUx0Eh3oYzG{Se;4=(@CT z%eeu6eZ^)Q24!~aoqPTSv{fbD2ttF*BrOrHJ{!W@;x%O58I-;ujh#IhHiUQKc`)t* zdQZT>u%tm9%))KT)_)pX@*_Z=4^VUe)vGrM;jMgtyv^Xemzfu={dpB;A6@wd=(&)= zNn_)E^T9ua@Rmv;FZu>1Jg~);K2x?fgty{{Bv%KqVMwM^?FbZWe|CS$AAxoU<+gwZ zh7IA(kC`W?ab*(F2gwL8>MS9=Lw7U7<>0IhGQnCeAo(bWlN%dq4=7+q1HJAKE+ zF_;tORDIzbLr~3?yZ;7BnaZeKzMj53^pO{_4Sl4N;8pt~BzqcLQdwTaz8vd6K(;B6 zdzENT5Ek$ufX@Taj$m$Gw}yuJp^vmsU$`?n*vj*m(+!lg5y=}dt~8;KM1!I^vG10U z@Wc!fOz5K;esy0c%M|*U+Sqld(|EBoR$CbTZhlPnqSt~c8k41X9j%F>5ti0!BTn2N?;`Uoz`Q5DCgg!p=kstav z+R9DnWAESnP{!F-e()yfS-lw7r3rCdYUL*MaXE%kM*gPCgV4wKm$}YLWGr7m?xmrK z-a(v(p^r~LZwc~NJi*&aRuKBQXCSJec)*}WUk}G92z@-g%XO$(>XW5SFbI7thg&F{ zl-wF%2zI1J_+h^Ip>iAgm*2z^`tnub2oF5}a|GL^<5^l^8*4mIu#NUm&L z*bNn4b%HJ^{|~sAhd#2Bf&x3Snv2Oz<5Q~*eLM<6pe&BL;|UFYEQf~`KlG7Lv}LG} zeVh$_qztDv^wFI8p^xS)41JuAT<^!0)D?}Eot+JRd>W*n?KbrBYn+%RK+A;; zb+QHL%1r>8h2UJ~Zo&D|6~K_pps(A8K8^=EGhhVI+a~n!z8_J8Fi)NVk2bTiA z5srpXqQuY0yM%)mB@#`;$f0l%3@;G+Sm_rk6GF!w5K7WYFRd*fMI@f2XCLY$$G+P_8{B6Z>UDNu^PcYshPC#I@+{a-%D8Q3ux z<8W>DV2m>X$)-{F_iCG!kCBCtEeYh_S)fQ{Lm$@w*c^bi)x`Q>REIIn*8ptjBNuPi zaSpR|ZvASO5-jL$x8UD6z$HU+;r%B_={^&pGK1^=r@~xrxq%df1Za2(f0T2o>a?Ej@t@!KODUp7hpC4B4B4{4riEXA0v) z>A)!KqU+A?2(ixJTK@hR-xwTzHBYd%_r!N$4sjOFU)!7Z;`~3X?ad^a*7iOEBTiyV zs;Tu7uI>E?gt@>rfL9l=m&V!&*Y-{VTrmr!B`Lw$-gB-)gOeuUv zXmB95uF{3SS%&|#@b_G#@E86*!S?Jg{5=N-qu}m;U-+9o_ZR-=adaPaYA6R5{_cPR z+AUTWPk)D=`0PiJXfFspb zJ|3^*>7{V;Dd~8XuVX#XP4PPH!ryL!uj3%l!|^)o!r!|pVEqxb<9DFW?sz+LB9~v~ zho}4^7Xey~4CC5h;qT}o{E0wy)CHOrucLoo=y2SEBDQ*Z0UZ#pLmAoJ3%z|EQ-ID4 zbu{o7{;r>buQzEf&jIz+;SKzSzh^eXUr5lI;OjSWpk4U;N%Y;OaePg16_hv){Dr?i z{?^aHM4Mog})D;^Hp{L<+hNP zjLXkcy}`oY<*N89CxQ3imAQ7|?>DofM}Ufmya3+Tkjs*5-TIeo?PuZa3JGWL$B!oX z0_4+K5@-()Ed1RG_gcff>I2*av1RTB?84uLY=gr8zd@-V(%2~dPQ@<#y>vfq?F>%e zkY{tX3x9K5WpbSe%7V-^RcG$e!NT7w^NB+@M&xCXw=;ou9(qxj9WMsdnO*q%j>3Kp zUxWPXzvN&S{$7Xf$>fmlLp&^EyK)ZU!r!&PsZXBi9Kwaa+e6ql0L*Q5oHi@==;6ZO zcY`xMuh6Bt931-e53x8*z`N?bmj}TNhd#pj+tL?(y*^)S6 z_Y&YYLJC`~PdSiK=uciDdjTKGO!1T#Ed2e>FmrLppP*f}H^?xaRWVYihGi86qe94H zi@->RAvsw1n^%e!{bn#ahAh1tgN47(KVfwZ2V+vmVvfeRVBznw9pQjirDPF1b8wam`){F_`7!_)2WEN50e1c>=kcK zw+nwicAqU^X)vl?#DDg};~1u)4N_@xf)f?84s@uNLPG3{B-Y7(a))Y#Hss-!HdEJPld7G19#j zTV_vWFMz@oyK3_wdl^&#qjtb@hRXaMu9N><#B}Lhf!vNQ?XlZkePpw)2ya*V5HwWo zy$7l0i5aLoj1=6XA z7`x|4a^^F&`Nu*2*P7uSO-16HvD*=k^B)EIH@>_C|C?os!@!OaH@TaC9OU1232)$P zLo9z|mlH`0?*CbU|0u}+UM0jNsgmL#lnqEQLh*eba8=S6Sla;im6-L&@4`zUeN8?H zgbb3jBwij^hqbPdy}us$8-G~le6SX0Vd^ZDK1s(W^k+?d$EPn-Q)h=(fw{VJd}UdO zgm^|YRds^x+*H*`_8&SemH&IKDy_9MTHji0=lJ-SB0ZX-jh&ZkFp5dy_BHRLs5O;e z6uA+?)By1QKz4qrKcp3a^bkD89z6OTC`DxrYApZX?~iaDp35CzO(gTQ>Q6QG9+4;} z^gbei|JPU?PvBoo@?Ry@5LR%Agbe_<#1pjUb4$jnuJbdM9s>9c38o0C`e&2;F=-9L z8EW_gU;?~o2&URnP2Coe$sbrXDPWWeSm{g_ECqE78V0H|V zyKcbY5Iy9KKx`;`32i>Hd)S3*bXsh(9&$P$Hibh7o%xGR;|;O1jOm}@#O6rvgSh^& zB|V}w-Nnf9UgT~FX9s{8CqAiexfW8J{%u);lNUqUGBPaqfxHD^cL=@^2YxP}12`Lk zP2rQcT#D+SC1R(3uP@FTnwH};#Fb(*hI*QjCH*#{iDO6=L8udwG($7)jOCHZ7=Wm% zTfpcYvY0dKxmzu9Vuj>RJa)P;OU8jQg{%$C9)zJQ;K(G29m0eJ2~PlA8c*QtNUW&T z=JzH@*aYyMcmfBev9c0r>^Q|q_zK{6A;FA0V^!q>?)^&m8(?k7z(Mf@23y6_r7E5)l`s|Htat+d z#SrTw8_>|zhGhU>h$k@EDmFw)Vx*vi?Ev48CvfB%8z~8{{nqy}fT!aL9J$8E$^*aP zCdgv)qRxXY@B>G#v2ijB4+%;r1+ZdBFeBI4ESb3;snYT)y%|Z3JN42Nt`QYVg#H2b|7Y!FbmmYp$&t{tlr)23n;~*$$+jiVo;dwb5UNb53gg{vwvwUkzHsonG`WPCR{eoDtZ}Ga5 z3ekc1VKkJnKQUhrGiQDnjX4X$Xg)x$pI}Q$gPYmA*f5&!AUhk#y%s=yu$Krj$b-!! z^4b&h!)Q7*LTQQttQZo~N$|sH>I8CohcFjnp4QD8AdDs*s12hj*f0pAnE*?87vO_M zo)IjrA4aok5oSPW`ol>0BvlXKnU9aXCI{}el&lA~iTE&!n=l%deH6s9AGs|U%I}fv-(l(#n~{5?q1A~}lVwbmQb4PQjLcy)X#hH928|Aze2xqNIyz*i zlPx$`rU7^`1n*|<7Mw3j0IbOj`nqix%{HKW0*0-JqGG~m+Wm|W9TY@Pg7Hhh${a?s z@+1g3&=3n_vp!&=%waTpli1x<0_CQV=7-VH07T3%2mIWI#Q0$q;)gXAH2mOFaH70O zO59Tx^;u%m=8b zEjW3X=DemYp_oi~9}|Q1N8AkR7m%MIwuzXxjeb=-UYo-DWd?;8{)%TND*}L5$2pcUek2CfJo}(NiY5cu|7#B-$M%9u=e}OQ$41*gbBaod#N==W?_OU z`9A3Zc|UAP^QjusC@Oyd-$R6OY5;gOaOkI+FAH$?Y-Z3qeVv-w9G zBGaOhRuNwK<>U-ICsPuH3L&YeywC#p?<)}Mu0}Qm)|$Ag0k4{biv+~NBtxzKv*QEKgQ{r9+oF(2N+Qsj9QF13^NL+YW_uwT_%dAdx1Y-S+$ zzMy6c_L0W`JQsqat0A`v(!C@!-hHXK>l~%7tsr=(n9f2IJ_CV@=l#*QrOF4oF z`+|GlMkYT{Y;8H?y=l!Hh)lhUac2HpG})RtmC)Y?dZsrt{MzXU*U8S7`BYpgg?@`H z$A1$DZ3t3D8{*Jb zDGubu5G@q8ztnbe5c8lcnKTEZQ^?XHnO2&bF7+@mpsd@$7$34!S3T3*?v#)Fu)WO( zyf~z&+ZxGIT-B-BL}Uw~_pt?)IQ;km*S9=NO%7n=?5*wIiIza|V~b9qzfYa~!D$Su zSM7w#7um(5`fR(KDv5xu#g>$!F0}ILQUf!r%eFIaG{GzHKh1mhd)^KYOJs6t)C zLGWrbooyg5T*9ABs7PiKYG73MM5{@iBTFHA8Jm`q>5V}i55valXk%p=g2syO>^S@r ztBX5iH1*i?xNVhT*|o6}2^%ZLeq-JAxizx@ra-)#nTv&f{`NL&=8c5f7|1l%H@bpkLk6jg8?07);V+(4s7h5c)rfJ&zS+QBVBF8jfR&EX!w zsGtlbtlO$m_*vwb7vKMb>MyV*ja0`rGC+RBy8Q&{KLL`-vzquiR}!H!iJK<&?x63i z>SR}L1dmYu-p6S7o?W!>%`{?f9>gK=NTQeEc0nEIF-dmdfw zQ$SaS4C=@)W&37t6!31#-l#WjPSJOU0{-9) z1NVu8U*LpCZ0sJ~eJZ@N3_#@JCE`?A(?16eIa^WTRen8Q2a^@n4FFl+-&I(@tQF=V z1|dw5GAHr)9QYPlzZIuj=b;iGt7mdO7>E3DClV!Iy1^jl;*bY){L9yXv1%<4v|he< z8Xgnu1Qx|;PXA#7>qg8Y)WDWh0QXFBf(fjfAxjVBUSZDjWS+np40LSBD9U@TO+Hy> z0GJHCTDlE-OcT2; zJ9%h2?-_*gFg`-vPU0dC%8=&KID}U{{+EMZL{h770HDt#sWo`R(1D#HJo!2a^$rDu z`sPYNt5rf`&J#xW`8eHwjbyI9iy0)(`OuzK_!yiMtNj&_di^z8zz<|dW9+$UZtspj zQ?7SN79n97re^<>s?T2azLN5|Coo7rx&s-6EvW;m&!Y^T1)tFB9g$oq_=_`HQ^A-U zvNSeB%cproX+z?BZ-R)2!q;))KNK2Mij89#dS>4jhZt|S)+@1R_8;O9^>*ycOr%Mz zm-`prr}dA**P5q}6{5*qk!LdIG+8I*K=W&>eL64n+P4EP!>3VX+#-N`Wj7c4QnW7o zbM$_y*9(19c%g3&FZ3&i8`u3a@OS22MCuSj*2%$8{CjDVW6~ zZodY(rnD+T#gaFS(a}9PN%wD8~1hAE$e`*VMAS^_7&``=J za0b*1b|Cc1qZ*p|1g>>&7LV6e??*|abxKh6{B)-I7Nvef)9E_>aoo8Qmqu1!L@eoQ z{3|x`xd`n;19J1+@(j*j&~uGmPkb@5h~8xvnfOv<8IL*7oA`?1@Eab!HR?N$3c$TRefG35oAT>b>JSzf)-j!0{v) z6HRDB;=ahx4E&>%8XgAtOhE8s3iy&T@ld43XI9NdFt!CO6h#T&ME*Qz)qDx?WI*uM z@GF;zCnNdJS(b~c$cxPs*n0v7KoH27`^IKg8jNaWsm(r%-?>aYA9=gD)zt=! zZkOreCo>Z-Mz-KTN2dH>OukGPzu1=ecceQ;=<4Uk!C0O}SJ>{ObX4@JCvde~dseTO zh5t~>dbQ~Pi@V;32NAZvN`Hjyk4Sv`zx^r4w!a1o;@e;Q z-*6|ymUJ`3ncCk_Nbd{~FM`9c{XK#9M~TeCZV_3nHGR+TR8c=ta5ucieul8G_$%Z2LPr&#FlUqfx*L z+usrpR84n)g93uD#T!TLH$pP?u%d_SX%qRCRp> z#^;ymvh8oq-G2GOaL@p3@vJV}{;J<*{ahG~l4Ql%rR`5!Qk3~64!qOcBie%J-y<0Q z<|O85YmmWlNKuXh6G!be$h0`*o*u9$vGGp^c`6RMaTe2je7!+lk3(u9iIX^GKM-%5 z#Qwy8jbzpU*YVyJIS!t7z>kl?vsbVKW9nAJh=Q+-K~IAb?40y{f0{WDTv)vaL3i4S zYM|N|aQwrT-Y0p07kj)4ZxC7*m<+i2%Ud@0moo8 zeF3M=j6I6J3NPTU`P*LMb-PtS{`Li2F&z3Y;9iA#`vPtPjj}J`-lN#OfGenM^8)S& z#QqDo>Zq@WU{^%){T2TLZs;Fa)r6{~w3V9|a4l}d*8)`Dz{<@FxN&Gcnzf``dC$pw z0e8(t*J-KzkydVAz+Ls2|5bpQR&HLveF%HZ3%Dg#ZeG9*?C8rkSh;xtw`#jD->dTA z1>Co&&n?JU&Oz=yf+Bi9;xv2#_Yk^IB^10APw)G|2YOP;2hjM`9D4x6=1dgUdl>69a#cV$;%czVgob(`qyzD{;6O43;Y=#|I|MK ze$WOrVD?=|Ou(!u9~+JNui;?1iK*}x`rK$cnN$7sA5-Z&3YzQ0e&mq7!oKcoc^sZp z_~dFV&R0R+!Kk6ar;RZARSb|c!_FgO9@lu3{`q?*`Un?ke}R^=KP21(n&~D^C-CxB zgY-I%Ro{({*=z6@7^CI>=D0}HI4+XS5Ttd)<-q%$Ua&fx6^VzfZUc{|1h3-74AGtGd@6iS!C`MAZQUwfoQ{7goF5o zqs}goYfc37j7{c(d>$|RQzhp}e84tUp25$ch4AVJNcIV~q!B#B1VT?d)fb$Wy4!Vn zRzM>-4eWe~-y!2M1}RuTWCeth6FLiGORD)O&Vmsn}AAS)FjK~(N-o< z$GhT63rO1&(eyCynejk2N~aF4b0_376gwW6q+Tgpw@&0_KfEJt$>XB(5&HImV~TEZ zoqjl%C%|1A@PWUGKfx5d^JIT(%0^(@LOgB%)ws@(Fzvdl#F>iG^qq3n$>ubjbYFYU zQXVH&ZS&|YjGkHS=#fh7K9Z~AP1c<|%Ol%D5wu7i=?<7%1=twHs%OPC-BS*|+nyMY zbmymgOtIlvu}4wJ0w(YS-nUP{w9zuMA92oP$V)!1vw1_F1fC&}&&C|! zad$iBG~@&brF-=ntS_X(3GrTa#=6cCU}oynOlgmnS%;|kCtllE;qQN%GtazLPixLo z&^<*jvSXBbK7JRbOVYR|1c^E>Il>f`me?H(&c26g`N2@>=_livw+1BOt=>-#-}e%6PDsgqAE)i!I)m@W&AmV? zhF!_8KCVGnM+`n1Jwbt1jL4F!vs-WQ%&Wgt{oH1Z`uQT}P^1Y6fuF;-WW(ua^L8sk z77qdcS6BJtGx2-zUCdaBdUIOJ)``yOX2|YNno4VPO?)axQ?0skDs2NlxXaiEe#n$6 zcqyW7;24wZ#EzNcxB2~LQWi~!E0xKw2t@H#>il(!bI+sWsfSCehx}L*uju-U)CI9Q zwxkBn!-3uqG=AqUISo{(R-`BPLj!{CQ*8R%MJ5888^GQj=)sMW=mJP19ni65Z^Q9V zvW!JVXJ4}67_a1Y0Jnz8G}{P=x7pj4_YjUPV=_iN*(c>hM?pRE9dmI&1P!tBR}(}beXn)@h>aAvlYioj>jF;j`|Z_R98ls$csp3B2qHs zhP$AxrR2t8%UgBMrgQvIN&^re$Hg0WUx~cSu+45!BfuIaptEH??2ZAqRfekKCCds!g}l zq+9b}(oLaDb&@bc`r$=NG@EEwb?P!Z|8t-6(JEf^-7xTw964<9c;=0LQJqw%KJh-p z%lJ6Yyrl+zxe@UGlU@ei+{fpkhw-?BlUt+`UqyVdk1rz59q|6|6aS3(EFXWGICsE5 z#3NLJR`bAT&ZTU+9@!o3%5_ia?J)U<8+^9qFiav=W9Pc`$#x!UKp4Ibpmll~Y9gB~YQOUr@ z$xvY7h+T*6mhekA5Ejbg@dRyUnnS?UrBq={@!qsW$M$df`Eg9;aM!qOB;l*txv zuJe)d(C3&x?k;^ZVWcCgYM9!AU#9t4QJiURc`vMlEoh= z@M4(Oy{20q;th$v_?X3&q&rUUgIR*i(aIb^CZF0u5|2Q-gz<6Sx7DUOAZh8c*pwj; z-;c?_967a#zC%_2(v$FgiTP{qXn71dR@glpZ=vK{CSzF!uq>ZrAcf5Do-HWLUBvU` zv1L&_+}W~>Cv&titB|QrpwtvF(c$e&f|-?aRp6+x1z2W=&vs~&Oouj=ssF`%?a=g{ zPli<75q4;ABAq%X=+*zz*sH|{t#QBYo0s3K)*IhJ*?7QpjzNJO#*PO`NuS^h3-a=g zI#1YO8_6z=&$B--BH57kI&4W_K8X9Hxl1RF;8TFP8{Z*2N!>0&tE4KZO|MA*w~{(h zCLSqIV>Df0xy*zDEgz@;wC6P4=SWG#U)ks;Ij`GDFo{S(x=8E(H6pP!Bk{?m;-L+U*fHkD)lbGnhz ztvjr1Aqn}kXq6qduHo|w6F+OquFpe|}7Nx;;)_|M~> z^9#bd81+A=8!6Q%XkE-VNh&)u%G8CHZ?L?BSwq&vHs5|uQwLUslh(fd_w-<0O#2GH zJnGxQTco*9j+Q5J&o0oaHu`mO^V{<2U2Zj!pg)UX;FtGm(HXtsAm~&P=TpqoUWQD< z$R+Q1(J7WbAf(SbZRhw(^=jVSp}bVDw&p<7ggdDJy)06v81+-Hq`m;=@ba!O>bL%% z)$d2&mbad(#{Hcsb=ompla!}@Zx2Gd{GwHQ9I4xx)HlWAi}t^yz68(a-DWHwiPZm# zJEpvXG($~}&mztLlFy-XNOQI5Y~&86VQ>tmvCOn&hAes%gz=&?Tag0s#ZZ$d*BT1a zXhJ{r;OR)6V$_#F>dVxxJp#fCqrUI|S^eKlkh-3$#x2Q|TFXwk*3gxW`}HBDZf8;- z{y(Qax)`aq8O!tIvl#!2JH~y6G($~}O_AomTRB>~=H@lVySfa}Y!HW{B&Ps3YE*CsB>uq2nsrSG$HyMnh$XJ*H0euYsgD&umx&J62p;BR4>6 zA*1!^f6zKw?(K~JWGFL}tFJ-U|8-hDL+*YDNidFJnl4vNqy3Tg=$Yr_&EP#l?rRLw zhGiotQ>ei&aN6hZn^}Dg&_E$_V`SjvH+j9|=f#|ZhlsS7&Wh7{o?m!%o9?>c{s9dx z2K&BqPx*Q25We*fa4vUnZp#PMxrGX{6(ER-U7$KQFC@KrhPxqeVeBcP_1Wt~=hg>B zOOQqDXsLut(;G^$j3$ZB{nr-|88Yonb*`pacf~a7T8L~aTJ8{=C#2+AY{2akfnW3kVaofn70xc^38dqPBH42TuJ@rZXm2M>JR^))gQpk z7JU!%mh12VfzUX;swvmL=gP(n9FElOOzLj`=hQ9FBK0<7`CO#dzK0q8i#swfiH5#M z?cIhn|J};bvh*9?|2Lr;<)~(ZzK2sw9(Q=*$qAaA>)iFb%$Ip2xiIwp%d?3-yy>$^ zlwn&f+T%G~)*(?N8CVn#1Wobm&;X}Buq7Qj1~AjJ!`G15>Ab#Rn1_#KefYRT22eqJ zk>WsPI(Cb$sN~=5b0Wi`q`^F@7%T-ay6|$las+3=z%|pW|0)j~Mx=;k1aJLyD1|0I z^kqEIoyyt%7TAdvBRnECSjcCbyMM<-e)+atp+GQuR|ZeV<8nNP z`*f3R*x#<=XmdF9?%PV@a~fr)T4LX72#eZs4$&Vavpr&E??cvYMNVAa6=dQI_=e1* z`+syD22#i-P&^H(=r8xb2B@JlERQ<)mU7--6g0cnpUvht6U58oI?bwmu^g$($vbOt zQoqtiNOBcw+RUnzlf0Y6Y1Ztsz2GDV;)=#KXL4S|lcl;Rjac9V^D<|Gyz(7%);fp@ zG`_sc(F||4r$_kv$aLrNNR#@! z)eyMZve!RAdS&$UC4Vu>J|&Z=VP*)vsOyx>8DYM1j&j}E>@GqOB|Aedlz~OfT;&zQ zTP98Ko7=V}X1TkGf;9t>nmQtB;z1<6%Ove|8G4*WJz=aH?xW5`Ig7rtU5jAZ5^bHI2AVBa zr6sVp6g!(0OF|FS{4v#;J0*+GGt~Jzogk%&1%*Yu9C{qsEfEFV1_?ulQ3n5a!cVjt zc9SxOJGEL&$NO6+q0404M((3M46!f27-uuhS+;~84RAKgoJAA5U4ygP<}7!@;yO5+ zW6ts=tinsp7WbR80tt`53hV)Mc5T9B^f@i&nzQQ?VKZL7L^!WA@RNQ*@vTrzntBSTw&9;st(FTiRTEzh?{c9+!uJ2GVlW9wgqcD6<8 z)0U$F$Rkt<4aktDq`WKHi=ltz&RD7xH(R!<&+>|I{3Ws|Xv$oXoUqJF%#exHvQOwt zX_rZh-)%nm3UnNhT4apA0%NocUjWA2T95^qGf}@~$SrV7$@|PDwTcXO0Wj}1%y^Y- zWaJ+PsWO!YDCPcc4=Jr6vhKT22@5O|89o{Oze z?i1WA{!W0?E+{D49SZX5j}pEM2&$l>G>$+)ZT(R~&Jxyc)1_<43Z4EDvrIqd#R#Hc zso(f>Z7Go|`s>Oq6z3|>H)**>8rnmNmZxqhwh)wq+eW=wW18^3N9Hv`n=p)zJsF ztp5UP2gp|Vu4My*q}_^ZhJBM$u*&Yg_2*F2wy4A^-`%D^$Hwc=@hA1?JWa) zOTWQ)I8_e(g!y5nlxihWh>JMVozwOEw_#-Bb~mFmf`atl3_D#`xJHv-jk{Xn9+&S> z^1M(K$9vtmJl20O>~p8#xT<^+1@MV0_d)YqY)PNaLkaMJp}+xGJ@E`ajl?uL;PQOftOYhG z{G2-x1eROM0;~}bOfP5ub8x}kaNMeC2S%5GsETQe`m1{xcyVQs8Tw<2KMf3Kc3fRW!;xXQU@aL7MGJFn-CRFjX`% zJa42G+P^v>FDkMyHsb`7ZK`OLdH%@vA6i}2z-T~LoN@M#B-cb3oWa*^(hZD00n1Dm z3_vl`D!O9+N7Xg$TGM{kl?~eudx`k=!}p1P`?-_Hw*3slaoB!#BBPI(*&xi>WNJT0 zApJ2w%v;T%{Z#CQkJwx1XXs%8zqw*rE%#3SPz2Oks8~)Q2z2Q)ctl9|Lu(+;~Lm+&15|t#0vO$2KK|G@15z{o_=<}Fw6L39WvR6 zGRj~u#*!7e4`<#9$b#|5q+$5eE=hAicswNiY)EGOF%18@R86mfu$?3|(t8)A%;S%$ z55u*G!1z97F{M(2@yE*;lrgPD;JBRFjAds0agZg9vT|aLKY_Mfb;jIyCHKA$o^>yi zSodCoB3kz*;V^LTaO9G~oJ!CKzP!CmhiqOT_sRkVXx+OMz$*cm#l1(j;Df&aWfyjz zl2w_iy{0$}+Y< z$YM&R2JXE9!yl%VzF-X|Q!O*@-8Gc%Ed)50jp1^+>U@j|g3DWP8VY0G+k%It^|s@o zX}w)=7`XQXIrEeZ!h0Lb~ccE{eU8ob*~`fyx2^lEbh&52R_Y(lu`nN zYVSG70{04D?L1CWD-hB{(rQC8?mdqiiE0`J!c>yfNbg>dGP`%xBXG#0V5|sPOsUks zy*+TzGp)Q0)-E#DGUMK&m;`X5cL9#^s)c(iSGkgV??qv(duQ{|xc4C*8uvbm!@#}e zDx(v?mb4hsK;B*&L)JEsd(Q$zBJ1AX0EP!(7Wd9BkM(w7yUYM%K3S`%+RKK+z`YyS zInM7St%CIRkmMPXac_o5~?nMaTQ!*S+qf^fqNU)#`m+B zX$n}S$W+UWd*`F;cA^IX#~yqcoLqIzR=tvY8O>_ldx3|>y?hyA-5bSW;NIEDWgc_# zAPwa0WhrDY2XgOfph#rhy9K}p0hq*SgsOCWm@8@|6V(qZtY&5$ky>j%8a&2^{j2jh4=OJ8GB+M8+O6M2j$HPxq3 zv<9+|4SEkY4j=*oW`WTaBtB(ZvquJIu}2&&EEsgRp;)SSE@UhEha3juOvqwNr3N+m;M=alv=W8m zJZ#1?CqSS7zsW0=8y=asBdLnbJye2dI z<1o4aIaQF{czxew`E*3}GfG0fhR|zFGs_7-(9~q*__@gEPl~%hY+^KO%VrPF_{Fl# z?H{Wkz+8BfSK4k01htxgv9>(kJ!<4iZFv~aqfOTD=@1B#RztAir#XQjIUfWYPo!Hx zY}_3z;yY7OL|uin$@Z}e;~k-Y4xrgii2B#kdY)J(n4dm_RDacj^ zaxV!e64{D*6Tr>@%u+EASHO#CfbtD?r^zZo)m~2=1{JfqDn5unQg)Of5t}6qHY8Iq zy_Q%_WkEV*1X$MB1kVPAm8dS_|M9DC%j00;5nQEDnqN|;w$9Vy= zjo7qeg4iTV&4TAPe~r(f7m<={t)s`;56+SJlyOwk<7jYGv@)`fHR=y*o80|3p2o|} zz@$iAk24>qw#Qk?L(}85L|(SX>43v%cBJ%soW=Od2}6gZJ%ncUcE872@eA@9PH`Gi znZPB#$NB2jptmqR&UJ{1v>lA;aqu3+7nmOBCd3w4hUsy3-yH}{k2AKZ6~xxzW{e)^ z7i4aGoRM$Y9!DLaJr2!wN*t{PYKaXyv5(D7LG9$K)2|+qUDo69PZ+jg_u-)#)AFBQ zwqY|~CTQ3_>x$DKThc+4J&?DTJ0P1H$i1(CB9U#_3jiz$z$^{B$wahYfbs@*JIMNu zs=b;x3>x+i#Swr)(qZhr4@r#-$u#WW=2}e=6tn;~W2AQtNSPbB6x?aZklq=CG>?1$_~Aor4hB9V3P&j9`jz%1^474JDF1C(p)i&FwyQVFW|9)T=y zZ{xL&Gl!(QAT$q2&lr+%?{y8WroJGIAxVw&#)6dDy+?2xl$l^W7P4rAQUmwys*3p| zNM$WpZ;+{$IVtk)PkQx#0@>HtwBO+8BW#9rDOmgv1bUY!++GM;eO0Xr8aCQYJhF9WAR>yCbk`6`l%fKVzV-D60mb&vT(jHU)4 zv?oc8^g4o+xpjA32UP>WxHDwY2BikAd&Z9#KQYsXzr!Dk>FK;jTAxjSA-VUGut$S|-a8m$g zaqnAe@oI)zJAu)MtPiN#`vkJUz3+X8ksC?lK$sDd4jYnj@0`t6)6*cVCP|I-)`FDT zy=yN*)ebNYge=;i)WE$FR07k=8L%#psg@b{>OX&?%K^tc{9y*}?S;|)<*m08hK1I> z{9uQ5Z!R7h_vXi8;NGsNqTbk&3PBpk+si1(CI)ivdZ0*T-8&b+69JgTy(##6&UFA~ z9d=vEDoNE|6&wcc%|MiJDUuFhcPu2;H6-ia)mGErka{SrG15!q>3(PnUgf`qUQ{r*#gVM8iy!0JS%T4vmD=zMe@TWQB3l{B$KmszY`@eS>~XS(N-O4?Z=tTCL+=T!p==fX#3cIx={^pxKn;9!6+XD@O*#ss_R|HZ=TeYOw zvu@7hZ6YE9VIFKrf2-Nq7OJ-mmc#@hmMb2s4S9nA3(Rgia8hXYL0BMtK^jbAek50K zr!!;4WPG3@Fq^<+x&0BE-I!)KXqL%rA|e}*a61!UORZkAG0k9~LjFyN-4Ks4@bqGU z1!mt|I5jkTE^sM?TvM-|I9lc1$uTd|&drR662pHs15Z&$N>47ghFlb3tcEoFHc>-@CO70TA ziPc?vlw7`SpBE-)89Cnw17b8TD&&|VXUGP;3@&*B-`4@-4yek?$Ppcvz{tEbjIi$& z{h2O5U?74MBKF4>w{=DG`hpjwCvrr0;xI?F1pFQ4OWs0v?sA+qH9rM5L)z3D4>?oM z#V>xg;wOjQThVU_DvxYkjHO#ESA=teH7WNytqt&COZqgvHd-!kkq~ zs7);`%~`F4vB;@iD|6N$p)iK=?OL0&W(j8+fZ2vk+b!NM;XKdUnzQx^qtHjUYj4gv zB#c{ubRErE$ApF_an{M4-IB1rE6y0A1TCEsa*oGYPjl8e;Q}6p+x0SMT@r>&OdRGZ=ENPSXYeyqDoT#dj+2td`l`ceCNK+s!nwDy?5W z(9_+E{5xJt7qh3!bpU6D1|fD7>o+=)TfypBn8{~L*E{gw`&z7Z0emRB#HK+^yLNlT zDe)E$nfAytAZ#9?XVHY|&|6{~z2z3qhw7^gd5-7_$H}8;fW?a#H647p$0HcVLX4JAkTl1y z+TYzxhBhZ=VC>J3`7NL$QHvyxkfDv8J6yrP6-Da&=AQv?5zKOxsSh&b@DS)IXmos? zNr#`y?R&uZ-jqN(*aDl*g2o`LfwRF#F=a^(7(7B*O5jHegnspUxbBRrmtI4khxC2u zqrxVKu7Mn#`p#>xXkrER>1g?s?l`LMm_!nfP_d`b1d6we$b8DQ?D#(;25QA$)pRT4 z#5q}|>s7qN7n>x5c*Md_!=Avm;Cb%K%K(8YJ! zxCfjZ(f!y*@uZIyIHv-{tJPr_Xqx_!>J1zLdl{Wwr^EUutNge4*mi@hCiVqSqzo}z zEe}xLi%c&K0x|5KbR$f<30iqkuposiVO+X?6CMjQ^31?HBfSlZq_(VaU8hU& zj(=N0Wnn%T;2Z>;#EfB5vqOI(@ANj;b;68o$$Ma5^W$C6RWv__z1w^kUvo4+lgaR-T{2n|dBR7OEC5nIwQbpaJP7Thm$ z0X!RmRHGvTZ$Fh=+5uS)%G)7rG&K3(XYw(C!y$OL0oO72&*cn&zXH%cyuu6U($c^9 zy$Yu6Y1P$T#3_o++PI6EV^QT~kiLBEMLSJg2ZW|1-KPanBZ^8Q?$qgD)yEB;EmnGg zF!XW~{+yV8I1jFH7GLfKVNO6oP9H3QvEMX7h0z1@EU;Da`0agxA1RxLKct|xWIM3; z|yXin8QYnquS` zO|Ruf7Q)#4pP^Swujl{GqpA>1$1_ZGfbFm)JwSILG`|UfIdce=w=nA#ZscbW=F6D2NYc_ZC!=}N%Dtq>ptCq>?be6=^JQ{L zoV0OS_WAM$9uCvns=f2&^9-D{a~H6nk#9!f93zw!-M+` zxp27lF_uS4K0Xa6uRdo^zGBk#b-EIX(wvf8W6A6Cl}aB$0#;I9c%^nb+Nk!>!L4<}Ca~w&IqU{$dY;Up$M$ z?VAm_oN6BI1IfEa64^rLsxf4`=-twHoixn7_^Da*T}axytWb7P3t8_@dIy(XbGGQU zykHl~y==-IUA_FJAZ0a=JqKDRmsO0xT%_j5=m68Zx@ZzOzcx~HU;`xSX3tY1kurD^ zOn;8+n(Auk>B}F7J&^%;L!175;~{J%?7Gsi$llCu;w;3L#OO5fXo!#I7FiBtZHUro zKAJ~lJCMC0N=NyqCvp_XPa#TA`Di{7=T;0qvDtj-9Usjvk_@D5h_ZS4D85g96Od*h z%4^j}@loY&K!#>UO^0s_T>{@f1w1RHtVYp&1viL10p$4*eS$Y-o3@O|8$fo1C>y(v zmJ>M$`<(6Ib^zQL5Iikys+7)#jOxi3CoSs-FfLxk>PU0y%ksgNmDmFr zansCvT{(G!Xdu7iPOM#OO)wf?#?sEep%nYevU-3q_%c=(UXG3AU>nPt2F8PzvA!z} zR%7W>1{tGW$x1NRU&d-O4y-299?rZD-jzLI90*u&)q+<*Xe#^gZy)_m;aPwe;|U8Z zg3v;`5A)046SJ$>Z21e|rsr`7U0pa1X)DzRIu5Tuxe2t!0TqO7?7G^?w6U1ZAfX4q ze({8-uSID($j)5i@H&)90H?Dxgd+e?#uIYW{axf>qB#1z?DoQN8C%f0+QGW?bg6>QmlwPg2Us?q zP-HGNbQM07X=6wO*fO55^Jx%nl|n5op+CT3@q|6KkVSXtikwu#41f>B6ME+cp@)pb z5J3sg1AIB2u%j}v=qdl;PNRff0QbZb{{9_=UUKM7OE?AaY&_vLT*&FYW%o==$k`h~ zP}l-L6k{>_$hH!eP!3>~c)~(F2&DIw4O=Xs6~K=1gjX^BlzyAsjQg<~IUHa{JfSo1 zu>GVYrtp+77vRJ3gsPZiNbfI;{VZMq_*y){#e_xr09m!vX0aFG!FWPL=uRIbIWV@@ zEY1PE6cEgf20h9XU=5Xxz3h;zU?02$#uhl^X9tAaWg;GFR81{__2UWrIDI;nu7J~& z&=p|skWfboyn&+JDHW!pN!-Yt&%QPY!Q9};}5b-=N`{`S@un`x(eJT zP6{@gquzL})7A?A^rP;m14dJ_jIMar7CGM2>go-~uuzxY;;qwm3qQ)PPMZP7qoFR^ zWt?WIAIjWQmbwPComr@t@%PEa?=AlbxIc${n(5ca>1)wsKbHx3e$_JM#@td8x6nIg z#F8oIJzCov>1~^~WnjXOr7Seu@h}Y($4z$kEdaMEcwIuSI$LR}a^Dy5$o1}5&1@+~ zfyTE#zDKAG9_a>FQ8&8Z4pSZlW7%b_bG#cAccUFG>n$+02P~*rniGT@+)3z7htdy+ z0UiqpjivvHeolHxH$O&2O85t0!a&~|Uqfj(qZ(cTQbP*BQY5f~`H5xKP{!SV$PyX? zY!(vgNQphLp@KWK5d6{;z>okmkF|BAX%jFix(oM$F&XInSs1C3ivy_}-6K=+i3qq{ zmV@yUS=x+X=1C6gD!EN?`&YtFfFFf~dU9hSw1}#1ug~!4CC7kVAgYDXd!BwF%&9Bg zFi=mg?(RUR%icC3iFiUw;%2ydQ9q2Q8S-klPh-Slc-1p=Oh@79(2M` zSydlfJ5RYtDIc{vPv>)~KB9J>x&jR#%09q6BzGRm8;d>#cfNyqx=u$~^QGsH@PV<+ zQ^WL;RrHep>4hRRMn4IVUN}OF^Sm({h8BtNL9?nbX?jvbj^pe{Y)Nm;WGyx_KypO* zPQl5I%^==8!2NXBMoKEReC;b9W&qf*Jp!rL6@J!aS+j8P$L zA6d~|gZL=J&j_TKj_lpwI26c3pgkE<=?k#T~LFjvgI-k@GtBL}r zU0DI)x&ZL}no#(hi<;OCaDPaMuZi<+LtL#ZsqqXLe}=5pkokW3)%_9AoudHC)hIww zY{m-n63$k_pY9K%EGrd^o3G50NNF@f&9M&{g94VHSwf^kMN60pa8^9wZ;m8$MRH>- z+LhKU1NZ_7ud7dNCFF?=zRq#_ldv@eovv5sh@cXByNht4JSvO3a{_pX8@UKh^Bq^C zxXnjmKqt+&0CAm~TRGag-Q}|(XM$?#wC+fkvwu3{(+mwWeU!T&$=%|)BUOd^)BCwn z8~PhyOX6R^d95kX-<1v!_6z`zntXJCDn!Ze5#h6C+tjk^_)y&N>Xcwo0Uv=NZU6<2-vJl`C@r0C(AZ&0iq#<$|6(#EdZi*+2;p4+* zcV2co4R8S9SCVW+Vx)1sE6YH6B@3;de0Vo#d)$>JY3I9uKmLEDy$QTd)%QPs_Br>u=P}*u znj@4-Wynm)Q0Y^m5K0;hMT6*~NGVD_q{tkpsCZlv5)qNa-)L%ZP#1RcsWzdW0OAF8C6**sm`7xgXXA-S&y^l~Pq!p%LaA+6s%|s`A>4Zj)~@ zUhz`ZbS%u*o?lA3N_VM@+KS1PdKjs)@V}7n|6wl`LmmXu%Z{8buMpN&w@Q-NL7(Y( z=0;o{lW?J9q<=jI4cB{3UH2=Vaj7Z6rCI3fmE-K|pXWo~&DwnjBQ@(<8oQe|yCy$C z%?_``-H&E>Y(hzzjb4kjcg;?Gj3PJNdx7u8n*DteJ3=)32$%xRZkdJ)WU~%PTgZE~ zaW_2kSM!2#~t%5SGVNP|FItCS|s-VoN0*L=eErW{Lh>IbP>G(XvIe4j`bbK-5 zx1pNUaUEZQ_*cb|{scXlpyGPOE3XFsXDxp#;*(KX>Lj0h1{HTBUTiwzzi@sKRQyr} z6%-q+s-t#8!LRYZFg_dr&(Nv*li|6#d|BSGX6Soy14Tk z5VX^1;2rzn^CvPfX$ok^1l&zb($7iLt<^D;#go8~Or-e$dL+Rcv$lIr`OA!WGXR}K z_!243MXJ_(Xgpv&HngQ})H?7sNBNCeWkW{cg@@x>gItSHo7f_!bLetQyo&_TIge|OOF4BjuGRPgItKGVeGS~v1Xf0u zQ13gyYe-lUR=#T#*2@(1M+R>{iRb%VnB$KQSckX;V@=f05TdB%9g~`nckQ`%S6LWx?}$A zfab+RYwLLZiNbnFd?85@CST%@`OAY~ zJ$V1W9I_)deK=$b<9LO$+2%f|EpgEbiHlZPT(op?(K5WrN_;ebdk~~P1=G+;^LL7w zXc~HHey*@!E@CwmS^Rt5!FiBVf$qUg@^JfI~)Fz8>b-BMM2xd_-eKmit zl#P<d}?+OQf(li|~!L_axJw%mg3IaVo=v4B<-X{8p#?3|KniQZ5;mhf_)?pq@nm<{=py}FZSu{ zl>ZDiK*QgtzgJ751LhwJyvHc%Qn0Hy2=1EF1M?3DlZRL#H-X#UA=25Dv(GA?*4v{W4ZYWNhe=PX3u7!;NWYRe>`eXi2!3m6kTCD|utT;dHcyJ%4 z&KkBCkROv_+AC@(ew%+HC^Xq((*|OGkAJig7}(FjbbLETi>wAn<7Alj+!~7K=AR52 z-es{Jfa{iwg=y&E`M(5xF0ruZ02z}Evs%)3^M4Hv{Asc80k=L6_8{7;Zg1keHB@xo z{6B&amkF)(A*A^G|4K#g%|8=#sAf}@9)t~V@i!I`M~n3)d7&V5-~6*d!TmPDEdbw< zNWcp-VD#Vozk@D!T39bYh9+PMxssrfIB>p7S+koR?@a)wJ21r2gY*5A8@}+(V~7>t zu8Sh*!udhUw4?YKDF<|Q5Zvz*h(_X<`Kc){KfoOD2BcR4e?7uzLnfTKh8mnNrAiI! zpVa`kVR8ZtJoL}}w3ObRDYGruj}W2Ua^AP!n1anSrQW%6Qzp96420xVr4fO1~RN+&s~|qM%>kcwS%iVm(|2uo{jcRSj?&Ij&LZO{E?g0Z<85 zCB^erjRFoY8w>tkV!JRG+|N_np>9GKDzDUFAYLI#(xu;~bx*NjCxq|UJ7>$7~X zy1Gn?T>Ax#f~3=cnSa7hRktZVu!09wTab8(7-HK{^c#?((%+%1TEg>(r>U;sJnFcx z=wyiZN2V!OnHr44D923{gBJBirG1XQ-mFCh{{gT|h<}%P;fg&IZ%X^`rQLz=IF0Q(f1i$472Y3bPhiT7pHUqIwT(TvJ;2E49n(L~7Fo_6h4l(HPSI`vc~tL**N zX)k;Oh9-I;)p<+R{>(?6_)nzK$km3xSPalu+N0^4#*LU^te{?*osixyjZK&9M{7%3 zJWoSLqp8X~vEGNYp5?s-`g;l9GHqGr>Gw}lpMbM9!DaEacVwD@KQL|FrN%6123G^B ze!-zI)HJ!BuNgeAR4wG71g|PMuM@bqZHG|5h=4TLASukn=I`ZLHq}Z%Uea zh>QuZfcB2sH3_s{N}R7D$q5FlZW!1~XA19i^7sH0A9kpMFP-||q}A?gin5M8cG`5g zah7Pm!B^Px$gg$k8#ZNts;MQMV|N=!oln6EjRc$|ya!)R?d86JU%X*}1% zBl0eux#846r#3{MVwRRqBNo>e;Ax$#>eUi!k5eq{c?XXzw1}CAK;Yp!N#oN!MEFQ9 zCeL9IDR(V7d=!I7Ar0U&TH+9kg_&~X0~?SS!HG}OapEKQm?VnHJ&#!U5V|GmLXPY- zvGB|=Gz|C3^6S+=^}uqkSXjT4ME(K|@8<&r z&iD>;dJU&o*bsnNI8$@(yjwUXrU4HK;Ce0R^3DQyT%VSAmzd%46blWly+k+@j)f2Q z6xdF@#Dv^G1q~<7;u97`SbCfoi^*oAh;Regm^nVGCDeY5;`mqvFEaKKF~c4wDYd^u zic91mP)I)y59@GRh*K=g4?rwjqdC2M3CF}VpoReWI0b3cQ*ydhpSt5_J&1RXSWr!1FG1;*ck^c1< z(MRsv3DQ}8Dm;csxp66IhBX#w#6FQk*Gv#rkyqtZLZ1wgu~=9Qh*(&Ck^r`7fTr*gnJ%X?aXDR$n=v379#65*(0-8!y($2BKPeWzk0T=H#2b)^aS{>> zD`5E#B8A_fgceIAG8wd3$ax4jv=2^<;aY?8Bf@Py(Hi8)EfYcdL!V+xrA#=2W>~4$ zN}?J#!RVg|tKbSb711X{WDKu;0}%@=uM)sU4bU{+fr8k-^{M6i61!Fd4UeZ-XlQpy zK*Fugwdn%`ge zFX=QC1K5jeCzDmU4nh1QsE&qbfrKoMYg!+XQ)i#h3~Pi&7@|47DUvGf z7of2sxATLjhs8bv4hpNyAvv|zCqrZ`7G?nfkMJ7-6gey>P2*c)5ac(MQyYC6tbvBd z6Uw7$_ez9IsAJ*Ja-=_wuUvj70(gprjlP!%`H)R8PKH?i2Z>#xPX~@l>^dD=j1yjZ zPatC9w;E7&G#m!b#~{d@4Ck{SMZz|Hnt@gBfc&ImU5`cqfVk}$@MPrO_(^#hgfr$^Lbqc}*G7$E&pqQdvtgm#|l` z$_lT~%W>ZCl8=t$!^~0!bx7gZjuT06cpwrHZi*K($22{HFVyMHc$xkOCG(@(7<>K_ z$&4T=x8THy6Q!7J0*A-~%(O5dK`0{J7!D_Xu?eU0rzs*EM?^T-z=_378xh`$z}5hA z?gcQA%nB%I=^6tKYr1mDiXkE?6QdLQIv=di|6ug^f< z?N|&!Y7fzy_t1hLK?x?y~%m)CpkHUbQx0 zD7kdJe-~Hx(9&hVtm&W(B|{&AA<#`x?Q!)BE58LG_qzlPB`2r{3T|zn0bqL$=p9#= zurUkrbzQtd+SBB0NaFkRpoQsnP zh^qnYJO3bFV4_XR5cu5VdamLQkuB~HE&{E-LogH-?uFc>a<1aOj4j#(w}IW&ff-5$ zb8E=Cin}4UXdXNb_813dC>hKR8RshQLD=GkARFvY9GIbGFgGL2R?}iA(|2IbQR{|c zZO2I+{!GHhK=(rKkQeU7A+ENu)2K^^n zOH$3lP}0*2wp2-%7I}Goz#anRebD=0OAU1pnL@`=WK0HQzB-Bn%uh2btH3`}XvqJuUGOrHow!Z7gS zipaeSFg@|t2G&;0R&|(sOd|OkUR9TcgpoySVm?e@CPgq3MiwQhY7Q{lTo!uNovSvs z#a-qGc+nh7{~VJcGyrZ3vruvEk6$oQsgtpy1b?j}Lx6B~&4-H5mSSnD5@@v?f*~OI zcxR#FV-!4Z32p)L4hNBO6Z+lQ4<_geaxceX2&rT6G2*J|JKzriWwhfn1pX;VkEy##N8&z|R3?pW`#6bbBb|2MggQd*LAMu+o*xRy}Cf0XD?rpLEq zeWMiVa3oIRabANI^*LgT6arpYlwL1$#4rhuJNOl>f^Qfh%uee{lGXL4B8Yfl1*Rk- zE}u;a8iLw6nzAFaC$$r;X9N+EP^24Ti>XL@cZ4AHek;`IH1jxg8V%ke{IMN-4Uah@ zP%~mk@*uO@7!l3ci!&0~h z8nguALHxC884}Yz>4ifd6>OasVcG^b#PPigBp3whESG>G6!)v?R5@)}ClAHF2bXUX zNuMV&hEvAnBBT4`kg*2TFP#jAT&4#kK^b)A@FE=I>X}PW%HIf?Vzp!l{P*EXz#}EU zI4D(;`N@vbR|S!610Zg9D29?RNoyeRBc*n(2)tM$`XE@{3J@!%4=CMWI)-~9{4a3l zsO#^;SktI1=xv}$HuIQ*1hbO!Ubs^aWFt z;LYWx9n1J0g*M#{KktB13r*m6!l+_@FZ|NS;Hh-RF&@i! z`}5n-qBsau9f%>PMNPqePc4pXEqDhlTir)3o&i&|;EhBv1BHqi_<17gMKcg)&G5X) ztA}IA14^|Sp4_bHG=*673lp94$wPGr2j_g4}vLr z7sX}PN+;0^8{-(qV|z${8o{CXYv~L@SSJX}R?~THnFb0IckvqZXV?qB$2BBdwZL7O zV5MPl6k`}>6=v~NL>OF`c>c$pS}x!fpDaOy4Uhy_D*HCOgM^XM94vu&-Dzo2428!f5<;sTe}3-V^@# zOCWnXC?7h$jMwRmd*LD(v{!Jb+z7%!2a@5Kmgwx&=tDAQDuUfZpY#+6{&bt6_DL72 zQ-#5TC&zV|l^vI%$f@~?5QoxrWeCJZ?$z5F4Dg)N< zAZMT-YKset9pirZ+p^df>K(ZNxbnc%PsYtx0eVg_Eg;W2>l)W6%!B9uCbAMuRq3DVN&i5lnN?DM7-J+5HL+ zb}5PpBb(hzAinNWNkykK?uET^jH}~CfSZTl1_yE#hkIC;OKYImc_-w$m*tPjLuM&Bj25f21{-T0X5v_rm7@hUEI4ElZdO{^q*e=WU_-X1TojYD8^3-dEbY}Y;~CGZw9;R0etLnHU=3Q zxtmwA+6)jOtu+UiuMj?kzg9}-#k!Z5T&gMohLL7Bm5ZzOPvTVYU3~Kje+?J!&+0e~ zFi0IjC$SbFjgw(uO&$i;Z6J4WEQX-|Hn=`Z)K62uhxz%8G#i_{L%liROA~VL62IIi z=I0G~XMWNF-LtLfKgy40E@4#QH&Jg$uAT6%;y#@XeQ2udz@hff7-h^V% zFHXlVt|maep!h8KfB0)@;{RFn9e_b-8&2D=1?1*r7+9~(0P9YW?{_S%Pqw;_rJe?| z`}9Q9vZ%=CW0-1<+~s-PzJ9(cG!&=_G0p?#tDE3M1h2-JNcX~Q)t^#+_@AV_9V5<2 zc}GNQDRK2B)%+XW{IhLAt(xyMgXSP7S5A^IYbqy25oanVRkcDyJF?=<#?^fbkjn$0 zX5p{R$q*`Mxqc>cJsy-~tM8fP8(>I|9mcw`ss)K&_ymq1p-|JMwK2O2?c#(Pi#f1QG%%owj zf@IEV3ceTqCGOFMbko;>`=!H*o34l7%-{doDb4j!+^r9e0`j|qF~mM3<>B|Wg93A~ z^B?{?OBr92eVLDOB@Jo-akE1)lw9hIU!;NfNwDA^F#9_wLw3OKk@x~w$Pb61Zu?5z zUctJJ11Sw*bYgPSl|(Nj1>jKvZbtA93!WGOlZelhYVf-PewbiPhqdG>5ip5fND3;p zHc-VtsEofh1VhP1{7s7Zc~4lQF_?EaC_~B6a5$y%3tqt^U=DRqhMYALAM6T0F*@Tq zhjKRjl`Z8(s=gEn#3;N3vU+*HjzoO>7st5bcddgh2>ytFM0H|ujqH*5jCEXf=ndUZ z16ORG#WEzFBg+d*`@H;lVN21zB(6{DaL8N!jsW3Kvfg69=#8C(Hu6PJ>qWQ86D z7&W$0e6N|Tu^zxkjd4>4TVo`8;f*-XRoo6jRS5bR_F z4{|^~g1@*ze4Z^IZzQ#oY#gB_L@m&dB9^HF{nD8ZB8kgZr^mq-HRoIXtfX{Mv?QwA z*=u-~7;VgkXSJw?XVdF}2vPikw9$@V$qAZ++y#HF1w+Xe;s=f6YWi!)x-Xa`9F(DC zXhngh-w3I1fw|m48FJkw@gcU5ADN3Qem6PT4#;trK-93!A@P~yxVrpJ=6ug+9;#M2Kn%QAWEMudyvbz8im|1t!Y0-$gl| zmpM3i6pX=+$xyQWxJ)Fj_-)rTU%18xV}sRl#3O zrz@`d*F>>?C32CqfH*o}4W)OJ4ssdC67L4A`kb0w336S>l1CeuHl&gjSHE?{sRg(X zBqQv!Vd1@!eX;ui>jTI@2a`u0$m4ek8VT}ij-~U6tBbpVH523<$C6aMH_`=nYr|Tp zd{n~n_2~iVPQdm%C_})k5T~U{EtVgYB8!vCZ>#lI*eCsZ93ZRlJ&;uaxT_tOp~MKO zXWb8r;4=WLTfrWj40a75fNZvcO;WAeo?p#Sg&-mw?>BvBYzW zW{c@d45$u3$WX$Wbvk3|9dXci-OX~pG2h@T1>zo)u_4wjyB#pv-f8(Vx}R z(<^X4z7eWdtV6Z>^x-}M?o)>q9}cYJV5u)a&RAlz5tgZp9#M}?N7$6c9)})}Igjnv zUXWiN0xCNp3<1+jbZyVu9*se1?)dt)M_l=JX%CRQIhHsjQ0-+pcTa%)oMVY|2UdSL zTEQrgUw15Vv%q={zF9B}RN=)s|`Mo+r&XMXE_NE|Mm$_ST19w}5*G z{#qUJJE3wG-QBJr_i`+8cfq=7Dp-R+e%Z0)#uQlmKyok{t-l(ml|XEA zD27m77mC;VB>4wG`P=cGJIv~u2DNQ<<%5SC6hbpBjlV8}xWiCp8CdFaknc-oxzQxz z{Pys*^Xo-?^I1M+)7Kz}EMA?W&m=z7^q@JE0$$?^5=sJMFk8WbZNX_L#UG8@ zK3l!UzSqAsPjw2$1FnrbD+HG_|9)<`)r7cx9xKnb9@iD9EWvNm&kC^ z{tv)*0&>j37)lH$0RULBGM2;1Qs$q3CGL9R@8%P_q)rhIC&vC&mP2@J!D8JMXAEvQ zA=M2h0+*>lwra^VL(Y?CoFdf?C($&+cxUh(!+p}r4E?{f_d2@~6rK;pa{RTPG9y4) z>hq4|CXn|ymfVp9s~Qpq-+}zAV==^0{S}&F3uY%lxC%Fe@Yhl`Kdvs@1Xe|muW~H? zoF1NLW9ZTdnx2)d>}fdg__w+><+0dBCviWpt`%qP@Ox_s9YHwKtDlW`F7 z16l8Zyf&F-M7(1~Jh>jYTwo3);~=6b&3XdlGv}~sGgX1rxEX-IX#j82M3{<`bs5Mt z&tXm93f6TX-SInB+N8X`@hXC=qLy2jksBCpv0T_E35YmJB zoj^OKBGpcKrp8Ms^09BtZMml$n^BOH_gu2M1<%Ivut%G3q`Kl(x1Q)i#ni`S;TglB3}e`JpQ`qS|nz@lr|0I zrH&;+l8fGjGqsIC9C9c(Q^Q@@^1gAlUL@`$Fs0Voj2sTPeJlE$h_Oc@QAM3-p?a(X zwEa;9S0c@IE*(S3)AW{7{6#EFJ1{#tsAK`lZ0`bA7RUn}%g*k0cLwVvkl#*bB^Prv z=B2^=K&)~onY^bn?uEsn0B%2(!zC3bzO0?C=Cf6v0$Up6W(3%Aa2Kj8iC#zw{90gx z{OfQbz+YE@O#O-F`Vo?CW$n5F66=C+y~8qu%KS{4*}uuZ1C&0F@9y=pnaxKtv=_DS z*(9F_Ze%hRD!ug>REmSV2!Cltd`7KxBT1!yjH4HBXEQ21oTVti3E@^yzryC)*-g%mFb_##=zayH_N@z-Tz2>d$8YoQtrJ{##45Wh`^ zM9T=Li1~XPVAF;F)_Y;6GlrKU;1XnGT@Bdv$euk(v-RLrqC;7L=E!1H9Zv5WgYwyG z(#=TGo+*Mi(0~NRgVkqZgfc14P7%Pi9 z=Bqnigpjea(tp0XI}t&WtSgY@H05_RC7Q3)JAi+bj~UEY`%n@Sq14WJ-6I(x$_TQ0fZX4)7((us z59htWxoF*3rTPkJlO19<8aHdDFXv>-KyKQ;IlkV6TL@Z#hBXwa*s2@8Yqq+49AJAv zFx)AM5zWOjFV2pSgK!#utsFzpU>s88LO%@r^iOgB4}Z4(RIE*w zd0fS1fYkxPwJb(7H?G>P0Jj+k?eNz&WC$ueC-aLybW^R z;cz91W;k3q1L4SUh<(NR4$+sO&e87>{mr+A=IB?5B+Qg}gXnL$@Mo(A#emP;%sa4) zIC#7&uL;dpm0rgdWICd6$KvIpNh%j30Y|Qvs9YPQ`oEW}#PSno7MkSG-yRWtFJ9IM z##IidCy#%mgupbu}niYoAH$cK-uvi6{6cx0S zqLw?sSO><}_-oM&8PS=04kO})9LcuhRWa0tOeTl8%1017ETR|4M)6DRvxxGw!FUmj z_wW}zIz!;O*$*M#WItp+!gy7bIoE;?ctPkh+?`nq>Yw=Q#BOc{Gxbd2+=^NEk4CzC znUAF~g*Gq70Y1Gdv=#S%@Q;W=0amja)B;&9nca{koiQ)`Vl=zZA+jGKo0m+o?Ilx( zIjJboL6VtE=106_zQh!~WLA4Lpz+wV;$&85X9T6#EfPX6r&5r`iLSh}{ zE741)jmRZaN08(TUh1lCgM3~xDbrmtb;MjU8KKn9ykrue=aQLzCFJxvkDM*}B64)Z z$k~#Q_{1f%F+`}5BvFhluC4%C-8n}t=J^j(;2gP@>o6NcXD|O@rn8sunzY-OAk3H7 zYJ=(pV0#+$7BVi}jvR7}dt&kbxbW=R7;&a24~$)mh+Z;gdh+u=MAZfLdi=GX`h~l= z`s`_#qczC)I+lGRP=h@e{DmCP{y*ja$uH0eqB)7IKEqoOJ9c%53R3rA?KT2 zfa~e7b~3mVEcFb?A0)HfO=V6+&GW(@GB1rhqO#8mFTm6^SOo!_oe-IqLe17>eFgHV zWR~uR;XjIWFT4l2WUB{JyFtBN(*(KggzjC%;v_QM#VZ!S7GWBnk6eq*B?D}_WW<@qEjx+JnvO%B;=CZ(*lQW6uSVsR3!l=Vqch=MLts0$C6ZPk%Q z7#k_G=HlKbFyF`76wdPnIaQE{#Jp%4{hhRv#Hyzsn=iYQ=B>gq;@pk8M)To}_ zALHOU2h=6WGN8aLvNnL6dk*VFC$J8Ke8REpJ(uEKD)0};C3jo3WvKwG>3*;AaFTVU z$JGXwqcRBf999b8eWGTxg@4^x%~kba%*LI9)<8VuP$Dt8VO0GavIYU6UnQ%$lXnYH z4SiV+pMdVHFK-njt;nZte5-&khWS>(8iXV3@w3%?6qJ9@e--2|D8#u7N;)D*qQ0T1 zo3yAJ9=i8NU5oaf4;t2@1+PpYo& z^hOd%X9C@x&@3w`c8$6e^uEqJ%j4r|mY98)ME$@T;A;eY2f_O+*goCnYAX`4RVj{h z6+b40XXU>llKO?MbiLq^aWDKDgU3R}t@t@*DhpaIhm$E&a#i+au5E#kB66}y71_s0 z#G-}~EXV|+o{FMuAD1O|+3IHY@fiS!$w;()T!-~-X#<{5X}it?ekuZ%uL%)#k4aQiz1 zLy10K5jfY!8A*Q@d@pW|c0wdJ)bz&^J9o4iRwjB*J)8TJT~p5p3eqidp_?h zu#Jsjl4p@bnlU#9bmeh9pH$cL8A)dX-OA9J+e&9%MM1N4-dP@>B-@@(qJFjva8Cgr zBzU(4^P!{xw;&M}h2uhXb$`?m)>$4WZJ(`Wz0Q(xykUiUvb z$Ztk|ZBSY}zI*CN?~f1stoJv49jdz%aF05y%uHb_KNDg`g530>o3QK(7l8TlUUA{# z%3KX95^)TO_M?B)-~NF$n>7<`rH(CiK%2Gj(~?M=)kU~JkcrT9Y;gcPRt-|z$(VK3 znc~yGK39PXR)Obe|32p^Imr{zq0Nqd((^wUMBaQSo4!f?unK3wrh-C8pCH(n5>zcC#eI&rx3aJUq{B~jx6kOK8GICE6>-+V)vqh5TFVa`P7 zNQ=Fo#=qEJKUC8PVVAZv^#)SR#9wzOz3Wn3-82)@7K41iv5co>IzbyW(nu#bG?zlr zU*G+Oec@j;Q|ud-4y$+zT3Gt!B0qmHcKU#2pLrxSvN zd`CL2zUCFOCn%%v7XxznzDOW7D#2YjX+W;#7Xvb#k(RBdo`o8FMG};Ck`_BjdSGgJ zmKcVyp7E>}g_jieYf%%%Vlbd~*=iT%Rr}Ty-pLC=(VEdC!UD;miXcWHaHyih#R`G+ zS|CF^Co-$qM!K%N#ka--e)A(x% z41v!NGsM-?Ux1%}1TH@Q5x#a9i{>iQ^;428ujuEB`=27497){rb0ls7K>Osxkb4-8 zNbn%YeH@D+vitVUq(hBI{=X3)gMUpmbu)H292LnB6kW!_x_dcur&Sz?YKugYqN(TCyxHhPEG5a+&YX z)wXmBsYcriQYs)4(H4)yc=Mt!6Uwc6*hZXvDxl|)=}ozttiCU0!yIALZzP7d54p@f z{U*j}w}aGV$$t~rJtEMAMc|_pv7DW{cnQcT^uzg-k};09GBXfQQJR^7*ocTzvZ6Vi zV)T0QY;`B)Hl$p7>CCR_7kHLT3A7NFXFr-E<;Ygg5jxSTprH@z_3=&LJAsAKcxG=@ z$drtX3PnvsR48U586Uwy#TCU_RVI#y-MRGbi$JUD5OT8wZL8lONPI2GH#-(XNPH^> zTl5NU0E|axG|ONx#DZMoN!6b8&?`t~M0&+AM359mImFdO%6}d4Z2WcG)$;MO31uDx zS$c(gZ|zf1Ix*&Y1+$Z0K`_MY8QvF^dk}3T}EVy@CqZUO}Sm6*{bY1u=lHd;dIjaBQ;c2~ovjv7ZX3#FuOM4`1ryOi(krAKaO()2 zV^z>l^a=^ES8%s{*DFYMy+TJ!uh0?GD=5yYGM1|s&Vb+wB)wu6DEbvfDkQyvAV#ED zP@e7;>L=Pe`WEB5c@S9~o*|bLtcD^Y2Z%h=YO-aXp%a;ThK`tdhK|rCn1L|j{PM&+V<5#JIgbJrBn4EQ zN<>|Z!T*B-*^)?CN?{uj1#|@B_EFsUByr+?Q$Lw!Xsx9@jpR9&5oaSJPDfmM67!6* zr6K_O+J z2CE)pCj2&6$S*jRc2H3*idkSDx;H3T|LkpvH1hr&-uqj&DDR$q-*UXA{k*RG)cp4Y^jU%Mpm z)&j4#;IKw(yPXT3@+;sAtQPlx!FRYc@GkoW zpht1Y5&26%S}O{*HlP(4$kktMk`UfHWo4+(-bwM+E7dOe1$i0eifr?}ER+5PbN&UA z$1<}oL==^4a~YSbvNXL6=may%R4bDp$ju5lC$|Ggd~&$&jXEtB@K&1h%Mh)8MQ;DX zAxE}G{}H5(lG{83T4K)lTwyJNQK|Zs0?+$YSqzKj_rYq?)rxs#o$$S_CRun!=h+J> zdN8jaTwdEi+8_zG8E}QAp69=kwk;2Yg+E~+S%i#CTkce;ez~Y(`A(H}_{5dYI*&cz zyp=^$`x6o_{>?Uh*F~@cUfGmNXe#ywLQpQ{Mr_dLd7sHw{4$KtMwm$RHvrkIEC0fT zOmBSGOSZ5(0qSPG`<*6Sdqv=FQB$FOQDC>KI{av0Z}|w|WU#iX53a!g@wg;D4Z=pX zX*%}iwwakTQXGNGIf^^`-Fao;ZBt{<0}B@6dE^o>R;u@K%u(DzkZ=z=oPZ9?{={-g zb-(BLRV?ZUU~N>~DewW4(R7>P0JY?IO7P?Oh$>(?iaQ4us?4lelX(*ai-R1M0v$D& zMkaWN$_w17iUL&~yp3whxP+ibP0ld;52u(jKjEPBTM&UgWMQBAIf@^E(2#NGgH%;H zir+(rh>}q6KI|mo1ye6`)2Xmw3&K>5DF-fi(X3#w_>P!26hNrgv02T+? zvgVc5<27Q9?AM)%4!)xb6>_a%3S35S|)$PV1entsoG~~6y|vbq_wI#%J!}S zSNPb2LVuqof@QwD8XG8Eo<+x5)1cwG;G#IchylSpe=*oe(-=fIpdYTC1s|TtD!( z0+pk>BlH_WXf4ALJZpgYjCIm(|3bY5IwX(BsZ@1#+Pt8>YA$%HH42ieP8$hbY*QHB z5%kYh!B_E)nc;0W=hP-SiXTB~1+kwhOVwA{`bec~ZU0H%%P{(kG3OVN;%-!!s`$69 zwX-0tm1-_)Kr5uy3g$tuUavHW6N1=v*4FDiHEg|FL^Xp%ef%a3g!M|8uGe#5wq6Ob z^;*-&sIV+juWJF&^?G?tTd$oBuoZ!)mP4(idhG?EuGhy5u&+6%wR%#@z#_{-X>-1%HkkX=h(2K6s0JD8dUJjk+=a|)4-Q|;F7YypQtkGuQOi8-*4(6eWMN`c zhjqMKwk4i44?W6=sDisy{8c6YABd`k!y4I^ShdSh&%)JN2v&}I389}5+OJkX@=o;{ z;tlIk=sxvEKd3iERX4JJH0Qx!x24RJ%J&W=)cYND;~@?aC-07W&O_9MS3uaL;yvIO z4pC*>Vb5m}wx|r;;@JyX#$_BTf-BW$Kj8k&_nLgWnlrZMhhEVAN-*aFmZQoev>l;b zWkCbWXg?wtuvMYf+e+Vt`u-Jaw(8#UZr^5PDRdfspQf?-}d@b53h@ zO7vszOKU(pN7X6_ncnxc0e)u_B=^3SK<-d^K}o%DrAcXfUoiTUfhgogvFU2Vv=U&~ zan7zoAv{-oZXmqOuts$HgQ}&WbE2{wX>=dekY7|=L|bD@*%}hwFv#lNv;@>CxvB;S zeVcRAbzJ7)`_w7+vr+1VN#7KYf%uyZy)N{9Pd$f2Qa?kR{KWG*f&4M25M!jT?NPsA zYzR%_RsevJBOlhOeXXu<0xB86C;}!Jz#{_Kr%FB!O(v;U29s^hBfy?PO$r5hG(o?F z9MNL3Xt6=Gc*rC?0j57$eUG$S6V(u!Y!l36gRzcq+E$8Rx-nq0&2Q|;Y0`w~W z>On#+sG*vtBz5o8pzl`|R(R;AZSjp@|8D8zvl|6ky?aExt*Q;alH=d2xSlSfF*_8E zvd(03z?}Vi)Eme{>-;=m7zPGGbXDZJRgVzeWQ3^Igd!TEe_!fp{q8Vl|3URFM66V8 z!OT%N<2VLjgI-}!XDs?5RRXft2wJt)_=Uvhsy+t8G19a?&pV`24VkUukXmSBzoUuL zdUvrVXQ~WiwHTJW@OKO%dm$q=4Tq#QwO?&r!Lb_y$-DBB>xr?P2D#HluXU;d=07Fo4&D3)QS6E5GkhDVT;8Q?#GpS?}w*tUlr81CIoBTK+rkS)d zm@ISl*I;IyI$4TySUt!_^7kOa`!YqB^3tY(cPE6YQfWzTWD@A#=-YdLll2GU`_&-i zE-hGzdfU}w-96uz7INo}wuQWDvRG!-z$+b2-3@@DVmqUb*9TgKQbrZOiYk?l#p0E$ z_`f*x@#=Q9gt!fVSA=$`yvg*HZWwqTY(>EpjKCGp)~~MabwXDGv{HoT$OZIU#L+DQ z(?Vi5QHa*=AtPj})$VdN-wApIz^I^+i0@E&lW3vui_n8=j4{V6a0NbtB-=g@s_zVk z4ei?`PAg*~c3=;+VAJHPEW_b2W2u;)@P_MQwSkxWU-ui$FG|&RJ_|*zhY&R;xvGcU z?5g@#vi?H+pekTev5`J+vmU^_zr3BE)hGl6SqoC>Q3hTe6zq?&b*g} z?7CbprrPaM+#=9IPq4P~2Wu2J1XS&gC~hqnWj20$jpDw7be;&_sXjz3|1Iny+{n;k zo2-H%YNd9OoVa}vP}O_T6tbAA0~0_KO9R7`=VJ+7H#uZN1`>=xZd}s_s35D?kY$+}479rTS_!K9vsW zw7v==e&G@{yYNeU*r!@k;VS~G=o?1iUjbjk9RJL32OClNpTWdxc1 z0Oa>t`749=$SW8PK}Gjs8tflk6{hBf&KLuohZBoD>{y_a)Lk<^*}@GfhoG zR^NJL#*PV(hn`PcdOl1Z^vxbf0YTr{12La@#v~zBdqKQYrhzjC^5SKUcjdGc&nv(? zps@nJS1^V^O|*@hIIO=IOf_nOMGKa3^S*;plbzBt*&+ zTfHfJ)KA&T{IDPT%0AvhZ_cZrfjX)RKZAQr zsTqdY-kdLPi3tVOJL%MuM>6c&)v*Fiu7OvkmUs#~4*<%E5kJB*d5G_IG9o@U=jq^= zE(lRK;jl(Nw8Du|4&YT=@glMvp>7E6SDhevr#gW6Lc~4qsA~8e-h)qFVMGlGbrDX3 z`zS@`Pq*zRIn}8=B=jJ5z@Dst}^z`BJfmO zQH%4UZv@M`P37C!c~L`yZEDVGtqKdC^P+)3>3PvKgv`9?F#~+kCP^j@o^&be&RSz0S-g(j2#y*@E?LwMJUpJ$JoflO#63#m>vN@kS zFFLB8LNDu-I>;p7Y0j725qP!H($qv8^dMk*8JZ;OpdZNM&UKNVwnvq~6=$MJd;$Q! zOKOhd*FEV~$WhO<9MLRPoYLd!H(J=5fiYj-SOnRBK-#B$X z^3W>(1sKMF3V6ZfdgN&)Ma^V*nAL$II4N3al74GN+>&}4BBGO`{C7i;Mz=DhdD)!( z=Bbq-J9$!6mH1q2zoARc@zFFrURTDOjMz2~sT&O_9Wf4!cp~HVPn~M0-xSayxW1pq?yFtdNi5|skM<**TA!Ym_}3G zU|N~8KQVQsG#XK6Ka`o8+R5vg~j=ZE)Z;3M3cCyO!Gl@GsZoWU6Jh+nufBw3ZUdTcl@76BRccWZ>KQjD`!UmU- zx>0bv#7+WEUv`&Ch+jPW9-$p7Z!&!eE_gp1fEIkI5%`c59Hy2pMg=JNUjVL@>v@h` z-5)`Ghsv8o3mp*=I@Jg}VTJya@}v{`1%O)Hza>O%uY7=l^Cr`RZv~I@OL`%H7=c?^ zwL$7KCv+%4QB7wdj`j+e7P47{=pr{s*EW38oc+@&nZ<39uj-mCs14#fRNf?7XkYNG z9ZQ%-(#f3tQz_k@&{Y8HB7Z9(7CEyU1?Nqs1=j(OUhP5CI%dLE8v4wAN2)gg1MDK*EDJqbQIXAOrb|4eWsWetpGQ%%u0Fj!461L5kN zqv{d3b4ya@8OYD({1^(-06jvzoZMx82iu`GJTfv}K5OtoJuY*ftfD_MQ zdfHK}i!urCG3VIBfwvE8t0SVjxr!fE-w(oi*0fFrwcnga16{Bb(8F-hmm!7{6W{c- zR19{hkGP3%M%oAh?8LW7+89PL@jU^}&BQlT617GmGx04dgcTs{S52@ll8o~u(m0OB zy0dR!M@BTe#KiZgDuD)gS(??eN2YEI-GKg>8U9?_j@hE`7oeMY?`4wLWsh>UFba7c z1k%iVE2ZU`_gaFR_g;~fJn#L<*l8;S`B$cmfUN&M@9m9z@c`YZ`~P{~Tg)V6<*h(w z>@okxy!Td<#B^bt^3Hp$@nqh6RK0+!VOCm}Nw&_McS7+Jcz;aw!Xc?8>`{x~MGAxS zK7}QEp^Nd;duE#3BM)Duxl@HN)7-HV)YIG_)&9YFCTFDWGw0ep0&g61{~QPX{4DKN z^zU(?Z&uyA_V@hdX;rJBHbGdYY%=v%7kzs=6$|VthAca+#YJ1?UckpNjP$j|bn7Y8 z6BFrM%KK<4UsZ#TwK|Qj@#6d=beUHpzOKj>=wzhmgU<#7bf!T70L5fjWgx!Z#ehc)RO05Lmil)N;!G` z8WYKLhUMElwE)ZDreT&;FKg%ULjy z=N*we$0p@@pW)23sU^>c3^gY~bv4>AlIJnYw|QQW$n*I~o@p2eD1eW_kE!8?bD^g4 z79yx`8fvWwHCM$A)!jcBfGgN%Dj$ZNt%mh&2|Z+#d<;WQjZ55+vt5Rqmq0zHjvMTR zgm7oXzYUKSx7_k=fvP476f3UtVa4s%I8&e^hVzq6Ed?rPsQD`-cYh8!RSl1M*0g+^ zXJnYGAIYY%W9k{=Ly59X;Vv{XAQMg zg33J2FjvsDe72$|Ey9*GGR&1UIF@uwQm*9ID&MuKL7KlZH8bHVgin*96EG z`0GWW;;Ug&!h!DnYkcp7NqK8YU6!I*f!7B-bq0qV#l%BF(r+A8HlQZv><>?yE-=1v za2hZSm8A@CB^aW%F0^=O6%3D#-QENrx8fQa4h!(9y4l1`dXCr!OXDupO0DDNtMs{C zFO1m#T;~6`Ju^4S$C~pm@XI327$n#vA8gLQ&}YJ*LD-_2z)}7Vu|l_J`Ck6TKDQ7k zG@&vc>wF}inBOW}ALL)+zjUeZb?c3LQ9TjZs)D!iRBfr>1(CU+Zcr_;ws?V2au9?f z$zCvXR0lAac`hEjYu#(%$(9uF88n~`@-D$z!&?R+d2=blZKOv^=lgw901z-vLwE>|159Mo;5i8JSXuKkX)-wQfoGwo4!^K zk5P(N^1Z9^*G*d944JQ9!0VksMrswj3c~j&@g`M<+=IoNR9q_^+>8XBlM@--PXQYT zZlxS~8e0yhwKA=5yioDwahU4gNT_;TYiB$%ldbkR8_x;U)*WDMRd+syiON+n_jy`a zO|bFr_6B7A`75Sk)zhw;j(2i|H43auu$HQA^O34n8fD{7+bq>tQl)fbV9iK<4dkh9ESS4jyOxN_ zTC_dt)C^4L41B7VyHaIjbD2^qj-C54^ZpUgR)Wr`50UvwH31APXTfn9fVk=V7J}(U zT&6h(|6rBQQZQDkc{t*y7dK8aW%o8q+3R1)vU9!o?N2gOwnGc)1PC6y9lwGQuJfJ) zh<^B%+21~Vn}$(?zZC?Z+9g;%e7hS6y(n=!Lc3(C_lE}ii8-gWdP(qn`1YINxhV01 zr%))p)VpUHExeyOr`?_-OT8NcqE~x&L1>4{i`yxyy=v=?EtP4u31BP}ZC^y_qNh2| zr=ZDL@F9~Zm>An3RZ$sC!g5qOgx-=6J0peUDhq!EeUxo1rSBil=3^^U)!DjYK||vW zBX+y0$!BY9Yc^REsD_-PZA}fZZOwuP5p+gf4E>{REek-?*8Vg~pRvlHr>${eZi+GK zJZ+Iz#Ugz8T=^LmkPn}SB9yDFf$d)mQSBsAf!9Mvj#iVoYPvpEO>T+*@9;W*oKhl02@ui-;t*S{3>9+?ofIVJ3wBX z?f|X9!!K98YVxxkK+I|egsV+Kr$T=WhBx6}kRA{oM`~?X3&B?cDUXA~eN_pgT?x~6 zJqKp(N{F>9-+kwAf7GrepR;zIjgYo$XmqZyjds0C)S_K~6D;j|)$`V_7Z_|sXV=4` zAMN@IQ2MF<0)&iRpEdRzn#Zo63z&92gU}9@7pLu7d$6%d={kmy4 zT}6X^3C5jBtuHb+y+8}|B4fe5t%aw>wn~Y4q0tF=p<#ktWkLVrg~q~1(U8-UI{$IV z(-#^GT0zhmRUX<#JO8^wP-1>CHJ)t#{IlXQR%E*);**O^28pE=4Fnk-KTvfsV|Jz__F7UrK)LvX_h_mRIci5YnDdVbk+U z+8)?yg5cR@mkXYr&>@6OmmOlJiX+WA&s(4Q#GxE<6tFI z%IdqMhHk58joJv3^*CrDl@mtoT9+^yl`w78b70n}gjl0qWn^R_J7?6P0BECbMMxX< zGh@_w1fHrZYSE~rCs?DlK}Z{QpTQn6=d@NwML!z#1Hsd%yAd)*{lS>z7h4Nvesx;F z90x1BO1tL8>2a_4_!mi7toU|)p z+OFrotX&DQc5Py0RR26;*Np&ZyB3{j?fSaWIg7wkBSkIR^&TK}W1WDIw(A^&UF7U~ zgW&%kV^;zmMbWgkcM~?CKmbt@4-mXB1jQTTjh|OgL_xs-9ta*01Uw;#;H?4gJBVDO z7&%16gD49GPy!)9Krj+DfFSXTiUcGkZ$lI^G<~F*3Krm?^0$H?aR3A zcs-Cm!pj@Wa@R?V$Q$#(TKS4V{vt1LER*+5QlyP_ajo=$Sf-VWp4+_ivC67P+NAoK zbmw^AK>BGfZ7h>cDZ4Q(RADyzav(p?%imsK?wg%089cWyh9iiiT>qyH&l}YM3x{?g z!L{XT1x0NkDl2J7jNZF1++-6E>J)uCgAjd)jomOnkJ9V>Li81^vE7JOwS>D8jP)pQ zxoa>n6_T-cTEewKV#k;8V1{c6s?pDh`;)c;9Rt~mwWn5y(u6x5iH|^{)a5D5)|P~~ z3cR(h0Z?In#tX;~>Hh+ea4kU*%RgE6y-CZTxenz&E`Bf;0%h6v^p|bfHyIMEZ`qg7 z2+C&N!j_z***pwxnY$s>=p_!~$q!8rR$GTcm47=hUUGOf=+P+A^Z1w5R{wdR8X51ewa&3^9a7W>Hm!EXU9GuJq!K7NJqSMn(T1?OaeR z-NiHO5o?dUuK@#(=HXXFZUjY<@7)8c-M=0QdE+A&k7GP&25X*=fANR^0wx!-@s0J9 z(|>%xR=;t=o@y^iYJ5g|*C$wk?d}{L3sm(@C?Ed@BE!3&(;absRNnE%GkI~RZ1UOT z2doNz1=x>n&wTeXxH~=gx&k!46)qR{ZVp*_vH6}89CIsiHO2Uv^V4o3igoKmZZaFU z6A91wgs+iM?AwNwrVvW@e98^)$|>y;$YPt@pM^>|)|r`CIAT`2lX1TEb;@_ejwO?i zl;g(Dsp)4!KH)9_H3o4NLGID6RV%J;F2#-8e8B{k;1HjRQsQZY1Dusk`(e z?0z-q=VC5YX{*nqFPI-8lOlH$sI{(LJ>bUE60RfC&v}D|xd7C1Pn`j3-^pxb|ET&) z__!15^vX88`cAXzfI98@yjzyVI(-dBKZqpU7ogUAif>qDJgAco>#DYL#^yDlTdGLQwHx}pc0NRQ0_dP z=B_Nq!&)JH=7oq*NWT?`gyXk@#)GQzi|JP>HV4hd9i8y^ZRU7f`ZT=v22`=XBV)LH z;BZ|y#2cP>WD@?4%)bD_XuRGWq#B3l5!c&TD*!{(@=g!c@^7tMiGo|TMyf#5|Da7F zz1^FF0Ex(?mVO=+^P6Ia|Sh~gZf-EkF3Y1%5F@!R!H0Cx$`~@ar-?4b8ZEdJ)x<1^Ryhk(qw~w{50>;X;Wh3ka^c-eWn_{{#q` z>Hh&rX8MM`LS^FF$9Ozv`sdFio-_TML7|R(8PPEs-AkZ6bV)iMC~VUQL#Fl1D8-w* z!&EshmqtT9`)(ThE~XGysy@4vl5|8K-l|$-2HoJREf=1&O1XdQnz1{OZ5Kym2Y*Xl zMIl~_scP`H2hZ7art5z$Ew~fRAAKzwAix~<4(q!MX_tdq>*j#^BP7~*CJKS{;U2pl z)C->a5>x^d0Qy@K;a*oD>GO0&so+T%^D%$BvS$agTeYqfkwif3Zq3*E&ke zcWHoKT5P)v@h?214JzHU%DM@oVWpd_Y@RO&zZZMTTn@Us@wj*x=C7w(72sC&d%T`%0;jb^6WgepRoss z?O(vw4qh8#UkM{sbm+e9Mr@hev>pqns()S-Sqb||%acQJO_s+pjvx2|v0Prf3Y5h0n6{fe^%&3o&DWE0{C$sS z9N!2E&SxB-pum?*Kv%*dA5uA2!VUpd>cTh)?R~(*Uzs~V#e?uY9{1-t%rkr+tQ9y^ zkAB^cYg{yltZ~(WSQsaSf5q-tbb~+C@C7hMv|sGY3u*XnVC4DYvP*soN~XC6E&;gl z!?Bqj%xP}ceAbQA+`B!+X>K_vndT;o1=Cy+;WSr7IL)PqOmkC2beby?oaTxIr@54n zX|74MQj^#;x9LYL+8AI@0JY5RrF`E2vA>CbWp0k9@>0#WP}vBVHvD;vrKo)-E~qY6 zOk@*G)hBiadP%~y1tSlNtNgC8WC+_RUo5) zNMOxRJ}<_wTY!)lHWie_FvGs3GV$yWJf1P^8;@rUYw#J0A#>46vk{bs=AuUdh3PvO z60ou<#kuGQD#L))7#?K@OB;{fH)x7~Ch=<1DaXH+ZX^6MN--7}8y8?EvmK0~$YHIY zZq|hq`I%$J#2|vmE&P#Bj*X(o7FdtU5tskM}RvMeM zq>bn5sC@u$^eZU-uc+)E**0zQ-!V;|iG1$91K^N>cs;q!$V>Hj0y6CgK{u>BTMG4j zgrucz|Jiu)v4ZC65le1=0*f^QFptObYr>rkYLKTogL)iPsSAs(c9(%y2wu6{i4a?$ z>Z;*DzvT8W5)-Z=K!17A=V1_++*WzeR{VBMFz1b+2(NT+sXjB=N_XIL7x`3EmssJs z{5ar+AdQ4h!8}hbJ6_b|SUR{7&a|*p!k63cM=5l88HkfBFb{KBW1wCEg$?Jb)|T96?*K;ADo`gZxpnEm?0y5|doNrG>e}U0!_T*{ zp5?B3PO6xniySxCL=FNaA}v6@4dE*HdRPQ=k#CVEnXCpS62+h>vDOU()mzJ!r$^33 zCLsO9FIb=lK|KI!nY&B*42h{rZu}sQNiS0rmfW&>((?siCfrl_o$3{i1C{={x{}-YXDv8_`RVz0$g${0;9;y^}o~ci<>H1AS>8fcUpbI zSaQqtQrF=(;jY5(8kDWB{AxE6yi-?jxZ($z@>TzbdTe^(KB#xXZ2)f!PzkpT)O=8D z-Nudh415UBCAVEj|HWhZjo!UW=zs2CeO|Gd-(c1=9kU+pl|BV**)QD}l&rZKFbhDe zxqW{HEnmClHU>agjcaais>)e<4A$I4E!W(rmVawq6-sXP`a}h|=EhG*O;Z$r#ct)N zxWH0CF3Ny4x1LwA3=PmNP(QHuT*+ep2#fX1x8EQvi*Ck_ zY=&)HN1LKvGSL}R${KN3Y!xWESbJ2F%mt zbPEe`3&e_i0dPYN=gV;}nTN$J^VnKSFmuWHP@H3bdQ!%)@D=iT1{u%xQ!8gy`bD>K zK68#|7eG|TGg4@6J&RB!MP~`R4@O~JkboiR5uk1cy4)Qc0{ca`&H?c30QfVyV6xUT zxaig>0Jc=1^ps>E7v0!XBtKqJBy)qF@*;{;=1$de+x1)0s@obhj;y+E(KA_fYp!Ct z>SngG2`nGLjbvm#!Bw{{@1dp5hCPc;d)#_JyZ=evlQ6-f9!6`VZR z{lR72iw#Wi$Uzc2u5K&GrKr&US7WBqYk)1f`KNNatmC3vE*z5uhAz5wjh}Rdl7v0W@^UHd*i*A;Ahi~DI^W(4i0&vmo?u~5wTy$%_iOuIbEoJ?SZj9mo zQA93PT@Y{8mvv$D91H~#$WtI3E*Z!_1X}{Ru@^uC0{MzQ)WB7@J-%jP7|45rl0e?Q zjWmYL?-J*Ngm5Uz7doJ@&SsyS&#AT!5+^*entg#Gm!TO1@AME|E$2jOh8xN z#(FSU-QEOM>cTjQ?VG8H>p=IZco4snSKaPcdyUg$uRWar6n`uI#Ack9={Y^3V@RiX1E`gLc2fsp9b*$9ctl1eEp8{RyK%SDOIo1{ zRwxU~xm#(>w``mztEBZ5;VlDCb}NPXwp;0UAY``^vHYuWncs8Wjq&=#@7R(!pDa-Q zS>R#aZA$;t`Q%^#Wj;9(l*}iSMZ)t*s*(9*3Myqjxz=mqd~$(io(n0PPoDR^%_md1 zI-ew0!ca0d7$rXdTNd7oT?p0alyCK8cjCeuAu_o#NChF*Dap2lw_+_`W|h|=VXR{n zEy6JNEGP+MQ61BA2&@?d8_In2XOCqVJ9>+SF~jbuGV$z=9?vj#15gsi9t8zMGK`(A zz+5N~%|{D?!WbEbm6U660bI$a{OEAj$VMzerU}tH2Q_N z)4=!xIbc%*CT4XZMSij;GtJgpSrbn7&Icuvy>G)xXBPRHCf1IC8{{Q8%X}78rQ51# zTSY=IveMYR#TMQgKF*oTw|H@sy9J}<$M~P>XD$!E?qs27aHM&gbf(MK#qk~QcIiJZ z;#&s!dEn;l{R!4#&`O#g;$H_z&Y(#1qtlx&rdcwEKFK^TJRA;Q2|aDEvpoDK8)x}v z$z$(kFr8bretii8^z00N*KWQ$dN^M2JV#Fkj{|3}KVcq2BC&ZHS22r-J|TSyo|SQ3 zpyvtvpYy_Pcuup4eW)|25NhyCYzAt;d0B4q$#9-fl*PF6R#fPZ7~h=8%`RZJ;jW3?M_F5GD%5;K?kx=0Z(5g$^A(+cF@00#* z$4I2h5A550Vf+tl_Pzys*7~L|!8&Tf-3bOI6TS^lX@$!IV6}S?oIfDE+C2^G#_gmg zf?DUPnV?SILDhY}#77WS^#ZCsBK_PO84hm-1NV#Yy8*x=Hv&|ZYaW7k`61!X4KOEz zDtDhjd9upb9*r;*AyE{uC1K&*m+}YDksn#MKR~quRqfJY?A5M0etY4(*nRayZ3(L( z75g9~?*>->S1_Ig1RDZCB|ud;0#>^i%JCP@InCfp1sWHNTiR@e_?(RGUYsu!V2R{T zqCuJ|G-ltD6Ufs^S^|iLPeSll?%qN{{&cWc1lr0*5?S1430UbJLi1l`Ll7 z5*)onoOmo57kEs7^caCy1wh`b9liE0&c$oHKqY(a?4NkSLQ|N^8_lNkGA>4`lTGp% zz+#g1pzvnqkV(W8J!lykm~COOLJDc%4>F`3wENlGK`&6)aOn%mcJL(5i;*t^BLQHU8?VU|Tg#i@u+y7=3c6qbc#2N#=n|J&j%$Q zO%^kc3XUEnPCS~73p^@7dX&Hl$GpX(qj4@Cod+t}qdRae9m!N?Lkf}pm_aNtJCfwe z#T|p>6Jni6*z80pZ0kT|<4^MVP_43n3g%?I5aiMBH|wkh`Bb4nJ_2Drbs&}(A^4LP zx>^;Ko1%Fc4dI347TO1RX`y+b%A7&9({^t^G;&{LXrx`9{ki*+PmVqu>s>9Z?S7;A zRI_f@b|?897{kgzA%=k|F|28gwcVxeDKwiJ74K?o_wU$|7(1{D6U=h~PB@NagFuz~ zUCgYhfvepYzU6h_ghy;tQJWvo@}6?P`#R@eftD&aEl`!~+Z-7_J$zffC^ zM1d~^m2mIlm+&fgei)96w1)%qT^@a_qSv}6pfa>9W({7Tord(bzq3|HgOaVNhRb7_ zACqPA^E`%IQRP8S!xRF8MeaXurVF^aRDfLQ#;C$qh#VivHF%g&HmnYYV*4v|-4*QLuMVA zNcBnMBxV2-5S>tuRhW!mQaHdT|AFLU_bN7cJJp!I9p<<$tr_&;W)>Jd{$y)=A5B?T^k^3XL(lfP+KGUOVi6VCCs*$q+|UZWh2;`renLrj?~OyXE7 zItD}PValqOD$6AuEh3k6#%}W?DrsSkZ2wp8u7;CNRu$R6G@pX5I0%V7QL2RFvn;QH zDtE_)fx`jp5&*9NwZ)5Epdy=Hmg?mN%O6r7|IRNAq)8kf7`Wa_6IgL`&_Itud-BZt zXo5Rcgd9ud100pmwy`Q)yv&}vj5K+SYCJ%fGL6S zCS0eu!q%EFPW+)cL*k3`>%cL8@Euv?w~2K}sff={51&mXnb4LTDd zbK+O@rbzzCkKC=1=-l{uFj%o0_cI)%Wy{=&+RTnW_8?p4cremj8Xy%2qz1_+WMVvV zJ0Uy4Af()N#I9k3R0Gmt7`7suiA1vTDPYYYu)RFthBu)3FkXdG>|ilVTRlc!j~_FH zdF%(~S5T60O+h^sO~c?523NZyz${r#ZYcBMa_iZ# zG>jt&EzmUmg+g$)iEU9Rarm^H$ zjO6?)A+Y8aUo6IwBjUs|mJ9$TvE+2co~y@r_Q4*{Sn|2YGnQ-tg=GT9k_Qy{xC!X8 z?H(Ca&Sl#Uph{gBC*frvc=#)Gy;R(mZDV*X6BrmCVEvw2)9cNFlj7CBRCM5@J|jAC za6@Jk2Acy-*c_NPyyRZHXhBZ;xlhd@^C!4)Qv8Bp=EByE%!Q`sW`)A^*WN)GT}YU? zunx>zNQk*GS9N3~yTFB801y}6)!1Bk*I_z75?Is07mF_Z3 z`RKxHnh;MHjs~SJ{7r%Xnt;0S4G*RZi$RsTFiu?PnyL%mQ1N_?{!og~KwYES^br>lCN8W4GZzwK zE}Ww}GJj5T;oi;6g-^FI7bes^*#y@7;`5^mHv%Cp+-EOyVX0!j(qlY(n#a?HBY+YY zz6?rT7}f5xN2nKm>cMp3x1dU07$+{=zoojcTJx*dg`2ddJIsZXB6p1Aug-| zRqDcEbD;_UPZt^}AEt^YXnys&@Zffm$MJfMPKlp#7mZ67?$O#@_!g*A z7Y3UPP56Jh&_LNR6>^zyx4H0w{mq32Iav#X065JThAt#bTv!KYE+oWUc)IGyr)TWF zB-;RxKpHv7T)11!Q{r8CmoFAwcmWXN!ZD!4g^kq{dz(kHkM(%Eu+rlhNHf|5E<9a< z=bC^9(xU*8u`nA{sSD%8g%42?U3jF5*XzO?w5G$%g;V2y`%=+`GkiuI3;VZaMq#kI z(1ib|3k{U{D_l4=e#O1!!tKy4(;0)@TkFEX_Yg)G5+*LJ12Y#AVlK>69ofh(aN(qb z&4qWjHx~|6^W+m)bGk1UUHCZ=;=+GGi3^7-c9eM}`zK#My0Fh7#M6cMgVJ7DrNC+v zP!~@2VD`eLph{gBCoYU0sxEv=#p`w9n_ANk%!Sk9pZZ$Rg@-_e1ky#IN?jOiE;Ql) z=|TgQ(1p|D`;Igh4miwQXpjZ9EAtC0%g{mX-wB1QvPZySeQWyTJz<*3YUHFR!(}nvU zMazb9;=*k3d@tOr;`O@lN3H2U=ECXm`@M1L!l6(hE#|vf%N+0nNb*QE;Ql)=|Tf#!&J!S z)zRj{Xh(CQLAuqtaE>nwT}YU?unx>zNQk-cBGr*k&)8VF8~_;$yPRMyyiLth;$1k_ z7mF@@5C{pRMWDom_bGOqc_jN(kEaXUo=7}hcpfNq;aduvYXa)Rn>?5QcW;fpF>uM6|Ercas+XTb>LPeP~mhHxgjjy_wD+3gtu3~m^g$ur~ z1Myj2{BwoWif;+To9b-PR!FdFbKnE!+A=SGghFb?zYoO6E6=VAaIMlO5dXuA&!{85 zH4v{*p3O-yPkuQNZ+#l;zN?P-wm|#>9iVJJggM%VK)j0=AE1!h!v7G6Kd(F+i!ndg zZ>-h5pBJB1M|^uA?z9!zIDoOKS0Mg?7jLbQ+T3>p;@Qfx7=*a^d>}s6iw~+J{$n8i zf%2^Vqff34#Fu*U(mLWhA-*G6;ERpZg*^LAgnc{)t9$r_Hfp*fSW7xCjJ1!x2o}}a z5iD9<9md+nS_F$a>* zYZJ>oup*0OZqLR6uc-emr3^n4YcrUW!dUx+i0J)=SQ{z_gt7MN55fL=FE$lgO!oQP zo5}2R9fJD}PAhh2RN++)y3kv~7(6T9^dUCZi@?|ce^2u}woNijgtX&Wuf)~MYi@-%$X;8r}0YoXP5OONOb-g%oaUAB5`3wv0yrk?lDP zKw;OOSIcb~l{lvlxIO1;tzZGgXJ#ks411(xkO2I;TR;EumQc*nmE#HIv<;7_*a zn1T}KmAXBr)mbbox91E4Rpy3iUV5jW-z;KhYJXp36mI#q%dD*422_%lo7Ne50< zMUlVYz}*dM9Vq*&p7;53*UrbF#EHoww#P$obR==&$Yflw$3uX0CV>^$3uVsy9p~cA zW6n-><^Y_FH%w&*NMZj)E8ipN4XPDy804L>Hv~d&)Pa~c2*F>m-yviQa+ue=jK`2y z^4^OVP$==pN1)2wXQ>|Hoks7Gd*P9LlbuknM`ZiZQq_^qENu%$`Z?B4PXmQM>@CK2 zdOOa8zs>Fsm2NWtk58er47q8;r|B&aOm%m-Mu$rLi6d^2&23!RoT{n(qU4dv!JCL` z1vk6)3gH*4&Jl=yC+leC^iEQ_%nj8Up)bSuf_u3wpxEUh@Z>6f0jhz!if!}RA9)XS zDr$rG^(@3jYs>6!zXkfCCu#XRz`z4;`2Euxme5)Cb0U8fN(A?D#~+&a zC{<`ve1BI|wg42U#j;ru`2?Pwqyi8;d4Rj+Dcvp~ zz=UJBTLenFU9w2H+fj{lyA)JPxBJ^`Vz=v{nP>i6+wD63hxxGErEs;|kt>fD7&jZT zXn^qvtQ)V%36Vx^A_3XJTArkaG$i{18m zAY@79HBfRrZrCSPCZ7Gc$Ftj(dpxhl{{^Mp_A|2rl!vzMw7ZCXHWLi#v)yoxzs>G7 zm0{2P2I|>o)5hn+_h@!WyxMfi;ZOQqcZFQ1$DrR0Mh4RF>OzwH-FV=n-+k&O*zbCW zm8SH&&0d22F7smcyK5C~{ceYQMknfX(FRfOEA*Yl{+o9;L;vV{7*YAL;RPdo{W#pg zCN{|YlY|rn&gav{Kg7OM=IpM#J>lT@J!ic66z1ul zjKj}M*vGToy?YJ5h_y_@`PSuf?1ZWfMi#F1^T7@sybjk*Mfw-6I|`L?UiA7sB9R7{ zaEDG79GeDYiCg^(Slyyao`^)Q2dl&_!K^Q%NA$RdU1YUSI4uH1PoL2CQZ7!-Pq@hM znm<16=e>&;ll6Xv9bqY$Zvs~2%0R7j73jfrz-{mnkDXv_bC?1~faUAt%5YsG%4`Q^ zyP?sOheq4w*`I6nkddQ~#0ar>i%#v4d$GH9HBMBx09DKA75(j5mgYV%YET-iE`eh4 z6Ye2UXJxZ_6S~^Hf%7MEzSLa~s*S2S(keDInh8}!u0NP7-C^}XT5|so80(;=$aMyV z*C6A!d3Q!i(`2=ZHG)AIi}@Pme9dNxWj7*P?6c!*l;su5|A7{~D*@-XfGTxi5qX7j zK6vs9=3;9GUrQymzOyY1tl+Yt|OTGGG`It%bY1v=}f;^VY4%F z+Mo&<`nZAlZKW&Ml88ON(KCJa+WKos51-=x>5XynNOZ`~_@C$uV)-$384KxZc`D!5th_I23Bw|^SbBN>Y!@VR5YSNFsd zFB*Sa94Ec~IoS8m7ZAGcpU8GWb$j%nzqW&V3RJNxTZ>PusaP(WMYK&?lNSm87L1<( zDfe;DAcbr>P4UzxElT!MHyhpYZ`E+o(UNh-LRXD^6YeuG1=bo(aZhC*ZLk`*%)^cZ zbNUr%c`F@p#t+ohV2OvA?4H1&<9AmD-8A&;f|zb3tX_*(&nTk%F;XJbYsAYeQKNN; zTTp|32-tI1a%|j%02vnO`e?%KwZ^awK@q#su^EN28CSs~*Zlo;gv7u3#EW(S9y z*Sq09=hmoeqh73kQ&1g1RX750j|JydF6&jaM-|LR`d;tgBdtgyGT|--bp@y(kF^S2 zz&tj%^+6t^gFL4AJP1h6!vs4-Yx5vd@>phhoQXnpQXl34n(>uu<^9+XjNd)}3Q+s? zW<3a4?QX;Q891jI9we>e3n;$PUFF56f^i2x3HK7H7ri(EtKD3jf9l1{+?!gvpq=@( z0DQHP23YFuMF6x0)~mLm&Gk7v3g%|$!G=j?@lydlnBhVUW&2=i9mSia?DARqSdo&oO1yRCaN+{i~b~q@(b7CIY{I0a)%%3j;aF`418?qsMQj zzRddyP=w=)&ssp66ht$!yt!L_f_rDmYm)yl{x>QjCi_|}Q_-kweKZ9{E^1;d|sP{mj0z~gn zbP3S|qCErjuL1hl9H5u_m&^U2`TeR#Oae+EQRH7RhsQGErCWf;+ApXHpycIpb;MF% zE+-;ZBGd&Y)u!ej^!I@gtHtD`o_4b{LuPK;^ z%;fE$$&grmuPLYjls2HgyH($4J))z|3UprBk9Fp&55ll|^%8EOV}|ORU#qv;>t*P8 z1i&&kTUjZgW2wu+Aht|dn`))I`(eI2m~TURt&dM(Sl1kUgBbdWz$bRY`Z3SqwWt+| zlc~YbYI87LiK;{}&0;Xy?()aDNE`LWj1JO%OOVB62)p@j1XoVHkUFP7FO;(3oj1TJ zaWl`yjAlZd&r(kSYpYCgo{Il90{$DHUF>!tAYP|R3m_JKCEoLOHuAP#VJZy~4Ar0x zA3&-hsJ@_?^ljgF%yR#(cw8XLKm&i>i#Y= z5<+SOA{xf*79?8ld5SyoT10#|DoJWiSjuijLh8X3sTY!@wuPnawj`t`rbx|Bl4>(4 zR6@H!390!hQePxV^$bhdtx8ChrASpJNj(;pvYVEW+LPZA=OZE z2lu57TPI2V5tgzWnUHFyII;YRNm9q6Wu^GbZfQd5j1;L$lccT-OW6%hNL`sCWzCVJ z%;PGB%THcwPf{R*nHGU_R_hg^j3`dpjNu`7uN&kaNHA&ZSEHQ0^1LVGH1$c9R7bVIV}4CYrtBPtOkCd9ypby zSr5j6H?oia42s21xbHv>LK^NS0=n9{4-w{ZzSI?hlcQ<|S;dA%$4ueq^(mMu-2?SO zIB35LMr0uC{S>H#dlSDWpmrFx%$>A>~;uX9Axtj=D5C(C{VTA{MkKdC4 zg5^LFUg_{c2(Pbp$-zn>vyDc|m+_TvV&I>QuS;F8>G)=Zmgq6FY5(Yp-aSLXyvAoY z5Y)4vFdkFl8ATSb4g;b~0(5DBK53AjaU6+Owx8zNPLG&zoP)-_(47J%mmRv}cn9za zcMhoML9KLGqk?q=Ip-MUEioFuA~FmVMG!kwzs)&JoObAo46W-{`rF#Hg4iT0*(PPq z`fSjxIf71c``(V_f{9S`HvVPV!FS=vJMQb-F@jwa`2>tL0kat|?q|x#cMX#x8E>JF ze(orL!+gBZyMwsm;7)S<2$hIVM~qlClYN8QIt->!ib1^(YLUOTpRZyiuzj@eRtU(Y z{XRFd@o-7g5Sej!$1d&3mP`BPs$l=)C0|@)Ec04;X)iEdvVWzpzx9Y~j42+*3)jie z1}70`{6L*u+PA%h6C*slr}+ezT(Z~2UvjN+ytFq&+m2GAXy5K{v0A*ce;Hcj%6_j~ z?aDrkw<~+W^2(lAxv~#qgDZOh^U9uJxw1EKHZ51?w!g_z@XB7mys{@)uIx|LdR<|5 zbkW6LfChRPFg1|zht=Zb%0A;Z8c43}A5>;Ob6)SVXE0}8**^%7T-m=33ip@+NWSWR zR0XS%Zddk1%2oF&pM~ZzRiSM%kjDl$C&=U9Adhyr{wfK8ho8Y@2# z?*BHObQE}NAzbdqc0*;e0_=N?7-ZuU5KC&68Tw*FOL&yEjz#`D$RG<)oM_*7eKx$T zS`8I)S(S{a_wuL3Q0BJAt1H){ROm6NruTaP0+@^hi-3@kzz`i8X=~&nFWE8@oUaO=(<54Bnb*RR zKwymUS1Nmi!D?KghcVFg80K3famEkS*+@`A4BYgxDhRr0osqy0FQ1?zLGP<)v05An zE*NejK@lif;|=3&BoHh|0%Bz(2xEhhK)@Uc2$qq+z`3+snX4&eDL4`cm?HtfG7=PO zy-LhLF1peS&_JC>1O_sGbuCUtg1N+Kl#XiE3z_qJ*Bh-uMuHRWw2`1UD7>r)faECM zKm{}RsEyJ@N|YW2D#+ttg=PVYk>Hacj~PK8B|Z-VlJhXZ!lXQilsta3JU9}J)I1`4 zB9E`!KRyqR1a0pko+H6Ips+#)fQ$q;;+$sS8t+3^M2c^8r~78Wk>FJ?&XHiD7tiwI zT;tv9#mn4p;bvBMB(V1NhUOCO{k+eBA!X0I8B&ZB3Mm{3jJ3y!)<|!jO($_AcmTpO z5*R9%6|j+jY#9lRT|o9icd^&Nk$?~x2|m=qt=A()g2O$GQGOj@XxJPHjNd@Z1DuQm zN8dwxmN_fv{}>4jQi0+`d(ZdTFl>*83Kqua<7>0USO!qMVT1I1-qU#nx!=84yk#3Bs7cSG3CoNEgNGhW3AwHE11{nvi4QRMY{ zZ26ZP18l;7^|#%9>{I;m?`@z~I^MPp3uJHu7{C5Y@HYPi;4Ha!O_@q(iskaD+~1A9 zT{COb7=Gi&FnK3>s?UsfqW2g{-%N3*561n{Fd6M(yICKyh=zL|~cP;0+ zro`Z4=rLTkO>tii!d{)b!pQg-CfkF%e5GTX z$XOv3vkGQBgs7LE%a0lsKU_OOciUg9R1>O=n|3EphTnzC=t0KEb9UIZl~kAtEJZn&X9tKEAzU*U6QyH74`lW|b-AreK!+n_{60jOjZ#W;_TVQidQ zBBuNV>mfc!jYO05e=A%evik*#5*UbqzZ&>zcQ2@=?gorW6>6pL^w@Gt>?3cfabS)I zIN`q`T@DI%<({W)imaer$Hvb2kap#Mrxp(o&HYZyq}=a$N(N_e@sazTup|c11s={V zPlRuFjkFG2tvdlqS&y_)kxuOqz^sW>wq`w-djB4(`1ADG@}bzBs3vAq)fn8oa{BlU zPtnJJf?DZ)92O1yEMoMth|$j?MnBgPGhd4seJx`2HN{F@SVa83|5%oUeh>2l--}B6 zUR2We|4k*^K^9b&xwF(3b=!e_@%=pIU#7>FkK#J^XE=7Kf%V`Vf->T6K@IrSe#e730gOrUH)Xp*PAP(TV}J)<6|um31ysJ1Tj2hg>iN( zC{&mG!`@SLKG7547>>wI9yH|fp!g>n^!8HlfqHEDsr$gI=LWr=fXXJlFf7A1>D}e^ za+4mxvQh6xm3B;z5J8ZTN! zRl2B5cavSBvyP*H5o_E@w9X*5J2w+MJk_)dP*VQA0>s4_0A2MWn@!z?JC3g3!@S+X zvAgBLv35AT=o2`8YeFd!@Euzi_nig2|8mm;n7Msy1h9KP!X~$IJ+_r?hd1{75hb`;ZyVYeZp(% zm4wNK6rX^&1!QA- z#515!4L%@oqB=1P%IyJ(4?U0%NPG}Vww~rc zpx9Sc+9MMBI!t*;;?R{+nOs)J9+IG8WPiG`3&^(p>15ab75i4vPxX`l*z%}Y;xpbS zs%;skqoC33U*wQkLoe$Np&q&luTE-C*tYtg_N?Jw(wREI8TgC+*%a*atW7#s=KV>b$u$d|o z&u-@NY#Dull9n+Bl(vlL6qpI+p*{H1fI@EqLz=}Gl;SP_!;@TpJ=7;Ri+M@B+H_cD z&eP}`W>MC}ngy*Q&BEBZWLvW!JNT1UF;CSL0N3)E*rtW4ts?ztYZZ5Zl2(x{5^fb# zBdsC@mC`Ey@S4~ve$~v|w5V+rk3VCrB8981f?R18$=sk-w0PE9g|YLX8s>Qp^^#UG z5fF(N`#)!`;)PP_Vv)VrD*AgYTg9C~$dehfJeJ+xuvx&yFFV0wCn9~j$1(&od)|it z@Wt1ian1{n9Pn~iOHOy|F`g}vrWY{Mo<@4~X7`Ski7{a$a;a?qW$p=;u8kLrBib+; ztkQUa0t5|%hLMJ0>;kf_VUQjC$slr~swn}kcnJt;6lI{+c()q%0+oqppYHJt6-{3@*PZ|hm1HY=SAi8! zZi7fK4`d4(2?{ST22WbhBnmQG^hs(IPL=x%wlK;s!J5-boFDMv(?# z>@2daL6BYhH`h%VjZt}WEE-)LjkLo5RKKs?ZxBy@W^3fQ2o=2ng09PQy5>T_PJM;m<3#Bz1?Qrm(P8mc9>N06^bkJn zWsm|wCdYnQLM@y~9R4cTsTem6QmNX|4x%2$$G!-YSFzNAnPmu}W%=lr>8POT7=!ti z)#(68Tk7_jwWZg}q<$UtVOuKo`LQjH2SVD?GEmZ%-d61UdW>g3omFRs;msi|yb2tBTQGVF9%TlxJ zFOU|y8YHS}V2|F#gwd{qiCyc!%&vr(T^p#5LYm9$ddEbw>lRQloPVLfYH!y=eX(fQ z<6k$s4hAK5-JsabdW>gR`0~-N%RGKCsA^DZ*R(ZK>Bf2t4e2c=(Wqh22KNrMxbCP6 zzH*~kg-yyH#Le*h>#(mk>HKB16+6y_&|B=rV6twITtG6Ojm_}Yn*atO}iC1bX z>PTEeA=ugLNzh_(hWE1+j3O#eQT%$hqIea@wRU4Yq!6@eZ1Vx*{K>YBH4L$BtVEPK z6AaezWvvR|I)4WDhE(eW(>^SY3vV!fwl@RfoTx_t_eXHAx~FGoBcfGG!J2f{K9KtgfvJtA(LZ`zqFow{#5J9 z202@`p$E4A!g?}c(v$1JtS1v7!{7ti~LHa8c_PE!ZpAnKUv1=We*_9Bp>kX;^+YXm0f9B$e6eWPY#_w0kAM=po~_vbn3=Mp9#6Y&^LW~|>05zaZ&u(i z6S!=><6L-@yaB8ukfkmRN{NuYRWfW+M#$UNh)FBNq#H|UQbx!@&?^zrAZ_;d5%LRP zTt-MjBtoV@EJDr)J2gVyt(j$urhR;7jF7dOQXm!~o4%c_i4pQS)l?vw7D3a0i;(>x zEOF0-DkyYDe7F~?jgYeeROIWbzRdw1Sr9_*I}^w|{s-6gGtSt%&BIFIo zK(?iXAr>KtD03zlijcUtKp-?`4l03ICeiUd79EniG)u0$`nb)h>~g%%F%rqs=8}z2 z&A+sF(js_{7hfY=Hy#f#BJn%tCgFLrdr237`<>hLf}I~ym=^gNUj*p~K7|T#{);=M zA!e-OG2hNdVSaUs&>0&&$gjPf_HJ6_H^7HP8a;B$<#?ee&eyoBigAx$i}8jY8$EQ@ zDmKnL!P{>ZJJ!vho&vSjrPqVsdw9Yf5@1^?HiAjbSkN<7Yc(6d*1QgdBH5@-IVeAG;BmJPyXqK9f99PkL%7s9B)O+`lSPiD4U_w08~3 z%o4Rd97xMN>p;|Y!l%BrXCb}J>pBV49&>5;kI`&S(X7w1B9uJ?e34rY9!$+Tou@2o zA+fc|)j1QYcpYWNYK@EQDyZEGI^d*x>=#VoHoNb&0>ovY#U$Zai85y;sz!_= zvtexAGW|peB$i%;&%V18BM7~BLfYS--IjcRcFKgL`?GSQ_h-3ZKDeh^dw+HTbuFw% zSEp!_E<4ftvnjf2@6YZSgZunyuASxL-1}jmDyVlI*W1eUGq8cHLHZZ|o;Pk^kG(4r zx#B%0B;C*6hy=U}3tlX-``RrZh(yNE<3j*?Z<`56yw3!^zdaqAj`@J?anA}DnX84_ zrbpcH9J_|C|7V3A}FL;lo^N zi{NG$ckB7T6|UewJn6TNw*hp203Gu%#DYBnv~RJ0;$o-jDS-@bc%HbHcIDF+p8}7y zcu`kbzu?l z@d95G`Z&xFd@L&IV^K*T|2LKN@wZS}=FAp#eZ11~0R`g^Hk&oe>hroCO*%Y~Z zKqcI*`27awCxmHRDz70_;cbVR{GLogRGKr^tS(kLEE| zcDx?3t0l65yIL-yX1w(T2WlvD$0&m1j34oIgW~Zx>CWdOWSg>SIu|K&^G_Uc)>lB+3uv{fhLxiYT=e)PF$XRX&RI)xLLM9C}3W+t-(X z&K{@i7pw$J+#zs@I6cqnV)OVG6w1uUspcs1W0UyOz33(QSXJB4m^&Y>>J4h8f3zwr z;J3x`@hXD1IX+?q!}0kl%2Ya2EZw%!6>3KEbk%2imWS|M>6YplpROu%*1Cf2f1GD$ zuu)BMqp^Y#+lhi^Y)omb`lgaw)0rO0xDT_GO>Wpa z#^w@!Kly>5bLxLL{8Ckcb^m`GjI5e1HVp_C^<*hO-iP zTYm`O89NUJJ~qMm!~ur@dtdC3Ts*gngspDDG$2OD?nDB=MON%aF2%D8ouy=L+MvLr zV{JFlbx(rPei83J@X_mJh?^%Ln|~Qx*<_l`jn(%QH=+2$f;AT1FVXC>ncbM!%|5$E zSg2nI6t*@3(ta^LF+_nc>>rU1H%eL_7nSfCG`QgbMdVY}*x0GqM~IuXVB|mnK8OaY z43zYf*A%=?j~PSLTYCZaldelBz<$!-Q|u>WK}kP(BP445WQNDGpL_{wnJZSD?^QtH5LDTNSQO8G%`WVS_9vBl;u0g$DXYnR$m%HCSBYyxYZ z@`dJ7$}}KkDP=P#SxRZI*rW6q&%W5>xs-C&GUBCK*v@$wNmwOwWvr{-NlQ?~hgNv%o?g-^j+X&-e-n-dZ|D(3? zNt`k_I!Q(vrEiQ@-P9QODmMQ57qDfJ+T^l^qaE&u=4$m`K3U4V$MUquugJx%_%0=Y zjY9et&c~}AQSvtV1RsNTL{}qWpD%&{wjK?bc=rQ_Zbl*zqW4OBn zTGsk-7lv8LTLgqW4i!ek>I-{><4z2H9SG!vj)VpTH4I!t_}#VX?-sEQC{hJH&Wj8%k5tf~XE zSVf4%s)JQW0SXhus#^h&ShX9J+!(u5ffWSSboGU1tm?LkSnhMVAC$zZK8n3gkMZn3 zefb!xHhVl{RlGEaRZlALc@s#DRYw9@>cXIuSarKf*2b#We5}HLzcqMEn{rJB%q}MH z56u#%!Vok2SRl&WgQ}o5PKo-mpj4^xfbU|=Sn!C8G|XtXA0BaW8GUe=;*P;@^fwsq z`0s5NM9L-I%%1A5e;==UW9lpyd)-CS&vU2YY?iwm0YCkGH|Q96FQXhvGH!hi*?bLZ zin|Z9=;)=u-H!jM{$~1QaO-L&A5s)Wv7TtaVhzS`^f53B1L0eyLU^VW;5H`Dl>Bog z`{78L;$DSZY$3=W!g9W>1;kEwZ@Iw;is_RU0L=@RTWN${kl4Sc(h+dLpx{gwz@E&-ujt{Ci4BJ!mxprjMXEM#;O`CtUgprgb+)`H9(U${0c0w8KRU z*jr`(I5653WsHrlzNf@B!riXuP0?eH#`V*hv`CG+X=o%mC^`qlkBu+67yIcEJ!Wfp za-j#{C%3R89`p^SMQhnHT7a74sW_+~KrM8CL#)xyub!2GobXrWKMtO(r_px_cPyf+ zsAvmHRO|(cDzGYs+{)ei#i{wnR$&ME_ec~$eu7;DmxHPmEOS*_Xx5bN$=5FQ;7 zk+*^|?0%0%Whj2E3-!M02VUE?gWvG@*4{WI)gj^7s5`IY-G|#Tu`-9({VwsDcDrJ(g zExVez;s_A|7m_FnHpWh1bE?Lj~*fBl>RqDdn)ovqrJvXpACf^_~3%=2ze1Q+H zit&4yzB7RL1E1?6<(R3*^xLoT`Eee*)N3-11*x?0>+ZoOt~G8?^mSvF1me$n@z&r~ zLmV@3<^V+90(w9e*w$Qm6_k)X+@iVY0jLHW=???VML-ojK7-isJWLp+&p)bqIvj$IadULt zcIslEp9l@o=eunp#XdjEQ|$Bafx=*fPHYM$siH>T6?h%&^rC~EUUab2Q%9)_ORe+) zAeQ{sp{%AogAjF3Md(RSA8xhv}*Mq&Us854pK}BVxGXk2|6aCKx%1L6mRJ~k=jJkZJf}W27~M>&L^3LJnbX+d z((!xVW|rozBv9l~l;&^uF-lY9o&^K1Aj9t#0HJOo$S<`J9f;iRu-_etMXnIP-VoDK z%f)60V9;>B{*i|G3XIn(S+^CSPWzTwpMts>xPS`ZXgJV=F9$=w-9Qms=60*rver_4 zywLrg2CRR>SkKy;cXwx5%}t<0G$+@5qtBi-H&Em-U-Nm$KDp)uVxq~Kw>nKae_K7) zS9?aVqm|zQ8d3X`t66)7uQR{1sjWdenX1;&OLh{*sV!kLwXFlQsVyNkwLM97Y@=hU`E z6^bF3;nf=6{?w!GrRxlcY-+d~RH+N&WT(heRKzuqe>A_^`R&eoe6ylqv$UrCpfU_Q z;U_cfdk~k+bOt%U*0583MQK>V#ISW>W>`YZuotS14u>ZhHhqg3wg)J=W_VQ#ol9WN zoxWH!>?}o6Pufb|H0(8?)UXw5(5)fEj`Cn`!FdBzsSD%8 zuwPLT4ZAF4SRFLc2WiYzgIRW@V#fxSebD1+*)c$gWv78s z%i0v7JY?Br9!$$tgDQ1loLKho?P}Q<{;OqqwJ=btnu{7>a@poLT9y|D7ec<+9l6Uz z9y8+ul75-{>{mig1EUm>MczNJn!yOkdekErQM&Ii_ZVWbA`uA+exV||hcIzZ9hkX? z5OdFT)zRU|q=vr&0EsBwel+)V*6C0#fi<`LV$nV0fslx@43sqdZi>BBkMZn7J)Z74 zYNxp;8u* zRO}asFLRd4`B7{r=frRsCv(OqM8)BY|8VoZ3ZdXru2SAh8G+0_l22HtJjE zj{h&-kq=Q0RPOzHL}(fq7~^$lFLTDSi-Fj94j3YCyccT4rv>7Ry|}SVTw9088?&%h zeoG*~-OC%RUitS`&RQsZc^odmC9*dEmBnA85S7PQHwJP>lQw<UrbHTY3oC;c^sEXqotn zsvXYiu*igPuWOk*QA4ILj$D3~1syS1BI1qHfQv@>NY(gj91;18^7 z?6oUpRbxHUbycHNl)QPrF~P5Dbn>ejPuFl&qZ+OHpFeqHYc?i_(Ubg=@m0U`##XN$ zSk*W=$~Q(V_6ePETP1pW^q;FRT>U}BVQY}k)hCSplL`LLT9!{ZWf#?VI2yAZ6mOLq z5Q&}@y#?#hZ-Pp0XGWZvHm#QDsAP+=tox|?v3Y-f^oP=?WS6*0gE0J9sd`5 zP?;l28zRJG`D2^$kAZV~c!T6 z^-o$aP%R~GmEqBXm% z*}Md4X*LEaA;g*u+0tx`9XYujcLn4jzMoK2SA!lp=P$gGSz0&HqDyNd7$J^f=o|E=0jn$f3&fSp?xv- z4gpZiVvrI-%q(P!S&W_8vDPf)R=8}Wh*_rLT+CwVzE;9c=^sUyC(S}JF-skondR7Y zGs{3wW|r%%7RWI$3jrE?m0e<)s#yxXGWMo2uZ)Hfv)rl31yC3r5N(fkC1!CA%q#|p zbV@P{*Aq4TVSozhFaD`*yqiCOBv%q$-RBC+>(P-d0~ ztro~JFbe@1dzJmQWvXWB8n@PR9Vq$R;o2!G3$_Rcnd6n$789+3#;+&HT&6e%nfnE& zLFNwSNRW9}&m_pas%LXdvkx*=nwk`3EOOKrWcC;iH@1VN@GO5S5W!B1#cMt?v;vxez-8Tj?LUKfe3@-y6*k?@5(aS$ewm7tXb@f#p~ABJeDgz<)GI1hsf6|c9S0C*`qz4*R7}QN!?si>kA6ak$Z+NRG0M7 zW9YhdG?3WK90KWe>t(159#GY+Y*isT{8FULW#cg_XbND~1K<@g>j%(X=FU`zT{e30 z9d18O?gqGTZ1QA9!&tZF!ODL3=)#jJo|G<4a8IGs^tjehr7++0h&Y|8%ajxlOP| z>jvl%JsYO_Nzfza`W`VB3ECsxi{=3FEfQ9^%o8!$ z#o1QZUhPMWg)#MV7`-m^A)6 zFl+pTSmWQRI`WZS(D)w%KpKBM(;ELXYM>GVYZm%qvGHdEA&WMTfRe^PNwIJ0F`hlr zbba)ne&OIu%!6c+BG>qkki-h-bD>mqo|GhXU&seQ2 z%hMH2)K^#~>Mak3qB6JHYB4G45kJ4iQrq9Axv^u>Zk~qHLN_2c(yBRIJ@=tZ=R31@u>C2rMWDc$p^=0W!y871#7pWqi~ zMn=~nA%O&RzRvhQ9nQAO;!K|JsJs?mC1crWpYT%)V)KA~16V&sjqzjDse6$TImtyn zID})`#JA9cAC^TJ&&mhu%9hmcN5VI>b92u!JNE#sP9`>CM5jjQ?_rJbzi`&y?gQEa&$fE)g3=MGquTs5J%&c4X+V~`Feqhb*bdFgIwkfkjKmV+O8@ST>B@Xtk3RbF&H!y8 z5v&fxA{Zg~D|XkTE%a6eC1TXcd(o)5U{s)lxT-~RwYv}Ji(K^-?6g;SCU&f}+V_+_ ziEcC%-y&^A8|(&RD5x@b?S*37@3FhkcLW)rT=3w8yw<+2s>`Cf77uxKeDm@C4!N7VlN=&@DX3z}H5rv=4c9uzx_4~k8Q6x$$asuIOM-s@zsMH7o% z2WG`4gvD;5^7R$_Q01Lr#XdOF)QY_`D0Yk1X6-OOC^jKdY=azGTkI`Cu|*S$T?b~x zCWOU4<$o00TKk<=>{j!FVt0mo!m*L`4vHPd2gN2tifxbqwZ(qT>!h_s6N_C3X2m9i z#lGXe6r0`U9p!yu#ctgw(>nBhzS!*06G4?Z!-Ts_$JFj(u(hUg|01uF-DROyNlR=2 zCEX>A4=h25Si&HmsY0T!-A)083Ixw>YA+$uP%GcNKDwVg(ihaPH&8*$+vA;R+ zI8ajTFg_?YAyRCERMi$c$LnOVMH7o%2WG`4gvGA;FU6(<<9Mo?e|zh(Rr_T=3r6J2 ze6i`k;h@T#VZshPA=QBfJI+)da{vGFbtT|Y6iaw}ci8|c#se=90)ikuHG;PfiK5~O z0Ri!jh+HZ}ks!(uMG?d&0WUlWs34*e5fv{8LXcAeVL?1&P!SM~sPUHf|6Ns+J)-k{ z$@WbBRoz`xUDMsu)3d*6;xR9h27DJO(L^df&;%i(34mVv8geI}K*VCWOVlt@k;EdW!K}!Hu*k)A7MbIi zOf-Y1yGUcPei6EmKlxnRf%uv)d2^)xMk?+MG**|U$q=NcAAifRsI_+NtPclqP0@Fi zNr5iSP$Ik~q*?x~UQ@JbIE;P;6Z{K`(=D)$X~LBA?{pYx>T z;Thqp4rUf%lyfk$D09C6_5f1r-HxBq86peO`H22(;NJitxWc7M-slbh>J`vdxph#r z(f4QxBF&;_9>knK15xr@kO2F`U~BMt0*xjR8qFjH5HlJfIAs5gR$9Zh`WtBx9p>}< zcp4@=fs{QsLe0S=K4ZwEjiY6BvFBj+ZGn?ca2m|ACxo)N@y2l~!}J_!8SUuxd=`io z0$Ap_`^FHYWcQ8#Dnn<>JbnQ1NxN@!NtL-darcc`KKHmgTv0b2s$DppnDMWGpmg*C zD^;;#!%u_{KGeM617A9N!EU6)3sM;ZFAy-jfZz(33KTDBoMm2M^lPk|&7xfnF)xt( z=miG5!eHhF0-+bALCg$<1YU5r3YcJmT0}?s{OARzpjhGs{g6^GFytiTXc;Z@9Q15>SGZK5Sgt#0(teFT+w{^b>U_>@zmgv90mMbQYv|mH6H;$Ikv7UpLTLGL{E)8bc6JnN&s|?dKEcc3+ zMa%8CEiM2V&kCrpoj|MZ#351qQgP7_F!6A{isn#${e-U|i`TS_P z5+KELpO8l^XUHRrqh<6|uNzt}dW2an4QAOBVwP*8GE5t=+znn9E!PG>iM$t(CGHw4 z`rj;Pl8O`?emHziGqc=XULvFAETqJ8sSJVT1Wd~jT;WoIV!4%|iRFym#q`oFI{a|6 zoa9H#8LYFx%yI&u<fSgy6#Gc9)=fMU7vWWkzEMgN=SOj4y{!&Ae1nw#Yod5N^# zR;0vosSJVT1Wd~jT;WoIV!2prvz*Z%HN7;89_Mprw3Pg4IfFfDFteOMXt^|qsg97q za&M`CMJA|4^je=EEq4@(C6?=jl(soTE-{Xl(U&|2EjJoCv0NI=vM0nWSEe#d&#>I* zUKTA^>~m+dTuPR>dsWf@W;v6TtrJq=$>BF!nC1TP5^1@tBh7ND41whYOv@3BHSn6d zNfyg>22I+W(YKjinnkx~S(}smXgPyzHJDjWAhcW>#8gK}V7a}uhM6{X*CN`)*OZp) z52RRbDtRPY8u9?+Xc-;gIcT}JfD_B5!7O`1%yI{-4ATZI_n4PO%YEu|r{zLzyyfaC z`rj;Pk_r_YzCS$d2(#QNkR$iGtB{g5m&y=WPQbJr!4)nQD3&V(O)O{hlT9zpqR+H6 z%SnE;oWVL6%q%AmS}qM@sv{(@+?6UI&jhuI#(jRY+%rIm<<^l$EN95;jH6|=h1U%& z_X}`hxipw%Pl#D=fXXmE!*Z8+S+v|?ZJ9eQ*AXeSxn7E{+j8Re%tC(m7vc6eGLfN#|Suv{DOW6$wuW|BX_~)3vScQzi3h z6CNi%s(NXMCt4WBEC9a1}}OEgLlp>%<|e~#Qp@SEq-Pp z5g4?20kX{#h>v~0lMV}e>l-}U*iou7wdNjon>N}Guxe>0Aj(FT0v=_fK40w>KR4QAOB!l!ARN%%`; zw(;+L&TQkY{$sNU3)Gd~*563{GT@VD5f&@SoHBV2&!G@Sf8MFNrp60y z-QfYJr31)kE?&o4kN5B667CcD9C=tcSKG_$UBz2UkZ-sxo+F=nY|?Y&R>uU-k%xsz zi{rvNmk(vM#MyTD^@)_k#y^G2U17v_;o7UreFY+>FMNRowltC3=pdN28{3&$z64OzVvuS=Of4jf zT8x~HS58bVq++`VToJV#cD$*@(C^i%Wt`8GY9X7bB@Je3DTX9b%ST9=T2@*ukYk`0 z0%X0SsUtT4%=42ACqcRGe@VZS4M0&BuPn?Yg32**O8OmxRp`z7i|=3f z^0D8s)8pCi$UF(fkbcJ;1jmc^k}v%u>UQ_5BnQtK91573m2%zy420e9dL~P2&3^kLwEJwqvD#T(>3fHuIVL?iRR2|46AquE>=; z%mb)&Kge}++b7*&+MUchjDM}Ge}uG;{RO`PS^r20F65rVTMpmweF$f|KjHwtKjMcV z>Hdf}`27(Zomvk!CBHx7(A51AyGcQ^@xE7hXynY}=)c@B>^t!2{)h<>+bpdAX^aiL zJ9SE+)_G?l)VC_`cXolI^O@bvk^6mi-0y5AP_o~dJDq-zufSlxGufF(Skx@TZK?ow-d<_|l2$Nux2D4y9hy|n1RYo@6dJBTlTmU2( z{r3zDMvb&$`2^Oy>I=(Y+?za}!KisB;u(z2MoNQGR|Q^b z49UT00FV_f6_gZ=vX!$o7$xqH*j}k70%|`FO-a-~9nxjru~e9;{yiY#?pzg88?SVK z#A8v;hmh_LJ<(#0-%I$)9LAi?aro4DcfaBL+qi)5FvGSVp1=@O ze${b8EX?E4%YkW!MmJU?uc_2{!7Wdur zwUDecQP2^1W3UCtJ0YRW9f(wqv*?N|{T9ajwh#}#IoP;QWT}_N?Tc9g*}?ct!0~w= z1qM49C#^{3HccyC$(wlFP;o^RcvYl5Y9`wk*XzvU-JJsQAD(?07f%OSb}uFnpJ%|e zVMt*-suEK+FvjM!$l@)?r=kXj8ei)bHP>gueS*JKzG{}FFCJiXf8d5^Q#khrJ_e~R zet+OZV6Zo^0J%5tFwes6fyuJf{h)GnSMRu6qZcxoit}Jq{#qGT^Vau~Qf2qxKlDs? z500qI$nL@BKuO*<%bf-vi?oF=b;sXqzpyxKzx!y6Z7hXqZ zi;gc48UMWkXG?j8<9WCEFvP3BAmHqe28BY8<7M9Y{u{je?j4pBet&o0ef-HHe$Zjr z@5uGPC#5qicL@w~!m2*_Jyx!-@HFo5{lQ(KP^Rkg{!hiDABC~5fkZdp)TCzE;T*mp zK-D!q!BKTnaiP*>;ia5%|LNz(r?_6Y`~xnp^liAUO3noY#IH`KOLsu+nx9K&qG`q; zg~1yD8{JtrUxo9Pjt09)nfX>#{rrrzp7{n4c6nyn=hQA_CSao*iStP~U+!o%V=f`{ zh9^Al3|wD)UOjB1M=Lelz28*bMz7KlhAAps-s^k@?@U$2ZTh>>y$f1T(C}SI1cHw^SuE*pDuCd_D+%lvRiUE$e>#OM3EXwkI zZZx+pTktSYY59=U_;f5cAA^fa+|B-fKm6a~=zEE!q~^ReEWO)H-`-YU~u>0~ap^q{5l4%#D|MTEpGfKd5Hj z>`j*ntN)moZ#sl5^Bd|Xu=t$)zgccBno6VqO=2?s5~9g`clR&Yl;NTb`aa@72jJY( zz-&y#efpgLb~bVIoqkB0Cv2C4N@3Gh5q>0t?+@e`ptn^M&eNNC)2pRvZbl)0hgjFL zyERS!R_%os@ebJsFC2jBy`kv&;X)-kEo_=CCgSoh{>`;NE@prG{nohfYq)hjVvT=~ zpLa*gDi=IJ7oBEz$Gf}IR=hhVLV~;FHjw4+*t4759iROI%g43g#gz6(c-=X4twkW< z3qbh41kiOZ?;JckI6Z>p?Q3yOZqflGX!R#W4+dFo(qxfh7^IvKyGi%UwPGC6oyCZ| z&w7f^7#!I%!H2B5unStjTwG#ds=y#utso41PiYNGfv!I}`t8}Q!JQzKIXb~TJs791 z*o-Zy6qw%yz^)nXJ#aDzOWa-l|8V>-bA$1pOj{iNCyA+J#uE2BE-rC%ynH$jq3bYT ziU;~Ec z=@7BaJ(7yT2XSA=HFPKN|4J`ucmk#pT>Pr~L|psKQ@L5L)yh-xL0k?KgvxpSM5^^w z`}Lw4*+(^M?)koJ|4v70nlFy*21L5|y?a~te!o6q+fssS?)6x9@8<&{-TQBmlJ31> znEqjLB>3?EfLFozyR$5`U%7)!iUh(jboQyqfr;t)xwB!}3IN^f&?h?CHp=TQzW zbBK@okV=P0qN+m(l@5_eHHWzNGCBm+V$>`=Rl!*A;7)W1ju{CN)fgm~5F0O&Y~#f< zv~-0cLmcXR0K}m#x!fFTdC{Tf0U-{x9Vu}r!;Vv)jNGR@o(^@y73NUq zA*Bwr?-e4v62i@)Zt_4n)KsMKfo0Idq23@P9jZj-(`kM}4v7wRvWiS`C^F&@f5_F! zXW|hCKBwO5tbg{0L};o%kX`&C36T93R+oMW8+ z+E>_H0VAR5e2=bjLlbNsg)tNTVWx7|?GJL(m~pA(6v706|B8Cuu^|zb>I-BQUr0hF z`N9wsSA5|+&5(24<_pK=nJ*+!)fa?HUr3~yFT4g`@dcw6Lo)2xp|kk{A>s=LDJR5Y z1IgwKHKvYk3BJ(zTJwe3NQp0epzSc1z?z?YUi5`XU-N~INQo~Pwg}ja9?LzJzA(aL z=?hOHh3`9pF21k?=jIDz)xs0?*L>ki&&}IZgX@T{ayt`ZLneA0iN5e`f}hl02b&)2 z-JvB|Ag)c}1^unxEdwJm5ROF_WiAJ)OMI#WQUyp=xKx&nt{Z5NfwskeUuc?&Dn;e$ z--Qtc=M7}e;1>@n#d#8_2|)awP?`Uh(6RlPGv^Bk-|C)Ic{*P}!*O8vb*}hvbvI;F zgh?6>3VV274hm1Wo(d*W28BoVr*SwaG{zhVsJ~$b`lMLAfa`e!nJ)*0XAL4R=`aq? z4;sw#Vt>vN;4L_pVMKeq*XBAku{<+j`%V zPlH)E`kotEB+hkRbrXvpcUNmON$Wu8sB6aAxl};i!viwO@F0n)uHgZpcpV(oKH>r!9{lFnIXpN?3zi3Z%J5*|aMp&y zgWr&n-e4j;HR4l*MEoRFQpE37U=iOirQouN-)4kG{3NPIe4+Z@pcb0E7V%#KuM7{2 zHw!34{EyG42XT1N`8HOFJDto%N+R~B+7&M(xMr5e`iMP}SiV=@5h>}-8FpJRJh;K* z*_#{T@r=7qA_YBgc<|wsV)Y^jx8B?m4`g`%8YzT#&?LO?b-VYOD%Uz8V!wwRBr@}b za=aOscK7x#n#=HD3}o>rWo6iBVIP=^k^7vHt4X%|9LcqZbO-0DoUGn{cyRnh|J)r+ zgr+(K*~KA}P)QEa8I_hUz!J^02wdh62j5{1kwjI85Goxak!lX{6nMoUj9LxJP|J=B z%^{8+Wezb3DRGFwI{wN-+m6({;jwgxZ5~U9XffIx!mzh0Pe$%2kEcUi0hDyg3XxKW zn6K8$hj4R<=RA-Ou?i`SvOyDv_@0csg+HS5*=4Ih4&o4%-XT6taR{tUt6u2Zwk=3l$TB+hcIhvFks3Ln1WQ8^|u+kc3L|hW*EwH=L}Q z7J|#XVYa7ou$V+uZxAZIA(3j{aLicq2BVfkGPF{2v3bMWfJk^axX`@eNo~P7Xp)hd zGLNM<3apz5ZSz{SGh7R6TRVc?lDj2mG zlA)15x|tuGGS2+qA*3WK?4vplp~D=hS>>_xgKCduRA_g%MFqnitUMXHQ$3zhp&w9U z&51~9RQOKKmI>i0TaUa96xM2jARbdeE{23-6P(~nh_7{mOq~F>@m)edcvqE~!&+EC zphm zBlDCI!HXWm5kV3tc|@?)=f@EN;alDPDlZrjpb~MHgFYvZ_Vsk*F4^iNT2O>-ibA2K z?y4U!4_WF$S*pd(`kOJnUg&)Et=)V0SLTKSHUO8(-0es$_o;i4+T&9XA$7{V^rJX%-}Njva2 z+drt>YZ`h%d{8+o6d4$8$_jqw9=#RAfz>Wo^Pk&K>isB6mDvN;XnlRsQ-QrE@TtJr z?_jonwWm#-$X;VPjL`_l?QZTYkk&YT5HM!D%X%A|+^u!o&Ili}8ok|BhoYhI2Tr#9 zt;EOt_+8SWn*W{p3yv~mFUv#Q+{Zx%7vQAA>U_LII7dC)O88Ngmx*Q&Ugti!gfh82 z^sq^EC~hTekQ_p69VE%J;LphUAlrgJQZa_Z6~dFUjcCl~yY zZN1-0I1OeC{;D8J)AA6cwUI$RrVvrm{Of4jfT8vx>vZ;mCN>_?2qL!-3rWQjluT{%T zpC{EqHc?9&%+xZl$kcMmlv=f{wOZgePzwQ~7E{N`DQZ~=gsA0HFN})8F5(a}F^@|> zX5Rr9-r%?=d4s8ZxV1C~7rs`XE*+y=kneQ-Zd(r^Hn^cT-~*eUW4Pz&eIz(`D@W1T za<`F-q<`~>xj6HetyAmNdR=K4cuvd)=FfBC&Z5x! zTZJ~E$*oeHFCa_GZJc+xA5~PPiNVz>ceXYO-aSI_LSF#Mz_kZgH>DqBG;pnUIa(Jj zE@SNbxPwJBi_AQD(H1usJZ0_+5Jo@)Wo{Ev10G>m;Vm%{961_8&rfhsfV^7~hy{@< zu`zC9J~O%dHi)#{B5QeY(QoIaQT|}$%p->-*y-N8%);5ek6Ji0NIoGJ&PbMUX5?a! zEu4{xDRx|ua5fv~66Fou95fz?@;CcD8P3Qi;Vcbi;p~`cR17zauRzM8yh#gPn-I<> zJ!avo1ebX%)?bVAogb$#F6$nMlpHJFLD2e%TD)v|dLwx|Q@(oyQ=A2sixg7CJil|3eV*Mxc*5s2ZecQ{ z)8;Za71v0OyGH7EpDYOEd%^6aKd6FBDfk!n%@wQ++ga9=77+~+>Wcz52~YPBM#MgV zNJM-WDT#;%&LOzwUXNu&{Ly0>5s!JwB4T%7cwDZ(8M*)Uct*tk0VNS}K2jPHf7OaO zZ80{6k9#nOc)ufsEn8A>(s^(Hw6|m24bl88EaLqdtg4iktJ)~-Sp5y6BK09rF%4o- zkq{iK+>0`u6n%6%KeUMR|Xzk5t7EbZB|gO-@eZG2FF9*E`@t70Bm2Q~z?l%3BtUk@w_is4&2`WZj=Reh zZ{1*dwZOC#4V=IP`@)L zLz{fX*Mg>=?lYpPcls1feZov;PE(IXs>&U#0%+=oz?oobf0Ja47n^g)6L+l?Ux%sX zZroFAJ4Am`qUylhpCL~)C?(n5SQ?bDZ%~@GNqEa~*O<4sXUM)ijhzaqa-H>l#nECe zcoM3D7d8M0Yw#jqSTaC56jjcG_3x2=rz}wp+7`!VrYZBuCidDFMN?1s|gcBr@_q7gqWeSx-mgp9bGqNLi;$QCH<#%5&z z`-K5}Y!2Dk2zVH~=8w1CbtF3o48Fk^RQmgOPj@mr=uM^aEwy_Dfgu(Un3=0o8sAf^ za!nFq>;jdgcYDUzUCtW!n#7E7eX45aH)FC8H!vaINQhhQOi>b=$~n}FJF9-uy8wPW z?=KyLa=5ren_1Oh(ZW&CNjJ=gxy!~TO`nzFIzE2|bXyR9l`q0SFOy}3V}Ej&^nq$$ z;LO8oFVOqggZWlvSK>GP+~@txY!l{MqcB9ZBH_$6$XucyVbUnlVAd!Iu}1Ne%E-Dt zp;7z=fJDFHFIuB08YorGBe3RuUo19?MLqmU{)S&{H-I{0 zuQ%&u>Wq6PrlNvgFCigVh?9(+R75d;!!MmOkYYH;cq1?}nP!MeB5d?YvWz~BoYlW} z^hs)^%fl5Jea^)BNNB z?+2N=rXm+Hmmvy?FmsVC<}z{#$TnF(DwbU0ikNE!&SkQ|(0`i-JJfsH=Sh>1O(qM{ zU}m8IpIi&q+Yj%Ew}U*Pkk{>di#PlK8M$G&d*{{t!0e~DEBIR^SCK=faz z)h^Os)BhcBnEs2Al0&@meHB;^f#Geh3^A>&0Zz1Hh|C)kv_i6I#mKoJn^%&GWk$Fn zS~+8(X~od%YPFK*^Q2bDCR#~@nO2rTl6Ym#o3&cmWR*aUfmR3*t>mjVOgpBPQXnLP zedUEwFVa!U#2w5ZH=)koG{~n`I6=7ITdW8dx)|a>MWUnBd?;ZYJrE`xr8Jmzln9|w z*~vXbW#k~YVDvB^0O=?l{I+$JECd%4SX1ruV@D|u2X*!*Vmw)em--e!o zvWd5)!OYvnyvwSyo3jupYlA(l638*|HUh-kR^X<^qf&p(+d_*djCY3CNXdauxIxI8 zTeWxbUUKi^3(Y8ND0H#(;#*8x-N7%~GDI#B7O_YcZ5g=`WYZR@SO|+NqOHeqF4{8m z_F8TI=`BQUkxjIf1~YACEjDdkj+AN3q*WrvKwFCd5N&0uyV#w>wAHfIwABSEImCw| zde_LzN1c~lH_Ws$3^>t>A##Z@t&l8QF>(>erWI20fCg7YD|2uzS~2uqnk{^2f1f9{ zLN?J#8qBnE+!E8uAf!wy`&%V$PS6SgqLq+p#k6BudBqE(4{h?os29=7Q7SM80>fn^ z;Zf4N2)}1qF+?E|rWKM!D@HB_*|b6``dqh|R!+gWXvNUS*J`D$&y!jqn`k8sW?ESU zh_tLAF3VGO3qUAmFtm`W0x~OeHi8Pvq>^ocgJG}V2`>u zyAkt*uHA^%S_J7vT&QQh8-bn5P_9Y0X=7cL+*pSwv;>&&>feW(0j8ix;+BS}B*F|p zvKYX~nZs%gKx(DS!4+}Kk8myqFm!=t3%8u(^P~aDCI(1@nE~>anE@V0$_!xA@{wa; zfWH9{15~O3%n)XPzGY^Bdy$eu+_FfER}6vSHJKw!E3X14S}{Z=5vCQAMJq(K1ab_tLV#$cT(x4_ zF|GXIg|V?7^nS8dURQzT5Ex#2Bs@wQ>si2wRt%9jJV7fYi&l)B3$kg2RCKy%xPL^-7^@W1X)QX{;aW85`?r_r3-RmBw{Bp#rRt8>P*6 zLvr)|PMNcT30J&1(oC`*g%pz*B991jRFcIcMlJ%`OhPJFG2x1sn{^R4c{$Yg##ejcKJfQgVn^PEvun5Ezbsb%$x? zF5pBfhA1M!v_i6I#mMC#n^s80vfGiSm4!H$=4p zq)aR4SS65S;41`(R!ke_Gp3bNFN{I$D=&jv^W9rBV)JbxbZx%vl_Jfz zkDmE^?Iu58Jx<%O4LQQ!41xgLYWGp4atNippb>gsFGQunyGD#Q%k1}oS;i2hM3`kr z7Rw}(%`&8-6$h5-f^(TZHFW59=&(b*BYl3fisZ-X(1pa2%6%Dt^;pR~bB%XD~^TdjaYe-DQm;*pG3XssIJ?glj+mr zA>VwQPlnE_WygqmotiP}nbBvCtqk>3PwW<-v06NSL&X z*7E^U9-M6f&U7(#RQK8~#zIs7P4Py4XO<Fi*sz6nx=&;p#$bVhuM~6EjFP zA=bo5mL_K8tUGFhAF0@930LHnunp%D{0!Yp^F=e8=JRATBbx-jG?+EDn<}_*4u|j! zcmMZe-D}5Upb0HR#%OWN+yfL^i<5>|jaelgd-T^D-W40I;T0k!hbZY(Eo=$ohGXH3 zyG%(h0w{L~gH#h@N+Ma5WaR8owMrrt?`q+SC~0Eclw{~LYnAl+oy?O;BAX~F4Q5K( zcaz1VzmPKRoM*K_jzK&kK-6OD*iRkL)G~UrsbwZoa;$Te5c171k!avTfNe#h;J6}@IP6EK0{>w}BA?C`Dx{QoW`;M9GrPXI#q4U3(3k|f zk}P&Lat_FLe<8Kf72=B6_41GG{$l7-(BSyveSWm5Z{UZ5!p!tPVr9Q_Tq2$y={Tut)Orz{UwlT`W?SCbs|8Lx3Q$t_4#xyO}} zcYQAxDzmpG*|Q@t?!YO)c5!sE7d-9=c=IY z`g@GOsgABe=xP|mvbZyH@HSX&4*|U$yN#U>W}l;e7W*VrMXjk z|5W7$C~orKn5;56cvo|myIPAj!>*#>tKFfhV$F{>Gm|FuIQ%M=S?-WK@%Gi{kgyYf zvun4l41MX2=EPP(uFCrs{SzLCe}VVECZI#o>d~YQ$rN1w%Drnt~k=A#WKZvS2;IGXIuA65hWW2YlRZQSr8{ zAX@OD|9U4@B&NM?u-uhHfyPn70^Kw8K}HNJ_v9~m4|r=cwnJ2znRg;;caM!nnakWt z5D3}gH={^`G>Xb5j@4y?|J@vc<%Kc*4P>gxPk@STL0%xXF-~z5^ZQ%N7$!Om%HBK`6GE zxXXpc-)~z?{NmZU#YBJ2GY|BXEhhSZ%~;1RCVoLmwwOqSr@lK(5%TVE5-RE4;Y+qr z((r_gOTcCC4#z!}?~t1WPt|vah04`giBx-c_=<1n2YldY)X+G8Qu5qy*x@G+-@ohJ&-q*Pm#iC8#K9*9K6%tNU&-T(S-+Z zB-bMc#_;GA*`nee6=^pax$fcoCz}d9qP4GvZ0tby$OCl5x_6mMgr+(K*~KA}P)QDP z8VW5AvB^|^cdbKIcq$ztiK-4ER60Z=)g0ooZ_Oc$S^~-FB|P>&a|lAjAq-MUh&cqw z<`AE2=`!!}GQ=Ua0U!=>;VyHCU8?*%0&6aZ>ck;t10fFa1ybS=hW$l(GIE=HJRPFR zcjgc|NU1~g*E>Z%gquTL?}2oP`;fx02Q+brd1T~D_%;bfFF+274)H$~S+_%oKm4GT zFNSDrGBK;@pZy^bn(7Z^7k@}XCHcb!lv(^ChR2{hvc}i?!+`Her9UK5)gOdPe@LX7 zKkNdp1PG(%Lo)nf&SdikLc|{oQcQ^X1IgwO`)cXRMTYpp9o6O!pCctb&;DxLtb6GX zgP}U{htq#Be;AIG_=92j^o&PF?r|PZf0*a-?0IfPO8sG$8a5lk%^!aAK>9`@yH?3AJ!-MO6_&>@sN!s7UAhHk35L}myIS8VX3}AR`G=-RFW_B zM|s5;YBa+VaM{gbho{mPlBntnLZvSxQq33ge>7h(YG{J@h1aH-FAyTWV32G=%oj*D zU)W>n5Eu<2%#CD$<_nUa4hK1&S6YG(xaH%Y^-^5R#$$k^3Slge7o>1}*bl3kv zQ0Y88ph^TK?>F%zK(YfJ;alA~3a#C5V!3~DlFL1Kzs0VROJ>@?u64GqM0)(`lJCTw|I!Ced^*1ATq{lOoe&O+K1F=6)3>m|JqOSgx{-$j8 zaukpiE)|sYI{i}3%5J2QDgHwp@_^w2jkp%!!;c;Gh^h5j$j1JBiU`KeoM1E-p_7QU>W1+SQ*gNk!bGy!ai zN*Y*y>Hb81;l9;sq*L)goyXnK;Q1KZx&hOY2F_pN`d99d#TW?pC8_hDJof|Tz8olz z^5=e_+?T`Qk8zIW67a7V-OPpvf#2>x_|LX{>8^pdg$LzmUVrQF5r5YUO+l{i%qNoc z_$aRLcEbh@0S`$vI9ELmq8`uM!*j34LDb_6oUe1m&|^EGe{=nYUWbn{$!;_yV>kKD zX9j7Ww^@B}KJziw_Y(w~kH9Z`&!nOvZ{TwYZvnEzy@dZ|Zl=O5c1>1sp-HIVu!kPE zMwT0jY3wq@gNj7Vndft6>>^Awod&bmMTo_&M^#1+atmVDG5{oYb#gK71&)C%kDUDq}DDZbcFp5U$NF$oi6$XDY(t>dnUIZFbQMt>yU1SUM(g!vXgYs@NBxmID{)d0 zKi$I(_CSCsn-gCI$urLYWvN6-*Xs?Yb8kv4)tG!zdi5rLeTJ3xLuoTdgg~} z?#Il!|ME&BM7Rfe!VfkCClfyOC)xkQh#g;VXudlfYIKWhb{ONz^KK_)eO8C84&ek@ zcH(7q2q(!pF)Xsab#KqZ1L;pCULE(j{FXs`?n$(_i)L7R8~HKzi#jzD!-h{Sj>gxJ z21hP=E)<&PFLe3bUtkN%ipCJBO5siAuF-k8d}CxQGT4aA<*w#tTo~dn+*pqnuDuW! z@*^W4DL=+`FlsAi1+_5kK9j;U9ub-T6r0PdAeIAG=4K)Fqfb4C)Y%zq8)K`|SsSf! zWv&ziVS5!RVVi}Nu>Ji-9c(Xxty93(K45FDY!xoGkQ-fB&<6ODoD0LG(i@G3$Xh{> zk_`0<=%J(>b%n%W)0Zh zcJ&{}g?qeySGtd*>(Tyv_eO=wTC@g&7RqrZ(OM8=^CV&i--oHl;Y zr)c9!q{POltbvV%jW!lG+F00V<1{w2v9Qs`!bTgDt-__Uh>ar+SQ6Sel^)nwMAF70 zk~aP)k+g9eh>SbaMY@gGyJj$q(dU}ZCSlKwV?gK+_A+-4QWJgZ6r^7ArJOoHovnT= zSaJpkWo{w<3(Jd0k!7nh={h1=>6SqI^))W!-w(IBBeJ`grur3x_260Jb|QuCKk&a* zLpskfDJ+dfgv;EJ0Di59_YB}4K;wxyH0lZXz5zV!;XeaJ>6k}CAvU^ZxZ1_%#+aJK zej(UPaZw8QDpH6T_@BtW4(B(3eXDD$b)(wlSm{1|0UMF2nu}TIDUmEh!ZNoTgcre9 z=C&dAHBzW9(MuIwN%T}0hR7rKGUWY8;h5!yBN#@mfUH~bH`_mZ@sV}DkE-?W&R|r< zceB0$E?Y~sf29P%l@KxuZ0_f0BB5)hoCSF}%WHspMCglJQ62Y=g}!r*-*78I{oaG; z;}TjPqj_f)db9pEUgQp&iH!kWe@ZTMEE^@n-A#(%ea7GW?T2AncHU(R#EN4#Sv@jyU&W@>?y4LqU9gBerY3eRU`F3q*l9E z6z8k0U$h*32n@5z8+*Buw^#{QxK6$VH2P96i|)~8U$6D=(YAh4dA2$eEX{VStJaL<+je2~Ao;dkLp_sk z+nIMI_gUyvvs|~i@YV*;MnWy|m*B13H}bYn{UP;uJyd@hz&l;fQ7&|K23P3vcy)yQ zmZ5kT0p&h^-ntSUo$WSooKZr-2WiNjk1+b?4U*7?oG1^w{rz>Jny#uS;t-SjrEaiPgt z!h8q{56n3IIr`3a5C$B;;KdCnlOS8rn%VjP+>^QSWFooFjz6I|R{8xiPQF)gTeSqf{Cc8iU^}@BFli^x`4rp93Z$f+{FK6K?c_U;WjopLAhwf3RkUv> zqYuFkzADUi5_kQS#5hNCB>Bs)4L@?B4hqS70JXU(W5sONrYQ&~K=>BFd^8C{LvXrh z4#+ayW8{-n5{5cezKR?&5hg>XG?)#U2(cm4=_(@+r3r>i`yEU*ammI^q;%q3fyD&Y zyzEQOA=6HeU4c~VLu|-&t77la-;CUW9?v1uJwVBj=>?>8$TUlV^Nb;R$g~#73YQ8> zn(mpPoV7zHKivb3QRnw5)kHw=N24)`-s>Gojd5-|4Q9G;3rO5Otx{^oRX&d@*FhbJ z3;xf6TnV5Ya`jOPzvFsM66N{?%1ER5jgm$tNPEyIem$zSKuUWlff9G?6L`cey*pZc zlcQYlz1aFp?R0;S#Y&%8sn+gWtnKE}6?NWs4no+j7n4HRd$_Is%!~XA{U8pmxS2KouiEaRz6F=AS(o?P6DKA+na~o5Pz} z!03%s+|}0t1_5J?Z-SUn!R*Z{AM8H0y6A6sXY7O*D31Ye3Z$&}0WS?^L9anmLKyT? zA$0~m!f{Bnvf|~l9^c2pbD1xr)!9JdhKJOfNJ+G6t#!Fte-W*=`hqfA9dS4rcvnBy zrx>jUAtlkOT?(s3tH~bAXf+?H)vl}Jyju*DXf;Nn)l*6eqSYwffW+Nql~5b0 zM1DLdR&qq($D`|ijN9u@*B`;)qFA*GIAgQ~gYO`==}QO(XTF^j4EnYR+Wti`(w6uO z-JU|1clHtl74aC3}}&u>lJ9)Q&IK9zygYM=TOY~LZZ4O_}43uyRNnL8HOgtrA! z!h0Z6xFN{hDERL(_8o62np9A^yrZvG$-=3~jm;k?)-K$p3(Aa3`i9)?t#qgdGiNL__g+!?&B79>(o>`Ndsr#-^; zTd=sVsZcF$N;$<{r>fnmY1%=tXI?RPebHx0cOBG@nbTd1eTwe78L3U)T}{9XDyZRC zH+UIzTaiJx6&Z9}%BXOuTCOH| zyHHV!gJPHYCkqc9&C2rWLfii^H4~`|kz!N0ZmtWN^sK2~UoXz5z8(Rg{xO74L~0&V zD_yirH~{AZ9GTYOR1ZEH1VYMOGo%I_%hUl#Q9#_S*76K)Ci^f)3QAFWhh1IhVGSZ> z%Yr9sJ@AS)T3^j53mW-CT%;z~-R1g2ZM+Ph1$OKR&L4UdlD9sZ02nc0v68^t< z9BR46%|J4);xaL19@&FuE^p)F5?6x%UJ-Lp%MTQj0}LEz&Z|_!Cm`f!vqtNXYI{7h zJ{5H{a1jMQ+n~J%Ujl-F&qIpfxcgJ3#+z96%YF45M0(d&yt~7!j8xq4PTg*ZFTUX`Tb8n{fY)C}q!>_UO95tQM-ufX1X>FpK zgb!Ij82cfFNk1eFX8jOCtRHfe%E)I0?1Pst0U*J(X9o+ed_jjt34t}+eSQqCPXQtQ zkj+R*aGk2y$MiQN_i2x3a6S11;@Ju{V4DQ?Z1JV$)!zSVBy(9aTp5 z!wHHVaH1)8DN=IRTBL=}C$Q!$Uo0wi?~_ci=OQJFEm!R3K(W90@=>v~Jf4bOjg%^O zhbr{P6vck$!Bp%4CsVPhI8p3{pn1jaN>Qxbwd4+du2!@J<%h$*^oHqm2)ISB2D!La zuPc2$saL{8uW2yTD_J1Vf8 zz?xk?KdQ7N5Teo%NQp|jDYm!%X5`NFc&c=>$5W+$BBieSkt$@X*+4s3%}=Lry6V|T zRk&1~u2BQcyK27XXL^kklrsj%)~ENX>=*SH$~`Ag?sSO2HrYxF1{|JW*o|$mu@8!k z3)tWD>_#$nZ&u+pl2rhWWl6yOjpyEwl6eC6?@DT>9tZ9ah9PoqX!Kte{XivI-V*+* zoZSd^V4~$%@ZfgOl|H=pBLm+2W$RV0klE$p+Q7~>q@T*E)T>!ny3qATku^CiG25=%GM;-A?z!xUV1~(jmBox3UW=*E^!*bI7IU>bQY-5#!%p;8XSb+! zcoJ0Q=BUCrKFmbV*aQ9YB{Kji?Gh;Qpv5MSDLI_ns|{{{y#e040TNjlUh<8=!(x2* zk;ev{@i-oqxC1cP`rV}AibtP6V%fV&TkDF?L4Qfl%(&<%9JF&oc>kyTig>irQz}SpMY{XB2Fb>@EX0kzY3CX}htc`C7S>9kZav{j} z1}mAdrx>ot8?0~QTwdQcG+zD!xd3W5zci>4;6NXm9Rs-0X|Qvg>0f06B@uwEeD-z zYRN^))N+p1;_(Ev5FlzXb(C19s+MV97}fHw7e>X1TKXt52Li(f#nzRYTDAiyYB5M5 zA*L3RMJ+}y1=-X>Du&umm|B{5F|`;v&q|2>Uwoca3)w_1X)sgEbC4w7@;OqbmH}1^ z8R<2Bo3#Fml zh6=t4v2IscQjGZ)*EPnR6(jB1^ZhI&6uAj!8e=-A#F+XjwH&bUxv_dn&1*`*EnZ`g z(31&XL$Y{{k+VTIuOStySaC%fQw`3gF&R2j^F@qV@E-G|*N{!TCJkm@GwK5Kn%9vs zuQ6#w$T9GmzX1@hDb&o0EK~KGb1yWnxdACTq%j?-$Wqq1OROpSAQE~X1yIytkkC^J zY9U$FV&oi4_)Ek|B#YB5MQZUaG#Az9R7 zdHRQwi)DjWBv0F{Y*B7-OagPGij3N|6}T zU(Y1Q4AHZtCfUcBH}q;kjIqd3SBzPK;;)UBDpT9LB*wgk3Ld;1G3KWgNipWAZb6J$ z8zb!%f5CS^KZyN?3n%5qLLbO#^>w~Sx&#;2x)TSZ(^ww+8;IX=VV%pGjxGhxbmyAQ z{$a;G-F?^q$@e-x^u5kGxG3`n6YkWm0s!GJW4qp`_i@5&Hy|?DHOT!6#UQnThjIRZ zFd6Ko!ECTg2wM*aMnx*49N7hf-T(BU6L6Wp14zld%wq}+6?3o~_xW+KyUb&`OyF;% zWUxD1u`layM($*f=V15hODLOz-Em048~GAe6E#UI{Y{xam<42oO9ds(AH1ho**G^` z&<%Bzk>+1YGXYTR(XfiB^)twhyZtm{8!LMDU2cbR_6FShn(eo6-kM-?xO=#uDvWwC6P5fcXA@E;Zl3 zUKJFYLEm5R^P}$%2SO%#<{>4%KTNT=>u*NxB#)=>@7u?G{{*De_ZKMeU1Lao=zJ-V z6)qK&J*WEV1$=@_H;8-) z6Y{`CJc?Vyoz6_*bkp&Mm)0V)Dcxm?rAM^j`LSGL9o9^DBe1`d!k}GK@8vzh{?T8b za6t|l&V|bLjd4gzz$d*@i-aexiVa%iKNkn(>7|urc`kx5Ut#5_vpl#F#oc_(fN1 zUFJqc`-aCa7Hp7P(-?o@peu+i0rpN{{Vk`^-*T?;gzTC4MEp0rMa_5-Epoiffp}6W zNGE(q`ToW>LmR7o#ka%VQjMHv&{&_1O~Z?55>Y!}&3hT0$smP*pn-Ms5PmdpBp}kr zUPDT5Fb~`#@=6J=Imu($$aZ?HUx#*$H8Q^8&SQ@LX5?05f50-wMs^QSx(*E~ZDfBU z?D43lx=*>mtOc^drGk=HcD$=uStG-z?Z!a7e6Mn(5=ZN=k0y*r)P+Q(G>AncLU62f z*EfiS+NprhvtFrpZDy_VL8zCvnrjAu{`4o4+^){|8lf@QEEOr{qicJWMz4c#; zU8A&p)O`+Z`Dsw>1N+i|)b=SziMCVmL9q#uVjJZ5+G3Xl#TH2{b{fozO$dwKK#NqD zw$0nmvtl3m&<4}?6+yAb2E|Ur2gN2tifxb%DiTgI%FCp-MG}jh2D4%l!eXEO55;D4 z8LPAhtk_Mq`7GF=XZm8ZK`%!t?hKRKT-ql$7lX|dYLS?NMfuchsiA7!{4OoSgw7^t+pb0`m69(C#B4NNTUM4jmlBkI^m}!C#YT`HL zugic9^mfZF1b7^JNEG|;px7db#ZH4+u?bsQ?Wsj36UZjy=nepC6KJda zZX!lsXBB7`ZMKCu^AqKg-vXozw%TB8@a7kSYhjFxwKIu7_{l&mZCpZme*%QLt+v3sG9+hEwjU95ZATMcr6{zl@}$a{%f0~-4OtkJ-H=xKyBc z!D*n07a09Gt7fxkE1xsHK=Pw040g1^%nJlUFGz!!83@54UeHqo^f5s#qP=~7RNPfS zit;9sM++D2b zf3uuPDphRw;n>Tcn&plgXzlkBq@?|(G6a?rFfB)Lg-ZpB7`lpvrnx3 zN`ADQ!G;;kEGH0JE)8O;BP6ig<0{~36VxJ_>1#^MJqDy$u8cflIYZ7cj+W6YJqInf z3plY{8qBgM#4Pum$}l~{au0Y}v|Q#OYrh?kg5@4m^uJloBxT;KZSINKz|YNcH+YF` zbCZ!0%cU{|mJ={7M{tEp1&Zb7gC>?U`unDrX3=S%ndKxuTFzig4Q7@T2rZWeG1U(?hgS>8Nxubv+%ca3AdqT`|zo-n;Gc0$W zmqp861fWFTp=7~6%8LFs%b6r@L&qaLHP-SAv)pVik(OJHlvpm6A+Vf)X*q%`Tq;m3 z_Z?_rIinw}IY*jBdsLd`BtKftUEB=kic^HselJeP>bjpK0jKnE0EIWZYPgKOG8dEj+W8;JO?c| z6F9M48qBgM#4Pu)$}l~{a_@Lqv|O3botFECEO9qZ(f?*Slf7`k8`BrOlk{>N+uvZOcmJ z8I~*XvS_*R5av$HwMGh-i!1uyEN7B(&2kfCxnG;*uJRITxx0`O%cU{|mJ={7M{or< zz@pkhCRr@^9B5)Wqi5K(T(fB5S7tfMkCro7#9(GQfzWbk5K|o?IK*=QQ32T|s6}+X z&ySW{0i;;&C-R8p4B5drT1Nl&9JE~1p=P->m}O6hS?*+&VcLM@vb~;ZxlRCz<@%B( z?piClZp+D&%i9%G%z69Su{qnQI}SY`hYYEJLB?1GnuHhoOj!ZK#P!l(Rslln$>m)t zqa4`B3~>%R2c(=Jh^-ZDS2}Fu40$#Z$|Dp9?yp= zk(-Iv7pQj+|_akMuCo6o#&YOzk`UjP0 z6$#%H`xvFNFK*3NGM_f#@!$Z}O9q~3afGk)1PvmCu%LzqXV)SHcxSfCnWFi4@HE8- zGXna|(k2G@5R&3`%Bz2>__j%3r-JynyIryN^zolX<3VC*i=SbbcDJGK(-qUFjbEjl@p^K4}(VqLR!h zBT2Ie4?z_D`CZL5HD36&9|SZ^2k^4Fc>1&Co$lK)XiTw8eR^4dU72{qk>eH=(q;aT z^aT0*TZ1RaU;^!TT);+=P{VK4e4zU!-ro-2?BA#6tJb<~@>X3o$ya8%ZOpNnT}S-| z$LO6@A)g6eHk{7FofJ}Gbv_p)+!omNQF+y14iAq#^ets_$@hAIbP=yYvd{p61$HFs zB3>ouf@}-yNX5ECT#*HK*#&g^epo|i`Q<4WmScAId2)dr+15LLxF`)~3+!HpBw1ir zjT9RzmwcPF666>xu&I8%hLTaTe#uZUZC!C8~41HIvS}yl_QY~Z?wWPsJEoFd+TJ|7i zYME%YK#qZ02#|G$rjE=MwR9P2YPk`qM72Dr0{NnCctq^I?@TSz02FUANG>6^jYYA6^(0BR!7yRA3GShHr}k zlO9JJ%t9$4EI)6qt5ilIvI}|~PXZu4j$=kykHczEN?^@jK0o$23V@IvM+s8W<7lU~ zJzjq^a^LWH_Bb*}6VD#UiAZUWV~_%GF^1%|Qhk7|aH*iAWgKTHXVBT0lJN1T3zcXR zpx0i3UW*_+?ygiwuvW_ReZRD73fno?wm>|1&!OJvP{U)PEZt#(!yUl8`Eu!ohFy{;R~QKK+VpHZlYCfL!3 z$E&FGX}Ev5yMIo)!F0n@k+r(xM+Rx3vAp1SJG(ezA}$Qag>_gzfxA4;bhnSL8RtUi zUm)q`Wz;ocdC?56v2ub%_%WaH;uDhXoy{7mv>-klQ3 zb>5i>#UXnYHN+Z89>vVBPsVjVKW=XJK2Wl`*^zhA54ig*k6^DN-Q0|?-pO`BhNz^d z%QKGukwxcrL46@WwhP*flx!E&O~u`>zt}Elf6u_}g3cUA25uMB&!@Ou(7i~>c0oN; zSZ%wYmpqo+1(hSU+Kp12cL?1CP&YSQqoiQFp!Chn9#u%zT-4@@jOTu0ZMeDFj}R`~ z1tmdj+nRxQTQoBA6DkQ&WU;RzqY+^ejnZHijR>)5G+kxnp)^4>DhEKK(Y5zjH2Oe+ z#RS$&@}*`pdI1QDMqeT&(dZM!Zq;9me>|Si=e%}TUwadWel zkn0@-L8{7qs1$BT_TMDRw+TGG6DV| z3;EsW-dN}rNO!w`v9RNJ6}=PJ*SgGc*af(|-xjzM7uLB-821$*%U%7MAocb;GG96& zhSiSOTr()t_%e@OjteW@LbOK9F6%{XZhA@N!W!!IeGn*ri@PZSk_$-v5%`iA148CR zI>CcTjX;X+oI8*{riCx0v_6q1y)^DV$`Z&1q@MvEcPkVaY(Sc{x|D0&R{9-CKT%vM z1zr`|3pJD7N88=U;&J!ULQ2039>AN(Hc z(N}mHH|TxxWlRpLF4t5!Uy65NtWzM-o%v@{GwgFeSNl_SjZbh?-5a=ok0rxP%H4R# zZG4J50+$c^A6p#T@IbQ}9qAOe=y$sG-mD!UWsatK1}O~R0NCi7;QV{fOoP3o%q5`J z&(E0Una>7c{|CrS`&^9_Uas=YJ#b!v^W~0KGv-P%Z@AU--j3^EPLAPAi?mY1-8*_V z@b!fV!Zx}IxSUb@5?sHPl75NDlbNg$2P|| z8s5-)HVZw|J}UXF`P+?)815g~ZDIC@wTY=6Lh@vt2MY@>_83wEM1t6Zam z?2pvS@4Lpm_XjQ72E=Vs{J;v*rK5JjR0aul)PB}dmxC6zj@qT3%#KD?R4}j5K7mX&q zWt0D)??R8k%*>Cm9wYJC9T)IfG1RZzwU~&@Kl%5^PJM{I<@dQa@Xs;s4IG(LIYw`6 znpHk{fNu4d-PoQ6kKWi4Ai<5zJxq_~jco{0ybsMm7qhEEiz)5b*!)lw&a)H*?6i*m z9|OA1WtHF+FyvG1HsG2R!x-~Gt3N3^Hz)>Kq!s`60XO>7a72pSeQyM$W?- zt@nAS!8i}YQbwPMp?VChd`qJ#iZ(_iEij4Qu$RQqARGf|nd^*H51%>-sR>9`xKtK6 z323FDZE@@&6{)CVT=gGNV-HDsN6nrjXlW{lA5i1Q=ZKE@-wPnw_nh#p?n#wb`vEm; zjnzsiM^52CV`n3HBsPGNV8>?S3$R&(i)w3J<$Jrvc<~f5CtBp0fJl#*Z0miGHw|X3 z@>5?#28ZrX(eJQ!d8$ZCYn3_3KCw_`V8C+-Tup41MOu)2Tt} zRWX~2JNDX2Fw)d;ZL-5F@bI9W_-9Hf`2>Hl*0AfkZu>YuSo*UCaHjvaTIx2#`GR03?%kSeGpzM0CDrHiseWyZx${2gUMd*oFx=X&G_n`4ihhFpP(RdGFX zBV?{eJ|U)x=_fyF80nE!7if2IuY`Nvyt znjSUYpng6t?K#&|`bc^wOio45HU1!D-43wNYuiL4A1=ek_b;vA!9in%F?qDQ){2`O_vETD8 z3A!(llFh^@flF;aaRofc$0mZ z*OwIiu9S=GORw58dBuQg?utPfm|ih>;4KE8uM~Q9F>B$jFR8T@7ztlU3B9dX46N6Y8pUIq;MmIf=uD=n)4bhIcWix8!SVn>UL^C4DRC@nIH zE0vb9OOzHxe-)wSqY%p^EmU)~lz}NNCt%6Z(k>@L%Wka&N(|FNfV+^QbbJy+%hy0S zT25GFBxbvr2qXKF13185G!9Mpy&&Hv)_5rou-B(!$EVV!bI0eq)$T8XeD(E6Aigm7 zjPQJ4T8)`j=KQv3HjzrUS%z^h%G>DH)$W@jqjD%W4?LM@kSS%Mm z4_Yjrs6FRBUHt4M*dCIGGCEp37e5~X$}N7rjvR>QD;u5>;0vlCH-BulVBY-kD{=)U z7UypMNPXY7%|dglsOt)7V0!k$5V_kB_RVw^_*qiB)XU{!65^JN%RqFwm=OH7nDt+v zX^H_wgWdFsWOp}&UExcf`2x9F$l-}d0pD9c{2(XC&cN7B^vpeOGECg&OQ!gP!HL!& z!}WtTqas~*m6{zf?~467P~hO~o;7hVY+5ZczOZS7%H=5pyId$QY|;vSbu+>#IO`xi zg+W|t@;~ofJE>-{cdywh{em+?T{K1OfGYqWC_Q4n68ZTmgVt8_gj7@9?Qp^?epBwqBeK;R%?ODd9?yXVcSd!O$7>lvBd)4|MEP zNIoGt_EGG{J{99Lbm6g&QkDadt_tfzBsiZn3yz()P@gnjD^w^EPij)8f*BLH#Etu>S1f3s$q%yvDAOCR*!c-}9Cx4pW4=VX6#F zhbcnn5=V*i#6~7v()W>6{e;2eyLhG|=LYtNUUq@bCa`3fb&CUgfyHuQKVyv!>{A8% zoTQ+NF3n7|leP*Z$bD=H+ z(@+zlp&lSM5?4osx(EOl>a*5qsP7bDI)NpYpv17cdjnheMq%G3pu<>ehg`cMSJKuE50NT&SO=A)fTTEajCAHJSZZq(>zMyNko@ zE`yCiqoSCpa;M1<$L^GLUs!RcRlH61t0F^Bk8~_L(Lhem^gX*PqV5B=FJp3t#v^2y zo(PtGUj$RDG5VYyj-wcNXsnPNLUekd*i8>AE`nGOjVZ;UF)q)z>EXEzIz1?QbYyxc z#8B*}2dcU0p$tr?huV1z5T}PV$m#T;*3wa8czU>RqfQUWGNPx&Ob;zTr7=zqeUWp& z&87w>?Fdp~R+hTV`8 zK-=f9fuz1Y!N;oWkW+axIpDc>f1BfwGvDSoKZHtaM3TY;`FyQ)_dw!h?xn-siNdFSt8|j2F?Y7y24sPW1(mw9rH>S)@!>g% z_QZ!pHeXWTmS93H?TN2gf7lZb+Z=mh+wJs`J#jK}d(CuFWKTSbnnd+P*8zJ4rmwUe z()Gl7g8$E+sGbZ2neb+KZ4L5Xl;?u1kT=8@f;`?j%^(xzf?NisK_*0l{I=N0V(j!l zuU5VW`C;T-kUtb)t_^Ze>lTCjp2afAN04(t-YVEHB@JZ+ES^E`u|tDA3ONb#Khgtz z;UMRk`2as}!939W2)P0ii*r5kC=IbE?w9g3(ryk0Yn=S+N;lP|2#~udOzxRqaLm3y zAf@MUr+!*wsp{&U;DNCE#a6wxh$8A72%P#_k?mIX&w>rk($L;$)py3I+jhFw^g&Sh zF6~SmWJml4P19V0dYOTPWCT1`A}wP&|d@Aoh(FdyUSk{|++VoKg~<{hEx& z7n>tyQQ+pN0>6$(;Fz562M{p+f>_U@yE-TJt>9lNH`8D@o_+y8d(EqYrvIs;AqT~z z;D`xGSg%!c)8DW?3g#9@9YncRjlD((H@@LvWV8xQX@8%m<>=8^R+L|A=#-Sp8)-MH zLg^I{#JA8?ld1kc`*e4yAx;22-@)Lebv5u45qQ_971Bqb=!?DU5XL@DnCsJJVA`h% z(LUWzY^0;OaG(AY05`inUZ8z?fwbv~1eVmdZm~~q2g1#+6~5Fyog>%}B@JclwEnSA z-wu=;xThf}eOfz8OKH|RyDqh0_UW&XD=@J**Qcu#N}t{$<(28vJa@ZVn7>0(ko%df z1<&1D!Gt@Idf4VTd~dWl4&Mo1arnML6ghmq3(e@xC119%Yh7;ezU}`DwEB_j0-ah< z1ARA2bAeXK-C_#?YIn83h8@wk7Fl8MBUD>+D zKv(}-1APs0Zt$Ki*q0;?WvsRSG0;mao-=d-auR4gBf2*x&?OekKqv2Hpkr|^(0w4o zuh1-!@-)zP-h{-BpQq%MO-FG=dT5y4v9M8S&XkrC8Gg58e01tM?1m?hgTdFr>T|66 zv6$gk%0FWCV##_axX~=v4L_z02SZsY=Z*5;I|SBefxrd3Vv+Gy`MsuD)IeSZ7ptP% z8XP@hv~#D5(3v@6t`=tcsFDs^!^;d>Ta6NBJ)Mqo0dlLXmAV;GKE}!My-y%TX5J?k zx}kdwIC&H0nNwGmx&U|nE?zwth<3CMf3>7H)MW1uDUl8W{MH!g(3qrJC+%7iq+1&M@=Gt$y zUu;9p^^2nUuC|Hm*)Qr@x7aUge5d^)13A|(jtcgqq@j#m)<5=(9E)eaC`3;B#REd+ zBuQhAT>l2Lz{G+|9l4&dz`3VgLXTW|Vlh|hxKL8x4S~tlf1X&R?IvH_(cofX;S&o& zbV+)#*vJ44z8eEG>XUb_IXncATXRrI79qOkK(SkMP;oxQy5>MB)*LqIn!_?|Z?;z{ z6`cVYmZLAX<#9RMmB%OGN9>!>`-!x6K`_ru<4yqFWw>04 zSH7gW6z%(-#<T_?m*d@4B383V2U0s`GUtE{c!Eo1FrsKUGtGu4@^^0QqJIx;NB_EkHRg zVhTygi;5VvJ^aOC>@ppmQms;gwOq#C&bAYA1BM$Y}*;@L&wUJ>j3QebeZ($ZkB(xQ-* zjZw5v>}XN(K!}wVN{dW3_BdMZ!nUJD(H$bRB-t`a3)LJgWnfCnAAq<9-Em)pmMgUu zC^1Y60j@!xlu<$HQCeOH!qKwT8Y3}|mYc+2;-{$d%Yg^cs$Bp63qaRe6p}%R_HT+E zEh^4}SZSdYH!oq2qvgCGl@>)0iO|x-mPuNu=4dGcQ(E4GB}dB<E6Hz4PJM~t@AZ1`m-VmqhaTItwj@eWda8dG*_DUy@>M-C|;is&yA z_Y~ZC+2T`hm>$#N;VaFg>%JD#b+3}}WdY=SJrHW5!FU|*xnL+Hmkg>BbH6@87A%j0~(BnkkeqOwG5OPZlfCjaKWgw z&~@Fql4={Rd{BeY3OV7!qh*9ZatTpdD0Z}{81)X*LMd+h z!yZ}p#RMT%o2k+Fz9$<-H=x9+$F(FC|#f}ygr)`bULTQo7#2!b>xrdY% zMQ2B7`O$`gv{22_QU<29ya7wD>+VHPX<4MTK#5^m2ynC<5n7ZUrKRc5+FE)d=YB`b zH0f;J!3Dc6zQ8>JN6*@Ths$oa{O0au7$W7fA5U^}>BrMWB2Tl*mhHzb0DnqpMR46W zEU==v24Eaqasg0C3U2!k2Y_N102L2}Si38wm{PFE1z;(*UAt8DNhufIb*L?q0ic=- zKpB_@pv_?oz)0jY00A5`@mGWr!vP?`1)!GHo3G&KPXq9wHO6+i#~PyyxAtx`-fd|z zyk*7=Z?{TG836f41`eF3d{z8K`BKP4LbSnB?D$e~4#dhArA4L)dmLZGul`P+Fb_&^054Oe92Uq1e%);#`Q87D|h-UZb?E!?vSE(N9HadE1srTBzn| zDFahly8NcJOhQhZ(G0BxN(?t60vs)Sq#tX4R$8`LV{AshSz{!|(ekDk%!EPT=ssJY2YGqWYQORpzJjhq#%xC zS39|kW3P$CjbmG7D{373U3O)|N8j6l@vW5Uw@|igfC?!hM46`8F|Fd19TBD}#fRsx z$MwrPN0n(s|0Ct1U!G^nB-2!LOqYQv(+gn9F@5$Q5vILY+yIr062nXr;F!*p@hd-O z9GeG(V|u+c7HNPr#b7=R`rZjV-&$$;4M0bWLK44-qJ?5di;6QK)&@vvk;%dyN6W3p zlomzTlX5{zCtD_Ip_-$m3`}V`2uqHZ!GA_*N!41Q#4s%cI9imB?_+4$2ZW;~zJ$gc zEnKh}CD{uzAJe zxnQ#aInc!WNIS~GYBx!B#rmKHb0M?x-(0ha#kqydPLSbOXkL@@bk)W`);{IF-DJb* zrEO&1ygz2%{6w^h$@l|-voF+!cpL1xhNzH~FQXbF#jYW$I0IsBh?L@t9(!CvT#s!x z5-NJ5l#7PA?E;p`hDbHn5X-={A$I*o8{#bFbb?T8IVdsQ5NrLb4e?iLfO-n6BjGF{ zTti%qocp;6qDb5;Vx1ohTzHYvatJ_2i$YQgqiCVn(W2sk5GyT|;_wT594+;ZD=mut zDMHJSHWZ|VYL1pNFs0=+SaSXId*qas-?SDeF-!{qu75r%6U1|pDlLspC@tNQi>4(m z+l_;XU!l(90^QN7+`M@|fQ}Z0WDugGImM0^6=y-Lv`~sOdhBtuEWx&GEsCxp<)XD5 zx1k^{RCBbHfhjE)oK#xwMowutQ)}^c6fFceTJ9A(lpdvJg*C>*iEphj5_808OC1g_ zqUX&t%$wf{|MvLb$z|U3i3@JtY%E)xH@BLGG7g9}du9($2ep$fJTayVcM$DNfP9Yx zez;hJ5;~S@TI!h) zYT;Iy@6lSI#4s%cI9mD%ElQ8lavKnimZz<;2rZ9`!7Lc`O%5cWRk<#_5Md?vmN~|$<;bcFJ@pr^%OKk=&V!QB7QV_fFl};{Qc#=q57k)#wWGOBe ze$~B9I_wiM9d?6Yy>G$qlYtqRY6v>RDHj5Tq!FSapxA{##RDPMmPsiN{;46^U8jOQ*&jmvv z`GjaND0ab6vG;u>7?fh+0DD|8uB)KIP;_4@7hU%Rs^UgZs<~j4foU+lgC#eqq*sgt zL#+)&iQzW-9RMyEdOWB>(O}$PN!#dLbi>3((MeTB@?-5T4svDTp08{7Z`_D<>uNs06JO}g7=_AXrb8AqT+Ojwd+!f zlPm0Tw0wbW*L4*=N6JNOX==+PEmU)~lz}NN{i`S~GmukSUKMM(C^1Y60ge_uyVsK} zrR5uIj9vG%HAZ4^vxyj+55LOoy2b3ecL<7I_hW~YuA3zi*L7FOmhHOkmYW;p=vnV@ zz%oLWE66*S5t=20aDU8jfp7^x4i@Llb;B{=1mt@!P`8st>KbUcNGT+3Z&aixc9Dt} zYosVezlMT~)T7vTw<0Jy6EZ~UGwUIvZ8Pyf;)5c^+b~(Hk7nhT)}X4$xQLC5q<@_L{>|?@{A% zl3donK2sAs^2hdpJE3IjeY`Nb7H%W5o=2B=g#ena_IsC<2l!S1e0jkQWdZw4wO3q$ zu6eeXEf#;oWXRS6Rn)sM67i*9{@@R8PMyYgrwqXS zsHX9%tU|+&*z#BE_N&8&Z2cU}65*lO9jIZ|kXQdI+Vuzyls%ag z!peU>np%Hs$%_pR%Y)q6xD~7FcD(xF&mi8;=A8o8%@8Z3xU_xfJ--BJcGeEoxtew` zg$yJ_X9$X22UBqt#M;3qEi$>-<2qP_>N*rE`V%P^o$OLuCOa9`+)!8srXB4qSlVFk z`KfrcXuiBPOZ%G|Ek?oUZyW5bKT$Z>?XrZ~S0vSLH|tEDFIFSxevYJF;%v%~VBkn_ zaTg`&5P)tJQpi9;lq8BBNh;2USV^K3hkDrKNZMFKNmBF=3tbxkNjKOsNfOl@No8P4 zQumrV8nvwz8I67tYbpDqMk4|oElS7I7+O98!kw~yZ;g?d?Ir_8p6F;|=IYlRdH?Z57hlJbB9OELDD$u2xT`g; zC9vS)s*p@VG_Dl8xT-h@VvQ@McpV4!xVXNUth0-v(+=9%rKv5CF?Ho}b}0qXc-F0> z@%#)qZSBp)`+>BkvrG578qXynUM;CM^Ur{A@%$Y*_j3=p^%i6n4Ep{Jeres~18#NC zW_>5G#9OGMAo_qCrG;jzNXmP_jUUeBudAfK__!h6$TjcF-T`%YUv}Mk%<;bLVK&G6 zvfo8+uW2ia9CkZH^M4J!g{HHhV{gE}fJYU)oS}Z?v!d~FtGm+|9)~naVHf1n(+cS! zws0Auz`D%K8HBmZ8D(I4IfD=eipMg&#D@1%)a8tu0dSWy)*{r7YX!JP73A@@Z!DOXGfpE{ zU}ACZaz>kTZCfcckBNHZaz@l^%JW5dNK%mdFTC1d$u&0@nu8(;-;_O;+WSm9X+3$j z@_;~F*`p}|?_3Nr5^hK)3yu$mToI7~V2?v_aw!1DesF1kxd4l}+7zuxo#@j`P4uVW z(N1$f4E-+Y4j4OR9xlPq^?P_MD>N#mL(#3050xD;I*lDsPvqIQlFzY!n^|=;2&x~b z18leY+%f(p>}X(jG;F{fH#Wn3(J;Wb)r_(`mUIRp)!rh$20ON!Of>&tFfMnGUu;G7 z8iwbROXU9Y>!rC7XT9dKEk%C z1oC}^3d|z#nowE>f#tueY_(OIm~FgA#etNcq0~OKrze#n?05?N>}z2PdP?<(_8$al@dJ%fVBxW;3FezSdD+rwfpmlm%HJqU~LRc)-(F8g-6 zQV`B5EU;GN5S)yD31JN>wX3A@`pUB>0ClfC``hOD%CpOxaIA<`aj!gk0W$Z>vlKCf z#uWR?vtt&-mk^c$m44+}v!*PWuV*HFpE*zLgZ+)*n>zr7>;9Ocu=eS_RJN&5`Q|2r7nO^74v%cgz|nyLZP#>)<}`4ffqJ zrSQDnn|ORHTI}oX-hr|C?iF<9-0k=5k0yfFbp2$8P3R+o9T=k4bd5y(n53b zo30gwXJov9fUSnl&rcJ>iNC<`g@JFZVIFODgsMB*T4;;l(N;8AkG33+M_a@dnz>>y ze6%HBkC2CJ`G~^z0y!Y5@A5!uA6AHuD4f%rQz{=(h=qk8Q6NNT@TpR_bo$>uFrhE) za0c%Tkek63GEJbE!JoIqaRw*M&EREVI)f9UGx!X#k%i*IHzd3OfSbXqo~JYTr7}ns z5m++Jy2Tm%1|Z}Cb>!R)30DiYkED42iN$jUKW6c~A)$5)xZ!5-DFVz=1${sr5P3iy zxdIc5b2IpC8sg|OOw_|OxcktEJ2d)NYMOEc#C8wtyjF=_1$9TPLQX}9{na{7VhMA^ zmVqg;geb8-@g)Prg^4Wzz!7_6OC>fzfD;KUS!3NIvD1NY#BN2-5nETVsgi~=##lUw zZI(tniOoPxh@C0GxvC(jJ*74ouCy6Jm^9_zIH&Uof&?3ZJmiTpBv_nX~ek9FLR z#;wE0I*)|jdK}NZ*&Vz7#IepJp$*UB!;09k-Q=P@w})}}(!NQdxm~g92Z?(-Tm|u? zx}?5GLpSwjqv6}(hM&)-%(uhML$1&$DExLf_gtX7Oorz@itv6#=YBNw?)BRKzJvkS zxfN1NN<^pJYD;A2Cd_s2GBEAjglOlkBR0}eT)1=By+AwnOyt~o&jkXUNMOl})-87K z-4@I9o|+eG=k6%ju9Ai_dRaU>_kBRQ&OHY?>D*%k_^>LJ{xZ`VAPY<^sMK?J*NLX~ zYv0(OsH5xF{Y9n*K*9`4y1vH+yF5cDptq?@IOWO&&+Bz@ z$omuUQC`KVclE(}C$_&bPvzrrVR7SqNh>~a$&GA*iy=$9grR!{xi^vf+FV=?zQ))* z(?5*uE?5tZXeIKWh}D$e;K|dCZnE73`&+i9<$UBGvAOlg6(P6Fz8xxB%b#WPOfKqO zqa9V=L(ZwZjvQ6omm@!yf(j({4>kFy$6CWLN4l>@4uApll;P0xg!5XG`fo!a&pBWn6lH2)Ht~+7R6yAs>zx(j@s+>$YG`UzxLDl^nFKb>grSx2kHc-k_OtQ- zGqbA;?oAcfd+x_B{AR&fQ+EIw_u=r{BA=QV7o>_+d+srk5&2%gO&6yY* zFXud;fw(LMGT)r{5Do!a`}qdy+dFbiqsBVyIN$&NS#WlG{zE0^&fD+C*`A+mA79WI zS7HX=b7y47FXIlGDMc`Uk+tEUUOaBIIk4a79TX3XP!#M9865C_HuVqS<2`w%29gg^ zTAuk6$fQnO?ih)%s7~VVxM{kJd2JwD=tKy{0J7B-i%CYyKfVYKZ8qsJu zLT#-X3IQ(O<9`m6u~I0YFMYO?^U*7)KMeWPBFS><8wat}S0PBck}kf8+$fuS8oA|H zu{T@?pH!`gY9o8yO0A*TPsCOe_qOxN`ML?der3-mtIGabk_JcST1~!A>-^3%~

    07cOc6t_#3InW*NhU1*}!@MuQH@~olzqER5vK$ z9<;x0sNGYdm~s?7tsT_z3sGe%D|{`v>RK(707+qo#4+g)XWudHo*SF z6<1jBZV1loLGVw=J%-$7^G*~PhhARIRpxpNUJJo~K=zrNmbijDaVpzohNB>UK#IR~ zr;%qSVdrhv&@_j_Z;{(;R=(>%KVgKN1DlpOOxat_ry`L(cOJ>&JPyX*^qRUzG3j(+)Xw_Yrst9}Z~B6{H<|*V( zAcwJNKC<765Bntbm-7kY68v&kM*WiA97>+(1j8h{Yi}B1rnZr zVud{xoQU-U=Ry#F?q>?wstjZR2* zZ_o}*f5TDB56NOAXas+Q;$>w?(P>g|V_+|Wa2XA4HiHpaZ88JlAgbPWI596kum_kt z^CWV2UdIFW03xg4xyt9P3Tv#=4y&pbLB_wu00Cf}aa3KED2(j0U zAdJKk=7=o=Q(_5GVy_b$#nHsJ7@)+?K+Y{e^%tkp{vomTtXm}ZTZ`oq)R_a7*gFI} zI!x@B);|(^FHmj?>Luia*fv6FdJM6vEtu=edyy+Ju{cNUS+@$YQ(}mf7AwpSkg8^) z24HsDUCL~G=sRW=GAzRE8@8romN3U`8JIFlh%$SJ*vKJa+GJM%;F@g9LCWkV@w(VD zJI1<2X72~WHQ8mzxhDIKVE2WYZDH|bHfgXj+XgvdwzDvr5oY!q`=-zduD#v>Bo4D< zK&2M<{`#M!j+R=c;WiGC`qSM?>I_(Rq$=dW2&pHn(NbmIa}5nuQWpqzahTM}7Ee-d1Ijhmr;!s<8wp=& zVN%`eSKqZ@HrFqaD=@J**IX+PV|_3VtofhJPLZk>J7zm(Dzh!2@0eA{vqk|P3r&ApFqy48oXp1J9JAL#W|?g%>N>*eK;V|7A6n+x z#>Xk(FJBIZSTK%8P*LPnXS3RAkP=8nU8Mm|UiPEaI?xm)um2zg7gXrVT@aa+NcWdan zySY{gq&T`IJqodFNd?HcmXs_`rk!9*8f8tfCDpk@ThevNxt7#Ku&pHxWi+yQwxksn z&zAHpa?+Ce3-DG|kd}1Hg4vSlk6=rR#krPrBV@KET_x(VEorkkjFpHyscI%_fEA_O zF=XRk2*yKyvuTR1dq@cbB-q;wvXFKV`~k>Dd$-+jC5({tW){JwaO0iY(G}s76B-PC z>7%uy6XrU48JKo-LbRjDiH)?AQ5}6f04_X@?$YoamQIvOU`bW$7Q>SXgzM;UA?L#L zk6?YucE(2QAH!4eZsHl9mdHtXx(TqaDoA*GTQI|OA94jI7U#nAE)8)At??h>`Pwf1 zBuG`8N*YYhGhFuh0_wQaP4@DP+CQG_VF(%5W>k=aiX&uCqvp};GF9$D;k)d*Oe--_ z?2v9f=4QyZnvtcf7ty*KJwB6xcAuo^MIo$vx*j+ix_IrOh@=PNZnoh(qmWT-r}
      dAZbSDJW5bg$7Bo+I%-Z=NVb-ZKq# z-1A>N4k;F-PmDvA4~tv0Y%i)7nwsKCscUX~%#u;)FIV{o%1CqcLpLD*2=9MINoMl1 zrIw8QXL5x&?G(;gA;>rV?!kg^XS=%l0YvVTgb#|bCnNe1Q>?2&aiiP>h zTe~9Mu3e$Xi*1qr9K+STF8*5|@VwCwZZRFdz=vj~s0CVN7ynPT$X*cE8_gn5<9Uc! zSbPoKVpSWrm^}%|2E%s*R6P3Fj_|$u+f6pg-8Lnv6k zGM(k0gk0n9;9Mfv#+!WMzg{yZa!6kp*PjejO;_f4s2Q%r& zxiM~-VDFJMl<}6ubBxQjc#d&-$jKPDOq%t_lIrQ=PZrEE?u`36#>L{?7V!d-DB&fbPCg!NG3c&5PvYZBsSg|4v>ofQbd&n*}g3$r<30?gk2AgSPj(Qx?T z7K}ba&Mg=zxT2OitHM#sGZ%~qa|=e@A7G9PMl@1r6s`+Kfw8!I2BQV8d~i6a;BQ~< zl98$vF-S2>Mkv8887U~y0Cd7!4*#RuTEhp!ZLOX-ovO~4vs}a#lk-KM4vS#qeai?} zOn!nbw_?(19IK@S>xv1M>sTp!+krc&zd=l8I#ZP&(q@|t1MXN}A-AYk$-esI2xBk_ zbHOYF(_j*!Q~V&YkwY%@)U(Ay^qS2-2RYaLCw}0Xe=&h2$833Q{{L7koB#O_YxAEW z*q0>@WxQ$eZ2r#y<)-+R$Vu}bB+Y(AO!NQNg4z7N@ofIFIM@6yh77+#vslX0=5J|5 z&^a88kcy`HY>0+Dti0X`ZO5xZ?uqa^&eBg_33I%bfhn(qD6gZ%Mkb02^IC0!^7=7y zj@LTka}I$e-K|^XH87D_^4bA8H>|V}Y@0Bz#^TBAJd5YBvK~3%b&~M;R1B{NESS7j zdW5{j;vBD6KxTRE{2#n>r8G+_T1;NA@ednMUU}(Y7_{9aGi?$X=1Qr8-%y4ZR`|`< zfD?^V;6y`(LZhI_L{qG{_?Ew1stPH7P+9uhfti!F^D8KWpcAG8{EhDXy&grK-9)oo zoLr^O{zvCuEb@u42nLo~2H5%Ud5jEjxisT(R%opN|GV=mBFCAkG*KIAt0~$@6_Tf3 zCHqn)Xy+%)HPSLLZKQ-~Bi$@Eiphm`{?h=s&i}&`+DQ5QEPrVMHqzg1d2FOjpVUS= z1Uc78ZxQTm;YRwp#j}xauy{7oL&!-ZT_BBfaZDqvJe9`TNLwLSU}ABuk=_m&euZXS zOd}20J0Eqe^b4tKCTf5n4SqzKeH!|%`zz$D2(u5`0I>TL=9n!5Q)UTKX1@^|IV4P( zz5Xd>w))e`?8+4~tXgKfS+~gS%|N*B{~~gZ*)4)CkTjIxSv;Bj%i_swooB+#t`kPL z#xQ#sAdcA~$Q77aoMUzl4UyS>QeNz^%I<$$Dw-AquRZ-kCu#RzW6R)$l7rK<`zyHG za#v||(qC;2*!`UXyFV51=@$V-y8qw*yZfucK)4dq{Wm|W-Csdj1f4ML;cs;Je=7@h zcHKWk%5S93{zvz(A@W?uK#paA-G9?`vdr%P<_uP-xd8vW`zxZ@nX34xHqxojX(Lrg zntGM&t2bG@KVhzsmVs#_B}5zP1!5yDE~=6CpQ(+s?ep45f071}NnlB_Esu?KG7zqj zu13x^(tic(4|o69ES`5_%=SP|m>ngIj*DS7 z(}KzD^T-vLSe#>a8x4`!_oTeo?$2w-Bc!64@ZZMtD5*)Erie17f4O zES|?h3Qh+YL)LLi9|uDR=3q!Lj%>whIfG%BNbP%>_F8*Y$aI#YPr9>h@w{}bplpIp zn5*GybnOY0+OL%I*Zhy#^F(Ng$n#z8SKHciFie=o+H)`*k6fYIAi)0~3>D$wPCyV@ z^GWTpM_|BpS%qv;uabSupCF7~mN3_4%fPhD5~5x9GqI75;=(g_*H`E@PlVn<&K
      <@;Ja*Xj+}JaFQlt}8`EWXS}?op zN#qJlEY5Y=3+J;wVE6kngCV*MB<@tGP^y~in7wDJGTR^ej#-85iZJ`Q4FH)X%rRRA zrpywe%!IyB&1=#^<@HA7T#NltT7!qDp8X|n zS+~gRLW^aK-GiLtwM4L|!!34*#go?#uhBMn9gLi`*uBzH4~JW9sjJ4116g2VL8Y!5 zCzMO6TLJGZvVM|+R_|%0^%K}GG%C^+YPPvmT7y)(xBnt6kh`lU!9|SQ%`w`6>2`eFYjm}89)`y2p~UMG z;iX4+twYx^p2v-z4}~GJG~pn6p2H85zY~UpPhX<$cEi(jwcw8)8L?Pbq#WYdYa_c% z1Kc})T)KNYdND39JT*XAVdV~v%^&(1S7p*;tPJX0At zV)-jD+99;{JKDa1ywHp-FXY&-*ix5n;(vXTxBO4z^_z}1>oY@i`#g#68cvO3Q)=Lj1a^Qw6@igY5ROUirRL zE@ggZ<~)WeO{l50#u54g2s7*E1@NH6##hlY4urT-@y(F;xf#ue9}a{*#g50`3O_@6 z&^|-?&0_Ab&rlw;&rn|bj(uMQTGw>o51G^_VC_&S9reVM6L^$j$UTES-{BA+w(w8S zeduGepdyI-#Xht7g&BJH5WLUHZsacs;mTVjT-fsc7Wx7{_kNcLyn8`;ns{H#MtmqV zJ2p!9&`f5abz#co&ol%~zsa`e}-*a74UYBibdcF4Jb65WwnMN4`uB#!w{EfNN}gg zGwf46-Vfm^ENT^-N!b3%@~6;`mA{G2XVM_A-7bfQ<1iLgE{BBkAwWJ}_Jx?stb$-Z z*6ewjT#Eg(mNW2tyzHRO@$s^XE4Yu3m$gLBJzl2zInb}T{}1aDA1`zIe7wx*^YJq3 z<9)qAy2s0+b;FOBIYmBR<`nsOSwwN4>ABj)oR63B=bj_GPWIj`sXj+G&brL!$Ud++ zK6dd9a$5ZZ8Y5PJ$_+1Q^;194>JP9vR)3PsvHFXU`^r9Dr}{_5PR0G_S{tOm*&qeZ z1}UJ80u!sX!#-^nyEjaUGek<9AyQJlp+cjM$kTVY0bx7twT^x4?jLd2Tjj`9x{7QS zNmtxT5@E6c|2+O!D4yRko=LJH0%)UPDw)pGNEHJU4QYQ_+NKtwo=AZrvUytIVqg}&GWM95w7Aa+Pj$2AWwKWsMQvep2 zSV*yX8!|kG{%TqEvsbP)ov}a9^v3^}R&(xA({>gi1-fpbf;5B`^GM^DwX0P4M7xSY z#)^Ar;vHThj9rB=SJg5w?J9(5S9wruWTLomSD6cd>nfAiXjl1N;+{ibNrH8YUF9<% z+`2_vu6C8vf{l}qg)%l+|JYTA0p+^NQ^-kI(MkFdRgiUyB^JyTp#tOzOf1f=TU1)h z`k-x{CF+s>l22+kn|YX6r$|kUNo;ZG#<^sSN2e{I?(R)oEReLS=u&y+z_(Fv^A z=xEO^Ca~lk>lUNa0|*zLDag6ik5?o*uS*)r7-aE`&OwXk>PO`b;pk|8G~t2F-QL|2 z5Vxw-7r6oxi*wO=nuZvikEFbq=(t-G3#F#Tk_OY=t%>hK8;=#sUiKDun2Ct-m{0|2 zc$*#~)(An3J{~;GvfZtT$Hc@yhjhn*ZS!b7RUC8Hc^rswfNNbkhJ7yW3jOgV+iV!| zvCu6v8%3nU86U{jVMNt*T*HY%4V-o484e?Jpk82NA<@G~tgQ4fvdOx>Q;LroM)n## zEIfpBzBCkQh4ux29fgE0vNtex*hSfyOa6{#=Ze9 z+%OtlIG?k`2XAE;Pm&j_G5ZDw?YiO9XZFna8__4?-cvJlyx5SN%ip6^)bjLAHw%bIY=o&WtQ=X4V% zxHspN*f-}~@hSU0AMx!hMHj(}@6XVSuP{(N+#Uvqd&D;y;xF%Xg-{0n8^m{n*n3)1 z-@l<>tj&KQ+yr2rIfC3V~`oCtQg^%@-_X_?`<+6uP4l~7AVm0ez`g}Uc#@K9= z4nGQ+B~T0-H)a#Y;fF9c{FH&|@I#0WKXb%J28s(0KiL4d;U{^s4nLm?FpI#FM%FD3 zKSO|U!_PeA-0)K<*zY6_W&B|Maa6K2h6a+x97kORWPynVl{$_( zBt=C=9(e`n4=8EA2$xIhI~97+R-hQd@i4yCsK|9BobtKh;jn0&R?R;{ABH2c4Vr~U zMUmlwC2uh-SY_%u3jQNpaIr18np8Pl@DZbpumW1T+s%G=o4D{L=Cg|<5&-y`QzY7n zxz<)_H2Qp%yETHn*sY$F?xXCU$4$xgo>%|PyECw6WR9C>4q)po-5PPd&#S-KZJjU; zPoQz0R}($>C;#7O$9LFj!BAoaYH=A8?%ZgR?WOGeDi82f(;{+~AE!0u(u zncIonFY7$yUTbK)nYbJHv{{DSTho|3*c5jJA7`#rGu(uI|oi-ynd63G&V}+qS@i8}o3B zI?Fb~e(&5qDDYVyD_H9H_a>|#?wD@8v%kC)0)KpH3A%<<%SNwgR57D^T@@^@1>%SZ_r9ou0QO ztaB%`VV%3&Ry;}!GKRhi0N1-4-Gi$4ZS~{!w6N;^%!XATa9dWD7gT+p0bK9FTx8+? z+CP!_LgUaS;^|j~`0A*6d~N*mo4BtQGKt@2leq0ne8D=qVPxYko|n?Z*5q&srut{B zgBK!tDbtv(7+=8}@vWWbdFQNe1besK|e z`#mq|+AsWG{Ul?HtnVcy+=n5rrs)ryuYP>e!W*$!OEwdeuAGg{+OkP^^8k~gFzHP2P(Rgdu$#k^e&rb6SZb7+)Z+ncHkZvYNta;I ztKY(;+X~*FlzkeTtqs;eJ%9a)CaGx?*gD@ZF8=zHOw!l$A-}+Efo*^N$tJ0OF6g@0 zd}FttFiDG7phsSAx>gk^3Qc~&bU^q10HHM z@Je7J?w`)aYv5f0GidN}gFg1cTY6tg8-8Q_Q;xpS`g6z$hH&Nbum|q%RE3GK*-uc+Nr3&zP>9yzE z4I>Q)__+B!vv<&9jnQLUA*TFun-Yq6(h>QnT+X6iF;=d{FC+Fo?By+nY(TB{BfJSPz}>f&D0mqvB|8iHkqAilb4>e$;-JmnX}s_^Zv9+b}dYM zHB;wbWRnGbY_f2iO%~0y$y*z2^7a9nEb*_QLQaZJmUgtsvRiEO-h(!I{{@>YUuKgP zpWEbvMY+^lxyB|R{$P`jd~3P$uqZSv_jn{1k6lg+DbvSp7=w*F<4&l1;DZ(Ev8KJR6d?IUfHKLbgv)OgeT2c{Lw zSesTfvus++(4ShV$%f?ANc=n#bc!ivy62 zZ`3Un`Q&a3u)BwAj-J1cp{!9)zcEuWEWd!ix*wrblR$)bw#l9baj!=cFuj25 zfN&97V58pkFlqYDW(e{l!g{6(M$|@qC)e<7+xMHFA;c%Py}G%y@1?ksZ!kU_lvlu? zD_8g5WX{6A)bRdi$8f*JwcBOzULh0RzU`4BAmI$g52nV~xjE_+Q2cfbk|B z9+`nzlEx3?-%%R>=Rb_&w0#NW4V!NQx_bA9DRWViX4hBSfI-hR8_)`cHK~Sw7-NlB zZNwAYJGe9VCWrUd!#zEw*=;v-FBL4d>5OwcuU%TTkMD=!nz7f^Qc(HchpTmbciT6^)Y9{zdpnb>Y_hK}@-OY$$ldOmBhkr;{{rn$Lu zjF_kctP08=hjd59jo-f%<<@MT zb_=3gvw5rAZPI#-P0pWSlM7eFe9h(;ZL&$50-IdC$0luu+N52kO)ed0llG6>setvqL-_-=&zP1CSqSvY_@N{_38Ey+-$s zHg90x`{DfwDUf=t%+LZTJz&;`1u_bH@m;a2X4+Vuebh|5Z@EpzHG)>nwDFy7^2lJD zOd4mC$CJlokOS;K8IW2#M_f5#@X*4pHy?KXLt zC+RiQ<^&HinVV{pd7W*NJ-{aOC)(uqV(VbZx;!HPnqznV^Px@tt@aal9^YZNP8_w# z$(G#NYQX1gOsxhM+pR&zZ8G@GL)<3-x%WkzjD6Q8_pP?c{a@PT;h$_W{Upi7Y{q<|@%t0dco;$spGkLiz|rZMaz5alZwLz} z8MCU2=WWAZ-K8*O5_lHl8pZ|Y2|$e54dKsWfV7PZt-diOVL`%EsZjN7BMm-q3yQsH z=}jo2uBih*jESc^ZE`nZ*E!}IQy+7}NFln3sa!het`Vb#kfbxT#x+&DO*p|I4*esfevnM{4Tcc#r}t)W$BraZU1KnWYe*K zZdjJUdZXagU@^ESy$G);W<^#2usRHa{5up8+}os@$iIT@U|4P&g=-ltOqGeC;~d`v zoby@F&H!_^6!*^#Ea#f3BT(LvzhTv!3qT9}xr#V5ZB2C?Thv}| z#QRM>NK>N`W7-07kx54jbBN0!?GizBFw3q6qOCatbEMx4fMgh@))Dwnwd3keq7-YoqahI^S!SkH2XzXAAg zISO#%-=)A_Z&rYWAJAg4#Dj*Dgg?iqGkKZWg5#6mAoD)l@S6)Ec0&vcbnWso(}07* z2vg^5Li(2rd5(}VCL1l-Z^nfo)^{HMd6${{;!)8l=DRa#WnLIUf)n^pAy1jJap31S zYr~M63E@A5JZmmRo&Dy=FvJdv{HKuT44xVVBvidrjVzDp=7+{`_eJwzcf6PsI)2lH zFzYS@Bf}3( zp~#}912H#(vNaP_hVQ&P1@!?C>mw-E&}(P!YYpD)dw+u)oXl<@ehi}&Fx>Y$W?Oa| za|*&>P3`yI74~M>V5aY#5n`bpgsB9$@k;>Xd@a$*tc7$4J4YtrJcTSNm!(aCkb zb79B=xJ;8cjM*xU|bW;B3jnZX^tkvK-SfT<8pj|Mz`D*#{lc1;$* zVhEQ-0BubI4+?(ttvnyI^d<;)QRrs8aL4fk_Peh^1HgU*Or^i2BLA$NC9qw13yRVyQj=EeVRU)Xp3^ zlZUka*-s0qD-aoB6zXLGPx==ieAaCq$BraG>$T!W)N8sw^A)l16ofOPEm**8f30m| z;cW=ti?;A$AuKHPZ`5&U8-%;U7Id_-sCWFq7i8@C1BlZRl#EsuwZeZE#u_^g)lSBl zF8-v}GFn;GdVk;bV(T&>x3*|M7`?-KDh+#{CY@-Mi63$i#fq&f#>Uqoe4lZ6+sCz z7S$%uAS5+?4Tz-?l*|bh)jcr3qoB3|@k0a^Gq<<1OKZWK0^c=~vX28>xo)_+(fnD{ z!vl-v2{aY3)}^7~&!X-R^hC5R%iV#vIf9CeK>~d?a50Ls(E9+J9Dxdd)klGy`GLC^ zq5sZ?^xX);9t%b+VoV`+b>PjHfz1Q%s~D^_MGM;z*o;BO7F-ON!7^5KjD>XzJs7C; ziTIcd*hS?)OEpTXbSiL%hAIOJ!(x=8nYH-D;1SF()}M*MPA>-!dM&h3@bS+Dx)`vv zG0+Gjg1;oV2;(r>GT#FGO9XEjlx8^oOOV$)co<`o^&$@Ku_peaS+Rp*J7b}Pf-m5> z$y#j%So;W+`{1iZjSXIp6%>o=2gLBwD0d{^)~sxavL^&*u7-=_0eLJ8gPoQ0AbdV} z#R_rk6$qDy0TJePY_s^q!6Ekxemk(g{TDu>t|e^<_UkU16;g1nkH1(7?8%VTRHdE4 z$vCIAymf#=-~Uold~xviT7thD*eA=wN5|3D$rqQ2W@8I^6$&3llx!UBKWVoXe`egP z=rtB!0PL^j;iKE3RcacyX1^%KpM$GS_><~K3ZatL>0Ls?tm#x!v&D!Aqc4cF>v*PR2Un-HeO;J&ya zV-!}kepy&M!^;!FV{vz)htNOM45-WTCkIP5W?{#16v+#3!BcT>pNrYAA8><-byF#s z0^z(W6pRn`{t!2Bz#sE45RZl}0`S>$03?N$qxKds55m`?0WV=yC0IN3{0OXm)2B5M zZj1)-`b@A%sLCtibP?awlHHeeS-pk*Ak_*0=9+KTCGfE`c{9u8Y*)%X{2rfy9? z0NB(BG}__S7o$nki@)w|fi47Wc?25Gu!W|@|Au>Etkvy+?TZ*wj4Yhw$N$u^}ZF;-vaha1RCw|{&jG8UVPj#oQqb$ zFcQ}o$3OTJ8t9oiz$?bVrSUfomP^L1u-!faW!+G=MeT^c8w^~H9i|@;cSTTPgL>Rz z@rUC-#qpBGPXTt(f8nhwrTjS=KLfS2nror8Euu*R)t@sfe2Mi7i#iCz$p|XqPc%NQ z!dV!ZExsnkjMn&zB_uL{dhxtg6VJ;*=_ctV4E-O*jrtAuuEGJo842A^10Hw7xKpyB z5yv#Ayez*|WPsiP{ zaOxG@kKvq(Ybs80)2(IOT(nbv;;sfbb@mihy6Ar>!Kn`Oa2;fy$pC5?k#vei#i>Y1 zcKz{6Tj|>4PA}CuzeFW|fHmTNxDE-tt-`y~(5KqtX5%gln)92_RVQNI=4?Hzj{Q0! z8@&BG;t-gzUq|G{IVRz9 z5cl$W-z;QWU&u??$vjA@~D2V4t)@OJ#w-G3P6B(y^| zfeN6^LOPlUvGoZ490J#{xMJ42Gj4SE2sAI@-+amsAI28s3o62Nx7VIP`=dhtZl_1um=+}7Q- zEAES*80h-tKS<)cjvIg^vFixLdSXh~N1sLljW{&-iBNg`YkVTnbbab_pSQ*9TJ=sJ zZc*;qZZ3rZuZwp8#rkjilf51WOSyX*OIeAa@`ZPH0))(aYeWo95;#x&~d!*fm3?1zG zgR;-p?QL-CkC)9r_u)hD_xzP)Grrq&uWq$&uCfFJ^jAk~6^3N{c>5fDT~1Qg-F z&zafTCxO@Z`@TQdwNG}=eb1RQefI3^ZXB0wx71#iGepbm#&~gtGg5~FjfadtX^qyw ztdVz0LEUuX#?iRPh~btqhwf`#KjMF5eieo@U(0MOXZe5a19h_{rX-(R%_yFU z6R{_GCK$^f&U$b>vlpIB%kH$dw;vV2C@1+6!|#{EfH`7IlQAL7O_T z-wJkzD<;K^wMb&E9nx?kt5*yowLq^s z6_j`OfpiyoowBI8t)TH7Z zA!dr~%j5RoRYjcIC=j0YNuoiMUY*cdlU@d4y-yNNYJ+R`edD<8y$|pspTL@7NB(Na z-dws0;2w@5$!+4SmvQd}CuQYCW!Pnz{2)$J9KQ88g>s?nis6trS%7OQpL%5=)EQJ8 zwAPAR)(W9Yad8-0mpmqxj0A03s8+EgB#x+;IN0(UXK_X0q^z7+fe%qnh3>wO{8lJZ zsODL8`wEG{b9l=SRj8AxJSzS(o}en!J%c3ThyxYs(w7Lte8WZE3Rzl*5E=r7x5Eru zq3&)KtU#iL2ufnkG8b9eFdSVh#IF7YK_o?E=%>EBM8;C2NE`(Mbf- z)@nDqGq9MvVR=er#Z$V`T_33e56g^WmK8nq&QPAHHepE>J);BIvZR`F62TrnUqx^+ zmMzgezvWZj9~|9l+(4X8gc~Ee_nsj*C4YNJds_(F>j*4ve=~MK4^+ zr@Tswe&O~oobvXn=*4SU%A2mDmu$vq2O89Es1?0}?!X8O{Vb+kRzkizD*1Y%Y!DVO zfP2qH&36IE3amgB9sg~55|lbVttT@yxQE&T=#cAVeiM>kE6=_&A ze1!mcr09y4^%#zrr#XEPcRN-kt16l_~yP41qV3Myv-8YYJ zNiP?`7r>b?3g84^gC=yMC6I}Rr8rr^1kVP(u^!!%t~G_zhc)a3xR(i@4MG@1H9o@J z$AoVIo)6W)_syf9qMCnb4R--L7&DCqAxxmL3$%t9fCZW0*}yl}qo>o{)!N8v0PBPj z_{Mtld>Ti(9FhU{4khr7_2^~PuRLB^#YRp9I5m{OH`b%qP@|u;4J!ez3nlRV;^;T% z7JO^x&OyUIfJZ_Jd>s+Jg?he&eeaya4*)NR68Oe?^gHxEoLxc)t7KUbI7~MAj&t;3 zD*XZKh+9A*fN@NaqIREy%nGDJx4P{d{T(Gt($walb@r*xGgWRoN8h9@Pmt0#0)$CE zN%SewJ<5rpX(1>2A_%WCNeW*lIzbZUJ44Ye?V}hS8c#tE4}f;u*SAdUn*pl2O%~n9 zZdMz#E1=x=X}a-?vS;m-rn+TjdlLO0ht4cFMprbdyFAfb>?lmO(uk{q)*vkvMZ))j zqTjJcJ+E0kz!>7QIHt$?(jM1G*V1$_Uhr8`CR*1e`&6RVwF!(5e3lr;Kid5qoypl% z2xWH?l=D7~hY>D|cVSr2NoEK2ZJ_rJ1NL;}HOga7d+gVG0SYNMe0s4sOrsdE4zUY5 zryj-YhnY|rV9ihh`-h{;J5OT=o|H}}fPI({(rT1zIJ&m87t^=&^GRSlZ`7!2PM~ey zAhBl7OWk$pyavYB2UyE*gO%ju!Gs!W!hf+)<}^1C0C33Tapgv>8r- z=#kDxowTmp37B+oq}3&?Nly2IT32;28Zj%4t|gsd*FtA=ODs5_K~ePrV;Hm2*d?sj zoK>&mo*~9znhC~YW`*bqaK6e@pb@5D+6eGnqek!9>O{|yV@1!gr3AhLdD>$m|^Pa}_@2IXmK_JRHEYe8lB;=+v<^5Mx%vZCZsz#CjYti=xnOty)UX7uUNX zJ!}y7CE!-zIS4c-5}dOLUiUd;aH@#ql%Cu~4sK}V#-S2$g|ZsDw88?2qRADB%79qK zC%?{VYP24nJO|RzM>mI{jj;a@$T%P6xM^%@js1UsSNIfGkcKjlXba#EeM&u)php?N zCAOUCOTgz1MK=_+y3VCxBFy88hg?K4a%d$cU}&{Lqz1?455CW_SZA|j7H;yqky zqB>|h81EStMlW8VL=>?1Vnpl6gi`>|FkuhpRB!ByC}B6jJ_XTm8{mCkgIa$?RItxu zaU>dYS4SJfp*5&|dlA*_M6}JJoJ3`SHJPB=r6$y~OU}l|7bbK9*gaGOFE1jR+hcNS z4Pya56RJT79c*MmX?PjnnoteA{)p&dcj~2$d>`O}Py(+%A_m%Hc5A}-0560Rc>NJE z!j8(Wldx)_5#TV{3yc)JN66p&ox16VYaz{`t>DR%iemc^AwwE#8_~V`DJ5Y&YCAn zp#>Fzyc}a8W~#+cgzYS?PS%rL6ivYB@Nia?lL>t#ky$BVOkkE6qOx3#Tx2OCrxQS@ zv}qCGRp}_QK#F+68S^FfAF`fZARJ;+h)s%A#o6?PPV6iQSJG)xd-EddId7sZi>mNi zaA@K%ZJ9UkMKp6x+geQ#fTft=6&~-+i)iN@&Z0Hc2iS}WUT+XWvNHlBzT~0r=6NtK1O3xy98gV&cjH8?cRnqGO3qRn*U~t29`eZ!q?`k)!G|VeMhRe54eqi` zC8YKqMSSO+NY(>XJJ9;3qv{lSy%}-U*;5iWjR$2;I+`9kg?8Ur4U1_lD7(_p`~ftd ztT=N%w?9HB{spLK)6(I9;bm#g`FG$8lg!)!Av2bhy7fqA_y^sJH!?)D4l9W@0L6k* z!l&_I4+gI!BYK5R%Yss?1+;--;Q4?WxEUL3MEBfrAtZz?Zi#_K?L`3znzsM4=SSx}@o-=)R4aJK0LI2V1MWXvzDYSec$ z$l2|;#~rKF*O(G5dRM5PSZ+Nr_CruslT zFvIWEa@!C2{2p^oMBNO{cC)6T;EXkz+)|uiHG29VsB4+w`;T!!N(%t5@hP$fsD^&# z@scu3AJ4p9;Czyf_i-ceI@8cYNODLRYq#kNI5rk?;u<}(I8A0<4$BXolLfmP?fn*c zpF{Oda9Nf_v?ptih$LnFG+4mDz3NMwc2=(KlywWV)ja|61{w&?=Gn~eHkBja>ItOvY5N^L2c?z9^ z><1%vGXg~<{kZ5K00`-+NP2mc{B|nV*rog0$MLvN>3+QOP5iVRJ`juKu&m^8@X7>G zDh{rLxOUAF*c~~PQOT9if*J9`530EA4JNSR6_<6S3mvNk zSTq?w?jvlT-M=GPYuoy#s6$D>33|_)suX41%GK}YFwb|OgGsNNCM6-gov2UH?+i>%h zYL4%?8U@~dGs-Z&=MtPcQl9YxUO>F|pWTA^ndgzRV;|@9SsPirs5nlSJ}+#(rifql zA;fhk3`^hmp3_F*G6@Ck(C?78f_(We;0!vM-LaOiD$0x%3(HH5gM3u3rjEt6<4}Gr zzlKZX_-EQSb1X@kDrx&c}>aXQ1jzhkt>eG(J z`E_WrmY+h+#lKYxcQus!MJ?Y^8S>pPtZpbBh<=ZIV(NQ7U3VKi+`-#ZcqcdK6<1v9(w((Cs+CvXBFgy`4tiI zw|+&FB{Ds#JC8d_stcCw(ue5*at?!EQTRbh7r`n!55+|BcsI$fhE-g%65BU|a}`x& z^`LENaPj{*R1h^_l9ORBJ0vPeRhHa?-Fp}m@S?32^$;r;IaDt+n$NR(QER3wByGy1vlOz>X&MUF)=^x z<>iWK7S;sanv<8i3@%zpL`#+-7(TonW}{Xr6bP@6){NDKU|C~{<43fmX-IVrj+ioN zzdVqOyd$lEY@?C8vNJ=2$@Ct8BR*J_htd4>C@-*j73hlGoB?>*CnPeV0_8)Jc>deS z^$eiB8cpgQ#dx2c?YlJrni}Q6RY-W_eK=iH331pJB5sPooZWnsiZLo;*xs6s)rd`R zfr#yK#I%%*Xne%pVvfbe(=cG87;mp}cD_eEJvFamm4uk);b)1D$I@_&^$}xfJ!EgO zTtZQnlxiF{eZwVpTP?!4}6ZSrWl}cD7ES(9->1>pGoTrZu>MTh@258*Z}JGF`-U1uMXvB+o63m~fH}=zyj#y~cNv@sOpRWYW@=ldR=YG@mv3VA1(5 ze5#ye70|x4lPrNxm6MFMYA4w+K7GJR#;wmd$qu0_9>ozeP+C=plk6O%R}JD0m-ev% zf)FQJhUS))1BZ(3t^lftzLTsd;A-h8PeYehSRYY*Cs`X1yZPjaoTl$2O93*$N2i9M zaFWdfvdTv}ZW>$QBzqh10iVJO(oo@UC>TX>l^ZIAE1l4gBM%c3-EAQ+>378`|YDeWXHI}8nZ zHqcjmhExQXvPa8e51ItpHcXG91SZ@C=(I!$ zyudm2on+S&w1yaf1(~2)m2r}dYoRq%16aq`V4P%4Cp*>)oJ2Cf-o6IoBpZXiJ%b4o z0Zt9opq*s7%4rQN0j>+xpq*srvuO?c03Hd|pq*sTV6`II`~l$QP=a=n?X9c{VXe?3 zap-bTPrt%R)*96-Miv5CB9x$=WD{^bAcVRAn}iaylPsy7V{s)?AAo~H3B06&ldMKY zO_&C7j!!U7vN*mfSqoq@gHjLDKhYwzlWaY2i8%!HtF#PPHyrIGyPXHLUqQKPXugwd zN4Pe_#kiaUhbaoa+XyGwE9D(^x3LVsc%R@o$)YPldt=DkGZtc|agsGfStW5%@O(D@ z;jAdx7n<~r3Nj9>&gNxH$fDfgkcuul9_idHhSrD!;Da0nvNmd%m zEJ-Xw8%%;YLK8DivcXtAi{Zt=D9bF>8#JMrGd)bJX$-KHQG?RePO{3LhCu*RLp5k8 z*~yk#!)$;rglf=EvR!ycl-HrO3E=in4cbXI9@`%I8j+3xJmqUJPO^W{mgy>hJ0`Z* zK(v$WQ>;Mn+C6M<#i5I9nHqbvlPoi?OehX$CBwk_haFWp2TU8N$BY)hx*Oc(kw_(E zoMhPxYU)_fo=->BDQYL#Cz+7qYEa%zN7G}cc9Lbp^iCgvayA{!A3!}PSwc~r_#IF) zv@W#z{7EB9g8HN(-OH69@XIc9KP+a;Xo{!G-}h zOAX~D3qzsXGzG{agR1#gdarSkWgo%3H^6x}EzdZ~3P&^JGoWXEhB(QzCha7 zWOdqbf-iux(r9v9ae~H4HVW744($MZ#HYv_Agz;Z!A$0z1?PG?9$#H!HxIN{qg*o_ zc6V)T%;`Rc8M!D9xzyr-y42FOFV}$iX(TT2a&{_<5tAB&(%$29;6eUF7LNt@1`)Sl z*FyLWl!Fxomn7pfPrc7E?v?Ib3~r!eV~%6VSKwiuun&1<$y=mK_qv9s8;mFH2$DaB zBj!Vy%(Xm)&Ovt7$lW8{HjO9j9)Jj>ry_Ztux0_6V?1G#!4XdwCx>$5aPT?`7oMF2lShd7 zHm@Wh8kb6Z$2VY~b{wt3spmL43iaA?v>2zJlEyA zs5ovX_>QA~IUH*htD@Rkt{g|b=i*bRBJZT-%5l`Fs$)sgl%nNH6JhY|LgO8)xA13b zxpEwB?B_X-R%^L(91X@yt{gm zivBdR=mx;>9Y@u%vp@)C(-7S2h~zttD!ZtH)`r0mJU!ZRG|6)CSqvmJlv&aQjpJw= zjNm3kvkV4T5nF_RoG$*ca_u-eg^I59-ZZZCE6%r&Kj=8(2B;iI>$x>qmBx)$^vqrU zovs>q*<9ExD}JUj;6KFAB($=3Fsg~4sjXq9@iTEZhMy_$k1c+tSzwv&A>+$fNRq@t zRrK7RT?zM~{ZP){seKQ`+QPBKf{<8vIUakb=5t!?o%$&>n$LrG>IJ62JCzZ|Xv_&= z^rmfCry1{5G0?<2#ko-x*NYCZaqvzhhw6|lHG|~g#`U5IP8qRYcp%mkj`h%jkPB{Z z99Ev+d!mWNm-ram2OU{VF}bmVyT)?WB;Ev9JF-zW=Vu4*ohtXtiDN7kpfg;$If zhB&fV<~y=f$a7?=knhN90d9L7F~6hng*dYMK{mq3-P_zWW0jXHnVthM-v{qA=sB{w zW0gv;0o>{n!g(i;=g8V)p2c(m0N^U z*Wi3A1fXJC(9^9QS@nRnHVorTP>!taSaNYQ!4_j=-LTR+vfASci)I6S#V2s2w2rLf zO?XkW4V1k;&2wb20q|LI3ix*sk@1hK5dXNQOv5)_!3uCE$ukYBE;zD!4@A?KUW1k) zvuVT`9%{5BOIo^eWW9oxr5#zX^Qm%VO-B3Dj;v{XsvKFYRXef<^63MPEN*?qku|qF zHo@VDDJ88c#F6znq}vVRmY4RC3PFe?>nMWX`<#9_RYc#Bbse&dJ-h^5p(H?;Ru~1? zcVy)S@d=+?i_`QSSyh14_t6F+C>&WGfei3bj+@37II_k8p6yduK^h7iSt|f<_9-J# zf*!?lWPJ$un4y@qryN;jdOKEg=%q_w+%zm#vSJ)r6S`@Zi(&Rr9IE(T$&zto#TC}9 z3SiXqS!|T&q57T<&qG6Q2ehxxFs1C#ve+;71#LViGklsTGLEcMogJ$xs)N>mvB9u> zM^<}WrqyS{0f3({p&jSccVunHwTWoB0Pw1>!8o!$$)`1B?1fh{;LsY3BWsj{i+@g{ zD8SN8Q0>w3=G#4IsHW!X5gZVuqf&SwG7O-Jz@S!eJBk)*aB zgl$X;vB`5}T^gekI|{-#=`w(Ali}D(FWrypg;PIE~*J>M^^J0VEhG?`k6d;LweXCk`;QBdc8u7-fLQ z8;0-5T90|grlvrW4eC#>;OX67Ytd9~dJ3G$X?ezxl?Byj(-NTTeTF!)WE?QNy)MJ! zXwwJaob-88OMYP)N7hrhnS2$*J3g6tz9Xx^bDkqB`v6RWICSeayS<*m%*JtSstB|m zGyG1S&XF|}ehHhB!0B%^xsP#z#*vjbjMs9L0MGX+vIa=&$QlV>Hr{^>&dzi^<;Y@_ zP`)r9jw~1BmrXx`cpZmam2p5_U+HR_nU`UzlQ9xk-Po*>Ut4=yqFW{ zZ=e|mc`@C2+}L&WiIfXKK_6Tf1c+@!xbK&J`45<}`B@683PJ;)BpNj7)qam_Qg;vr z`y|oiJ;ZvS9U0F6oZ}PZDUI@!z)nJX1@ess(`&nOGy$%mm@;8>0?flLN8)Y5DAy2xFLM+YaQ&mvSC|e5DR0(sa z6^MgzNIDg8qSEPmq%L%QQV)WDRiIp_+dk)V0Q_n|U4qGRTLdU7YRj(0Ni zu-;@B%yOA|KL=n#F*X@}hw{88isU z(>P>Q;Xsn~5k>ZTTshoA0e30jwH}uPNzxNESI%Q;ep%su2KXnB%YmdKaDgRpGf$Fc zu4A#(eS;fdDRz-1t}2ch7#XkvTv-9G_ty0v!QBnF2{o92+k164ao`=Y`3d4;jC0nr zje7-If0wvy5Y9HIIyCMiRWgBWEzmmLT_g`37bsee4nAXB?t4U?p`!IWa0@nkO{Z)25d-%pgH}CKH$VR-iN@~6b@C$ zxII8#h|r2&yMpildC@^@;x`@Gk^C&T+m5&qMY1Cv?-$~d4m5_&NZ#|}cBUXQ5V`pS zoOdB^FOeJgJc;)6Iq#`*yAk)jNcJbVm29q(NPc|GebT-$5$F6!x0_(!n2dAwF1S_f zJ2+3EwQO`xdIh9BNQ6!y)iXF^@^Q!`^rhSt@OmQ_-3EA{2}Lx4y;tr)+6UPr9F!aC zV{vFgRr>f*5Qfp97ctm@U{eCnTFg*sRHN3lz!*VO6Bz9Pq?bWmj)Jjl4e|@mqvIx$^eaLhNt7P#n5q;rYDlN zqb1M|p*nDKk`8mEO;tlcekqch)!tXd%Rxs53v*S~AOW-6KbnL`GRSoTkl&!>=CTXa z^Xy(25>vp(?8}dNCT|XjDb~i?fA03IJsJXvwFT`_%{*&=2?6D;Bt`9dK{(STpMj@* zYXvM}@4{2Us@W7`P+Kc+CMjcoimOKzvsOq<0n6Lp-1aIOA8peytI|#G-j8P(QWGB^ zK@mDM8sKv{RQJ>pghYq~=<3#|V^ z+3C}`QF?>Qm@jbNIc(Vpw)HqTr+uDQw+waS4hjq65p8ARZBQN=WwOsSQ74N6RDnbo z7uNq#yo_G5R1DsqbPDw&3y7-pW^EMO^I_Evdim-I^3Z=tK_a{yb`NEzQkV(y z%Kw-`IZ7=J8>iW{6`Y+$G3HDGX4v!zgr^Olrqu*#Ry?9>-fWxx0LMc4>XuiFDH`45 zP&OcWeYAl>Q#kSEHkAQV)u4J}RUT6JE9X!nvYI0TwF9Mxp}CTTddA*;)!uhQO~W(} zjAxmp1~KLNbYHjI-c^N2%K@%6YA}uQbFS`YJ8q0BG};63psztWHr*Yzi>ElbqUkKa zpM4FQu-kT#A1-#H(dc$Kj1Bx64fjKP?R!X?3HbpQV}du83gM95F9x1zCe#MlFjNCO zHr#G3Y2qmyv(miF5nhv)H z)+Tfa;L%V5yCvOk?Gl4D;Ud6mK0&!X+{!du_Xnml0^B(*#TA}r#E~i`%LS)2*w?s#daycOE) zVgg?b@{jfcx$T_(7{{q1C{+y&M)A8J+`q!@D4kq8fISRB4Jw+IF=MX!y6uevV>+|c zn4(SRcR#qnj7>46N(NVhvFQO8ztzDV;M}OA8~PD2zGRj(Q#I@-kg$e0_iK=9?bpEg z+t($Nj(Yclo8nBylpviZdYonD!;w}Ozx%-*=`=vmNzX|DqaL%A^;#Fd)xq5qmQr26 z`=J{cgM3{&kHR_{mNUUp?|zsH#sXiLW@X3@UHLN>ep`2gH^6w?u<)GULU?=JdBmf) zP2T{yfI}{}IG``KRDsBaS7$1ZTO#gtM@<6Z1kv=JDh!Q8jmED<6;4v+erFRhH zQyh{M2OhZ2Q;DX#&P$*^#i3oEjL%)mF&H;r=k0} zukuxoz4-&2uH%cOSUS@P=daTS$hY8#S;aGqHBialB-#(*F$1`Ba0*}5J$x|L-O@fA zJU0-~CH(xxq;(QIANA#KwmnNZvYuu<6YR~3!{FU{G}@JT6i)_njAFpbFs@S1M}qI` z^C_k#N6aa> z5V_Vwehc$1gwGkkt%Fl9)?c(3q18Tk8gZ>aX$bPs=C7gmo{Mh6VcLtI!#HAo6#WUR z-W_@b-um23IFFx8p#-V;jPOl6RzW5>$bV)WMuXIB7AiE!u`aXHf&hy%L1iI9Reg|7 z!*NrYHPivv!VpxoC8)Z8lv?8n9Z@p?jNyibNkbY(e%gpTgQ8{@z$J#@sgc@$g04>1 zH}1B8@jkO8!|rt{8jhc!s=pM~XrQU5LA#WW>eqk4?B!v5!5bIx8@L01P%tbHUId)I zE5D6Lzd%tc*tnrp$bW%iRa~be;)wYYE+(#X{Q|`{ko7il_gi*A@sG!tKqG-Z<1@~O zfD>sUfE7M?iNSo@_guN7WBmpJy$iwtpClSI>D8^+fheRiAYArIqRI0;$2Ek5`98o1 zWLM?DKgyx2C~)ZVi8bikCS0&hP{?_f zZNcDDwlu%2OL|V(irk6x8PwX5Ztub-h-4HfjIRx_3mV`+SEHx*zDwtUv(T} zZ&UAnxNxh(E^Kd_8oH@>d49_p$*L%qma9#@Ga@XDGviPhEmxa*$KYC0lBW7vo-`3@ z&8~DE1CsE&YPs6f+c*)^0oK0`jnZCs>POl@eQcw=e$pXuXgFC*?-GD&MLe1B(w0$_+7(F^USy?>rL^$;URYK zk?g!^cCzV}Rj7>hpd$Cdz>eJ308NjO)npQxu2w7Chp@@kBp6tN$%ct`HY&}cpn zJ8~ak3U=f!{f~?%IBD#h{VbFrN$>fONy`pDt^q60Q6AjlOJqP9Ke%(2DJDBsu>Vpn zu0(m`8;=0-buWTol!Y)$U~tDH;Bn8RyXr^4`E78;SRs#b;p!1^c|)9e1YCu@owF+B z@0^_p3+LmA>4-+lgPnc^d^Kd7jNI+YqlpHS=>q_t_+TFfy`8fyYauu10ABS8gPGv% zoV{b@dX!YdT11m3-(k6x6Zz3QXCFIlcFras4lfJUBjB7}Z|CfWC0N|D>8%m56ONd% z9P;oHIWk!m8&9dg#xOov<7(&Z=jSnKLQD(sv&_f!Hq^1S5wfi;S9-O40_}(Fn322F zpw$YnCe4^k7ZCW}XQbUZ>&(K|R~$;M>^D_9bo7~22xy$okV4krY^nvIsSnQK)HOJt zk^u}&3wpZs&e=&oXB&pDhkT@V&NlxYx9DLvy#~fs!%DkzcKt;V4g>t!Cvc>+J7Ee~Jm3=+hwbU2Q`(pdv=8;+RUveKD~Q6mCpPNnEexRf#`byBApAkjiJDvnR^>+>8fsT;zY5`>bhzS6 ztl)wUMNVIV&{;ygSQV!;@-zL4T;Q_|U*KQG5e#4SqSoQiB~7T|-+$Q1&R>P}%2HM;todOe! zIJKzxLNNXyqP272D8&&IBMpF!heNIktIJ@YosK4W22C6db2gSEuiOBO&&B#JvX4xP@6=*hUM8v8K}i?#2~(Q(RwQQ5HI1r2*1 zD*D;&XYq2X1(5bWns{X%K~2^{vb|~Kt_nW%h|-XC0>R&RRS)=J>(4j@oNwdlt4C!d&^m`=@|!F z0WR!3Sr;Mer8_6j!}L`T13gb)W(6J#X%QSTZKUUz6?i4c5{=yL1k~Th(ZT@Uyb|~e zMUtlo+90Olxqu&>ikTtf%=En|n>;) z@=^`h-4+oEvk?R`0>09Z2gVn6wRQJ zLLtZ$N$14l*j#~hs)r!llC5C$OvK67OPqr2P2~&0MBbjmyPT}3b(zuqvR$B$5V07? z=0>KvR<_IZT6f1v#AP(i2J#|~m_{6OwJ()BV76arHMX4z>uoST@LA&7l^6cX)n|Zh zh#Fl?<>3+nUhb6FYvf=cF?*^nw5(WaRKdo>pA?QjB#xLCoG!Lv=EN%iV?KKv+rn)s z0HCx1-FBc@U7OCar5{nBFUQ-+|ChLE4#Z5n4_^2N>RouTmxTG~Hif%hLHyDko;)LqKP!oQ7u z2{Fy7abCyboZ)SAXv;oJbZAz4dIeiTh1Cpjp3h+2_?$+7x3fj>>>M9CQ;v{zl$Blqc!LSbMCHfMaoqXqU3>tSZHUC>Z*Cll z;5ne#O`YRw=jb`DrW_cR4GUQj!dd4n5JXLDfL#s2QxnLGg1YFexUE^E!FY~Yl3_Op z!=Q^lFrVX!bNiA`Yy}t_eO;QBjdk5{GU6@0lHx%yPCTHi3mbmRIbqp4|6tsHKo@`P zA;&%EefS}yoU@^cV3K2G zOb8+mGDkgHNg*$UAi)gi1A#EOr=y;otl+mpU_Q43ytg@O3nnQlmXzUh11D$To?}HF zsG^XoA&Be_jha|OsmzEQPoDkaEs6SQC+93FLq3BfXHYq7&JUgdNeDqy&I;g}21eS1 zAd<7-kQ``LS-P$OFq{@%u&gXSX)*%xDpu})uKBT=(}$R~KoC%#1~)(G?W?XsRq>tY z5!-%Y1?p;dJ>>quwG}UW^xDe$Nsj@t6be?u#6!i87kvo??()SyzcG;~vk%b|i+}NT zBggs`$|*Z=mk~97@LAVyK2rNdQKQPc`f z#Dg+$ERW-qm1CK=-^#L*Ppsh9{7hK(6BCqUneTi`=F+}5H4}E#PX~*3;>Qj0rrv*b zEc2~6aV)bwE12UEq!Zuf&UR zPeANBmU~om;053-p$?GxZ;L2{y9UQt6%EsJ%CY<EmNV-*SDbMyJNX=ocV*K~gH@_Llq>a$a|5CW9mm|jl;b$v7ICXmRxI~8V*XeD zJ)$hbtxC&ym;$}Uf1%5I9It*T8=+p}Fco~$*2Ql-5)!pJLzN>pPPH4p7ggX`@bD_khCP+i`sK6q*V<4A+3eEA$fSL9u(0^rIqqPtPUJ2 zT``BGnr>eOeBZ2z^ZJ0M)&DC^;+5lOfp-lP4?@3$UxorTJY5N|0zk6IC%DG!f_f~z zDaT4Z2o&EU54p=#s=sdHu@|2PkJr| znI#!^N5TMqjkUXlPAm)+mKBGx*<|ckFF4{elveRgpM$0*{LTJ^FU?drQ{HY*Ac$9F+npcvq|Gub z>Mr(RQLu+oaE)c9P_U+B1qV9k&OvQ%ND>=Va4eqP6PxN2nf25CSY223Q@bgkusC0f z1amk;MPUUzYaPs^6!!X`C`_ZPKQ5wpIXD9`y(O4T(ox$wDP&CuB3CiN3RuZgt{VJN z&r}-qAsokv4A2jpdaF5VVePN2c&Vyha4*qQ>0%wc=OU5Im~udeMB%dbS6m!&z|Rf_ww{kJutnYdk=Wc@80ru_mE2{4tw1@KU8_$yCk3MODN&!?!6{W_nrlt7T}24 zkiL7r3h5SuxYcm#ckgzQj>QuC1V5iMYjfJ}y%?UZ!A!V{pFctgx_jTi4BDLukGzWh zkHcut-TNL^_3yCK(f}(mL78Z}_s1Y`wNP__oejb3m%4jrDyG#u1;#kT^1Js`G%!)K z7~pC{@YLw;eG!AQu-*gX2(u)^Zd(}Ockh3&5EGk!0OOjkOS5$MPQg`)=*om@jmD8y zm+szshI#o1BY|0xe=kMdy{jO5QqFC_=$1~GbZ?m`0-Rpd{o=a)gXgvXNrSoD?svJD z)o^YANuh#m(aRDY?x=JOlK)}19YG_okP9|Y-Lpt?g9g&q{oaj)K6aD|k?VXDl)JJY z9<$@l$xm#0#we!v7EXf_*B>vE2tGt8jL`5*KdR4yjsCa zHfY7aUJX!PdVI?bR$qF2mjykmA0V28ANgdjy7b_<=F$V-=?(Pev}^5WE&LgQnA+@p zlbKyM%tkG*%GQ*lU%-Gh_`E4j#2UQ-kn#^sOJr+~$F29Q`JCn6h0rHhVBbPKiUBSk zA6C{d$5?}sD2N%2f&-~HXd|e=Y?Ss;ViJi(yiRc0sjYq_WvgMtOhlT37;(g>RjboD z1Y%m{K{V{5uQMB~m#(k#J>{e#_%``72}f*;zmrYtK-e3U;6jcawzbbvn?ol1Gj;eqy-`6KG|9C$9D z$q$NSCAInHq&rBe&NIhhqN~@;gGN9KN*x^c_fFuRJ2{$`j{y_?v zk{Bm=N$84)r!dYxxD?NXrF_(@6uCjiJCRhaY2{e~>^c%xi)B!1qr26Y$;@>@h$cRI&bJ4v+u&qjobLZb5}=cH0JLxQvnZ`Pczq5 z_*>Xh8`YRU8%?!6Ts|T_9y{j{AK#BebzCS7yoZNZ0NdpsRL2QiA)vIM^)PY%gc6ox zD$g>S)`B2w5*{@|zJETP4rK;mA$<`_@P`|p&R+q6LG`h)k7~>}%jgd;Q4YCoIl=oR zVIV6lYpCpR>H^_nbkF>P0vk?qzk$oDGnGk$$zp0amA?&aG_?TcFS#T~ns6*Lv8@wB z31X|HV3@KS3bx+B?c>r@WO=&QOAjAvfUDsr{e$6Q(p?+(+DIH#2U#)SI^?-gd8|^X z-w5=}I5q42#f1O1%7s!{$o`|^l-l$^i&Ja?z9zF*#TmkJ{s*7cbotZG@`LOi7{G0% zByJbb9K@G`k==Uy1H4>i#?LUm$;0{UTdsV9E0rGGf*J9vmFVa6g@^O?t;-_$fszhc zxIv#nWzruWNlL$4RY{})CWxrgvLMd>mNtSfhTT=%eumTPmS}FM|1_AajEB=~%y?Y? z!2IOJn9E4=h%5*=SdY+W^naefmCec<7u zsX-ER9h$tltDZ^~ALT|aH;ep}iMi+Q2Zm3wActw8U>d zR{j9F#ez&caRX^(Q)%VjrtRaD&Fq!<2DSn7Z6N=yj5^ap^7m7?a@f5~wV*&u1v@m^!{v25>pK8Xp&oEg#9Xj9@x{j$ z5U_2jpKP-5w=DFjJOWSu$UXBEstW&3%uU7rAq~F^-$g$Sk-C%a${poYs>`jXF~16h zob5UTd_&B=+DQy-pNVn4K}`iboNuMMc{&UJLwm;AjZ3vXT%5YY7*C;AMI6)m`hg(r zLi*vNTrAkAb#e=xCzS)qd*GS0};>ug6Qm8ZfgxC7^{0FV6R2}c8 z$~Ax!qu-gtt*_QfUAtlfheCWiDbx*)V6;AoQ~sTY#qp=Bw2{@El|til!nA>53{nzn z;O@ryr1eQ04xwmn!QF+{Cuyzl(o)QRczpp!;nv6RLRFb(kviiSb3?<%4wyHhNiI$I zdTE&z9|+}eSsNUqEtP{&(uH;({u;PsN^(*kTf^_f0a1DU(v^d&J2#fbFIOY!O!} zll-M|x+p1B3+rQ4sl>_n?!)3pmCCvzZDjd~8%psP+!{ueGDvZ(fvc4DNtH?*4uN^Q zuT-g|mExtPn5a@Y;VR|tG^HzUl~yV}BiDybdn1Djpg>GJ3*|2VAce>Rc#2i8F-~&| z-i-f0c@kA#I-uS>kV2!nLen(0b||v*|E?*OJ{W{W#7UV0+dvU){?Chu0PjKx@O9zn zJ3nEQc{9FkPh^eBgtb7aI$`)74;|Q#TO7pEJqlxsQL%Xvc~;Z0e4u4Be79JW@= z5;0f}`g0!2Yusa4p47PD90f8yInJta#rX~UI5~&}0aqH1F zT(L`HT|JF%URcooDHn*BIZnncYZlOLDQB&x@23xN}sq54Ut z$H8k==ntiAG&31h%oNJj1Yl-ImSl@rE{EMx8>`Q7Y=+51mY+IdqY@$y4>DRiHw^eRfz zer8CS8arK4mqKr`tvi*X3rsV%dW`o5Ls1{4$l2pDbo2~mP=wo6^w{*^Q{55sT~!&i z801BrDrBktRO$|gN8&B%5=l%D8`%P^{YEW;WhiQK8uIPf8))eE4pVdeQKuIe{(UCT#q7-m4?32ExSx!Zz-1A4pjjU_v?# zDbx@Jp7@VSyCE~A3CNk0tR4oqT2tw@7D(P`hEq?Wy39OCTbao}q0F$ba=7uCLbbm`N;y^5zhjPXxTs8_ajfMyahcM+G+Mmj z^Ch^43Z0ZkWhi!EXgZ3KN`n@Fu~+g_lL>wzEQ1-Xxj9Z%U8@5#cqo8;J1&6=)l%{? zMz!=ziJ3}2j>e!hY|*F0AaEa&KQCWfZDj`JQTH7M%?m@ z-~lWfk3ADqpU?WC&Uh=#^G{)x9TBA2unjMdD_&Z^yLoLZXHmA6$lqkWD-#${)Ut9Fz-=amsiA1&2ek*ao2@QQnmnIc(fT+&^Q> z;=roJOtDO@*>khLz(v5p4E4aN8$S<>!cU-J>sHPLkf`wA4e|1V1Rbb=p{Q>4U(X5h z0m`m!4TU6j3WKu?+N_*qj{GM7zJBRv4*mG9{QK#+{JZeG{JR*0SvkvGDvf_7sAs>Y ztTHEmt%Vo8ASRuM4K7AS^<%ZZycb61*l*`Q>}_B;WJ`tf1_s%O^qI|0xJa(`9LMbU z`CK+F9JjaPyc~TS0Pwj@6%OKwFdQ)>qtTe)WfS0}P1Fq1P6kn~K)ucAy!{Tkc?3Wj zfuFI=nlAAZt~Qw0B(4YVLuN;ZTSg*{JZ3T^9sV^EklbhTy4@`~9|4^Sq_>@B$rBj$dvKiqKr!m^U z6vA#W4nLqvHa28)E`O?Zod@IB2Xx8y`y9^O;bgJDmI7!LE)HEKa@EU?Be4`7^Jo8{ z)jBbkYCqjS^4pJ^m;Ls`PIIsQe9Gs#{p`cJ-+o3Qp|PA;TdDt$_A>|4Wd>2Md((bO zCF5h$0BIY3b~CGo#5e7y)f3o!#)OmjIUP#S?dRxxyiSqh+yZ!y3CaS~eoBGB{eyBH z!PC7s6v3-_X&!&t9ZqUB)xfA@Sl&LCf9xO#q9z&O07LN9==PHzYc$Ev6fov7OY-9m zg@sn2I?OQbr)*W7;#;8Y_7w`%w4e6h>SRxXaXy_w(|)dDF(8F-7mNTZQ|D3Z((Nbe z8LcZn7^RpMVw`?_BZt#7FSh$|fz}73nPDlf2{#VE{REr#MY-1Pxe=_w{N=j3eL_dW z{(3aLUl*g{0F7+e1=_%np>gY8w8UUcVWe2M=b!&Snt1JH1?PPwHr4p}|HGys=U7u6 zjF1@kXRszU@ZX2r4E#Fq?*o4oD6)ccYl@~Xd`)o3`kHj$-!;jM6in_Wn(}^PYMpW!{-Y0Df3VX`uRqK)qLDS( z8>ZJE{J5xDf9!@eAL5Al6;dN_L0>?2*2vvIfFhD!e_RJ}&w%OHA8+TwS4jX;PK=%f zaK!x0s@)eLGwYA>1M$%!CRG8UzE4`ANNW8taER8_4TRxL5+mJIkkYO{%Dn(pQ^8o` zv)Bfqn)Sz(~iYsmV{Jz@9 zi6}9+Ib3N+(^$jEn-zjxPdHi-d^?r1_+fEm(LRons zdn)e?-EZ?pTh+sLhiqxSAq%Tcm{`1taTuTLiLp1%{fTil(tH6&40d*Yy#v~INyhhq z^pMEiP^kBcx@!s>r83}LMNZJRgu(?cnZZKno>cS!Xz=$oeEOg zA#qf1sCp5M4L*xw3e^mWg}Pf7$EE#XeauX;4Ef@3jbcdr1F{S#R2kUJT}GDb&*7-_ znXWPdRIu%j7F`GdN8F#Qo$>cR9EoCc;NC2ugj(L;Yo_e%)Xw_3fy zv=5JH*I6td`IQ@r-e9^28+y|Wrtge20yUWa6=4KwFrD7t2-INuKDOp)9cnQB)l(Xj zZ%J4Ba1^qr2h){sdzkyG{#RM8g41z#np$TXtp-#6`inQ1O2ZEsOy|${2h(+Yt_RbX zaqbVM-y+TPIAWgQei(X{dJ|Im(nDNcRQQAG?Y54!nF)`Ak)K&*B)%C;i&&2J9uukn ztQ|_wgXuA3p(4lW0WQYkke*!o2BDhbt@$KICP-;0SRfjS=9-0k%Glfg<@Vh2*#;UmMrpFs^9gktmH`E*OmAgPsFrPVNp1Yeu>Fa{r2vV znA{(bCO@5tn2F#dKM<3p=^ynBG1*P`tfvh4@~n4&zoiwN9g9+ntX%ZFhczSKl%<=| zJAA6V(7g9hHzVF$XPVJISaJkMOs**C^yDq*8^|sgxyv7y0jQhNEdXKYLMl?aW>jY! z)+ZoP3>d|jRftu)%OEq&=$8U`Uj>tDfzZ?^y{bs68Qq?(HT3~u6qCeAcQi<8o6+O| zR6P&Ia-YRE2-P&BuW)U|ap@hf-e;y*hJ5i$B2igCLv|a7RI}OE$5OSePp8i%tlm+H zYQ~EnuyDzSs>qAO#0;TA*m|h)0tWacw!v}*Q680^PB@M7ne`m%#b3BA;h?$-tQ8XpsIY8v)3B)tkp zOf5)_yajEAY>$z<^?@RiZrH~FoHk&(hP~(&ytW=7{fQqNCdM>l)ov<+reP<&4EG?D z9tEL@Pnw`es$p02G}Qp11(U=`w-rcf8}^UbGS^ z0{o7-0AJSzcu5&x?{$E0fdn^q!?L_?&mJi9|Fhdx77&x@U?yxXDD~@)Fk}MMxs~u} zm|Cq)qKsI8gjW}A8Do7zusOJ73U4gfJ87|0I)NQh^%hB=Jq0Y$L4okf)_YWJAu2`V zw>+G^qjK*a_kW+why8x>YG+*Gb5Owh{nD%{-I~o|Cja0$KYKXn#T8wsX|Cnnx!pkJ zAHMOu3@fifhl%~e@)LURK5N)Fd6=`BIcMn-BFNoZpQ8#Ug?3=REc7#ByBpqm0afW4 znF5`|dA~qm%pj9V{yjs#U>rk$5&h30yGbeLC4v{=^2!ugkJC(naMVhm3Jl0S5|y41 zp9{COo~49JT_ES!L-8N~R^eYJ{i{XaWJWjqU^%V=;$mT*T@+i8>X*e0Bg-z76VmeB zwCv~sIIYA9*j5t|Y87F^yb3t2U5ZbW;y_4*kIk~b!@8?}-8cF4K5m@XZz6ig&+75Bg!RNRQR z9-j3{vKmz8yJ?sw!&hy_`ZGa=0^wDWs|GbyC~J7d^}y<>P_FQ|iy>5Bg<`|Au$BfY zR5W}!YiX!LWx}6iEsa#DQuqj@)S$5n)d2e1n?55K{oW-8Po zd>DME4O*yB%ka_b5U-UAwF<9!5ur9J)H-}y2ZY+GP@C|~V-QMGp|;_F?nEeAh1!J= zVx8SpsD1cTth1*IbqKG@I(w^7$MDUpv#$zu3J+(ULsY19`0uQ9s0ww#-kMf#AUuxq zM2Atr(p6N4pF$M;0pP@wJj!GWG(+Gyy2zxqprZwUhjV*yX|fu|a+5>LX1(~wqedpV zi;qAp41JmOFF!p9(P#LVLXV>fKOV03i&Xy!YWWA$I`}u0N>Qe^mi2g~&Hq?E^)Q?i zx{C^ZJg4mVp)o9HrxSEGcmndr)aH~0A@Zgy&!@KSYzUFJ%n$hun=?eGSbhj+>IdCJ z?@7cIg3n8m>tk9Su4HS2kiyj@m#3gV{ba5jVbGA7%ESgRtWP@q1NOjfaHJcQAU7N&r4$EG(J zqBY6njyvb6|`o`hgidUZB~GoeSAoUQW<` z7K>SYhWg{iluB)DfU$!!OND<9WvE2(h^Pa?Ztn0@?;!+yjQCMl@u_Mb$sPlm*H%Wk z%#(7N$YM@U4dpBYVb@&{T612AcYG*CoXXu-Yw$i*2_yEBM7HtV&Q!x4-%f?@_J({mly9a@d+^ZKAuc`{4JT= z8l}ZDWNnE;_zp&N^hJC!;Fl55hoGK-7t(p0n6?LR^vPzeL8h`3eJ}8!6w<^ zekic}eU7_jzhf16k575rJhu{r_xDRE5IzNZ3+&_4vI}HI^-YC5Q{Zc)6T#j28w9ib z4V0x55D@8ao-~L_2WjUY!Z!Azv72xn?+_QOD`lH0a1>fn>Gj({ew9ioVZap1upZ(k zRU1wWk#E2vCVzsGcQ*1=n!XzR8=@w~h*PNR9*A?RwlXtB9@q`}qe{&>Pww&=a>JQO zrOy$y$xRsnKVyb8Cr&`wpF;By$R8zHqASdh#?C+J!MF1vb~d$HOI4{NV1(Wy;6?-WYls0ncBFiN2 zcz3{7DBLRX?uUpouZMV>h#%#vW0O^=If2W>{D0U~nt}hv*qgvxHNF4i``P>6d-iR( zCk>=Ynv|3Vi4sYJXt+&Eh6YVEU6m$EQJPQ`m8s(r-BMDBdsDY4DQQp=qELtiWhVab z_p{dC=bU@{eg5C`dhN5`_e)$_>D1$;?Im25?-skkl z{p8tfd4%d-p}fR*dVt-nE=7oS5u(qcff&@||2j09={`?#1tcFrK0msE`{{;yvmD;i z{k5Q_``kM?-RI|Sfbn+z8~7q4b5xJw=v?mq8yjInIy60ou0xIc5m4JB-C;@F!}xdG z4nYg+wcTF{Db@CZp?Im(wpu>gr?!*v=!iJi`-MQ&reckBr~7%kn>p^BkWxmAe(~ZOusbFra728$LF>ifs2T#>3?LHlNV) z9i@-M<_Ry+^7nf)+PAlY<<1q=FBGu9^IC)du(-nz&iB^=mEu-Hi~O*BxCN9Slv0Up zwDX9hM2>j_0WUKj1t@Zyp_FNetcjdpAWr#GS0k!F1yO%gs2a}#ud*5z*&~mE@GP#1 z{WJ}zz_HA|vI30v;!LX1XM6Nl#4~_>B6|Tj6o={NFjmK>ate%p0D^darkL%A zFBG0;7CCSY9?d#ry&r&Cg+V(!C-P-+R8K}1DMU6;7AVqN*OP#S&?v(394u4mJyI58v!{i0y zj@dfdLG~Xm|4`tJxI8zT`Mx0 zxbgsqvqOeW@^13yZ(v{L-ZmH!cs^vCW*M~_zuD5iD?`4)_0B;RnIj`RLgYr*ct+6E z&aI%FK~NBB@3QANM<&&Pr-RF=&yl|{?u&F(bLR+;43A{GvlvhJ;N9@77zbP3BlwHF zI-Aais)PC~4>hY%y(pZk9%FQ*##0Z%v-(-%IY7}jZbs1fw2kJ}$j3xbWR0QJSb#<| z^7dH6rh$)1+hL=eNX}A(P=iOEMAklOxDzP+=Y628GZZ(iGdxS)B(lO7IP>!jatUs3 z{%TNOnL_60FT(lW0mIxxHM9GGve{7F^+Yavibxl&TVzY*lv;ZN$i|H~gVM=mexg=; zn6bhy(%JnNB__qkVdXw(Q&^I_xLW(=JklB;UJO__mpP1Hnb&wX8o>r?fVg61fGOfpIRYY9Nb!o5q1NGns1|e5;_E$TMIsi9?nk>VbmlBDvsfj&pzh zF|NLr$fw|Z8|SjH2eP$Aegnt-C5-fw37YGQlm@4AocpTbUWGJ|)Dvj{&NU&|)>jS& zkhhmf&08JkP3F#s-?*@@K|=JF?=#H#BiAo>dt;hN4abu_Vz>4 z%PoNQ4WR&}bOs<(9=r#|nt=Pjd@vEPs4SAPv%Fta9M(g57R(nD0q?AahAz?=^B=5= zvJT8miGb&>gobYNUM;-sB;YGBk0b)VMG1-AB;7HtW6LWJ#*qNXvggZX+QpkZkM`pa`c5FdfLHxb}= zKoA3DS+))01em`i0W%eDggph1iBG*E*jub1tST@FOE5QU=6 z1M4HhWkNlxraPFoCjwrn2*3z=7>TCgj0N-lIG~AcuNN63b*7?7JpsluWa`rnjbfC2 zrHQhw2binCSQj#*+CgqATCZc*O>aXOCDXR(dw zGU?vHMzr|f7!~5O5luv`kX;k4u7*HdLzD?oAG}uADrtMEm_)l7i2iY1iKz8*!MvI(JXYkJoe0cauoF8Tea#XEQyorB9p znPvw0@e^C)&*Z+#vEqispf+Gv#i6RzCQ+B!$doVT`>J?tN$5?04J6bgQ6jX=WI&H# zdrL6|VlrTlBtwzQiaILw-nM4G48-a<%BH5Gj>$`?7Fwyc1My`XrNPpIK;bX4Ezd&# z04)7XXrabC5&E0lfks%hRt4KM;(mfIiz<8(h?Q}ajl81L+##JTYAX<*$5Ek~i2ShTu<#sr{1=#; zK}T4A1?-;?iuOeZTjksZeZVaFFJ@M8CFULHMFLm_w=;SWawQ-g3&8NuaiWRXO75o@irc$&s5SO}#9>Cf(B)Mz?;zOb|(Gbz^*{!SRwn8JUfFocYivzBfOEF0v zY3OpznG?PmHF7tNH|-TpKL+lqI95xngghTaaV`-l>2cs#Yg!rvu_#GDxrm(a(JEaf94Y59tBSup0ud|kZ9o7G zg`$y)o?x(uwF5|q-%BtzTNp+qPvjy{8-|?d8Sn$S3p{BBPNz8c3v%aTYhJ3Y=0SV_ zm?PqV9R%1RQw?w49Vmt9ZpywF<5_ZX~)1S^8e#@YsUrB@P-l>(}PSvwK%FFP|=dy}SM zH6pEP1!g+}N>ZP5m443~Y3_CFhzdwR-#F9h`XySw5|M*07s40FsP9}pzfDGc@3J(T zjQYVf(*YEX{OHP?(Dx2?exe!GP?YhLD?32^JY+I{UCj9OGc(+CM1!CCQQR3A^G1L&J z1Hol3HbyoR(!9=fEg%QXm5Bh&grZ)tUXC+~)@%iH7Xd$On%GPz?%i1dleYwX7iT(M z%V4Xw5|Q36&smx$&)tfwj@;#Xl`tr7yQvHcUfV2m?4<2_a9pQxJ{o|?aF=65&ImQu z+1)J62(y}D=I448%*fsDKM2CDTFh%G)F0{RN^d9}h^rz$fM6X`Mt@hvfjBi}M5!s@ z4sc~YI4{Jx+RRwlfv&s(&W1QwABdN!W|3W>ABgkxyN=7GG|Uk>2Krwi&rV%5vVv(y z31g+%cn(z$vFZ8}dJJVF_qz|EMH&2f3q*5{`%fPfrnVv5Be`U=JGQgPA( z)C~7ye6YkOQ8ojyFBui|;u=Mv@L_i-He+QYC_e*sCJrSHN4PG;mim#$-7)uhXuL}! zs?~8Nnw*8;v1}89S4#%ID2U8;n># zm^23Bx&o-{WN`m+m>GAU-C}#Kw*k>FMA0rz?5}pWq65VlT$u>w)I>n#JOJKue`_gb zK4uY^FC_v-awNFUeJs_^=;VX>ej&g{cOtf%V6BluU>*wrI$?w7`W5G*1>fX;gBFb? zz!e|q9mQp$jZ9vLz0)G^yEk5gw3iy-)FJl+ZCkF!zU?UcAGmX0Cl}l9I5)<*&E(~S zFmjvw*JCENTp0lF2qF>^wV6DKbc$?umt>iwcjXa478ZbAE!)Qdw!_V-K|5E1y_OKQ z#N=c{VX2AicjY5+_J&;NNim$yurtNskQ~)U-|<;g{0+zkpAVP$^8J-;5^D~~!DI_& z{c6#HVkhON;OogqUDNjY?qv!T;l>`VaaCN0=2D{XvC*t-c-fc>6X%XNQ(LGG@*P5u z#UfzHIQ%^nB5YfPr+=Si_$KV-f%phZv(GKzD*Q!4w=pD?TvF!CTzuqOBGQ6pHZKBu zNu|A)DF^3Y!v7t`cBz5;Xkftm9dr*umiMJGo*HF^lm?@6oT-bYSWL#Cc~Qr`usTWl(9*9%VY@{ug95z zP5sBhrdFVfY!11hO=LVJZ5{Di@NIc>qXu4rXcf3ICVhGty=z zq%M8~A84oJP-2lHUTmMIqKn2K!Tz0c#id-L?Hg?;u^#p3G(;QIIoJkNXT+Rn;9Wx=Ukf_*46m6Su5INs`7y_!ui(>tzV}bp_oY~Uz(ZDWB*4v{O&Cz1~Wjn<_SIYD4!w;S zqBqOqE#0@Ya{x@&E>617t|VmH#lr1=jVM>hr~5nr2qb!Nqc7d(XLs=MgGS_({y$`3 z#fFpQ_>4{r3KFhK+!ezBKs|9Mm%NWUmQ?QZo@4QMGCkl>bXZaw0@ zbpKC<|M!3bY8cK#qt$m{tllh-KpC>OXLkJFAeQ}1FV0AA~?eW z;7i803%7KiM|Gt8ou?{i3OoR;pF|pai}0|EhoyifUFSC?hmUq}em4LP+lYfN-Tz1b zH=urjL=SEpHsi)oIPzTq{NM>BeyWyk|M}SuNdKB!^dWNi-4ke*#qXQo8>T`{(QAaK zFgGOL3WFs!)l6Ypm>sgWa+F}ofZ~4z~ zJjnsuE|qAUEzf8`$y`Bp&+9wHSw z3U3N1%IAJufi8)w2-+g~8&(f@k-B_ulkPJaky&7=6Zt|4ZX~7a7fSH(+pl!{|JNMl z_j-&ZKIGEF3({yU^T+d9zTbpJL~9(?=pxN^8) z18}atzzrn5K8xp7!JP{0*4=#-q0s5s|K^p~J&t;Bn)&^zmC{0TDa|09EuU-JL|HCgR$$0o375GJdB0p-9 z%+k2ySGs;<1;7;ac6AMUx?kF$`0*7O+*b}ae$tEE4T~vrq5ktALXeDyoqu>Za7nlS z?2&_HZyX}vD+T<6W^e4G$7JC-sB}ICgr#vkFB=+Qr*61l55K;R$sJX}=chfF72wC@ zYl>b6a>oL!Y&jhTi-(oHATOf+W;v<3H;IEEdPGa9c6JT`_X991l%)&7QYzg)a4E6< z6`KdQw+!SpA(k#+pTsRD-;=)$&V2>=F)30HtRoGC@p4X+{SFUU)h`wB>Z(uYEQ6aLfvtKoTB_;Fgc+;I?Cez~?pHn~_KT9;qA zEs;`<@cmj{ZGF;xgS?-}=i|t0jFcj;A(Ej@{}ei|r2v&bO%a}^W|g-~5NT(X^MJLO zT*5ei2ISAUOvLDt=Oy(7OorKrBQ>S#v1~En$#P!NvY7P5Wd!I-7U0=(C_xAz-REN? zCLNjVEdcBniqVxQ_Pq3e%XRJ~)$uRF&98&MY45wMPeoFhNZgrW?&1R^d@96Gp-H0Ji@ADo3W-+dW99Sa!W+G+29@v*HMHt(4 zfEa7bV`>HwWO_1;V_<{_=HN|!8= z)lI-VuQEK2xllP1fBvojfO<#NzF;7StVURfD!Np^hBu%-K)28c-(qc#ZSQK1A~ z(8*&DW5O}NOs6yC()y&_ZX?fBg#RRB4c<2z8CP_9YIv!+7EfFrIl_{JVu(DHh zwbKgW>oj>E^PdnOh|44eU6LdBI?(XG$2Vy?(g-JOz(d`R&zDaz;reawUSOw%l61jf zF6v$(TrMP=Q{*`imxd6!0O4zqY@NH1Pso>koT*?>DLk*eH6Xtmvgks>WNQ)S>|jPo*$>*` z5TT_S314Cognt3q!7D5iTO%BkZe&G4E?B*H~<-)CL~MU&3ng z2L50p1#SU#k3hQaJ(UjboYgOINW@Y^?e>^iM^_Aj|okK%+>=qy_JC$_J#v3BnDdE zNYX--HA8J#AzZtTg}m}1aEEc3G@uJrk*yMVN8xjPu4DJPj6GYA_Vg-TV51oiy3_^| zP0*z_TnM-0bKd~{Ln8gFiPU8oqTeBq-k6X`B%=M(L>fud>;T2yc@RAkgXqnJJDx~H zSp}*EL6$`iI$KW(^)>{`cmOCBFcV2cD-8<34HV4NLcQYwn5TgTU=kglloi6&w}O|% zsg?241eZxT+lFbv9T3vluJpsfit?qfNqbc;WFzyne&YmXe1nj!2atOA0j=eRV~`-S zBnFY4tm=XiL6kLJ?a$VuO1+JN77k$oEhGk7-cQm(l#P={EGEAq5xma<`VNxz%|wng zndBpINF<4l&#i%Ca*|C}6A)U53bZ{0>)ugdbpyFi$f67JzEE4n<>SG>2b9SnpDyq( zQvSo_KS5preoXcZ2WutBdqNgnwiPaUbU!?_cAQi4=$CLi{#&qCGtlPZ&gRf?3ao!| znQW&Ep!Ha|5R;nZm#ivIC0vR8m~dB4uMWtqLl#}aj@6ycxu3Wy5h!s z3ZLV1*Eyg2rp07gKS=xp>K~y5UEp`u96d&Uv1&LW50{C#;m2ei`k&rKAam0n!_w`4 z9G~01#e^pScx}Mz5%RU9N9lKb?*5NH9*f)%5T=A6Epn!EUpkUx$LC3}Fsin~RpBAlxE2%RsLkycL3|^W z(x^u1cl=rSk4fG+Q2ha%Uxy&gXVy*3JJi(l0B+Yv;C=??Oo%gW4+fZQwu)VZ@{h~J z-mtQz8?wf$2Qs6D-rj&R%&TmfMf&w|`Y5Hxgj?5n-9aA~s-i2o)N!}9nB2z}?Ex?s zhETeap+5qeEo1HhbPbq{6s#!gat0oZW@PM)GfEgnOjfax{tArWahWJ-SJy^k#cc3l z!)Cl)_tI*j|BuVS`e>UNlO>J8x)9_#A&V|F8soIBzWs9WuLY%j$ft{qit-H$0BdRcm%Y{USvs$~4gDCX1j|;+n#Y z`SKzdYeObofxh`0;BkB|SG4;6Mv`PaA^Sl8CRqfDIE8tA3gmx7R*=^fn3u&b7KcZn zn_^({61A}r=0CIbBzNyxaJ6f|SyPrI^gr8?==c-_xTAu-)0P_s>08FCe^FZ~O zjAA$K0XUz=Wdfy3pJQY36qgu$j(;PcW2WbE2V?L$sQICUsi!gd?@F+Cfc$yLG9@4; znG3)=3bI!_2#2oVdHJUI_k85NzfqrO+@{Yv5A4fAFkRZs$ijIs@m=|RZsr%0)el49 zdO(JR0(4n{qRS$)Oi~SViZ0U`DE~f{J9hx&CIR_yC>K0)k9-E!(;%-3S!zS#LnbC0 zrvkMBh)+WlUCGTyZG^R4j?Kg;z8$^eV5eRZqyb&Y;GO_uq`@YoDwwvdso*v=ZB0)y zu8K2C8%9h9O$OseFz&!*GE!^0ZEJpS1wK-0F>`MOAQMBF$vu>t2`{pcRb{z(30y5? z&nA=`5*?p{7+$m7ln!A)MZlQ5ytuoM+0>j)5)`)=hAb|g@?H{ z&M7^oJluHy!&>)y@P|3#`=Ikuu&&2dAo8$nut&P%Uxv0QTRvhE4gkR>O|_t;Y;6F> zG%%LoQp=dhY8f3yFL|M5E8z(&djoFAU;PvQh}OTD{7ap?!TJrC>STjcSk+YWt*WVi zt11Hhx1kSDyUEZJy%h65xQwuQ!o;L8Q~F|%FArHkyIHFtSRFtfflH%t_ONG?Z^NEB z25u9qPjpO9vu833)cLp)(iW_)4B#!0zrYnn?tg?dhrl4g4#DkcAo_=THec)6b*yI@ z^{5dWS~h|al;C6niP+);6uizLs$+m+PnjrA@{mY3CwaQU9iP7-$|_JTh}60bOAWy}eh#7P@qlt>$Xb(P~x$wrMCySF%B;)F7TX;&lXbKnSHP8OlRAV)6}E z+IZu^d@O|0l?>&3h?wx`5N|P<8$+mS4WfBJLNzCa#AIa$V0QucYlx*QjAlyvg3;`Z zFqX^Fb{fs14e3GkJSuL8_7+kfCYqpv4?Ddf7_!L}$>34K3d%Io- z_v!&0|0Ne|J784R}j`lNdEeGm`wtCdI z^eo`<31D@vW|TV-emD^x+8Pv_1i5*1M+tX)?jjtMrn4abCkUyHf~?XG8(3KngH;;j z+R3cMVv{YCXuu6XXt;R2hLtezMLXip47Kf4#$BHRcn7G%ahWXDu^>Wf!?E8)kY|Q0 z9s7ZmgM{=Jg1k6n(SNRLSiKKrHt7Yngrrz*>d-XrW(A=dBU=Di9`UNR1>{#3CQki{9P>uwMI14?79#YZw+ZYoLNHy)U@jhs z3Adg1{si-!D{Q;Nb%F`mZFA>7!hwI4sahG>OK=%jP?jpQFW401HU(JO@+T{PFObbB zzxJNflQjE^aBM#e^zosH4iOO0yJXD(IXh%&&&&25>k8>8TBTU|7qjkt0D|tmOXWE_ zolvTbXh_+znTSeP0@1dS=aAU4gLUM{RS$ShsrsIgJB5#8LQktWhtmS>4&m)UBk%Yj zSPvV&V~MB(rB~uIi7{EHNwVcHhBxtlg?A<~yuhR384sdW_f;s_LM0`yb{wt@*0zO< zd|PhWa2Y{v2R04)KZkaIuhX@&WUC_X2!12m?c~mW~{G=xb=L<}E~hWguL{ z60MygOv+AQ-Ii z81#CFKt2|-bjS@SQR>lE!zvf~dk1}~n^=k{zGoOYEp_^kwkNyHlyRa~D>!Ezupz-0^$XEdPr zQIZ{hwqki+f!7*@&LNgAq-=HYv*n-Z;Ew~PWse&%@r0ycfklU;zL09-oh`Kpn-7BJ zE)sfzRJn!OwG4zcxQsz`A&>{uh_=na-v-LQkZ)e>WXr3JaY{2A8WG2w|0UPVxw;4&eGvp~aezHs~mhnPIddkCFz>05a^f&EO#gibs zuR%z;nrhLbWWP=Ofux$F9|}YQW27OT zb?KErHA+MU-CXvdQMw;MmU?{w&~7e?K{wa9O*hwq>rvZdX915-0IS<{a|!=25w0bM zwg%nY1i5*1M+rCG`Irck=^zL{;WFuNk|`#a_W|o~kV`gCVkM>#UK)M~)P+FQ2~j%s zL>8>z2=*$FuMb%|f(2_#JFvQgd`HOAu_Rav+JiL$(>T2bf#5lhMu11vu z!Ju-Gi1|PKqu6W*YB!v}C^GTDOH$2&mnO!EgXJ+COlo~#1R z;xbm7kt6+%pIU}d<~erWCJ?^El{{!9)f`KgP`Qkq#p8oU%2{pM@-PRD4O%3WevNVz z6r(AKGBH7vS-@5aqTConsM0~Bv2GcMv^Rp>9hb3!E+ol2NSB!KNI-8eDAPlJIJ9MJ zIt@*Peu@BW*FM0`2kzAn8&1}Qttpm9JP+79K=y?&y5e*Cy#T;Mdrdu_<>&nZcCqUc zQm=4w-N!hhNNi;KG*zq}RNKc=Ss|4kG2rLZshlkb$=*cvD+>+VRQz&12{n@`#vN^wj@V|)nuCxyLW$rUj3v_k zS)PDF2>^<`20*En0Cbt1q;f=pN_7MLZ7G0T18j^>ovUwBbL6HOcm&PWg|azvOWcFp zyRQU9x5L(g-U^ExaT%NG!n_&x zgUJ}e6`!2o{O3-5Q8H8$(((Bvb4;E`_|hKW3An-}H9GWpy+osRzJABDL}O*#rh=XS zE#-p9%*TR$Z!HxS8n{Fg1}rUgG@%szLo)27ttIju;_nw>pT1^6OWw+x}^g1XRK5D z3v%hkdyy~d!foCv>8qs`!i^y1Vpm#$aXT)P?{>|VuAjTuCEa|$8I$fDfsX)TVhE-S zrTMUq(0Ll2_c$o8hWv2agv}&RkPDj0${d}q18!@G)$tbxCrxy4QeqVlr@+-`Dd+7N z5e`mBG&6ZI;b~!B^m?Fp1${>old#8&&fCy>*~`9`eIyJ<}?F&~{8_ zbpZA#aBkZ`S2!`A@JN}v7_f5yxj2N;6@R2$4S?e>(?<%=+V!;OO%P+4w)ao)$tZTg|*?- z7gDiK6b%@%@m9bhH-uI!5_$|bCKvVww>$_J;WBZe3yEJ&3uJGRa;*HXmtZ2ah!4WY6`2tNyQPRI%t0seRbay3Qrz4q$KvG5*C3im0bXJOeyn~8vI6_g@xH)LDx#bgL8 ze)w&Z&V=$BQwo8?+FqpQdL}ftE$AmAw*Lj(~d#m&suB+GDv)I*x2P zBwk0n_`qeDhbw7e$uEKoJfxee#^l;2&~Y&!*M%_E!CE@jDRY@ey5m2DF5wE{eyW14 zZF_>YD8$=N0XF~wlX_o}*LA}ndE4W3@9T2sC>-#n>(Iy=K60cZuX{a_2>2}*o{1pe z$VzBD7;05xpOcZJMu5jyFOjU$2;m!M-4Z=2SiaG-5ilLF7m+vt(Z54+vyOL#a6?u( zgZ=L^u^l`vlM;z0pHY)hFR!DPM!@hqJcHAv$Lw|#Imm4L9sk}Wa0{QLXL1Xt?U8MA z>)b26sqi>H_37UV;a->WV2V5g(r#P{<}5Wy_FxJln!RLrQ7kxfQhJ-TS5i>SpqKuU3*a7!3ug% zBx0GPYPy7)I>j}epgYv$sHUmZG%?V`ZwjoYb|m6cQvAo{XKH#J&SkhvtXp1);+P|^ zVfT}YMTK<7U#P*}$a}EkM`iE zbjAu~TqZ=ikQF^39g|^Qz^?{My^tTiARqP=(`Yec)&pEkBTkzIX+)x#NQ=qv1wah} zVQi>}E`+niBsjm?&X!G7wi*mAJM0dcDt2!16jJFK=bW37@)kVkQQ%+yVls#NKZO5N zTqYhyf42Ncoh7@df%W6lnSTQqpU%v3irv8AR!OlNq69;|nOogW%{4%2fXisswS!FB z*TL!oazSg)Pa)M>TP|e)JPFoj%Sx=l@zzq1k8pmeUf?Zx*_I@l0e;}-dz7-RXe7s? zb5CHcavSY1!;))hiPQCeC>)%i(7ILO5UNj~Z^6&;aM zm(%zdRGmY+-=y8&P&ZHRWOQ17w#}p}a{wP_3`x;+!h8y$S9i0?WT3D|9m`K*_G)Ti zK-rQS5gWx))}v7@Z9OI4Mh=t_sxwi|mW4B*|6vfq1k-7?0ic+oMuYI`W10{|4~9z9 zRNor{NAxi&GumwNdkj(a7K8j6u7pHG-Q3dxtbCC7C$p#*Z)xUxq~kkpq*6?-Y6kEz z5Ylc+(qqAGgmmoU1u&Yw37Aj71NaTdGz49v!_|~QqeY_Q7sY=}+GhcE6P!bEX?*E1 z=aCzO^@a2*iO!4?0zs<6ntP6R7l6Wz0dxe#_tC0>)I<&8D41_8_7|X)EBq+>F zYBYIyTLG0ZnLZLK?*{oPTqbFB$Zql=x=gtKl*L@%%Pu#o7LZV1g6!o$=8aHpauqh7 zF}VW|K<_<}kA^H=&X6O6`?yYYqmXVah35o3n5Bk^KE9$s4*z%$#EWBqU`?nQd{t0= zG#EAFjC#RW1vMLi(FhElC~D%MT_L6@xOps)lmwL)BC zFZXtjbkobl7wk;|ZVkc^TrHoO?KzBZLV+;r0LsjE`C)}AUhohdWZZD}%qM}c5Lbev z1@Co94|>(ymS4)J$V$*Y2=N*Z+b1laLOPZw;0droxLv-~PmzP5RlOz9uU%S;ub+}jb7Tc}e1wNlgtl`& zgSLvdVXtFc$&VgVZ>JTvQ}A{bFuKp)dQd~O1OK|<5B5@4W9Zj~3o9F92x}F18o#hb znF>n5a2RnuqKKwD=@GRC#OPZ7ZNMJ_(pIKmXd@X~)!Pe(b{ZlDLkn9T!q3w3)C4(N zhkp(5clH4BVHQ%!YYjjzTnYJ|BXci8l0PD(2cIl_{5-%TLAXBz(}e_Ui?l*XttO};;%e83}A3N3?LZl%^S|kvmsswlq+!=&HB0#)-I&xK_C~j_WTr5t+nM+hQgCz zExxGYFyLJZav0D8wij4MP_`wB!7#wM%`kvQ#)kp)G2PbFl1T6Wp>S}5LhCle0IJYo zz$xnJc~%`-fcYXj90pKZI1DfzI}D({DAkzv#MyG$8t9!#z3irwt=)7AF@?07uJOp0 z+X+1!m|&pjrmKV9bnfM7O(?0aQ^RgLAvwC@tZZq^vE6j43rwlSDe{JWY#m{Qw7*dt z6jKyvkap7vqDP;}RBpOB^e91NlCe8xp#SllA4h?lE zlLH@)fu-`>R5`aCmu;z%55^~CvgrT&qZJ5l6_IHj%^(y#3hoY?iJ(Fce;Ux)y{I*anaSQljJxQ(Xjuh z{@=g=T5AocEY|eOZvoN1-~Y*gC5Z+E9yP#t5a8`p_c+vPEEqOsjKDAD$jO0<1s?9EG~vbT_E+ehox_UBe&py6?vQMUj8&@ebbgLSKhA=ID^ z;wI`Cd{!OWAo5jS*dS6{*dQ8@suPV zVe3WZra^2AvegzWg6gWByOFefbfEbl1Z?N7KZ%Y{3N|F^3)D;yp2TIE39bHMy@__t zTMY7RA&V|l#UVOD`DZuqH-YkHGM`3j%R##1Kds>JGXXvYLi)fU995RM?Cnh{_ZV6> zsRu}otZ5E+u{6G&$dQY%~ zyIaP6M;3sA(FS*rEB0Z;Sts0uEm|@tc_~ecN%3=# zQWap*Ww=a^gv)sPIH|`-4&EbjpL^$e5PF4Jx(a-PfY|5Dm7uq~+;e){^m^akyTFQB zl==NmOa}>-y${j`*ib7Z&q!>58Bn15n&4Y`*oe+^N@|KmXi){Qrq^tW_FVMHjY)c2Nn~T{fnVIDKbLW-DJ0s4A5&)zhlA8e}YC3TP3Xjz=!``zXwuPFi4W^~kv=gKa z8gw5EnuA=5v?!W{*dq5@ZV;5F$%hhXE)*H=4fEd|&zWQ8UbOd1cSW2Vp<9M&0NfsC zHb@^z04Nk0YFg9Ob5>dn`|W)T#Gat0pF>SGcQY~+c+GJycikaa0f5WY@`q|LOA_`8%~wnIKI}Sk@=aq`WP`a+gI&!bC_9ES-Kpnq zHI@S6LmE&r7JZ z?*U*cZH+xarQL6VnFRhe8D=F_+Tj42O8cD!9=G?j%%&O#R@xmvnM(T$T(;7l34k_r z(vmCfd3#xD3xbj=?cY{Ia;4oQ+Yn@)~3gV&BwyHx_Jsg745Sxl}S#5wLI ztUZt0`*cYBhN#H8;X$tb1JVY~<_Z=x2g&0%f4KmH`FgQM zk*{-x1^G&t$=5=#AYTay^0k50aWXMqHvwSs^`d=2zV@-e%4M0aH^Z!?e9Z#T7wjN{e*w_V?^jEE>ofDN~+L4Gaet^;f0XukZym=3^mO-8Y$vm*PS#WP;Mv=YG-Ax3`$gTS$ z&USss28fl+uJUd-h44Z9E+8gv4}2En?TeVK)8F~b+h&U8gSN)!#PV6&8!nT*t1LFp z-qSKq!OC1=_U0>|&)UOq+3fwp0>wrwt#htEYyB^%oR8Z&aBY@?xR3O4+aEmqw#bK8 zO_0alW9#pCP}12u*>98MfW2$4f{h&0!&HVskf1UUf}cs(qgFw4Bt((Dzl{jebvmpt z9iaemJRVdrg)un7OmKx@L2!fwb?=nbF^S0@bc9k41o`tTT&5#5#>PEg^XGtu$Naha z%OHQo!e#P@o9FQNsJ*9UKCXD?&!>uK{+xl!=Fg87_)8#Q^QZDxLH@LYYqJ!@nf#dm z9)4S7krhwQA4K2;O77n_rcODg>kC? zY0Ud@jfHEc@Voa!kz(_A$kU+hklFa(B~-Ih`1yPiYT^zV23oH4#s3P`R0pmSHt-mv ziVe(_Ye6e=h~cn7PU7BXDjK<_q6OTOkVPiGH;U?6(dGbRD%wwQnT+fe#Iigq+FZpl zBd`BD$jAraG8q|Qd8`P3X_>buo*B7T@yy6WaKTP?YEx|m>kZ`vo{eeWM35+Cm|Uw3 zKYqLA9;=+WwjAow4t8}>ueL}zt1ZY+Qqh5Db*pTJ<}em4w=DZik#}_v5U}&f4$3{* z!EddkHo`Qo)pDJ^7mZ=8z>NVqz_?9vW$m*;b_lnD%9URDp9Ng5bb)J)O89VHT~O(Y z9m1Waa-}Z*KU0Y+aHV}4!I&%vnk_wlTjfS8ug`;tAms}i=(R@?YnveRzEG@F3n~tv zn97`cshvmk9yfy*rTB+{VB-f;yGELBY{qH+Zy`i!9tHsSw3hbdVBA`1v4b6JJ3 zWZiK%C|MJZ1SPA2wJM+B-yFrVWNik*G~v#7LCLzw2 zixB)w6W-G*aByNuk-cw^4brtHtT0V@fVe##)DBHA7GuIpaD`w&aD)U+cweidIYLvD znLjTAU~2voKLq)6!U87|_*+cPV*Y#ygvp<>M}z!1W3g#La%Xl^Jo9HPP$qw#h0Es8 z9Tqqw5U}}^uVCiSVYoI+L7d5-ia*-?Iq$6bW1H~7)~I|<*8y6h*@QQTv}wXeT11IT z+JtW(pWKA61<*9%Wq%5q@I;YDv^*}!{4Drmx&DwmZliEEp1 za!o}GxGN!xOq>S8O%q=4Sdftq!)2QAeL*ZQU`F1gSZ3t+ie+D^%JCp01MDFyla^UY z@yy6ufif9687|v|Pp~;q8OjSZ;V%KTOUN*}wvAG3!jDHyMqZ~+GosWg5hh~%u&~>cT3`ku~sdo4?Q=R(J9K!loc#>#FrFs_H!QOv> z$lVlKg}*&IJF5HgxBZ!^d$TQxT^b z0+8>+P&E2)fWB8ZozJ+4tmE+Sl9ec_pU7u88!+R_*VC}6z-dwsg1V2(zB8Keh})?k zt`nX_+%ic4ZyaiRc(g?ggK;;S#BdGj~)=Z|`0t+lr8An<*F=;jk?Dg`j<(M?X zgwMtjm{=Ab#+uP0-!i|n_jwR0IT4ZSj=!Wl{nSLM1sT$Hr?f-(Tdh=c2HHAT27p%K zS6X)qT-U&5gUgrdC`&xQ^`I3wZSQ>ndXOsT;V(~*6=Bi4HYj>L`Zi;r^PMUAAk6ur<>Ijlfrc1O9h9pFDpdJR8;pGUqa{Aby8-EG)wi_w zUI0|SAHgigU!Hy-O5;kmViN3b^gFdD~o8(R4>sj{Y0c=FBp72oocWd+LT8LCv&&jlaKK9-KfIYOi{3O~u4KV4p zQ`nYtwU81QA`K=cHyi=)mLR-@h69~U?sWUw8Q00O>`C_iI6`ZIfMl$O#(i&@LcMrL zAz_0Ph%{%Y4+O1B(8}<`2A<=dF~yky70>h1cEN6%yQ?&LBs=~WD7g6=QVYC?4op~V zO*sWqwgV?$;xA9Aji$`wosAgJe9xG+(xNxpd*?qQjyD;QmiRLzNkf)yw!lv(gK=RA z4x}eBE;E8+8WdZY$aCWJWiz6mHyJbPHjqR1z6yb5QQaE+<>?l^LEh}Kkd@T@L~`B) zyw5Eru~A28+%@=o92$PovYqddSooFvGva*7&`LkR&|b88^J+rg1R@6+>VmW7O+!Jd zEpnEDI;LYo#4rM{N)L?F>mVe&b%4HP_pY; zbZdLx4XH(h9K@f=8x1+kn`|CMnm4g*pW$#xbpmnt3XSIUoCp`yJ zuFQq&C|q0Qc?&%!9!_WlG%p44p9Y?jZ((2Cd)0p;PT48Yd?WsH^`NB(LCTf)Ag}|j zEwbx>Y5q(P89r$tt$r}&(LaNioGqu~dtGy^(`$5h1#yE$F~!0%k$=m*(h(Hn3u!fKdton@r)YYr2=2Q%$Q3e4Wz0 z;N1?SnpvsSkg5}xf*C=qk}^wIn=F^oEY43kJs~gxSK&(Y6v>W%Mq7)vaGyUMrObx4 z+TNr8Mx5uslN%pmE>PPoAmvJbxaPsNPN#q77ZA&M<^=e8I#~Bc_g=I`mRST}Ff+dH zXuJ#DCbKQM9MmVJM%GT$VEmXG?&#Z*3_%zy50}N^NQS`JFd6tx@iRRII^XIqgUJd0 zw!>s;IW5fpH|Re9KjuFR;vNg1!~9?Kp2nHwtv?W^3_b_f7WvxZ&Yu5)7R`Tasph|H zt%7t1#lMteXFy>0#HEtz?5AP3-r;c=>MzPNz2? zsSRV_k( z+CYxj`?l#Av6~MENAkNt@3E8jt&>jePzEjHb$geQ6@bkZew{lFy0%Ebxp$;_eTxdE zg=M7g*pkLsCjLGNb@WsnoEBQDIs#5m(!9|pkSyEeaVs$z_=JSlj0r5`x`^kJ`RU#g zTNIHMLFlXvZv{AL-zr~P?N+mc0>z^_dRVek6$NTy9VBS3j0JrsOwE-ca9!-t)f=um z;MyXCtVG&Yn*<|MGzlhXRY*tMUF<*n$^{8h)aGrF$8zsr4TTA^Ni|lthG~K^1)vDhno|Ri;d3eV|OVYhR66&U=?iLBGVC4*xV7CNif(7*ZKn()l zB6Y0tu;`j~0C%G(bj4})%`LmVz5j@q)R>8O=u-UU>DSum&E`wb#@JU6UnOQ*++Fs5 zV~X$GMEqR*K1Xf7&4LEmyKK&tBcK;c^_{PzZ$P~U>B8k(Q;K1Rd^7ae zv-fUht+8kF^{fvFm%wVR=*?QeG2!f!SUUGXmeuslPo~UX3jI7CQffUKj0yEa^A|wh zE48r-UbroSfyuh_fncw1Goa{dX`TO{E8zbohKR`#P%$M33xWwAnpIs#6-ESkzW z(@KM(nkepS^jCgBq3Ks>kEAX#slfoWnTXySTWp*usW zt+8`#DgoNb8;$C}MS_5mYOHN!%UeCo0wX?J1&urOalT#}St|1oftIq~FAD~mg|E!{ zGl3$XcT1p{S@cI74^9vi+k=v*9zj+i&8+^gr9hUV=JP}P5qLD6v~1^?sbn7^kusq` z`rr>EypC|9o1ejZSI8}b1cTnNGRoD#tI}DVL{mn3Ki*Q9$q#1FrYs z!l3azehq)rSqF(vaG5^V;YyHPVov-!O0xOvAYT=a#McP*Y={>eHx@fZeaD>*pw0brQK~$vQchDR3`!dn*JI^A5 z3h$2Yz%o3@s%9A$L`AcE0?Y8&a3zG2yrzNT13P$5bF24Gd;bagOFRZ;?eT{dn1GGS2%cPh3V`Kb)Alb1;wuSM zhtCO~!4uwInKXAX+bLEWV!<7Vzfcq$SIG*qVwh@ zS#$vOFT|;a=P(%7s*ctwGnKW=s@iMs8JS(6$V_FOTSB{yr`w71tz}1Sh#8&V0&Itr zXiqSAUKtJWTH!Ig0XD^A10D{ixC5AD>sS>NYgDVquU16G#0!pNagC*F!SIt3DMi)CfU1mw+XRE z!3_3ubun0q@o^Aj$UdkJa(TbT|qEY>>1_t6*Vx7JJ zhfuFZ*^rO%m#1g1vNrBx8{Bof)Wtmz*~!FnWrhMfC?HQ-@ZJs6s9=61x5C$}6yvd0 zM#24>4doqs7f&#m2ZlGwUz8`)>AJ^Xv{?!Q-WD`KhL}hOkv5SHK$!%&G8(G$q+n#p zG?D!+A+md{T?haFB3lq>Bijj)MQpESY>UcCtEKNrQ^o6)_MPuwjXd~dP{nnxqywOT zW8zy>d7aB>D+Ck2l`Y*c)Qrk?Q2ZRo-%3_35K1WFI}q?`Y(o&vQNp*_YY34psprAg zJC_fzDmL&gc*>xRb;53S_c>;KGt%Az|0Ol?4O1xuq=$6AEqB#Hov`AY?R@~0O11f{ zvs1wS4BlLM46e)1qw6`i7Q>aNrz)lWH4c6(mVdqqS`Mq>d3%qJNZBDgL=+th{HK(q zd>&j);KG!dg|TF4-56OJH})1ai3c!=%gRoRD)+NV;@2R11FVzP_%rRgChPmEYS_7%ie5wU+KyA%8dJ;O z8$;wP8udN?^7MhB12?`8Y4wuh)U&uN?R`G*(FMSl#b2JjB2hfs*Na;^PIHTEXYaoQ ze+}{1E1u1*;<;hh(?2;*rp4W6@7>G$&T!(#DxSM{0lz|?;O1DD;~Wf-U%+La+x9zY zJxKj>J#`p814^b&^qk&SW#p7e|20s(6+BtGkQqx&11m6NpMdK>xJ+X{#ESJs`b%Re z1@Jricma}4Dv?-T1sA0;!Sb0EIAiZ~A(1CMLqjq*$tK(jBFa3UCp>;bGS|w|v+$$S z-8|vZ9g_L3@Z^s`!5r8W%}3k9b3e5CLTL<`qf9O8=KA&cZTo7bSSPIefjN6|C8e0| zfz(MR{EQNUIbN_=;B`p}n^ITV`xO;^=O6Io%BL75YGUjCKJQ)M)kj}x3(aS0brzda z?`TTFP9_ubkNvgw;%q<|&8@&-dtZPsdPBWDt6>ZUjA8JZ7ld)0g*q1@jPA){AfbXV zR>%oP`4()92~}Hg6^`;PvdKi5q1~J2IayZsLVN!M=9~aeE_s?!rY4$`%e#$oAkv)X z+?s4oLX=lX@zXG;7Z!9uRd-y4&FLj4j5!P~4fDG(YsLrm-lLN5OaxEz@RujlM048m zZp{fqCefVU$>t=bPHmdgAM2bTd<0ivbNb7S4O$==+SACaoz{%M?ENj6Q~Vi(eFOgT zgqmp1r@Z$u1tJj1r#SK|F-S5dchCg@vruDW*zO9K)YR7CDlPGdpI>A|i?Z6VI^F2rps5*eFa5~>3qz5mw zXlXtcfW)lsL-zg%f=qu7QQ3_@yygMy7)ZIY1FkEp1d08Mg@0)8GFrMo;B1i?0U=}& zw{;BAI|8Y(@~#HM%^lYPXBJ5pgr)AbD>n^1qmAAX37LU?kEE;G{+{B`ou6We5sdfGris zOhB7)FBlk|BDXd(w@|i5K+h~(g>!3~96F?xly*%=C9P~VwYB%|Refg_cya=Nc|uJz zd;;&b%?L#5v6M|uuB54SoM$v zy&uU1@SRu9cixvv;7S|e`2UqdhpP*8-eL6&w|6;&R2T_{bj_22ym!M=zXG6-WHLB6 zLnD8Or2j8StM4RcVWodH8FwE5t71@5COhc3Yd<0ExPPY{jz1W^Kzt?B;(NL6c}B=Y zB#0Q6=7bUY;_MMxZH-v}zamr+WFl0lx{1(sX^v$2+$wNt!JHrD88xRj7~ZH77}Ip6 z>z)#ec3}e^rtvWNuT=%xP0&r42f&d@%6vY>FfpRT>Y=`;zA6q_sc@Aqnxf$zVZ$-hi zRt&cH$&lYcYup!T4L3YGq}H5<>*9;pyYFM6EZW+{n;9;n`HBiyCk5cR;o# zbjs!UGYb)PA0hO9vSseuc+WNijBs1>mf7fxPZ)xa)lWCY_tSIX_o zxe|Yvs`V}+S^Pyr^1CI$5Jn@}xMnzn`9pdCf`FxK$jfi#dv1CArw&l|*W!dxy^CFE z=F6DKk;8SsD(~{c>1wro45Yak{7D;VbHJn$8u-sa90hi+d<55N1u~Trfo1l1*eD4^ z0~`hyf!n2hg2p+}7=6;a4q@+*$H3SjQ}lm~{@;cFcZD0|2bw8RssqM?mnxu&{+H2z zAODz*1K=aM8t&UKq5X3c%u?Y+-VWIZVyzxdHtat896t2())xIu8O2E|zt^-oa0_)oQzQqA@eTe)Ot}PNESV&l+Q%0}6KaI5| zW%OJ3r?JCR)au}f_7CXMav!|hWl!U=1VBQi&>^p}yMaaEwX;)dy!TOPckN3e23dJRgN4 zS9k>70kz>)%TCYJHznO%uDg9#C>gMN8%ZOTUXPX!EGWe}dHrn{9y+(@H@=8MA-@sS^N05Tl5l>YxXUS+7+7|GAVUd1D4_-VauRhj5a0#% zi8xUMgc3>^1cIHUDWxKIlBTp)$>+dD-j>5_a%)O+gem8^H=y?CN)Fi3ZZ_Tx(!9M_n8XNZUqQPMe=EuE^@umS8>EqU@;Nl)@|1-9 z+=4wVI-qCK>2H=}nMDoL@(p{dg+rjBIW)k`)7Zl{j5V5ReWNp)f-;;o<>rIB}MEA~=_+U8t; zCmN6@+C=nk%_d?r8m7IbIn)@Ba<{bOXRxQSlOW3Pmeh3(rB0*Jemw}!w+dy2;o(Pn-ocGq#rfgU}JT#{mU@k-) zGsiKp`d6a;lTRlHMRIhV@OPRPd$zlfLR^}gf}m$(ALV*B&&qd_u4j8qrE*iHhC#~x zp?&~w+X5GAe^Lq=>ys|hh??gzLi?l++68sh2OoD4YfRv6uXPDO0m0G0V*y}nsCrv&~T^sd1Gat3B8@uPD6cn-CM(4 zuXl)2)H_!x>J7K2-f5|NT{pDQqAPbp%q(j@C-AB4otAA+KS&4g*DE{`ahEz`+ibV{Sm)Wa*-i} zz_2pyqeb`Y$33x1G~+gExbC-onIPzZ;>7@yxS6d)IzyB?Vef8XC7cW z;sWNRXC3MQQ<0uyecFU)Rw(&cmGJmYjw-j$wbxyuaAox7Dz6hHE$bF zFdazdXNEUboM7_F^LR`R+^Xt9aj%g7nRe66=ZNE`Gc9@(D^@y50Z*;9OAdTFF#zL z#xIm@MZ^~OMFba7`yw{%*=O;=y{#XV57a`w9MSF`ezm0X0FfK*9wvb8?x9>M-otSn z7{`0K9#mW!nr%rB9Jc~CG{h1Mju+<|V4Q_T5E~5p~qgRnQbAM_oj<8H6( z2DI%@f>E~uX^jXkve*&}5AU22n$EO7$4}Dw!xBx&j~iYtQk!eR<6MsM+gbPnqzb6= zc{R%JVzWH*C$c3T$u-!e7Ix}_5+l3>KS|lbMIzkz5Uj)G8MxTO=@8mOp&LG;**^f5 zaS1D8E;7$u_rUdhc@Lb|P3T<;Ys0Mto(av*iI-BD0|KG1w#r)v)wBSWmuGpAa>S*PU_g469>8r&}nS&9HHRER$4r zf?-~wvSCLdg@ahG$u*rbEqnti8~hK3O~y}5P6jO6m4+=+!+3ozuAO0%P3To`*d838?H1o8(P3EFZ8MdD`c~uqT4J zDTrGsUP$ydgQp}e?Y+ei5Bi=(ax*UHF2r2P*yAnS0c|Brbhjoj8n9vAn7~*A2+d7= z3@75cV}nqrzyK>OTnMombD`-e{KVuXz)rZFt2^%)V2OpJ0{&p|u?GUA$1E_69EW_S zF@(e=X3^djJ${S$R}U4xS)SU5C%;a#%(!1$_&9WZObeIeC-uoc>@>`kkU^Ua{Ii9- zAhe4@f8uAJ)B+4`BwkGg@%GeEXt&`GSlG3DM(FsD0Xh{w^Q48tZGw*>i1x;y!A26tLjI&Qga_7w!0(d^`lML$0*{>ThMsdkG8?N zqaHmuD&~3ofu?*2Dvq2S{Sc~SdIEnoAUJl|%J{-F@^R^DmrH!BlTnY|%KihexKXsg zxSv_L6FLsk;$g8Qi!bRFSlmc0ep@5dz(#7|;a6}PGt=~N5O6V6_)5A`d^|hcyvhYMKJa$4w zGmDN1@eofaG#+Zk!!*Ggn5by00pq6LMut6*NiQ*zT1M*`{7wtAuEY^ziuIiDGwH3` zxO@)rmM1MWPs$Kcq^UPD(e@Tft7tZaW11FWF-@HsaGdaBLp27($`%1$3A+uW;=#tO zVBqbPh8wVvk3WUc)8y#!#i56yFl@S^Vy)qd;?g`eXg&TQCA&(%!M?>%b zVXDZD7MSP@77l`n1yu1>Wfim8Zsb;|c$+HDj~1HfTNZu>71$xg8Y+I0+mX$(k}?-Y zXBjqT;b~W6{fjae973juMb#m?$gsoGTnRr6nL(6!bV*WC9YFj>Da6BlCm7$$@C-cW z9iw#R7M?VAOo{sH`PG!|W*g8cdNPpCozKi`cs`x}L-rXYrzxGvR9i>{r%fka%Z7y0 zC65>j1RQECT|fw(!Q2Uma|ZKtAF88c)8*pKE+csFyNaa`k*|Sp&R}X>$K&nvZMxR5 z-&mNQ*H7_RgLfBD&WFfLpzsC|-9Xi{JgIM?_qVoC!E^?*71T0G#W}Ykb@HKzbEsb| zy$WYN2SUo>K|ppJ_ty=km3tDadZ7PLLM)d_50VIA=W`QKurQ zQJVd9)ETej+BM+&m$t<5w0C45=a$jFQ4J_*l2;AFA&0_g%2f~$4 zy?(xY&Ngg2pWS(Bif8$Z1MD{g!;3p($!iMpXq0-pPms#T)3-nwRSmx&QH$-P|np_qDUn_Jy7HP z^dzB@{PZkPP4v@qt}g>fc|SdeUC(s*oF#G1PY=278S~r%$fEq3!f^MD-2;d#!!JO& zXKbP+w430)_zEfzEW@S)d>P&h$~|Kq`?SfV=Pg@IJj?J+#naVVF(}x{XKarFL(S=@ z$N4kdtw26s)oVRZnF|qN|?gfpe~Uma7C^_1uuEG|5%ZPbxuI zJv9e%>hF`TaMd%+MEmoih?9p8OYWSyxpPE zJcCWLa4&4gT#DO0c3H~pmgoZ1V8a!l63boDs{nP2PooF1o^$aj5fUsskX4!XuyDUouCubRPKFh|Mx<|d*Q7KuL3P{be2U8RzXW2~Y8bQ8{i-sB^ zYtF{MJGG`C@xbJX88(uKTTM%mh0&WbLRW()@8D;iP*{2{k%On;P?kX!F*C=(+G-6P z^Q{zSbdHqDYDAXGr})LOY5a0o3+Z<22Va0lx6G97vTy*>UBkp0EvH0(z&Mt^l_3tu zF?}zxo9RE8l71rdztf*74>DKAM?>c#nJe(0kSq2UK~oBx+D?FDi~I;ZjH8Q2rHeY+{#isGcD&weT&-e?{e) zaVqC`PY%DC%J+fl1!{$~tfbs4ok{dnIPq$TUKTz9xg6+|&iI+9UtVG676Z<+ePs;0 z;ll{AyD|ld+Fdc_Aa5I5tj4(WA@gMf ztn-W<17y94IzAo@EJEY=dFY%kmmCT>9Kfp;I26C7dJ8w0NL;+Wz=fRKx{J%vmJo|f zt-&anhf(YCAOS{#2VwWID|`jkIau<`k}R+4QM__tmEaEx54#QPzYvtZ#k8J!o8zL@Gm~dda-cyk}9++jkaSNDEcG9qPuZ*seq|I7hKdW_>q6 zT`l11%m%OH8?2C^_Zh?G{d>Zps67%EehjVSAt)!5_(wy_q37+K9nM1SeRE~7_cl^L z2#(pI?Y*@(B|R*Zk>R~+FZbT&Kto(S>%aHj7Mbvu6-t^TNjHi7S(SKJu=h6nAVx&R z($qw{0dIGXzkOx2HT#_ujrUj?Yt6uXSB<9N(g6 zTPXL3Gmv+9As5V}hw>R}gr_?dR{a?4^|S$l5WMeb(#iEJEkZVuV zD;9QvqVtim{2dgXwrXn-&sJ@4DC?he@=hGaR&5i?@&`oU6v{e~{umm&8Hg^@*VJw^ zjdxj?buhhLZ;7v})wzQW)^bo+D8<*+UI!Hy4-Z~f^P|psoFw-*WfPv&!s+3T8+F55 zK*LWB2bP9k*>fU^s8jvx2JY z4}4(&OZR&KyoRRvQcD<8VVYts11A zX>{hW8G4W^w`9GtLZ&(|e6ymt9ou1q9}y=)f)O##vbOX<-O4K36hm&<-XO_<ZLWQr<%y?z-#^_ z9B1&hv0koB=EHGWMZNUNvtDlZIBimgnRe66dH-P+#TK9ra+9p2gC;nTX^^07*d}h4 zBln|h4u*ZEa{ZEj|Kk3xgd$n`c~aR7y@$=>-~o42s2Uc1wj#ogEVziPMzTFAL#>(# z(eLFdo=1yD_%=43S^Yp~sgfSyCxzz&`n6hBh>Xj%efx)v*T3hp3L_pq^H09;o?B(T7VWbImmuUilDeI4ts_YG8A5 zJ}_@f?1n~TfscE3T5bgjkjY%LCtj5Y3T3vYm;9Y|HKUYk@Smm%J2 ztLn#}`yjepo-u9Q@oEc2Y7Wwk%j?ErW2CXZLEz)CS;5dh}uL189WsKGvALzYlk0!@WPaSsseQ*3zgq|DsIyxDSVLC!{8O zg4-Y^KOugLT#Zv05c&%-oyY3jt`#%)*p`Sci+*whhSeIKgJ}1Bua0)=hp{DMH%dNY zS3`8R^c^}7FDOR;#l=E7)skkDg|5x6Sh&c2j&r!E-XIT06^u0tdSo^BqMIYK!+pG4 zj(oCk{Da4xGx*8XMKTf0o3S&QXHtDFd>jI&ufr|fhaYT-1GWoMF_{MH)N!O{gUSbm zQ67?7B};JqJg(z%r720wQ(B3<2{PbOLO%Oyn&*8Ywj4c@{nZl{di%X|^Hh7PcbZD*B@l^6Eb5YxJuo`nrYkc;pMc z4c2JFT#ZhJ1vQ!wRst63Ow*Ca?06g}Qdn5M0B~9Hq*Ba^k3iw;EJ0T6!Zn;+ns{OX zYW3ll<_o3vV02C$Vf?-LcMC!LPQtzN*!ZoXDlMafP@8!%j2G5F!`)9EnDsY+Tjil&5b=ygjG4eX)DoKJm^HJYq{dS+>q{=g zT?fV|ayfo+wvPAA#PJTL=Gd*c9`i5@@b)t*PcRPu?cFb{FrPv&VFx1cS0oe8ho2{d{%av_>!h!k$a7%cI+4e%VVxJ)wWP-1XB^>!fjVjxuz zNVNrZSc;uTjKH}*#4mx~m~;hI^>MBP9%VS~w#K;jQx}PN!xQtdWoLk){)S(YQwp4~5O8CxFnWj=N;x{Hw;P-9VR#|?Pd<0%r0r%bb{rFtF;QLLNzG@dZV@7;ju@gY;05xA8Z&!i6(qs>T-)Kd+9cNjE|ueP z2mbyB`TN9ap2mo8VklJo5}9-!UjH({ZZ-+;NQ+G@k!4`uC>?&^2RiRBkot_J0HZaucP$)x9vRXlfYpHVz_ZeyU35!|_*X25JH_dB=WDv&$3k!Q50 z2G8x>o`!4ul}j@dcteWPa4w{;B3v0}jxu_g5`3cOvuremnL_#kp^#|gXfm$l>fhtK6tuhmS7!m)Y zV%LJI`Yh!?1Jx4LLh*^Xjap~GlXjCYSXg6*wA$R~{^~a}tay#NKYRC0vM{s_~}uN82BjVEH z*@i@J@Q9G@4!Z0#t9M(7$}#|!yN|08=7wXHV7}52!U@KHllPNjx|7tuh4QGe{y=BD zP^Q>b)nZ<4u&e60f)=0KNs~Vv!xu{7jTnx70o#7TzZ;I}Fo`2Dd=UJ>FyliRZ7}r5 zY3#n(F1Q~q@NI~9{^7239{_V}Z$U1;zLhtb-VYv85H(MZ1SL2je=Nc~C$nPK2Nimr z)LEb&0aYZ=L9JK0#1CMLqIW}MsVoK)Ls0xu3`M>CJG|y(s8Bl$QI}($vKf)bzCg9S zmrFsp;l}|3);CM5JRE*XZRGG{p$c&L@tsl}enemN!;e(aVEEz0IQ(#89DY#D4L>T0 z+3>?jaroh+IQ(!@9DYR1K5wTVezbvJH~i=WYK3GOPKO`1dd=w@{=OAo9KxYB$J(>8 zDiJQi{r-%9{YE`6`b*r-WOKD18bP%1?08kS5zC zbQJzwRe7%k$~TMG4m3v|$8KimGFL5r&vW5@FugS}GIEEX&uF@TAl`N}TSe|fQaxUB z5ko>*t#lu==F6Pb=Ax7@hUj~;{fclXtF3Ku_PYXe0!yk85HRZez{)ZTj3ZuQ#@!BT z94M?&0I)$G!SxcYrCu;}E(G7j!14>+`eqek9!;1+Au>0}H@Gg5_c~UjmQSIlgr8C> zl?7ldk^58GLvd8{Wkg~m@g#yzWCnimFrI7{S2!u_jT|eHESTnbh1CD7-1|N6rW+Wa z!<b?1BonL5xfX#BB~&0w!+`4}poL!p-5h zcwN5F3J>puJsz~EUWaRKM_7`swf)Mjw6z6#qvRtmHvYtA7~PZalu%*k+1(a0yE;V{ z0Ocy|bTxw&7L^su#LDW0Hc`k|)?ZbCl@*I9Do{~Ty+FNO2s|YR@mM5Q)Fk#$RDM>} z8((8Su&&0muEud4m!)R!p{lFrJ zX5vh&T;8)QZVmHu2^9)^=mWG6D@abEGiQfgsX67c#V$EKx!#NGI8vb2Jr2UB-vt&J<#(3v>V5V&Sooj5UnTR`Pr^oA&ff>%7>!ZTe)}8V@5VPH@ zCNIhbc#vni_eEcF-uJi+r7xzuryhKG*;KIKGE1lye;Kt9j+2ZVLmVqjhqgVB<5-aO z*!!!vEI8rKj8I1ar8$<7FcSpqDMaB64XF0hxJxt7M9M7u67W^B9{dg9uaa$`4uC4s zS8G2p)M5+e6)A>*d&Rc-bgHIXlDM7V?DiO7 zO_y_bQDH6^pQ~_lP>0W8r@}7XgYy8c{t;Hu5$A9$B;rcsBQ$ItR{&hr6KUgrrqYdI zIB;n|eF}xU0FQ<5REenKXK7$BUX^X1+yTIS{D?YXV(uz{mxJ-Tc!gA3R{XH--ny zna$Ugc3HMZ4JtF`22E-ln0Han*K)Y=+FDo!zy|pP*}5#?onyRJ5<$7Y2f=bV!Q!~! zJQp(hNMbY?m!`(yJ5Y%2p-%E4vBj+6+fYAw3A_*Y@DabvvNFxZkud9IEP`h2|Enhs{?*Ubf>W;q~B_ZwI^6`@*Ng$NK{s@i;&9 zvoFl2_7g-blWfz|*ut&ut3iK-xnGj`4l|^NvA6|NZl>Cn0=E{rp&|FudVe~oUL>oo z!ZD8@L!n#~zth4-PqwbNWFFzFRjpYW zp|_w~X8)FS&vzr<_D@oEJE%jMtw0J;1tRf_pn^k%_)K%#l8Co$$?du=dCrGHrn!jQ5P>tO z=Lh?g-|If*JVbAlJVYN4jc%{<2i>b|H=CTX;2iip*sJ_8%7lyb4f-3*rdutP9nnG{ z-P`i7LE61RzYJ7dJjlN{uWwtF%Q%ze1HTx;nh_NX_T}<{0k{qNT?znC{|Z@Y0F`t# z)XfLnUTFtoZ^C`Z54KnOBTS;~bCqS)F1K|$M>?V{4s~wl57 zKbWCBFZTyv?z~)+Iiz@AZXl?*czAGL&i3hPyi+{H6pr+Y=SHp!6n~)VmP6foQ20a* zD7hBLV+uqGu<*wUn*8~yG5K$s0HAa_inr1;JYjNag zWX?Qk3PuE;U*M|q3Xp>J?TZoif>cb}ftmu!xx0VM`Ojoet1|V z!|TCveCE-#*a5 zoOv0cOQ1>OfBW*)8OiI2w;n22d*x&2v%s6&u3D;Ln(?Sc+;|K|K)I2rM_?3*h>bD? zCH6ja*%`2l>Ypf0yO2^1( zXmIZbWi4P?^8KJxSa8IN5bB~=+pA5-4PIC0NQvsA2is-Jbs)2ka?@9qzpPN=H8OX+%u$C+XaG9inHb@O1 z;^I^2j3-L z#G%Oo)58&4E2yyB!R!A%1>vK_Xtsw4{RyAI-N84stXpK0Y5Lp3fzUqz8l}PhB+Hf~ z-kzOq5%O@%%Ujk>Eo+4cH@e$uy1utix<{}}jKbq_8Opi+nN(OXx+8?H47^RL_mb$! z0B`m4MtVjK%BOOkBVod9_t*1dv?dj_nGif zmL8O}K$7kah)Yz7XZf8g|8dh26YUPX)`^5;l~TPhqr_^!5a`hc^>P0#^ZFz zcAObxnrSb+abIDHj`KI&Cvp~Y(s|w<3VWS5?q@(bAKYGG2pc(UV=0*5v6`!3ekZ|E zbOl8*WSdtWv@rJYvTG@pww81ks7kzVPNOe09-ox~o{uqBxp+JHs66I5wlb*=*yTKz zUMv$$!)qR+vF};z$39l`sA*~*l}mkJZ!nMFo&b)Eud6AI#$&9}`H@_c>to?Yj;G^o+}5%TUt1YWfU>*~z zYq*%44eAw@Xb37UD@2-F==uvF&3p41duV5{K(;+@pbpq$iqpqvyBBkf4B zliLnFi?l`!<5{GApi1;ClE)4~S)qr?)BE8$BnRd>B!aQh$#Y1*nC3#Flg}X4UI7&U ziewAwrO%@-KCfQFtH-QIImj2RYT`E+5?J~L^{G;sppGbJj)e}PKu?)n3P!2q>Tfgs zZGhkTGQWG}6l?O7*{@)f$~OJofZt`3YS>a4d?;a@GAmT6r}2vq*5mgg*j8D7mCOY1 zY48@v`pYF$&u+N2g*CgJg8Pn16`*zl6_bB}YPga`%)&Y)1xW??xn3yWYYtcIpJ)Ui@wl@Uc3AvIu?xAa_ZG0uxMK>Y6xM4)r!ah(Bj zpb+Q9E=*^6R=D!GqJ$PNKO3`NP|lS{qDZPM52|slJd#jJt~`EJO?2fk#1bC@Deuao z=_;nf<1R^DbLByjEGC`67!3nsavi8SN_7Xd1=LcZw~n_`#CR5~2IA9KQ|e4mrzu5`9X&xU zl=n=6b6);stlPnv?NRN~m9IlxJN&RT>tMCxqXX?*Lp9E4|H|)%KmQ9(J$GV1_onc4 zNR7_y)u^Er;-n#@&&9v?q`YuFsq3*-;RjOVnk+&r>CN&LC&$l4@@*LKTXkpH2$(wv zIC&Nk3A+J15sx=~k(~p;_+I|F1(V>HBX|6U5yGTR_O{a$ecP%18uq@|wgsS2BmP3f zMl4gOh4{{gjg2SU*m%<@_sY}LX23KHWpd;gpkwNp_u9`nWbv$EZ0z4$L9x2A@jMe= zTcM=8D&Zl@r&Nh&Rg8_l9mP@HgC=qt@CoA~edWp9#?Tt%F3VT~?@hqEmn0$!;+qrVgI zi|?%9_xyG2w^C(R$?M?V4c>emQ>F5&@WYxMPsMaBMI~-LRS7t~RL4_pEcG66G2vK> z68NNqnHY?xP}KZetj?iU7&rT3^eC4+jopI84&@)!#SW#(df%ZWN~Cru)Z#jnBvev| zGEg!p_ zR;UX*l)8##hw_zTdBV8*m%c;s*p4QXp7$NLFr9Cx%YbtJz3u>I9ZKAQ*--9J7(cH- zo-kej3JdYzxjtnJ1=*+EY+~$FTEHUq9o%S*%bo;|kG1|}x8+zaZ^ZW}%oNw3c=iyo zeSbo>|8tI?vX6Gz(a^#gU0rul`zziayOZ`xu{*g9lzGhDpbrtD~H_!@M^k=jsjy)2 zj}SH_@1td^YdQ*%8}eEt2UFdc6oWAqpqMNIRr70R9lNzeaFxk$YtRCb4#=*Gz{NTR z$uq5?OYp$t@5Jhmn|-_qgqwY&eM5?~j|rfb=v3a&!;GUy?}39@2j(D_V3^Js$5nR2 zvxrWfar7pNf7oX<6zAYs$Z2*Vk>T-C`UxVgK*Xh&^)7@|Vzbcr)SqE`HX$_>+Qn$9 z-I~$kNXxnP^ANsGq7MPbkw1a$9{aAF{9}Kq)xSal_a39F_}IS%gd0b01?9$(9(#q! zq~~qW`oeMK@tcX~IPwBe_Sk3J-S9-ef9!8mARqh3Kwsm*g<_S$azA<(u9ICLjK9kYenQn5~3EATjlqc*R_ z=TenH&aP{LahmQ|O{qAiX}W6CVxdpR`>c|TWwE>w*@X@P9}56uC2(#g=pl;$sWL?_ z1thWKK6@*ZWyd`Ul$!}AillbjRO34CBvewz9al~4xF0wBc#7M1+^1|~I(&qaxYlu# z>pE`F&4nzU-oy0X_ykV|#67`#KrL3ssRt~fLW1{xfh*_KF>gDu?6@a_a!;_wQX~J; z^IlXupWsgw&nNgtP_UD)1{E4`7L@xZxZ3wr%qO@RC_KU7xhJ?cuJKnc$C((P(%ndb zPbxojhLKhR$H$`0;zV$&-N+_)*X}J3W{T^$Jv%!O_vt%svi+ZP>bStPtg$d~>Npa{ zxxT$JB+;qk9KAjE>){`KzrG|@X_8aN*1+MMAS7-C6_;W|r)-Pb%*Gq$%K|O1wFtwR&ZBZ8pAoqH@_oFXo)~=9R_K>D9P#iuiK%mEK*_1crtuR~Lqet4 zWSt>jzYz)@Jw(>(#Wes17u@m1#b@Af1NemB@QtCN(lbU~b7U`|xtF_2+rGOCKSf?$ z3H9>BaW-M*RUal~^WFDvfXyv`w58`!;OAzmOvrni)2^gQqEc~J=XWlVkoWlTSm8@j+4$5=s*~>2i4@=MW zA@7%-yVpovdfw9%FMe8r{Vmj`=WsK;N(G&8X=xO)3U8)$!kYtz8)qSwo*e}KaKXomoE>3M&JTq^V&y|;C5UNh8`~W6C3yR-^z?aG@ycazxZ7ysrr}7lZR4pCweTzyX5An{CoIaDwiG#jh^L! z0DYIDZ^G|<`L};%8Uy7RG#HxWd z`U=2B!qs5Rh7KHa0QIv{8$s3D#n%5>Q0r2}IIDXD@oj;K$$U`PDK!h!BcK+FPas$% z{P!5FKT5+Z;pM|xug5K%34s%8qjlJaA6@q2Ri#$!oL@3RKV#{yJ(xQbdmCaf1mJVm z$8_a%<9zE|K-^S9Y?3@T6J14@&jw0@{OA@ii&PnjGa}s>) zD1pC~;_p(}53s+tT}hW8zrr&_f!Y3iPuHrS4AHadAU_IDvi#sxpI^d3tFA9rP6kZ< zPh1Y}4h84@s;zoHG9hTyEBT(t{w<+ZuhTCSdKwYV_rzqggs0)qsyD35rlFGW2_}qJ zi-5t$vNvGj^Sf`=y*y8$p;g}p!+fiLTHVxEov-h{WeI*{p|;+XMCqS%a^Z9II-j#I$v^d2>nfaF z%!Y__a?x@xDLT2h50rCqk*eVTbaGKi;LuJkQen=?MQUu#LpZtk7`82wRHSoqk?|+z zA#`%l&~CV^g*CgB3zR3hd>%c5p zf?d&i@K{&0Gt>$etpl@Y3AUomF_p6_7wv^a;m3h&xz4#oA~$$*pKLdS_3V78#te2veU>g~u#Nua9dYTo0F=#O&5lI` z?|nwGT!Y%FSk7P@{1ePz4SSe%7wLJ|DxNdge4yMK)Ptaq5uCx^Zoo1qPua_S3#ipX zhMT^YQi{{p6HJEF*Y}~G9hdiP@k9czA|AQIDePpkE`%^xdv=*d&laA|dK64y$qxSJ zt7nV%P0bPubu*J*Eq>EGq*seG_VZrpSmFv$&ap%+Ma(;vxJR*cEb+2Z^lI@LsD-l7 zB!Y2D6jsiWlkkdqq21?R3wJ_bIjW~zafqIjDCB;tUJWxxt6G@Z`IuIwq4#bJD1EENnb|6V2)_FJyb{+h;{@2s zPyp)Lfq0}>pVEm;CsO}biZ2{FfH7af@QTIwrQC3OC^U8*#!dLkTkpbRNK1CZw9tj? zC&6V7BH_gPHH>ygksf$31J~a?@2_{_`YY^U_XVFqcZD)TyQFp|UL2i-N2dVg_=PNc z8u0OTvgp{n+fV~psq^G zL~%TI2>fxw@sd5_9d?>wS+9e zn#oepr!f=A!lv+Y1*U;=B7Xo#ks`Sj)B;OriG|StvL5$QDi4B*H8K2VN02-4yajT% zp)%IHypIkZgHg}7Kc;0}D^xu{XKo}8|C zn~(UHR98<><)9YGZ)lKOS<>fQ7+pIWc=)BM0h91;BqZFySiXit*CpOgMijS$Cedf{ z_t|Jzp#qhyC${2P=Y(%@JBNbhvfXZgxL=cTZs*QhbXTyywZ7QzZ-p}IZ3~6g$b*NW zYF-z@l!1S}E$j?aTB8!m*wg)ihMbEq*I14C)iMOR@rAVM91c~>XH~A7&bm0@*6Tyn z`trI5t{2NbzR}wat-e zZ3BdQ0dV~pxb>I}L403;VsbsGB}(-M^_NnYf~u3jyZs1v>*aGGUu)a%xZ9X)LA;ay z0+f^g3>4*83z19YmK51&d3sD<3a zPi}Zn69d=UhKV@hFNfVR{qn}6N_~vDb)YE6?`Y&2zN>}R`p5KB9!F$m;-RDFR75oS zgB~&cpaYZ;@^fs}OmS!!vQp ze9)~_ay72o;d-Ow_eu+$f~&3aAr4zep*mok2-Xi;Bjr_%c(Y0-5Up>;@tUd8F<4MP&6}Z)RqI()K2@dqqj$kXvor*+AFwi604fH&F2sB{C^OkDhK(7lR zZlL!9C^yinUCZ6oB7*l$QY;60TNKNIUfpVJx%iE@#)dt|!t}fjiswM@UZC7SZz?FZ zV~G61fZuun`v%og1#`RNCs4~I73ao&^|Q1_#HFK&2OEr&c8^YHi_Y;~9#%B@*TceK zjK>UdMN$dkw<-wXUx|!DO`2voAL^|+-@Y+({#h_Cf*~<^1k~f8;^Or^g8>yA-N>ZL zW88)@r|2d6QJOQ%oIIy&o+{(#XLhTy{-BP|W`Xh%^56o3AH)&nY8Z1kHlLqF_934g zLh(0WE6_np*_SLTk*h%005xALP%0#-M1Z zMQ>M5ir%iA6un)&kzyyutm?r)L1ziqfbxC8~mecUMf80PL#rdo5?UMg`;ULwQssB-b{?xS#0 z-E@6xq0EV%-Guq|5|~#)Q%nj#Jr61_9(1v-W@m=)NAvCeT>Ifut#_4X{e7y6?Z*LC z#rEUo>QvRp%nRC&;nS1a4^H(xCeJDRrz!1XH?R*XTsM#i37%lGou@v}&au?cFlMP1 zev*LvpBZqoGFot##K zSav7yIyGdRqtvo#($f!hVh82%Zg6M&IdclibvD}X2s{ATvl9S$rKW} zcRSR$LjWCX`K-7Pl*@`fh8^VZEU!@U%!<8=XI9icF35`g2K0lYlx382fm|l3Ap1IJ zp60^crora|H>~+!u=0&I-ZK`WA?b(a##O-K(CxaBR9H|635koBPVGjVu;=<3gEU+= z<0IgftO=rlyb(`wkBD_cOSBgnV&$-j#q>V9IQBr#BVpGAtyYRXP%X@jW9qN*2Bp{o zO$Ft8pz)?A`x>b6JOS;PKZ}G0kG(n^%0AAua{X(&@Fe7D zd+3uJ;Z6`=g#+w4M8)JaPPeJR9xalIq?7^Wu7}hy8Oa!+3OkDB>NW)1eUe#^ee^AT?+BC`%># zS{Ob#`iiDR!=FV;&hS!Dae2gmhceu$@`zljdOrGNpeo};uc|$$xV-Rxs`7{-RP{pi z>{dQI?+H|WsH$fCpQ_$9L?KnZ7#$O++8L-ir9Q2i|Nl^hm*9{k#fI2mp}Z75uQe_E z4a`1J0{1&OgOUoOHLC8|wUoTD3RHYE#(!^r5+gg7PIIMr+dWlMKYyI<72^_5A z*1FqP|6V1yt$y@LnOLs&7W(CCXFres@b51RVgEm^xu`??rMt5}6$I<&39Xmz&h}qY zv?SZ!0_i*3`-5`F0`{azB-#FuO3?NX)OK&3w;e|oOrFbG`pmfHw8*3hIzV$?1dC)O z?xK}J^DIP@Lbu^DnFuDIeypmXD@}#*;rSTx4)MgH5O{cAF$A)(Nb>RgdsBUjgVegA zt(hlmN99_#b0yXsm7xOSaOK=~9J$af`#g2aPB#{G%I@~862Yl^R#f2jtddZ+XEje9 zvdcAP!X2x0OElD{V#jJNve)^VPU6~*6}fH%o5&3Y4`jO$tY;r?Nnp6Ox-GMqBUr-R z2(}W;k6;P$BiL%DBL`*%!?t=SvkGz8)(eyywlyyG2!1HXyJT9*oY8Q@d z`T-h@$~ZflTZ$hb|G5~+zwW(V*bE6*$wmGzKR+q|ry<_lGu;=Zd!|Nb1O+lKO7KiX z;H`cX$X0paPq+$tKy$ZQBcHn)EUB#)W)(!=K}s$Y76ayTH>WWv=I%G3;^N^!?%I2a ztV8(X6u&#Wj6g`X$=7^>)EIPi9IDSmH`r%1IA9upAvZ$ ziF;O|lkBCE^eI;DEN|(BO3~7LK*7V(6)q10OGnoW23+V`jLRWnLf2x$F(%o`5Zx`z zDvXu{$u19)&Cc-|bS0>`cz8v!)bGZ5co&cvgyPvMvzS4zX$H-KV2Nz2gVWKLRwy4C z^k%d^kTKZz)D|?^`PEq zeA^)T)c6Qybj^)$u~vjukW6in}`d0_?9oe_L8;BIY1& z(xDBDdDi_s+yIrD7x2(taWR}16y^EnD{h5d`@(EQ=>GbiP}csixsj*RLaBo~8NLGO zaroDBgS_ZNW@3`+l>T;bvWQdF{a#IUN>70~(iPhB?XkS&N>>h}apxaGNbc#Fa61X@ z$SS3N0d;zF#xaxgL9G@Ft&*BRuf_ESIR#XSw8HOGrgk^g z?hnuJK(&LxsB#WfFt^%+LNfxu1{tP;bWiUE>-B};Q}PF#dnJ1PPGWnn-~WTAM6chw za2=PI&4l1oT?P)B!@OQs;wXmk@|X&|eye$t!D!HesvZJ`WhVSygX<-do+6^t`ila1 zbA_K~@G_a(J2?fqy2cV%cKc4BVe>l%>M%z1na+zHJJO?8p4&*XiEAqoFSRQ!} z2G7I)sn_*v5*mTmCtQ=IU!|b`f)Sx(9weXi-Jt2#Hk3i&W}%ZCc_}=^#$m1My0#;u z6KHwy9gq1>0$74b8z*+PW+VSxt7ZSFg*Q^W4tt7Ybm;I%OQ?)7ey z33mnRT6bD_A|mLn;A?rdj!QCZN%!d-cqVw+KC%5Eo(VoT;awF@S4IKbyqPDuPAOfv! z|FqDtKyH=%)gtE?Qp9zQgWyd>>Ui1I(?yI?bc_gJ#Jz&smGeRB-hkKbT^ zi)RIms&~j4G^%Hruul(4E`XAGx)&CiR5oe~zJG3*)K+zu8E_p0tUj^QXshatW2-to znV%WnRMD!|^y#BjebwVo0anPV#-ZlOq`7zroijn?TpPURVaIBo(VWXXpCei}xpS;s z@&S`)!v~?zHMs);aZT0jVQJvhw+qg3w0FMQ_V zccrE#s7Oihj%eT;A~Nkl-b8IsHz>u*OA+j7w!)DUe>Y6w>-6K1LQHmok$DltHiK#m z3WrAl*dV{-Ixhd1Q1JRaeXT;_S+K_Q7CD7O)#T1C)8H%6{OF0?RfL;4G9Xgd0xC!i4>PotJ_bY%S7Jnl;zf@=fD2f)Oor$zIN zEn4&35?PU4&hE?ZX`6+}?uZuc&0wyDe5v#W1vNgG&)pNKp~31Jg88sQj<P?RjLG(B6-tgrlJ14?MXJQJf~IZwLG9ee zn@DTmnNL2~Ibig*v1#j<%+CyGe;#JdVX6A$Iba;+anQa()|htFOz=R9V!?c1;6%s5 zxZ$r15|jbVYNJMQlnD3U*LHanqguIj|HS&9h`ggBunMTD!< zRZXuhy+ftoMbX_AB%*FrH#dYlMsv5T8mA|tLh;P-pa#y#%)#K<<)DrquMwJ zEN5Jmlvgz_=CaD*0e4fV8k&rpF6_Q{qs{vp^GI`6zCLBr^rcRkego7dP2U8QCi}3< zrf~JCIL2@ZABtyBbT)*|me;XbX%EGkln(!6gRZnt)`a)KYWGmAhBnNijFtLOB+Q}= zv8zH!GbHIAian~tvx0}h&!SA^GT^nq5@%7y<3n**GCwn%SMgAMZa6*^lRQozioM1$ z&FqEf>ir=rt9k=aJ{!W@)z&p&)VP!tayh8Wl%mJ?p-R!?`&v-Yz?s!!rXimiz6|%k ziXwVZF!H-n17}uiLAjY#A~={?IUr|N1jePvG#+YZwbXbkEtIdqg_%@N zU}i-KE$7T?v*{?H<==!)#%cpzN&}$SKn_!^MtSowrH*j6}7(AS=)oKlWZf12YD9o%3NLv$lk`pXXe+!NWV-wuo&=egewAYwY;{fb+e)#iUZWJ7>T`MpP4yF|VJtQ53LjJr zY^oOnS0rTFF>xT{!l44)jxtN7O^s#0&GGVxTg9DW6lql2~G96srm1k z>THv#ZK3=gKDiI?hfVbfy_1{jp18&+&Y=I@RC`2dpx)RJRmiq*1QZlYLsM`q;@wSf z5iG}Ig9_pXm?JIvAq!uwQjvzk}i zSo@RA^8$f+<+9bvj}0=no0XN=Ah$G|J9wrx$o`J{`PhU8`EipNQNcsjoRL^|u0cNB zqS)-d;lbJ=P^+<+Hr7-;ZDIYZGDFuxm3)mKZ0!Oz4pG?Y z2Q?3r`+UiL27kapsT28B1^D?A!rYOcR9Nu&5<=+Y#3!3%Cwr`QJXZQww9xcdJ;gQL zdmtC?3-eCs=QBvZ5qIO&>^!bM1G)NFltc67h`{@JsPbFo*p`U?JIZerg|1sd{m?yI`VJi!lKoMpQKUJwFU1T=PyZQ6d{7LzBHdj+eF`lucRc)` ziro1|;mjQ#tK%E(sUYOdJjuX`De2DLw8QO=S%A3w-c)f?g@JB^JZ!o9DA+CkU?09Y zBEN?b{L_Q6g)*L7-Iw4#?!&)sb@QUnsYt)i^UsDteKN5bl(=@Po8Ci!$)ZHoL;QIJ zKZn@|X%>{Nn{xvOL96GIyXny1a$(oo&aMsuS`3^rYJXP({ zw?gen{nJ9-@qcaYr^2Bqh(0&5G;jQ@LpXHI${L6m)Rwm$8dx8In{GJ|(Ip9caWmu+ ze7L=Cy9kxcke=?MH!iYHosQ+<=FEnS*}R#ZJL$&laC}8xZU+B7{3om}+c|{e(-Y1i zR9xV!!SVX}v)~*;z4XnSY1bSnK~W6B$c}$+vrzGO*0q_T9Y{c4A7oj^tJEw@I5$uX zfi3Rb&RAXEezH#{ocUypO>cHRy#`RvE=28+8K6$Rj?_$0?}6gH7ggmkT-v#aacXOc zoQ#}*#7xV(5qUB$y%&%%xe1IPAc_yKgE}#v6t}l#D8;Ju9jMhpp$#$=*X}d*UReQ^ zJtcp_w#0J)N$mgnO#KUHQ0fVQW!Fl`^UA3IS&5;`o+ows=vVi8Pk|qLkTd%7oc2*J zvfGqW)OfDa{tofu`*8%)J4F%B1q5lAWdqWmZnC+M&3d#{zCj#L59{wr{KjN4ey0MzM81b)BED{Ocmcl@l@5L!@rxx| z{O$m>RL<0EK6w-^mQqXRA>_8}Tsfin(qgCjSa&o5uPm>SXRVrhwAOjFkt1-TV6^cb zvJfW|PDh=qd@`XDF!^Lcv+HTAJDK2hrJhXiD%{D0M=V8mGT}A5awik8wvJ4+(>4#K z^R&%iBv2yPA{&0QTiwKbemK1`Dql<{fpPc%7S98qx+`@Ts8^I?3-UQAd?67+%cT(4 zlIM=DU1=%Ty9w$}Os}r$c=n;*4O-fuE>MbRAI5-+%ODd;Is1@42`hIe)#C&(VhB6` zz)wHouSn)0%lX0^|JqrY^+@_aSXC-(!E|3@{0PYu$!4_99^Bl6-;lr6!oR>I%zce< z7pSE&`w#;Di;NDz-PlSh?{@>eBL}j2HMWGdAr&`}VHNVpCsZN#RYuPUZstvV4Q4!U z1ZRox>%PcX36xxS&OySy?sz@Pbq6{6gO&OZ=b2r$O07$0?w|-zzC}-(cvtGns$e7% zE<&E~z`yHNF2zhmor4YzRgVkf-QMS*P<8kjXSWo}cnIe}H%qGn=#mCRvTb0{^;B1y zSK%g(MHP~kL;R3P&x@==ye;7mi15?Zxi>OGzmqpWzeac1AP#%-AbTQ2?EuLj`*35~ zXg5N-Nk81U3ec@?uk$ul_B$fJmxAlC`8nJq3dU@egS8QHmx?@o6Q7&fm>zaAiwkJw zO_A>rV6Xzlhk*D`Hr{0*|H;P4@B+R(?sf$)H)a_%42m2%n6;J%G2D(I^`P4FScF$I z+9YIf+cgJsZq^Yh7~iY!4H;_rxM_5We299m%#s}fhzyIoc?)l& z1dQ(>8535cGj5>{0yfA-T)XAct_@txn1y&$qDOD0Am`vtkjteMbjzhlV1E$B0XYXJ zFfKQmMw^4vqtj>}PqXUp+Ov@c+Qei_Wiyg3)w7}Q9M>JtzHWpW$iuR-2D24~#{TZ`o|L!JqU zTB`HhEQ`I+$D(4EODl`zv|@ngxJ?1}9L3Vb0QVX*GJHC2tXR&o*5@fNghWx=|@{9f{M#u2K23fc3&<7)){LobqtTx!Wm(g0q?2~ z9>ywX2DopjdPNblNJc~^Ln858s(%7KU%zj>-&A{W_2h4<)*hm7>860(w^SF37vi2d z{))vn8#9rf&xm4q*NXPjgxGTV$YQyR_KoLYqEIYV&G0=wR*R#i#a2awP2H}QTp^7T zGTvHFd_3DCllr7DH&aJ+vwX09jWGhO$!6xR?{>Q z`nFo36n$I$3@R?w4Eq1_ZRHam!n=L)0lnM&3(@Wkr|I-<)d7_AZPnTIU2b7??Nz`h z`L^n1EMG&CeOrx!Dz+a!v*@$x9jLJSjv(2$)n3aP;!2Wn&bO7f=)ZkiWoAtIfHU(i z@SB!CEG^U=|85LLN)ld6epLp{O$)VV>5HH-wUuk*vVE%f#YwkZmZf>A_vr&Es_ZB|uDoyU<0Id)Ong)jLDOU|PDoW%} z+|E8zwh1t)8vf-@`cgj?+OpA?A-D-jO60f(SaC9BHk#jz=`!FB&YDjH1IK0Vow7nQ z8ai`Wh~Z)DVRng}2Mx6?KF`Tbg<^+-H#XZ@F)a&|?+8D+1jUj8ou* zyTLph&IjW)*cFpoK`jThShk*00p3k;|EOYrM?4WLD}7P?5}~d z{f6=d33N=2t^!<7;8w_1gH&W{xwJ5YnOhry_dGr}{NDQt@n(>tUw|(XZuWS=E~WtG zeaUcU=(k{wM0znP2Q>{;Ts-I_oD^|-81%>tueTi{Ty;y!IEf|I4VzjXpO0*W;^#(E zF?YLGK;07IE>|K1uKDm1Eh3M;hl5Z`ZII`1y+8}aL$5GXGsga^ma=dLK*G5kOGO>B zfCy)s{yN(3TTR^}mi2?75qk58KYt`|ehsLRN-YQVic<4IEdjMy`hxQEA#|X%w#DzF z{1b?G^5Z}``8z>Tel{`}Gz+#UoIE6mO7D-7W&f?D!QadF?sSp7G$tnjKY8WTO=w0`)4WxV&q6 z+oQC#F1TF|Ju1Ce-Kls)J~fS>dN(tMjn|iucdz++#B9@r*K_A;f_%-FFt@H<3Fcq( zC4_6&-07TaItq|l@S5*Q_wp9`n(r&1+-tsf*yFQ^z`YNvS#(tMy<+L8=ETwdP2X{b zeb~bEymJ*#?=1HL<@}z#2@1mr`aOHyfbV(%b5!%0g6{@m7pP^DigS)?8jRunAah?f zasRq+c=#%A3%LqgW_KFGfFNW1;(L6B?F?yGVJ9oa3Oi3JR@hCT7HEa_@*7Q0t!)ph z4pv&HgO%3lV5OywWs)j2Un_8GY*2}vB35Fjh?V%zir}E%3}J=lpR2%IEcU0sOy`xb z(OBLlEAWjwB=%2!~oEl0Dbinckd!0Qyv3Vg(UtibzC@1ZL20y!SIhE@ufSeP;K zD%I8!yepw2CXGRjQEhDuGoVh=;}9NJrZ+_QLSBupfEnZ6^DtKx++YfVU3*vL>_sRn z#y-YEG^cCT7(P*7sRqyT8uU>tm(T1zyF7%CF+;>2R&)ttKYS zEL6R?>`dVJSd2e9bNq2iICO?9y4%ilp^VE6T?u*l@PVZ9$DN4ZDEa>%W8VQ@Me)78 zXE!(H5|RKn^b&dvgx-4#Jv0>oLAro+5k)2Rrhs&$h=@`}ssbV)U<|#eC<;;(!44wD z2LJb*nc2NJzD*>ab&d`@K@Q+O} zqWFhFp5nG%OIML&2>(dcme}E7{xMId$1!3QaWp!+h)+af^m zr}#%r-6XAbi1I#=@_PJZ863iM4|Hhk>5du12N~AIAonf7nwD|Hz2Sw1F6IhV$>W zxm08qIXN|zOjoadg(F&@rqON@u}o`@;_Vf6PyKhM=<(dVID>GM#o^m!;} zeY~a%q~agJy6(`e6nW@Yiad0Cis|G_RQ>Sl+(7r z8)}Sa81oN?DgN;g%oCH2~HqUo^TOCC&^tIlNCxWhgsG48N0BBuC<(eI?~ zf8>9Kt!>lT|KJ~gYKUoj!#_HUfgHNW81|qkr{N#ZY2}x7h~c!e45xfWjS&k*WGra@ z!C%wmKjt4pp&}CiR&tNfd@WH^0w8B-nNDKB$VHFp0d@u&F5)ru;Q zdpd;6{aR+>Y*K$^$*~U458*9#toJP z@eiXoQX4>fx1K5^8u&*yr9${e5yL+W-ol~)3@>__4fn(~y8-4D z{|JV-{NoRZu}lE1VE$pC8j5@Q;kBOdE*dhJP&7=6WJKtba^5!+FuU zTzDSNyGe|P^Kla6;e0h>ihmgWmC(of$28XGpUjG<}m|Fi>rmw@E47@X4++zNbE?8dwuooEqv0h`h=n(54f@l8G z3n;}urXr^K$1x53+$iYvkM#m({&5nqG|Grm{3Bu^mj{*mu~yHNf85h0T`BeY(M;1} z%RpOo*ykk19d?<-xWj&gnBpHsKTKzW^$)SZomSc4POEHir)3*ylu=9ZkBq5qCsu~I z6Dvd9i8D8Z=Y86dQ2vocr)GEERQx0BA}%I(;1&{N{xKLa(}9h(Q&K%yWX$0Xyi?HJ zfqz9Tor-C@nRQ^rKTBmy)Rce=+l8kA^hW!CH&Gzt*Qz&Mu!z>Rk3{q>!^KayTwk+Q0$}H+&7-tqhgk4&t))?PDYejvDKQHaeJkyyENO6EY&D{ zMvTnWBGYG_(WlVbM`@4Fw*>G(wIa1vy^aJxoC7Xh{;5jgjjas4D_G6N-v}K0r(nPy?RB z;NDXN%LJ4WN64w7N~=8Fk8Y(1XpBxjC0dGrzPQ2=&|qn%{N`^!rHk?dxGTDiZ|e{) zTd37w0vfgwctt=BDx1ENfvzoWzy!1;a7QRgi@a(*L-n=8TwC3NH!_5pfEqVg5=20a zVn=NNZGK$x;{~ub$WIZ_%K6Y8{JNg9Hrkd1T+}p641#I zgMdOSn1C8+5A8){>WH~)kO}B7&`=NHGNLkVAch+PI$E0>hU_9IkDtdTc>(OmDlR+| zQ0GmK@qAuFVmzO>LQD}*qrVyYd9Jn)eV)seKF{S!pXYMcKTV8O1T`P*2(B-L?Lio^4F_-d{Mp1(^Y z1{$pGW;TB-0%{O(SQd|*T66(dEKircpsxt1LG01CKpbn%XBZPuhA9I25X=xzh8P06 zU)xAQZY}}c0DvN(CEhXw)LdC}7rBA^*l-A=3w zaVJ)WxD#h?Xdf9zLJ83;VDDp)R(1bat8&B z>c9&S!^Uzw9%t5p^#YhioYi6EjIYHS6VS_IjR|PPI<~e=WB!AH@_#GfKhySxfHn{V zU9{Ar0`kn2=LLQM7p3jz*CB?}M`SqVE2_6xFd}0?6VTJT{+I_0gNjT5LO_dYTWU&x zXZxtTCJov1WAh=E(*P!&8;q*ZQF9Sxprao%9sR+cqs#J|4yVJv>(HmT#UXU`2c#b( zgObHE_C>vgeVJCXwNLGp+Df+Cs{V?skFu)45G`L7Vr?PPFVGh?6)L`#3Zs{}T<5II zbriY%OGC42D4n&pz^6@+fDqM{bRu zAvEm(bp}_BuC9tuPKWfhos81p#S94FhJU+h3}XI`92kP&2 zt-T(tLzrDFW|`b>hlzADqRfh|`lE5XhN-)+?Q3F$`{R#dq=FWi{%FW;C!MbY7c`#OWH zo6DX?Of9Y&@C_bE*3w7tX18oEy9me;8l!DVhYi|WHdCi3;V~jpy``b#w)rNm-_CBu~ZyHMA=%b=*pZLW6>xi#QZ4DQ`quuN_lafAldP~As)xF6TIBDbS;dK?}f zn%!j!prKY*gQb~rryQGQl2UZ_q;BIIIz)+o6gQZzMr~m?zSSbHqSV6dKRVr9)=!Oh}s&(53~Wa_*!XkrnVK}o1(Ty5lbfn zdWhQY457BzZKU>=8GHj&A`IVpgWHKOpjulEwGD>2)OI1ncwZMg<=w8rqBX0MQx4# zCFtk5T1@nrB`AGn2}++?0_)?YFd!AR4c2v8fl_2vpcI)Ec#7#n`m+9SY8$Chu{t!= zc7havnZa6#F*7)dn4z}DdK{kWMoxZPio?txYzJ2YQ`?e=rBh*TH#26SsI5UXU`tc) zzs?oQ17A<*D{5;HrL-+j(tyC2+A>U0+lOF=+A_pY+j80lKb&`|?K%JywJr9Zp|->H zCAFV{cdkl)Ol_YALQ&f_h$(9OlEzNfVR*`Gf@f+Q@jm03+Ll91Q`-+UFwH1vYTHi0 zOl?OYmPQ$IirQ{uLriU#X!T5~ZK^J*g~!a1QwzvN#U1vfaU_)5 z&eQI_=DMk+o#vM4@F0TU{Ye`Z){iS-i19t~Tb>Ml3rPD@jH?t0`sI8f{ zO^=D3@t#;?YI{+vF}3yWW^1id{_ZWe*h?}LyQnr-%`@8)XjSa^z1(_6lv%MA zLpQa5&vbz$_H;4A6IClQa#@SaWn~z8K4a9X6QrUuwv-D5mOA^fa4}$wpdHO-)1l`Kj+!U z#IvWi#U%({ejcgQQ)20hHsFKNjfrQTj#Ptf zMkzAA@f6ePs&@FlIr`5UbxVhaqfe9~FvVFXF{U`j5HlRzSZ@F)@&1QY2U8qh8dm~y z^iqgn7pNY(GNU+(qZ`C9wlsD52Cf($`ksWo;^+nut!;r@@01Lgqcco#^oL-Eqcg;C z^f+x}C315)`g#BqM=$<~;ppbdI>o>{lf*6N=tF=|9DOZfile`wFSWHg#Qq1tGe?h1 zXFPNCM8q^lPt(AYMj`Y+y`=z|hJVbbMjZnR`A=_qv@lb8UP>1-ZZcQto{grjP7`0a zuYMsh?yG-EjQeV#!-k$4{VLi{o~x6@2KQHGgZrzp!TptOq)|pKMb9&)y8Txf;{K}) zasSQS&^|Jbgwpfc+Py}un~I(fLP6Blhcy!8zIy~Q(|3)v22wrYGTdoWGrZUURY}|1^5vvGWH8SAEhN~Hb4dLqsf{|oyB{i z`)GO4*%^94!BO;PlEpoYAtLt1D51iNZ>IdY8a#E3E@Xh*55R*XO%x)Km5dTop| z!>SM}k8+|%?NzcUYk-L?#D2r==C=`Jw>$iDl0S;y$+UU%HCc$%|pJX*DdwX(p`tBsBfgi z-s?@1&j7FJwLzHy3Fti1228Kl0(XRlYeQbOo}pOX*j!t+fj2UQnqC_>SQ139jbc&L z(|6e$BtNFtCy<|_*8@N0HZh=w=yl{-HRiy0@as(mpNeWkXS%bKTZ%8Cb12qLAx56nzEe@#-PE|prPn>MpUK^#Bf8en`v{GxUDDm*uf@wMe)tg zx$sO`&P$9b%L9oqWhr*n&}*ZgfQ`j@u9g&irYlOH>59^4y2AQ+Zwp98uY+}6dZHAW zo+w48C!Qj{h^8I>Z+bmUqn_2Fq1WBvxS}W%CB_uxZNv;kG1gPyWaQ*^QXHlz7X{4} z#r}f(!gOsnGm4_GwV|)*wL#3$wm^$>y~i-7*9=qi`XQL1*9?z?kc@?(0P{3T;~d+`Ls6urKov3GSCp0Zr< zOs}s9p6PYOIk=%-udbl4%^Es1uQ!ze1cMa7?GQ_&j5xIfK9vpe5_lG^o+-z^p-b8T z1&ExQAQu&P*!7YJci2BA#vL~QSDY_**oKIyC2*t9|0A=R? zFsYt_Qa#*(YkbXB!5w%AV)$2T+HPhYSaEDKaho0!Ib)YtV~)LBtTD&FB-TFA*8YQI z$LU5jZEu#q^PFdQ%4n%a1wuG>F>SxP4l$fo!7Q$>s5)Z7h>QizvES0o%sikiRAd4W zj$L2dQd0sda359GQ}Z9fvD*ZlopISOGwDUfkZ|nhwC@=>_U+r?*iYMYwDk34)!%x- z+s~j+O%H}}?6XJ*KS8tY*v%iLOz(^j>y5G-!?E(;@VEFHbwI*1b__l*(+3I1=~iBR z_qwUFdI@?o+U^h4-BbkbzXr%|%8A$&iTM#LbCJ{TLv0jd>C{Lo^Vg)M7El~)uKh-P zJP*cnR4MaweE@ZPV$el-fwB1utlh zhH^UPY4*Pu7yr9i{)@wF2*|aFxX25d8=ejh$A#lo8szn zM(&4E#kf}J^v$BBCiRw=4dV)yW;&rS0~CL1LGvly(O%FYTuy<@!3&yiT>)M(E`u`N z6X=;zKxSO&z#XAE+K_UZzY=tYP6pN1JHQ(mLe0308!QQ8Tt@L*Z2)av;6rXkW?a7_ zKgGB@e9LWOKo2plq|6zY!Cyi(!teleJH@z`!kl7U!4Q{m-Gvy>=AjkLxD50+?P_G| z0r8X>SC8)u=}vi1h!aWJb`_P zm|D;@`l-;*b9IU6^W>%UdGb>FJbAG`s3eezaRuwTla*5B$x12mWaTO1Rc`I@e>1Lf z8dX_`X2QB7Mc@f5|My%#p0Mg8W+p6SeX~?YzI|LBJYkIyG*4Jd5lbijSJ(WP*@UGS zmqA=&OH)VgXG_euK7+nuTn5ov+X7RXE*Uc8VwhrF55WxMVu)c}DcVNDD?yB_z%?!+ zztFW9F~zw4*1(<&yz{uY#fENJ%nQ>i546kQrz$wO+@B^0zm0L`UGi6+3bOBbP0FhJYeq=gqV`!@mJ6B@d zVRuN3JM348DaK{=Cuuu*u0Ad{xYH^d+-a2!?zC(pjWTK}#+5PE?ZnCucVcCTJ8|ZQ z_K|TUlyS|}?#*@GRI8dLe&k|u2ks>??!c1~GacAiJ0;a~UW&#Y__Uz814sPC9eB02 zn^^}|jO&y}m>v^3qpXZz%(yzjhI*mvIkEPw#{LK6DyV7ECAXB1Nf{K2*?>arfo9$Dz8MH`QNdm(_&q~47BXdJrTh3#0cpSTXu=P-eJzw~f)1&%^9d~MCVseG z>Nn{%h^0u3A8tR37?=!iSAJFNShJ92T_^9yX0Un<7&TZK$N~+;U{&o9!+5Y_m>R4e zf|(K&DYfP{`Al!dlaeQ}*Z{D5F{oJ+8}m zPlwdpc|`o@#n6M|kA>KEiSc4+^zZQO0KJOD?Yh_pb%-X}D7uFrtN`3@dLOZ_h~YCg z8nmXA{+5*b@UzE{*(x{kMGgGhv-+dk&@YLtTUz8^LtLPJ^ttYxGq4wDAKlhxYU#hT zE}xR^&}ZtFrGPfavNQCUKHCNo-4fl}Tz6;4l$Y1}2N{X}el@-{g?}=uRo#n+zd!XG ztr>)SkU5*EeR!Kt-3I-GjSO&!Fkby7xiYPy>`om0!dIg(Q?{Uz%=w3JgTtbCSJ z|8cR~I5nwg15Ul?rk>)|N`FaiH{8@KoLYHSIAgE7sef^5l@i%G^^#7#O;=i>Gofa0 z(}pK3tIX>hyE@&nl52B2tVMknT+FdyuUggxOe41`d@kzzHID7-hB~X|AU127Wo_|9zV(Kzg@7$Lc|MWl4^mg|vAMd{d3)eU6u#dd$3le$5w3>?7!m)?K3E zZ(7##=TLIm=O*7HN-N`73?Vwp$#uAU{z=r<#zjT93{tGbUjI%Bt(h$3&j2gyF!LSm z%#@juCOP&Kn2qIY#u`b3(US^&K?14Ih>D!vm(Jx!`gNj?M#~ySdpCoZH$j20*1*YP zM}9;pk&Yih5xag2nAqc`g4pI+B%kW9Lw7bYkk)W|3>SYCm3i607ni4hgye&q%(2*_ zIUr1=ZYyA}drADiCNcMoYpyIEpAONJTj!!O`QLW9#U1yvDK7v24wd{D(YY@GBt)Ld zfpLZ~9{i0@(Ed%d1jE9cI8+t2G&-tiQs@5=?QY>%hj2UwuZYC+Sgr*$-xv7!jJ2{O zKH*CZFIrYu!?li8q$62#>ZsvIQ2OT_VL>=D>|$QL6FzcOAFGMAaS2pTpr=y)j=nE9 zq4Dxh8wPZESpFIP5Jo)n2J1%l=rqidD)vp|b)o__(~%m*|Kqnn?PqteQ~uf*MGDk; z0Vi1~E63~YsfrN=IC=*^+i^rsWT>*nz^pxbjJ7ypSuvceZ^9@s4$Ar;#(NaPW4(Ig zafu-pi~Im*!x26Ge;6k#<~V?1<=`{E#2A*a9K|iv#dl~1hdolD8(RrKc2W4|8#Ikm zd-vniT5f6~KU%F&{}(uw6$BeMw=iz-lCmW<=&}<&B+UHreGXn3C1N#}X|0S%TMMF$rW#SXxJdWnCm#F?OUJ`5?C&A`r5^Omn!PZL>Z2L!o?YZ}`-i|5~ zyq6-u`=vhQ#GMT!*wssd-4iAFV6_B$PD}9NFB0sF+sg_cB}#ChodgGmOK@nO1Rrmg zAnlk0pZqF8dh9;dJDeoJk@gZC9Vo%Ei4q)tQ-TwRBslq<1gCuaEh~FMB$bsgijpPt z(?AJx6Z?}rAs=z&WKSqaTrJrX3KLgI_JrbEuY}esDSEyS#-RJe{?OWoq4;_q^n;%k zqQm)P!^n#Lxf7x}Xd!x7?C&{$0dNhjzQD`KFEAHBR?IUvkEg!Ft=K!KYU00jb6-8m z7#1r`JPjUY#r_orBO?AWRGgE(D+TlSKYJB(H><~nL31&y%MUwd<)Wdz0J7=ro|eTa zRMwy%`x!%VY&fmBWm&93?TswJP~}A~D#@kr)4L5VYXzg8WfaFk@;Uw-P%(75rbaE# z6eTs1on{okH*?w6K^G-Ca;?Cxt9@WACpAyPnhsLvBBNFVZ^fkIJQqcCCFiHl@F9Fo zz-8*Wn~cpNu?bWF%2I8GS;orBLT>6iw4W7QjMf#ze-mV7tlXg=$Cjc!KuU^2TK?0o z;&Z**YoKzo6-inT6WNMX+#x}w{Ss6@DnZr9KVn(6z7kX)CP9s{64bIKsGU`UI=LmN zTU3Jj=@K;9DnX;OVyy9H37Y&YLDRbuG@l}n>mxBEQHDq8JMgk|OHfoNpWRyPpO-)a?-+g!j{g;C5YKrAcT&cRY>xMlUk z5&bi?DZmJ;Agu(yDcXKgEOtQCXh>gl5fHAyEL5~Zp(qy4gWxq!ScqZz>StDS-;HvK6hxp??$pM?m47_fauLKUfQ7Ok^Y`y1C$>RIIUoT{Cp&9bM6#{ZTbA zAvfh|FyAXhAuZnR0Fbfgm#C@CzqqVr74N~|b9P(cT5%gMT$g`xHeq zfwuHOd^k-6WCo7t+U%rBA4yA*w#H2lG=$VDMtwhp(sQ)k73k`+Vk#mjTZyX8fy-8+ z+UkQGRNv1*$$f(egEFmZ?klcq>8Wvc|!Pf9TJngp}L z(pY_VVF~6ml3;Eh2^LJ1VDVB3URx)@(hntAc2R=m)+emKqOb%jYfA9O;}YCFB@W(s zZz)6Wj+Vqf=SlF_FB1H{L4tpdN$_t}I*_G$?BKDcRL>)F*6VW#djBRtpYX#h>swHQ ze$^!C-$sG~eIJ%2p;6kzjHQ38p+M!PFrL^5uODBa3fX%@Szd>18<{M^2V3=v>^c z%#%tCt_NxtPkS-D;=Cj=%$J?$kl(UC#}PdfhA6;t)muu@G(d>1LioE2&>g0<=o8&{ z1%cws)-CD8zUP`D+cI0aA&UZ341N&Busdb1C+#xaU7P5a(mqN$K*w=i76X zyS#5~H;!_b_r1`cqt{v?I_@l5*Wa%hmYT-rT!CoCkw~4uCHGh7=*0SnmRpQs_&POpI%Yv&9wBbL^sVR=KQLTJx4x_eb=P}IaH zG5=Lk<%n9i9w*g@?&Ly6&2EY}gBu+`$|vQiX+Id-(du9PR}W6fLVq_$!oKpD@MKm@ zingrkIHJ$77-P^yuoU0H#~)~U3S^IZ^1_sS8S+my;3kO%BYh;xmWys-T8K9H9WC`P zEKNiD>|j{~5P9FpKTkup8tI!|S%Axpj6cN1==-L@CClOlr^5i8azT)vhkL#&rE_Tc z50L%k%B6p(PLhjaQc)d+?Qtc^63-G)bCQetk%6Z$%@~CIez^y$R26`RI8;HDnFB>y>hGSnXVm3I0ySEwA8qFa^d z@H`kQMt8%NA%{Kz@C1Wjm8#WLM{>*x`-PkUpactQAKwsE(RXp za1G_+cBn*CQO|u*@eWmjv}Q13R4pK?Q3Lcah3EunR}WE{wzdSK7G(vsa%co3&#_b- zfe!^5LE4ZefOB*C9GVa5Tduxpgs0G1t;#eFE7HCebaOQ0_5gDx1CA{O1YC)>+=Jov zl#W$FW%w6>?`NU_C;r+3Y!`a(C)JM~$`gx$2#2Z&WwHt#0bBL;BK`-u4kbgZMjOsh z^~)+$EFF+Rl)oTD24xDF$BaR5ZE+!7!2$j; zkeO5vw*d})=0b)sgntZVHr2__8QpauGD7l?fy^VvW=P(+kP=BfR;A0O;O-*Y)f)d& z3f?(XhhgF^|DajIz=eIQ>09(ihdM&~6b{|fT%4+)%Jc(j#yE$1*!Eu!O9UNH$3UOqwrZvPY~JJ zFwWx8?y@wfY#R3kQ5j&G{x4iemfsRR3gFWo*zF%7xF3ne0W&89PR1LZ?@gjr5byLL zZYK#bg$1A^z?}7P?*^69Z_{;1{`90RF~b-GQCz)wZOVdPk{gGr2t7;UlEtv*D`H2q z$CE|aq)LF)b729gO^qsJ-`Zv=)MG&O@leu}G^(oI7E_eidI^Xb9!mPYMm4b?z+FMD z24b^^l9Fjuik&!EqmBS^)~{uf3zZ45nuiLkCYYSgM_)V~d zN1*CkYlp$SIC&4k2f=`f!vWZA*PWsPc>p#WE@Q&fZxWv-H;x{LDhBBy~+o57V%lb}>AyB0C<-12}?URt5UK1$@10zk~f_ zR1DIxE&_e#Y35&%&IsJ)@#RQOA#BY6)m|0oei#4+oStPN>;=IPS6dB&APc*IDC(TR z_)e1`o#`TA|97S?Wt}PL!a};L~ZnF#EPU*eh4 zI!j*GsBS>?c2Ovo0H!;u(0tbOYYY1z zObfQK=yO!IUs6y zC_P#U>Y&rVne}Ehagx0AhP6O7&xz zcX8RX)$g5WN^1{K0DIBHyVDNpUZB4^bXpM*j7mW3BFs{`I0*Cm^_wM2uDz*n2SlE1H#te zhE3|PCSXlNp{Nu=jR|Xqb`ew$AclFU;QABj?64a7HFO4G3q7c=zrYC8&KqGv*5LZx z2p=rE@pF`2=rQ5mc81? z@_@C-1R7GQqI5rOplPb!P7_ zUX5scP2ZZbdhY%e*ase7YEXB>mp((~b@2U!u}QqhlMlE5ID%`1O~VU;_VO(RZxT+? z1h5nj%4r5Q+Sla=jT#8V*ie*W@)c-j1>`->H~&L4+^c{rc44ry6Fttiz}NUa?bucb z(_Mg9^QO%NzrojMjK*I9)L#Z{zDHYY&HT`+o|$HF>q&NB`X=I@R_d)i z6#D-!C6mbw-%UJ15d3&xmt}?zZb!+)4j+b91W|eq3dcMpX-E0dqlMt(!{5YJBlz!u zr2=jpc=(4(QYL&K?%zcz9~3J7FC|lw`r&~&8s7@oewpDPDoLO43Xf`~R46RXOv$@P z(_LUl_#4f&(hew`%1lX$!#~Eo=fb~vMJxRX1z*8T>cFiHqck!6GMJ6jK_MvA%1nt# zq`J%0?kx+SgeyptIzeGzW=b*uRiekxm3^DSe*iUSyhD=#Ug;@FeR)4}fmWh#F%A2+ zhQ9=ksI)$S#@WoYyhg1`ImaTeBjKY;s}&W8{)L9>^=wz&168F6OpCs6!~2Xfuws~w zGQyIGA6EJP2p^0qg#Dv>Ky|{Q$&$30>o`~>ui*Rchi@!`*>50lqZz9>6PE!M-kq6T zWJHHuxMxPY(HtNaxfTI9HV=U85j#+N0c?SAXE5M3+zR>fL@XGD+YR2qY;4$z<2;ocF6Lo{?XU^_f$umb`e6|wto4Lu3iRS)VqV9F-=@e$vl zJ4gdQ05-1h!*yZ2m>aRFnkM;W0ITgmgB>OwzgI>)2i7lEI|J6wg9bY+&@BOA&WBX=pfzeJ&ij z9|t=u(3=sjq5nzQDgxHrgFfW2;O|E~UQ3&P64()$;Nh@9vqdf{qoFSYw%mgTJN#h{ zbcsTdk8IS?_W?`ypur9cG%4~oY`PGKuK;$>gFfW2;Oj;9eoULrUKCHkaOk>l@o-q6 z?IIuGwn0qS1+1+H4R$zyuIzgvvT|YV#Q?yb^Ps^F3v_5?Ni>yMod?)D59&H#`mo?% zjC?zEskR}=088$mX19tcS z!iy^*{`?y`7o`-<&!Bb5)8q;?{=`RphV=_U{RKo^@rMhjmU^}SNl|$*G7G*8uucCL zUbzx;7_}6`PljTeAXb$cV8@qlSNQ9%nN|4dFi^9{6m_cBj%Cu|HNQY(_z9)k)1Y)R zyx>%$wCg{VtOTmJ0?!@3rB8wSfsq|&D@8rgxI{wDb+yEPuCYt7Yl%e;6~Hn>%`dTK z!9#jJ;VOdk^LUI>XvCWNLF%7!5SeurZl&(EYB$19h87p0#b!t<-Fo^0o zv#R`Krj$TWRK1jt;+W$Qb{7(9;XHP2RctwgwAA|1pES{QxhT$ z<*2FyY?rKPaZMspNg`HE1r#LgpS^IXY{{^Om$03%Y!lz*X&g4qSq3e0awW%`{RGR! zh)>EkqboRxF2r?F9}k6h;0!HAiH|O4>0xzRn#2mlz({m)##&Z`S=|tpD;SoqJf5E< zCH9<$W#oo4PNC7KJ`Ph({&(vkKBFvjVqU zf9mUq_WK7~^58tN|940&ItJqw$zYKFjmY6q-y=`lm!{( z!lCp7xfr2^`=}HIRXkyVAmIsW3PD#-c&`mI@N!X)DiR~}og7Sv;p#16E)C@BjqA#Cqi(15PAxSFLb z41#ckXF)yoNbEzuwZ(c5XYn$G^E?Y0@H90zVp;Dp;2j9J2V3ChB8j7^;UC(<2?#$A zwjh9U^a5_8#KLb7-U+tA&qWfa)0{W8lW~dY1UTG^;^!iXbLmCW^-vMQ8o>a5E|R#E zo~lABiw+QW2?p?Uk;K*1>Zjz%UZ(q zumi$9!2o_PlK4LD#l4CE&O&%07{HGL64R-|e#@%BJ>V{cPI=SZfvQNeVw%CWdTNk( zo@$TR&?119_n@^IDh~t_Z&P#`yeGu=ngh_$1BpEax=*<(W6WUCU;xH2NV<^Dw7q1? z3wwzj>=PIr?zaJS5nyk6_L_@--2hdqoQeJIc3?}i7my^fkv&R0%KmCBAQuc}1hD0@2Vz@dad1pW83?*R9kQ zi2fc*>O|Z6!TzF&wlyAzxgJWKlWf)MK_Wh#Tb%Hs1t8l!7!M;{7a*sJIh-E6zHkK6 z(=G!3JPsz1nBRE}kK6mhL;4BA-x*-WfI(}aUCj9+AN~(A1ENt2IdHfDUI|F7;yi~9 z6f#I8LRgalGQz3`ROR+8h#K%9Qa))w&4#Alr&UA3*BfVlgREkTWUdKJ^QvSC0d zfFrn*CedOTNu2L&>0nvcxPMj$qA{aF{1Vg}XVrSk`h`*5fp{u|tr)J!n%OY{@+>JY zMDQG0GyP-B;%QNsHBX9GzP6k2DB6GKbZrdHFFYzUtSxh?{~IQm{%ynYbFtH7_+4KZ zKbOa>!|!U2UYW?zYpw9}ZCAJ>6RQ8}(v67n)an0zA}UWNRR6W<9OY@&e_eKN@{TtD zj}uYW1R7i&@q1LV5(WVr(Ff5$WK~z`*fB;8k=n+U1P()P#biN(#$*MiFHT2$7z;hik-q3!Oxle7b)KwqrbKM&QqDKZ84%&(IuH8;C|O3SO_`PFd9cs3z*4 z0o@?%&46oMQcN1WmBL@nZiAahvG5{ZaE3yKl=>)A~vV?^gH z_Cc8DSqOd0$y*=?HQ z3z=Msw;_Bd7{H9cKiRG_8(yMA(9`8{KxFdD*$T?NM{#@F2Oq`{GZ!J&S*D= zLO7ZMrZSoP_`k8g`BQVBIS?-L0EJ~MMfQeg%VUPyi1eK-lR+pTZYsXwx1A;Rv4FvK zbq0uUGDl@|qHwJoX4E|(!f>T3N0hC~6q^m+c0{MwWc;*uF4!fE_voUxzdK>^!o z06=R71^J{vbsT1#l38B>hG(#(c0>4^JDbp##nen7=DMa(dAwc1-_E&!$xzH}gm9Z{ z1_0g-;eXUgkJc8BL-<*+1p)MMo*Ahv{0iaiU<>?o!9T?LXDVv_D2fwX18V{}+^azV zqn(9V&yYO5e-WPs`% z*{J^)XI~eWQzym!5#=EfBwE<)9}(aeFEtT7l9p_ z4X|+M-xJmhG{B~-klb;l(%Ds=Ri<9efJ+Nox0`WUYhf`2M{s8@NQZxg&tKJA%7_Y( zHt-Nk7mTH7Zl_(e2ve6$j{@_whm$(>DyuRLcpl(@z4-+;Itjoz9$2pHO7t7XmF&&z zg1D}E6O>IG0NLuouxIy43_1Q9zTX~IgNseaA^nCC(m7Q*c^wh;aS?NlznQNc#$=mr z14Cd{x}4k4hX8r*UzqFQyNK(+q1+Ic_8`ImN?_PFxF>wmUt(MXVA^NEMKgPALc=~m zmP5nXx=q7@nTn(4S5INYp5*2&mBQx%{;^{CyfWQ}YWCT*$ihpxv=wT5aWs7u-H=b3 z$qKu6UgAO{nG*_ooY(=D^3_27;r*Oyb-*59dILUS#m9Z;<}S?K#}OTS2UTI|^pV7G zXXnGA(gX33dhgtnas}=?H_T0&SL*~D1s3{7K%U$Xch?0L`S|6xnuRfHaHPd*Ok~`M zR*Qv&s^8eN^0d_R(+pPANk6S6ZF?;*BZ(p#Q`U1(rxE9OD!O8OF8Uq~l3~I4_ zP4$|xR5X`fa=Ub!vCTh)<>KAe0vmf_RfZaW3aP_zMAr?52^9jT!CBT z>`A`g`yi+C<#N2*vA=H(3khaTB4{Qmkt29?&>dN19#07%prK7rkXNYCS2w4V7q(+lpqGCzImeC%aAqWX5vNti+42WA%9#u|CdA%*LP> zzngfa-7XqgqWzbUen6~Z7cEti(k9wg{D(vzB9BAt()&_RT5td#T0r78SD@A+4{~j3 z2>zwopAh?DQ0XejVTM$u9`VTT6b-1$yZH+PQ_96zHA@{*_o*%XxO}BztYp4-jPF4_ z8^p8$w#|kfNJzmK?J-1_ZG8YI=cqq2MA_^%@}Q$5$rFM$@&Ka~@e>R?nOBeFA0=+4 zWL`6le~h@_#>|1uWWKMB??xx#WAc{$hdMefsVT|%M#1~p{M1Rd^1~7o~ zRKO?{Fhb=~ znL1(XV*E42Q-w{-Az9~21FVAPxjPenzDXYyXUKktk7a;VqAHgG*+4U)pz^r}$Sn`H zi!EUz4!7F{TKpb*3yNS<3}%>k9NHa?xJ;cOeHJ=4@$<0ij8J8+M6a)c%2oPnqOs8d z(k_fpMbd~LXxTHy#wbX~GQ!x%zX&#dq3KQVsdn*WA*9QLZ3yBfEtzd>?1Xe*u#ML- z`^Dd;f?)8f$X`KvIoO6E{-p7^>*Dg;_yjGwXX7A0`u2hi%l;bGqHGj|v^XP7Sp*Sg z=bdJ3G=Q|ZXQL_|_y9H{?X*>v^@ilq2hxC4cvX649)!{MSD*wue%LfVNcestgmLzP zI;I3GSU3S8qMZMLh1@0(K2ivsCbwO*x$*nUAWaeGw|~rUG;arKinj^& zoju0e>`gqg;%zZ|OgrOkg&?6kZ7gLs&w&SD@WQ6nEY#kLu$=t?)+JT9c`8V=MpcwE z$v)oSXif>z6k!$nD^Oge`KGH`iEi`dUC1}IAy%DBG5gvJ;Sn6FeFDFr^H?#H;7%p_ zXd2!TSlpPzcMDs3hH>%D zu>ONX*MT;-6m1g!bXX273M&um0Ma28Cg#+%Scyd8#W3FZ%GK!5(*RFo1-bC$qEJ74 zF`!(VuwonkN?5%#Q?3;NZ)XL${*-a{#^fLh%fs%Y?o=CrjLL~XOtRD)hb;4 zdi#-oR3*|C2!C+RU>f6Py7(=2#j&c=$Vmnhz@aUuRk-+_b}Sa5xS^>Sgk>3^MnMhO zWAnoju6Ak)VQbHVT7`>0XutI#vSvU(2%q*WXuv1-Qw6Xd!GNg{&I-1`%XINa?QHN> zEUbm_-Czp>IB745&=w9ucq-TeuPnuXYM(Lp06#)_GZ?^YXz^dzW2RdcGb_r1t13GV zw zmr+nB!gAHtPn(Vc@r7qgqkNz{@kJs^Y}dCjH-Wh4qP!*H#v~j}HOGZ{?Rv zTOonc@N=9&9Ys3}4dC{FFB-1_KEm?v@$*Ztycb_4A2c}us>&MSC{I=#I`=Fj@&o;k zTh^1TUjnj9t~|i|0pUbAXL4i#7^fI%1waQEWaOv&FV#i{LH4XGH%78yVJiMysZzRm z<^ZsaK~j=H4|r$Aun$@2(GQT_g)XNxayL+E8IW?@&y8rc+JyyEDjKK)?~C5Lj^7yG zu+u6mFOpk*4Lyn}R0exUmTpC~)nG7E{7)6+Q+MJH#|m>QFK&xXYwdSnFHyvxf3OS{ zvF@^Mg+-)S!Ph4vX3emzxCrK?2@y97*w%h4f@x+dMHFddTd8(Li}MJ=B0l>QL1e_( z9th$h25mu*5Haax1keb_vxQWsOu?t;HdDmRhPHLYipVzDwkFvTwXroRH8sqtYkiMw zo&KlUoo*@YPPvZk&iu*j&TQCL;NhxeUQqJHwnE#oGb4Z9IeTpJ4E7JsI2>>I`f52qLtgJ-YBC7j4UV z5C!AOU)4agC9#J|^w?I%avIr#P>B^_jC$f{FplU$K2&^w(+sMkUH5H`nu6p-p(q0# zx(Eheu}k2adgEuq;1<9>^q`z(B`4s6!_HI0ZI;prZRXhYB`|pO8pAoZ@6)%p<@j`( zow5;4=|t+&u=WG`jr%&Tj9(2LP6ws#$?T7XrWjVR@X@itr&qJC| zpQd&wj^=j?>Qjq4v_?O0ikNe|!x!ifP6=}!*5M`e45zd?kL)l6UBoG8&f_{vMf*Ax z%y~kGDD)YpvN>;%G97)#six02r_4eha%$?+mK_4AqhIkhXIqiU6r%Ggy}0=(trXIJXHljyJ_j@puGOuk*du>*X>SeZ2x=w{D~vF zxQ$+@7-w`@j$>Szi2iPm%f8sLzA28B?9eWVLtz8oA}>V4?Vc zLkHEbpoMQep@nbsfY6Fzu??&Sf zxKVyiSMy7ZVQkOx`Tl}x`OYOC1%MaT%0Ipd{x#f!EX((K6H!O9FF)u8%s1rzR(|3x zL>>QWj=vny3CRn~BD!R;pn0{g{HlUTu0>&m@%7R^hw9^ld+^JlHb||H^c6n=^Yn@$ zSf6B5)K{mMe-Y_pW@N#ZUP*sZr~ih%O64bx9fLIrNnfDTpGXCMR*jpMHBHjr(dk1m zUzT6OOAdFibnno|I(_A7q_3XHxA~X_9lD^?zW}QI=2!ce^xHapXDy`fX;KQG#TI6rfWGAdrJmooU!-Ff)dZeF+nz zT?AV+cBbGSqx|dC9oHgTrn!ugKAMZN;9Gg+H_(AYmc?C)Ho3BFm7ime5OBT-*tow% z1K2w91RA;=e@=|b|LpvWbosn$`Mc`5h1&rid9{&wl4KQs?Hz^}Ca35l*uu`AV=Z5n z^n;Gaa6ihIq*eT_vy6%)r-h5kp;4|`>rpC@7vH4+*P(Ghx#{xoYA90F!z)#n+(Fgr zACFP>8z^i=+J!62p*H}mX);#T(S@=c0wOm#bST)cXUTe;Vi+=?===YPNMPrt66HrN zg*q3Fl+2wAdZ>0H2d?V!oFGPP|_c#8%X=dO%Ke2)ChY}R%DO|hf)eGVPRp)Hv$>-?SSq=-bh79>NkHfRz-gASFKlY8$_NjL$#;lI+2x zBC`3iX&HWymI#}Kjvd2BSd6TGn9R9-w z%SS@?yeH>3iG&gO>w;KSnZ_h5Th%%_G3sZlS~rUX^(J6}K3mlWzCSr=m_vd_6(nff zT7o7|NzgP^f@W_@(0sQ9$)^$co;iuk3%y&c8)|dGO6)P*(vPVf6OKaL$74V{I>O;-K9F2~yNq zdlhuxpk3K+;HHV)L0qWq2-}JZ*fF@byNeEG(^Qz`cTJ-I#VM}e>wPf5j^|g-D$%Ik z0AHtm8w_|mfFF3^N;CtsIx3reevm<&h4g}l=tv(g0perog*3W_9}8|oA0+fQeUWsc zG=`i6t<3>hURR#U%Wqb@{ku?0!4qdC=n?fd zEA%XlAbX9hVVxz632TYaw_%H8QJzJ2kws!ZZmvb_0Gi8X=T^-8#{pb$8?F|5w;p(` zP{cx8xkEnOGlZb7FN{vIgI`~lo}ozQ+bfV&{-KY+LbtH|!{u}D=v=;4H@VO4euXVd zN89Ulw0*oaM|HIQ{6SbT$7z=D?0al(026DN8>qh?Z{_>^8q5{%R<;Kw$G-1MSu(jp z*oMOEI|OFr?j6FDO1K&dGZF(u-3e2?T+Z%@JsxYD>BsFNz;;_h)caKYqr6p$}G z*mAby?r|9O8>lUcVAJn_{OQ6B;xgqph{0JL4)g~1z@f|R?s3@N(%7g5XE%8zA`z8P#o?{WBPxhe8qNIwp?q4zjM zF2?=|Da$2DuLawX9SoM83v-`p9-F6H9Bx?z5oX`%X>1gOv@9c3A8_|L)K9=GJd#T? zqyedLcaOs~+_LaEW>eoFq2A-Lte(kz0t?%6Q@MK_&U|Y!ew~F}7v3I+^D9l+_XKI` zJr3_*GMeXtH1!^bsc=SldnZV!_c-KiZ@kUX*UMAyaVQXp2NF`wBo=CK^&W@Pi%gTZ z3DVSi9Pa#r4FaM$Fi2DHaj@qZ&8e=YyT>8hLbD-Z6@;5`sP+jILMOIj2EeGh$Ki22 zdQuw_P5}2+2CTcs;S0>g3U(Wi@P4kzk6=vMb@w=wtz=9V2Ch=(SiQ$#H&(WHzywx* zfa~pHx#Ut?>Z*44INW#{-*XX#mjIrfK|w|UcaKA7%(V);9=P{BtcK}54taEka_BT5 zS3DSZN;9bFJr1irXJ7vW#@FAi18q+4aTtHVc$ff4wNRLtQ_B|a9*1>tcyCvV)E?me ztRNSQTomd@CUtj@!|1#whY0{L{*N5=9*6A*@y?UvunpkD|1$?~kHgo%TyYJX-3i#^ z@COoom;rQ;l4-TLbSoawy*&>3fhpzT$}+^;<4_BdW}dX7lA1jZk3rJcmFkJr-Q!RX z*J5=j&^SP5y0Cy`;qGzR{tec#F%8pOKx|}`nS^8u!+N__6V*8=4Z`ED8BAk(kHb58 zRHe~12!Hh~xO*Ii=hGGp!YcZ+8R%0*}^*zZV$Gg_c&a8Nt4MF z5PlvE(0d%JVe)6%MZZCKCm6u%kJ#hzBGv{35H}F3n>cha-8~MY(ETV8f|@LpX)nMn zXf`mUhlk;jtV1afck>|JV-4hNcpfkchekp?DHIYAoV&;2AXqJ5^t1x7^`THSuHNI2 zrx_~_aNM9EQr}Q3&d--&B;~<>r0?emy^d5(vjntq*ZvnA|QEE)l zuIoJxOQz}q9tGlyhfsQtL(@Y#$D2U>%P7@`GM%`4943_han;z3Hfl{jU4obR{=IO=!|M zXuV22HDJRRG@9U$+a^BIw@s?(qLDEht_CB?;VwcUBCmo2?hS{?f>*KsC&ObXPU; zzdk^(BICc~yD!yJH~3pSC1jIKMS2v9Zc|<39;}+`I*%W+%o+cqG?ld4Z_?g!FL;x0 z{}QNsGxV`rvsw}al@o_5aA2lX4eKYVoj2tvfEtqVr7Bpn#XV@aE03irgOn;|@9w3@dJzxhVK2#Yx%|L$3s;1B8K9KjIvA)TBf`QZmThvVm0 zA#(QT(Lq+Sat@Fve?2GXQ#>&E`I9+02TGJz1ac1I1p(j z6haoub57)`z7dV=JIcyAlbjJq#}QpuTDq}H$5XWYNKAAEYWbzHRLci&Q|o_3jR9%r z!CEjv3y)Dx2nKt?c0t0g=tT(Tc|u-`49X>oyau21hd=Rjxih=A5zw6;Tr$$2dqbMy zc`JiX18~6uNrsAd=FCc|xPkC4hAr5%-NJq&D4NzA^b5Iz%Q`pY)A7^ zWs*hMC|v(I+$<`>ZqCQ3a%1g7aR|!=1Na5@oKMnDbae5d8H8HB;9et+EiKIip(p4WMu<(}<*?>YD4y*ZaK1mK8h0!OZe zM@gLRend0_;M`~eN3Mm($n0OSe!*m}0k|oez>#a=3GxIc2}(Es@UTxXBiF)D$PA7M zz60CG|P?cSukGo z)MR5VveVC_oMEKw1mpdibaA{}c#U1Kh^y-xFwWnkOIfejHOINSa-sMO;>vCpN3w;t z+eyn^T`6ERAj{Mu*Lr2WWsj-l>gobU|C@AiBwP3syFKRKI+7g^#$z|>Qr1yB)L9H` z85rww=&C3^Fa!|U3Hg3cLuBpR8&uvrgbWTvw#80via%9L4X8IBjl0>ok3$S}I_}PW z?BVdyp}YUya4CyCs)Q?H9_k1GHPLJNvgpmy<8n*Z6&<}!Xclenj$;*&BY6z@-4uh zeF6i)jx(vcb6-K^!>zb<=e{z3siUU#6%t|+9HJ~lKmWL{f$wS6QBy|(R*>Ex8;{oa zzJ&j*O7@HG4Q1xL;{NKkVsFDMoRYupS^!CM2rtm)uP@`^c^Fs1My3;gzw>L;{7vdm z$$ZF{6Wc;8w3GJg@S^+=a0MAb@f%wlE0F*G7boH0#@h1)`bRmR0f^@p&G{#4m}Xa3 zA+F5ysgdzT{)b7?@df|t%|CTNL)^eLDF36>nj}wP*qwj66rO;WAaEsQaEOkpdh&8iLS_q*U~#BJZY0$tCLKnIyo#)l5&$ZCpebzAt>%xHzOX|Y18wUwn8R2h z)Y5{IK0t>0=u)C)D3-r~BqF?)$W$=qur)V~L7@t0 zn*1b5gIDh`aGT@R-I`w%a_(%7^v~v`@wp`qV>Z4{R zWx|$o*L^cD|Gm~V^L9d)4D{jvXt=Tf&~Fe(x2RAG{oZ1kW8EM$+6xu@0|{~q@(-B~ z`5asc&JD28;AjE=C9)jC^&Vidx`IIiBD;Vb@KH6#Me~S!0pxoh%?;IV{i|}9yo@bv zm@=`EDM4H&YLg^WORMyd-Vs(sFlzfO)m6(>x3Tg#-ixuN9pLUhMYFA*^j(4?j1iG> zfF8x=6=J`$&)AVzbChH^R?b#h@2%h|WK`^7)lj2 z0NsZfeLl@XSN@oshU|hT4;5lAxZoW58$cfDG=W0Vl{Kp}+RP;CN(Ld6%y4c6S-bUF z$D$%>MyQHW+4&Wu^hxOr(GXmkPKI}N)9F`MODikW;8j)>!!no?d*VeV^~?ZtTltuF zBvSelfy1q=6h|uS_4Tfq2Wd-9#^OSk@4@#KYUcNZ>Kn*Z)-UlSHikf)NBmHxvhKiZ zGj|dyMMy&hv!KAMthFJ(9alnIvZ5+$2MGIlfM#{h8aoQ`B%h+%{Te$5$YLM8ix#_e z@h+K+7J|u>&0y^IS*pXUv5gkHtk1zX>$6msS7W;&jkeqXoEzC}5@PbMp6uJ~*4WyB zTH^9bvL$OQrKW1S!C0_4nj*_oU>0wr7SBWuwoSoD27xNM?ZxOo^HIXGtsuo#qCy94 znGMzRaV2!qjIC#Y0=7sNq}x0sTh40W61E%weAK7(Vcxl_OX2)OAiw%(8c{dThT3nU zPaeuBgRrX@E@MDQb-1jNb~iM}%Bl@UQ=g@}Outy=IXexHhI9j(<}(-y`yrM?D_o^0 zQZpUUB3wG=WcI;P(=_aw@{pgU1FRs&Z>?WPGa@Cg#cfA0GrIgEPWzqK^Dq*WlA~k4 z@Q?>$N2t!OqbxIG+=z~?_1Px{ytLRqJ>H;LE-K-8#22O zxmKw!Y3V;5ZNGd=tU%&R&LpgKSKibRvx-#?mzzk%k41lhMM-bUh&hJ0C zk^KsWg+ennM_2`@>lY_iA=|`Q42)#5vgzte!+&!=v1~W}V6?wU7q=Tu{L9(3PfR}F z1I7b6bop-&2ARUv!*`nc`8;^0h7XEunG8#VTn&${-4tp%!U#p58VKoW7=8}Xlb9}`~@4lX=`-=clcm#f@c0uYU#|Twv`V8 zxf_ImK1nsWq?aFW>5?XZ@VHM>O_6D9cT8#Id4O3yftq2*Jr#7?dH}#lT-t;%C$tIS z+}%xBA<#p`8AhkAhJsz>NwI?bcdB*o?-2`HguFBS94F6e-Q<8lDnua~u=VlPY;DqF zn?)fy*^E7fL6B6blLkO1p;hX#>(!CGA=KmRs8t$I^9W5$(}!lt5E`69tku%>53tC8 za}D@9r8ZNo`6rK5J0Za*(0Nb`JCEvSo2FAz1s`Pce=qq2$d|YhQdkrr%J2;6W=`Ko zo+K<9ko7wlF;L{P^p8ZfRpScMhSmpmutxTaO#v@5qc^6M#lK%fT1O!!=Q{AsU?2md z5Y4&R@6jd%lI;_@1#*&g2`-4Xr6w818tk$_Z8N`_xN!6fO?!{!q)IAT49d4l}tk3`Y@f-gm(~sXYv9Sv;A)cyt-!&V- z%*SsZ_ru)nRYX~J@VjtEK7Kn7_3p=STj7j+{1)>h#0x5e{oD>^n~&d$Lmc_|tq$_D zCG2vfEu{X(Z};Kf!aYuqJ34?4)qn4*#dA}*(&ndhU z|8psStt%f{k@ndw{`m>@_4Mj zMt%JD-#=~Z8X}g;kcZkKiJ=Mz>3{t8)Xy%Vb2dUKku2}yw@I*59`qR07}4W?{MH;3 zP->RBWa;bI-p6kiKF{Ur#j?)Bs{Hj53-u@GbBJ#KxQ!LeeB7qbDn3YSaMFB`mWW#5 z)j|Cq--5*ak8je)N@HGu?j?6H6uuN|byKLi|1*^ST~BkZa(SM_@6K5LLnJP14_(hWjch}%k{zY3m7cQLDsG_8pbFc#*; zm+i70=(`>xM4k9HcM_GnhmRPJ1NzE?(E##0g_xakcNizq!5+B=kPZ{S`A$JUyNGGW zuLP<~Z%o5trpRrW0c(KUK(5OGYEp=@2y3`>Ugxszg19?bCRyH>2Hwd*Wpv-t29@rP zMIti6oJqFPsfidYKU*4yW#~~}ptAWrF<4%hjcL4Gn#zmIP+iPGLLO`gWY@Amdw zijcAh=5y?BKU#vj6};qC3&X-o46t}~U?+`!Xi^nA>3&e|i;cgiFX^7ijPOc&ey z$$ra*V{GdoU}joqrkrU~<_8;^Ib@L+BAVHshC1fen5Vx&oTC|eGlDa7LK6&r1TE3+ z?YUAfUqomEmM()< zfPcmC)3Whfa^Cz2_k5HOFi=snW8tUnP4yCzz&hEfm{Ulo`ZwWZaO1mfLI$3WN|lMvhA7%fo$b00)mUyNA-94NqDya9r%PFA&9*?;QO?)H z#v5rOP2p>gE8%DXJPRT2h+y3#KLORyA_D=A@Ca^8c85He@qiV`jK^y89Dp(%H#!pT z{S|8Pt?MYL@5l!HUn(!EWR1mQ-JU*?U*#S_aILZ&@tI*?x|Cgj&9oNerXtDv%)e^W zN82?1Y4Q<1HoLt&&ufwt1XI2Ag{I(rHN;!A32~m(Bpo8Sp4+tE;Ei8}UF~(Gd4B|_ zFEkAY{2=_0epo`PrlYIb5u8REyNAeAm}ceaBWto@q+3IT8$INiAP0c?gE4=2I7B{< z$5)B-2lY4WaP2j z+9Gu$>tEUwP3W*~Fg8s}yoQGHcp}~nm5B(ZW^jZWqDXHb{W1&t#6G6Fmq$o!%k;!L zb8KCj^h{uu^UXQg9U*Cg9!%0Ky-^9z=N^seOa#vnQ@T7m3*BGtc#W#$v;QxW;WmxW z;Y_{KA6)2-$Qv=(mdD-W@@`zyWR9PSueN(#BR+)q`sZ#sPLCg3BCQk2d_bAA$c&uU z=N|@$+}3LQlBu@){tq*mBav?DWAr*jzq}Qlqnt!AvrLdCOV>dB(x)g$`7>IZ>Gjj( zD0cTKx>5U!N(=reQ%pBO1xSIi&ndh6zp!bA)#<|yXbE^=W_|O>ACsL&ZEGq7G7&dA z5*8-&nNQVcex9&Q>&bo$R{~jBHh&R}?PR6>0+wk%%+@8Qu^A-qle$lY#>mIG{r4Z~ z|5jzKAOojM7#~6==8e(naoa-V1iyXN2j=aHsII)>0sJMuZRKezy+A;HuA$RY9Zq(F z#2rp*AbrgqtwoL2DgQ%jnskq|t%CP4oV-pFE5^T0xY8y6G0f30SY((h{}{%9 z?6c3-%(I^^d(OhN;V}fI^rEN)H~9QNCVDfuOPAY_{RIn{xCW9*`xvv=1~qu)XPgrh zMzzz#`#0{JVGR}CX6O}X*KdexJT!#pLZ<7UKKB{h)XM~~Tf2Swg_&9)jfsgAcSWvQol zxNQ6u;`+zX?TA(Er}LIoqGdUR&!6;r<=vK5AW0-ue{H!JzxflY@N4}12`L;;7Js4~ zADxDEpGS^z0-Ml?s7|~Sn&{`=9Wj+kXv#KQUm;FtR&p<#E6YIIyd0cK(zzSlouv9= zJe{}_DnTj{d1pz5tg9yvRRap}E(Yo*=>Q(^K<}^lxl4ieJa`qaW+A2WBp3_HszcSG z+;C#rq@=#3zr=o>ByEE9O`jApByQJ|FsRm4SJM$l&yu7@hQ4P$7NSLEbVrti`-{8+ zRezF!EOA-1L8*w86VrszlfTFRhm5p5SXIbW%S0VwDMQ@;NyM#Iq}f@{Q347 z{W-Hvf6jiWKi{9%pC5AX$Cn#2c-TW$g`*dm;|mCcl%udAl*Wq1o7MKmJ!qp6_t}M! z)n<+UeVYZYYxKGnf5>KEl&b6RAKUrRXq$EU!*&eZ733r;P~xYyRC)o^JzNRDT|+!* zp%plae=}M@+Q~yg+9SG4?WgTGiiq_$jFMqsj3O)W2g6s_E&3AA+7IKI%mca1#BE+Q zL6_Qpw7+{1gAj&U2k77IzPgW;fJxJ9C!9VLUw_8Y zt^eyBw(p1AuRp^O(I{LAbN@ut(e-BK@e0;7l8deLPU*Qf66X)(=#57$H>z3gtD0GAP-UU>QBu^Zj38I+vF=$ zs#kw{oOGi-0LIZA3cdPsF_)N3_!*4rH|cWgPk#J0s7WY{;x3CT+Bo;`wZhKeQutDb z8F~j8Ej*ULe}i9tVml56ukqmJVCCM~8x7!)=+^LFw>A8`6SoSvuKPCp5c6r|F@8gVXDwKY=wTa3$P;G^&UG5wfeE zJmjF;^?T@Ch&Y7H1j^AvZ!UuZM@UHlqXAjD5m-X&AoF_Y%;9)xk)$vP{e03^Loz+| z@R6>ju^`MKNsSE61SxwDUF%t>S^~xfpG6y#>h;hYFl=F1c^|Bg$W+Tr53Pr?1X(z- zEj|S&p<%t1|CGI-F(Xa(GKibK#gRled&|J-Wp9lYn9JZwsK7jk$U93L$nN&!p%kEg z_TB^FK@ZH4y{F&Cs|m1OW`VJYtXfnZiigw7-iu?=?~wE=q;L78LWX3r_ZZGwQB6l7 z{f;CxGV}uiX3ySn_dwNkF!CZxToywr)yv-UX?WY6ktTzcLZ(_~vbXeqVP5bQ;MkZT zI0+3GtooFU48F^?KP(OQb1yI8Sb7b$# zDj1bPqqGI18(FKUI8xOb`BAB@CU$q=gMKwLQ)zCBYe_(hGdHT_c^Yn=^!j3NsSCG1}S@yPYpoTD`4#MS+qf^ zUXdTafcNJZ=`parBvUOzy14IS!dS_L3@w5SZ%d5w*KH_u4^=bq>)M4b{Uzz1k_nTf zCOD0wL%ODtYO0iun1d|**jl%WCAG%$#r4k|7dE;?c zVD`wZ^-gCbQMbXZweOv~qcg()a=GnH{^f#6C{G`bOhTD$(US;$A1Q4idH}dTi8%I$SdRjf3%Fe&YqEy-CK1Pe6zeGx@~uO@ z{_0bJ=3B5K@8ME)~wdUkJ7$_n{>I8(1*5(#X^!tz?k8& z{1sQ7L_EV0d)pp-!cc!sZt&|58@}lJlj~7`5?YdOcM@6vZomFqKtxv<*~%M;I=cP@ zup$(~WsuNX;C}sSdsM7_2qsm*s6*Bk4e!;T>Uh!ZV-h+6>=sRM>rbIS@j)oVi~=~8 z1Y?0$e;&dsiF`g}9>66YAyV*e{YiSmRr3ZIyF8X(fAVb=qvklkZ#_apjaz@lX5328>&}-%I*BCG! zxk;B>e|E;ZIq^IgSvTo&>yNckEEbaN0b{?%^50MO>rarYI*nfGjeohC)Zq4%xdv{q zao>zL@o*dfUfQ#*`-cs)ttNF6HbSEv-+(d$WxmDaj^y5^({$_a!s&JE+hNykTnYby zG^$%a4B0799y$yZf!uEW0)Rg~Fh{rk`d?_<0ZIsMe-f^QV^ke_8Zxh2Z}FOCO(&@V z2rYfm5<@cGdI^k!R8v0?Mv|mPhDL*wy<7hV|J2E&U_9%y7*eTTx4yrYSPUy0z}iBl zT84DJcLCk{Bsm1xNnF~k^93L`LVXDg?{1#d&OZj(UI>@R(m!n|b@%cxR{Adi>AxrX z!dj5KO$PaZjwpy14FgSj^OdsW2%3)$_U{#ih)5X1ez+1oLVjX{S=_PRput8!KEcO6 zkH%&~KF`CfkunhfK{x6DpGLOD6*sXH?Mi^@wunJS<{!ry+Q6BVzMBz)}p6mcf;fh|tXE9*kBYsY$uU>)A|T#K;A-xdmCM!%OEZDG|K`)ClRX`#A;e>(N=h|#$)LCw`fp=yNg@u9g6p!N#2%?_o@ z&=;|EThGzK=Xij+u*|&m76wCaUgsrkO2koUb!2)_jm6vpb*&*CR0*Xwwf!w%%yV1Cx{N8%1CCAP#VtoX#l4#TDgb|5wnEW=M6e-dLp zFUH_8wZIHA9k$pVs#;b?U_bDTKzY~&wR^4*i91Rbr|scJskF zzIlz^5Vd{<&f_ie%j`Gs+Wy_2I97`S;_l9zoDYjfEp8EJ5Ra2x*&E&>t~W86|6jH! z>UxVLzkM0rVy-tS`P?LUi@V;6$(;wnTf+5LPtJ7@yd_<4{p1SI!duGqHcej92i_#t zo0@#JE4*b~?_J4r55Qa2_4Y`9?hL%Q$|9uFE;k^#P(!g=B+F9u4o$w$6KF*@MWd2C zU}DmuitEitZtyO=RpqO97~bxYMcuF*=--G!$pV7n3sKc4DNVh*M@o`4X*%0`Z6EiPiEm z)}z!*9pD@&R5Lcvs_V&anAqas92e87dl~$W@4XZqVo$>38#aKmFHtMy_0QqH+pSV5 zV~~Zd`q@D2axvBfK7c%Da^hS#94r15l(y=B71qRmMd!T)gAAMz;4(;%0r1yrt(H zX?aRd52U6hK=U6%&~YZ{*qhL^OzL;Wy15b5nj}A?tXrKo@^smI9jsYegXC?p*qnw~ zp+fW`YkI1gPu54Mdkya=@-%C5kke(ytx$K5F*s%iXuLs5Jbr>k(*itFtxpWYq*s?((=v-pZJwkOHaS$x-FME0ivM@K*evS5AdQpSk+UJR-{l69|QAkb>6$-37_ z@rsBUTPzF||9V1?93o0rq+mO;Ozt<@FA>xN)9~~nv5UY?m&9XGvcW`A6i-x6Ub_6f z6?WcXG&LndbHcMTr0UXT6K&mL6!FpYZH+MA8UaN^jG~7 z+-?ekt+;tvOf%Unem+lWk`|9d|3>@dYtqzGrWx3{MX+zVR^aQNeiy6R4%l0Y6?rq- zbc8FJfViJiowbQY>%2&v*O(P@SN3q}a$+&Cu8x9Zy?}nUQHD~OjGrKnH<+Apzg0i= zv5Ie@t?51m?bLMI!-lR38l==2#ut;)w<&y27+)ZzS7G>O8ec-n(uVLoX?%$(>o7)1 zon?HXl*JhAq|P?JA}LeQ@}$l&z7i>N0=~J%mz45hRfKz*f6QT<@|5Rp0rm{*xm~V0 zD$ETmrnM?z%AzTZ)pCaX?H`a&0n;j_QSN1wKBvgZq+JNPg0aZ7NI+9dm@6P`;WM{e zvwGz}Xh@f~$nVxSOx*t=Lo0*2G-KV$z*0?t;hUWkIY|+8kCb>}C-j*7OR^nln zF@r7?2@Ob>R;0Wq{P$H-vQyHf#TU?hi%D!Jf_`FENxDpC@WaAfl+oFOM;iGTFr{jB zRM;oUGylLy6TUjzYLBL1bM{Cy!_uWI>)&+qM14pGTL9R;6)T{vnj85APqjY$8Zu4( zi}zAmSJbS|_jWe>UBbsdA*)*|q53}(Myvy2suDVT1brl3Eq+ z1!ej`K~R5`5WCwo%T(f9qy-+CRt@w=36(uUbjqGz05$uCe}e04XHm5$T~-kMTKN8v zzKiCAk%HfL9E|Uz2^q7z2(%jV;jl6TV=!RK4B&fr)JAhRlCNSgpxCn%|2mZCU@pEA z`kgk(TxE&hkMe3$f#Kr|-v?(U*1Y)LM8Fdi&uSX>+IQ{bD+ttyJ&d$l^8~RPR&dc2vE6$?c?i`E6#K&Z@WK zTsV8H-kMF|?5i5~JPl_*b$*SOqfLKxRv>q%>a9WUy{ch1x%a8_D{_ac^OFFa<22Y| zIwz{MLUTB$t2CL;8I;;~;)oCM6O%Y1Nsy<>n2BTre$K^Q=KbMwSl7=~vAJgif>4aZ+uNtitU51gYl)NTx<$vM<&BAcUQ_U^mQ`6&MBiYTyNXi_`)d@ zRwG;&
    1. r?0fj`HomSYTYAFR-T3ZKiJu5xKjZ6`auuVBw*8H-d&>RPnPz-FQXZnt z!N%7!r4e=BV|=|*UZu{V#@9O~jygvgU!RoA)H%xd`l3ni@(TQunI_qd95!QKc1_kJ zA_e~oaLPxJOGcnI3NHRVJQM9IY27`Ca&I?Vt3@5O%YGS?eE~u2%N`#nl{QddRtwMG)t1{QW_0Fhd9$N z7bD0Uf+XSRQMpBOcY_^yZT>Jp(%9pq%XQS*4!4*NwHxJHD(TYZHpokuPGCfoyd&jh zO!xSBlssG(@?UJu zl<%S9&Cel){Gf=_xJ5Z+{KDP{hF zkS_a*!-|8ZdNhbIpm`MrogL?CzVO&ZGbUs28Ob<)3D&WzRvEt6>kr zla`JigD#|{D}I7Z5Smq-4Bq^rt&iU52oLgs%%fr^h9^8ZI$PK0K9N9~mraetw!VItZ>l*GvlsJA3#9LH+B_cLKddVl_f&FSr?*F(c zgz5x5uFX4$l#R$toaqub1wd!h47JGyn(|>2z>XLnVOh=hF~1~DieXu}`6p`s2!>Jn z)1^)VI6F<^pQN1jnY_;k%!+3gwoK-oZJc z()VL@nCsTvmKB%lk+UFLjRJK6gnKSxV7y;}`&hJwk}Ing16x2Ht9U(pa}@|@1P|i9 zyo=4n3QuNfqsPZV-o(NWiM$I9hjAs)CcN3lM!URMP&qO)MgV{3Oa?w(Y^?f(zh^%cW0!*6)8)hcko=&MQcQ_8Lt?_`ou#0U zUx?}+zQ9<<*ZK+0i;To7QLr&m`cow3PY6|`p>>jkhJ`o56&>)X2$-xv;xq@1Kt0Z^638E z;gi>D;@e(YH5`m_9xGIuk>hkt>^l_x;<@$c=(m704}>Ko&1aC18j(l1S$p_Y6ZCsZ z+6uznn@NWpEBs~N%9h3C%SjMUdnCm4A(j)uU$;boX@&R`m<^(d3HZn~;NRSKC*F3X zCB=c2jmGP+x}AO=#iB;s4y?J450+w=Z7Y1{JG`jwNLK=;ESPo-rN6{5A-su|Dae$U zZ-qfwAY9*e&VibIycN*KI$T4Is31hcnBFW0m_=QSnH>OH5@=}4b_n0|05{8Vy5F^{ z!0)j8-Us>#4>x^;Hc-}+dKz~i+}3v5e2hPY<-tw}(#|%X2k2>UcU5HQ&+v4xIj))| zQD%x! zMfp5%zV-&8&orQASCY@N&MSnt~)@cjn*x^zlmX1z)$6R??KYpW`VMSn!`5D3Wx2wAL8K; z6yXCqM;>KW?qciXFSk%u`OGTN?zUOP81p!lKS2W+?rF2Q>~ck%%0rqWNH5o)&xlIU>pJZO%6tN;m*+EhVn7mC)NY` z6Ab$^B=sZ4i&wt1C2k}$FS!j|34j$nLP%3vT`I;PqQ-LadzaN5jE*<4y3m{^^71g3 zH581Dn^^Hod{eoGo>-gIIbbZliKUHyGbxL4nX)#6vHK=gcRr5IC2pt2@Ubouu{O;0-gXHq0IrQDypC0x@E~c8{#b3;2k<}9 zgl_C%2TO8!Hy_Rb{3)7HD+EHiER94FcN|{=;qpq;?uaPvk##S*QB(j}HJZ>2y2C>y zH^%mALn^?o9>H`pXi=UA>pt1p-yM>T0Aq~DLe=ImAmNcRxw@-nF2DuRg!LssctB<$ z(=?t<0N?Nl=J<*5SV?&dRq7ys&j@O7hek0U2TPgqpB?~z1aQ>@LpnmPE_@?4{J0GH z!fk#NPoVwB<+lIPtU1y(!m0~KbDzbz8xo_so{>3mIJ4mjV(bIPP_j(h60K{IOo*_i zf-%Qusjm9M&EmsLr1Nt87lbZAR)ewKXHi$Av8uQWNmwRpF1T6rDQI71r^2`g*`%$I zPH48ZpScD`?B`xW-Ns#$uv#YPby=mssO+<}FLo2UPP*506WS7t&SaT{Mzc1^;Y?T8 zePE3Bb!o@z>UvGuU^Q7YZ5|j)d|lD3x8-a+s5b9%t(3g^ghgqCe_6!iL3^L zK+Eu{YK5CcUFM=tzLf9FiJ{H`Z5gR%xE4(<^a!YDv5Or3+hc{;4%)lfsVHS-{V3J9 zyJmg`#yOwm=BBdF%gcBy^r4DHy)KL^I$Bx~QTVI;XQxZ84q7vxs_BlVUX?*;gjH*A z&_?@IFEJsP@1!E1ZpagRT-8s4`-0EcD(+H8qa6y1eJRVOZUt>Gso5%=vSRF`zq+h1 z!1&&0xrtX+oISj=%d$@)uW&`_G6Tx$GJ@mo{PqOsSkG=V1+>~8743^owu;${1_Epg zpf^F}U3Ecqp^$D(qigreAwBFP(7GNd`npxN!D1F3WD_qGwf>uch zivTY33Dx9Qw0PkZ`@W(Gy#>G?4>Zf{)udHRFsj<~IXpQA^uIY6)g=!HQq}BlrlNsF zmdgz=V!nz>==VrKxVqgE-MxdTWCqNc<-sMbwga58f* z4AjGQ>~|-a_R5i=;AQw+eg5Z);nlU5VZ_2#*^yb#e*)zIA_%Pb>~MpSJi22 z=STQIfKIhLKgM~fPEk8g<>G&kErppRcOKJ~G|qxMKSVukA46Ib!v!2p81w!5U!Agw z?gJ7o>d+YdgeF|fVd_%1KY#=kcR10kAPgEV=}4om@dhHUgy(-lZsKzq1xjIm?(UEd z@{rJrz$4*GJ2D2yBR)Ef=u=`s-|8Uv0)Q|1gs~*JQ>A2Q{va%gFv2&%*zdDmAuCuK z0`pZ(xT5nhT6_xRJKTQ3Wh^y+lbD@9!d0Dy*Iia#WJOV2|G=v4gt4lp(bfW^p~s3u z*1#!%MoI}?0rrk2a4(B+V`s{vSSf@NG6vuz5?*IAtQxu(O1PLrH1w)w$zj)MBmX7^+Y>U*1yzA305Y?f*TVbJh7Th79Fo;oLMgf8%tEq_Cp=X3-J zMM^@$U9wRUNdT+(gy@p^#cqbD^$BWh1xDCs&1Ffrg>c0_Uj@a4cw{&j<9rq?Bv|~k zDg38>ZnVpK8jPj?%o3*}s-ecX4UD%vRwS}GCtTGfoB;TBG(ig?kCV_J-=)%;KL84{ zG~wCkLdfe3D}fzWNVvrZt+s`7J1B$!_C*Ni$MXl-9m!55M(DrR`JT?N7IatTfaq5kk-Tb_bsA+ChaP?%ir zQy|@zH4tv`fDkoB(0gooAIPUZs?E#OVge7b<+KlJFNntklD2OzXU$q>_dknK-U2rA zpV-rGb4|X4b~^l-F89%7-MK%!LjSQam29QWR-?LEn|;|%+2nRbUB1QsC%6*QnX#e! zSQ&yT5SW8B!>jG8xm;={q%(6+&4+~HwKlh%E(1_j;_6t2+_L3UpkI*@mH#zm8uBT8 z&|W>tWW6nafD(s-kEYd64Y@RPL}4{u<_mj&c>9%4?p5zov^<$9k(^+xfU! zqC-;2WtXcD*@Md=tL@6-D61eeDGrO11-`>f09V2_L@6Ogga>WhCZJfHtPZ4+hq|kH z)nxq+z$N4Z?C>gG01x&kp}(QVObu#D-ff_jmY10efXiq>tt|E&&|77tno0LZE`yzWsy2!l3=w?;=cS+$Kg>a&&rd)Vx*pvYwI{R>fNyWwJeZk z!-u0)w?f(by!Xkr!jKq~N1%QMe z#~mL88th@nANMe8kUUWjoIWu^m9hl4wI1qLwnZW-tg4NVB6s;}3BL?f`hHSpF%mpx zlq{4oFgRjQiNmZAx0xp?U{@5TM#M%!g18b?SLkV)SHWO+$4C;83LXjrzsK__J!6D< zAdP{v^HASFeH?1HM!B<-r-4cz=25kPLo@}s*c%nBdR%u}JpCNTICS9Imy~PR_Bn18 z2eIgZDhhcbuR+N!D(bA++1=QySiczg7|1aXg}uEPC@n@v+Cqrs5AE+N&a zyc5+%`nmqQoXV@&$n|&qJ=_*n2AB`{*uoBQTUZ(B%Fx16_7&PKNpoeflvVx+o6O4~ zhZ7RJ++e4oCK}`apD_N%m9R+5cqz*`g1rX$E+1QI%Ac7f>5lNV?LT}}r_4;5KJ8IA zwiV{(F%&H1+mhp-pI=b79H|ZD_GpwX zxunG0hW^5lFpz#88r_mh)0n)QNf`t9ksOpd+LBBAm}g<6X~~y@V#1G-Lo8n{6xry7 zbRS?VNMOXlo%k>`?vp;3EQ?n@-uSpQ)A7Ym`m~hL;l+iMP{BcM2_0QrG|x(sQ$hz9 zKSv&&5<0fH#45ojr^GCd0WKSFZKs3|EPkP>96(eQ#xK(OB9=aIC9Kt|yUA2f#b$_% z1oDuFT3zHr1d2N%dts2w0`Qy%`mK{z&nE?Md6;o3np5S!3GRN6AIWKsG0KcmIL1tobV8CQXT~M0m zpe=F77(ZUwnq!DDq9$6@K-_Fr$m_TkN)-qq-Eu`CEc&e_z zz1jsdDpFsBDrFyThdne$FFfyAjLlf1*$XTEqDM7ZUQPfu<&6oU5j6AjGMB1e&oIg{aV{glN3kRa;Yci%fe2 z1FSb3VKHrSj*AuAHfVhbp|(MFs&M1rQ|Dy_{`=Y?|dOFGcf!R z@5ar0hDtI5qan`-^#2%UvUSc396=taGb6ykai(g?blsF>C&^&#jX)WJi|YOf z?jQx3D$Wd0kP*myk&@#t(QWRBZ>Oa09lTRbrmKJ(K4u2ElV*l{Z_$X7)wpK_xNBiX z;478TovH4O0QWJ(S469bn)|nk-rJaxmQ8r)mV6n3yKv7`cc!{C0^Fo8Gr-*sGu-<~ zgvt!ut^6U%r-sZxYE#}j==}xHoe}7z%+no+-mCHhchX&^HSb1FPNvJ`Yifv5@4sj$ zBjG(GU?iOtb*hrtO5Nksy#jZ9VAY=Yn2tmT!krm-0eVn~Sk}l4aCIyr@T=zPFx1+N z02f6v1A`UiS}8biX9R}no$Dr<>PA_7P4|A>Gn5}>CCv+t2@_}}p@ zOV^#BV+9H2k9+X5clcmGiFXUSZqh-n;E6C_Oz#5@Y(qnY{!+iDF6m*147Q2bNqY47 z5!3Rd$!w}y&+yWYL1+t%d9O30RX^%QtcX&mj`0KA-86tQAyoHiL@fd8m5_(O$=6-*D^m*o%^9LfKNg08Y8z?YhZg3vt zXOM;EPON1V@4-92NRm4dzm$ z@DSzgMpE)8?&wR#)BUtc3TvnzRF9G0p{SAYjvRv|Bd}KQTo^%aOri$fkZp4pGp=74s2TY|qOWma& zVNfII9Yvw&;%Vd)p6{$0xSR|3l?_CXz!5y2ABzZ=zA$ASoko>#GzP zF*ou$)jjoj?>+?d~72*N7R?D86_~#0xg@2Ca3Zan@PrM0A3jvx5@q!%CDv3(~^eV(_ zWGx!4QC92@e$mCaZXvWA(1%_qx^OrSKmExF@Yu;L8892Hvyfl*SagBK6B^M=_u+km za)-n16aZEVm$9BMaBqN{CC?GB34h}pc$VxW)B)n2H$nAi=TL|$6gR#iKXjDTTsqcvxl&un5sDYFTgjBUno=xD|ORL%|9oOk>n z?W2OUca`&0%q%&@qBsubMO>y7>B^o)YRU+7L*>X49z*Kn#;5d2xJ&@LvIpP^of+=P zjw669`M5KJH3c!v3r1ITu+@^j&9?9dG;%yx9zVg#xMj)0(g->c&grJThI`$=srGqi|=!CS9C77~7P^ zW$d9VJDGbUZWL|_*rc6PA8;p+OjmX?HwWA(+>5VC3kU1c)+CQiS9Wq?JYB2gNe3xk z1#pABk0C_9%f|hoy4ON(1!wKX?P=VyWD_5qU63BYWlT1YPL@UPjw8!iqhVCy!RPd@-Pv2gMAO^4YQok;2BY1bP5iA?Ieo#-J<(utI(| z9q~%k%FlQq|hNy}r zj&h~etN2Xh2sjTq`-$sEuG%iHlGo9cIX^+l00S*^J}lj7t{XNTA}2A{!~51_@?fru|lTH)@T zfWVH6SVfntkfr?Nxw%~pgf;S-Y`|iLbEkSyul6CtD(Q%LozkGYap@Vhkn1ES=xRkr zCojNb1@kc^8CjAWlM|;{JQ9h^3)zyMZ%7OHHq($$DqPUlHlozEDGk#V zX9TeMxUk=H4T~|tQ8OwZi9zQ*Pa|N}g(Rg#A(-3f?!nPyeV zqT324gSJXuBY4~eGps5X>9&G36>QGpD1ycH|8*vHJTQ}9Ry_niYm;umXG!VB2ww$) z`nXJv(1n8F5rbL6qYs_-kPOO>M-No9BnwZK^8gr6cr3cI4+d_B!c5(?WR?C`;A{g0 zBT96dd7E&}e1p7>4Q=u^q1+1cAA>A;fSNyq^EfVJpK7+Yh^!n4Gm~^6E3xMzCjeT-sk{NIWP%g)~0UMiuXm~jvN<)AR`nGsp-G=F9 zeXZNLVdR#z;EV=mCN5(nUHY&Ovl5TmbK$dsJX9davjMV%#|JnoAl>MNpbHlBz=JHg zo6W~NkR0-G(;{RE&zf_-g!nfPqRWr$I($};XTb%ZRb`u&Aw*(cu`1y*=F#Q0MTzlF zRrs(8I79FZwk#>T93h%R%45o-LZJK_KEXQ4ZE2h_0L@O~_xr5?g;tQ^Fnd+*3*^2S z;qo7sNQ*(C735LpnE^{%mp92h7~%4y^9YwhE68Kdv*gQ>V0{DUHC)C#x@3dA^E#IC z{`d{;?Knsz5XABO+9Oj_tdMs-*sR{kbj`musr)H)vb?(_rd zS!YgDzYC&&iigxlJdaF7*aslU#AV{43wf5ItyD6bu;(Fh^K32MRk?=fN-l?4!9bR)U8KRq0b=@Wve{E{+4P>fP zA?S+Bq>3)2YL?>l*ftJ@WW0xK+Zm$Y3i7DfESbp$Y&Ha|Jd!qG%!z?k`3EVsg3Xk> ztu(mXA$Zs0ngQEZITDXyS)w?{fL!oUy0SO2+;SyLuH}a!JHJ>(aT&{Xc$dA^=3moJ zMKGFpEV{BQuXEsH%{)?m;W|6-P(-S@K%}@Fs#Y-Qz`uoO9W3Er9qX z57Jf$+8Y!E^eV*MINg|QLS^a-@hag??9QJ6Z{Bfzh2)*C`=S%Z$PV>7vA$y!V6IY~ z-m-)TXgVQClW>_RwAHlUkm-qlvg9@7uu~UkACIBgyF%BaVheb)yMY!wBt?qN>Wh%0 zAeiKZ)O87@Y%z5|3GqS?icI?7h+p#{onoPh2|NwxD8#0cIAa%Kwqzb1t3wr>c#@cQE2+J4Jz)_t?7Xgch=GdCS@= zm)%;{2zW=2quCImA8Q@BXURu-5p5cr6Frhw9k7yDQS%B~FJQE^O199*m%!A{g2#C= zEf~0_Q;7CQ>+Ckx*{u*9%C6HLp#Le9TR|Q@zDkZzWg%>y|F6S*){NK%xmh<&&4^u? zn}LiLtX#4et^`4ITqgJE^1IU3O6I{ZL7vHyC6Crdh~AJ6@j^uU<>rJQf_Ump5D$BC z=0Uu~gXlu#nI@aGYFjpzE*--XjR-w(4ImoI0g62z*Xg@ zko#$b+aQWdp%q+@JEmCZ)Sd4rz-I_1wRCA}$63`*Ni2N$Km)cWMeqaDpbVoI1t&4l?4J%`#_=rvLt>4 zfENL5$7L+1OLGzmHhhQi6h;(UOuISOISBNO$JMb8a}V6#mH>yn`G$e^D=63uH?k$I*_lj>uCHVHf8#bu z7#m_ZXrumB(xw}<;Y7x`NLTh8;eSh*GHimLR{*|?%R9HnDAYP>Y)P1; zC;cE-SlK@V_dG5`i>~b72<4GPpJ2tygD*PW8kuDG9*A_T(tW3$Dgd+um>Z1d0qgc^ z6q?6mmCR;2g`-&;#E2Y}|cNH;fzPHPp7@ zAIKA;$m-tCWx4~T{}4_0Y;_}<9~DmBA<|7LWyuW0?c9JMcdw>7YYCQ9FrVkrSbVG4*J~gXG6O~D^KTN~@dpWweiZx$-;B1cl)ffk z@3CU4_Jt5pf5p!J8MxPbO7+hw7SJFoW~W)hLbEdmyq(~D>+y6@utFx`b^n+t5(`3P zc`#v)hp!GOMJHr@&G zT^^DWKk((l=D8s|96jlEH`;>k9}Ob@5tlV zxB#@A1p2ENfj98LIP^BN(wrqFCxC}HnXTfuOrmu{VxFq}voB&|1bdrtgnt_-bv>FH z;Un9qp(Vukd5~&|sx163OXpEr$w3V?i%&er(|H(@C%uq#p(*B>ovY+wHc78R(x68> zY)#z7{7ry1sD@B#1&1l^p}Rr*7y{N2pv#0FgJ#KUme02k{EW*akS;{>Dnes~#wEp= zk{Ar*GPoJ2WCnQd>niES^1ul|c3bz%c4!vc`2qvx%{Nr&M zy}mU~=pz<@zQmJSlKgvXXT+d%mkmo|lLm~!aGh-4C< zdszM=^Y3rvb~R_6x;a!tD5VFDco9*$w%w~_AH&qbhJ0RQ;)aMGInZ{jch;J570!2r+bhN8vq?10B8ZkFL@AM$k`vXM|gnv zR!H{dz_a9oA%G4;e9D7Nr;{Z-gwFX1;@sGAD#{j9(G%|X&z#GWd(*%z0$vS|t7=T@ z3yqO^CVgk{<1_`QeRduaF`FuSL!6Nva#gH|s3^`wlxg71&CY|0?+7i0c2oq z@w+!cXeH7ALHzYiQ0jevE<*fg4rr@fM4lFUL!7)x_)86!$so=4sOK0)wPLqk3yiiN zOS2}LwMr)PnHdI#)*}A75TY+M0yi@m)QNm%APF7hDp^kY;s`y`+j7C4LM%|>zDjnJ z^-Rw42?q{$HtXhQ!~Mf4Tow7UN9x z4)9mV8&6&v(@>767eKlLmnjIk+(B=(AK!+DHjlTe{kRWqEBFeY3k~d!57b}PXytyf@d(E4qnnhb=^t`P#e-7xO5et6B1p;r^8rB%vDk9 zslMqi~}7 zQad==xjFjBh`Z50_66Klki?+BH+Y*H}v$5uQ(Y{c{F3L$xBk%u+nZ zgT{@M_OxED-i#1i7$S1YomrA>x_}{|atKwPCZWsRY$_j!QmJl`Kg$Plp<5&EciSkWV%-o6Jxx}t(RJrJZpe>X+{4`p8hXZ85~f1i8r)HErhMat5kQVK-~p|bB& zvV1KmBug@)gf?r7ZOWGI+k`}t5K>K>lqrpADp|rL*_V*9mHzMdSw3@@eEt6S^_uyd z`#kS+p7We@p7rzjJol-9DPAn+jan?=sqhJEVqa*wK6pN<7V(XafqrkG*XEYpSE z9@~zbcT?r)7nAdDE#h4SW*QI?W+CY-it*}d5Xj_ax@gwqbFDcQQM7FKR3& zNL!H5xTVK}$go|MW8+Ns{f}J;Zi9qw+Xe3xXS#;RWO-*JT!e&Y!gbdV#OoTe<%b(2 z^i&Db|GkTNvJP?9MLcB_JKfM(Oev)zo!wT`Pvps;$>AfWf08PlwZ0_Q^hvqvJ3M!f z9-M}M1H^4%9wz92f@(wp4dajQV6M|D#P-CW8dM(SnH~n<^_uvI&w+&x|6&>E0FqsU z>2j;M>5I%|!I#CFzPJk0d%aOSIkb5QtmFR|>$l7`)^A%};H=l@ZUgI-(1!x10Wu4J zsv;@G*Tc9>4tyOZ?75Fv-Cl;79y;>%4tX)=nJ@qp?_2RPI-WHYzT=~{{C3G8cYcBZ0-kcVubY>+?%%} zYdVr=M_Hs$%qomkct%zBPLdA;wHfJ=5p*ocua{)1_U`%hlYih#tp0rbmw!{j=M-PB z4Q>VCPwTGYCx?A0^GqaTI@2K*?TvIsivDge!?q|^_hinbXN9^aHzF9~*<`1LR(F8C zA5yNvpGub9M!4)eN`4Z_nc6l@GS#$gmYjkwDcVjBJB|h8Rx+|5$CAonFCY^H2(rI1-IDM3g(VWD(Qk`Ie$33)}y zniA{__XAi)-oT{nO+e*esdDqSDGoU7!{usF3dK$7{z);>R`2NXkVmujqFQ44A!u5pg67NJ&6?EfullL-;N3d z@e5XOqeR}!0HVPyUFs#7?k3@z@}U(H4on9_&U#MO3z2*o{={4SqJ4s@DchQ}LgTTG z2!TxP68KZ)iSbC8i9cD&^X(0hz|>R;QCEqT{SDmYl)YQ>nKX<`cSG7Xk%WbQBxzkF ziTx8IXDczUv{rkK*S+$LjyabxC8Yxhwun37dvM z=1OG!ia(Lb=O9ETpIK0u%!_3Hi7zg58)&>lfldGVWUEh>DWTI~$ZU83;vau1ffPmw zzU?|C>@f)W2O;Hx^n4m&NNnddf$6$FEQ;;CHt;112=6D%KVJ*xA^?V_GehpE>yUL9 zk{^z;NTJ;Gh4p6Y^*mA*NBN?cmHR-P>9P7(3wToz!0#jBrwB~SZum6bH&hFF1ipN{&B(cael$`nf_a_v+KAj z!!HE>P2%4XJRj^AJoWhrFUvV@v*GvLTqpJm@rQT7U3Ags79`D+3amF!MKP+@DeRdB ziOml#B#e149$OH?S&3gznAK(`9;J<)ueEPv*Vz!=2U5bbB8s(X_A5(c^@D+8<51f9 z$@|hED9wdrl}1|}G%FD+FaaIydL~4_%hGl}kaeRiUXjwsu&06Av$PA7TctFIpfnef zRT`hdKjH}-)@1^&wd;2feIyDBw@PVzD*x2#IM& zBUOqa1*&*{q{{r@MQ7OK&A9mIqcC^&kCwlrJ=T<72GAn1pJs`V%T zPh1@MJo#R#NVIKwWipvCmV@rd} zx&rq-a41OVlpA6TtlEFrbuOTrz#o3*a_)4VklRd@iJE-3VJ8Shp;g*NqUIeIXwG+hi1? zG{`9pbs_0m07`M=D#TWSS{C@u(JrR@NCKv)H10LrLJ>ChoAsv!$z-2Lz#M zt+_iMD_#Kq;*+;fuLp0f6U#pos!Z%e7f{Y~NK#);HShu$Ew{@Rf}k&R|8`$GV!9#W zgVB(tz9dY2nFVuS65_sm*<@@=_2obS)R(J4sV_e;U;!T4&Z+JWwbFdK`!@IGmj?X7 zuC)v6N*(CSVL+)bp9E#T+-ksDW}VvUzI+SF@{kEi^W|SAA=8&-C~}VFRoXSTOKIRM zYg-|9QSekm0LF$+FpIXp4{^9mp?QCyT@Q)n#g?EdVaVa$0;eKrnKaq%2I>v-)SA>M z1Hm?WnIUEfqN^b2*E%83+NdM0G$j1m`!M$_Vd~c`nERCw_v-+YQAKxo8!ZAr{aOi1 z{aS3m{0HdQHc%_gue-)kX=$VXHQ;2s)-K#2%F(Yk1Eqc~0cC!jX~0rvNcZcTK$eG0 zP?}#~HqLavR!AGY!SV{Bx3|x~SUB4D7|ZkNQyi0CIF>zU)z9%*z6IKNyLL?E#U`TS zpX>n?bjR+3_?6GJhPbo z_Q1FX01b>WxgHn}tdhXkTh!vHTnU5@%sbTa*l?_0YZtyR`Y|^81EsMs4wS`)1N~aN zN2v_VGX>1C`2$epS(aQWWAjdVtPfhSvwMIf#?2prv~;@`;FP0UYaTe-?b;FCI@@t} zzrr33B_z|Xy-`|Z*BJn)T_@Gev}*~0)i;Y;wCguOs9js^@XvN_FL>JZ zcA(U*&w=_EyS^h}+Vv+;|76!T_5RJSY$N`u61#Slh-S+;72NXzpBVE``-kJPyour2 zu85kj0U4!XE&jg^U};zmszv?0SViCyY5pNg-G?i~M5I-Q`|*EOU|L1sgKhp1)bPqM z5NW01GWvwi934Qt3~Fgq0K0d7bdH{>SgkcWM_&V;7zTTe<#WG@m?L=o26?f&5!&I@6Imd8 z>|2qvOc)$h0i)Dfb8rSCHOvZl$n%=~V=04u`g+Lt$G)f4F@(|ng#An3Lr7NNgVLhD z=fs8{vKKeX4A~h3R{tjDF=U?yLi?VLpmZYVmGo=v!fAqM$R5|&L-tBg|I+u|BVhJD zFN6B0zULbX+Fq<~w@=?BcD?*Kw`;wf|A$?Ni}`6+!v4jsgk;*a{i7*%9Rq;&={GgW zv}+N8)n|xWwCkHds9m>$`X{?41y8$PxQpBMR#5+9*U18=U6+CSC%eX*{+nG>`}7&8 zK&>^6C8F7g8=K@>pU&L$KD`9IXdH(?aqZI^@9K`c7F2ql9^=zh)j5KtBUcEPeR}QP z{@IZ$j;CxovMW&9r(XstqfgI=@QgnFE}&KgW@w*2gIt+?dUL4r|JA2=VJ*B*r$y5H z^de?^pU!Om{7av{3d;Ro`tO2J!`|-w=@a?G+((~mG4bp^%qheqj{G-iDfkR0Hxj15X0VL*V=`T37*mXvf#P5 zwic9iOHUi{1!u4+{GS45x72(uc1xK!4e)c2Ck`8L>={#dHEgYAT7eQ&0ERvD6gTWm zU{}LBB+sBQ?0}OAqhSeC!)C$Uu!Oi_>zjjwP@In zfKbCWZs~^oz_6dWoeDRLel+YLptPHK6qFfuM+>=K?3&S4lmb~EGC^tU=3oAoO`BLH zdqa2FblRzI(_bN2ZR(I+Yiznm>PVXsrZ&xjxlIXin>IHYB{Y?sY(iE<922wCPKNXRy8p%51u~S)`pi!GiS<0W(tzz5s*<>zAO^u%{Tdr`xG;lHh6B6WS3^!}bSd zhJDzDJA)baJ^|CPGeMQ(u@Gy?c2&cEM?vhi`&#mL4SSf?v`P)z>kK#Sj{CV`9dcxi zVXqhaGhzu-!)C$Uu!Oi_yPAxGk`%+f3V`+k&+PApt#%I(SbdzRMZ^9Ggc`QZ0dCl& zRj{62YZv}0`q8jsfKtOw2W5tBZ@|Nx!3?`nz%*<%sPd4BQ^W4x-VD2kv1b{Uv%Zt9 z0wt&bx`G{LXydf6JJ@yF*TW#20KrmzaQF0S-wFVA+SjIoPy13?GN*kMqtm`LRNA!f zB9X*t-$hnA9xRzGmiE&jtqfY07H8$e7wgo^%R~e;P$+exBW%*&h4M_K(i| z#+a1*?HaA-TR=IT`DH^=SMz;<)0y8r!ok)2y_rJOR`WB2gEPN%pq2(N+Gl=?I4(Vo4nEy9vP;>!d+6867+zo_y7vwSuo-#LbhBpWR z?ScwAdEhQuq4g^wu=;ILi-CIu5ZVPj1xow&3d4S2*V=`{1kb=t9Oi-B8kBWGTMU?E zM)cr4MZgT+B2eWa6Q^C!vlPU>{TmbG;c5$do#CBr)|!C|!1f29<%V4jb{#Ywa$b#L z3wshq!xE;3&4RgM330>rG8vmv4SUMrZrBY+xMBCUI=6qChTTonqG8*0cEer=3JI`^jS1FVAtqE(5z7)*(Y{47*hnr(p?G!)C$Uu!Oi_N1BWx6c-ux zj;?OlSG&1kA2g+B5LjII~l+_1la(s{w@rgRa3)%%EAG;EjS-LN--(ulpluzlT5h3iB= z8umlMGh(-aGQ*BG;5cV6!|rtgh10MnfGQ7}I5q4DvIm3I@YB~cIKv(e7 z`Lq~kcu#^|XLwH$Edei@M+2!F2g>n)Xy5Y#DD`9=vr_C?dUE}F zv;#eP^2zSW+d-)(9ox_yQ}~SF>B)J5rzbanvKd~X^~U)S?t^6RDelGnKw)nWdFr_y z_>Rx&&^*O+f1!k$8D8Iv?mcCOx4$0r`$uPZADEO4c8z9u zgP@$w@UkJPGrX6jdfeOlL^wFZ`y^9n+6*t8N`r8Qw;!mb!Hf18-g24Yd1?vtN5Jar zt`H3DoPV_f(l+gT;6?-pFjp8(p5#I>OUqFW>9{gAg3 zh4kew1SQ7J81aD|V;C;u>w5n^jlu9hT}=E<@YQw=174B&;q%CQ;dEAszm@(0C`1|= zrWi2x9E4w96@m9U!@;M6GH}e)ZBOu3^`KR0pya6$_&tIbg&R#OVgyehF;u!I2J>e3 z(%@At;f=4G_gx`sg-rX3#k7MtHC!{^w0bGrZ)98+z#; zVKm<{=q}$U^OqDy^JTrU_`WvePmRaU1E&S&U3)HOaF&etP+#l2o3B^C2ju(V4F2}j zy(}d$u6V?I27eBbBNZIR zOV7{&|GS4n@V`f$h!fw=#RKMeEOMEg+S%2Z7qF}c>q3vx(0&I#BbX)*4nnig{-#7T?EiG3umRBmjWh;1@K4KC7Ng~OokBZV2!g+&M%2ycVeY_hW1jyt}#gFo0q5J4C4Z0I>)X@KvX!Y z4^4OjAdlheqHvmJ)=2HyJkhs8{g~)&1Ot3qv-WLT<5$fZvZVOnYxpoRf88#28btmF ze|oz^4hh5}nFT$B9|!Ag1>9xV)hKo(^1>SYn;Xa+&RQOLI^I^nKRV0}JR2`D zD0kxWuun#I&g-EvoQ}lG&=vpZ2A<7FDD+tu_{(|4ChSqWc04C9_B#u!buo_0kl&~f zRq-;zy09D!B?g>o*9XAR2H0@ub{P2EdNT|-+pe3za2^>h&tjMo_~V$d8<24u{!$(Q zgQWXci7y(bA!wsi$&wD zRzk4KL2LJKYrG*q|7Jomw00l2rjMtDvv)zC^)?j!34dzP=&&CgKE7L$V-#P0yy{LY z9`;DKs0%i@nm^TklwRqf24l_Wdxykl2u?^Tz&%z2yQJ<+RH}?9;IK8^9FA zDY^4`Tr=?O^bRKESg%<@d@5v>hW(Lw7ht7{%!OucRh0pT9!`ORTUj8)ry#=15IU9+s&Sx1shkYQZo9@tt42kV_(*WuO^TUxLXp~C$jt-9k*xlGQmwiX7U1RbT_C| zLD|~Mk;9y0ujI?Z!A0x!!0Fm53+D4nLKv?bA@&xNQHUDk?3HW>@05mZ$e1c6^QRuF zKrIQ^$51%~FYPHP}XLNWqCm4tgQ^Jh*qNQg)F%&Ty3aR8%LgD-;3^F zJ_`en;BR4|c6JTTd=sk`~J=Aepe7c5o7HtPnml<&f4UDaT*`PzYa<$bz`B z2;paW;Mx4+O~OcqO)G@Wa3t32MJMrC{tH3P4<)W}uO?c(9K7hYHwVt1LbZmtIia#G zj_tt@!&VsjXS+TR8Rzsv^QgqXQhEQj?nNx%J23PIHBU78(%>_wN!$1w0aKgh0;V=i zdQ%&h8?v>*{Gcb@@tMhD2Vlb&8#sSTH`YhH(8uiB4>Es6S)uurX$|}%q%Rc3+8MH= zUBmwIGcRXNsNCUw+*FG|l?4a6Ztvk*m{jC)E5CLmA7D8UE(X$(+$|0!0LNNEv`_n z0YW!%o&#lj4TinMuDJgxc&mi?>Ke`vOHvh(smq+jMKLn z;^WRh9T&SOwRBb-07Tw)^T*>yU~J09Y~oA`&W9)cDh)L3x~yjKxuPBFJ$H= zUi`?`3v&aHj}8|t7JFuLG_;ag+52Hy&DRITS{xZ~GsaOaV9(^~D5F${$IGCG z4w2JA!M+@}9C^2M?3ElZTCrc#VzVGM#p?K8Y`imAtG$vth|M^@zb7Sfd~be*kMCV9 zmQS#2&YI7pyp-|%6w5lxA!+0LFo@!Sa+8%Bjqe&sIst>dpG1I^7^aHe>=M6TG~?;y z^B_cP=a8q}07KEVX;eaJCAN$z%iL_&aD4o4k;Rs=0l-pe5^b-fRCY3%3}_Uk(kK+n z)<7^eDNN$Ow+9`n9H0LpYIJ(4ndblnzx*3|nB=+J(P}ejKVQ z1ka)BS5P)oU2DLboFRRv+ND2-s!UMYP}RXWeW=onG8l||${uGf0d^f1*|iYD%fc1L z?_-tnuMX?2%bfmkEcOz3(0kc(AB%kK=QcI_an`fk^DzTm9lXa{4bGoEXK)vGhPE{U z0cD{yMSuwB^tCLiY}x=QKeuhCq}+&|sKjB{;*kjar3^Fnt5Eql{9z^@&44i{KS$1j zS{HuDm^0F9`eI)l1O}o0w?al(ePh~~v(welm~&E`dG8@%URd1_ryrS!8H~|W;?oB* z_-Z%8mgoQm!=Hc@Uc+eJ7jhk3VN5v_>Kq{q-H}OHX*d?tOrcmI3MmT?KMD0TyU=vH zvr;F~b+L|BNbAAZzL$q7DAk!ZF-RxWsSFE|h)sX|j}=k-wke?YGXUBW#zL9OaH0Tt zmOgvxLJ}FZON}K-IhTUY>+J!%eer)+BM_J$KQc051F8}rXP$mYWm||91+>Hw&_s}-Qk|egWRU=uXCF^q^?0> zi@8!qcBh1?O|xKbQ$pOPJDQA&RGZ!cfZB8!D7EQx2F!n%HoZsGqD>oK?>0RRl-hKT zVHer8c40Tc)21&7o;IxnWj4LfEHWXosXl@9tAKfzvDqM+H4|s|s*s0IS*Wz~+^`a= zh*b`lT`aE<`iIlw`wXUCIam$?w+@!2pq9&EnF@{uN(FMDB(N-8U=pK&Qa7fzJ8@*g z>u>lQ>>AF94;C%h`05U(7F@qx1*$AKsHX9;Q_;NwZG4U>W`)j(zk7oR${P@%K`B3Sk;3SuhV2LOf7Ln2ZYg-y2`M8$3|vg3>^#Wj@S*g@N*#sKr3Z8RCI* zG$;*}Muy$h{a$#L;29_r1mDD8~h z1BG|ikfBqn(N@#P-A{$_{|xbH=?4)SE%$@csZ}OJ6fp{B#1LE-T;l&FVmJ-xU}}18 z;N}UU38z=(BJwzcMAHDNiOwSWSl*3xMR)RE#Qu}8Uz@=$Ek?PW%iA2d8)Hz_xm}Z+ zSf6_`xD(QmtqxCGN6k6N!QesUMstu3m}&S3%bCUno}YFT1S90?(9#@0F+&}ucVxnW z$oB?CF;97Zx){RTdYqY*It{`wI!H!xCes{+*GUY6eclzE8=&AS1s6mhN6`pa3#+=Zd`mY9EuS)rPS7 zODwVfi07MzC)xG3oAYANKxCM9vui4czimLe9$mAOAq&w=!{7030G9?HU30)tMmUeI zxfxVhIM9Iqcyx^ex)~7CO6BO9|B56YUGotr-5+-FAqK|LHIG9@-Mb{iVp#-c!F=yh zA>6ynf_Se*2tG@LE2Kx)YzPf_zFkNZTG6-K^>5%Sp+k6MXqv5h4U4=Q63m;5goSci z&*jE?qg_KH@gx9R?P|bE1FL<&aIdyA^fv}n`+i~IQkx7~?JSsATOq7=7R0Mfh*aB^ zl4|4rsTDc0Cc+RsJh^aAcnAAVTX8^7v0zPn|BlHX1hOt&W5bzZwEtU!76B%F} z8K~QwVFWAAF|0eN`N5@aXAf3(gt`5+A)HCC)Je=Rsqfl#5=2~%(nEvcXTl0`0J7tX$+$o!d1l^U|v7Z*x(5|6Tq5`Fr%B~dobg0jSVOL7`76_ri zxGUAdWVCi!yC!}YS=^cGa2tTyg|xT)*i0B~=R~&=ERS8tg}`VRQUR(g9B06&3z3o`K-Y)mM-P>gk zP}&_iLtmG=B(JS7FowvW?J^7I?NT9Zmst>RmxSQ6G+bw8NW0WI+?|$G#Cq?Z=n5a} z_&OL&dO+1!gOmUg&AVnGyHvL38{FaZuKNvGL11+o5yg4ei9qP0=T=ZU@0w)TsdmNr zH&ScPyFL><=Uuh$gywoiRj??|vunnpXI~)8LnbI~(et_$^BXv*1 z^~s(eNdLJZJixYIkjOWyTzrK#!ckDU#jR-TkB&-f>wh8L+Im5PdAE&XAo3)+6HLT^ z>>Bn;jE4kmPoDv%?Wx;n8pAA%dbp;hAKJ3J0fganO)TR~|YI76v1AP$ZY2F3vyG!C+09tR3x z9ArV<5rjw_xKb%`;7JvXgI0+r?({f#Ml@s`IHcS)+%^7&XvjDqOyeL6=EW1@aZqV8 zVy~sdK@|Ynw|2YRL0rS+{_t*Fcp;2LsYlj>0fvwjqrbv$I3g`*5o)3;v4{owsg zD*M*Iz#@ICF0W*Hc8uk-Z`})>ndHm4mfWVW4rz6`D@9B_PrN)K9*;z zgNG0cxXp9Y3pfz!d(EL@sq~y2E$mc@Ni~Z+?+#ET3^y>+DFv4X0VAt4vd9fnM4DaEe zo3pC-sRNYZ01F*faU?7_UKxab5$5)G{b)Fj`=& zK|jE>2AQy^283{Ob(rzfLV03&PQ5Rj8 zl0iGZESPtE3Sq~W1@WGT5Yg2Yl8(=pVomnLQ`s*kVqHvu9(Mf}Tt(0%tPpj0rur%4 zsSdXkPs;#@R;VJk6CVLYmttRonjc(R`ch1uI+3LqPm5d^cECbUW~u{ z6dt`R&FzmMUB`^RhP>RaVc+CFz^duK1k7+(S^hOOxHBT$p$`D3>#*xBzl2e)s`rX~1j0Qq!m%7jIWFhaPv z;v#Ib$%wrUD;$x$QRHv|wuvBJfW@p@?TI-g`KDmF0PFNHt;Ic@he4Hv#s-WgjF}5C z2lS?-PRY9WP-`y0W`kd~c1Tl`6)nIB@d-zJ%Ph2OI6OH=Wbr8DPem(kj3g&`@HoT4 zE_F%XG-2R`gACg4vS8ls6vB3w1@U%A2tG^0F;+&(gyS+xDq+2kOfI^Y_2#OhH8j)( z*p&vU03@0$UW{y=BrFD{lf@eh7@NgO!c-B(Ny49k;;E4OCBsRcGiairk!;rEb6QY;lAqv<7a1WvkC?frz^`W%c}yXjFlqjlncOL z7CtdZ&2$A7Ssh-r2E##mDp=A7>9XLhjGBy3h-qO02(jCc6&M z>n+f#K`}a&Zy!$URDMOet@gSknfLBvG$ijwpKBsU*fkuJ>^6?}<~`|=kJJCWC!O~M z8F)|H83q^w?iIg_B1;4BNfV~`q{j-yd(sqA791Yklh#{Q|8!4!vD}k(CRZ-HFI_43 zrRT|=W(Rd)ux|^^pncli=EZX7dXT9*#MRz{d(ymfT^Z!gwRam{)O|JfxKkvu+t8u< z8&s_EToADx0+KjKgTHU%yn(<(W z(U2a%Q`!~c6>+fd;XovT}t@i~TQsQpeHNI8!<{FAH?eVi< z-lG!YYpAD9MiGjO?AmgY+x2l!YS(V2^9%y3%S0`9j~fL`yEcE)?b_3@=ewB-ZxcN2 zIsz!Q>(ijju63;~HnMBR{?t++%R?q8t$XbM4<=>zxX9|bi6%Wh+3x|Gl)nV94RUoR z?vN!0#XPo9VC))uJ>^|vCM@b23881Zm>N;n$md9PG5?8){?Us#A=%_XYQjeH7WlQH zG3IvthLplGi-s zf!Ikj}ED--|z$wmP4g5O+vw`pQ3}Z19 zrw#lh( zKUBaNYgy44Tf^;K-kRXrb{O2Wj~OT232TKBH}`s1hc4zJj?kxq#fE-rCmRYr$Z>?e z&hvG|O5ISHog(Ibhox*Nc(78;Y|ppB-u5N9@9>3Hkz@U8hhg8hEb1q+X8~)%Etmil zSoQkb^)*yFjF^CfQ}rJ3sY!l0Y6`aw4l)eu+y$vp=aj93vr_VVXXJD1z{^P8Iyg%# z=J$Z-1pZX|gc*rgk;xiu*Co*4dB_Yi@o%pDbh^B)cFMPSz0ENHwQH+qvEU)L*&{xQ zc^j`3g*%bHF_(Q;&AFxQJuJ0XO{(~p8%z78lzFG;dwnZv%IuU0 zw$#d+)Tqq=q?Gxm=X;r7)s%T@N|}uw6MI-a`&-Vwn#vn8u<>9^J-#M2D)Ww%G6#6R zm$|j3%;JymjGk`~HuNF8CILc4}u$yWf-AGZ1lFgT*M<-LmxQCll5PY1WRJoW-# z*W_b>Kh1Jjfkok5`)2$x=*yElcA16Wp(JHD&eM$hNPIzZL1WFi&exgMjDr004( zX5a-Fi*a(>et@K&>+vUmdag(NX@0IpDof_M9u%YJdZeM!&h@xVB=KC2XRYu};PP`l z9+zCMMALHZTo2~zxgMU|evZsGzWgui#Ipa7Dl%4CbyV;zW}Glwl#mz5A0o&DKza+k8Z%}p&kQ3Ee&3@AL{X1i18^Z9M14Q z;_oN?X-l-9%N+hZ-b}hM&cP31&M2OSX4%_Xz$bPc2hqEfAj~hC#89B5oEa>41E@6_964c;DB3Kzxi1xIP%o6-d9o6@O}yg#t8k8=5@bXxAPQh8IFy!hz5-8WeYy|sk* zP(r1=39oO#r)FooAzdl&b^9!Fw#g~CE3|Eds?C+PWa7GliI{3yR?R%`8g?)*Sn`2@ zO9ycsPZ!XMK~;Fqa!-tM8Fy~R%>MB^)N25ctMR8^k(&-r1@X#d38p_8F1Zdrc$290 zHGfRD9L@=sCq6*NQ{i*^?ux`G^5rJHcN(rtY>+Q<#>G_$9&+(ikOMCICwRhz?#Ih^ zPtCtM;?;2wR%O~34AkE337CGzC*k(5o~9?M>P|1w?Kgrd66#J+&j~diRPM{nod~L* zP}4x2^GY7<`Ua@@I1o#O$XzHCyZYB^K|9+u3{KpE@=9eo$D%B-npu7^-99++5ipe! zSQ=ER*?E6dN>Eh<22@(kuu2K2D46y$sS8x<-cO|mQ)>4A45q0jXLe03`aqU08cvwW zC5LB4!Nd`Ap`5q#rg5#Q;T|L0 zm76E83b$u%hugC}FyMn@BJPibdk2e|H14WUXyx?*T$@X$l;+agaz|Kh;<~rByT)r6 zRiVG-J`v?sXznoP4zb)hQSSSi3)5Bwx9ZBM+jc#A0rOt8UQHjlG%|I|yvy!GXf|J) zGYd=6-mXrb@C>8*4P-p{1{?S^P>p9ZuKzON>=w4~tgFA2bq%7I5);>{xf<9tT$6kv zlKL)Wsno0HP^yEnq)s1hD;7xQc>*Vxw9{Sc4au)XDmSLKK$h;=XTqY5DMEaUb-l?L z$vVRz&w2|!WUg;5I%K0ku@iId6vDWpLzwR9WWjvGK#1??xQqoTF51yq0)X!599`=3 ztGx!P+9D&V8WDLncnATuUj41Kb%_p6}=+$1NCME3)h#X0Afi0I~PPb8gvhz^|LO z4%u2`*_WlJv@Bt2*({h_mJqjWxLyrbOoRDm_`vyY*>6GV%=H`7xmMt;hbIxFUWjimVa9Z{VP~{;Lra=2=zq=fkqsCx4sjmVF5PYFUTWHz+K!gTQE6!ql=^Ft;orZrKJVqY%YKmaV(U zEqe_pwd|c{tzrVJKbG=n*;#_+n&4+pYS{^fooLtEh2sTJ%l3GavT4~HK$&Hauvk4d zBW52JFfBVDRC&n6sbznoAja$~R^Ik4yQ@{Tf|l)^%%M#+2-P>g3FG#WM1OT)**y$~|>@3r|kihB#MJ-zPJRr0;cmR}Ic9~&UMwb0f z^rK}r3!av3x+Jpf`DW2eBg>{etkoIF@{kEiyV0=me;T!&)v_4Mhg*}+yx>N?9+EX& z9db~OQRhe{8Lot>QL|ufR6^XShnkFvRHMERfEu;)Qa5T((>i}4je57JMWfyUgc@}| zC^hP3hP^s6YFEM2sLkIdo<=P1;ck<- z8AnRV1kO*8Xl=VlNYu9jR1?==mTNLNIXlwi5Qr=d)a2qwlT3z469rQfg3H3ROihN% ze6LQTX{sjJIYubaCa%HzuE~((u`jw!?uaybDbgg9A<{&_)P&%&@XkMJa=D$^AvWQu z8hY3APs0}?zQVxd<1;+&S3{h}y+i&sD7x2IL|Mi?VH)>YFpqmeJnrKbD#Z+E9{^8U z=5fCely=j*+2B$kaeuq0#kkK~?s0!CD2@C54SSf6XN89eo^k)Q;2HO2pe*iJ8}MUi z@S8;fX58=e4&y!(r*VH0^6UgGsst-&{_)Slz^&Np0g@Y|Rft`66v$ha+2M#{~O;VCkna2$NNI^2^Y z;VsW`Euz~8OT&YPyX8G{O-bSUE0Zg_0kAZ@n8vj@g{#9W88wc!@Rx>n(zw>AaP`aN ziZ0O6w47%K*-Z$@-1)XBh-yP};wbX7rIk-Zc z^OAvgT^o-z!0J^ToO?Nx^QFyYo~i~Hud>t28N6=z14&Rl@Ukr~=jwq&|AD>>Li~nU z?%V1@g<|2zNJSZrDi9?@FQqBT01m^&(D-%U#C!fJER|nR^2=kw+_Rrd}3r&;)Q@EytD82^jFzbLq9aT)tM_I6L=W~XPA zdD(N4aj1?5A(45%@OqZ;4$XDWb;hx!hO=|T`I&J3WLYVktgmypaZ%qFz&TgyoA-0e zTk4B~sCFhYwc43^>DA7ukb$Bqj58hHLy3z80LjzBBR}GeixWp3 zfp!oso&@@&S1{pN5}w5KGOJD0Cob~DjUw_Tp`thv7mkiwK!~Tlg->Pj-Ssx(Ae;!x1cIRGyE@)wD59P zglXFoFbD@dBAv#m3~NA@hBAI%!)BhT>&oyW^135$NoWcx*XppBT^pX#TAXq!@tnCU-y(!Ic?`R!SckNX7ABSJaNadu{SY2+=9-Hs`0r+1@qZOf^p}I zr|#sN+6iK`*dc2ig0xrKRy6am1wS%-=yDQ3E zy({Xun`j9tpii4dEGgMUx+}Z8AgW(QWV@pVi^xDq)Fn9{mNx zOMf?lL*%|DEt+8?)$WS+Hl||Mf-4EGMraYeE9%(`nC&YOX8T8Pc@8ltW9{1D^iuiV z=~JPb{`T}8Lh-i@UIL}RQ+i7VSKjne`R(b|g5~c||0WcF&tUHldF%5|Lr=hwG-TVWA{rm;%_@2g{90MMdgcV4bCxcG% z3sE9g@D`fa{o(9+Y+pGj;;ryIDvNH7b!OqK0x>H?BV^9~n3EI^9?rj`$;mrBXK%>B zL;;z5e?pfzg}!s=-SJd_A$M_(BXe*bH8S#ko;}8f_{y*^67X3l1I6J6?QU08t4s>v zU~wx7!7tB)(t#oq>;uJSQHBG>nV(WE4ipnXEe%JTSPm3igpX*8DVwGBrd=k4q4Qa% zg~<3ym|q0dr;1{p1jTwT4_lk0v+X|y*6X~Bv$O-HECrxm1an1rF_Y!*((n_~w2<|n zl;b^6v;#r(?7t)>mk%>F&_+NiLRqg?*zfi}4dK;7u ziJ1Z#HpL_A91<%7hr~)54l6@H&^ioeF~q^ZVK99N%!KI>n3>veP^Aoksl(rqpKMqg0n7zV^4pmZ3#0MDNAQ%rF6szt3pmaQ}pTX+m;SGZ2c=)JL91oX(S{l3%9S>E3$4$!9uE2Ala523? z1-=GbWuO9D_<>)0;hAh+_!U6lbr<1a!FS_(S#aUeTAa7p5k4GV)>^^sVWurVk-;D)cK2wB!!oQ&Y|bPB!3qcFh};7%LXyd|(Vr+m%^ad! zbck}%A>>*V=9z9am856f;_05rg=gdmyE)-uG`gE`{`)3l?{%Z@G`9LVFV-J*3|*G9 zqR#>L9+FDKOi-hKVcRT(*-l)>T&6YH%v|D50i|s-Zo)>=z|}A?UzbuK+vdXnYTI;R zjxnHZ9x9UAHp!rEGYjTzQz2}dSrBiVgy8de*u~07Ynug@ID?vQwooVsi?+@7zj`R_ zYrwC8bttFz*)$d5=QmKlecF;dHn2<_2DODA6HhGSH&6^w}ki@a4u>;}-G-3&1|{SmTyCd?<`LSH>E*%Xt+rgje$|EMs3hd6jqtauV-&88fz` z*r!6`Nj!M_QZCcEaNYbEzP^&npZa+@w8QPAoSF7Tegx=M`NA>=#&TZI<*%Hf3>}Ns z^@qR$$SK0#VUJuBkBx+@bx?{bG$hvem&EB%jU!Z1>X*U%LRPAA&Hz;CcX>3Gh20cu zyd}YUqp%lc;A?O-Ds(^4^YACDXMQ=JC8ienO=vtWynviW#EEEbgEqcDq)1yAj)k-t z=*IY|LcsHLIDGgcn8J~3QmUi9q*UiU05(E7D1J^3K_~yl>EtGa?x&&U1*pJD62V00FN5edIs3fJg~CI~C=D;*{{???1~v&)Md+LXKj2$TQzOj9pq7WH zAv{%NPTjoHFb|0;h>?UJKSEh6!wS&1K>W(^A*iQ8eHFe0wK8nR{}1tfUZ|B)WEXJd zypelxId$6u8To&)@;iY#9u$6~LB#Hd??dsOb38en1f3v1{AqN=WVx`jTcSqVE!8u~ zPIkpFHRuFfA?%j2Al@wzg3t2sUIA`7n}8CQ^?Gh)_ydX95yAhLMcMVB{sL7N4lw9N zn5%KbO$XzsGCGh(UX>;ff)-|nY7q)i3N>=r$r9q;6qTW5QbEgage`FoC7m14*mAR+{>Ei z9J@9?5Ia|ck#RhLWnr8pA7>kSe60hY0yrI1qfLp%b%(Y76Q! zq1c}_i`9iXWcVud#P_d4AN*I3zGmWzDDIEMzEB(U7wFs*OzP2lg`!8_2BjWNWpj@z zjvggWJ(`M(JgPu?l)zPiWvfTyp)M%4!%m=5Jvsp2wIR945^$lX-?5S!vmt4ze9grn zRfKpW(rh-Ov}|uc%*IE{m~B?ce+L3)=H48Y@if%X#_Evy293&52+PTWcv*ztqY=8= z1bpCvUeEm&<)udGC%|ijhIm~Bh(j$xySKP5HY|2sZ10i&3Byvqv}?`ZZ1mV&Z{>7h z-QLL6*lhv1+J~J73Vj$dHFk^fT|W!MAcRe|u^;WRyCty$#*Wf31({1k3`eqWL6ys1 zE}0$tRd`V%?{;Y9f{IWS#Yk4Is}eXs@LFC@^``fz3O5H=3YMFLb#v?5Ju=7kGM?Invjor0!Q+6^&A}@{ zp%(p-_?Q9nAv|Mq@IIh0$3cc}4$dSOHwUjY9&P~UL3J7KM{uWRMoNySqG7O0-N&-J zuoixgj26+2LC-E?ws&*PmJgaDoYcuglmOHC88pRRkhoTAwKu4OIu!OX_PWx5g8}>w zi3&^rcm;r^;Wwm_1!oeNT<*htsP&QecrlQsd>*1K3^5kw z2#aj$O$mLk!s4JKpcmpVV@-fX&R?~du8SP3Ubfb<)eBb^>q5(KaVVQDre=@Sh4HJ< z{SNSiiJQEA$Qw0n^6FymqT3%>Ki(^^*0;ou>fjtR7;Q9=pM|5DRh(?N0t<+7Gw?>u z6$1vx!uTZROaS(?aA{W{?oVEREfIVj=1L|!n4Gp!5{AzX17hK!p_B9Yl; zVZ9X)Sydn5l3%Y|7+OHg&Nr!9_OxplmHb-DI0~5+JJ90?fqJwahm}n5SK&0|l?7*h z6N8L6Pm9q>tUjdbkP;|~GLHO+_2AoK7uK(f0hyuhkk+OO!u{M23FB>H!t^24ESQHq zAsl|#Q?xS~RVYrH4SR{d0nlEe%TC@)oMT~8P|04Rg{Z||Vhj*^C;d%OdMCZFVF%b1 z@4twC>?QVYKs@iHp9l&|fA$hD81OY`NI!Y(Dj>^4CMfNR_gjtAZyNCBE>u!|ceYis zulsIva*9-dzI#d(qVFDQ$YL_V?mK68-z5i^4AYf}Jm00>b5L(sDU43WK6dY&)X2T( zkp4B^+j*UPk1+LK7R67PK}<AtCV8b8mo8i^1<{4~Hf2GXV0WQ2|4$b>s9+UbI41e#C+@;ao4E@e zGNZVRPIgg%=5)E_`3`bm3M|)&ScYu%k2BQ{n}CxC@U1g%{8=aO%Qg$P*Vfwe0P> z@Dr=)_wK^6$^Aa1ap}SmDTpo{*_;Jsg58DA{6Agjpenj>Z1T=3cVYViccDWz*SPR; zQHCxgOkJ1-a~BfgF8tkO6s%5h;g2yKNwf>IaW zVAzp%tzEd6;OW9M_9mV#ydIRfaH9c#a0YYX!vf}m{&PW+jZey zH){nt*frdh+$37jg-x)hse|BpP~{;L>@IZX|LH;pmB3Ue<)qKth2vVf3mwwQltJsc zXgy(cAz|vmESS5H5O-l`lTnrG!UJ2m3!mP{UHGb*r(g|T*k0743%>_KUARwccj23c zeaAggxKZ?@3r7K^E}RC+T==sA|8fR%;kyE+3pax*51BZ1VY@cw!YX6mt_v@-nhtUo z-kp3!YC#vC0TJrLru(v>Ot8Dqng6E?9n>493U?=W_}pFi8f5EC#vwy%T)5W;cOhZw z!Yr7(kPvs_NRv@Q&-hq)PFr{3*mmy1J*;!A5*Pj=<%UD3sz z5*hbkh`=)xmgV=w6XRaMIziuAdBpNOl+nD#M(pPc`zu-O(U`=eRx&qwU2JI zGweGf_Fsg(he2wTp9=P>Xion!@U~XN1?PA9t2X%7Ju!IZFkpQS`AH_$U#U^-tHkkF2XOCV5!St_ke#tXv=V8|#SfBZ`XMAXYcDMWD)8x*m#wWAQ-z0;okaycy^_;`ZPF<$OBVof&3E`Ujc`RQ zJSm$;wsg&sOLA^9|xrmrJ;UKj)+v7tK3l>ibZBp(&&w<9BYAf?|2>L^e^ zKaN`OXy_`UA4#tGmgaa385D?v#X;Qz^m5r}N(JxyAgX>eR@e&U+MU2vfs$5+)A4;N zzRwHmvGMMVUEYULw$}RlYi=8DLI&PC+1o|rg8B|DrQt8+v^;KL@U5M?&rR;$K=dIMyRlsgFyssg1>Ol9#K zAc~_SiBm_W;-VWM3Zyd$ToqWZIWzuHP)a@WDX6mWa=J&j;btBgn(mRIsqRU? zKQY^6RIy0EKhgS7kJDbD(1yigytnoMzDJ+c;Va|50dH+?g0?6gFVOrxRJRgFaHRRu zAhpnMF`L^%t3#b(+AHxi%r=&j96Wkh#JD;%G6;`_JVqgQT;gt)^Pd!vi^8=wQi=}a zHVx&T`8+vf??S`pe~3=)!DPXYY>zxvZy9Q%PtFz@qzDikt2gQgTE6DV*`}RnkmY#F z^fL7}GH_PWoe8buK9N4_i*ASa4Hg2KH=OhN;sM{4zbrVg{GaXw?sJjRO|1cmIg0cAE)J{_Ad;vp1Ry*VPbNd z1nmykCEm3&m1}{{I}^6^d06fsortpF%)SdOTYNBp7U6U1v&{S`;)|$=v!Wt0VO|6g zWx<)FBE}UDW3#IY58kNlJC3=CwR$>Mj?DD=PQ#CJqr>u(gTK;FLwXN%5Z-2czK_-) zfzUxf_*yf|`B6GsdsXOTb-B*d$5kPHQMfRzXLz4ILs{_ci}dGY-^NRr@{HY@@O4YX z8P-Sq^v0TipPNwaaN#d_!sq>QxHmW_7JDz?si;_!p`>>{vM#=V@`!(b4Bz>FW*_8} zsnt<+W8a6vAquC~t-`a#@z@7p$pe6o!X88HC1igH_`q0`u}>_I#r8a!ZShr1gQlAr zGws@B^u0f^Ev`XcF;I955LBHm42+9GW#V@kTpDhTu!9ZD+pnL2p0~j&34NN}J@jWv zuH6C+8uIY73P7wE>U&UKy0VR(n@s1*DaOQh7!n5~8`Eb{%5n)PvMda@B=DM}6|~B( zIekM*lvWugAhR^wjsNoj#;Dp7e0blacY66mle}oNg?xJ*d{8%0hjE zj>Vi)`Vk!v<=tD>b|Xsg!e_9y>Q77H@xJcBRd3Kb6L(ZPPH&jG zMx&y)&)#3|Z=c2LcU^?@Y;wXvnn3Tof1lM@OZ5L#Yn5)HjW=y3T=8o&U}1dk3W@jF*35{FyFW)hdvW<^J^PY zo(h8=PQ(%~$d_3CdB4SClf#Y7-FrI28;*G2!Ni7SV)EE!nE+{9;oxkdx3Zk zuO#ul6uGZN_LT4j?e{v!4Nb{$qiSTh(K=5BwcL5Lz~hqi=W%y+rtp zul@BuhJD2~7xO!h+PmXe-gm4*P}T?X({TG#y!;;m?&rnwkK=8|vF`(#2s~63HzJ45 z4t)n)8Vj`og)IrCtwQV@E4TeET5k9&r<(2R6XZ2No-L&kRN@3uZ-eRwsyt+Jtqk8F z@1YZ!_kD)MmEm{feJXi>SYCmZwldV(2kr1A@@>h=Yk<5nktd&JVNZN@HG6-IS=p8& zplW64gmgS4g8$zyZ45&iA@p)SvjmJ=HPMkRV78kU|yTb&8&^;0?7fAdN_WthPb{dT>A`P=mbmxW>j zM!#L}XKw79as&mA@#o8#3s9Tp^|*$=Bo=CmPcJ%+0a5fxJl4NUM&pFu{i zGwNcLeDgL98}?0@D{z#Y7iK`hdzMk5eBXl)Z{H!KG_YUDEo5y^xLvu&qVclp<;~`K zVI8EOZaMi?QtZ>eld&2ZPk^yBd<&{&cg|4zq=0)9d`Y2TiwvQsiaky#qL z;D6sUfnON@#PrrtC)A+pi8JZ|HyXG_!Lw9(v}W}8wM=1Jtv&FO?P10WnrPQ z`(|`<@TQv)>WgJvQF5m`eTrRW>z#LCXb|1L&w}{+f)IRGgfgfy%LJ^lYi<{uaER1Jj%WSb{J=NSc`iOY_G%Tfbw9xJh20&cwtE>vV`V4$rR>CHxIC8A&w@lT-V ze#3%hB$yC1zs2Hk%QR%vK8KxW5yB@GlKVbpTpT(dNA{{fuCKz~_`WPOYgq#=*Z^h6 zHr&GC>4@~>&!t1!fa(vbEQ}nj`V84cx(0ME#X8qdjHrNWOQZ=evX-#goAAghMIf8; zc!<$voQc|QGbWs~y^oQpY=P+)5okLVD-_P{(&c-6hnUpr#8o3)Cu5%ff}A zoWB_SO*VEF{=1N_{KG*h|FxjVkF7!=mxsm~yg8NF=Q<{0JS1Xllg5ZCtoijhUBh4x ze*RE7^bP=|mT0E*`L9woW-1!9i3q&l_X zsHuY90>l@f%0gR{+p~Fw%VZ6%eTQQ_T=xnV_^sdtw>gPh#*qZfj_?7Ff%j z0o`*)9V*R}(b@xYEn0<=XcbDL71R=mR_AYLa++-1CT?NGstk!(;gpC4RUR_A7EAPI zrbZF0f+T`PkVNoy1uYG(2&0)FjoyPyy~86lHG2OLd5qrXy;xyJZ#PgLy)Lav%yXNV zhtYevpc%dQg2M5BCU^VMyF^C5D)YmicFi5NP~>s+n<-K}C%Sbeo+=NXUe97cN6Zg} z$J3lgnhW%w7tYVY0^K^J{Eg^-+k`U$yWgS6h+V|$UIS_tsIsuP0qsZoFz(Bos!rml z)Ttv*5}6nNMExD!MdeP3$1!R&LbqNS>fry1@CBx69ZhBzyT)(FAreSGyf@q7iM6s3 zi5C-43K_Qnf^9BPt@@BU2Nc=LL#EJ`VL0*@0foaRKzaV*R%qhv_=(UCu0`e-B5Yq! zV=m^-#dpc=F!U}B3D`xkzX3tv9IhWjs*CkHCCHiV-C2&?x z@BjDQJDE1g(n3i^r3EAVJ`(v_C$jUEWDTW~Ej1}ZmNrDBY$eo4sIQhOrLJlulPuB5 zP7yM8{_pp*eD1xUJN^Fm^{R8`^SqzuJfG)0XFs2F=7%@&tO}U<;dR7@_h!35+Sg$% z{$3GUqYZVQ;xChlg4@y1a>PsMiZBA8%S_~ClKWwFIt~x#he`Oq)@AIRU77{jLJ;n& z5(RGrp$8z#!UyJ|lQ3BTu^dj{U}B5D5)R}g9e{0!Q0S5OdrB~DKrZ@!{}=qpzMyeiOF^1$XRilwhm zu>KZ>3*iVa+MCSxSMCr_u0?;j1H^j)UK4IcY*n~#yL|Ajo3S2&=LcWOcbbaWP{goF zG$!<&@G5A{u9Bqn3+v;oT|C1=bn70IboqsKHz4&3>qihv2M75F)_OJ_PKZH=jFkzO z8ywRU9s*(2+wmn>D{h2{Mbb-l$a$6~+Vy$@W4lh6w(EH?Z`TR&cKsrgF&W88Z<}L_ z7FSbmu3emun6~SeTSZ+(VD)-QkL~(Xf@Qn@F=E=T4>as;78aI_5j@-Vqxw)b+x1?E zAwxK}c+-GyJA;ia?hr87FQy|_5#l%#{4`IKJc6M`CERC z{M;v8ScfT|4MInxh!1oSy967B3=_OB@wty?REE2Vi5_ZmX*)2ZY`ES)1fy;cPSB|T0h ze-5NhCwICQJnFQL?BX1)3(AFqPTK=Gb=o|bCr=1%$~oi{OhySTQLA;q;bK!xBHsfL zt`0+N31T{le2C@C(H7QP+YtCQA!`!3i;>(zawn1Zx{fKQLnll1lt$Vqk4o=dEWLcs zt|+GC3^moluxt2I^y7rqDG;R-S~nr46IyYGXhKWDoX{dT9b97Ggw~<4UWsY4#WZL* zTzw+!9QxIzPf(MIktWL`P2voZCJLq|1gArRNzBuvbIqE#21TyP_Ti66lW!wU8uxXZ z#2F$@6iiJB#(Bou(xg+(nz#lfu1Vc6qMqC2Fo@LLxh&Eo&Jby$U}{2eI&|HZChcq1 z#5L&Wnluaz>boX)MVicxG>J1rnkbl>5S$LZx24H`HEZG;jCM^LhY67;>mp53{XBQ# z43Q=ZrX~cZ!-#EZa!_28B~o@=gEH5oIr?Sv*0vC*Idev&MI0Pyp#9GeoK=n5qz*4lXgT;N;CoFOqK~9lzE!IUv+& zKus3yj4Dnv;YX5Ri6%S;G|qsJCG|r|1@l8mf;pnQxDBR&M{3njii$M+eb^2ZJr>XF zUr&4Af!I{U7RkiBV_!C&T2I$mEV_J**HZ?*s4~0z6%3jTi(wdHXZM`Oa8MONe}x_KdU~1r ze7VehG=Qjsc^cdjOYj3%)el8oBZs0!_IlOm4Zoqij&A7o>NddbwG6QZVlT%Q0}B-w zig9Tx1=Cgpr^D9R+hPg+*6rA>uakHWkA5A8@Ju!A~B(&hFLM>O_ynOz+x0(&J;TDnl6wSCyG{T~?K&SZv+EMG*D4F$u2ll2U2EM; zyT);9*P}oayIyYTxm~3QfubFMU-|JNOgJFyx3gQfCuF3=d`(k&mf(>ggf3TZkBtfY@3m*D{=fL` zhD|nJt8Q|f){VJ!MQTv_U<^qnm|3(k$-WgJHE0VQFCE+@IlFMyhXa3x@kXghP8zG> z3cSLJSQ`%q6(#NXv13r`!!ft;6JA+aKV4`i4VF)MzfC4yZp@X_0R#Id!X>h(ni^9& z^m|=7?`0205B)Oq?UM+X2A+rXJ$Q9sJ;0K`)xyv_{EXD~=&~Jeqc8F3vTlf_gM*@h z^#HlqTc-bXSnUWL)sTRwQ=pmFTF*g%mM(`3wG>e*dNm@9rHe2vU3oAsU4(e)8g4R* zkX%%{HUOZdtLqRiUH2NWCxO)mh*~UNw*aBj<+BmfVf7@#K4W2F$=9MEOV=(#y>uOh zn3b+zSy$IWFI^W3n5AnNVih5d)6zAUg6Jf(EIlt>sX-461wjkfjwZXQg)nYEyoGJ& zs0=-f`Lwl(#A6`Pw^6!=NDG%5GT=Bssb$Z2@9Gs&p5(vQ%aj~ggp>39bspKqY<_OIl?9obA^zk zBkcF^w~nx#@iR*eBkZS}FeQ$#$)+Q0hi!0}AIPE*j~^%U zR;z;dBt4F>>ks3bal_U$#B5aT$cCHXO05e@#10%4uNE{%#oOKPqvB)6sQ42sthKf+ z@HwO6lZ@2EAvs&CxMUEIDHV)RL12^A{(Cj#kU~eT0p*Vf7Q6 z$H(b;c(+tDy26fcV}s7M;tHRFU0vZ+6EGRD&^M%ab5}TexVyqlh^Z@NgCkc^AYFk# z95)L|>I$>)x4MEeo@J@Q6=v@0u0S?*1&4Kan7e{P=n8odw+JDTD-1OO!(C9Tf=?wq zy295$sw)(Y0FPE>jvVP6tqb-MTS!L%IL(kem?wWOMVVWTG8wBkiCaw-IdrSB0O@4Q za>R79rJ?ys6Ze_5w*jByR?Upm#vwUwweub73O8D+`L1vq4TCwksfM`ngG6Ez63MAp zl0#UZ%rXc!e@T6Uz3;FPr{!KVQq%ji9EAR%9;z6vIC?+{tvGH*Y>72 z0M&yoLQFmAFJnkq#?)H75cnJqDl}3gGslA-l+@ETlzf#3xmQwd$`}sm-k_VbMQ#7WwODM&nS>S zL*ToClGIN&;BWO4XFS?cgP%0Qeo6HcvS}^ju)`hZexeZiNgl*AiV*yCO1GB@xZDM` zD(EKZ(N7xP<$kgXF{>FIIeN3y42uNKeEmhxY;Zc>?fJUcihJ6N{o03t&&k(SMq2NX zoO~SwQSPDFnvU1IuB{8Umt3HSz6PMyZ+S3(aYE<;=NrHK2sZh`5#;*^&~Xk8-fZJu z+!uHi_9NdIDzRPg&U=_cBie<;5aYhxLI55SEyjWPFJMbTulo70x*Ww027!<@;d;cF zR?F{^xkzh6X!$yv?&fef`q}r5V$;Ua;lq|lKfuD^(4ZAvfy3@M1i~SOL&^a`r*mmb zLb#sO?q22|hs&c7(_!7T(OU5}`~l$V7X-_WXQf~{tZQ%|^NyF9{Lip&SXfwciQw7s zybdTG){R5VI-WmT4*p@GcRXJeFgukI5+p>(sE|1^l^e;&m1pAh`CIL|Q4mcSC>*6>$rnvMO(gQ15u1N{)wPD3_0D$WXI zaV8L7xIvN@=V$S^7H4OC)lx%o{#^2q{YSECady}&hk0>U2#a$b#NUb#{IocKXaYWQ zL9GfJ%bT${uLn}A{kDR+~^#w3wj9$jd}`jYScWKCr^l14PTm!QhHbGg7qSY zRm1H7X_Y?*F|G2~TQ+}YVXd{ZfX}HKzB1B}4#}w+Qlpu2I;^o&6 zq>f|H9m8>~gQ9V))kl1R1u{k6$;6e>S#JyNQDN9#X$a6M@^2AaAybgq;Al>InE*Nc zNMJggWD=vvR_S2r;OfZUtauI>OLiyuoQ9Rr%HS`~!Q5~#Ne2usQW?&( z6#3QSvqp)AgzV~L4Z|QgJ+~zxxpzo7=}Lp3*2OoyAe;+*yiE5uVinC)8dkUUGCdC< zEz>8B^D>@zGS*8iZm@q2SKjUvL)6RH{rG_#+rwvnLnI_v3S#@>TAcuLGRtSA5 z58}Q=i1-q_a+6KK(=Mo0!MBng%XItkd^3&-uSd+vv?HfEN9%%v#TInsM}X5Zod@&e z3Gp)hg2`yOMap!U$YGi8@*q=YbAJIEz?HwMj&_9^*xB9Crq$Z z<7HYqar%MjD~2hCX2|Vf=(_0#rcEAV^T`X!<{M-(Ao#%a>%FN=<^$8w0O|*(|01Rz zm}axYKQN^j{lGK_mGgn=K@U?BKQOJZ#1lVeJ}`Y+sBGDDsP=&=srrGbQ%k^$Chkcn zu8n$!2~?Sl`kjbrqwdvX8Nt=p3zm)gM!~XCZ~llk>W=+$w6>##B?k+hjr!R@X`_BC zVt5N~((rkJatQYZeX;=Apf5!XU(|!9jrg}@WNEKAM&+{+AB7a8gM~T7-wUf#Hbz6 zIn+9-?2Bi^fv~Vn(4J%Xi(Qkm!+6nz4cl1|sSVpG5$>RMoM6;%m~xUEDz=mLWob$USTpy=|R4%wC7`9r0zmYi_|~^mJwL} zwxq`*wLq{eQokXl{p33hd!L1cC3g#+Me5wgy-3}LnDvtnAFGaeoQ1Ld%#(qv2ysx( ze&$J*ly{M3Ce^cOnGxT&5Fd{p(usCu7QHVDaSr`Y#M0qy1J#^GJ=&qSVu&p;1+wTi z5p^*LCr+Y(Uyc0if1}x3mTLXLG92ql{b{gu<>ctK@-%^D4r6omrF=6V(c`)~4Lfni0YcfiaT;#>ACc773 zfS7u59|M*VSpBG|MK2yBSbFga#MFy#GwcWp3rkKHJiWN%6!+p1#LSEDvC3+kh2A&} z5HK5u35ZpMI8Gai)f6Nxy`|@_Z21JU(X!W>a2JA%+8SB+XUIs0+YOTGiembh8BKm) zpYYOzve02a&z;6kvaW7prI7q+xb_^Sh4a&Qas4BpS{GyG0<;s&iT}o`Mz0v{Ory2G z5ML`AjlJ5+Fvln@-b*AV#JJutTDOaEB2f<4*GB0Hu8J5}OS2g-LjN{Kb4zh;ub{{} z;Ftl$c1AN4DJ`-n>9CKPAZI;Lu11!x^4Eu2KPM6;271N9!(hE$5EItzpR+Rf2%g&w z+uelr2Oca4E1QMH1;)CC<>bV$6By@(FF~lA@@2{=@TCwQobVJI{jZ(qj8n7P#+BJR_F|7elHefk{)sKl@H50JLL8?xV6*3}2JC0)c?~FL<$Uxn$;1=K zM)T2AQ$8P!1u>A`Inrk+Urcd^@@UA@%=pd(t_CVRpXzduXU1!QXl6L%2ZO?h=N?EH zGlMYAj69fU1|gmqE~8;}R%Q&D?wRq(^PU- zAO)iG|^X)GP89Z9(h`5liI$wVmRywm2`1J&T_J(VoToGgwQwoJ`MRZxk<_w{$3s zixqI#>6gQzx#5|qB`B~9X4b=G@h1~7SzMM%<3ZOl&vzG>_!ap+D|N&np6{Ck!UoPE zJpntH z_k!o<|D9is^6LXL^u}0z9Sn$`_^{u2^gO=`2CdFa77w?K7-^wY z74&c#L_ItY;vP;2ev9NAvLX|3yoF(IYV;vA9ls-cRW#;zWE&B~!I=iK@5s>noRGcc z6h&3%B(E~uwJvm4Dsd=AO;y5gtlT--jk@6t^5`@T0Y=+1Qmdn zNsl+p-3ufRyGN|`E371Vos%;>W(>G#Zi+B)qKgcwU>?jTx)eeM^B}GuA^72TO-n;A zfm|e0ezWb-9M|`i)ccY=r~OWVmQa&zPu&UXrY$Ul>o-NI(Q)KP;L^cKnLeU;No6Q8 z**`ph(}lp4-S%R(qB2}y0M1&T?*Kb;UwU_L`$tEG#H|jH6L5O)@R-VQlS$x==z|WB z8BzDW_wIrdImK87;1*bqmV8|dAag0Jveb{M4&!jOs+l47urR!s>UKDd!_}%VMFr=B>%O+5}!ZCxDlk3muHUX?^y_6XCmmj`pNAjDgj z?t0xTmtc8UoM+%;` zRoywnv$om~F>77EG2ly|CIzv!dezvywqpOz-S{G-c>{%( z`;*AFYak&Vt~ZFgu{KUx3K~A5c4}iGvZgtD2wDn$5%!iwa&}3*DpXk?pc~+s-W{r~ zu36O(C>r}G3$tmt=o;*O#gJ@FgCveUWe|J)PLHSEO}7M8pz`q2}I1Erog4KedX z&)?p2X-PlkweI3?yw z%C8giJ6MtJhxZQ)QoErKs}u9rfmJ8wn;2v@AefjRR-8LA{}q5bF@N?vpP0{PiBHT^ zj84qwpmHYW?-fa$nBUtHFZv@hG5@Df`SLkbo0un6C+3}63SKzD5l~z^P{ZcCBYcdQ zI>Kx-auvbVbp=aDIBWs2bc6wjX_e&Id66T$eGFyO5ndELtE4rE*~EOcRR&ui+@0W8 z0n!PYFXY5LX`1oJ;&1#a!^*6T-wPVC2CHT}P<_|TCwfxgupT&np(TRB{ zmyqm5hh+ch#Qb?C5m~U9l z$sSKSGciBIYClfQ9|cckWm7Qd{UNebmA4XBg<3s4__9CS)Vi=$LtqXHsR$QU^BIyb`WQIZEfDHu3>^J~0tDltIhhD&keND9r;TE(~;{fW^ES7sZ$>Z8h+{Ujiu+VYqc4+*Zh@CTzq`A zAN`RO4{poakN&7V@crl$~tV2LL8K{KC#M@%H&5WN)iml z3ib{w0p4MQUCSc7j-(ou;Yt(0{o@~kC|v;UcIWIKuMEQt$?o-5M@rA!EzY9Y2tFV( zGDWc}{N!3X(I@G$rwj4T#1MGc--e~Im>_$tcdVB9$-*!uH3oupOZ>9%g*|5H%QzhA z0~pM@y$ud6_0wU9bV!=5qAnY!+$zIHo9^Qz^*63PEL<7tTXn{%;nWF{;Xv_;HNL@K zPRZ`OjWgEnm`^-D1`yeUt&~y16}f=a030e+8O9re6Xe4jA-qo*h125`og&%fwH2k# zb4n(gD#KsK%K7v693VmqEmOK(gkFzRMCeXg*|j4kNn%-684fT2r`J0=K!hG|6fS6; z=@j)0-6+^y`@$tzNepycw%(g9$2qHhe+B?Ed4`iREsK&4K1H^TnRuJ={bLgj$+g1S z;Zd!jR>5C>gsf0}QqGL;u}h=r_?uItO_m4GKgHdKsh@vKB>u$%ou7ZyWG4QGoFS>{ zC)O}OzeeWgb#6WzU(?+Dn!vgFbSO8u(Y*WsndhouUVcG1v^K7dG<-4jC`}dphlQdW z2tD6qt@{Z!bU9?LLBnnZy9#VGhz|j_M5Zv}uv(pPyaJ~$2w}^yx0~;Ps9dvna=xV6 zL>C$)j7U{U5}Yqt4St<3X|RksalXVE{xC+&m%JkkOppvqq!rJD`Fx2&IA4+n@y3D> z{FVh*O6E%{!wO51vk(E9oagV~8Gus>t@8ot;7M{OB*vW(x0@PXIt+D64>0${KRqJ$ zahL+L>0u!1j3TqspvTlBJHs%;fehcBmgA8Xcy6DL{gfi@?B(pM_Csddw?03o_^r<; zc)TIBe-e(mRhs3)({$A1A@X!fYBe3?msH`YbP#G*|1I`O_rqa4XB(vGAB-?AFTlY; zcsM`&2mg-}5cdaNW}s4nPOO!^H)s(+Is_qH_XcId<3kXN&>=_;DrX4tt4QJyfWF(meV~UJhq9UD^Tyk-F^Hq zgj{SQ>KPBa2G2q~d<{q8%o(~J3geYow9IoGgN!zljpmzh?*{u^ z&?&Y$C+n>RX2wnH5{dgA09I`HG>U(M;43~Q(BWMqy#Xtq@cMs6z5hUubzw9}Gle9d zKqU%TLdJu%K=!vjZW31m7HSoo2&B#R5Vs>Cl6yB8Ghg~D zBqHX>y!5hgn*p{wj7{ZXY!-Y%K0F;fMOI59YbcVz?1J&_@tRdeLmSc`Y7a@&Zn;0iBvsUMsiG=C(j|jsmhgHD@ml$q(cgGeDlO?U=T3rZnsaejlyii5 z&Yfv8u5?+OQ!UPL*Ln;@ zOQB~OD3c{|cUTvC!Ztfg`S|czWXMV>A4h`SD&JM&6PM$G4z=CI%D@*sP5pKz--z=c ziTAwabI2B&y;*XmK-ltK0f@GIzaggc77i{-0bKpCVA=8=yN*~+zTJwLwtOS(eMVVW zSaOQs+46lPc(#0r_mKyBblFn|e8CxPJz!5jbd-D|Vih5d(|LP;S2Z&nCpe=%B26gz*GiZTf zm%6=6Hj94DpnHJQIgFWzSq4=Z@Ed2yy$*T}kQE^g%9+D>&p31Q1~%nRfTi}5Eel}N z6{*)ndF}$J`w@-BPe4{1GFoV zR)#BMx@%H{CEXDqZ1*wKtUdm?%1ZDdb>>}-H8=-PC3K=w+nzcI&H zmpLF?!l5RCYgR)u0NDP-ti&g0D9i#~B!1Zd><2BX39vp(!p52aUm1Yvr{FH~ei`-C z;THo?{n*PR2RQ8Ts(+AqJ}QfzkfgQnUZ2ocuQQU*N2R2~stV7TbKU1DYoD-AD!U(3 zFlZXO`IW(|5!z{nGh`dG#8l-f;_?gtQ}I_A zl1O|N_Q3yJOhnPs+8msOd8kp6N%|ntW0>bMQXAp(hq#$rGlmxCKF5L zW{ZYs)IfjWQzCh-g(J&=#3cHBkPo7E_E;tn9a3z*Kpw#WP^kTP;3DOmDSt@MMB7Z7W#bYC*)}&}@pn zs%lsc4fR%wW9)f%3;kA${XSz2#AD#&h#HT>9|kyndaK39Pib0PEQG9 zSOq(U*#%QCp;2D|VGPpJ`w6lk(ftIwe!(F=x%7Sly;8uTBiw$a^P$Xqxfx^_IMjx5 zRLwR7+z)A=XySSnA~WxpcM(PMkoGOW=ppULe90IOY40U59@0J%F}+g2`A37l$rmGp zp9i!nKM!bEejdsK{Kcfnt?JZLYzy_sgFO6%%Xy578OLZ)GR0+T#?MJ3ma;Ta?JA51`5T&tXV>3_SUNby&#uP|KZ{Ml zpyh+{DS_U+;FxlH;K;E(DT~9C=OJN{3>qD=(NaY3_eDvPy=cO;7o7+5UNj-zi~iDN zBx+~%qT7B;wfXVi6vVU_-O=ilVgjpg7PZ)m{#LN;Mep^U_o9z7Y*z~lOAZh`d(k6+ z(q8m)h*>Y%tDyE)-^3>QRsxBe4240zKV{+7B8d6@rLa%2=iU)2P(4;jN6MKN8L0M1b(K1s`6lyYtf?_#5?22QH^zPUVMw=LEIM-DncCcb+`z$RpHMD`RqH+Srh8+z^U&>_5HBf5n~Y+l7L7Ms{@^9$CB(F(xL1@C zSUpYDVoCW!uq-JDZt;>*&+=#|3kypw5jlh>4By5q=>Em;xvqNX@+S4??)zxwsA8bRXc;%?v zEjYU#UZ~C1dWrY-YQb0iX2CbZdw(Pn=UD2OTNq~i2JLVcJ7}kYYkv41u~~@W5J$tj ziFYvl5nz6=m5oE#aPjiKAqJcbRl=*?E~h|V@bu{~?B20Qn~kWkCw6x=^WjbT7Wrut zH^+6Hvsy&*Q{=aPrH=d*`Muv*i1{gU93Oo%rC@$DMQ}Q}!04MPA4A5^!-ZK_<6U^i z^@rioM3_r+kNKVE9$hb$*y+Y(VvF9~_o0t>-jds?*4#m%AR7?#iM+WK$=L&m% zvxPpwY5uSG&f|z0ec~s;@zW7bn-?^#E*8RK_duQOdZuN-^{P6;anwZ_^ioltBb?)a z!|lOFqJ2|CSl?8JA*L{`_BHU4?dkW)Asphk9whMz48?YBon?HY0W$vM4t~d(^XWE&Cw{Jv^gq6%$lPe zt!CQI!dS=cT_7t$9F)^>`^%E@mdMV=T_WxGj?+~4rWQ)O%eI@g(6&1d;%zq}_-T{Y z-UM{D(3`Y+1#|*`s!mW&Hf_?JPzu{2w|;@~vR!R|a9fjhiU}@Lq&8_iMEY$;irfg| z-;xpW7v?TiU3}#J5e~rYohS2q%CE|PRkZuH8 zFYK$mU47IE%b!=9dWSS~Vc(F+weu%-$&6VIyKz`&?td8=S#9!z%^M&hU?jRfITBJHzek@qJ+4 z6OG-gpqyL#PMoeKq2*4r>*l`hvZsJsUG@%%(PgJej4rzhF`W%@{vIZ$$rrDP494yB2`M#u7~zc4;MIp2MUHqYL*Ew9I@UhEIx2Zp|+ILl|Z4@DvNL6iIa88Q@khmZb})VLwx57C=DCcfRCdOvPB zTc$!|FVgZa>w8P?Mss+Xh&{7E+l%;JeKSnt|19LSXuPX$Yy%cS-qjaJM0fRl1PDG% z0A$<_jPb5MvQ>mQi{90DTtgOq-qq*y*_J5o>f3rfeVKRlT>;qqz`OeP*s(sWyQ!cC zhMsy?pJIOng2K6oJQ2onvHnicU45$Ovw*1RLVBv4>3`CQ(x`I6hu#n)1#aER1iI-6To^?Umn;zMX~f03fAA7 za#LRmYnb-6Fs$E-H`a^#x&xbiQC}SE7xnGfgs;Sl`p!qJBE)feQD5DrlJc9f2tV7B zd&86cxa$o}mS5u^44|&VzlB&jI3`+$*YT&_)2FSuV^+gG!pDyfqAXU1r|jyjxg*}P z6wwOLk|f!h6Q-?s9?V;FLcBGvFd2zPS*`h70BCD|;%?rW-)t>q5rNgiMJ=}GV}Q`T zE-MhzvBXHjj`qg61%2Nr%mo>3544>AX20xQe<$XNE{z2qF^dQa60tZmLho<$f+W(K&dNI(d$;X$P$Y7yCO@!ixl}jQe?M1JZs|kND&275rWfU{I(RyyLwR- zaRtg>S*kvA6eOyTToox2$481Nn2Hdb4zstVNZ!qhtEAMp0#&ZaJXPY}NQpU- z5^-##go3FA!Rb)BEhX|UU9_@WWkqbOm)*~Y-{$7{DAJ^`rRPf=A8DdsYC-Q$-QE%FX0EzLsC?r(j;}M=B0a}0HR!OVpsFxkpV~w>tL1EAKv)BzfhXGSFJeP#^t5XV~NnKc?Ogh9)4AAsw6)T@T157@P=U98vXT zJH|-W>j51xnZ2Og+wo>WW4#{GL8}S+D-_}NvTw#arZvpDLaqlaunDb9ze7`;ky(4I`0wsLGw%6q!bhhkXTNx`%e!Rc^>CG2mCBN6}as{x(i zY-5bQd}=Rd7yZeBCpz%2us?LpHUPnBIe0&!qav|27=e8^r;ipRyflnPV5j&BNtZno zM_lCTHcKuOTd|u!n0AWuVBSq2#5={8n2gmlqwgBKU^OvV0MaMKn#~` z#c?fRmn=XRAM1d0wed~s>8SwDR7 zpUAj7v}X|^E=4X<)F5)HdN?q5{>(UIF7@Z7$rdPr!8cdCyS+AZ*!t#?KzGE9x% z5I8M%L*R3ALtu-2Sc|fT(UpFKjhRO>^aX)VDW^5ji(-c|Of)PHWw_h0{K&B~xY3_o7828)l4;3t zD8npO<2@((_Uf7rWiTv-Ng2rqf~Qp>C$4`uIzRK3=su@)p?KF+V#-)QKl63D;b$bQ zv?#2B>s~rjRk+2%FgKKsr2lLJF;PU5e~Q?8#Pm?~zHx?*$>)TD(@abDCj(F1p4^#L zi%X5BnRMpbcBS_*Q9ojmz+Q=qp7eZYEQ9h;Y1g~m^A9?}J>MZiObR@9zq{P?2~*F{ zgSqDu;-2p^wjjC4^LIRuFT$@YD zydwJ1^LIFyczXVUh?(afXTVdO!6u*15imV}Fk%%Uj#JN{O+obh-Hkot`M7$LXKa>2 z>B{^0b&cG=G(YT$T5KKI>~ot1p#>iFKg6q_DQ4L!@P+d5#66w~`y5IL+Y5&jHxt91 zEfDSkSPh68@7lxMc#prVzBZZQ>Z1fpE!e z9>m>^5d8E)ra5j|SRyP7_uWg&a*D0#5q!0i5jz7hy^tvz98Iq&kke}fz8k6_NvG8A z!rwZj=8WZDLRu8uFp4R0N{wtwWP^jl<~hu#)D*%gwLFNw6(RWPl-idj;9D2es$i<5 z$0@Z1K?ZU@Hx|I!;U>)1`C~C(#_7lXkj_nd>=$PDI7+A-a9Zd$-v1cB`I@YDuT*tbooH|xd z1n*_346-mR3cPqrCoR5)Y@IooT+D3Xpf1i3O%*7ZgF1rov5!ggL0z<9+0?e{p|=etMG}HZLfu4$i}G8v`_RQaOv=qK{B0LDZe;} z#$;c7eMlSvrtCHpoyy9vs{!QnQv*b8zBcIX4Dub`^wyeWcut>mSu*jU1BOz%zhXD^ z9$$5eHQ`7e9|C3R7t;-1!Q)MzF;{!e!ti=%`vBiwF5|=7>+z;>SaiJUzkvAhrdW{0 z5k#KmY)d=573PV=eL;M(i`OF#o8++0$r}X5dSvJ0kUcBH82ICKqZgwDhR!&(;(0ur z4f^~r88IR;t7f33yCf_Rcs`DwRL|m4VTeyXxfS88(Oz8YclF|OHDX#^-itGIOdc%^ zEG{1j1B*-BJwZ#$=SSLi0iD{{YZ-way9NuHIulzlFf+2SqKmt7ibA?drXVX}dbX zuuoW6SaOo!*{*I9JUb;jc7q!F_4gtJzU2(oDLD`j?T(*^7}i{4IBi$QP!QewWg}TmP5N*|8ZZsz_7h6EG&6Q@bsn2fYJ``J&2hveQ&^DoxyzRMFF#q zwg$0^5XY%6)ji34X@If2FWCu*>I?rEv5`3(jCPK6WHJonY1TT>mjhaf=ksbL|dD_F+nC0QE4XLr<=6hbd*V#1B)V7(GlW2bFV} z(sd$_JEP@Il&vj?nB>V(AEHA*PjzV?XeGE#VP(x@GqP!Lw4CjhG##bdF_CPYCyp`Ue7} z6a0hNyMZ*#_&raPjIRven0#jZR;0i(rsug{6RTdb&U0;P78}hMVKvI)L!;G+2^_T0Zz|zeOx$rp6f|*p*iQdmJ0{ZbNvai zWxMyo${f%*^`TJ2;*wva-=c&y82Wh27$& zuQzUzU}ZRAhPn|?QQaRbT7Y@kbY&>CYUDf2c=s@xUCQK@NMCc&QYZUNW%kvHb}Y0P zU{)ei9G|H~D#L0M#*X$~L*x#IzEjD4M=Gm#cJeK>4^^Df- zB78ewG#%45HVVa_?v!k?MF!yMseNK%Ps(DxwF~SBkIqtc zugjhvmpjf>AIB$JL!bM@os+hyPs_7hpKP9O>qC4x>|myf^x5Xwt~$d~WcaQYhOwaq zj5|;EFV#)?{b;xcj@y_XMH)KM66eE2%e=tV^Bf+|w~!|tTz)j);&$>BP};lmWIedf zZl(+8FphyTtO)!DHu1VP2H;FZ&zbfg4f4bs zb-uNDk2fGI9P)II^Id;-w6OM<(0<2*cS8{}*p4auJMeVKVdrobTMj4uM;6gO#sfV+ zb*LpZnojX==!TDb_59SC=h6pwe(IeD*#b!H{M3EVBZ%jxK4_rgJpsx+KeabN+T|x) z&ri*U=XLoZLc9DqsGKhUqaul2{#llAKX7@M|1+VoNywpEm!DMa@;kK*yl9jEox+!A zU+Jpzy*-_Sn6{^NEi)SK#rE_q!LmKwiMa+1F}Ty=a7{Kjm}S12$ux% zAZ|xO@T&}u8#7<}IV2+H$bRW*2KeA+98}=|xqD}R7VGCu$*|%BLIbdp61iZ5u?E}Y z=q%MCwdotRhi09n>h(cnP}F+4XQ{FuG}+wiw0WAR%kfsdVearGM*p9LML3C5R{nec zH>#lC5n6|fnFZyr?I<9vl3EjZmg;9hO0-QS+6d|2X~=;0q`EqzC%KA2`r<`$$uW{2 z3h6G8%m+UbF|+VMJCNU)lBM7ao5L~BdRMUjCEhW2$Yz70G@SJeVeFU_rXBM5XWiV@)HHoRX(@$ykoAXyP==W zDd_*q)feb(VR%1O%3E;7rcrNd#TA>!5nCYNUYupXV!Uzan4B+QPCwVbj9^Ybk4G#W zT%u1u7mS%OG`fBT^zJ68hUsT#?Z-6U4|`+3q|R`*yxeo!Ay=9d>8GnUcoLebu-L=xMYtS0|BOhu`j z1%bLoJHg(+Ct%^5up4$i>KbjgtGJHBHCkPt%?3v6vkKz+EM~GGLDyy<0;`_O>r9hD z!>10v!)j|}T~-?~C$A=XWpa%aS8cp3Zus#yeVh*GfuUZ+!ytb-nd# z#NG-6accf}D{ZR@UOQ9L8II@Z98l{gjGX8Ia?WQ97xbY=R)+bO8rNBW13N4IoU)S+ z%}j_d#paO3Ks?Jc^*=4zMMx@C$w#j91JCkYg_QIx&*s;NfmjjLHFQr!ZxAP7CGb2j zS_y1_ElVFyL2Y5+juxUKSS}2#2+jsfD}rYbO9uz#RRjfNM&sm2AY5EdRe(uQvjn@} ziRZ2PvjMAg;D0dyPsiNT00m?2vT8>9BW?r^0=m{D;~0AdCURL#faA>A1l(B@;7kKh zi|6vS;QdjT7=&89Rg;XX3_uHfo&mr%1C0{3{}}@yGq|?tZ*ZPx#-=azd9pXvda`qa&c;d*!j*Wgp7>QgQ*$ES2|=^HbtSLbMA z`b$dO-aJX<|LysK87cOw{6ti5E}sBidSkwZmUANN7`<42gt;fz(B?XWtf9Gav}{9T zrV%^tRD_`R;%7?Z?RCqUCqITOFvX>t7nX=!IHul$*b3RakPVJDE+~)#X#&$>hDnSD z(*7bP*&7$o_d{oG3sSumGiTN}`$_s{9s4oksN5?iYL$gyYp4&jDtH56I_RH*m=5~m z43Uxwrji7wLwZ|E#*d1JnONhw1}!_nOuvM~MGMw=OGFEvUflS4adbJ#*`${!T0bAX z5p;F5mk~>cDg(Kr$%a0A@h^<_yM^J`Pzw#KzWDbdh&i)ce}C~fL-gVb=8F@I=^&Gs zmpf<1b0-~|o0m<_ouH6P9|jEUk6VP2v76t9*#p1%?e^qg3`YilSH}@=S@Nry z=OdCMF=?qi%jW=DBs~R(R2URJ!pAWot36A?v}c(I^PVLk-m_d|G7_E8+I!D(0|45y z>^jJMmLD0gh`{RWL@o9#ZvjGkma`Glp5F3k}I##y>bx+HyDf!*Gy>aDtc@R)u@YRf!{==(B^_v#56U+k=Lsu$UnD zSwG~%EkJAxzg!DXxj*^BJ3L}}@=zR72GR>?9=;4$p}#jiS&7-k^{|mT*l;sa(LP`s zoBSFR+v;Fv-Q*7DkdX$3V{j>79gHw_usoPM7$NRpE~6ikiyW-*W_Pf^5Yrj2Qx>af z$_cD~ThyY19e;~E*igjO!Ol1AB^DNzj1W8>Y=hwGUvE!seLzdN0nSt|f-blsW?xKPqITR6WC!s>$;POIS`CSI5I>x3 zh6hveK=a+j^#osdB>5?(*?^_{qtG zG5Mue?yM4xd4SCCh~d@+18w`B0~OlFv^w0v@Mv;WBy{)NX)_8PhFCf{C?hn!yK|9T zZGXH8`;QBKEcvns<>t<3APR59iR_)s&pTQOfB9K(?0?o7&LrC!$=5c`w3VUCUhtn` zsO;gN*;SW}iM}%cH+LT70Ig_s8Sr-l>@);JH3wt{6_ufusn4yQ{Tv{Zm7ZZQ+=@de zoMNm3a0|SE7JXI>0PWJ@zb2dN$5e-LxcBpAQ|~nkQNy-I4@dWYc7kzq?`Iqq?foRg z_kL>89A#3n%jSKE6dN{{70KIU_k;d0BZ zF1O)m_6z`h<5HvCYft|_SKGU9Fr}n!xH!k{&(rPr-6~$w4FC z6MrylwS|QxQv^>>d=MyYZ2pIsdE!;pO7yqTd!HW*n4Xxti=G(AsV5!|8h+_eXzcEZ zIa?tI8Sy>~Vcf2faW8_1bZ}CxE9zFr$(GftnJ>>Ie_2R_b1P&iSamDpG=miFFIyom z1SESa(xWCul71#$LxbK-3X_K+JlHX20Ujbc8REtoAxi9z`r2;SR*KN;<``JuECN znJ#!b!a~8b*YP=Gwl2EWfF%&_PEhAw3Z@h6ix`dz15GpjO#F>sW$0~e%=mwi0t%OH zg{%{=oVdQVLYMW-Vx@c$UlyfNbY^+Ek;_Q-qC>L(bSvaH2K&{*Xe;C(D5qN?^C8(= zAt%b~^=gEv3E|*Y$e-dubGAZm5e{yJY<(ZMMtRbit&k^J?Z>Ty=8Gg79MaaH z$ck@}hSp|;X>FDV^DH66YqJg}qu~LTrF7z30Z=EdLQI|b5CawySp7dyi?vzf``w94 z5K|}qk6}wJEG+3Ocsg;J;OWF`5wqItM)SE+3*C`_6EGcl_Xk*;#c}G?XMu)aI$UDu z#cDI%2w85#QoH~RyDO5?jgU8i9oJeI`Tw&Ka*M&rDCMr?*&>A-Atyr0;;@JLh_qGG zfOcp9(1tS|j9R74Gca?YdAk72nzs(w*PzJTrIH5wOoVCP=D|E~3Guw`Y%&@in3cC% z0nohdFxvC>7y}j)SpATw#k}nagjP_GBBpuU-LU6cSXgqh;F-672%dSn$CxN@|M5JH z&69KiL@TK)5UU7roaXHl6vVu}($e$16|$Vkk|o#zxQ^8i$Z zCgwYLIMF9kYS;wng_jk`vyRVHAeCXT3F9WnatDYWBaOl>kRLilrh3L2g+l*yO199a z4Ztmsjh1G=+)Sf%y9notIYos2FH2~NQ?iAwGype1UhM$U^vf*PQBKKb{mTH{{`iao zgw+cGU*%1w7^{rfeCmu-r&SpM^2x{Fr2LUZNk=YN!*uJi6}HFYvv3sWTrWu$nLn3V zSbHq?KVtSGe7r1Y&h<(>|049g0n=KSBpcz9-r0Cy8zL`B5*)^{Td}ekzVvjNbmZR2 zLJ+sHA@Wr4=!VE_o^5YHBt9L^G5MJdh%Mp2v2!hCL!=Jq?>GEY7KT2_OGPIhGn=!S zkmLGUl7?e5)~=wm;{6 z*&=oOgV83!4`hb?6FksOgm0VH#Rnl{KTO{H7V8>b!d~_e^O2hf*BWFpAhAt^Z5}3w zn+QKQ&=!JnHxXU{kam^{*G+`k@OWpLBDAxdgUabFj}b}iEC*B<{Ixtd(^>vdsO&7~ zP_45}s&c~Cc;mEdN+`u4NucYrQyN-C&t5urz6y%r}-u9 zA7;@q&yiQ$L|EHQmN>+kUpC>iiuRVBTtu=r-y~;#>q1WuJFbWp2|p4)I|8cV&NYy1 z>&g1$FnHyoc#P{aEmdwJd|%Z)iv^=HTxAsQr~BP0nN4w(VW0uHiEw8mDy34&RH;#- zJ#Q>bn9nVT4!x1IZ6f?!)cXv2V5;}fRH9f&atZqvLfUsCeS(_^8=B>c0Sn(IS0Opw zM0hhGOT>N-+1a4cCPIa96JZ|2?MMiImEnu5m;T=0Df^|j7~qMKIEWYe%1g_%TP;hM z_G<5x3@fgtHvp?5XF~<_x=GAzA{3v=*+l5|L1a)4va&8@|17W<5vC`%SQ;OrUgB>d zUhD-Z6K-FdQ%7C!SX4(%Pm)&uappoln70r9vU=+IB=-^SFo~pckP3w)`v_-BjWt9_ ziNjKfgWn~W>?3?xNV7q*wd&a-<`X>7xxhow?D1CwzOXzwvch{(H$CC~T8A8IP}BpD zuOf_vf-vpZ=D|Ee3GseyvB~I%8Lf=K>gz-;)+KX+(0=XD zh-qDNfnj@Di1k0gvo1Mv3h}HWar8C%E;6wp)%uY2~)%7!Q8NfxMBA;8AXR@ z8TNhv)Ub7)a>G7kO7|nMda?r;d&x5B9%dy^T1}gBx$7DT*5$5ZgPdz&@a3*2 z0nz2If@j#DI^F==SnjGq5?$A@9LaUmuO>&Lyj>1Xy^h+&H#`EGEJ=PWny_c}H6XfF zQuHkA^lL2{cB$q9#ipiCDt6a&I<&Ia&h)%u5Twfu9b-&fG1Hx!toIHrzzrQ&A~oH@ zHVH8#e3K#Bm+AzV)NJpuaZ&JBe>(0ANj-C0H|mo}pw|I~jm4hIS?Y#SSq5U#zVIGB1X#HvnHOW)>S` z-ed?bEGWRkAxTI4J58nk+-ndYWBP`uM)qc9p0YMOu`8mv^%pPeMVl6U#~HFs%x*G& zoQ?l31Hg#%J)<;5WiKzGZy4V*#dL7;g@I#p@v?VE9eRLQ%yg`k$&rw%3yO#0ZPlTB z%X{B%z>KHHH%P4ulObe$B@2&qAXZ76a~IfkX!4+mm|dFjRX zI;{wsv54)$R`Uf`qh)D{Qqg)EmERe$lM&PHw+>7ki3;$|x+9>c9*acq3hBN$q=*nd z5=qJIx;VKf$zB%xB#uCKBW8FxCUH>9`ebYq)zd+VVdcdl#|38yVYu3ZC7;STSNdV!3x~ zI2EyJ*kQOe?0Hlo@xxNa<|5YN3C8xBimzT5F?JDRpFzc~q4PP3#EC~xgWYE)5_eDI zvkr*;_gKb0IxCSl>QKh&osDCvnlQFMVo$DQY|gznFYAi8^hNjfqs)?(L_++P*P18niu$Pm;Bo ze~c%~Hv!Y`LOdxbsCCtK0~5){eek6Hb;Q)J#Y+K`<&?93DW8Pet0-r0%IQ3oPm+bV zK8Po6;3IVo1TB#&D15mIQg1{#hrY@uwF_tPN#ay+b)i1VF&JCdIgW}X|BHQ8b-Gf6 z)a%4?=X6+JZ;wn(UJ1BEu(kw zX{`YRdnZ~XzHXaHY}aWyGHkz73dgoW_qM2Z-Qs!Bx^~@Br%G_&ItlLoL4pUi?@Ze0 zBPAGfo&;luNic4b1movP@Zg6MJoJ+U4<`;F--Nv-c;s{m9_=r|#3v+pY@P&@DkYfw zs{~UT9Z0?>J4^8N`4UVWEWz}rBzR$|1T!{DQ1-6`FSR>}e6x;|;N^=Yn0>1RuRJWl zt1nCN+Ngtxob!|fbC*i+zb_?tz3>py<{c=({1OQk4v=8cXbBe2lHiR>36@k#u(Sy> zw|3n(_mf~*cL|pFmmob(g12T%uws=2E5DRr)pm!GucDmDB)Q|0TA627fmQmtCKzSH1c$ zY}E#9_><71JPGGcZx_j{*o0@@@q=B2dqey`m17bKCKrw&{ZF#Xe^e~dF!b#O zP%=E*Gm+qvaDk&h+k~pD-gaTq&xr(C!Z4@RCseg)7~1hI>V}zUC&JgNb0Dbgy?>x~0hdZ}P@}+y2e*{q5Pa-_zYfLaqX-V4 zFOVZ(MErH+yAmAri3G5bS)>IQZPbZEK@lyBN{h4Nh)}c%ze_#N$(o zQ9C8~Or#nI(i)te3Sk63*%^(0O`0*Q>JyP@8YbTla`zFqj64;d1@*-U0pe6t@D0w` zqYjC0fbdp^xNB&D_Mt(K;f)gsib{pgLHv$@R+OLEO;bKU{Do(!LQmJ9Ul?}5vzF2G z`t9ft#&mJmAB3Ya#C`B)PP{an2EzFnVrOziFq}{@~#gKGscm;&T5wVGs%0%<9+fT_vgCVz;BaL;Seik9>GhHas6{Wwy zJs%uk1^q7oQqbS*vU|9GFzDl&9U2lxQ_-dwT4MXNVJu|j;S7^A_CrCLvkyQmUY`c! z_J;zReC`Ce@hjH>x66HdqTuatVI>~#(X^f9ct}p@i21jRSpbvMTOoSs$q>xc)H-`Y(`Rz?Tx- z@Q(z88Xrf#8~2ppro$z;?KBC7TqeQLVG;~`P=ecMNN~qm3GUn|!N}hc?6TXr5S8rL zy-gy~>TbAB?PSA{3iaSo%vaPQq4hN|ak5cph5iBl-ZK!E+$n_j>LwCj;a`)+UEx6W zNmp;#E8GQ02tP+ecNX!^L(Jd@vq6HB%}J+fDT6Tjr0FC`VpXY$;FIF2M1naPW&`kg z1Ok0M)Jtw`zq8RRLHi=2OU7&NHw+C*VUAYGq1dz{n$?5lBo+NnYLw>To<2x#^KXzE zS_04s|4bnPbPT(oM&Ef}==24&=>qC$F+?ZaNedCla5Y*e(fLXs`bMb4KB4Xh(4=p2 zz=x*v9T8C#mRC>g8`9$-Xs_@q){Q7A6=nfAm*D1NT0`s|es1ZAN>HnaXibE8KLl+U z2tl2~&G=-Pubv8j0+MWyC8!DWp>r4sJD0%lsjxe!du1aAq9#oq9E#y#iZ}+;6EcYX z!mN{kI6Q2RUQsGs1WIpGMG@$*J1U9fvElZG&`VMn3hL;HUo&AP+yDK-UArJt{}X;3 zL`|jwGe3r-g!%&BH@x&41a}Y1n@@UlxVESSj=g&07$1c8!p6gbWOm;lZhJa|99H*^f^Y zg&Q%umK+(@qjQ%Ek3|p~xIX`L$f(c)J@`~u7(p%|g#S6@fpFwbOlV^Sk*bgXIb>W& zB?+n3Fz1cLj{ApC_lCL;hq>tgp$-JB9buv^|3kJEU_m_jbodPZmY6g+2iGkHCq}S^-TDz3$c;C>8b$b%9L262im4P0C;oP(pbK;Uzqs zA5pYi8{e`J-Uj8P4D~=bI+_KMiaT~TgOb`YQkT@McQf3&5E=nfv@KjtlAndp1;BGN z;K)C6aNlB12AEr8IH^u7-5*1^59FsZkjP1LMEx1UE5Izu;117v%eu+%E-0U8sJ+_Y zEiIusH1BT7Pz`blo}&3?O<*VKs3uz{3%g_52QtI%fV7Wb^~IWo>X7{TW%RF!Iu3}_ zGbr&SLmiYn4Na7wt^(qQ3`%_8P+gP%LLWgr0K~)$O5V&+CCPoRG1MzSEXttxhKWw$ z$+~#Ci;}aKXyp_>0%Bu?a=?|zAJN*f(1gE0Org=Rn)JYM*>$}W$$rTf`F0G<<23gSotv^MV) z2Aqf@^H6ft{w84xh|>sA9Srb9@|UJ2VKIp5Yzb$BH90L=0P&*aXCQu?4cPyB0Lqd_ z-D!Y=T`(-gzetB3e2clsZ_reTl5Ifjlnv-lB^M`KLy!PY0P)mpK=nibRwRf0KhoX< zKB}S%AKtl}O_tpR5+J0I;F1tns-ZWL8bWVUq*noz5ec$i<=l9FbojK1rbLPz4xpT{$gOv(Lv6%+qtV94G z7dWptbBRr8*xwyIW$)e-?x{Nz^Nzcj5#r z?0ctPJ;1&O;U3IX%M1i+;or0NOs>De!MRbru$W>H+Y+Gt)!6)< z1VDapLSyLJAB2$}w@!jsEIbNCVelo)?`Afr3p@nIY?K-^4#J0AK~ z0e6Ssp+7OwXvrNQKIs9pjwVJ>eS_<;cI!aYn?QU-ly8tgD>D%fVJ8H~ueGB71R#vN zWUWg@DQI5s?E)*QE&xplN|4mVe4WW9ZE(vviz)?TfQLf61h6K!4c#YdPX}=}0dBi? zjYhk!43^z&C9DB)L!tx$Yzbx`wi50JaYv$r&2K=$ZNX=E+F9WR5a0A9xU-d@?hA&l zv8eBX_{&Gx*-B8mg1H^-Y?YOT>jwU9tL*?DN*1<>noZ~|`J zWKNq5#B3jBXHh}DAMAr36Vw_YZZ3~XxHjRmr_|%Y`3s6HMg0{Vd$mPHFrn1Oe?mv6+IEY;brcQQ`b7lx0b;a| z^5-B6U7yr0&qC(|w#)etw>kgd1n?b$LN61>xmxwuq*e8?jx*pi4fqT6I z)(%C1y^?eYlZ@#24PgKHP?2b@F3?YtqI;~4Ihgob;XiRWoMcpC`a9_yx2pz#VM+z2 zM9T_3J@hrMFQU&yz^<fhEX)W_MuwVFiv7jA> z7rhSS4GDdTxk$v^EYB@!L1-i%kV@UdfS6hy zr7QWyX7{P6duizEC!yknfUNLfsBJe!oU6~11gT=Q2c5r3*lUgz*`P31X>0B_Ztc=OON3%Abm3&L7W!egc z$17u!<|L}ODEYsaTc$U_@Lgq0Uc=lrtw{a=D;qIfqz;~Z;r}EXa1p6@nO40Uk}ts- zBut&bFsw2rnSh#^GclB%`;$M%(wz99DFb+|&mi{lf8+#hWp$Sw zUm2I*sm)ET#i;A~zO`nu}1`Zwdl&kkZ%}oj}i_S;MQ_gc?)o?kg2y0^ap2_(s zc?Ql9>Sr1P)fxYGu_S%wDUMYnAHF+(C*NCutKTr-CK9V_Cbj_vAIp_oIAzGAfdJJu zi-B0~Nd(}ki~(SmQ2(y^w+SB>F8BK~b7z4;!>3A7}IPsqg{?E&lKL;a4h(BUb^uC>r9 zfX(-z(ixNisb5mz$tg`|S?GGew))US1q6Ct%42_6=wpB#@u8jqZrcREEahVi2T}M7 zVE?ED?`p9z<$kZ#yu8)J+Svyf``HaeI@0U{TBKxU~l@+M1^1a5(*zn`SpGa{T?s}i~CBt zSfJmhT!--|ZOa3!g%3SRVZr~MGOB|W-4EEYmEfVUKr_Od8(HZ2fUWkSi3&g24nyLU z@bG&rbQ@qheQ2VE1zH^bwu4ppFkm0~(32Dv{ORGzXIjyJ0b8}uvxSF;!U7!_{^uGC zjRV%+hbAgq6GPb<7j9YCYHyE7-HBTLkTYY&u zRI?4M&+KtJXdPyuI(f0gm!vgY^CfBK7nqi7c3dr#a8O<&)oe?iHl}tGNT=gjFo;L+ zpVhMm>Pg*(!&EZhovA>&nGcZr%tPR12_MbWEZqhH1R4W%!uZeXM+u z<|I68+1VY&a(2$a;X}Np%A4U@5A)4%>*=NXMk5f}_C47id);H(?X8+IJ+t9sJW&P z=U#S)xp7p&zRB(+FR-a`c4yIe02UP4T|6zayLzv+v%68DTr+q$5ChE&+;L`|mX)Dj$` zD+M(6l>g!p3qfDu=QkfTNI@UfgQUqVms?30XlMccRms$P0HyYzMtP>}bs%SE-v?1` zf#~IdaQNc3{&rkra-Vag z!wUmWM-JZHmz}v7TOIiVIQNLNn#UX$xvw}&a9n8K4I}fKW6px)8Tiji>Wz8=EtPQ8 z!H1(LUF%U&BcNmc`Wv4u<$mZqg2hos5Y6rQxtFL+(6JlAOn(Q0k2_1T!YU=;S^OMM z1WZC#<$mFOdJBdDc|Ha48v;~=CPo0?J4*myyG^(e#yb8LkSZo^Vv zT6-ucB7nb~o&boLfgq0d0InE5oy>KDT|b0@SlN6amJucGNv+!(txh`?lqQCc*m9GD zHUDR8+zQyezCeLCF=4z{%8dlaVaAnep9SL83Iegget|_)k=>iFr2a1afNyAHr)dc9LlaL}w4>&sD9PIYzFkfet;gb^L5>>W?3p zB@)KZT^uuZ{Oski9X}7@*dIT)qoR9R*$2H)b>jHhi_#Z7O6sSe`{SqCc)W1}(R_lR zuZa3V_`UIS28^+afaE6V0Q`FZJAPi;2#b-Y0f@~APz}8C(+mKfAEpTU^^kRudrF5hX^@YMU54elk{ASwnyrcakhS zex}sHhbc7ZLLioUC>=i>9RB!;444jF&Xo6nYWVnQOn}o8XTx*sZ1_)4%!cP$$~}(* zHX~tb{20?&Ad+7n*RY%^^^y7iE$Mxcbmd#3Q`!HGq@$FSM!To+aa89!<< zn?OpPj`K@<{PuBgP1DX^3$o)Yqz`CK!URa-^}DSFGNx2 z`*8SHeunw37?;RluLcA8)eR>~tlJ8zogWC~XBoXdgbQv%f8}S}YnR3z4mDv+;t#6Oqlc+2VqfsmSKrY`cO6n~<$zvt0^qg#!68o9$Kb%TQ$N z+U%f$_0J<)V6$fyY{7aczn&@TN}VSZWa65Jq0v~f(+j>C32NN7sH~v>B4nG`?0E(4 zpFy^n>5gu43Kte^{Ri0=2B&`@Sa`81XoU9?`7KR5$uBnrZ{7lWE7KgZgM}+hLE%1_ ztDWg8`PHW2o?T8LzpEJlalyh3rr<9J_&!EH*etx(6eMA4&+lvVTTMZf`F=Kkrzyxq zU*z|<`R%5lI_U#UH=IJj!ri7|=rPD2B-#fH_nCqpPN4oFrc~-bfIG~LyRf9`%6^UH z!4BDV@)hqXukQkD$M5mh z`;>`>V!DQ7L*E@92;2hAx+TR%T!OUw=$it8*hrGQcW95pv7`p#J8{8^4MUGg2wuNRXPD1uT~zTit~yNF%z`{L&B_^>PHq4GO~VsynbR?gd6k ze;RIEP$DJu0&B*bU|p!J+|5v)dYn!DRJG$K2UV=M`3`*@`&!FO%~O8@wN6HmDQF24 zr{h!(s8nWQ8t%3zHEZ#FB6g1AxI02kQvqCR9;*j&Q&r(Oo2yGLmgFu+cZ>H5$>99#}2SA zSJQC|hxU$3%^d=2^`MLr?(9hAk=n1+3}BzkROv%WlyM}z%PboEhYY54_RjrU1vi9L z#Fd(Vc0te6R1!BuRM0b3#Fd)u)b%kH^bBEAmtSG2d2$v6O;bVKRiOyW9>U|(*e+$~ z=96;71z6D6eN;Pxv$%fkCF9t3KhLK=W)ePluluW<7~Ha=no}J-7-NtkYc0_;ou$yIgbG@ryC@6kMUXyg2tG7OdA?EdF9M@NGnAq4s!u zOBQHXahyAa#Td4KosD+oXgHhdIVt;Nq@~eZgol`K{ z_8P96%uJ8SBXkKBC^bC^dDd`|2A3u-zd%Y&_xB(>OB>6rO9`r4#1gWw4OJCI_c2Glf~iXcz^zs%17_U=z;Xd_6P5zxl(fnX;tVuY zmEis?QGyqQ>Tg2prFyD!$Cf2jGjCr8!u$MX4;pUcQq3tAJAP{10eVmp0dRwt-?TtA z^J_n}`&0f3ojbqE38)Lx$Eq480^pvo1Oe%$J5HHcdr1VqXHdQbHD0N?{u+omXt-9E zr&Efs9e*o{#|)oU$RjJC=w2>&zXimnhL5?-w_XMQ(C8QDhNpgEZWrrmf3<{rpn^{N ztV6uKr_YKR(7ETMXPBFK`pIwqFIV!A#roSbd^(6d!+kJ04Coi;OxaHsAw9!<%F{2* z$7en5FCUNg3v+8o(|u$UL9pKm~JvEU2C0cX~!CQuZ^ zIfnIh{mH!w@uequ%C_TC%M=!aXVBcUW(Mk?rMV=0OAb{1sgDBJHNF11;Td@3jHd+3 zGead?o|#@fRe-8L>ucpX{{@`7d{n4B3wi!|^(@jHbbAq~`WMs%&iM{@YEaq~?9SIP zPJ4y?l>jsW}Df=K9GxhuuXYf57nok|F7) z%5bQb<}e|<;ie^pl$t+rPSnrRYY%rZ$yyfEV(&&M&(rym+nU_+0W7bpR}$`Xa?6Jl zp!`RNcV&hfpM3pfp3TP~~{#=2onV zh@s}{c|e?S40mYBuEUCr8fsE$;f}6Uo)I|l zF5G~!+vUnXjm4rCkI;KO9s8K!U4Yol#u{$^@)24|ACrTLx&9M8tqiw?RRolp1GS;W zVI3XZF(wE|z8&Xs{7SJ4caZ7wg%=vvaF729z)%@7NzlSy=fY;6usd>s@;JOMi5%4W zIK0$6@iC#WEr%% z901J!;5NJdcDWAjEKlp2-Y{#_wFs4h;`k-M;@MUH%joPz`g* zK5XOyJSW%{;m69^`A-z#aX|dR19&v>BoE2@!7Tvn(Ptvz_@xk={}kK74OczG-#|vs zFrOO8{diX}$^AG>KLt%nx#vzwYv8>ws?M8D6^EJ&u^P*38#D_*PvsAo_^hdqx%)Rz zzL7rR-aI9inh-8@dF^!w-;+>&Pj5Vv>Zs*Ud*yx1np=VYQN+CC6_=U`dr_RDL*<8r z^6(QVudQOLb+gr`@(7Bt5q->SU=95&mk@3R)WO0ETopI=fs71klHo2v9jG!gO3iO| z!ChU~(%d^(@gx%)l$!sZ0~uK=gL?~o8E!4JUk2g}Z2`9(O1aJzR0bn=+GRk*v@P#? z2p*v=A0SC%gD|OL=T_dgj+}Yivgp<@kv7WJ8n}m1%Lkh0YQfh@Q!!~D^E$2Zp;&`E z8^s!dq2}`{kl8nA2C&SY6x(nsl($p(xb4v`j<81`mf~e@vC@W`R~LcylVi9sQme=O z^C!ySBkX>+OzSK)$rpn#SSKOwom7iZHJx{5fjrPW90cqD?QHs(Ts#=fdsWou21{2| z>r`MKw@vTi3b5mo8yHw-|3nZQxEp6ZiNg4IPr}DzZoz4K?(KdYx!QUXhvOrdi){oy&b>GXM&r6@ zHFDMCbx13q2&b@yo^^+jk+bfffO9+Q2$%5-Z0AoN&iM$$$W&a7H#BMXR0%3>isL55 z##Y=EtBWSBRgG}`XRJb+bZRHGbW8}yoi5k#!tD6#nEab`NflaNd=r)~O}b`DE*4+3 z61nbUM8$gX4ObyoqBX?hZ(+UDq>nbOIDQ7!HcbXh5x#cu*RDZs&}_+diSJ#7+~`Xs z*DK!eI^@P^?#%d}tC1V4x#{tA>T=GtJ!yo60cQ$q8J>4GS~_ALoVT=d!i(mE7H7Dj z@FhIt{I-hrxRkkI;U!L-Uju|!(sseZ)k*O)!5CgO42Hu~*`)X#k0HDI0_YMfyf!Jm zoRZdPc571nCyJ5>1Hr;Olj2jDl_vwi!h4hAa|vFzQYzY>6f@K*yx7b{LDok67&}`M zai%=eYXT*u7w|)AZp2OnsWqK_sj>OUegjj&PU6Fnf+h@ zH*12K+o3?yev_p;!okcxcO%=MHDfpha}5PG%{K-wpsV9QixQ1L_23P>Lqr`@2x_s1 z@ZP}p+mDSAv6s*)Dqwm8F^H(6l!N!+dsuzpQOFSb*`SqqQb13pw)HpQmmf)(HK1)s zq|ayV4T~Y4O)z(Xww-iW{*!EclUm>x`XSJcB+~a${;BDZBJ|He`!11wkn&so4k@A^ zpA)C!-;;lk`nMhF(i?(SoJh}yW=%W14V1PYv_XmVrL4cxFZk8=gI1PEe}nWcbzJ#t zK-=KcvrSSR*tdHxXbJxhAUsIo5&W3cAsDWKk)|p&=yA90fuK3)Avk(CXnKa>1|!sD9z}-hgnL#GR2qw3u(KM{%olur&Z(@IRWN z%z1#XOSrFPO!JrUn)KH(&@MO`#bd`kb}tG}@E9VwjP4nph0J)~;Y_#y!h?LJHIa@^ zlbZ3x*TfpF@m{MLMF1->z7z`{^kAKZLtvc=8#`|GTj1_WEQEfK={a}|=&_T=k1q>2 zkFi#iZ>JQ~$E~cNFQuPUHrb@1E6nvqdaDV5Qx@Nf*M`>{8f)xXX9vt3a=F2$?dE6L zJh*@+3YrO&S^TqO3ns3a#zQhqJQovUaDiNkrkdCH!P(pCtSe|XfoIzI@$*nXAvm0c zLjosu8wan1r<1)`V6x$qo&22C8{9{o2Ck6;(xjTgn|I*<+K!TS+9zYX*PBe-i5CvaC!AIq&qeI`qryg2j0;A|UBltbY$^C4_JU~b^ z50XZQ8>22EE(fG~<#2&f^H@g<6n1k7qCqONfi!-%G>UFJg2RwM*M&$Ou>Hh9wRtSW zn|cEIVRP^zQwPaw)LI7g8C1nGK2qt8ig zJqupW%sx3DeOGE=#@0^3z{eoW6j9HJs7UbQJ@tg|=2=qPvr>Eq@Uwr0l3lI8wZQ49 z{h%qU4*ussEKA10h`Un*bCPYn^xrVIdP3$6Am(8U>P3NYyL#bv^#gOZBv7%RbYWt) zXZSbZ(|D;pj~75Q9u8A5<>FrkB@YrTHg*zbfLU_#1kyMS&;JYT>oGkavr;F+*(m?s zg_38I`7ZpFQRd`(QUeQ4SXfI7yBvh`3-I$4sB;?F(lKaMU{2?R+`=I?W6DTdR7_o$ zl-a_IY+CnT#Ls~+^A3J4;JnNO1hNUF@q)RCR}ZuHVvByrrpv$;90*DweuPU}ZH6tL z0P|m1HhDT8OK<>~!H`kLnqS*zc|WpgmHScyrIaxPKTBA%$T%Ct7rkvU=oM!k`ev}R zU^WD8prB*lS)zGW?Y0dZ8z|^T{FH0L(j#Pum~@M*Yg6Zb#9blB%O`PcCr6ekw#cqF zodk}b$YBOmtm8X!)H8!Da;i zdq@7k3U|4A&Qf2ssfZc}#*;}a428~l(IRi-aK~guA0@#%QRg1~%c;o&BU7sL_0u>G zq|u{?%&V6e^V*}hXq;sVzE#I$$E-N|JLlgesM|a{JP^3l$OZl^nSWvrqH)L2xb2{< zG&9bcg#j(o-KU_;8jQ=XnJFKVM0TbEFfU-{NOmf+vo6GC+RQWj?BD_BZ{~$;qbwz& z@Yb@*9LCI6{WVpftTTwy&7Eh!uAHNX0!=hTq1RY3t9esN7yeLsL;?JMpAQ_eEqQkPU**f+5Pg9CQb zGBd-%9?_8r&(RQsi3ne#P5|dW!>}noV+*=&k#yC^;MT5MX&LuX{vtC3KGE7Joo|29By(vT|*O}td>`vX9WSu7^adQ40@w^M>e|AJr`BT4*7FEfrk zIjpg@I53-oa<6L(ZK(`K+F>@wqD%aaL^}>i#NTQe^z&_s@PhfL_bY8jGM+ zy?$PA9+spF(h;n|iPF{?#IqndRPD5sa1r;JQ_Ya%lth?ND zEJ1nL>c#Tw{PJa{x+QRJK=A;>ZmvaJL8h%VaEUQxT+$h*2=@V8tfbqHz4)k(m9en7 znR6x%vEluD>Ul#f+fm!g7zY1(cNP6Cn?K?Y*krQow0`~aKVua(bY4p z40iRLzidWVb#5O#1robz4GnvWGafgS>?)Uh&Rg15(@>%Lb~GeVE&PV|QJxEUA)&8^I^k0>WtTyn)}zqKyD+v*6FWe+U#NX}%u4>wt)YVx z1z7rU8bnJUZkIY-NVz`LGaWsMt1K@uF*uFpU$IS1OXo_%Ym8i9PCyVx58IY(5j9+7 zBj;k)%%Aa2zZ%F689a>FB0IZ2oO>MfG*wqbM4G9YxXl5AuMc`&*IeVr>sp z@$Ro=kO$Iv&E%Q0%gWr!ULEeV!f+9}wV$$byYhf?r{G|jdC%gl+~5+Ni*of$IC&^{ zkR7gP+0^uQ*1NKAbY(y7%1(cpvL{$<`?1AxQTLj~Vvd~iyDitV&poZ=>|3;ftK>FiR*$5&)$XT3yBatb&G-26?`004 z_$u={R>-CeDeVv7@_GbzyxQE2r{ks%pIF?F!plq>jF44UYM=)gN;iUGgBgeNcFsm~ z22wl+#P2u2FEdYD?3C$j<4{v9)@=uME;D>AbA_dMp{$+{K~@os zWtSvG*rl;6;27$0m&T!kP>M_AdvIWv#_woTic7d?yN3#K(e@LOT(mVi4$zsqE;y2CcFxF^PYtj9!a$Re<+Azi@3z9G+^U=2x> z8uBERH6#(%kdImcWvIzDu|8#R7A;e ze3epY$lEIzk~gQ&<}hrLX2s^))WiOGR8vgwh+DXvrFvzmImg!ll)d(^-HS)?(R?m?}C<@i>yH_-1ZIRy~I@KH6*ww z2liQ1!Fvt|R3Q5`+)EUn#d`^Pr!v)nMFLw2rS+iLJ z2j$(ZIr%*4SD@vE`#;qJGrRG2`Ehd`W&X?ZA z;88WSfq{dzn2|U-d?~*dnu+_V;$`dsLo?~uY(vf4dBH&a&v0|jGI=2xl?Xr0HNp>{ zoN6&X+e0IhyXz|%J^|G?^8EY)U#<3p@mid^1I74im9<=F4CCZbq%nLnp`RFW!+I*e zDZmHY{~W~=z3w~kG(_I3@i~RQKrWRyI4SG(`=lrantq8>YGzD=x^K$nGQ;~={dBI8 zsg9?hEt{U$WMl_BUX3P%3hGOoH0=gI;*c1^aFwrLPVIt5`hAWZadp`%0Q{F|G~cQ6 zb)+%8FH<}Lsf6OorOA91dX*Z6Yj~9-2zdi~qZ=Fv@+QDed=skjcn_gwq&^VU5xvw3 zJ%o&@jx$e*a#WAm9{9l<)odg^!*%4BpOy3sH^Q-etlAz2sr*4PFc*bjIQ4P1V7-Xrr1X&Ukr#Oib61d5j*v;t3;*}3#nO+}?ODF0NKY0!W z{!@Zy^nuAUukVT&YJ?viBVe>Cj3hfQk>tUxlI-M;v5@o7TarBdlO(&+Te0ww&m`F$z}O2pj}}Ps z822`XoX4j~^2C*rJb9ladyh!6|7%H}s@8_cr<+T1;0#HgIZu*j*Gcl+{gNDfS&~EF zN%DL~Tk^foNRk)3OLBO!Brjbe$;-D%a^x8#$xhgODQOiGZpVDYG?FyiP@iO{wxMy7 z9c<@E^OBvqh6YJ?iY#A!%hy2oQY5TS@bmN}3>Svg34S>mGh3Kpb%I~j!C@8g@EFvv zI_F~KMEaq=$PoMlqV17SWmuh{gw^Q}yjf2S$%;v3Se>AR)e-Xj<;iK{H76)xby%I@ zQ_;woWS1W*1|JpllN;2qIxI2Yx+u`-k}IfTb;x2egNe+lMODMFIzbJqGmfZ^MDeIx zJ#=>#)UY~&npi378p_hJI)Yl|p{QJhR)Jm&tAqG146DNub1P9(P-7t41No{FRwt-o zby#2y5Fm!FY8X~0s9|-)Y@fKyDxsQ$)d^}?9brzFusT5vt0N_f41^h0C+Q&v#tnsv z&q4j6Q1khcw76K3mTM(xo!g$YHbs)OEtaHRM@c$7C6JEXT@(tP_Ld}_K9Z#KYJqf_ zD@nI&q_F!flJvM&l9ERxDeWncUV|m+Jw}o~(6Ib8L|XP z2E*zkw|OiXZ@?t1PIBLea9o37b&~tvh`Gus3i%oA3xTi@aWXf5I&j9J!FImItoD1st9wI`KP=sN1 zk|nH;jMxnTY$izUQd`36BuiMGm#OHzJ}nUaf~R>XxdYQM!|EjM-UCpcgw=_@2xypL zb&?(~!Z5BbVRcf*Oi#gA>6aBrkDKtdjRS#{@iLLolSsE*x39FN`$S|CdGFXEIq8~!5P`Gt6aG`LU$sL)r zUCN}&g7+jjKm9c37SEUDqN^oYwq26t2PIi?Op;4}lVoMRPGnfqRg$$MCAngOBeN%p@{?K4+82gpOU9OzJ7gQTb#MDb14!YUY1>{rYoCdRNj z(M)p@uAj))m9RQdgw>e}ROasxVj`sJND0UQj4t{W+yy(vfHU7*37|1iN-f-nYeuxL zX@O%-P+>;Si7sSaVGh^mVh1BkhHLb~G#)Z?PIM`qVucwwC%WuFLmV=4PINi74l{C2 zbj3?JtS6CkqE`nSN8r44#w3(q!%9(65hLeBH)}3j#K<|(YwyJ9JawnAD;_GHK*Wt9};u1M0)ke;F6x3%bAR0>K90U?%|*?92E?=$p^WHDl$T?9ra!!q^ZbdY3gg-9CjhxfQgS<)z ze_V(gIcKB?;fT-?U@LMX=UnJPq(#!`W)e9ks*!WJa0r^42or7jgKkN}Y9#7L&UqNr z7w~UKnuk*ZHIc|UQ8#kVhX68|ksS@E>I9^bb2tM9O|itdi6U}N)oQ@;Uq?=JCG0cC z#8KMHqv&~U`4Bm$Cn!UFYBt0oWKaa7EQ-iEQ$V?(JT;+h7Kg|=>wvlA-*Dxs{K%L` z0esm9d*h=V4v}*{0Op4ZIGJy3y@;HXl#Y+S@SkW-4w7=B5ILs_FztL?orG2*a!wym zM*Gya3w;4qXb42knF;a*9>gw*8p>KUs*!W*L8iGHkgXmpBG$AhjhrK>$AEa&N6ARC zD2<#WsAE8U<)dWmTa-r55ma&p=70QK3rNc>N+ah8stFM7d=y(4Xecf}qZ𝔇Ql` z#7Gb20yJ_CPZ~21#0v<}nY4vC1&wOt9FcG}h}ZiPEI=dYhy;c(dcv2`&@ggNR3qnn z#ww12_`WZ}0yJ{Y`vm+7;@^o97&#}Zk#j^sc6F?9@NdtAh7wvQs*!U1ei9l2%=Lp~*5R+>pv|=SzF;R`2BY+r)4SYacBIiVHj2Gc(j0juQ%y6FshMr zo}eY;Ahz-VT1P{PoDY$Yg-oFk~|K%D2J>}(|{jhrK>D}cDpN7>m* zP#QT$P!9pI&qvvLh;e43hb3~3pxy!ExR0`W2}&d92r5tu&o%I$pnbx%38y`!9+${D zf-eTPtB?0CJFvY#HFAzXM*}vkJk&*L8S^R0VcG?T7b|0u38=9|&WUQ|9O8rKQ-Ga(uRZ>d_AS>~ zBIiUka*lH4gQHz#Tz;oElgK$yjhv&;LB@kaM?Ft`y@_fjk#nLNIY(iPW>gW@P$K6< zHF6GBGYnz0iz>+SL!SkB+G7>T=j%}$Ip;;--Xd04B5VT&(O8IyYUCWMZGHgageMUI zM$U<9@_~#yNE(LfokL&fo=zEzYq00!a|2jyrxikK)Ej&CF7N|zf5ojmC z2KdlKg&DIZdQ2kc2y{ANi+pIJ!UEOEIRd>3u)BPyr+{l=!E59k!9NY`>y_Z4us}6( zjzGTw>>nSRs4!#JL^X1bKy&bTy%GK^84?23$TWlZA0CH z(#Sc2dJ%{ZeUvBAUAG8cBj*VIPhj&3Ju{TYmz%JJQzPdHXB%*J^EqiiS09a>Bd9Sz z%=J;e{6xG)&Jp}NVDI=hyqYG;cQq{;Ifs^Q$;dfP9UL%n4&Mp|@+5Lj-o8UHaFk}Q zp4T020n<)BSPw6M_;x6*4Xdxg$T?{pK0$TzVu|lT(^~UAXbncrN$dEJP{KiZjg;1w zJgp=wPTJ`~(+0vy@t@hKJL-w#;4nf4ycT8ToV0G{Ocagx5O`U_M>A;>Ifp>A5VWPF z7gGZ0+t9EyiJU`e=34yR?9*GzL$Wl9oFnwzpzZbPZ4fz!770YT0tlz$fn(Lv+58j< znp5q8YIxxr&YXmA+IGIlw`V)?Fsj-^yb{Zcv}zCYy>Ckf&0$#}MS|v3d#tC&w#R4N zOJgY8KE5LsHtEy044P9ka45J8rjvG%6v$xEob-~fo8axE^P7H#W9;WNj(koN%4kBv zhccS7j_MLLC!@p1^-&4CC8LwPo~FhbokimT>u}h`(;}m*_tH9}o4&MW(435c=D$$n z6Z~g>1~vK8TFM8TUr^>izLrP60To2)i1sOMj>N;skf1rYuzBr)C?V=6 zijF*jGV~&Y=443FoO=lx2f#T#=qUv;XikO%%@Ii}0JxeUQ8IE3K#@17QLY5d$!%Z-hCtdWU-G zPQ0dM(46WWZH7T}s(0>%AqC1l*sgjPrL<(w9GGB_>V{4VoijwgPd7hk~Yzic&*^=7<;uKRWCITrqrn zSwn;7NP9j7;zy#SJ&{#xb@Udf(NKcs)X<%`0nvk~ z1c6vl_9E_hN%r)-#;Vj`KjGx*#2i)<~oX2+j)W@+uezF?D2>8z|mHtl{Kh06v$)iO2 z(~{o!VbGkfp`#fA#5khP6n<~~Flf#R0v6(6X(GUm9|p}CN1iPpZY4l9@Wu~==J5P5 zkAcY0MG9~`UWUgn4uj^1m}5YE>Y@Dc!=O1L#_+<2|MFt&_+ii-X-@+nS`sDgiA-Uu zqaQ#GZ~QQ5j?_q(SmS(w0`F$PAsmX5UE||)(D*nVG(JuTjgJ%M>y!>g z;^ROfRM*?gOA7h`;!T6Ju;i^Kw`6|>o1F~-NKRo7+*#TXx_R)Ni)8Do5$TJ=m7w9F}- z5Mz9tTJ=pe$xe?kK2EK;ZBbdQ{~~0Y*z9>R#>c7E%xvsP-i0y7$EnrA{DeMde4H5L zZ6JvawT7yJ;#>a^< zK2EJ6rm@t206rlZA1AXb`!z-4<75R`cM;>`WCi{}v(T$WjF02yl8P7~M`7@~Tg3P{ zZZ17=dRRWk&3>JqoO2Y%Z4PRh3g8lnkCQW16+S>1e<0*}BvF;b_&B-ms-#~$ zNph4}Ek&0|e4L!0RatJNC}(2E$I1CaiQHZxL@+TvPHr7lg8MC0R}t=-j`4AFmaFNw z7ejl;rREL+wR%uS3AboOc%=3#k@z^dGgbNy5@j4o?=p+Vo+*Qg@o{qQ*DBtw1Xm*Q zadJ;nN!;B~LC=VYE0Op(IghCzZVK^rbrFn@lRHfXaeIU!EIZ@lW`j^+02MoSY|x#$77q zX!)tAdyB~A)|GNHzopC*>@vgsED3xi5+5gLXi$i4NtCnH>)r^<&Rh*Iahd#l4WbLUVaVjE_@$z2;&?jE_@$Bft4Ze4HZ2$EkglE`y6PY#ARX zCr|r=+jgYUDBt@z>=f2niTikbL&FV$&aJG)aEFg?Ef>J}IJx`8)ZF`1Q9_Bt z$I1Om>t0KQ3AQHBr^cY86PL7o0fC`lizmN)Qpdl8y8b^XH-Se zy(B(PZixW6XX<3Ytb5Q|%LTyQR0@z&(kjRJIJrYr32w9!C3rz#e4L!6da85ll_jJ} ze4HGKkHa1`+>fQ2Q!KXbFg{L>#>Wu=cWU`f3#3VWoE(XdBXn-zDkq@s7zoh#I0E42 zt^@&94ddhFXnY(2@NttbL5)`;@o{nv8ZL|FL6jnF$1^@o&N0Ks67qD)C%PTa_&7PA znkq!dwk}o`A-f{_gt>F6Pni3@de~nrxfKhk@P14Oc|}~zg&QI+TVDMv9v=J(r44v; zg=?LQ!-gDr;eEt5=d-hLoY)pz6NZbjP}+(soNy+w?KlR*0j!Jix{2H?;RiUcyT~1f zYhPXuk^9~%9QG8s{~!cWUVo9hf!F~em)i{U28!Hwi5)C*-&?VyBDT=ER;O67~^$t{nc4*co#8Y8ZzLh3yp{E|$^;-Eg={O6&7* zHA_2aOrZ`MQ>aIn8(w;Zxr3>X{Ptx`p*~WqzdgdQg4iScE*60O`hl5bF#UA#T503kUxi2O~VhZKUwv-~q6w2>lpFb5brci!I&4r5?Qz*Zy=F*GW+yz>x z=CX?zQz*Ze=3+&RDU{z^bMYd^6w2?Tx#A+m6w2?bxpqbK4QTx|*QJOth4TAru2&Ib z3gr)AGZ0g#h%tro2WoC`5n~GF57yj}BE}TTKSOh86m|U!xnY_cTEv(_`6DzptcWp% z^2cdzcoAa?<&W3gh$6-m%AcgUGm98gD1VCPMiw!qQ2tcSjVjtfnbS2lx`;7_@@H#q zOc7%W<(Fx0EM|1Z6v|)1HW}{tk+VfVCGRgWh4L?6hhozs%-um@Mg*#Jxr_ux1gdj| z95Q&%DKU=c&f%B@@8PbYA_nh?O<^&vxC0oxCw7+Rk^EXiWT`w0IXQSdi!=uw2JeYoP#d`R4AX-MnWJ&sBRmnm z1E~$SG|97FeZX5HVR~ZNb_$xgoJ9VB<0>SBs!Euin1<;Q2sc3~q(s8>#Ip1f$X!ut z$Px+DgZOuX=Qb&~oMC!mb@hVAeN%4vkOGwd=2<53(v;78s@{)>a8xfHb(DXxK&G-+>0E; z^wgaz*H7->(o2+gGXQRe>4}Y3Zf@{0af2F3y{7n7PWYU-s1@GC1HAEyV+R7&1618 zE9oU+dSXv-ely%=RuNDlVR~YRb#!nCnjj#VVS4IbDR$wGG+jl>MMy5)y$r+j)Ez2A zfY0XrxHpge%*6Z?b*@FfzaC)P+WeteGa*2pkDu~+4q$mjYMRqZ8VdSY+N zC6Q13PX;hdPwYNfjqzQ84?ueurYE*tF2|e8(>kXYNSK~|C@x}{o`P(BND?Swn4W?h z-j_2>Pk1zzQU$qWKZ9X-NsL}~E&71ZPxe%kT)5~`h^_S$ zjm6zvxN<;7k1!uz$YX&bz~r$2OJ4v@N;|rxH3DIV>B*c;6^BTeo=k-483lTTKVae` zuU-dlh{dYNZmxFg=-HXbZLxAtsc$f~`eW(=G!drfu2l zA$WwgJcA_424PY~n4ZjU9Xazpba5!3xEK7nTEp*Nd4CDhQ?IF*w3meGDg02Z!JU#~ z4fHF+^kgDT54TNLg*3ZGw43y1%y!19^p>~qQ!hmHS93fXu<0N z_z(Vv(=9p=@J5-hNQd#wZSYYPyi|@loS_Knp-vMRmW{<+@I8<}bs;=}0PbEM#{J5{ z-%(JlhZQf>1OX$=1Fyk1VcN9sP2eyZ>UshB-g*PcIttG@_ksJ&iF@D!Cyh?B+d+&9 z`5R$ou!e$s{PKBw!1^X}eUwyv6WTQ>akVR;cGsZn%oW1M>~F}9u3`D+0h)t5SY{fm1cx$N>;A{4vcx!2@-db{tL*XuWH^+gwC zSG+ID`adMu&G3 zlw|)!l03CllBb`NZwTT4j1 zwLA^Hxr!K)6(inSLgKAO$Pbn$tGAYrcxz#GhOSj3pOamFs2HA(aBo&fy|u8!{OF=U z<7c2D_0~cbSvva6s)c%M38}Z1Z;66u`apz7J`}PJFG4-)twm60Rf^)~354If3?D`a zYORN&auHeuvgoZPq~2OsV(uX7XVe&o_Cj90wS?4L3k%Fa0>rTDttF)1TEuLhyUZ#< zy|skYTZ=HOx0aB4YmpK~s<)OZ4=sdoLy_V?P=6@WTwF{Xb>j(MD^AZ z6>lvR6*L!uxPpN0l#frPs8w{7xf*5H`;4}HjJX$OyS?&AZ*aLxQ)WsemLXl8}-ddvKtwl!c)c{;iklIDPwM4~R%LFRA-KPbj-|#dKMLRGR zZ!J}J4+O}1YdHd_cx$Qh@b#!fy|tu{nSrHB{?7W+@=OR2_ZO*C z=HXDiwWQ85O~KX*|Cwv4hFd<*l%Q;|S01?%RO_uJb&(n85v)P5^9@>s(pql@E|k{h zr_-3UO~*PWRCU2kxU&pZJ^xin7PrOiPpIle!zEcZSCZwINwVTDNiNwh$;z)KSrh3( zhP4HfT+vyQ^*pOLF~hlH9;MmQd9jJ4$lX7)iFCC&?|F zB>6sB>igw#EG$D+f88O4Cti}|_jorJ{&8G#e~O2cs(C4@+{+Hp{H11K0sm zDBfO-xzi&=G6x0lCm(V;i~c~h_2}ls$u}Jr-*J|oVunBjybc5n-^yxm6Xp+ zoyEx*nljFv3p04g4|$!X_n}MW`&?()*Nt#UH!sd|HdoxdI4ja|SpV9`abh@E2dCqv zrUBi&IM=XJRMdcOUYyOE3pb#f7w6h@FrN7!puV_yajp;2uSb3{m}#*1ii!A|wS_7l zr<<4bw)-$g!b1Yxyrg$a@5xL<@v`8Eo0sFXpt^Z+#LbIL9WO)RQT%7tCIhAxx_NQL z&5O{#1??A~u5Ml&b@LL9qI2<|d5oelZ(VaHc-75I1C%#Qq|wcbqi$ZhqkN!8i?H3O z_{nDg5H~OEWiuUs*&YaVx_NQL&5O`igSN$^%b?Jap>AH%)y<1&wihs|MSoYxL(sajEEar5G+n-|e34~Rk!1$P;dx6v``=0yPQ zJ)$ZsO^5pqx_NQb%?oisGZny@1ivn(wFq_dqKMU?(nCw;J4DEt0YP;0;;5S!Ha%z_ z0AyF9Ai8;R)Xhs0`ZZ|i#rUm61eY3)x_ME=kD&hUBbteu7sqw;l97gSjek`HI?&CF zqi$Z`_ac$5{+`Krho0rkR%&CB*gouEfiklZl-MpyabpYR32?La% zn-@pjyl@-`&2Hch_*fBnsvsX8uCHFWdhxNcq|RV#zg&5LuM*@_Vy zG)+B-=*~5M;8bz*;<#>J26+$~IKm$n;<|a6=Rv9w!XFpnx_P19Ch=;6-Us#OPFZOA9M@dyg06#mmfe4S93eq$EksuiJKS4b@Orxfb~6a zpt(*!>gI(rP|(yBhb#`1O%h=4Aya>wW51 z5Q|HOFvHEuEucJ7p6cuD;^5}x5HKJA8?IcH9~tutfT`)84ZQJD4hJ_cb$~gw0#4=| zs~_CFbOm{Y5Ag;`IZ<%)ayBsYecTTTt%RGGRiIq!Q)}Z2;|idg7YA-$?gsf04`MHk zjb#z*sGFDHAk(}8$on2FBG$Ahb@L*qUx5f_lrsRFDFrY^I_l;{Q29VK^ieYQElSwdn-`Jr3W#s{5-dR7yoiJ!Ks@0~Xe@4C9Ch^6%?n4dsSRR5B7lz)9Ch;| zfYU(io(NcpRg9xlH!n_pP~5zjn)p&3{|RbvvG6EF zST`?)pf>UlkWV)+j=Fh~MO6`(KZ%0FOIr-`G%;q zKx`(;H%Oo*-Mlyx#LbI{+77@I6+|gW-MomTHvsscf~3ac#l=xKFM|352q)965AC9x z7f0Q^NL_g#782mLi(XtDb@L(;I)T_DQGx)}&5KAF2jW?Y66kcrQ8zC#D=Y_tA_yX?UB0#!FJ0=*Wn+sZ>- zl)8Bl)E*#S_EG*hWCg057lD2b*v~#x+TBRpyg1g)OEe45Kk#qcZ0*M>eMVXg`6fn-_t; z1=z>sp|GEz)Xj^a{sy92w%6oD`w3Ltya==*V6A`gviENF)zeYZI3 z=0!yB2JDaz6{-Az76Mf_FCz6Lz`pgNEOSxn=0#9daM8%czcqu@Ezm~d=EbpYUWx%} z>%kz0o;MtI^CF532637P@GbAI#00NyUIf1k*jxS$@3Xr#shbz!d>mXyE8|Q&FQhtk z^CC>&fg!oJ*G$iDdQ)bbqi$XV9|N{yW%$H?luFdii!coX!?`|_XUlRnP&Y4vzZBT5 zmEliniMn|arpLf=xTuhdB`Q8zEbbP5HGrdQ%Hd8k* z!ZZ{Nvnykg=J3Z=Pu;u-(;6_`RvDA0sLQlM+`I_W9x%LJ857rtdY5U{Q#UWd^dlIm z#BJp=#!RpnjwZvVhTN0iO0)<8$rC&1Nc+1J0A;P-Mk3?DPUjo@!mxg+6z?Oya@Db!2b53en(j7aB=e@ z(Ckxi>xX}9I_V4&AeFvb9Ch;|(C&Z@^`VIh2vps?2y_-;m-tXm0k>^}S2r($zX{j} zD#5#2sGApo9s=wgADXBz9jrL&=0%`C0TzmRZA(;Gpz7vDpr-)V+J~N`u;A6ri{J+W zJE0Oh6c(tuc@gLZfUWhRi3-!filc5`1bRDQyL@P(!U9z{F9JOR*l{0vlEQ*lH!p$@ z)WwTI{M&x^@K9Kw>gGkDjR8B&hbAga2P=-cc@gMvz^3`oM1=*aZe9es46w~U)KkD6 z5`tGZFM{6z>{FHCp|C*J&5Jgc3vfTC@fHQ^CHm80lUeECMrxfFOIr-X~bz{H(-Z+DA`?$(XEQ3 zZeHXKqFT#)Ga7=^CGA!g?OEVe`^6xpnJ_0yt;W2e0yL={u^FYDW{LRc@fTe z;9BZ)(txf$>gGjITYz}LNBR0B;?>QI;12=&@xS3!l_=lUMEN?X6@9(XyshZ#rMZIx z`g-B3q4K_7XlwQLl5uLJ2oFyAiYTKEbr4@K866tnL6*E-5~m`q`4&}ty<~LkDirJM zC8I5QT8kr>4ETDXrMmKXEa<|}L5qM+5=QA1N>xDqs zt+=1`B>Sp|&(bo)*9)bYckuIpPj4en$}+^)i_m{32u-s5ZQ<*M770YT42afbW9jgv z`suVmyW?x|;aZJJq4p?m-@OSMIXOgvbp=!Nfig1Cn?}u@@4}4Y3Z~{myjsi4wwe#~ zrE)8}f?=6;1yl2}J3O{MKHFZ}O4;`D1+=h9zjrXrufr#kXH6Xh<(~s@Tlyj4#X2Ha z?2e}38capos>n(54*>rUT^-?VsV;mi-$lyTw*LPIJ~@vp-z4Rm{r|!z(~7j?G`h5D zI&cXX489*c4Hi+CHnmD7qZ2~m-}GB0W4}3a}Pe;H~Vy5lQqz!G{9#y_|IGfbGt5WvId(|P}bNh zk8pnlMkrm{WDPf`fzaC{+9%TLttLxc+C0zZO#)&TQI}G5 z1S$yQsb)Hq^c3Ky5$e(=yX_bt;&f?~-Qi&jOT3b$OPlPDHba*-*`4>G(?Hor+jUV& ztI_BTPEGg};E;YT@V0&?@Uea-@QHpOa9qC+_)I?<_?({!s7srw;?jnkhOeX}+aODR z0-e6tkABWM;PCx)5nbBkJm;{(F%hXto1B-O5)6KENs@EK8O>w5B*}Tj`9Gw+2Y8gl z+CKiyzH8WQ2wAca60(F{60#{kLN5UcAVPpZ=!9aTl+dJ!5J4b-H0e!I5wRQ(cCa^& zDE5lI9Tj^=JOVb<-+ezb@9rk}o&W#(zFb#!%5%>%&pcD!dFP#ZrVRd&SguKfNgFE{ zCB=W^w=u9Oe6)Gr0~Af#G(~K7gyQ`GbPUrpX_KZ++Pnp!R51|!i26#>=Zi@j98zDl z3#PLOI3L8Ru>hJRNz*26jxo&&5Z4i)CCC?(Hfh?V4a===1o5s2z$+@vS2RhIrcK%i zo9BQy5y2sJq>bcQ z1Xw>pMQ{zx7n3$PI)9#xWos!v5Es^Ai1!LguT9zruQfnyKZ6%dlHe%!H!m4pcL4Fw z8N6tcBu$&NVI`^8fp{;1ijKJ*XwpW;>>gs$2JNSH>uCGoC=uI!E{$nF+hW?!np*9r zI3G&Df8%?Zb!__?i`Xd>uh=5PygOoQgN?hbC==O+21yKKw`6nD#@HHo_(k z#7+@_!^X59nzWJflmRiGC@GKk)q!k3UgREWKQw70IW7ilO_ZTPBkhMKZ6w?4fw-d% z!$|v~NgLty3=prM!OOHCnzRvKJVE*E8N5vUp-CH7lJcWbG{wKElE}k1+J3Z2o771Q zfy$vto7Ae<(QvvM4QbLQb%vqPq)qC~n4$3j4vpHRP3ok_|1X^O3nwvYlR7B@f&aBk zw~$i;b(O%*d-l^99qcyTyQ2z0@|F+6j|@O(*TWYmyQh!_lC&y9>bcnlX^@a&qOD?W zAE#K`$0^qKaf-El95}R(Q>?^3PO(euKzGc`#6CdQzC62C(z0SwSAmG8Db2!v{Tbj{D^&=Kzp@X!Yj0WoInTlA$UjZ;{>{>V-jAg?c)S`sWxC2v5ylNpk%MB zV;?6l(1iCYv5ylNWWxKD*vAQ!n(%%l_HhD(RUyXZh<%(unMiLt_HhEk)CtM|Nn;-; zy%+1%^UERIYL@dZYPHYT_~HLK&x3#-C#G{UEQ%GT>6{E}E(oabFiqz;A$ORjb2JPm z;lebX3HVmb#0XC?k571a~W@0so@$zG`n~sPCqKm|IPO!gAa6I-Q=^b%tIwypU&}72H zAeu-{1CW%abAr`6DbI-1rqXmy@JlTnkB(@;28!vN;P*PdNKEGhH%Q}BzV<-z@$Y3@ z^D+q4@C-|ln9d1K*EpUz(Wuq2^A@EK#j{8AM^(%Ze0D=LGN6S@4)mU0jiv&Ixtb zoOslvj+~lZk(ka2KCBt>gicge2SL+0p(@RYXH_&pq$yG~ofEuYC+Cr#T11-82|c7M zgD(zxZCu*1sebmSZelto^s{sf9t6^oQeB|YbWU)uv{9Z8ii!ssP3Hs;3XMmGYSCyq zCv=tY16C7a+@!3eiNcDOdhgx_UPQvT>8AQ`LEmrY# zQh0O?rju(Z4+lD$&S|k$huq-_#R#p_Ay1g5b6Q-kL-oTnozr5y4*9|~ozr524mAp2 zeGh0GbtpAV(>X0R=};g{(>X0R>rgOE(>X1+aRWX~=Y(lGr^R+X-7Z9fq3IkPt(S7~ z43!ib@id(i^5{{ChpM8Al70#;({xVoM&_b;+$yRq2SC#~p+ll-9>l84p-4>Ug#OTZ z2RZ{GjX`{(Sko9-ljR-E@K z9{tkk1yUrYb6|HsMCF077*P#^rgMU?Dr!;jtXMR;GiuUwPVgFoZuSWqj>gAMgYXqbWX6hj^|;tXxSZA({xTKN95-*wYsdkiRqkB zUjgs{+nE5G&Izp$0FSn5fOJVC98KqhMra{;>P>{;1A(SOVmgO4 zsCYO|OHQ^pM@7>)L2Wum06aDqEt)Z%6BN@qLg#t9S`279C#X&52!JQ;Vi;)CIYDhY zM*v*bigM7(D-zQ=!Dkhx-?HGP5vJm4IwyEkarr}5!JKL9Z6Vo}FEjiB<(>a;h8|kI#oXjvgmzd7U%w@|H(>a-Kxke|Z zb28g;x+tb|GCOdFBc^jQyRZ$4>72~o!k4CVGW!T$n$F2QNBGioPUgA7m!@+vONB2@ z=VT5RzBHYaIYjuB51gb24X$m!@+vXNs4mb26(X8BOP8E|yrD&dFROu{52Nxt6iT+H_8_Hl0)A;pw9i z508_T%I{#B&MB2>{afOB3&ax7%pzSort!Ze+eRis0nFiq!V_0l0)(>YlKb*M|2rgO3e=}>W)rgO4Nb*O)srgO3evluX)6Q=2$tRXryG)&Vu zSwnSbSeT}BvWDx>@Gwp1WR29J5n-Cn$r`OgBf~VElXadBjSACrPF95ujSkavPSyoF zG$u^bIa!l*s60&5IayP5Xl$6KbF!xD(6}&7=VZ;+q48mw&dHjiLlZEf({xVO5|&Bv z_?7e)y&zsDrgO4tnju=1cz9IHL(@4eH%d#O>716E=&hG{*tUGxJuUz++!g-pp7ioD zdjRG!vWs=dgUaoSc+b+u5ZQ~~p*h*5LveD`cQ&|uk0aSR*@KUfOAEZbWS8lOr+!Vy z9y(Vv?G862ZJ4Hc!fl>LXoRNK5Br}$XpE-$!i`BAt3!>#ZE>7Cd)!o!EY<4&BiT$| zhG72__^gsWg+lb-K~NP-rC&gTh?EzQu;m#JNwcS3M7iDBGu}bb1~ZAIp2-&)o%%v% zXnEda(P!lYF>Dfk^x4T0PdWS^+8PQ6i96Th7F$C+^A@J9A@?LLuQi;uhTM~N$k-Zk zPq`SlbA4{HHN*pQI?YT941Mb~7wV9)HRPUki%ui9hPalj(^PXbjik9mhm5Tu_o5Gw zMr;kazi`oBONl2FzauCO59GwV_#cwCk*A!@+CWqWF!$epJr4gAg` zG9gEr9CE)Va|wQTsVgdMSYu>!zb#VxYOj2d%sL$Dr?iu z_2r7mp>>E3U-mOL*QDxoCo4>oL%C^O&xn{D%5BQzV`*|IU`!4L9_1QWm?nn;2laB7 z75?~o0RE*{yF6i<911+aiswng63;bAP~zcwkSwQgp~@@*m3Vd_AhGT~CKe`#{=%r3 zUiLCxW5xPV`fN&DF4l+AVST6#pkDrfD;E^IiS?oMW74sCc2yJc>WRm1dRN_=d6?CS zr}d%qA|21utvbG&SRYFNN!akTs{^lm3~bVLtGP8Mp4Nxb(>0rCoOmyNY_f2=iS?m+ zC*{G$qq4f)Faw7-tq-L)lp-mfqSe)CI{GgmJdu+1TM^IJ*6nYigCa%iL+MR451ze^ z@^EsY^`Z1{bO{y+BMKwK28BT*ruCuppf1by2!cM8L%8Q(q9wtc>vjAMe9T9kC>t}p5kc%N<7@m3X-M zqtyH|zEtA%Z;6MS9!fmi;!)~J!fzjrW;{eY4$<6KGXBxW@es;S9EP|F*FI(AHx1oI zP1pv%YeFkb59|qVVFu!!P=epHtmLPWAei6cG7RnheSqe7W_j??wf(~|(a7(jgC5&| z2rTlua?1reuI*n!aJLXLa%HC4{_6=Y;tIbjGhqAcV+6?Wu7l0&RK;xaTdL;(KZ5_p z%n#pP)KiSlRv#noSR_93k$wTDVfi^W5UC@>7u9r!Z5K zG)2Joj-q%8inLkjy2ln4G z3$jqUN|^?h87?MbkoqM;HO&GNY(ZRQ7{!TuR&Bx}UXL5Vy-VCTt|SCn&Vt(Fa%|3v zDM`zt1m@bD31el;ZuubujVrWiy2O>)%5K@2;kGs{nz%9x?Ur4j&bW3qi|fj4XNMHI z$9<3UkC1T_{u?t-ta7O9NjT%QwM(q`6t)UXiVxb$j?V0*w!n=6RvaE zgpPvnC5bzPah@7Xkxsfs!cl*K;KqZ%FKWzq*P+l=fW& zVm|_|CTl$xGN?aXlTlJZoe#v+ST^rd2e$n>>OcT1KwL+FE_$9ihC;=8?3=bYlxMQ3e`;HPhiV`AjhOXk!An5TjJ7yY{nndziRme>;J(xU7x*NEt|4z51DXp z*j`|=xZC4Y6;jM%CcoiFS(DWtEM0R3)Urst(+trLnKd5fAeDF;;TNN_{4#z@+*(h4 zq4P^EmJvWnU?(f_@au1>M@REBe2ItOaZ5d)62d1)iN_}p9nGB{B_4`VMSBc(gF)DQ zfd8p94o466W^t$Yw10R(?SzQwGb$?PSgwbucgvdD_GQaz^)nwl_6SlheE4=m{7OGE zB&ftwfxtw54W8DRIDROe^^^;~HvF7C%a7$AyA4?YE3iVs9*V$vN(zDXBy9SHYq8#C z_aYWd`Ssa;FM=KvMGq3Dv#EE~oc%2@R;ei*J!&d#+ua8tQA}3MG@6jI10c<*sJMt` zqi7b&n#)02-KJWB(Ai-?50dd|GnY>Rbx;jL)CINZvuH0B4fffHEU8VHP5UOah%y%O zvmF{ewFIRBlq#P1wpW03rGulV7LKP8F5&?AWj*_L5Fc=m^gwqUG^%)R!G0bQZ#q;h zip;!AZM7-uuMX95kpdw&fhDAcFJ)eFeO#O9DLaNUZKJKKtQWRIk zGxGMIh-_SDgcO1_d{>@}#lpDpHD-RZX^@6B+6u_-4q7tzGH4}`MHTIP*hAps-c%{I z!w};|j>rdwty-d+anq~49+g!O zRsuJ$&gHyK6|3hF^QMEl9O$lCs)|8+O(=)^U$W0tVd{jP=o#&{{caG%CKwDzd~ zKP;BU6Q)@#iysHS7BGR^UaM$Fz@CN3Rrs%4o^xD`)$pnZd_e9(_^!V}ws0}l5}pg1 zZpG-L-a*9Z2a4fcEbkSg!*e5ktBTfQ>@NU0?QoMu1%;!je9uVTQs#2(;rfGt7doq z3A9BVP#jtZ!^V~FdI)K&Ij#`2*ut272B@{F=7Wj=%es`s?_$y)K_1{yeH?Lx@7A}f zS@0F`EaBs%w?PFU&^03!WbE zST$-ryt52!p#vYbbT6WpRqw=aC2-4CUC0V`J7|ikU#VuAbTrs=nNlNMTW3?TRXpcw z??KM@;Xm45bpM>{mKHkqLDpF->nT8vI56Gx7c$vIyav=5{{J!VE{JprG}U4xO2w4* z--muUJS;bmO6W%wUN!=4Re8{(yb&v@*R56@GA?B;$D&>Nu2pIuB5Oe@{Yv#O!<7e} zQ9xK;^|72$)2j##RfQ#^U4f_t_^(@m$84#N)f1e}dH(Kbv|E_PH1S8cDWm=~=&yxo8 z5aKUabNI^8pQ7D#l;Mq>zDPLtV}>7;FsHkxK4JJ~OyX64J`I-yf3xR zjuUn2E=t4kVi)K#WV{BC3>h^BxW>44*%X2=0l3{)X2=)~j~O!lVPJPU@L|;)G8Pfa zQR6yzmaDp`jWTMyO*U+!*O_X# zA$~Iu)ts)~4Ue_B7ks0QeCIiG{)Mr#9E8=1lQ#S$M?_CI!E`8xzS)sF-L;(gaa>@2Yuz@F5_PH{rFnS}zM&ikkW-n7@JNU98DJCR+GT%IDt4&D1kZx! zD|k$Y>Skbl9Jn5r5`F}f<5D3!%T-;J9+#$qCRLMT5<9)hUQiPmmv%cfGMF{8Z-P&I<<+? zP>s7m7d5^GkErnz1N_>!c3EG7sm4w)CMaqgN2`K*M%dbDpi^x%E+v#|yb+$|sxC^a z@qMyk3;)C9<)|?-IB|Tx!<6r+=<)b@Mvs3YvFOpEABgJFM-cT$km&IYkkKOnMvwQI z^uZxfJ@z|c^mqk4(j3r1H{>zkaFCd-EMvnxE9?t+7JrZE___RrXBu0;mL6-J-A3UPRR}9K3qaHIT4fXgffz)HmpN$?r zHo&ipYnQ!Asi?atkp{;5!B=&p<-SYm0IwD8gOOIB*ZePy~nC3yv?v!;PfB zY$F#N*^?$Z@~XIm)Df5`;cpqY$P^evPvfeQpOEuzkoE~@htRZ_a2|p8SWc?Cp_pu5 zyknVvzM&}Q$lOV$mS03#>G2MIjKSgQF<>G<961S+9)AYN^mqbHj~{Q+7b73%2^9Am zbjbyY8SqGtpJq^Vh&tt?H0<%$6UZL_K0NXST5NzTjBA%YL#f!~i+%@q7Ce>km>&PI z>1l_JYwMA7C86x```}rw>Y{XyKT0;Nj4MoDPLH=2>|X}L628v9XK4GW#`z~G_&*VC zpGF4P!1EJ4TNSC>)V&DHO!>G;B#=f>Yy>>V z5j5R3WHLZ(1O!PVI0IxF0Rg5FIO&7KqKzQkO4Nb_!BA64bBH?Cn9{Hj6uJOp zBbW}4G=hl+INhn$vKJ}UCBQsSFdM-S@R&x>)hMR7aZMvgwgF`$=nT(tRTrfj!EDg* zw^A)Oc|{vR^euCYQO|w|uI4YOGHTq0w4z3bK0d0(D_AD;YIL1t)Y#leS~#3)98YPe#(|)V8dt$1YHVwOT_S4q6HGOJPB7Kzjf<%9S@V|o zYUC|bUe;R!A!-~3&vI24rPX*j*-(vx>Zs9~&8=5+Anue4xdPIKD1HiI z)opt(K&pDdREWuLb_erjH#-T>Rz+$|H|uQ@jWsU1S&%8&%?j!vCA--|cvdP0;&e0j zf?fLEC*IDE?PxvN(fXJLhYO55noQYm4hXLaCfa$**$ZC5u)Re&;;{ck_(yx-5eR=^ zn&I>oI7!plZe+jODMPyJRc6PgLy$C`GeD;45MY|l9+TcTBH9DHd7uLh!+YS7Vfbm& zL&}IcbtR=?)A^D>_P|iQX*%y1;73lEDjQ5No6d4zr0LuYkLiJqre+w`m>&2Xq3nUj z;90KfqIA>A_L`>ilgZ2Jf%5!E`Q&l-PgA}vkX%*&I^F281c^nD4*kxk9@7Y-9tjdX zo&hp?B*5tLZj=5*S)qLlj|Ejc7|uUs*5rs8EE)hsUH7tdVIr_uMCo_MZIPkJ#Ir{ z(W66uC#uKuXBa&aBzimpCu@5}URb7%~EAV^y786eYg2{0qT{U&|ksA$W* z4P!^v7fL*xzsTcso3z$6=HPdR%N0 z|E(U6nDWhm-zcpHny_DGQE@eGjBBLPN_@0j%asUb6x9sya} zV@Zn9W0n#1xae^%rJ)|Tfi8M{5guue?F_K1qnNTBf~m(=O^hCg!ejJUV_@qXxYpx* zLaE2A;90KfqO=}gB^$QKQj@r@9@neFF}8It_P(1*;YvLz+=9aH^BE0K$%x(h%S z)g6FGRQI8I9PK6Ql%h0L-ERa^bsf@;>b^6;pNwmlJxHmjx*fnszkUcFqq=UU)O~8J z?%#w`bt*vB)kSI5bp=gSSMLnfVWkNanQ1;^%6Al!t5p*(HhLV7#L@&E`eRW&u4M7p z1PKy7o&hp?B*5tLuu1P58`a|#Ad4Q4z$1Em(V&WnI#ohxsK>ZwMvuktNE7_f06#ab zU1kwXJ?Dsj_Hda@PNd;)R}R5hruSiB zkr~wP;*wL#|-dw5=(!&%PeZtparYT@2NJq zo{NOipB(!A(Z!S3$({X)An8wMfJ}cP!1SkwP5MJI{b@7E(w{zrNBWc7JWZ`}>`zxw z8uq7f(DbMC;gSB7Vt~zzYnPP~%>MK^!R$|8z+?K;k7nKDH)pLy_ow)f=}&FoS+44$ zbbp!xn)IjECa=2vX}hX1Z1))VTStxSkaneVqNDmpL*r70LvU6=GcPgfzf;oPZP?XG zCoN`>c~5cPlGNoDPU6=k@x(fBIQD{9O<^xgsBoOS6{zhBQjrJL0%!}(Yr%Q{b|fNWlD7m~lt>OBM41=*?{mYyyc zIKDQNEwMr&eweBD$0G3<&~%y4sx|)bDYZjgYT#c+;24((kCcszzMGZv_QkTLFLv}` zMj#o?kO-yInd#E~VR*B2-F2GS((P0M^U8M*O1D$BGD8+ao7KCfHNA|`B__j|>RqV{ zOpEy#0OYL)TBdZG=Lm>;yGiN7G+?v(*zhFf=~@&Rc@mA2a6pvktMagTxXzmU6n z3qRGZfEt{c2<3M*^bV*iYZvZbVR!XN;W1rh z4}YsVq{vJthjUhPLoc7egw>Vk`>z;?+|`0cIxXJ4ZZ zZiKz%54p2&4-zin#{MaW>2VhSs|NTORs9E|FUrBgxd##uKM4tK)qQ~q!?w)5JuFo3OE5^nCHx`l)*WJL# z!}W1^%)`}fYBkZgcI^JQ&wyL5>OyMmfBVs7<2+aG1$SZXU@`Y)-)3}ow{iJK!~+B0%3n2B^o8_)a++?g(t8+pPXHfSmyRU;zA_yi?)S9ax~e7$-KX zJQKPbxNI~+GBQs*$(KufxVw6%>TG~yxLFM~p?48F-z1B-JDGN*rNHk{)gIspF-aFY zd7y%Kswsv-S$3+qCS-4hc#C)d#fe#KC@Mj{2nN+WWAZX|wo@%JltxUmQ#tLe6@v*p zdMRh!|AR!k740DYRnNLs@o1@PsDh^b>^JVO;F!7sq$T)?*&BrcZ>O;b{isxk2PDcXu zgRYwok--g=DTR^B&Jjt6AY#CB)yOa!W?WP8c`;HuBqKF8sz5SUIrp46 z5<1Fir#7QORT^$5jC&0-Qw>&8S@KkBCo=sWm8qS`)UT~*uO_O!4l#24$1wYQ?KzW< zh;*EKIMQ9KcyLMH!i^o^eoZz{H@h}No|h_*i}TCW(hz84l^n%ZCF){4fA^Y%y>N36|EiIV%32+1RV9-7J38~D(aZKb zR^^CNyH)X=xEiI(42QRko7EnLg%Ij#{KRPGGQ^u293?e)P$Faq86}dQV#?)ehhg-l zaZRfl6C<@linJ<6!q`^jD63N4a|jEihTFoQw6c14fU+j7iL|Opk?97+nyRZ5nT{a> z!zHUAX8IoM&=$z{PQ+9%gD0^QJnP|E0nZ|ythvG@ z`iF6mMZ2{~#^W_F0koLMYwCjj?uZS+nB^$$8@tOeD~7hzT=hN~a^u+e&d8n{$9BRa z8^>ai&c-o8apM?KdgGV_s{uo79D9@ulS(zimFkemF0ye9lYb2TubAk_#xZ@yi0{{U zgmRha9fNQ*hr*{qXR(KYzB3T#wcoY1g3r=hO?1c2%*ja~c~@cOxMl;nduq}jHy>1*cSR*~tHg46WFkAjpnMga$UY2d zVkWZB10}0OV+^XoxOUkB%FT&vUN^AhD$x*l%tUsUfh~04u@l*Oz~Km89Z0Q->`X&+ zCbCj-s5uyAVf|aIxt+?<0iW>J4a$$Racchv0a))F_f}-4mam6O?nS8&nAkED7H2DO zRF5H2-K1WC^VeTH)FDG3f&_SY#5|rcWpG%kbCJ8IItLjM!mPx31O5l*hmhiCb*daI z61UKpky1CSjb9*is}B8BEy9oxw}?m8t$(VPcw)vaHi4J$mKJxZ3EYfPByNcW_Nm<% z0^?SF2;r6`(AL!km5auw!ZflG&3=R00G!I&*LbvWvs`Yis>WqIezoodW zBep(}DtH}^=M=8K8w&``hAYULYb@(`|7BYR-cO(zzUivujnVXZRv#t;D#e_M7UshonYsQOhofRuI<{^WZ=?BzrlQQ4MFuifc-mQM}sz zCKy$${{S!6eErsyQKS~3l7z(B*#i?z#+WqU z&9oVpHhmyrkqV>u>Cd{jNTB!zrVZXPsBOau3?elHj#%A7_*(V1$XwL|I_ubIBczuK zFH$2hk#?0tznG5fWehRKJB(KM&HHYYKblR zb_e8P+4@=rS7Y+&azA7A4Gk^}1+#lo9v7{-+I=X9i`HE2b0~p})?Dp#nYD}7THrXNZ^9TXm?^?#5b8{Tg=Z5~`+%!j= ze{K`!)`!Ho{e5xn{6(DojeSgapochjmy2`H#p2w%Rh;|o5a<5q#ChQQhD`9_L*hL2 zzBmt`7Uz*>$)r6xK%9e9#CdF;IFH{f&J)jybNCx^o~-X@f~Q)G^K@Tvo~aV&*|p+4 zcZ)dB^Zt5|`-M-%dGWM3F9jMg^5q`lyfQ(YBTM1LyFKbAapTqF;(FDm;-)If6Yow} zR8G7*Ls2d9FqcV%#JgLXblE0dSkk#(#q;H?d)X8`afPkLVf#X;-B5AbPZXzPW5vi$ zL2)|gi_@i(INc5kqzLT?knXRG)8j*Ndae{mG3NfD^~RT5IDOCu;GA=nIDKyur(Z9D z^hXB*tz@(~17NZUp+RWea7s^zGx#rYhIoZGbdxy4FbTE16Sl*CU#C8CSo^7f*Hdp` z5BTd3yaCarqtJp~FkY3YNUJx*R_b~;hI;%r@Ha-|Pa?wdslA&(9(oxpf7|LXsLw|b zApR4*zuvIsu%KtFqab`4B{ozIFnH7(u`&hU1HcLyoCP89-yn_rtz@0^Se1sjAmb%p zCw{zYi?|+<_@w4YU=YSei33nFhd5Eq0AXR2n8%cUvG-JOj)jG&LJF`2fZb7$ zus5LjyZ>!K_W|&D6eOII)tF)!idn2)1L30xu>praJj~@j-FizGA42E^s1`&sDrLS9 z_*phX8}g72U`Nv zv=_DD@pOKaPW*zaG0=PB7rrdc;`XTwEgdG# z@>$}nSS`-VJ>pz;zc{Nu5og_B;;e6y#&nxHh_iX9I9uk4vu%esJ0B2d*9+oY{jNCI zd@s)Kq^3-MEw2*y#P8vS;hy-t)5N*{a&dliNk*qW#fa>Q|M_N#{PnOnzcou|VJ!~t!(cvP^N7cNS*_uSxcJ zS1lB0^=0C$xdu)uFGg%Wq#X*bl$CN5y0hi|?tAp)z8}UTjr$ip@F_EZxnuzI)Ngf_ z4Ql2AqAvEB`Vogcs z&3)sMG1UB=u8DVb6?~?v;B&3}FSPEz(iQSGs~{kjh2!PsKBiPQgiiY0`LWUlPeo+n zq*BB*ePkR2sEUwYK>uaiPeNC0Euc=C5ueX(}6vF`Eyrv3sJ6==eUHB}9fzE8c z84bGJ&RTaJfXVZuwp|g`T&}6|HB@n^#^A`;uy&oSSV0)a<(evA6V(~dZ`jWb-UOxk zQcX}_Q{_uDL48e?uc-;@YpQ(dCaABe@&!y#UsL64W`g>fDqn^P>T9ZeK@-&1RQW3g0^#CMm>GqGl8g4f4qVkuMoXxwa{1ZsELcEL0 zKhiX*5bvV$pSKtk-bEE|1W}(sASV$XtowX03gn8}B!5KjbP`jTIM+ktASq0cCwEc# zmn%-373a%IGNk0mT~z)rToTW%cS-y~Qa0{9xr?gNa@7}c@{>fLBz15D5n=1QsPg14 zD*p-1jPvg#QZ+J9?xOO0ZRV>sFkXI4cH0n3 znb$;e%12V(Mdh#7Njb-_P32uw{x7w3oce3QTFG5h{_k~sp4>&{-ykhWbs-A2b*v;d zs3ZoV8oq<%$z4?b=^Dp(2CbSp;5@mD%0ER5yo50RfXPZYDVh`SqH6TM=5$wtllWq@ zCF?x7i^_je3(L2XS}NvURQ}&Jk?$%(L?Yfr)hI&?!Iu{;t1x#|ci;e$uF$IEi;b=w zhswLC{K>Yo629*w(WmtXJEg3X3pMxYBuYDy+GP-hZ78DiE-L?>It#ug)y3t>T~v*_ zYfgMss3T{Ru*;LXsQeFWMtsAH%IY8v&O(8!G$X!iXoN}5yQuv4>*RbTt3~8pRE-|e zmBCRwNq(dqo9btOYAttBHTqdP24Cc~q%1RNyo<`eR~j(i?xNy>#=EHe2ZhF0zFM?q zP*bC;geTtvYw_e=RQ_LCWr{C{G3oN;E-L>BTZqRa2_w~;#5mN#DL5&=8H>#@1pYG$Xpa(m!sNp0KAK;(IHVaU!?1D$dkLM z8vUX3K8FZt2jUaOn#RByZ!LFG`Tr38^F=(G9fajwRQ|^lCpT(kgh(H%gaYKrT~z+3 z6=zb4ukJd%K=R}+Dt{AQSiaE5h-whLi^~71q81h3^`pt1QFHfQP{&(}&m_fVfVzm* zau=2VaVY^82x2l}9AxBORQ@%(M{(^yMgYX~E-HU-9nZytXxSZA^De4JIihMVGt_0> zTJEB1)K>spfH)JtyQmti5CE4ZG(ftf5sr6JH5#FX;HrfP!3P5GqVg}(U7hO~hESm1 zy&MF&i;6XqoA5#^wjmnU~o`JYvs)XF=CMwp7{T~z*~iW7Qy@rV+gisxNa z{x20@R@7N|1+9y)_037PzBwt^!`Ind57#H!%5OW~oYYpL^>40c9EiD|-eA@~?KB3H z$`pC44e>stlx}+BYlV0pQc95yc|yDoDW#VV`9i!8DW#tdrG|JPQc8av3Wj(eQc8&q z<%IT-%K#lJ4Dmjslz}?bC3G>SN0SGDL@l zhIk)R%1|8|7UF$KDZ_PWc&OJ`2#wUC5h31(lrma}MuvDFQp$NcG%CdVkWwmiXmp78 zA*EcPLt{d`4=H7m4wZ*^A5zK`9U2?reMl)&b!c3O_aUXs)}iqs-iMSjM~5b0R2hB; z!b?~t#RUVYQ<;re9ppZwl$z%dt#UnFTyQPltE?ug*~MM=q$ zBfRSba10CPP1Z|n=PTjeAhEnrsmVqejCrF{lTG5?K)_D%zKDgnCO3(9^;&pup*L;I z<(Tp}uAYm*J5&sdt&JCj;pNlh8E~rHFT_=k(475vyPl*U16D`gFO)i2 zhuoH{Boo9bWSHekmHUObM55Eo)a*=}3mxXJ_?bvE>mNFe+%Lp8UY(|zJp=;jd@j); zkL7w1T`+agyGWBc9M{&vpiLUmLRcIsSRyvTyeEXHzA6KvhZS|)XpwxUtB|SGT_BR zseYR(S6oy|qK@SUiFmP4>Uceg=Teg-az=VyER;4+9wJaB zT|`&8SSS@23vtCtmOkqis;gWql!}XmxSFNMxmI$qQ0k>xiCyJlp;TNf#1*b2wsLeP zUM!UQ4|xj5H$}9FMIUO9DrhYi3#C5D!YVF?MG-oa)^f2>>Z9x`ipykm0eNzd%$Te;kf=!vc8!r~}-Je#92Vko2 zQLajac(IW0pkAP`LcCbW_bR{J7B3dc^=v_cTo2#i<=vP|3-WHv*mVd< zEY~0<){n1b$U12@MeHiK2_@k+q0|84_=7}T_h~J+2_+qqI^kNSCg#a)LP=e96E2O3 z=WRksMLM3VnHt|(ZWBuSN!W08(_zEggp$&9Q{i%_6YqHx{&daefD@lY9|U6|TFY%h z=_jSza%ogImhk{MJb0T>QbQ?{;;N~xJ2rSUC*CHMj-_)BA6!eV+sQ-+d2*XjQWMRC zYpqcpPAFLP7R%;xY8@yK)v!dp(NZU#ARQR9g4f*9{BH( zbX*2@qIsK8(tQ%mW#MQ^!G^a9CE+$9E)?tRG5(x}zf>u%8tXzcca$Tp1`$K`AjGxg zC{acb-Pt?HZ9+*;QqK^-DHbV{UK8=T;H<^ZQyoz~NspMKGoIpU0bHja#ck?y4r07R)Ydm^0Iv$shCv*~z=!_n57}3#X(47!E`*)$GhTg!m zAfxy_2?ats@wCtA^|^$Cp-WaH)Q5SyGP6Qkwj~jjq5L={-NBf5gM;UV?zJJR3&4A4owaDD9dyf2WyK~m@VRN z1f=7-u*ZPqbv+{*wm$%&`;c`K!M5FfJwyPJ@n~PvPY-pF`-&#X=N&6(S!d6auylnU z>U#z{2r(~0>_B4AVmSd(^dOkP^nv2m4wb^K9TO3DHV8amHVSx)uuthRaOizIIi`@q zbj0;Jgsn>F2&XVP*;|h;?aT69=Ik)wR;HYDk09!P;Lm*$p7idCR=?{Epc5Xb{nbd- zw!c1?)8DZYhbYCP{_aH}NF+sM8Rnw`lzws%6mG5N8WA9oQGC z)F`c%BTEO(n>^oAF-Zb?tb+ygVLb58(q3qt*-8Pdg?0r!-$NpPo< zTEv}7EW4BbZ3F&tNw~ZVvXFZI2nmPOrJFiGvb2o)tV=cZp4!XklPvlN^xUWlX=Dsc}@~BDZY`(c4+|)NzFH!G2$xbR5{ho3*6-%m^HiI#rIr^A^q@u)B|2`I2tcfnix5%Njl(Kio+- zd^tSaNH?7KwQ(Qa@EUlyjc)kUj9JA|ej>-9?Ru1FqtZh&a5{@S65O2z!W$<$65Ip(!e5U&65ORk;9be~ z$i4tKcO={b$?wB|{0z{Pmk29Cb|kpXj)WHw^I8M}B6lRX&5nexK=>g_tS>tf+_EEq ztZap6H8wGT|6KCNo;*tB9;-r#!^TIGuMu?20m+U80UZS3xhP0DCCZKj_hR)P2wz5s z@kPi5k9paV;MO}5PJ`+}W+o4^gdp6J;FcW;n?FNMlx8(t z3=USZyBl4<-jT2b^hUBHq2UC0t;U`d56LMW)^`*6P2~zt6N%QpF8xI`#WN8YKi34} zHufe@t_j3#5^p(&{LL(uOMf^`@jM4K+9p4rrqR!1)J-47&tF)Z#JWMfH_juI^O4eX z)o7iPUue;Ev7iKzyf(hEF{PiMTI1U`ML1nPwR#&WZfFVcQ>!;wNw%3*AZa1K)HYFv zkpyoP0e))rrkbEH(Dy0?(@Zcm@YsJ4Y-)nRz_*tom~MhOfuZLk7%;)YK)oplHZ#F4 zf$&ZQGfc2Ja3h{l-k=Hg51hgX;|-Z$Szz(YVYAxXv zD)9F8pm&h%I{efc$UFpfby2;Lmz}v*1^B7e+e_UHcKp;D;HOsa03}@zpIQTMDBL^H zg!ifdKec)XneaXpXo_m_mYVQ>6-Xw1uwq5?Q)_^qTD@f=JwLSu{_`vHAEx?A{`l0| zjPH5g`!nP{&-*A<(wy&k-h)~@R&&1RdH04`mLbcH|08;9Bj1#gb?qWa-Gc<1Me(&DSQjwH|08;#m}^|WIe_X=wjT4 zL@jTHjEEo|JYRndHF=UOaGza-r$lI;Cz)T1C$0j|lLSDzBqYt2{j4gH`&rq!ow5Co zQwZR1EuLb^j|WiLIv*Ey!jm&)j-@ilBHlh~c7o@Ai~ggsk1+eKN0#J0!eE#=o<{m` zF_Qj_?vy))@gWD6Pp#}W8Px!zT09F>t7VAp-zU*(H6Nb&^h|^2YIs^dZP243NE>-p zx4{(DYpFIosM`i7$i$CxxqP8Cx~gwD(C@BJJzg&+i7sBU8_BaCcX6*6L-K7 zBmqTHg)B%nh|!*v+}~ivJLy{=K~Ak+2WcXBw0ahvP4pau=Xr88E;n@g#nK#kRwKc(-7JNXEo$m@eb-!mb7;%e%WL!GYxR20~WrB zsE(Z6#NWbBqf|#uZsKp%fliU#;%pyEu~xj)nwKN7myz11TYhJ?4*4Wr>^cC5>Y})c z5Z_SRxT5O3gvk%yi$@is0Y2E9e7Un%)5J%%X!6Xbn|cZyUEi|HFs!H#ErDb%y`xCp zvE%WMO$B)+u8V?kEh{1562YmEXy#saS*yF*^KJcd6y4FPzbZ0!dh_3U7kA+zr=3wC z{dceeosv7b<6Cw|OzckX`0T-qiP^~=AFf19>`w0Z+ zJGtXK>|;#KPVV?F4-21qck=nio!s%gDUa;rj_*T3WG8q0IhFKsCwKh0%vyGG$Cols z*~uM0n3>5=?)V|hMRsz>4<&oq$sIpV_;M$A`~=~^o!s%~iI+RM<156=o!s$Lg)ev7 z#!nXx+{qn3L%iI{9Y0gNtmXJ>N%kteizSvjx#QPJEO&CpuVt+4HFM4&2;nF(QRbXpnRAkrt$KmjpMVnb$J~ojdB>`9#8pNUn)vaGQ!vh_j66dq zk0Dkl_Rg!L#LL=KT<~2+=A2$V=j;G#aRiY-mJoz4r%;e`04fR6dTA(g zPOr>4FC_iqD9uW~2Nh)bz1`@_F4%+zM*^hhoXI-@ZM^m*64mee3;ZchJ%Tzc%EUUa zQm!HlRrR|w&m@&d|Jjdrw5*4KQy<{xGyHpV2(_A2jF@8)m|9V>Ks=b}?ghQ^iuuBP zr2D@yuYjiOpS>K7IR!Y?4L`l`?``uxFvpgyKfpXq&K@)v)O1@2ITiX77jWmQKXKtO zaTY%*&eBiCS^k$eE1F=r(Vw`oK%C3^iL?45an@}SXZ=2LHgR{VKXLOX;%xEZwbh@v zt(`bKM~bs+nmAW;Dbb&J&3bWm-yzPmFN?G12XXe+Yfi}Z?Zx?Vwa9X64$9|G{CS8( z{yI~f-<}rd_shgN{SR^e_ykVcHmvojq(14sM0bNArry2=ZX2$@VMUram0dC!x}c9Z z6DNo>X}&m<3z`QY*U zdF~8O+dks78!1lvDseidVYu@9J7tN}xj>vQcr!y}x5oui^rAT3-xjCGC*t(PIyNB1 zbH(Y6moG^oYlgmcXww+_&Y^W>=zE7Yl%Zn|Ee?fG`N5%eU_p+XP;fmy zV5H1&eTi~&o)DaQHb(QAt^^Mr<(V~M+}&P=4+$wJ6gJO$@v?<~?=JwW1PX7pP~FMy zEZ5O>805Nx+P@AWQ(ZW1mX(s^%EpEXrcsDFzuHPkaRnil#I#To$)%ZV*LHAO0S=p@ zT-N)MPnNp$1qc>&{khqs*$2d35tP+Zx$%i3WtwZu2AuDP{InpgKnXC zf?>X=GHQ+s-V4RMQGq^Byv=iXb1dl}?e|=T=!+$gfapo$`wM@FzDNS~5PgC8YDTrX z7SZ!1kc8-o;)DIN9}qoL0?CM;BEHG%>dmy0sqA__eA!V=#=n8KmK(;3CTc@9PzNfo zhBR00MC@+-ds`PmftUeF{6*>x#61*=PiPM+7E&j_jzpKJry~S!CF0TYlV>BUUKnjq zrM5b&J`~C=(5YSZ#36grTUe6?LZ$_8q$5qeNvzf;F9U7{gVRY*K^#az%JflZ8z})zwqwtTt6JrO|(`o71PBc>?uIv!PKND7y~q%1e`3Llwnc%|?V#NgrMFg9_}Jrl z-SelRzX;mvQF@ZPbpXaDNS8ulPV1iRvOLF+p1{j7_i;DEf2;!9Xa%^H z$_AxflsXn(Y~AD3+v8D%Zx|KyuY<6XUqMASZg31b@D%O_wNR>}ovDges^6O+b;K(* zXxo_jHI_4hbSwL%_Bd&WTCy4?tmi_7x(6`Zr^v^5Kv}Ks{y4s;r>f>nu0UMj@q@P2yy*^T27RvZ!AB5EKO`Yf z;b?|}^2(j*E8N{1?^~hEm`P@GVFqa}$ikKBw|bEO&GUmDdFstwK1BmH3 z1|ln&s|4Q=4U9usLlfU(CZ`~HXmKOJifdYAEdRo`euBTyk5k(%n$ruRtR75dH#E$X zEZ0ilS_I!Ac@?~w*(5fWZFyPMz2Pt9w!ExGKbcZ-TVB>;(Fu0qG=2#~fv;ur84j>z z$N?Vy#I{0b&{_9!8GYJw9NLUE$B}NiP+C;7Npvb;yHyx|i`w@sTyV7rni5vP*~J z1KRpzaQPlzU~{quPlLa(#UVh-Dv>X_@cc~nP-zvJ?!tzo4bwDFVH^$Yzl zDUdxz(|m=ENgJy}jSAbcFylTI$x^M}Ka$Pl-w@O#ogAVU;S=aW z*-JE+oWi$$LTITDwKC;jc05vonr+~(%fI{vc-d3=K}Xs?BSZ}aTrZ0Q)%74skiFtF zmdBmFYPid7y-fz9jnz?YtYMKX*GSN_*WL?+>ycNGa0BHyhcw~u!n>{TZ*CE#3p+tCf`bEDTDf5=&lD8axZYxg2{JE{)gVR_J zm*#XXX&lK;^D)_(z<LE6;-F%rF$51*JDh?5v?WM{OlS{K!a=lG%%0}F0px|BaUy#z5Tm0g${M zFD?D<80WIwd2RV}(Et29vDVxFUVNul{U0iZ(I2a18ot!#b^IAr+6f%W8# z;|%q-G*lNoc>bw@iWH?oZrtSpJRYrLPrjTa;evc2Pm<(MszfxJ{t%ud$)Bu4<|Ik}6s9fq<;zJD zuHNf3Gx?Z}q`6RsFwNyjlKfe@z#)yCB;kWzr>W+XK9c4V9Wp0L@)u124pR)UZO-!~ z`Cqthl$cxaTSl2U0?VMGM~<$Z!-yCq7!tyEROWN3JIfFh-&Y0v^Xjc55 zQWri-&Y0xmj0r!p$cM$cB^)JZO!9HYgr8t^!A8p&ll)7yMn}mRlYE>p;b)nIeUKZ1 z@{CFTKcp)D$!L+0K2#<3(N>Kr2I4_cKEL2Z5jvB$a>gY8(T9;l@!L*az%V&ulK+x! zD*Wst2yp&KHz;YVC@F{0%r8NFjDrAe5SvU*wN*TB(rQE{GvTyXV@X0y@VH5Snk{o% zPKIOVw!`GONq(MUvsauVJDKyiN&agR%_(zTsoTnNll-^&)}c6=J`=#>Ci!=8{-`+3 zjshSqkDKK0=R8hv`W!<`mQH&v*5z9_XIfX{jqnCp17fhFP1~%XWsQ+tWCab?kC@Dr za~D}bvQ#5FayfUA6*N&)7haaixr?kI)dYRz+(lN9W`e2Z+(lN<)C7a&+(lN9Zh|@G zLosD42$*1DId_p2G&8|2<=jP9kYR$w<=jP95H!L5<=jP95Hi8Ca_%B4Xkmh5%DIcI zAWOyJ?cbGIS=Fi>#cx$O_u4?h;<1%HO^o^bRT+yt#|4oV&;hx~LWsUaQKvi>#oRdV%j&*hN;( zU1S9V6vqu4yU5DjHo^lR?b~y1;bR1>q!w`<`b!vzci`N--g1eaJRrX)HxjF^EEqeQC0mC3{q&WQb6PG#O+W`(DTrk+l>; zC{zm3UVh*2IoJKnqW69OpZ|P5b6@A2YdP0B=Q{iH;CEBMfbVw36}rDv^^V8jEo|Nm zspk8HJbX8#nvc;l9=;pm`ND#HH^iQX;Iy3YhIqa>Uwa;otForBIUHAI6H7YC!*NwM z+d}sRc{r}hhqlZEK^~5)vdyL^4z+tfB2Nr3SIqpE#bxHl45eZwlsmX4R4+kQ?#pyO zZZ1Jp#wDn>z(?@|rrRN^s<{MJ`6osr&xMdF<`PupMAwABmMff>peom~;oJ+h!m64} zP?di%MQFs$9&9x$K2U(FMhrhz{l$p8q;)tt;GF?#Mk3 z8vth?I4Sih9>eorH%Uq{Cz>kXVp1vGhPDlf_Lsk-^!@S14uzZ3`8x)cak4j5yUohr z=5>w?PkG*ps{Fl86!*1Fxb5ty5}H`vi>jR9rotopLlkr&d7lHsGmRJ(V4b@1&yMLW zxF_z#(23c0hmC=oIyY@RikkPLD&t-h_tA~+C}iG? zs=U(habMjF=Dn!Ot4%QX*>h3~F}xR58E3Y*^KPR@pZPb!a4(A6@HWwm9q9-k4Ma;Z zlDIjagEYOK?Zuxq_o6CqXFg-iocE$CA2RB52j8lnV(vv%-l$10gK!G93Y6euI|-e{ z)IGk06YR~(nqpqQ362qN{R?;e4G+S3QH^E4k^unVAwkuZ7U++cCO>HW8z`!thYVn1e z>QCC-;;{pZWKW(7wfMqKaEN8)X@tC3zHk#fZ&l(U1*=V4^TJK=k_}HWFWdxQv!>pf zRH3m{6urm-o|Z^4FWdxsTRNU@$TyO*#3|;5n_zdV@Jy2N10iz&;;kgUa8v!bmGo&y zl5w%&_oAg9DdvTn;B~7k&rjsZSH5r){L3PFs=^?_ zfsXuiDdvTn>UFIo9%{&^XOt0_VqUljZm@!Q79>YkkAg4URPSL0@l=GRP6I^52 zd3Yoba!_Y*uD6B3BPBV*KU)q}&D%EBf8#J)c-X}1$kd{-;M+FAxv6jqPoU%|1{~kE z32rtx9!trCa1Z`+ifWPNuA`L<1Ivuov)N(l08o6=L*dgE=IAm6qr zJ(U*Dw{23)+cv>FZ7J}aj!87a`L<2n)&H?^KS>InD80S__diiBYh!MAOKuh_c8^G&AiBb;yB1RL6L9(c-0 zyO-5`+opOslhr&5m0xsK^R`X(2MhrZN!?7qw{5DwXb57__j@Ol&$3Pl|qQl=53pxdE161DAhciZ7W-ww{3#%@ldxwkd4hs;Oa4PzCu`O^qa4JsSqT zRa2vm^#y`_tENT+>x&EWt(qE5tgmR0Z`IUjYJCYozExA>A?qs_+4)U#<8jo0C)8Nm^pnQ}&S5B!GLB3T}<1y=N8RT0vHCkFp6Z`IW3Y<=y5e5#&)K#~ba3~-+!DZo9SME&yI5NPmC3?SwBK0sDF zlT1L82}lfZK|U$K&5cC;@^DX5fJcnXTxuNn%v>tgSC4J{o1WkC75)(?TPD{UJg_Q~ z$7}huh7Lp;XllHcUu)PL;|m0NEx*?A)y5Zx2_AeS78zgBAg|@u8aLAT?hNu;eyx{Y zHNJ!(ujSX$eywzn*YazPw=t9p@>+haSM8)V805A5T5ptyW9+qqyp~^Ua(UxR4)R)l ztr@r9LR`}zujSX8X?^X2yp~^Umi6@v@>+haET)*(^1G&ECqGd8?&(Ng!yfxwU+q$< z$bg2Uv1MDkv?)5L>Td|XhZ#`##pC#;oZ9!L+=oeezuI+f2W%9moqUX$6a6>H8knOG z$ebJB!`ILzIn386u6C1{Y9Knh2fMBGit&~IanS`CX12V zB9GjbD%Y~4gjf=4w|yhT(k>6n6CTSiI0sStNgHP%xQgj)e?d!av=6=x)>o7%>olL@ zO8*6x&ddy2H5BXdDTCi}LEUqJrll%QNY(D8a(xX;egkh^W>muqID1sP(Q4-KQ7nMe zewf+S?dbu}`D(XfrZnvRCqg?iu??5}3TGE4qTzXp?@a~Jc3wen4J#b84Q66Z>kA9U zpiFAl)`)|%SXj?2F_{?WtHQ_x+h9eij=9$3 zl)5#@^{zVip>u-FBEbU4$U4=nuV|2KUv+9&-yOm8D7ZQ`IWFO7@CtpktgoD}a5Wr9 z=vlXH^%_uf|5vWB?!9r)nA!2@Rrt!=BRD}Lq;3VvRy+73O1*AHi%T{l>sGS3ror$_ zz*V-s7Qw#|UEM0y*DmNMU(oteeT6&0Ov=@LXdfd#gGyKTVdgg@uZJ@qb(>pXSgYV8cvSXea!mef=d`(3+uZzSPQvXx25$J4c>sntJm>vU(69u)zoS#Vy7}OB7hfZ1J?18q)d5g!Y zob4!K=NA0}z+9X(ybCfxY;)Ai;4sZ2#x9MK9@`osGbDgK>r@;P@rJ z7FMwLwZSrI0U-j4J+bR7$O7sO^VKYiGfmDXQm(bn*S$HKp)lu&tOQ>|EDFN;M$Qy6 zd~RhS);TKj2(Yd3A4wjpyU4>td@0f$fdfN`$W+8Az8=y9=Qo{W5|6~Q0?O+kd6Q(7 z4S!E*MS|lp70tWM5AoY%`QnQsr29Oa-m2||G*$awHjnkAx7KvXZhHcI^D({DzfR=>l}`5DCtZ8{{>o@m3&51Mv!xNk(u6ClTdJWqmTiZ+cMuO*Y}AEz5q zYN!PH7QnwMP+E>N4_x=~4kaiF-YNiQisAyH1i%|u?y{Xje%LPk*{;&_0?5a}j^ z(3ER8P^5*Ze7$V87I9q}h0uv1Ow@zW)Ysb_taWa4TSC?52ytazJ`!L2I+T55e!BmK zV~@#BLw8plpYNFr^a#!au02ZRBvkkj-VfXq2r>4M^gaBG-Al%DaV;qeb_hwM^Z$wB7)51ZhN=aDUU1_ zBx(7`?y(k->ZYI#b7d^hZ{#Dt>*1Hzp8Z}$U&;{ zyzh=g6K_O64P9wycEhP|{TB5$10&fDnz4M8^` z({d9mz6&kyi%z2-G@D)q^7Y&Vw_v%#8S6CtP6@JrTp1$p6luE=c00~#4BIrhy$=*$ z-9**-2&i6mvJR*=zkuRTQrXm&7DMogGsGjfwH`7H|CYduEc_V6yy|?4OO+;3NuX#D zqC%}V1QVQhJc9N>_6QMpVxEU-IIlSoKda7TKrtmRl}F0+_0A-xBzig%<6@Al%S(!S z@Yd(hYqIku%t1Z__Sj7n9jSS`vkr}cTn6^nZ2b}x@i3L*_|KjCl2VLC zI?I`c4p^!Ko1BlLv;>Mn+xHw7Es)XnNld2wf{_k!-VKXrh*G%>4V|-LcFyl}5@xf5Js0){S|2oEPQt#E@P8XdYj8?M zJGMjoF3fg_aZbW!bhXa;Fg}lriJX%#hE?K%()V-{ios-^izY6oRGO3UEez24Uh(~$ zgg=;3Kd8UIQ&|?W3T1{#)BACt1OJi3SO>HpEG@>+7ly6GDAibKUyuwU*%+-V&9_36 zMPVtQDZykQ-^xvpeh3k)2}?vgM#6F+H zEnzXA1ISOnT+hL#$zG;+TUZ#{9Fu1fmy8Eu@UP;{re2x|CLPYlVYeZ-ELkm(G|eGn zpl!d>B#}k1J?sw*k}Pc((De?{qLZkAyE)E|u)8sswiGV`J3T}Z#nQC)k|q_|@9Yfg z2%)BsWjW~f=FplgmjOPFKI)q)aHdH(i)~NXctm8m&V%Fkd|Zqhv>9y8J`LM{)YGO= z1Drd;f9@PklT}RC-mn^|L{{k}kUX42W|XEP$n!F+`kr6Gb_;XiUJ zO*+?Uq|$PVB$58Uusx<&o(0*^yri&QBPhm?r)7Yek%OL@OXY(8E*JyPF)A<1N8*dW z10mgeVmV=mbGyG><2-6I*eT(ci=YW>1U26`YKBU{n620M8imXHZ}Ix2;$XNZ#N-V+ z%KPh}K1&@S8s3Dg;CG2^2SnEp(jIKm!EHr<1LTXm0PL6$1^N#&@T}y&^-ImIw}G6O zL!e`a%Kicv#K}4!wug|O{*%}Y1pPfhVKV$AD841t2TU~b+T=!U`DeV);mX@mrbK>1gDKI1l)nKaeM{8SFImOB--?BIo8%USl$3un+rX zATY1yU`-7+#la6|MP}0TxPO~A5Aq&p7lr7NQO|coAJX2x9+ljrayyWp<|ddr8U(5S z!)Q7U!M8yEm_yLZs?rnLa08)HNQ7$oG4w@UGaYX)|DA|nx5{*$NkO zn-C5gbl&x+LLs+Qw&Nz;dkz8fG+-41I-wFf?`gm~2je+L=}hv==TPYc)!NVehuJp5 zXv3N8-;BB-SAqB=H*(AuK&Jb9VKGBup=%NRhd3R!PE-6P(d z<{}RP(IPj}#5v8M`W2Affq0h4&s8B4=X8HB4ui)6F(Eh7#QB!L5fUtOfyl~@G;z-G z&qPNon}OJ#gX|+q*jc{qZ+x8dilfBX9Pq`rM2fqggv2;!sXzH4+Ks*fB5;>+Aflbh@O$I;WvPe5GHjWoHr-Y+mEiE4@#AOCr^-sm5uU7l0~ z@;(xLqscN_Z}LA4(MIb>fNY&ZpjvPCe~121dIQlvH_~YRp}!7#NqGf`Nx6|m>yP}8 zvWjH_@j-5+(Rz#jm%Tu41>%z&WSW=(_Fn%6h^11loCWq8DNJcZorm(~O*G>2g_V3IHH|t-e;@pH@?6uzsw{yE&-GnguXNO-k1Kpx-!s377&j_~* z>9yU2gH&ZsICF^Y&j24SbZj^m(a?}E9WoQYVcZP;AO0h$viJr{GYpnwNsKUoQWuzq zLfA-F78?6?q#3^{wGV?Yw(ZgdB)vmqXpL@TdvPY_78d+yAYKb0?U<;fe8sFN7rq`! z%RFEghA1Ha23wu-;csIaZ1$o*26BIhz%GuVH^o^N`5|U92K>f0FM{HF4%GrE%ZiCs zR>l@Qh*r)}#XgMo5C58AJUBQ9DcDr7if7_MAnS$*Y`tLD7*^ z&!YU8CvP)*>xJ(@HD{5@U?4~4CTPOxn;ZKK>bJ?q89>g-AwcI(V~>g5fbp=b24X9b zrdXoLfH>N*mX(fu4GRZG#BorZ$q|7GDw}``u{FNd#QqIrpm}~V@1qluuCW8r{W6oJ zBq;6;Q6Zieze4DM*fmhd5Htd^S#E;6FjSQnV?ReZnM~~pWWNxBRrfjR2|Z;&?8|3e zpGn5^(uKXjn%JK?ei|f&k*BgTwl{qXz-{w7O$NZSWm>^-n251n`54GOA@RP!5>^}v z?v8!e8+PKF4eiyDOQ5=zLpelJp2y>b&xKDptXby7xt8*_M=%M-zuLi2c?R`Qj>dk9 zZW`Bi!YoxiP&Ce=8Z19^XqH(p3#DyR?!@^mWe-sG$)QY>8z7Mrv7e!zA*Cy?0y`~4 z5yeKq_kuKJk9~XGjAJ&hU0DH=sF5%sA6}|r2iYPnh>GCKr$m@-oWXKGxh}@ef$$rw zs7{<|kzDx+MAt)+U_8i*?z|a}m)Fo*-HLxTsiCl2Z@Mroyf-S*K!mtbAs>ma`y>pK z!kp^Pw=I3X;arh+N@1+G2sOc}<;c^Z?@pdhS`iKrk?5>JE6Ph8G8)KNNYFzGK5Kz({E2?7~RSWXqpG@)6XKx<*24=L!m&#V^HxESa02c?5KL+zBAThM+Ex zO+y4;Gi0dRI$b?QI)kDQsf?x`)!S%ZoF|<>y|!pPDBcLkLbhCIi`m{8j|7|CT?k}$ z4naxjjymCVaNcAKz7vRjMB3cIG?-?V>bPmZpK65^2=1L^KuLP9OsDv)f+NA|ERM3O}gApC3MOipN@j0H6|LpTqO zY7kFn_l9Vx!ki28atc~^t+trd7v!+v2a($lTpa(A(`gCbR@G(s7i|p}Iixm__mkiq zLomY5+OEqHG^Nr8h)zTrZhJTBVTobGE&UNbGK9-fZ~&zG;(vzf-Djf74|7U5t6D)f zhM-A-Zby&-PDw{rf_noc%rjBza&uXyrq_xe0rEHr7AS$K&*hxiNOLNczYe58xRv0U zq*(?o?^MHt#ZVOkMad8qOwtfkaQ?vr-4N6TvT2CG6JwTvD>>O{oDEfHQ1l8>L5v}& z>co7xag-R~ z)+3&nz&FXblLBUUiUXa*0B5|30q#g(bJlzhnlIOv5(C_qNDOdMDKStO^Qa{K+7Pbm zBn7zcloX&lF~HS_!~mCglJsjsIFC*Wa5*9=KzCw*6TZX%=iZ3{j?EJTob@FII1|8W zCAdd9;{)6WF8nas`J%GE4Kg5jAG^+N8=<;`z3MCUeQXEKxM{+%*LIR&d|qD2CL5(b z{E_XMc~N9DeQ*?s7>~_^zmSi(aDmE~7+^n{82BDv9FZ~_S+@;m+nyLm2Y0-6()<$x ztfh$o7B})4MUxod!#KFD63y@T_$C>5l5ykeWI={MiEj(qAZHP&2)GD1S^`5)Vu}bS z3dhLeed45m{qp{EV!(cRXE!Nezr16d7_eX7i%kmHFYoat2JDx2Pm==n%e%5Dc6`SO zuQr!&?>_Um&-Wt#WotF-k{8AQGjj7*WS%dcm#fD}GK80J<<0=%vJf#{d5L+ed5rKf zZ~2Ga9q^n85!02InAeHN2yfArZ{%KuC!(#V23>iHd5?FjaP!l>3&`3bQo3ZE9N_4o zxmypum!LJbKjT@5g$Pf=*@>C6)(MDRwQ@Drhu9Rp8Rd7u}1D<-d2c4X_J@pKZ$GL;d@!3~JT5-hsuSjz+jFaOB zjE{5^WTFVCboV*W1!?xLiSXoJ*zZE)b6+qF{Dm2WkYSwgCuZOw23Eo&e;v#t|U?V1dDORP0pnC&CRa zBW4obzWvz(gl}By-H))w`&}*)zBjFF24S`F$59<|o?+dIp@hXRetw#8{8xwGBCODS zO$6cQ;mb!77O1rDJYo7>A5A9g8n^Z?!mA0{y$PH4U;hi?$p#;eBOGz$7%GF$_rtlb zpCxR$`p7lHT`wITOZfPVv_gbi7Ch6H@P$7*|3moW?rswZAL}5kCK1Fs=0Y{&^|p5aBbc zBi|?dbHVBwglRKYpbhu=zSzC-IAQW1n-&wEP5Tn9g3tGShf`>|F{6+9;soIn^$vbO zxH$M#8NwvrNi>OQ$66l!gs@1b10NBtzP9Ra!cyB;q5@+aHEqLw!r1pWuOrM@=aeH1 zjQ2lHxZ4ZgR z6#Ry8V@&T+gq7+&Yi#YUw65v&ONTDs5ngNg%rk_YJEg%;(SQfLy+rt^uk%&HOVh&B z2#38dXy>p#a4qm6VcYGo*9muimEDc7#l^Mpgx|0Ga3bOG@$3I4JayOCoe3YRbgVGp zFT)SNM%bh_1=liVXYBY^_=H9pIJ;F1=jYkL@ynhO-E7*LT_GLZ7XSW~B zB>d~z7l#RZU+mS0@b9nsR406Je2*oB2iBz?BOF+X+Y#8VxXZnd@ag7}iwJiQkNKLg zZhwCZ!bJ_7vV?JQQ6Cb%oDjX6@SfE@(F)>}z)O7-2qTVkUr#vaT&K?n3;uEPDZ&}M zzq*&Om?y_HW8j)_@SnXpcW&1(slq;1$jm@szTCBii;Kbl1teP)eI zIP1{z=Li#zjo2dp{dPxZug&FAzrU zFL;h{_Kk?Cgk_idA_~N4L?0 z{cEP(PIx~2nLdPriXHiv@N|X4uM$4_!m&8Qz0JPvLD=`y`acN&`1!+0gpEF2dmG{B zld@9@FTD4~7lb3H9(Y1)r1o>zN$!g*V2>i3A49#eVee%)h<60zVlx1=LsXHKI;%J43Bt+ z@cx{8_#qid|-cC5yBy7BIgqR zbSUO1Ve7GBj}mTM=_V3(D$^s2@V6qV2M8Z&((56@z&*N4{@hsttEy zU>w-fg=YmMB_IP3_CEgYFqkfxA_MW<3XnWRFi!S!0X@as*BB>PG24WP!x&#Y&wQjy zO;jwo-7lNKdpNJ8+ym-#DbWCg^#bxOi0<^m7gM{B1AL_iJ>d+$eE{JG4{KJm05`}vwqKH@c81ns}#>oCG&Yj{(ux* z+Is@XEd1w@V&)Es0ftYIHzn&Fgf=i!Qi*Vr;p5*#8(G5ux2Gn`B3x&28U;$-N?iPG zd@xZskGZE)NZhezX*JZ1yxVJ>v%eCSL# z#Y~hlSZ~KvERM#PGDJm}z+n3M0zJ&@;qiQAd#p^20ckfN`-e#BLQe3J@3F$29`_}L zq=)b}CufMfgxXW!U$XoD6r2YNHlP4^sTdRb`1lh5vLK$OD2%`MY#0>$IbZZ!lq%8QChMYd4(e4ZPqWBOU? z4;qzSCwDh&(U9gx&2~qFYEnp=sn+N!uwu1>jnPrNVl`GCp}{Q%-MSF1&8D&PF2(FZ z@aG{EU8cw34guEkNO2Ki*FzL^p$xcrF;=*b;YK`zIU)XSij5+uUdU?ay16wEI&M0+ zRY6lPL`N6oaH9cBWKFok@hpBp6QSdz9fxtx8msiplsnSlla~!nTilFvb^^28P@5$s5BvBCmY`4IjJ>`%B46|Fpu<;FAI1nJoi*^#D;S)IN>C40%FH z=3%ryNASyc5jOzvdvW;Um+vrvlLc6klf7((QkD2Ug||0>-0){H8W*!*YKVp+aGsp* zKxn3nP{xlD+n3OXF`8c(&Xh@tIu6uTMLB^DzV~IiVvKqtnB(cf zOHNWJ+E)~jSHZtE2ea^+yB^Iq+BHP;m90WHC@kAF#`icFWhg#bLOHJ>Xn}YHa!qr@ z=!Yn|m4^*WLq zrV_<<<^a~oGNX8+7m3F&@y94GUAPN{eK)5te1-e|&3K2wR3sYwZF!YD`92W2g-hzAV@6>?dW#m(uL`e1xNPW$wMAQ3N5`asC#6}8Z;7xe@aX$N zVR_<%2Y{C9&SRihD}_K2mn8v!N5GsV|A2BPTp3bP z>7RxQrtKI=(3r_$U;tRUASPro&iX?#_<6P_80Gw}wyoI_Y_r-F=HCNe7{b7rvD}>4} zBzCc#MBW$6d%W8bx>!EuJoCQTRLF>XjP|=knTsj&Mmq(mVI+3|$wrxsqXE*w@JvC# zN|}UG@%Yv&zch?x{w@{no<+JoudZf@M{&fa4nHF5A+d05^5&Sz_|ud1L~IAhLTiMC ze}*VC<)Wf~gpkI-nf#B$ggiq$E}}xgkem%gVl`D>>g1`|1x8Em;N{WMqX;{0rR3H! zLq65$wS@Td?})0kV^#~tVxJBz;};No8UHu8jODdu+$0TA_foOA6jZ$?D!htB3Vt6D zX>JLU?k$+jEW$)3cwC|Mjls_(A)6UnuEuVK=W2YdAOH6-Vrf3byCYs^Pivczd9lGT4akC;`Lrw zeHZzK$0aVd#;H+mN>5gGd;Vz~iry$M`E@Wyd}g=&B6rKfQ)0Xk;6)A-hrvHv`aRSb zg1B#9q!sanFeH+T7!dlF!#_{5QBEI;%SP!}^J+kP@)l``O14$wybJ>Qtpp;=k^u-W z)SB&k54Z*zR|mK*7#BD5n{i&XT9UiDzTShepDX_|z8k5CZ!}Pua#h8$bXtLe72mS;>!=0$#W0gUg0&!dswSZXeNgC9GhGfUh5pJsX-JmY7(kW(7j+hL2 zR1p+ol=&Y-VDn1`V#v`?>4z!&70Hs~Ls%hS1{%|hO)|DEws5hGJ6dTbD17{J(6$8a zBJqM`EaHV|b~TfgY^lOEB;O8l+o0BO%f^MW7v>|Bpkx`T9;cPMK;BnE@iMglx?Qxs z#Tn%ZNXk}%Z3^ci4*3(ZGGvPeaVlU-X#=@UX3SJDr zDo-cLhJ~J1@~a9{$<_mG8FE>J@$;?t|c7EE{;5Z?K6Y z;R!ZnaY{28nVTUc)t4judnBl(?F&-aX|EC*8=iQC&M;zyX^=oln2g9PhBImj03-3;o&mWrgX5=+8H$5L_7!sN#>1@XUrFv)U{A?FDdjtiMann z+&UImU{-m$A#}0a%SrG8NrjN*2v{NQm1(HLZFbdpg;{lW(p#)FrIxDLo(g5LoInKG z(oF+Qk!6S{WvA7?wN$f8Gd?JN+fl^6(I`Dx8Rshehe|ga7E*enQMzM$j+JIA%`ds~ z#OM21WEXcpc8e!tzS2zxm%Ij9+wEXzw~-}nwo3`#+}UlCkMnq&gexL{U%}*3IkzeN zl@d-s!a`%}%Qd(k+9o+6FmMgXF^dg0g+sZE^o>d30j2pt;o}`3Gl9Chat<3 z;xph~EpgrPdv*xhVMg(oS(i|1GnZq%wlixK?8{t_t!tK&gG%&{!tW`1FJ}FVWhN6+ z*WtFpfTw7U4Y(d#*O`sHJ8uFuaABveL-K^D*~cV9hn><7Zy!l}XImVWk`cU1QdRh5 zg-gM(Q7+INx*08g0a>Q>R5V|ve+eYind7%i8K#)16A1M%5jSAb<8xu)ZK~c9Ak3C& z>Z=4Fcb|@ol_s=MWXH2P z3q=sUkmZtM)uwh{1n}L9Nav6$jG#h~Og^_j;!RX&}DdL&CQ3jhkEQqJM!uyM1 zNLAA36~=Z&^esk*lKqQ`zAr)-%ilj5w)8u3C25bMzavQSjw^oxy8IubZ2*}(GP0u zwA)X`+*BVou41sxzm|JTWlTV}tX07r6lBU)^|7RW7#*r#p#s~Z_)vlM{S>mEHE~{6 z+@A`^BQj|;CX{2A>H@l|5}5qa>K&AdqB=NV=3n2h<>)8lKPe6rKc zlC*X>b_B6m@-$qJ^rBIC1YMC6v`MMT+_vM9mhPZzEJQ(#(<&xjGi9k!V_+wreD3lI zJZh04QHp)plhuH-C#)JsVSEVGNio5X&PRJqS3|BbTkq;LYY4B^57?T7Q|=C0wC8zZkEi3 z>s#ZR0#{UT=7>jrP*b7vbT`r$Fv(yBrKqo6gxedng?|Wr0)4?8aR&Pw^Z?L$rAEx| zVijWcw9b|dilNqMh*H(dP61xe^vvp#d2I74xF7fi74k*_n(J#E6-ZbrsDqmR55%g` z7-^8wkvUnT#BN7QT&Ag1a_l!(N0Z1*nbk6-PFeOcYy9 zz>n-Ds)UUPMP!;;lml}O!+h;Kpc2jFE^UC?C=aq;B!$g}evjd_+%{Q(HD_rW7LS_a zre}}XC~I-YP@0FeErqiLpx7wq*@!)DSgxCZ4eW0gn1K8HaAlWgi-%}x45-B9jW zpUqTh9hPmPDqb1~eETx0LU0W-t^iys;K~q>ykg!+HM*7#dJkB|WEI{LRC^%Rvx-dl zO)=#m@v4WhibuGKxZYy^G9^LP>IhY%Q36H+glD4qS|Z9W<6%%wvgIwskOzcm8dXma zKCXljZa>Wqq@}ykkMhz2DG-yX!NxQb1K*+bPYm#fUK0Zi@trR{yJFuO#h$S>i8U+k5LK( z{bPIsNk7ie^N@?QSt{=lwgw;1s_>DWIHfp8eqo;#9o?`oB&DvJj@x2xdzNr9%f)|vZBGxklh|$r`|>|yM%d)*rKqkNg-2HWuTYB z6ysv5Ux#bOO*}hHN--Y*#d6_UAW!NNl`6gh*yaEt+lb=1Am4M`@MzjOhj@_^OJFFU%U<;PV5FWB$e5-$UWj!24}H|gPdl$Q~dC1>FJ2(FdJ z#E)x~K4rt%mCc61oQ?vSHSH@(_PdvyOJP~Yw4sgW)Eku9VRSf#W`P@b zunsg$hEfp);xxh(g%3ec%mko5$LCYC$83&dEkyV{Nrg#icUrJODq@Tr#HN%vT}B1W z1&Kr#copnxO-^I~hS{79N}J6dWo6|+Hm^0=3`*uPDQSlu9T(}}gSZ?Et*@LVPvV}0 zhZ$HK=G9a&-jcap4c{ZZnc6}HQoSg{Z0Wp-sQ!WgDg9cW)CLE~`1abvn1u@PFlH|V zES4*nic<>IyMlmuasY|lD6g=yyW0d09m39M2db{zTY$qZ-%tjeJA;5=0S|BiBrM(W66#9J6%Zet^!O>O#iulLc&QGNE)c2$qxSd9t(U3(P%p zRj5t@4tKkmfNy?BuGBThqmP+@iKswQ&ty~CVPq-6L2ms5d`Ya5NE&GMGegR1{%NCkV#*V(9s zKY?*2NV4QFko*AGTDc4tVkg})xw{hvyQ5;@sstAamPsO9I}x@<3V|JGIH9=x!`up)-%WrVQ>Ge9&$ z;SA}ZWJ$0AL!v_zd(a}t!R=rr>7XS3^iM{<83tk<$oSLu!q3)tOSskl3x(~WKaKIR;3)c$C&t{9E;~1|P)*Ba#;RIa&RSc(54BaO)e@!ypGRdg=B8QVtav(dS03R=Q z(+`Z?C_On3oMjAgEGRya%jXdAb^+c{?7CVKp24K!4dw`nD$|r_rnJ(mVt#Z3(v(4- zJmF$vie2AHQ)13jM|s47KT+B%a~0!a5A)w*GGvDmdu!khL_kIfmCka$q%!iCHAjzV zIFypMRRozsrNh$KjkJBeiIx+sOqrT1b#;|cXENHtuy@D#I%D{CpaK2(FG{qB|uR_^O-mH|&qFpdGHp+02l$8ZG9lNP8E+6*5x&G2djYcu?%VGMsM#%sCHnU?!`1lVTy zFI6TRLgZ+HFQJER4z_^AHV41L6>5e_XX}5vm%aK=0^1B9MA*&s-!?v<1Z;A{G}&^h zK%1#vY)P+pv2`>qHa?@_S|Rz_Y~NP2(_v2KK0` zMB|;Tm^{YYPYGyeYjRj2L0fH8KgTH*ZR~50%Ju+QJpi$-#?zII7UrU;RSzS~>nPBy zC>6Ce6eC%y_sH)wo}UUNXzo27X>;=vB)S2F$J(XbD5LA5;@% z2nPYxO~6XwDf*GB=gVGcR}cISHM3+Lkp77*?Zt34fC~jNM5&e_(M6#L^Tf-#s=&Xl zc(%3GEZ(dcWy*$Jm`4=jMqU#%Ci@h{>X#t_%`irhS3FM!Bq-L)R!!nBrhgd>C2uCN znes;g-q1m&WJ;r4F?@YfBC@eVYKzP^2b|J=iyYvivZ;!>H`-FnLWD)8qfm>?V3zTs zK*86TWez4T&%(7!1}n=;3VVWlncM>WDd02YMGa@0V$8@kWoF%Ch0M(tp_P2w>pXwK z*re6XG*@QE^nX0Mi*Gb<8PPcPdzv-(H%WT%!PUnz6m`4g)Cr;Sk}%fo|e9d#8R zgT%Tp5b2GNoi3Vt4M}hCsH;b1jEtF)GaIGp@y;6G(M?uieH9J_b2^2dGp5H|Yljh( zC70ofo=n$2aJ7RAdn0Kq$!Mew8`T-oQ)OrsV~pI4!2WbU0J|qKUsA!&S9$v>^+tv1 z5E(TSF|Wc0heAMhdphGA0apv-ngG|A#`P9lw@hKvmHe#hdj%Xz4TqE7Zmp0Ehh<0; z_KT#2%vpG(x&1XxV!6c@sW-D8|2yR20pPT5n66X^=e3B5()a>!71gtgJDYXGDSDzz z;JSAGa8C1aq@O>*bqm7H@_3jaS=9PIOdpd~+Z_dM2KPW3YJ*a$WH5uN>v05S$-8hR zO`~fmTr-VpBV32zT4I)ao>EbxpEU|EfRrq=h8Z>8Tk09BBoh>371J*D^acs1Xj2q1 zUe);wGsYdV2l4Eaqxg!fk#m693>mRZuE2E!oJ-7B#vJ9%eirdp2_N(hy!)&Gv_hJ1h zcyBrJ6)BXnw_&w%H6@p+RlV@bA+4r_wE8fl)j6Y8va*CWSL~4I|5nc1Rk0_3d#adV zAH@7n_=CtwEXgD7cg$uIAzhpzg!qalFeQKE6+QcU9C`gIzgPV zZe$Wr*A&Gyr#BR3r&1WBfiA^%3hkVM(V%`*4qt)r^ca8eIwN z>wt6AnZ1MQG#EC(n67@lf3=ujEbPRmbTzUl#DE84< zTh0@ZNo^2`9Kt8pI%53H(8^jbbLaSB1YlvYk2k{Wrz5-;I{bOg4CuCiDpPJ%;cVQu zL9VI+;O#KtLP@sVqh#KkhmS_fl<*cBJWJtO$o!ouE}G-1Xj+(OX0e*E4<4?RlcAlw z7v2$cc1;sD!8Oe@ptPN@M>$40LTj3!WY0@VoEw%j#hW%`DC98->=ltZPX>GCsfx0_ z@?_=8(<|?hIn4S|fw_vU9cQz?=G!s81K^jzbG>w#CEO1Yu8W$ZOxFK~fO)b7iPO9u zWAZxf9R~aQdL{CTS0b5mOrv4}G=g+f06MC(_HPQ{x{}#ZZ+X?r>ymZZKr0Nd0MU+K zWg(@8Co6F`h4Y}yY{Vo-@yRv7aAwmWQk04%xC;cK+*~A{0JHG!+b`1|!2w4lpK*)L zsjd(r+NxTQ1eR!qDx2eZvkebwB}M`u{b`lRV#z5MSQ(i?uz3bKpa5Z zD9?QXf5kX1?q+~srMZVNMWcFKp(MnOewVEZZy}VL!xrQ%Me*i|$;jbFu}vfXULaFc zKWHIk;;tFa5%p;T_PtTkwo~9gKd;|v5?%B~rRpsF5;*z3tbYWXu zoC*fH8C_sKK&d(6&k#?IJSDwH_^TdLHDa>TZc%s~IZzwLBpdLtO|vQeI+TAIL%>2a+e=s01I*#X2s@8k0<@jmeFxW4;d~EsrZ#i1zXrNole_iGu02VfNgZYl zN2%w75x%|9=gut8BI$xfKJqD|d@zEov_2rwB!XK}~$y90G|o^IwgNW`6qz9BPp?mzCeDas8K-V{ofjo+rStX*>1Y77^6YCJOI| z;3L%Y3_kWK3tbp&`r`Q;FzHgK7QCk-e19O=zsRdBjXEO~?elqrZpF5C3zaum;V#In z2x=LGPnMARvBeyTwO4{2DEGF&89QPn<}!5eXpwjX_Ac;zb7Pf1pgCC?-%)t?k{I7f3h;kGjd|5}41(s# zT;%!=b5#j9pp{tcU}U}-D)84f=PF{c!VO@p2to3Mk;dV|9ZOlR9Bj3MYk_#A;*A`* zx?@g--gg-$aU+tQVz$cLuJARm%4EpgZeL-z5y?lAP+F^muQ(h~vU3W5B>6g!FO@%m zHgr6}a#`_zDQvzBbl)2~&O)S(J-rsshsUrP9Y;lT5q=xIjOfLl063c zCa91q3QthjM-aAD-ZaTsD(@1uUMfooTQX7Mr=ZMT=K0;A^40a=a`5|?gc5aE6g|9n zVIDWJOen0xKor6o^QsvHPWl!COB#X6D(F##?@(a39DybC3bah2)T!5KIq(MvEo&aC zYN5h9Dg2v4H{=K{n^$OAqe)1pdX3O8vDzXPqhN}@ekyFV!VW7S^h%D zdyy#|PVNkFFO|oE=E=A&gsrLUKAx>fHnDC|`p*=eAm1-Ju_ot@)iQ-LPQA3XO)#DV zD&!l5byq=Hg=JJ?zuMXfwY7`Z*3zYLZD>_B+E))`58>Yqfz2ZkXwt|$_!G5- zY!!P4lKTNCNAbxLGXIUBObJ&49?5$Xp=>2NSj?0{ijmV8`R8Cv<60GMjwf1pW{+%K zQXtk3SgIT!H+dilOM%~k_Xhs0qPZV3Zf_r=!rLu;ea%^Dt_Zocv-!9Xp1fHoblMk# z;K4c+JbZgiJ*YDELC~0pJ;EP)m44Ad)p~`(_N!xjy+9@BR(PGKQQ<7Y7n}F6z*G<8 zm>1V@ICKCF^w{Ozftcu2h&~O(5|eNDtIW9mFo)-(dx0)Xt{`dQYuOw#pjEi1qF4IrYfGtet z%h6fFOZ4@@yg=r9wBD+jsS5!}g^}}ZLTA2UAn0@BR;rQD&u!%MjgfPN^&l)ZJ$j3Z z>u{T`#qT1Ln&6ZlS9!)vmlWPe6XgqXJC)-yb(anyK0QCmDg$)ahl_Xih(x|bC%p|bJ>ak>##WU8oKm>B+|3>3tNt}es8fzXFuM{i` zOTn_R6v)CqYpYi@J-;Y)hPpV|pq@sEp()fgc8E4BTgqxi@h&dSaxhZr*Ra!2R^E#K z%%qQx-pOW~3EPEsO5)|S^R~NI9Aq>a;@^OmR(8epCc61zPmzMojCERp1s7yh9Jjf( zj<8)c*E-_)qi}nq2n+b#=v1ZrQDGOTblYm6imuI5z&8+%)?y$Jyi7iXbYwd16Cz&n#qj0T|{KU3a z4p!C?o(RttI&JZ6VWx4>7WTtsYvoOBo;_GL+Jj}IJ&=um)*iNKOxwH|hq~F)S3NBC z4B4YTT8C#Do-NE%++=1`R`fBGUfP0xt7i)rl*B8N|H&3^qWdpf$P_O|Zb@86bkxWl zxK7YmoY9yYRgAc?hw4-7L2Z23nhORU0BTkxA@K?zj( zn9MByZgAQ1zlqH&f6K=5w`?qbvgMS23ymqoi;?9o>apejr26uf|4P#qR8rji3gyG- z3nrbkfwzrl7U4Rs*%h6I zko$MAz=J3=bI5mhbSgCQ?Tpb1m927DD3pWIE2Sy;)@s0E53w(L#ReRGm##o&$rJdN zfs|e15q_$KKSQe>G7L+H&E|C_+&;vjuXqo5+HaEgp|~$O26@%iqYDyW+0`iAu$Xd>efVYp}I)mXf{Wk^hNWNjd8@V3UXN z#Y}~qEF(wu(lRM35iS+AT`6~Z98QcCby)+hd5DOZlOa)OLZa^27ZUZiQvU04L_rkW z3NOIbER^V&CLeiiMH&Ryw&Er-wiOQGDqm~ztOff}bc865@3CtOCztZQmjFqM(ep+!oJ(-1K>TO|)*c!)w=CuIz zjf+O!8!l_+`B@#W1$f;MvjxaDF17$<;~G6%|9%?RP%lnj%<@p2hYbsRfE&ieI4kV; z;>^z)it|yB*dCz2aWPJ^d2vqGxTbk={vLe~%-*K+O~b-Cw-^`W{1Gmj&it&QIAafZ zaaJ=f#z{8bEo3?uXk5#^I3w`l7V|ao>cD-WmV?noULEHJVDkn6Z6MIbo?l2P_DP}G zmxp2}8~^qQfA(4KjPdIFqGGN=909?nNViW z3lv)COPT=p5bHeCc}mlF&P(ULF>h?+bj+r;$H9DQ9pVMpv_1_%Hm&&uh0^*VNNnkT zV_eK>vUzp?XN~!ar$Gf&SgIDG>AppwRE;U~@&6aq^0w&t#e@{Q?Xag<5?nd0xozDF zX{?34*zZ%d>S@3O9wI4b^ZyUE@{0+n)iI>j=>JfwiN^Yn7kgc8-n@WEJw&~jQm_;I zyd27i?{D2i!?w+1@Ww&R`u-|ps3)v(%)1cwe_KV~tj{kdl*ac$Y25iAX&j}oj`3oD zFlM1?E4_fZY%80@*tFrbp>!q8+eor1@psVWk(g{H*rD(uVlA=*sBiGGJ7|eWHl~c| zJRy9W?I2sk@P`B=+yuSwx5Tb!s}SEHXwf<*4I;A48umj+XhwEb8#!JI%i13*?Z*o7 ze)n3b2LuSK0l3cx<}4S!(4C*snSe7le4*QtaHHrZl2<{(Eh3UYBv*o?n*m&gN`K?u zt_0iPe3)<2I^j5OF{>{BDjW~BOYKDJE8??M$c(LnS@IA?-RV-U?@5IhK>HYJKgY*z zks9$$KW96@a~4IFvYA3ThUaT}&SC*b?CH}Z#>I0Mzr&Rw9%;UFp7I!`XE@Z2Z;BI0 z0Kf^<vX9<7*e6HflmazG-5n@h5fb`v)C!JNkVmkYC z7w3l2Zj^wYz)N$bx+do6}PtZDB_UiRUT$MqQg2<6CQ zJRA2J7sRR;T!=2gO`kk+o6P$-yi1hrxjp7I2j~!BXOZgELCpkHmBQ;f9zO z=}BS_8$@UnaSB7HtA~MvO8|E%f-f<^koYVYfIh#-vtV|W-Xpu$lT)l<9}^u{>CZw| zhIlA%l^!>O^xz)fubB%Se+0)ixy}PBB?{W-Z!Qndlwfh24aHC6{yRvF8Y2T(y0~94 zd>Ci9VkC+B*`veuWW(lMROFSqc`1+tzDHYARd47ep<2PJdzigkN^kNtli;DemGs<6 zSSkGVi&e_J%@Z=L;8Y`|E0DV&WVtzsoSzK8ieYaikR(Gq?$F^4ZfKxT%R@+8P0axo z>Z1iu8R?CI_#UiT=4Ut(PEtr;CCsqe%2&r(|pGy6(O&M1^&1q*!2B<}?BaYz9j zQ&muFkXMsH*9~+_g{hJbHck17kS0Bj(jh}isD!*J%9NIxPjyhXqaf0jtyz{*%oD(D z$icAa?i}H>cd3(;OXqTyH;3tA7K4W6zI!nHV}~10}FadI(v5 z5N%LUbLvrrLs1OV5vOG1V_OF~#e*LnfqB&%0$8Bo*v@I8jHwEfKz)<~PUExG6s_sA ziad<2KxuwZI19AyKF}V=Cs&_U@-&;s4s6sm6=W0n76NcKdI%T)2eR=yZ-NgXc(o)W zcozgrls~@%$2Ei6C95@(&lN5*B)i$}{#cM(2MdM23geOWgA^dLQ;L@)~iWOJx&63%gN^KB(C_Db>G@Ao8y;pAnu5}a0; z2DWpQ)ZlA zqViYxHpbTzvZX&h*rWrQsgQF}AulUU*SoD%P6X|nq-}C2PlddJ@WpbHgNm5gROs>4 zcT5Evkv~;L!cZV%W4|-0;Glv$*-}&`n?c1&q0!u_L1h(6q1cxWdPZ{-a!Kq`V>CA% zh0jk3+xd^9@cF5%32lb@*eX>8JQK2K+Y>ePK~KFqVjbkhT64A?8JO=DfIZ)yp9$yN z*P6p=V90k3AVWOK-bppnt{fCkMp4A(6?mq!P&F2vMzf?CsgC;VmDyGxK+eGjMxt9$ zs{NE@lETwSZEvv3X?$!m+k;k+e4h0%fT7k9rF>PPltESH3&lf0vO@Bs|LcWfk5ykN z&igVk6gvaOCad@ig|i{uJq%6i;*+cW{|DjvC~*a2ZZ$8k`gv^T1!W|eKly;I&>Y*$P4!=u2ge=$AA9csWmU1X4evf@W;if2 zWF)5n8G=MXvIH5DWJ!WZ7zP-G8Nv`111RRKm@x-T*PH|9h{`qRoUid3u6ot~d8)d1 z_dekJh4T$o&i+gKb1HE$vONbFtJGU?DJhDT?TsQO8lthI_Mv?VQI~-#oIN;p~lP6Y+%yR#EN~<+%guu%hEf^ zJ|9I=Q}7BIoqid}PpHiejBUSS$2rX69AlsN8ac%@Nlq~lBMj;zLJQ%%XmecZi z4^5l@$}z(5-!h<^8n3aA`GKqVZS;|>F6T8u%$#zpHvWp3d+pmL+($G`%Wyw%9PxnPriHKlAUIpP4Zfd9=n>?7*~CU z1T}y6%_=44aD^DYsAPUR5TDE4R?r63XTv`%NZ>Vd;dTU$DZ%h?1ZE0oJ-;j8b;EThR^(@ypWi^;J}QU1@hQ}` zx3@(G*bQkW6Mb%BA6SNfyBa;qJo5qY%L-4NBycD5v&@Iz1HM4!E`UEFrvEypFcv!a z;21ue_k%4eysNj+aiVzLw1;!WZe)yk!+e2BmeiZ(iJCa+ZN8P?G~(Ve*F&`q+RNar zdJYx|FgyO1*#_D0!!B=`{01mNb-p#i+qI|g?J&IU_>FImF9$;nyc5FtHU|-RVk7vF4^nd&QGnfq`TW72&I{@?*^RFuc1(`M z(nQJspdMl;nSZwW`S$=Pnr1q@2nzXzvqol;`P;7u-D>6_%Fvh0CtUEOca1p&{+Kb{&HFf#GqkNB zajHd;7zC&5(I$s{q2;5Sq2-%ozC~*ryhAB-awGo_71Wf6f&Zi8)0rjvgmFO`~pedXMScDQ^-##-zxYcHPAOh&iiJ{0jbM5vc8!ryiQ;whakn8 zZSvDO(SAdO)--ecQ{Zt`N~(JjK6{01u!)TMY-bXYg;YL+pvcehPBIhGFNR#Cc%Q|1 zOqS0e@V>^Qt|Iq>(>~-oMdlU4LNuCc>P*FOcu)%0@BzlOsG2Ll+u;1Puru2Xzc(EX z>&om=1D~S?`W{X^xd>a^C4)%z#H%R9T33qC|42tUw`qo)#1i7#0@h>V6a2S(3AAb` z#x*g9yxoc*_`ea4x|}WRo8j*yv+@KJ4gOw}aGqFO2wL2~rlq3P^b}e;I5WJ$S6dt# zo8~NUY=CpvLa(VbxPjMLeBQpR_)IS?R4C7h=9$M(H@RQFhy__`&AcWzK%LeG3A&rd zF^HC2!HbR!ugA^jrN{t({vE)_F<^Kpu5#Pm^!o_lbC{LkK5)gJWVV3FkUi1@zmahM zpy>S4@FepG5)FA<+v`roN+;$UP+rBOuHt>lif*D*ctfjFnPfhMb{%q;!t1;PxcoH4 z8`5t>Z||FFjzHa4@jA&|g!7z39#U*xVItTlQK#3_(ZF7FkjU_|Ditk*@-_z;$71Se zU?0KYt#0|eu+gJ|^o`f0qTv@AktT1Sl1RXNUu>e`rh!OSz52#jjYDu$vGUC9}+d{Gb@aIr%Y|(oy>jxJ{{uJ~ zp(^+T!sX{ps0NgT>iYv@##AnhMmBr)S5kZrDBAufnWu1yYDjl2MGHnqdz%yCUw2cA z@w4wc447W;A&x&FSyP0#g#*GK+5-<@EPoJ7RX52jpi-~Y*wrpJU+Ss5xts0#`#C^2 zXE09G8sCtdLi-TMRM6R~{WccAoHR2K(&HVGi0|ehreQCRJ~C!p3S+#OIU+axk+Oem zOyjYxW9Jj(F>vMH1Pt%dv@`KFbTb4(%eglvCn`Ds_jnbhNjmD*L7(?k;Zy9HoOhdG zQRAVl_}Oz1VpAsX`703Uu!o7#?IseE%58>TmVWXd_$e+0Bqt}gyrL>f?*ZdD-C-4R zGPxMyqx5#t>3%FBCbNTd+LKO?^9V^*JM?To_H2lsp4SnQQ|;DDSm?}gX>$VmF&?)Vu-4$^NSkMwY6o&IwS5XLgk^l8K$$IQ~Rh&!ISq~9d& zM3PUpKNUYSg>Dc0re_I-ht9z3!Sedv=Xm9Z;80ZJE)u%kiMv=RY$xs^^7<}um&ohi zGk9Gq$#(MfP=OW?#p|&GZO7N+2+dttH9u+`?P!My-@TqhwYMKr?Tpsg9@s6DGk7ex z&g7iJYj+Do#Tjg=u4tbpZg*?uv+k=>Ac9q9jW94!7A@bO=Ngn5%E{}8X zmdAPT$>aR=-b{BvH+ft*Rvuf+{ru#76Q*Gt(bcsBk zIanUgu93%%bL8>dUGjMTHF>=73m(;TGNxr;KC7Dn@~mMFmS-bFeyZm*H55+uoEC;+ zsh-o?P$1QF_O$8R*>uH{uExD2yr&f+X%FMe>uFh5V4QsJ5w`2c(p_Y7VSAK+HUcg}8q-0y>pyV} z1?kLjF0O#6%0+Ec%u>`ae;b06Da5*wSbR(5vtu2wYMS=}7p#|dizO1NYfflx6zkU* zOLC-Cz}Ls~L2C~)qML~bF?*1kb3r*Oyc6Ntrhr0jW?mX?A_8!IzGrvjPe|O#G)H0) z+jN&$Dbz7#*z=d$)@*Bm=}RWAYohy*q`kQhm;zDED82J^6Xo5;-kzz}4Q&CB?!)EL zW4b){hUX1nuV#jieTwDLyN5jb43tN|M+K$-^YR$*hCBv-ERR7j5|M5&G&mkZ4-?>i zaLEuFc8NSnZjr}`k%BT3`X6zl4wlF0a(RsTR#3+NCXaD>0vumQ9uv=&$D||hs5k3O zB;KcU1`8px`I_0k81D`CzYOnVcS2XC+F&p+5;s0=%!zqeW5Qp<>mhnmK#Zu7xdi-W zCLUc2D%#wD*xOJ5b;zT*{~G3n5da)@_j1G z9De9_gx*2y7coWwNrI7K=>3@!UWfLP7Mlj|HSlNU(%dXZ%gCJBw2z6NC!;NWTvRv< z0z_5z<1>9DjEKCu9sp8{d#?dz;UJ)n8xFqG+y>b87+w(dLsqR! z*^5ZD&g_UItU#i|DF9_^^vVNXrp7*{{rTv91RwdU%LeeV<~(^E`iDFYZ$6N~qx#BY z<3xFEDwoI6N6BOJ4e~htX?dLZfjmz6Qy!-_+n32t8z_%6X3OL3jq*5mi#*Q1LLL{~ zC65c=kjF*8$zy9Xm<^fyOM1%VQhu)^lmFcg;q0eZ+cWg@asmEwiadV(Odh{oC69kU zA&=j41_QHT_BPga!JJ1WH1BzNlzuLc`Oy%@l{J#bf^PCyI6@waX3L{|qdXR0E{}@s z@~He&9?Pr4ILQ>O=p>JoyeK78u<8(btllJ#HK)mA?bY(waIZWL|GPYn_*x!ErS@aG zjZNio%uso39xsn$7vNF933Okka9RI7qp0=qXgZm~+9v&F4YVlMD|Cn{S^~ipHZZq9 zXCmCj5UsE-JO*Gj+yo+~fN|PVB58ny>lPz*+nWypW^>Jzf_KPep}C^+xvT?kfS^NUqbp`MPNc zUfZ2}FLYYrS?R6Fuz1Nlz_&0{WK_Hu7Ion{8p;&chKvi(?T%VcwW%GoD}-g+sPKaH zQH3b?0wiX++i#kSQN4#U-+s%r2=p$6foDwnQ%g)#bLfLCy6Ip_7J%68`~Qy3e1tSL zzl{Lk!7gd50dg_DR)D{TPcs@C;$7Gfg^$em)5h1Kxr1>^TW8o%MkbcFFO&p4)9~*xB`|N8Q=dH5Z)R59_|E2g_*5D zxH3jU{99nJ@PiKZZ2SX=Ie*y!r6~NlU(#iltwdi!Xe1- ztABy2sR7aMfxm!O)X~(3(yn=*+3RC)vln9fWMOnNBX0nSlv#{HNO+zEj00n=XfIRa zb#PLdT8Xh(5GvzHWmt+Hbv93(2|{hn&lpjOm&QGc(0@ceUPNm#+M9p2au_&N89hym zQ;8vs9E9Gj0-?Rky0jKOZLkO&VS&UGYRG!%VUC5I`=K$VO|_cf5r1)3RZy0N`) z^SFC!#CFV8UI6ITag6qBo9+o??ncaGKK4>{fXK!^XUwaJ`6?M3l+EJ3ijNfnr%9c- zSft|d5?NvrW-lOe#>~nfz58 zO{8hDI;Q@4D>fn$t1~eAdMxQa7OPik9EK>tIsh26J(je6i#06uCwLL8b-*~rV@b&@ z)`V2&B^K*qU|i?1Si-22xeN`oa8~Lz_&V%1<}qMA8)G?yMXB#F+OpG_PZ0SP5mb}* zG-Va@qrzpW8xFA)s$oQ_i9f5qEW)9wu1F*l+9R?n5tKqF>^K7tN2hYp;bt<6QHY%2 zDOiM)Q=A={K!nAJTuuZ>VI`cb!YwJz%m{@O5qSm?REKslf^c!_$3~XI^@zMRq%ajp z3$IDh01zg3Ao8UUq5E{!)*&=+6$R9(5$t=a)sn0P~2$QwyV-Un&%;X9(`EaTT zgan}*B727jKV1NXXHrMOQei7L6A?K*MBt1-;m*|ZPb|U;M6L@FHe-w_d?oezCW~+; zBG2~-9ZfB$)WVNackPW)`X)p?#7G_S;*Nu%TF|~rwQUQuSAp_j5)ByNj{>hhr*43o zWqv_y)W8u!n^{WxE0bQ4uLFx|g2>iH(E93V{=noxVe|ByPAFw>MC=!*RwW2y;cj5G zNk0euZVp83oEQW2zo+TaDZRO!HLBJl@+cy>_AmwupN0L>PyHJ$jSc1kL|z>uXda!6 zVC|niDGlqDSPubX2eG_BqMl}MRa7`9J^MsU>JuP*pG8WMR;FJsvXt`SDL3R_K&g}Y zssT;f^m!*)tnR?*6Jw!Vf^dBLGE|?iJqeKq62X=0j+rRe>FH$`TM8=?xjv*I2zm8g)7pJ-)gnO?TCCRrchwDm0;bF&fQ|M-UP;{9?NPg!MY>eq`%cx zrXgtK&z9P1E5UjsJ^2w!s~8x2dn~JmR<1|d9qBo6`$VUW1;&9M%km{yZ>LA2#sq66 zFpf`R`7s9q75q=qt2$T?F9+^z9zPy-9O~EUfv6lI{T$HVNTNEd-_x_svRFR=BNs{~ zsOSP)Zpk|@XXhM?+7f7;JgSttqq&(i+AQY*7%655V#j(6ONSG0g`INFZfWT(1jb5_ zWhEn6y>r@Dvn4$l80UE`J0=L$n4C+8TC7`v@s!6Rt%Upp|Dc?=if!H>0`~`xAIeWq z7v)^N)uPsH408Z~Rx-B92-e!1@u+Q)a!+8Ccr34jI>{7l;i)-&npxD@Ks&^vTKUyq z0qIE#~v8$>+NH8udQ7Bo#ubul9#uwpd5pdV-1|Q8+ zP>XXnKW9+yk+OBUpogF(HYimV8HZS6AeHMDAJlqv93- zWoe8CI(MPP6`q~D-yN2*V-a~#jNqHI(`|x(UGDs~7XMD*zWP`AKDo>3(cEccY|8JD zssPP1TLgi-W7&HxcN2VCky|??81Pq#TqfVru*-%3Fq61W9xv z5?tyNNj=JsZMTBoAn$VY8o|F8xUcLEKWvARsAJxPAKOIVB0*mBxcEL3+t&quP+tAh zEPgBC_TL@;E+v_t*L9jrGzAHk?Jkk`(X5Os@-7`=6PvLy_0hc~u>B zMkQ_jjuhJJNmreyZl)TB#ljEs=2tniUv`7m$#5yD@Q1u5=pp3K)We|F0e@=1=v+X| zIIKv{uNVH2cYP5?zd^v;pSWr>u?!ISELw7zYLo89Rdz7ZO&Ktj#1w(>?3qBQTkUp~ zUJy1T^5hWVe9Wp8Hm-K|A-E?Om13?&I;l4>^%w5V->*3+ZN=pE;88;c1huN#J-=DhD}Z*7M~xY9WfT0Ps(pm!AQku$a6jG+zT@JIYB%m< zjr>1>R=ag9hLB-H{e4Nbb+Gz{YDb{;_oyMmf_ihcw@$IBQ-F4eN8N>C!GEAyo$DVL|Pd`KF&`_)ehh@Tj{mEcp9oN~c@Wp91$^yTJ#;f;v9)=N5}vw+%j0fj=vY zkm361iiHPf_HJ#t7zng+9yMfGP%AUVkiSTH5zr3zsJk#M_!}};HL;}61@5-p;Dcd7 zJtfofO-uR_puOZ#Lxw+o7z}UC!AZmA^n2zElu}Y| zLn`iw4w|ULYEb2;6joc~Mm7 z*3pnt`qt%my^SW2ETq-Bo$J267LCxwjHt$C-!a)ecgM*d@W~#eFf`eAt`SQzsnfo{ ze2i0?plk+d#hGXn@nv`s($<*76g3r|J%slEJ-v(oO zy?)c$BNJ9jy@9ekO^)jg5{}2gmZ=Azz^c+tAvP+hd1I29P<%|y7J)A85vGqA}; zYk^NR<$$e<;RRnK7LgN}XsX$ah%@6zJ4@TtoVpdU2k!U@93s+OkDt4U^#e&4bi^xa zQIKY}d?rXMfwo!yk6Mh^!8H@-(&2V6iC8lr|^_e|+nQa?f^{Zz9nqWW z_nVID#4_b?*ilozzYX+y05O9OL!}{RJ7iaXu*US7i6+eMily(TbRqn8T><|{SHM5k zrSDI4>H9NX5C1%8Fy?g4{PNW}CBVgIrZilpEm(*=`cwWdk@3S4GmsQnb9ymCgQK*7sHSb zzM3ZyucUCRG@#4kn1XK+4^{LBHYGLqAay6~qE?7BC*bFFV*MuRJDEjqfbb`&BVb(Z zMTG0{b4!RY4^`FRi`1u=BC-U3&m!_gA}9x)j39iM+5iNW+kAz{Ut)v;5osrr$9#TD z-SvqjQ?DahCjMeFg7AB4I1q$PPecxm5gZv#Og2cRhkOued1e4(0kNb!1=YY|R9GLm zcQTw^Ymk?&|E|sP7@(c*2?}Z_lfjZwgBt0B(>B}dfN^IQLD<^lzGiw1+P?^4CotaL zg;rhCs+;~|ho$v1Fw&^8QXrY;Ja-<=i%MApA(SL>CEhj?Dlg7pf|-a1v?V$r^{^2Gb7SG zjh~&wdM(+04nR?t5aCPwd>>s8xBKyV&uHtR` zIS}KakU0PtGh!@Mw{1W5fFNY55P4*b;K8Q*5%B8Ie+XFZ@0|$+xG>a)i>)^Nb2zl&AvWf^ zdx5qjP>rjg&Y~L4+hGi=KR+LV|7l9#0+ddFO?aB}ze1^kJQY&zh140`qP-1Uw6Wtm zkD=N*Z#2OpCui>~fWd8ODU%w@N2c0CKQff}3S#Q5c@pbUy}5~Lz#e^WHAtGi8CzQ# zcE1gvfj8jwwMKQ!QQe}bXbN`GH>zu>)X@2gYOTRen}&8zP^Rb#$hJ`<8?0Saavp+> zZLm?%gWn_A#0FaxeR&vyO>MA!(Zsn3HnYKQMb#D{*xUyD6cwM1U<(@@Ty*(C2)44p zkwrgEMzFOFPAEF{X#|UGaC*^suw5FpHD?Sa&vS|zVEk#+&YUa3MMYm9h}ibFM9YfC zu0wDy8>}ko`xt^<%o+Wec5TrmeWb0&`b4^hW)NrHyZTJ#X zl+W-O8^%`{nxHNkjkV#MOi^9Nk25c#YSL})GDVZ$1N{lYeY(wdQ}q2W$bXW#P4a&f zTMX)KLw6d&dacona%e2uHj96Oeb_j<4#hyN7SBW5ccGl(_3&R6E!8Gdd{Pjq9qpTu z{j^P9x*tjVe}~2CCUXtR49YZ}{N_|>UTEpTIZdZEz;npVtuUnyWb}}JeepVru~G4@ z7+ji8Da9)@Uj-31J@_Y-DAgt>8cKIyDA4vh4ln5_{Wgd;o&5z1{4QS?GqRA0hh?}e ztB?swO!bk7JIZjgzTqBy)qf@CV`z=0pQHqSF5&z^Qa0`qb4p7XXGfXsfXPn*-z2HS zdmMmNPVS&rh~6FNCz}4C#JK0bfU$~MV(LN|O>3mdnW@$TaQU&>6#`I5>=N@62J5CH zQ-a5%0+QabJAQxcHJu^#X?TD@BS~pElGb?@N!Mypo-0Vke!`-Ds@(CofigD2e2cnn z`jx^<%)|c%)=AQW%&o-YxLUvlRlp!b!*dTM=0r>*G+nHCJg1I-K~`o&zq}|ZS}K1jWqLWpwK@{$Kc@+<&Y`enXnSu*wV%qy*_o%Q#@-h zLdR<;Q#@l2gig>{;h~RSwoGAkA&uFeu{>g6`R)) zI#olhil6O*bZ4xR+}jtQ*AQ`MsvX-6&Gz?ll&hK61<&0`p#gvJbI2*9T8Rg7yr86? zLdvZkK+4ORi{TL+FD-{~JNw*r5j79*WK$?Hqap8RziZwP5vv>S$ZZg9+DF9P*RWyVc>Bx+uyO; zqj+9PGyvdt;D|)ip$g{#CSP_Z>JQ;+Hft}U=Fz5X(j(0a|A44V1c8U1c15Vb2-$3- zAn-VpBFNBUnVUcjG+CM8Nhx81147+b!SxZ^)p>TxM$|H|pMZ$B`O6wKJW!>alPu2O z)Vmt-X?X|&k6QVnMYYV&*umKJQ~pXk&tN48w1z>}w5H)h5O_K(AW+-vhc45!uRH{S z^F^M53a`XmumxnEG_-4FCP^`D#b3_I_YCJ1WO~U*x{AN+HDG*dI3;D|To$t`U~Q>yBRQA_U zpW;<8?^}$~(BR@Gk0LZyLnDj784S#EEJmu$gyMfPG+sj!i@Opwdy!?0}LWeRbEa#}kj<3>D?N%+@4X}uQU@YXs?@HCNw zPbvcZpDB7=hR2IMf1-o*=QS`MO_W(peCnDKH#~!+O^K{Q*Ye8cqTVu%X?QZpW$+0a zR8hS&MQ(Uhsem$;A0#@SB0ET(0v=$JL~i700^7OG3K^6JGL9oafKXyGBa!87P0a&O z*%*_|Su26@OUm#Zl$`C$F4QDbKq0qJ8J>|+tvJHupA5DRQz1?=L*EC+;l}XXQ~|v; zbgIKn1MEr})n6i541d0%_Sn@%nyG_a^X2GHBCgb%Xm1_-1~1JOqM3Y8EZw5kqr(XtD|vRrlmQL z9ZXA?nEUPpOC5DY;q11{aSo1o7X4iY8qRiSvpUjbpel-9m2rmi;JYGhqP%Vp6DJ3P z@dzl-pKzgzZjv#sRWfc+?Y0ePoC}K;;Nqiy#=K}Foq33g^It)zF`ZrNlJrbqwQa)W z2OPK>a{zbL7+W8YM)#e;q_;c@xBq^=qT3d~50ARh1LsO8Q+y1_HhP%C;+dymnVEnO z%Wy_OeC-<%6knUr$p{GaQ3tJu!}!R$VI^6dWDbL+)v$Nke27p1e~^gtNF&X)|3b{y zQYX<67g=I*F^Dznt4+930KX2Kh8y-*IM2u_v61HZ%Ypw-Au}QdmzX&Z0^C@e3J=jK zI(o=`fHze#hdFow-@q6PG1BlZmDGc#s?w| zo*xuxpk6=6p0tMhrwtDi3hxlyWpHyE-YV&MxX^)XutskeFxP*4NkQiC>k#(?CLQ-f zgoprb2uzBVo&~ZC3RSaYtN(YFX5vFuD`=FTzDOp;WG13DleYi zn+yOKwCfM9mJ=1U+vkj7SRPq{QM=tBnPtVobAx*j)ow5~0OqmM4Yo0Mhz2w1CWa~7 z^)*e9vNir1k_4=J^X4QIwd+@oShEj61H-tlpG`;Y`u~`VxJiH?7{;xdg>(bbxKG4X z0KUq{H8%y!d*Ijj6@_$yk3%_LKzVAk|2Z9Hiu*oj}d$oRA)!`H3j3pJAC9f}&t9SxqtdEXlN6 zkdx_Mf_t&2y+A-I0n;lg*FP^?X~xwQO>^QzGY4Z?G(8K@Mff}D zAsG97!2&gxg=cahIDIGprzK(!%KZlP!L^BIo|pm3Rzz=eD0~3{9)_N|ow4@;urm=G z5SV3N+Kwyd_N9E%CT}>di=91tB>*fkUMuj*b~|I}!I+lcm$Dij&1PZUjW6#MrCF5d z1>SkM3IyithuFMd`Fru)Lj2xrF^*i1OK0|*$46;Pz`K227|rj9m(=NV${x2!o5y24 z5I3=RUx2IHS1%*wh2|}`icuRN#P=*((>9vxLeMa8BiBVeDdJHS>o20+h_Z4kk?X{s2%XSS?DzTJdUwbu!KD? zI@A{MGl1d(4!3x_7O=uBd<+aOzwME9L<41x#r(!TTYd}5g)p5eS*Ya}daiw%s=JV> z6z*yumN_`&(%JgNxma!PQ7HKd0G#jJ{t-nVR94t`;WVejHYtyC3l-W(NDWA2^ z5+pTW#@TIRb~^x*?8+?CNiMt1lHHVlB0C4m&h7`6?xf+iHN0R`j^9&Dw+>0oj8Q1v zcfX?cP9jTR0VdhKZ;|U-WOJ%yH{b_kS7>3`*^Og%Ti&$UO|V!m*ykK1HBZIaZDDqw z0VdhawMb{!r#Vlu>-{6LJK4grvm4F+a!FHUN+#UIFl`vK1?E zlS?V!lL247n3VoT6`DT%rX$u=t+t`m>4VEIwKTV>zQFzMR2YXN>DpN~YA2%5YFe?? zJo+szN&D{NQ#FlT9_OSjF@OQ$M*s z8o{kp9XpuA!9Sx&+fk%@0AEuTndhIfC0K=dT=N3a&jHTry`F$HciuLb3UKhcKP+i8 z0UNP^0wtJQJvds|z-HA3@Cz;cFc#JfTVN(uPcQvQS&7!SwU|t~Qp7>LiRsl39s#L1 zmPdgO1~bkpSC|%$f`wQ9d;m8OqI451fqw0kA<6CH40PXBkkN8!9;@<=KpS*{AvC`Z3UD zzaZ)&q$vLyFWdR@AznVlOIbIIISHj;IYknw%#kQ3hYWn;2CviQHve^-ZE-dN_bJeg z@uBV4onj*??)T%!Xx+^gPH`8YTyY}JqvC-1`^v8bIbT2kg4qB2)J(jpygqrzZTI=L3RU_`oN{|#M=7?xRbyy$iyZm8?o0{Pv7K#XS1_3?kvDd9Pk(dn<(aK z7I?JbF2-ZbqV{_G?J;H*-mX1`uxpW?x8ELPe!v@Vzdgq6i_CfZZHbu&YRz?-+*}TI zRlqs90=}VZQ(=~vYl$+_P??&?i6TE1mBfwb|WDd#t~F zR9H3at(t_+iaI{>rncuuxv8>vlpt>X(G2|ML<=v#mMb$Z1F_e|&y%RB zIZ#{f-+Aj`&kknnfMrt@SkK0p3#Z~OUBJkr`MTG?3wbZ0+$V^=r)JNZ_43m-o7Sv@ zepEXT>U)nUU9(?)|9qbAPPdKn^Y=wOlGxV_%$>d_ogs<=N?tvau9=_jg4J-dzQm2H z*QW-U&T+B1M6TW*#G8SE8Y#RCD8LnNHoIJASI{LIRN!)FY@r7*SkniO9b9u%J;G{r zF<~0!Qad*ywK{POhz}@WOx>7(fUw)9XI$C=1YR7z-{aB^gw}vNSU|Q%^pdw+00sEpAZ@6@YE7e6UQdAbP1CVzo{= z;Yv*uLG-rf`qb!wRBd7bG*czPncJ$*cwAc`WiOTb6f^D)If#v!-& zAX_I&q(cJkusbH8td{vGNT&>r7WU6?gjZZR;|ifN>D(0!ibe0zOZ1zh)wQ`tv*lys^%2`m~N`@z5Jbc71a8e(cfNE}9vS2O@{r4&FKkITO*E)%*SQ>=3J4Kt}V(yWQ=F2A|x)V0i-{g--mohH}r z%H-=~dfL*)+5spy?5iE=AVJDin^V)1r3NTf)Cnq3G8AYcAa%hh5sXm;m zHGEo-DwO)^0Xz`9W_8A2N3zDwG#uAeMV$rI5%pT-s}4Hb5V+oricgX0{TQbw1-`BklszOS=1oLX!h6MSc-OaRqFZJUFg74lXubBJvYOm$-CN zahJMu61vQ#%XjH6H%Nl-nJ_hN%E5W(3`HTX6hsAV87iIXDs%is6V)-@!41BEiqgmU zEb28V>XbabZ3~K%LSwu(48vr-4ztnSCGqt914RJWgURmoQi#JR)qNaP+Kmzu;RAPs zPeKkZ%}ohR=6iF9gS5AV7%1hf;E*iit`cyh`Q6S!0m?$%VNO5+Q#DQ>3a0OrjA{Gc zrO1HYZ3!^5d*Xx)-D^X9zmF2PwaFsgFM`3f7!-r8LBb!jY0jp+x7z@Y&IY0-xrY;_ zBIFUvXB0i^vO?vOOxctJ*|xI)at8LPXJJw8VLXjm2Ux%5Rw3+AOV073%#uY|0;}yYZa1%Tjj)8M_xd! zuDl>0xKSg(epq65jQ^AVr1W#|PkOb_%E6%~HJJ*+;$h#f>qja;S6(zI6;GnXY_TY_ zB#8xxvIhVN5XVPZa|uV%yOEL(PNZ|}_Hd3}Lv`#Lh5lS)KNhnPP5eNtR(;cWoK5(1 zs8{vpnycU2!lR+R>PSy|Efa7zmNKT5kKwpQP-_nY5z0s5MG3fr2A*b&jV%%0t=rR= zMO8yP=hhW_w+-u@I zGLQbT%j7(oggc26yR5B8891_9z5DJ`YH~Ix3+mg{;6#jv57`CII!U^n-qqVL=38rp zbP{f-H}KT!WM#VwRK|xpSI;|{fvcxJX4phD)u@u?A65^gLp4xct+fDEaiPR@L-)>TzTvDj}D1*MVQ%ZyqoJ`+tO3XE7pb=A@Z#PYS zyXi5G_w5dh`xkU~;63_6%=D>P1Kx=g4M_%Og%|`JoKUK0gtHSG5`Z~wP@C)gzIp2R zmBv!CUetUxXXizgX-?WZn9~BEwa6st6fN|z&ODFkS-QzVBuOTKlj-7I0_L*VgM(bO zWn&TAo7yV(B_RMVsCQN2fF@kkO6Nf_mu0@=!XJ&Zl;MK$D}0Zj>VlVw_7S+VRqfCY zuz$prK#^8E$94@J+qFVgx{6bO)-z@AQTA~up$>^~L+RKi-A-5P4ZfmOw;k@;ckUWI zOjkg~IWlk&kFutb?Y64#=u;+LM0%BObd92;6E5O0L7dBzJ!o^1v>VpwVS2H$AkIZR zZWk9Z^fHyT(7n`@{LHtP0$s$DeAv2(p<@{~sZ#<@f;OdDo%+|2YzU_XE+Sn`?;@UI zyo-1yVzeGd!DVB*v*08|(b+Iz9h{D&I)dj|I>b9ysGwfNDLjw(qS$EDobOpfY^(g9 zqJl19iWuiYp~ZT24&X%&61#+3#U+G88Fx65Lc-gNolN9J&*ReAx4JCgiDvobSzg!` z;75J0E3H35XXL8T_qy7VK>s3%YeEvxh1-+_Vy^W}=I+Ymbu2oSGUl1V+&Krah z-Ap>KS#BnBx+$m-9prBgAhbAd3ByQnYZwNHbTys$=_B3l;=vPLPG8~lk?wS1#L`Ei z@99dw)ORDSKG8k;h8*wJH}G z!Nf{Z=nXXT>V_?= zu@{pXgH2)r32z{95|Ec_aHenO(S-*e)7-~6=_XwW2hDaMRDrc}zE zx#D^c!qugkf4lk+w2`~|!eq%e=}CCGcTc1sob}`#3(eKR_m27Y@Nn@8B6K61x*B0~ zQ^xmkHnLx`QnT0P(I@687%zhbEYEvC!3_I^X3<|7Z7x+L3p2pi4y%hZ5CgpdjFl|g zX8|8%U!kN1$Jzq$A#r^QMejnyCTXy2<+|Z8uLY4Snp%kiNZn}D8SYh~B4G+cXAMT$ zekeJP0-BelCLJC3O+kT=;6_=kMD-BtNI@Mr*3SJvgO2mlK;xZdJi(id6Ln$${y@Td zJir-O6zgQ)q`7m~u4YVia|_exBuw}1MU6wQ9t9TU3}=kbRAc<0c1ScUP9)NWb&s5+ zmeq-!?F>v_^KF-hL^e+FesRben59mcV__(6T^NjQluFkO7`sfZq2-nXNwLDW3AZvNPM9;R zurf5F9<3#3?W~Fmh4ijat8F=ijCF+rGJdUH6VELCx= zp-slPgQ{epSKwlc$rztqXb#>W=3^rOoe8yKxugxE-ZWhf8u zca`MJB^luakZT}?ti>5x%yD&qrE3vZX0CJDq4BG-ydDtF4&NY82$SZq_5n2@|7P2v zv_XO>wwpZAfo`@SKjj{po~)5wC!AHAy3I?-I@hb;Jg0uEslAx_uew9^WXq_b{mZU| zWnk1t9!G$hKeaa9-h%Q{=&vi4%&W?7FwiM@9y_#VLIK}DD}LVUf-MP4HA4S zDYc|UH`ubU{WMHqx@>WKkexEg4R9MvYm|Y^LNWWk3nun#h4y)~*ai@JH}~>ZLo~3V zX*W6JENMi0iz=9d7an{}>zEUeQ8Vj*Xcpet=hn97=%to>J6}sWWfNG}w9nhe8OQc{ z2L-7)PBGgJT?&A8ZKZ&E)>h~Ca{-`Y=^STj?ei|7;Alt3lUi|IBrRwsgrxn<8dl+C zThLnAy?tS_W8fJ84e~H>N{)@0f27$3`%pt8W5oQHRY<8CRoP z>=p`;F#V|rq_^OlcB0ncQKi_W6!(cm?Uk=bIcROTxNsNit_@u+(@=e`KIxedi zw718{ItnBH1TR9@Mka*RFG@q(>!&Noz~d& zq;GU!va8Ton&I7{ncf`=X5lrz#2h?qbkCksb8ZeEW3ak5bDRYyZC1PHTyGaB(!9{^ zDYf>Nwq{K+KW^i?sDQm)-ojSi7I;Tzp&w}%xskTqJ35PXX#OAA(d8VSO6TY-i}{gp z1vBaB6oHSk!udEW)yMgZS@W>^u(!+kIBV(SsBJEN)d_c(IrF%aS&g>AYcw}gjon$! zfm2m`gx^1Pq%~`(m{C32;CW^su2svv-L3?kBD4K& zDd>OyZmj%pex9@E39BHvP;{1XN3C+UM^ugJ5$P*9U-g_|&i-5^@s8_xhE}9{uAE(W zuImNxDAWsZii8`qeBV;0uQOlJbJ}uSu zmBJ&(HyVmp36~5xj~83DV9wKTgD@~FZx)7Ub5VC>z4OV zV^XgW**0?$<8CgB<+Zq(k(1YfrTo2tH#pu9)SDou-7F!1w;VUNKyTaptqb^0z=RdS zyGk6qzQ?oyGw){!z$W-0$U;Zl4*{X?{E<8{4B+S>(y~t@;2h&m6eJnQP{E>oYVo|c z{8_^5{@l~?D1YH+`awPIO~~Y#pse}IJU<4~mB>C8q@HATXBN~@TOi+!@C9y!Pi{|h zBXce5CAWi0sT145(x>WrtBU#7i({pK)pvt11=PT^h~*gAJ|aKHH1xh_Bky}Q4!u8o zXVmRgVv44omby8?atjA^XJX10EpF-!yhGHOH*%Bipj8SN*1CSqtKG*pDwRgCRZFY8Pn?Uj0sF?LsVf^!{=~fH zN-tHnKpi~iW>PlR!AoE(9G+el)VG{{6EPm1+`L6N<(b^L<$bRqG2i4-;fak~zAdYV z$VydI$M`Teg;Nr9q%v@MXSt19T-~=7HW7u7^u{9j9_73~S%T5B?4PV2>hLiD31>PF zLD1MNEDW82=NQ_9<72+jWL&A#i4^BN77W+@)RT18r}*wfkjJL=cmUn%$#E}3{!_d% zrJp%f@)Z%dTmw(i3w}Dfpmp#MjMb26zZuSho$1>nws9rh*@XM(6w|>uy53|v$!zb& z&rx50u9YZ8KW*~5)Z;45F&l zN+(OQi4`NyfX4eZBkQ)V_BdfX#LAIP%Kqb;mTv39X13lnMM+?e^YDqCDK9ljlFe zS#@V|IT0Rhoa=s!QQv*D@lyxb+7&a-6kKMavu-zX*^aNmK7qT)q$6?*S8HJ5L=aQE zma7C#cH7G!LGQGml6CCqRA9OGA07yTkl6va=#;&u?F>g40_EZpxRIP0IxC2CnNkr1 zex}#LB+vCI*P7TKT<<-{yVSM=)9-Yc${LRec?eT-ZOUs`b;U36uDGRiVF1w@zDU@1 z&N+_`Il9u=e0|eN{mV!;hD(ystjS9?JJ~{@+3}2#x&d0Fm&ak(T5#IPvA`xrGFJvZ zxcac(fAv1Nu578_yA2MCJzEr4&~+{=v67FIeA$ zE}=d>H-D+HSrTpl^PJxA=%9%{ApZP=l8zoeX8^XlJn{YzN=0|;VZk6@^i+56EA!Nm zx{{CS8{D=0Ok`x8)*$7Ju?x?$M(V=9Y+0dzUJ28Slk#c;LXXuiH@_}%_ShP#)_ScN zW#3flQ2lQ~A31N72WRlkU#e_zVD$3eGr#{!u`-X z!z|H9j%sv&X z4G^^JoIp5<;AaAI!wCXA6~Ho~Nw^6DyPecK*rXrN2e5KELEt6>)JIoa;xKRfE7FE= zM*w%2ieW3wR8t%gJK|C}&IcqX3^*I$JR_CI#@MyrWL^8C1K0i-7^=3qZU5M8^wySR z#l=4k^bjw6IQQ@Pz{Nj7T>S8?mio0PIaeE0ovV$T2DAKoE;~E_{?uJu`O_Q?l$EZ2 z=*ov~zN63X7p^Ub9{X9|^R|9=mecQQGj#dY;pZ(Nv1+jE<$=4OJ?X+dsoDg6i_o)O zS}$5F*p+IXY$sLjNmY!vzG;ziS=v>QM7T}QTLbf$j=x(Cr;qPfz-4{fu7K0AcPrqy zHUye1-kXYA(mO+3+fl!lds7{RJ5<&CzJ@u+KDlg7Wk_m?8&h3t;VQIe-g(#82Qba$ z2H}gn%FP*Izp8rlvA_K{$BE?PHmfp?_o}g9)q2&p#EyjA8UmFaALEkrx4U>K6?*b% znCHsNosx5wBXyS)nC3WZgf6{ae1a&p<)i|BTrZ-JpRudeRjEvfEu7s88D2dvvH5xfL4)=$O| z@Un!o3D7^}O(L#YGRzg|&?|f`#770aF6_~#XJgZ>?85MyL=7Cuw}ej?`fV#WzP}S@ z0D|vYH`5A47NKo7VY|s*gpOV04;*7?n?(FD45J`ijFy5i9^sE&z83!z$E}V3G{gtJ z&q92p|6J;}d%e?#BJzv4E3imkf|O?R4-}M;uUxzg?_X;?(tQJ|vD+l%_AR3I9Kv^w z2lP)Jy1oZQFM9c>ym3&ZBhTe_I`H1ED3*_}%@S!LD!XJj0()hpW~(u@#8^1h+a|pU$(^ga{3vLD!v= zev`LdwTXpO!yA#fO~ors(fH0f#7=jzk4t2%9fW*q>dJmCzcgIiFAdl6>*{s=x_a^? zr4C2+b%noy|zNM z;ag27)?BdG4}1@|3;xj6Y!!qPyH^%<2iIFa#iWp22~XVn=@(*jzqhxNU4i<#HF59C zYel*|{4N0Tg|r3+2t#4>SNK4`YD2#L%D-zI*!j)H=Hx+2-=%4o4)wGhlYT)zaD#?< zp@c4AiMmS{o79z6`b_y^Doad+!luADwhw)|fasm>cU8lhOO zgk;mCO*0W7sRq9RU{V$qY^?+0!X-9@PL9FoJx)5={x^&6Z(WH~#IEf07=%9Os#(2p zX-W>H-nf9YG=V1`H(D&>I}Hx^+p8yaZVqoAUR^qtGg~2QtSF*r7yLR_Un`6)voXR0?2(Vo+NR+Pmii(rYrsYb(P!0w#u(h zuh#8sYqF-c*M_^#)_L6s@7!&C!zC9txP4K4mj_IStpFSq=oi~f`e5~_w(MFsn%LR7Fyf(Sx15Y`;Ed>&0 zhv8a#_DXo{f}=!qz0t=lV?5sJJEzN(J^xf|6j@E}G!XAaiECB*sGG(*eHXtvyn|C& z3w?6uQuF#v>(;8Fz&6j7_*m6KU2HM1oHBG@&Jljy68L|Y_Z=4@+5Wf+Fjgm<(G@`+IF>(CLx8~fq_hCJPxBO-f)$OCdHK8B%WMkClxHc z$F6%Uo445~WXg-~<2ybCGVi)-59aZSD~hGdjpA;;!CuWv51sAnb24j{G?V_dbFTA6bkD_M2YX+K*&zH)FjK(= z_Lwf>{>nS&c&^^L^Ua~O=$`8^r{45W;NLpr-kbjK^3p^9nljw=__%kq-4XI#zkh+s z)vG$N&E5OD8Sm>>_r7k8ShGvNN_y6+vc;>0Ppyu0O(~mH0gCRdE`OlfS^R7;wPRhC z8{pOvSxNm{D8GZ@w3@@jR{78auJ27uQVzDt>+ln};2e0|=-bfE2sDZ_@b)7KdDmMR zSId$yO?(PxaX0lK%elHg!QOhn9d_W9$Jp3s?_A`Tenui|Cp|7Zjcdhv%kEPe=ppo$ z+r*5--m>+$)mx4tcfTnTsO6gQw`s`~$9Y)i*xg(Ng~B{KczaMObo8cNTyK7FJ?qVt zTo=h@Y>rD#k^24hu9j(-W$&-|RnXNJ6LdU0>5UUk>e;@ygZGH})?5isc;ddfs2d(O zO|9Tw&RgCm<|y!rdkZk^5}K-yJEG9nt8Vog`o*nThQCKNck8^4?g$^hT8M~ zz%<&8BJK~i0?%NK^9;tSXE3fE=!}mmMUvr6v^6Mg>znAjf=S#*t8TH>i_0W%i8a@F z?>fBT)<`o=gu_)*(QMP*@{jj;!yYg9kNQ=inQnxXJ4c=P)li$og`wbd46mOKTiR{D#7^{836q_g)L~}hEZ?qE%ZZR#0y1bGB`H;unS#sj;Ui8 zx&tIkk3%dOAaW$dWkqUuIRBM!sDTRGb}d?EU`oMoTIQB@mizUY6?zkiE>)}yHbquh zUgK3PtT6{BOKdKz_S*~BILm6S(zh!I>l~#lLt{N9$uXClAF4JO*N~-eYI!!qC@A#d z%Bp;fLdBRx@JI~h0gHC^!`)a!i)3SLAa1fYO4jEmMkQBHjxl7w8&R8`b-?f?AQ*eqx9rkdqP+y1QW-I=o_S!vsDxF!@eXC~Df@UgWIuGhIp0 z$k~FtA&nz$yCwo}`fq_v%#xn)N$XKW#;6pHb60_f+SW7np1t^_AGW# z-_V@u=RKzW_7xt}0B=MMjO$Vo@2f@>Osj+uH8?b)hWHMHbqi-i?dOcBVa|y1=MB-+ zwEqvM5j7%i4FV5ura_BQM9hhXM$~9$MD4Fe)R=alGd89p$*?W~#zb)1vd23kY66WY z-RLK^;WC*NRwV1&T{MF>KAA=o))>4|G}R5AFs|Z++S3!3#dJHufhmp)_yP`h>(B7D zM(E7YN;oL65@u-xxjEPk&$IDjXM5s{V_esotK$cZEW1D+tRS$QC`F+1gH`MQD1AFv z|3~S|t{S_ftsXR+pY^hxOWihmSa3>T#t{w+{{AvMEV%p2&=WY)1Rk~y3mtq1j)#S$ zqIdc=ThTjsQq8lyb67|!`EXcBDtfPUcXhQXfk4s6>YwoLG2h{^pz2;M6h8*&iubN# zKuDdW5k3wksTu@y4+BstjkHdoArR?&@tH!9aA`TOpPT9@u|}~&ATzY+n2U@ zVrcPhwq5C&;Y?%behw{IKX&t!WMh`w19WgqORZ)d{Ab4;I4Hj3VQpGz0dr%7V2RwX zFZ*`N{!yw9`+Q&H{D6Yp*d4CCE|BV!54d6t*$;(_{7?von{bw4F=qz2L@W)L-aIyP zyEdaJ&bvlsz_<1TC60GnpElPm;lQ_cB9$fJPYBgvE7&bcPx-^MQZTIbiVOL~dx8RTH^R&)*x0k{}AK!?+~Aqa|u4tGxG5kWeM zIWo&XJu3FAH^MViKXOyBsB?6<(nP0PQ8vpPKel1JHySKmXe-?84U@+M-EWvYK|(4v z+9)T=G7f9@Bu5V7rXS1OfRQ0^P6_>JX^GB%)(Mc)EYI|y)et&E(sC!ZpXWF$@VU?C zyR~+L&DOgyw9c`q?5s%Es&B$3(~G`r(NKW%Ss>d?S)dET0-{(K#@nU2u)Ev25!qiY z+FtFviyaAwoFwhiu4o15nglypYrKg#Jzkx)agwXOdbUzOufdarSK20^R|LEEt|O~_ zVZ-(SF4|n%-f>UdoQcxa0FHJ{iyt(S%Dtejv%0z@3N!EUgz8B^D(8oH^0M%m+hI=~L6 zqVln75{`kC;l4H=++aT<$Lhge3GRCPY(gmw^=YZ~_fu8Q&pHH3v?Ltvun*A=6R5N)=HN*SYta?^8lZi8xl{KekaLYOMBt9jo zY9_fr?bS?yPoAY_0{!I_ho4GyEnAJuS_vW!JE_^&HfciEQ8lC6#`7BiQqMI`Hm~|l z{WQ>?zK83e4P8%Zq&=mv>&s1CUv3&J7%?Z@W^dF5eaPl67bu??Q50FrP^3^mzA%36 zs5P3gZLm;6zD>i~rIzs9wvn55sy!`|bgFiqrbs!_MT*%c*c96bO%)t>@C}X)xnmGS zL++H_koR)ErnB!gU4mZI)mum1v=?^wc2tjKTi-hjlC?l3B?|!M&RrrxT zxKx`B!D%gP1*tCdS}WG9*_*5tF;HO&7!aBXVW$gbtz7l9k-3hCHIu*G4HEXjYRNvB z2^$ROFM^eK6VAd>;&YT2>znI-KiO$-bt&iZzt%Z4NuziqJmjK6UF? zW_-6x_KiJ!QMGa#x`~8F{-{Xf@VrVBzw*=6FZbvj`|;6RcgH?Dhmvh!^RWP0sV!}d zNe4<;1r&MfxJO}#b4t(7MAis+2t1&T2RvChy@W9cA`pLPmNLY;LI^^#yFm~(Pv@wP>7jEdBoDC0Jr$buh03Xzm3@hHU|i!g>R&HmMbd9n3vx@@cVIDHV*_r?{_6y$1K#lbsn( z=%hc>sZZJ05gLg4Ey-Eo_;_$QKF*GFwZ`lm4w!S1bua_x=bM~i!AwhahHZYl|6GRa zGA}i3^oTXH6hY4`h#0JJv|9(q764Zzi1{a5j$q;on?4*+2&e|Yqh)#z9@R!VL9`p@xmcwh1Z5uf0(#(G}*YEdZ>zp?bJi~ zaaqEs{4kN_5(|VpV?HZ@jjE^Z*ek%b67MCO9ltJ-K09`OB37MQ=6YxX&fEw+%pHE& zkjT^(^6*el*n;Ax8jlP%vmb@IgyhWMM#FZgR`Di@bu)%XOALn%s`z7Mvo}6R>rP-` zW>LRF8_pGCYAlYY%@aQC-1ZaBsG;#C3}JpU%PB-Ui(Bn99sR$H!)Z&- zkU4oJDCngGcD4=_F0)gI@u#yOFjBrErp)%{J~ykES%2N=5 z0WX@7R}Z?){?=o@U4+Ao__0~d=uXL!L*HFNf>;jj>U@`RNzh4y4XoC13)#08D``u*%({m)2d)I%i6BNT4nW_X8WO#}G3u&FV} z=fS?~UUq-~3tC^m-f6Lk_;=GB^~nOW5$XDpn$b|!{iaL61Tt&bD5V5aPDhB=tOaYhkGjlXmxWAh(E`_Hig zJ1Z6JYeRK=Gox|bLA92AOt8Jp83IkSkRAO0?_&jUFO%kC;#h%B+x=(DgHyz=)^x*z zSWn)g?fAwI2_t^fk=grm+N15I1d9!s2D@%>XskDEm`4JpGryWqmay`(Q zaf&^|4#E;QQ;kyf-wtAoTJE!ar)Mtee$wLO^x z+Tcd#3~kKvrG1tupgHpZQ_j%@&`(9rRfBzDeydrCUxRKE;m>qkwQ@z*@`}Sy8%dnJbBeu>)#ZSp{l#?y~YOh(t?@=FMGM zUOIba)r#_pg}et3i2L*-8X*aLwlG6)Var z=9jHlS~#YQ@~rL(1lt&RtrzVr~qbyKEWS z)ZD7_$_h`hbkW>pWh*Kx%3`z_va+md)iMvRT)M1sWqDQQiWpS6x@<+5ZAE2O`GQ?? z0GTQXz-PI#bVXTN#mYsMRUTGaSy8p3a>=r}6=h3e`lU}Gsd0rAlo(-v%t*Dr5Ney66tm<4|u`g?-Y;9@TG74e#vMQ!WwV?HZ zfd%EPC2C<*#B2~`hlhG7T?3J+6LOmopzia`()r0yZ^@_4J364;P zidE6HRlbz$5mzc)-?g95 zUQ@Y(^@b*;O+X{#cO;)Zg2K?22O5&KrR>;XanbI|*oLYqD@7Z?mRP-_d|B!L$KHDY zMpdP63Fz*+VnA0{g#q1lEtz0jg-pP8-Cdo4tBXP?N=t4EAw?z>u@1$q z0lP>5K@bUGSAuP=p;=IaV!;xzx9@r0d+(IY1Z8)B<@^4B%A9jgukU%!+m0PkYK^ei z2!tXmF3rf2vDl)qt)kgcVm4Iy!Q#6@K+65is8B^B6k+^hI188rf6$@bfm z3O`ytW<0heAYEl#_2ng#Mp$D?MvcZ=E+KS6{i6}k4|6x7>>|!SaT~&D2ec%$Nqecw zWyAyp7bt>-#?^wFN0pRJEMWr?3qG(BIg2h%|302RBL~W%#W|&g!$vP%SF~*Tua_(> zyXBw@h97a{Wd1$qIIki1c`UG^p071qiw2CuH)vV%g~yUtYJzffB!w5L7uQAP3^Tm& z_&=l>UXRaggJT#6clR1TS>Z7)70bjR9Tc%qEEKo0 z+PKh@SfHCpZZ+DF;?8PQv&ck?IR|x^xJ45i{XI-(u1=i}X`(IB@|fiR5m?bde4!=`z}2MHLs>Tx$mGS#-wEo=lJ2>@odIk*!Y~nmvMDIj||}V^>B5*Um=h zVY4WU*ITxb=4~h(44gsTN0~0t(f4V83$Ax_`d7;aL9oxavsL~A9TeD=lr^ITnB!` zgB!#m99Tx$ZTQ{uogxYM24a_h5dQ~I;DjrL;xvSiXc`X|#X4~iCL@}Fed9=&z?2uyq*{}2T<*mxIjIwq zu&n5-(HSvExfy43j}x`!3dQ{o8?Yt8)*xz1T{(6SZII z2;KA526v`^?P|k}Hkcq%9gpHOW^b-GdT~p-?C>)86PFz%;T6KU>^NV}WykrlFFVdh z++_zL36~vwx4Y~lhv=mu?y`dvahDx@C0%w9mg2I5&^=ss5X(-vSC7QY4kDe)4vThf zK=y)*UUpJo{aBuHSU;#zJ89Mogyd)U|KG~ zgkUU3W7HxXwO!R@XH;^V5vRK7c`O z#-J8hGS-s)TV<3bzlg{fOL`P@Qds0!A;oEYAmnEkc4aH2~5*kxX)oiFdUesUQIH6PImx%PkwB_YrDwWoGSkltTFBQ6( z%Gtt?ao_d`o>1-MxkV<0Cs$7T`$WkJ$;5^d$q7nnNIL7RGyCkg>|xRDn`&`|ku}V| z#m+tp*~7RJ$Fg6;MT2!TF(h3ZWO7J)gyf=P>26vBq@oxX&wGC}DKCFW$R?nKsY^xOf@tEl33xONIl4#ujE0g*$SxE$@cMtO!yekBq=jZCZH zK8J>^fNKLYH(}7^JYIuAnt(~cot*ReAr{B!A+A;%3g#6Pz~na(Y_R+lfQ5i12Q+cp z9atQLF^nu|AjtfElMJ!s55*F+WHUnVcA7oB0bs$x4nvn7fM+A(Ry%PIV)|AX*c1EA4j&VdM&y5m1ullC1!?bb3Oq9+eoL;ci%gzB zX-o-<31d8i+ypFfbV!ys35!Cy7a6($Q;73{Lohy!TJ5x}5ehKJ1P$=Mg-sHQ$Zst` z+z24AC8Hv;zlF((V3I67PM(K5BqG1Jh}u9g$yJf&u;oU|~e| zbBdD-BR{usB@yZJQ%%&7LmOVM<|bRDZKyySa9+3YWXMJ%0qOj@(?Z;7y&B~FuzAqr zd(j7Ed|op?tr-dWE3Io4wiGL9iU0^mFP&2^pO)C_0lc+BTnzAx43$W)u-NUjd#uAg zZ@)pLT(s~739Fx^s5ixo98j?{c|dQd=74@`4`_1qERCM-<#<12kN1D+ z80$=;)tjesjPKBTD{}IBpPeuD9>58#lyW~;4asd-O@6MXQa@K#iJwzA+0V5$$ZemMwekzWqRiR0&qGt4iC0DzZ`8z&@X=gI^rif zGRV)9?liv~4@ApPbPGpiz>-t^JQYv&%Rp>YKT()Qn(5(p}|VH&%nJ8?z3>0!~G{*BA3wJu)@8E{v{s4Cx+#lgy4EJJ>B|p~s zWg6Tc;D+IT54RrfcW|e}{TA*FxZl8?3HNKbv*3OO_Y$~Y!krEG3%HkpOJYcKl^;89 zRXTV2(>WpYme25q`>iDMF`}QSB1l=APLT3M6+z0zbTd+67@)CbD7~!&REz%tdRvro z)ghs)f0U->N_Hes@!C^i-9i&-WJ%e6lE&8G5o?GeA=*X$Eb3Yu!^zk;r8E92kI|2(K%fjHAQRBO^()iSA#^2_OqQ>vY)`!)-Gzi@jVy8b za=6Npg5flSY(6wy*}4fWV^bWOPRhbvDhMJku(|LoDUMqY>Xb{ULQItM;js3R4Gdw{ z9#6tzVGaq4rJ>8125qADp1vgF6vE;;@hk%DPUT;^lo1d~N=8f=Ig#QSh;K)6LP!z? z31Kz`38g!f9|XCCtPvNnCG8p7n7<_Y4Z`9E8`bM1+e~aQ$k97xV#AwAE<|^2!V;L? zE_)k^qU`M$`39jJ8|50XM3>bKzdJ=poXGW7;ROyY8Wfinua^!B{Ct2nBX>>tWc?+6LJ;KWE3$FcK?y6D7 z>E~<$k06Y4mwovHA({K2K{KVUdc+m=3k z5qpQX5pl0h4G@c&65et4SaV<5-wci!xo`}kUk1HmzhD`XTwQ184)BWd&UU6X70Uev z2_0`#Tf^$V_yXmIPOdcjoHZSp0=OUuVe*aD!E5HsN66h>%_f;K*~CdIVR@u;uzaEX zIH6HK=@yVh6D`>U^e8ehAioSc-VhL=NipVRDCQ-f++}ljikNqy^c(kSlUK_*eD#&! zxTVXRwao}7zb@V7UkmxyGx1G6bH{P*^7)aJ`M}C+MqY680?Gvj^EMR6uSCs@J>ew< z{Ywk;3X$bdpoXzlc8wtG^R=9@xF$J8pN^s%wP>@EC8DT%JJN1noULL@iD^*y2q-j%{t^h|Z|V%+iY-JSC>nLDa$un^u!O&@w? z{2chInxvO$^Oi3RoO?M^RJ9@eVe<%h&%p8xlBV{{K&`tF;yCQc{!v=QY0bIDA=sU| ztglDGjc5X)BCG-DVDZ>7VYjW<%BN;f?yN8YD$YcmmBAvf=aHq;oP-q(Ncbqi zE7*lhcA;EL?bI~(HYd#lTxzt`?ry~sG|4_3iU|ZkjKEEgzTh}`XLsWD?8|a)li8iP z#n+Z|T_4h5j|sfDcZz74Z-h`Sy1 zu)83u;*tB&0>Pap!r|JG);bzrtLwrW0b*NaV@*I-8$r0idaqAf#3W+;8CGrvu1?tR z9y!JAey%g6vpuFg{C2OFqkkh?Kas3f6uHAgK=kTV&PVcq6A+n903g@L!>0=0HUMur z zYLxxkmQ9`^Sz##)NLHY~*?-1pbEx^dQ~y+ym(Oe$n#;{ohtcP2@XcBMp|_LVT^$5V z!<#8*1@Uz_m-|*v10!mKgY|=FDz1m{p8~J}S`Rj^tgZ>e|Fp`)%&G-+_TuUlK(;IE zni(P7AQ#tQgJy;icK~Rp|A5YH=N6LxjxlAKq< zH3+|4UdH46QXml01v9Bba8r%xR}T&vb?q5ni1ww+LsL73_3qAbf&A0J0J7u? za&uf#(~OWAwQThl-d6Z8oyrD%?ll8Lr4y6?ScSF1STk@2a{O406TyR{oeMc!0}2LV zUvzt=t3+AC8i?*EoOiM2FsJe`>qOC*qoGb$7YaHTJIa$Tc40 zcn_NTwO$oxrL$+dt7AR8G`)538ShAy8F(8Q!v~+U)I4^lTsalvB(k`x z$rEAgBt2NyKsL1pt==cI{Ju3xGfc za9FdUFMYTl8|=A!*PcrVFk&9x(G~k?ZAcyga@t~Xvfi%^Jh4n(!c=a=R2E_?%Q!a| zV>~=E&7R2@YRy!#b4c(xK<;ESyu>U61y;x3kYmgy47Q<14c9V3NZepVM>I>8)dIYW zd=DB(mekjB*WD}J%ijQ*1rrM)S@J9nn0ARC&_r!+qNRv_KMm*^r!?C+~$I9%eo$S3>O5-o%4K5FeC5LCM8&z$gG3$px;CK*E|gDD{`RKg8@f z@~QgDxIJcUAL%Zc=yV%@a`C=4BHdfWUU2rLJJ7%d3LY>Ak>)l}lWZ~ws%GKdat)6B zCM<%_y$rc*YGA-Mf9D`HW}|K#wYtaeiSF?qY6A}!NbrKCuo?c?=sY6q>aJv-jc#_FHRJEa7aS#9hn#B!~`ny#|!Yi zZvQ%a4*u)Oy)HbX*NQWG8R=-kp9iox@8fE|x6N@WWR7;!zb*6jQ(87D#o&?%dnrZR z{=3O`2~AC^T*;J>7)g+jcjmGkfeuqzQ9|JykU&5mN+8QQl#)2XB`yF^)l_EQQL#W! z3NlhVs$jdO=&Fg6fO3ijfh8)p)c4fuuNEp;M?Uu#_l9g-C~1h)nUcLQvCOS|MWE(+ZJ|v_izh(+XLb zLn~xy4z1AfLX!u+g!yo~5gQ~&lLzVI>4zvbK|&4R?dXNcAr9r%5r{*45JHb|C8 zu3z@>I+Z1nevxOdsFQVfJD_5M&gW7wktj;V1aZ?5LPKbjipdgPDkl6c6%&aQ zshCRmb*Pwjew%cOgz=X#dYw6I+$YjhtCzzp-f_!#k6+m?WLPWt zoWnvzudg3`^@4(WoQt!(ps2J%i{pqdlFN%rb8UEu*Q*siDv&5qpM8VcT}x7cHUjE4 zUL4RL;DXX|fhesF7@b#kh>eXqlt0jwD6LqB%BD*qc%zs>9X*#^6+d`r z{y!l!1LYm?`60%%e^7b;0T~riKYrm4vUDA}O;dyAoA7muG__xpuj2CWk!@2!c4*{) zl5ULQyXL3X@2MQUx$Q>}QY`kZ5!Z^i>A`)V#4O%~{@g(-S&D)E8H4v9TFr4|-lhW# znxoRLIp$4vh)c1LAM@C?;Jq|lka8*5Pzb5jpb9wzq%fp@{K6j_`cIvqpViUOf8KuR zK@iw8=s1r<|CP}Wa&$2CBcelp+5ZDWKg-iv57t8ef+bj8hR@7}BgUbCNj?a5fEX0J zxW?`FI4{=vMM~}Tfe4OF8`D6!1O-FcBZwT&vHcw=Dvh8-#p#AQ@mG@S61PnrPXh@c z#)e{zFJ@rY@LJtv%!_Mp{BHWF&X& zU(C42QvWwalF%KnVZ+e)!wekMVQVK#vBfR4bkX;=G$-OY|TXhkYzEPA}g>#IfsQ@}Nu zX!J|y8AR$pG?+PQ=CPG%%eg#&53-h-Ic9GYWO8%BTJs=$oQ${v?mGxXxje?GS~7?W zqqv`*2f$3R`qRO-j9?Ew3Cg%v=6OJS>WlwhK(Cl+l@FplBo=K*YX;-sB+_EuP2*^O z0ij_O3QnD-^FTZ)A{O{|{bf?K^lUQ^L*6T(e`!hqOMcSRV6Ri-P)v3wWG}A?3z*~H8Ks-Ob=NwznhAbpdPg%gXr{L`6DZ}#^jhz{C5YbY zA;Nzr7}rQ@uu%(Zg2SY$`70BWu1o=1I6_xwimjTWQB#XOp<4eD4C5RPV-a_e8xA1j@tuD}#w;`E zpgkLFqX#m=cVU1{X{#p0jsp)41R$HU8SzmjEfzWm$6X|%^?dS=;JDMMW)2XiHL>zG zt!V+uTc1$V*ILs%;3@sgnr@H~3Z1SsedpHneq2pIL~B}}P}2+?L#Ax~`86%@hRO=^ z3kp%)4+l^-=p6_baO61YtImrTqN$h2m~|+fGR`UcfjG>(-vMkJJDAh^>XR6lpbE^xLzvd$B_+r-`e_-KRnh-b+k zl$c&l<+s?mhc1&#lQ10i`O-2IbsW>m4f&PPr-ykYlFsiC+w#a!W`j8m1>yV+At?|5 z`#ypoa;Y?AfWma+H(e7eOgyvNT~p&CF*$nbI3_S4o8->bVscgiMpgd)P6?U=OZps7 z*4S3qzCb_j7PD>mabw4z-dixk?f|TYfK`J^+Rry4a}f#sJl-{9s4Iliz_cWjz8JFW z3z6hou%nanHyM$uyca>EnU_;#4ztm~^5z)n?^y-Hr86Ke=o41AwCLC=S6B z)W!|k;SiK6S^H(-#%bEH`c5LS+a@77Q32~s4x+ytjlW&T z@_KtL17IA+4<%PxI}FmnWKKtcvmodqIRQ>WB;^dXjgddqostJVnLJ1Xl zWIg6=9BxW7AZa@927vL(OWrmN=eHGDsvdbj0DnPFOX|o{yCa9D=t#;f1C-1oO^|*- zX>B#2g%MK3#^o_1G7K@@wKyyy7mjqe1tI^_=4-*$dA!0HKqN5LS(R{bC43~2((J9I zh$FU=T9ZMc+?^ijhoLm(>#1!v|2Y95xcP{=b=RG2i}0ny7G1m)7rEq9DWPuHk`0>> zB=N8%VFz%nJmhH~mW)@rtwY1KSIE}>+}5ZD`}j>f(VZCO%Kyyvx+E1go1{WqjM@>0 z+!oLKXqM*)0w!{$-ENMc$v11fw`p z)RReZBDcTTHA~+%q>Eka2#1|(9Yt*3O(RI2Q)lwNTfo(d?U|C&>W(zhC6OK6IO)r! z5?`4qv896b$sVGP_DkF5wzJ2%+y2{nOqldP++)fYEPU1Jac4?c&Ls}e?u;am{U1M5 zZ8`y#lfwL1a}w55C#XaXNu^jssIj>=C45W0QDOHvmeU7=dKa z`DWm_6TCj6=T8vUIFfXLQ@24?DocI<^DJ{7#uHG87!7WyChr3A8;rZTi3m*um5q!P z4$dzuM@=uKk-|Q!jyQqt=uCO0R_9|o1Y#14&^?-BK#gA!4zYVDzUg#t1_BJ3k&Y8I zQ@*VV&hTc-CQt>u@-9SK@o^J~173*H1>wIQm{O)Jt|ctJ!4t#8GND+#T%n1=y`*hkS{phI1Ae{Us)0l1V#tHh@iOE)@N9hY zO%-b4r9yV$k~0)#dr=Gm^)#{=Ghiekf?J8M1+VWj z4DK!IZTNhhHITZ7+U~BiHy@{;6pHrKuQWOi^($#1+#%CtR5L!Ngwc>jbShI`Mh8t= z_9LPm-H*=Fn3>Q+8w=0if%OoUq+1y~&W+8E<31vMSDja;g zC$*;Bqgl8*aOj^xj%X3Q`==_RF+~yMknI(4nxC#iM;BB1A97!c&!@|kX1LCv$!1-& zpX_iJ?Uh2v`Xx_LtX5DO(q+3DDMYS&${`JwDa#EUe;M)y&h{)hlLBJABinnDw&QL~ zZ$X6aMu=HAQ+OG|f<9SO!#T$)0azqWqr-`L!U&yJSX6|HXJ_c8cx^e5giKikWfDwG zjeUi{xtl5Xc)(trj@E2M;hD0|pjOQM4ElFeg2A0GZ$n1a3k4qnln=1n>E|T{fLRGT z@vXqt1``uW+L0%ZGWO>%b;jO4W2ZAr%eLof%un$9^5t7yCK ztJ?wWvgK7zK$pvbgn9qqT7Ivl7)k&EOktRL8$g|Zy(Xq(lPTAO6qO+#W6CgxS3+i+ z>#_k&z9XGryanLPkbAs5KU$`ea1z1YJ5#>n63zetgZ)zM)IBjWsgI2{`dUrk39s*T zL?<06jJB8XJqDI|mbBCae>&}I18dGFJ8B5l?Uf#*M#Zk|dIE7PU28NCgxo;7+@FCR zX2|2!T)A$Ch)lCXS-4pevi+K;+(>Ss7XVlF7Lt+l{Y?-#IRXZ_*bW6>P|OG^N8+PIrPH;=5vtKsw<#OIQPJdoR;}daCIkje6bb#}?M} ze0@C*|Xk;O232ni9P9=5Lf2mfLR8J z>W@nIJj;!zBJsAG;A*e$-aRMAG*h%Tewt(JwcRvxLa#SMKs0oko3+tgo-I>(%)XOB z{|%L#-z$l7=nR{)(14_~9`lMjQd$e)-4_b)B7k?MJXWLndWgIomTA0l2SzSkZu61s z_dY=q- zXl|R+Bo~a5(tQmijR{6`;lH6B=!AOcB`9weXzy~@jS|Bc^VKN z0Ojey2|Q~ah0a(P**-ofeHa)(v)#Z}1ojHH3)~4CF~70{IURQP566eiancQ42f~*I z!3ox2$l?;#um+ksu^PL;gakW2y?X#{!=Zf_P`A$knC;|UWgbw6F0d29M3+O2jSY<; zq)9_AK?u7NQ7LI}HxAWqXQ&qXfDauP5@D%)HzkIJLG>ajRjhWF#Fp$*;6D%ObUSVpsVoJYY(?;xPzi$bfR&_3xreJx zDy-`$v>3xmf??8-YQ=6h&+|Tng!Syli7zo}lmivSNP3D;YpEoPy}CW&m?hOq$k4ut*XrajcEB*IGac zaViN~K%C}-^Bt#);DoeST5y8nRV17sSEB$;azY$&d*{oxIE#;%xsI6nLc20-tpp0g zJLXaB9zwp}E}f4eI76mmPT_3CV7zTjf#2EVVt-Jd15Y`WI&ZgNAZ+RN^NL4YFiIar zKL0WW2(`patOVZRpm_6k7n=8nN z8PmD6rwyHDADGt}Z@;rzoe6b6lhiX%l&zkjRk-RI2yLhOfsl3z8%~I;rGZaJO9LgL zSG04&_SlMFob&Jcx1#2cr zwF57Lt~jQ3fiG7%gAuVOPw-_Au-%$=8W?B-HR}dEjAZyDUwb@_s!@l)6Wzc$MlA3Q zH&9cODuI-f+(1pKqzVJUk#DuoG`XTHNEIMKPKOMsA>U^=m}e(^lObAPN|gNj?0~#g z3R4S1j_-3km_E1G5%b=j)DC_`Mc@=~x1@~aw84OuiZ8i@vmqyADl_{Z9 zs6?An+PgG=lPdrFT6{%=PMCc3!kn9Xm-WpzXR_wEhv%PNj>Jbxzv6cW52>e(i|f5% zxj0V#%8&+61S;7XKy@%2wl-^qt-WFEq*}HSmkbIO*@hnYUPjpLt)2V9u+1WbVaVYJ zBLtg~w$O1gh@VFBFlgHcApo9Bt$VnzhgRd?Z1$GVjbgc?rgfNnYS?B*E<^s#umwbk zVyJfeOqixs3L;F3tu(518h2|JMQ)`W_TgZ7adj0j|; zy~c3cjPh+ z(fRh3&NmO0$>BfLGi;0g`ka^<43aACaaob(X>wFM3eJ9%-)0|ySe~q`X&EL@!Lyn@FOn;~P3Az^J+)D~m<{#PFI@O;uVHd(>kc_QvI91f>vzEV zZhgHR7~Ua&jqI4aLw*g@yJ6$tea(Jjr3j?V-eL1r`3p7h4};HK2kL&?4*4B&!}3N$ zzByp=xet(L#0&S2RlLDZOXn@($Eu+8*5wWInJKNH6B%+7=zjEb+1=zV9)?Fe<`y2f z;H&}Ta!QAeHpgqXr*Ps8Unt_suOIUiuGS|VgBcvyt0*6|#yr^EEguY>-s_dB`EGhJ zXb!>WwN>1FAEx78vjesUX(k0Y|5Uc;0WSrHnzhmgybS~K@uYsN@xs)>Xz9@qme~^i z`HTKn(M7+py8WX6$g~&z=Vd>C(O;SAF8amd*a88sWHE$dKqS}6$D+SWu;{npHh+iY z!fl2NV~W+f=x>!`*|{rhlvlYN6SF1Jj2 z+EzTOB4?XtvQX@YFR=|S<9_%Ip4r?FyX^fiucle|9n!pysOy*paiXEX1C< z!QL~E>z-MUJ=5K6c&=U^PP2E-U^BPg%z-)39k72pM-C1fhw3gF3b|HL{INL(;NEKn zxr+{q$kFaDD!?u}lDp^>?xN%DT{IV(C`fo6_Fg{r-tdUo6TW8Sa1<%U%{%0*h>SHY zM4!{&xdl<#kS zl??{u?RB)<^cZ-0hOGAmX;)xJDWTkr=)UbYA;HV^jh$N&@;LIEFf2+d128R$@O9Zu z@V`D4f?MBLfQ|fSdO#LbHNXvmycGhWi{BxztpoBw6^IK#`OX`_*%~DT$LaFKc~SI} z*)-C&c1kM>03GmWm4Iv;vLl<3Z|l^y|8R>;SbzmtnlmfcgZx7S5vD9JHNzm9XTaVZ zz7r6Gs7a3uTi>SRNY_4wgHa@8+*8~hYur=De<6;tP-GuKdNnUzuOv|i1tUPwFGYjY z@Jfnk%P!?IkFCZ4&OZg%JIlpYIAu&q%c7JUpkCKfLt)s7J7=)gZqRaJjSrDZ4rK|I;p(OuE}c~rDvQ#f8S)ofrtRpC2Lrh?#69*nE{i&| zl`p~4xjinosu{TFN;xhovUOZuE9+of)@A6x+*^G~XOO@-MVro_Pp4106r ze%Nt>9V8XIw*}epU}NWI#H_Nw%3@SZ{@DQ0mr*NIMXl1P`%*>SuTd*fMXlDT<*A|` z(5QP;MXk}OWvQZ?G-_$8sI?lk#G>v}`;I-1xX$uo8A$W6+>V=8XL+HFgLZGG8QL;= z8NQz?Z^Tf3mBF}6AW_s^K7w9GXPFBwBK=(N%c{U!?Jh5-2TnU_Fuqq#Ayal3qbNlK zS}w#U@FFB6nckcn95@$gUr3J(m8;ZF*Bura_rqvoD>-#|%v?0*rff$)^S9l7#vxsi z^8Hc@z;u`GSmrpLz}&!&FD2jpCY)*XbCuBFP3}>nj`KW@G^5Q)iEUx>M6rdb`3bEk zs9oED=H|>chO9*aizWji5(GpKGX#DCA@&R@V8?X7Q`Mw9w2X8tkr|Qm?0j(`CeE%A zU`qxCXIVgs6o>?aqdP^B9qK>Q(Zrx;a?P41Tus3b)lA_OKxUjq*=FE=x*S^`_NQyw z%jW&xQEc>7?u>cC#PbB;c;f_!$x^mkKHNV~cj0+>$z*5J;!c8?1hk!P4+p_*WIdX) z2p0Mb*`$}yMJms+2`Vtq3WCo0RW)t$uwk6&q3vBf1#-Aw&I-#?Pz+vVXpy&vY=%)k zQ;LG{9!fpKqA+~FCF&hwSj=}Q>`Xd=iQa;G{vDiOI;5bm07>2fp0~Z4ETK01nsNZ1 zh7w~4ZSLKy0lRSV19-@y9bm-c6aIPClq0;%8YMTLxm@qt;j8Uv(zE=OSfFMwV zVJ6E;U6K%4az@M*;{&>#cyN(zou7*+d4PMLz967 znDU-t8P`I{ihefzT0lM%c+3CnOvsO|4yMPyjtn=|`F=PZpF3q)@rjw{v7L+VMObFy| zd}aqUKt<+FZ9|fey%x{A+b~9kyrIkZ78u0*M89`=iILfHZvq+RrZ96$k#atyNcj~k z!1}$UoC-K6Fn)a}Jeh<%%PV4nKUi<+p@O2f5Z$KGe{&hp=A;uN6g`J_qx31}UPb?nf`oTXxhyN&(vkDIUi0hRlnRVFr%# z4B3nJUG3$e-(rGL41u)@i@UxBs3_z*pd~Bv3J%Bp!>9mK@%WQ^bZr`U$~=4ua9rx6&f=Q4I_j zp`0BQE_Su2e4x9a-M7}E-u)o8%TBzEHBUdrmLD9hM(C{zw9MM{4g->>M9i~T9d1YJ zY~t@I{;b7Bz5%g@goS1wj4&P1@jdrnk5uF(&Prs$oy=Bt!4(kJbBw{dMIfr7mru2b zfX+Qi85|_oX21wE25U==ajXYjUkD?{xMm4N`Y`2-N!8E56D2fztf*BxiwcxF{8XC0 zD9pcg^63}}ql`aK@nwPb;WP6|C~*-U!zOns}VD7;;c51XZ?C8I$%t zTG0DI0exq#*~k1nW(Y~PR>zBRVn53D&j@xt) z)2#tSF+BPN32v(aCh~U|6w1Lt`FoJ^#D8y;g9x%-*3p7(RB$dNlkq}0;4GRRk!L> z8NZabLAw%}VKh14t@=G3#@zXo#xEfh%lPNhv2yH8a}c;4fwrJ1P4{vq#^T=446~yJ zGA)k6^yauUJ2mWLO~dlu)9)WWtd!sH>-P`Q?+^6*cBlZk+*CZ%frlV|`T`nIO91YT z@y=>@E8OBWgVP5OI37&{69S!i%V=E(@G=(zqmb%3X&|JED5UsAA;ogt8~?OH$Wno02Vm;7v`@h|FlXJC&iA#L zb2imSu{gj0gGOh7$kCGU9ne)U869|Y8=BwPsxP&u!H_NZ*HGcNQz z1$A)XLcxJ0QW$`lw1p)*#v6y^$RSM|WmvPfr@RUwPNQE>l=H(>LN#}u>}zdLfn4l1 z+?Ur^5k-B-W1OCtgs=&>=$M@pJD(}#`#4)Z)xWbiN<5#(1) zJ-ilIQ2O;1y&gLLYCII{GfF&9A?;_N5O$LtU?$kDfY^6pLqSkB0kpoWKvRyk2J%7J zV}gUV&p{|-^pqW5b^t=b0emd=;xxvm+vRwYu6FsMXqTz-g%1eN5?6xAEhHUPxIC7J zV}N80(ziW1*&POe9`>CVPTIYQ8wYv5Q%F89fgHO%D+^>;1FCDN1D?!2fy5_kDuD!c zgC?ahkd4M93{C95QmshOP%&CI))>W<^I-HQ+VqD2D&mRPnu%k=Oz70a#4@SuP~b+x z58Fks1drqt;*2MCBP;B6#?JRO&eFmdm|n%YuISMfnHj=Ye%% z=Dzzk)PZ*v5QjH`NCR10158z+`W;5YX9%F`8aQyOZLw7W<(;q!v=0%p>p-PxqrD;Q z!z%kyQwn){a`+A3!g_+8#Y?9n;e3EI+@Pz>?(Zrriug7zFoz-H9h|T6Ml*nrdzvrN z{Jf+3zZ@YI?PF-fAsR6mK}lyYE^vnIge^Fv+-~Cu zgHoq+$-r?ERCsCoOHKvUXznamG_}YU7epq(76$Kz|m3H(Lzp(g3+4mUD9*Ki`H$R7UX?ML_!$lU8-tH%kaLw%okvCoc;dXr#jOdRe@}W;zoAUYJCh(5g6i&ZtNVjihZnC= z*k&yktQ5SSq1E9=Y(m#%y|9!9nL71$x$Zp@6 z!HK)RlGxU}h%luAu(zk&m=2no@p~IvggTAeusCG#YG54es|bgHr+}dmk8-f>Ko*%V zc6bu+i$@mu-40mhW=JTgcF;6=O$u9Sx1MX<;38F*YUv;Xl2Emfst!X}X0I@kJeAED*O%>QIHag0{(MMV!uc^#N<&$C^kSg z<^$!PWV{enf!hh)v6NB3bYO)wzKyoUQ%qa8MzeP*q8O<>C_^i z&UR{$il9Dh#*W;BPJvKg+e+}h!X}|cso2od0%q0@jya%3A57!P=7JU!b9tBI4%q{Z zrDPAZWGj1M9qifTEW*_rf-7Y%d*J14u5df98PAfLGPBxd4}7cFxtY~b_JAR8f-Y~$ zjgpE#@I$u4AGi!x>b<&AUe{SE>ubu15NyCU0FS<$0KoPy0zn>77?KvCTbC2}a_+n~ zbPVH>I`__-+`@PU!L)3fL2wCR>s~eRo2;-oXYtN0c;{^-q0k$6LlxBcI&3n*slg-u zZal>Xwnl}EqkWahz3@s}#3j|YIF$OPD5btR9glQVM$IMHlUlz`^EOGMiRu_oBl+ z5Ar%5jLihjhBLQxkK}n0jgrn|mpsqD{oF|Ra7C5aqOPo0As)F$A+|sQFvh>6z!(jA z!6dgLLtZJh4;V=1WJR_X=HE7nv~?NHA9DbI2lHo$LtIyxcF-jY|Blc^68n_tps>%- zU=`2sO{c$rKag&3OdzrM48w}C?AL1clJUHtDPjGfc*6RZpaa>b|NEIrSl?}Nt6rYP z^Wtiig!v#-3G1I}#1$GbUn4%uRMLNxu-;Opw24KTB&g!M()KS@~Mq@yu2D@IsvD2peocR%r?5&Mgwq&vXgsL0JN6hrTnjF><8wlwh|^HkE*POeliHDj zQS(bD01qqTJYK2SH+oHrs9ayVArz@lvGcDpFWM_HG4{f1yL)myNq!l*D+qOJaN% z-Ghi`C+*(WGMB_SGgC>7oAC@Tx&<^0CRugO%*u2~jH}C|B*vGGJ&_pig9L~n&%axNmdVAjj;wqo8QiVki|a^2Yr)8q zyaD_{&zwzUSg7xeDEYC!O?}*fU}Ktju-xGg{%)~iq(eg<>ZDlt7trT$>4})^PR%es z&zryTwL_uArg?9Q5?Vh@w@0Ce0@p3&u#_9k+958f^tu;10RdX$k}%`jvFCh`b;20H z=rFo`ZMnALYnF7ALz1)$iqRnm-IMT5hYsNqI1bXr--dTwZ9Ndjo?&oOv@0;DlO2K3 zn#kUiPpOfYIw`SpE1v*`_*I6oXFjYX8oiR#&cx=~7_a;CxFL6CC{^i4OIeDmQzu4I zG;EsC&%}b1fC>_QOrqDNPsIqVwn}M7^wk&!j(Vb~cOtPCVm)Sy>1e@{nEJw$1Y+tA z2>T2iImRWXwmGD4TE-_dSq3hlAuod3W6IJ>o1QAmGe|w_#_N^^OzJp{BJ6ooxZB|4 z3_X%Qt|0C_2h#|)uNL!3hEnrB(ulblag|1Vnqd<(yC^A(rWbXmypUG>4^mP$so?%1 ztSj}~)V0^L8>A7G)Ute8QfCH~6ni^}PGH_IS=o z*MjB-N}48rK$ADyExbk}-q(oL8nH2>K_;|7iwZK zi0?I`-gM~4UslEwkUQK^da3)7ub+W`QR&cf|7o}QDs9-O+AuP30nO|dU#Sso8ez}b z3+Oosy0hIPHrYkY(v)9o%Dc6Q&2|wpHR2nMxJx6pI7LhYt z+wC%b(1@@`EYOHIQO57kjIX21<6XOqFE#0GO?sUs-D#Kcg+^Se5g;k*3=z(5tHd?` zXVI4LhyDtQ%dHj8=zV8b`IgQ{gO*%h$-4FwhgSW)U$PHx<8Trvn-3&MB@ztuw*Lpp^9@E1j0)ibFT4_o~ zzM%{)fJhUNA+WI^V@mFYJe$drWTqzkR!@}~(NpES=&7=}PRYnGE4!f)Z`Kf=neNue1`$$d`FZMn+$tenlw!-jrat zyrRsZC_jdl8*;KuP|oMH|53@wd7P)yNYugW1xiaM-hn$c%rPNm5zGl8coQyg8#+VO zFN#9t;0oztOq|OUWZ_1Vg%6FAg)grO4@1Ic$a{bkt`gqOD&f7hCX}~?wBQAhvQo%& zS&d5#{@k$2@Z7gU4<=Hzl?D+(0EcBh(0XM&?;bm+Bwlcy^XV12%KWW4V#=g*kYdXe zrH*!ZM!IJQN`4s}g$xOUsGjn4L5e59XP^qDAM{^GDNk(^xCacb5fDJCFD=U}EVarY zEqM(naVkbj0o$D*@}>}@?VEGeUW(D84J#pInhs;ZcwY~5=7`in#a$(*s6L9;-mbzn zud2%4?U3#ec~u2$?C@3y%+gN!zbfxaN!XaYD@2L$&H9Et)zz_nR!)Ki+lhv_p8D5`L(=V+DP8UtgggDpP57f zI0)@B*Wz>9zEF!T#rmQ?sx241psFQ~$|#?73rJ*Q1A{ho3&Wc-m8}4)8NXBW6x2FW z!l11;`}4f$!{=VJnG%SrYQV7oyrP|2EKN#gD&7M**@OjU^X!0@seCV2R4Sb9zbF#V zQbCZ=5!j`yGR60OvZ4-WC|dH0f!DCmFwozX1lci)lq^FW-Aal-CFm^eC+D)Cc=VNG z!JuQ_Xe+BGYO}h}9T>73=9M9@%11Y-F-?r<@pPq|-R^0`v+jgluXr2H0;GCUR6;ze zER7irLOz_d=LSd1x!Bf|hD7<#(35`M)+c~U5)ou9R8_V9i6YRRH#Fa^j*8l5NtM!uB(FW=0!qc(jytC~($OyPjMlBZT zg)xN0k;z!Nhb5bG9VZ52g?y532G|nNDHW+@O49)Kh7UiKY$M-?2lH!^+U-N@X6s+%s9)|%Qze`2_MwTIGhK_ z94ciz3258|gE>z^wg@h^)V+GTTtlfOF#2FcTVxS+rtu;jbeizB4m=ioZGim(@UpTa zaw*I$JOh=Sm1;#fUa9v-tUWM}REFcJ&erke#l=H8}#W7loDA5T2aJuPxi}zu$=%g3 zQGt3kLuOoou3mj(aPXF{t;+`0my%JupoB-{+nsrq-dw`__1m4pMKEsj;Upq>*LPLf zzC|T5mNtwm!OY92z(i5@^OJPq;yUEC*|xI;DKaSZA>DnG)C9ZTLvwOc82v(+7q1(EBo}Lon6p~R(z<<`z+h$ zeKu|0Q$m*}MLn=O5`oFxUgULl`wZVBxG%rg=N#*)kB0{x8u>ceOpp92B1Z-r`Pwwz|Nax+0TubO5_I(Laz#dX@Rj)d zv4WPthjA%93;8Y@FW}g%=?eNLtQU;2la9pe&+=kLtHwaIz>au21KK+XT3y*Z59#J- zU=@Yr2Gzb;46N@ifKwKzAkQ|35FU8^K&;SbYnr56gG>qtwm+n3J$~f>j(V#ClLE~Y zO6U$HkQP{jdfN!%iNp|%K@Baicc;g)&$X{TY2!yeY@#~yXs!9!(A@L|+WMh?|vBTy_q zbAkMtE&4+B11|G6q~%c3{7UOXamG={KTB|s_mrGgiU$H&=#G%LCKJ8sDVq$yQyd>y6g|OD;Q@0;ZBrr6f9Qlj z-tabQ-BfV;{ETRnES6vVGzFGg!z1a1@cZu!ktsYWkm@6hPPJ+H^F#7d048#h)q7Mdr#ZUyZsT%l2pEJ=DnMmd1o@dA511t?7U&QH1nRJX5MY#HwfCr znR$1b8dp0@VoPY|o&E$f@9rT6Gw+TlovM2fgtasC?xv)f_vEchPynBN z-IlE4a~~xA+yn~~pchm15`Kai_(5j`^U1dQP6jBgzw=uo8ff($$W3b%CHub3CZ@i1 za=YuAjk-eWnfJVuaf+v>vg*!`V_Ds`ecjK*i``LraYeogS$^5(e}v% zm;k`%;DZ2IZAJ8yIfiYqBOVU_`7R>6cs3n5-ZUc4YgQbJ?OUDF|LJ4t)1XAyQ-0L9 zJEv8*zz@1?p2s{Gam!4Fw=aMz!wdkmQ4!V?e9E`5G}!6d$UGzxBqWm zBWJw%Ke0v#m7jmhsriR4o*9E~*_hYAKNj9&Wr+_oK^+2OL^v8J^OQ?LZ2$?+k)Vnr zIS@WZ-ge6W?}U&0qvC(GIu*Z|<}nWIZXEqfAl{N07&P?86DAM;{!cei`^yWpL46bHwPX1%$9PywPkNW*Uwkzq@u7;Jesw}$%@{Lr z{HXrtmyNw>X~qcR8F)_Qzg7($PPu57EcG&CgsB@R3W;99$fC4Tqq4*TT^=j{%BRFv>J4A{MA z8a&+LJiQTp8Uv>EVH&^e0t-p-7C`&QI#5Zh{n3Xt#!k41{a|_VPiycA1Lwhu*wY%R zUqMKI-(%8(%Jw$3s#)4U#Z)?mGx5*DWgPU616)Q1nFxGy;!p z*e^cl&^j-0;7x<*vjt3m$0Yb7Na`0jkidO`1Kt4li`8%Jgn@h+zg<1$TYE?<-YSVu@rBEFiPLU zz>_Q^E{cBHS?yw+&3fM038kY-oLw>rfzFJhl_}oOz-%VHpMlmVK9_+2dlKwL7JVZF znSb^h8Az)$;=I43etR88-^<|2nmD0&>}Z4o2*f>$fiI5X$Wg_1mgILa7<~a|!CBjU zCgY49&LMV}#{*N{_M?~=<7p}PF71(3b&+~7mKH&&G+j?-pZlOgIqbv{!za?B9Z>KLn(<3-sRtL-Dar z6FpWN+%yJRHsF=QF5uk-5Ywc6Y6gh_!ZSdh@pNi!@t9MkYa0^wV}Jhw=5k#w>EXL! z8{Q*3(*kgVFjW(jYY_2%TA)u(Uhjf@<2OC!WRDCCR6q+kH(wscv+|G@?+SbOC}x}m z0%ER&Jt$@xiun=6OhYjjgUWF+ioq-$>J-xh0?ZyrFQcG4SkPAR7d?x5mlo%*oo3#- zc86Jr|3enYl!oy#CGZITpMnZT1HBzKxUj6$EG)>!-2MnAsfPxa4)ZLK%7zJ28F&=` z|A>wwrFrDN^?CUh=Hu#czYfGxX@Np~Q03VJQ%fPW^A9Oo3R3SdD0kq|E9Q;%qPiQG zB($;GjC_N-777^%Fzi$V9z$?l@4WnBQjjahG)^}c$Z28N=A2%HyR6wX2UYxql!M>3 z$cJgcLM;+R1iUb9*hOrlt}4D)J4LRnv0ov8RHIL3$2H_jyCKiu4hgOcxrg16Gq|p2 z*|CKu_Nrg9)Eqi;t?aH1$JaU26H-HFYN^cdea8jH09&t0xL(Eg8Gp?}`Lq@+6}AK> z^*ng|(`@1bn^QIe{nI=l-%|9d0fRrdwG2sUNw5pv?EqhdAAE9h4T#1b*`UjQO>MA9 zCO4H8FzqIdzNZ!@iahd_uee|c9tv0vTZ8tZ-&{i}P@^7^FF>yePgw^F3+v_8sxa=+ z0l5>;v=leWr`}f0cRBOnU2F~otlU}PE-kI&guDoL^ga+N&1E@hffMl2h$WSmm!FT2 zm(l_Q5wb{=ZqlTb+4ewwTa(@uON!OFJAYbb;lSexpDHRWUkn2oH}WwRkCfZ&U=SR- z$|hf{xw8mV@~c%b78-A8H;d6~%a{rudX$2kOHpQmK-! z*OgoItU1=4uyhH_-1MeG*ux0I6TrZHh<-y`MzXDMPm;=Jlzj!>;k*#`;ml$Vc3W-m zkGuQG7qGH_2?+LIdILk`QjF1;-rRbbH8q?+tPcjuFIOP4jgeO&vW<}#y8JQn5z3g0 zxLtTv{u;O+BC1~IAg*5CM;yc6L);B;cWT_#h?@a3YaY1?VQ(XDA>6k#?#8L%!tw^l zngn!q7ETSDg_{pL4sRuTF^h6H>fYk@*K-!@@wUrL-X_d#J(k)QP)>AOmYBojIjHhs zQQ#W26f_u*Ofv#Q56mY$;Zb~%FYyR!eH8A)TI+hW2vZu)Dd;o!k5UDrD*MRuH3567 zR~P{p(CdG8e*W60q{4$|nWZxK%#)H1pZtu-%rr7UpKBD2D*7z@FGgik|A=SX)V|^9u~v5&>R7JQPVbk_il5F zZlER~Ot3ZGnt$p7xdQgycGRzxiGVm=<#LJ(EvXI4%K(p!fX*;ej&r4lya!<)eB6)@ zyFd8cQ59T*%s($2x##M-7dFdO;7BWGo8gIv^RTlfg$8OiGK zXtUpFX~fen`}yZAAgVPRr4yo7gaaOi}pJ)$8j9> zxuvt|)3f$w`p9+op69j=w(Dv8GF?s#qX7@60a$hdu*|sxPutJM>rvrx{b3Q%Dmr_h z+*IB88H|^kRt|}Ho56MR$OAA%R}qGfyzi9XY!?A|(y`m-eR+9{eFAk&-D9F zJMr-M!}v0MeufqMb~k+j1B!jvxbXC~b2+MdDyo^#AwvuD4=g-zl{8dP%JD6%*9Iup zzh$<)zA3N12$6HnUf&x-zPrMY5xUF_3_Q>r4*Z41_-uO>dWsy#fcnz@n^&8En)`~` z-y9NL7hK0GcNFx_19df1uBhM(-TPDY0Txj3R(D!dekA_&kSvG|ryydL={?2jSg*JZZEv`3&m)4gyRd3K-b z;9YH6(-v$-$Te_s3d&}1Wr8#9AsH42-`!LXTL{*E?PoO*b|FC#gJfZmC?wH#9Fmz3 z$;K>!fPf}|T3ZbWYF&bB7Y(?!YT~}sfLhyXqt@L9+^xoa|DWeQ_ujd)vD@#jUq5o^ zF6W+m&U@bFd6zS_Ils`@iGR4jx{K6DOWQXqx()|GgiB{vwV%hy-i&`zQ5U&e6|#m6 ztKl+jPEi;tl7k|Vs41l7$5t}*t5sdEdY;8eRH*|JovvOwE25EIr;M!oCvTXi8hSS2 zUGsA~3ePDbm;RZM0sQSQ^(vUJnuG#NgVq)<$LM{ALaY57nHzEa^-37+T4s5F6NwHB(!LzeO zy#EQD=u*eMZ=t`q_n&g_Z+Y)=Mu9PklX@!(GP~4Y!Si2f%xR$0;4i{5ZM z_9=*^0qRynxX5vbLVio6Z_lzKpUL|EKo*>)E|>T1+y~$_8URTr(S&^F=$-3L4OG>blfJ_(yHRUex5Nsp_3HdRU(?>JOcNvz+CjhMlGx{$E?o`brU1%A@5UJ5%ABDZ7^D-65gLt6%XOnE8rU$qB7hk z3Zq9A!|T+$E3?!_cR{I7^)CpkjR^cw?;_alwC%>_*^%d=EGqe+PBsZ)ge{>b9#`Xu)U$K={Yh~CdRTGV@){atR zq%qnUH6@c@UTXaK<5qn7+bI0wLdFBcN2pXGxe=jU-IY^}fknpu;N!oQ%U@%Fxg^}_ zRKMNnD4Qv%8|r<9l!QancXHP`=>^36h~`xbc1-#pwQcHrT>Lj;TL!2v5%{EK zCd$dDqk7vA;pgEIl?!erKmR*k;8I)C$4aY5AY?yN#r1>4U14~nnKz)ai3U9Ho!Z@v?S&eHq*58Ziz6X9M;g8&% z`qrglhdd^Az<-OH;2CNV*YArgnn(W0gR}?gKr{aXQ+AvyS?Bg8xayX zlrd$)SQqDit`IE?v z4(q{T4Lah|rKaO<;;tiy$+umGx{rJQMrfKBEo;HUcdcgK`Ju|k{kw-z{E0l1T0jwj z#xTCeQn*{tG=^}Nw{H&P_Ceg8+mdAKZ~|2w#irCv5DkemL3f?m1ZCeASOw`Q7)0%D z7m^TR19Fw+AEnxlv%z%5Sb=215G8+jsQ|BG$woQWa?*V)3JS$Nb|${=J9v6I;vmwgsXwO?81yfITn-p}%@;DGPxQKvon_egspmKSVZZgrG;7 zx+H^B{&t8G^l>o%H1#+(I_<*FK>gL<<@Z*xSO1PEfAF6^*oA^LwNB{sODxF1Y`(Ig zMLmLKdzbnPR1o+#MSJ`R)rf|bpj0#~mAG$7{Q>`|n^A6xpMkn4z1vIk*%-D3;FH3w zZ$s)1e~`+5jdh7m3pe~V9JFaL0Bh9gA2(swPExT;ZR@S8!kw9;hP8kG93Fmn z103CwQ}~ZuWar+(#snEC>Q8a=9%5Cw zod<^u`xfBph42aUD#x9Di@##RffM{s~+saz@TfO68JX$ zp!mYE{!yUrZ_H5-at|?{H?vbPnJ`@UXa#? ztY=9O__)L%n)bt5@HOy3@o0@q-bXC@s6}l^ZBy^B z@Z&FngL-k8+Z#)Qg$t;KZiakOS0hUF?8cIg!e-J|b}KjS^{YRs?#GS6(AOkpMGHj~ zy+;LmJ@>cc1JYq>q^lN2ySdbQW%M|7$(tM>`w#uG@5{$-pl;U$a}s*SjmSz;U0C7Q ztp+41lX3wpfC1_}nUpV=hr;Tkv@V2TaHiI#`K{Tx7EywO)lGW9o|D=6z03}F4d(2? zh{bh1JLe!Xe6acsSQl`OUY#sI*!7-j;{1FYH9u<|UH(dUxl_7)m!6+r>(`yrOXlYW znV;YEGMWl=M*u!W?-BOaq|Qwbsn4K&SRe7#^3aqH>Ag(X@*Lbjkp0_LIrtjR@t@>l zF4e8SD<88_KIT3BF|Ce|*(4wHj(p4}{V}2UFu%}jFww>&p*GQAK6Gd>7is1C4*8lV z^w)fWsm04T>91KYU$efK(GIP6NB-kjIKLE)`_nY2Q0gThJ(j}#HtIsU)J5q94N$h# zJEHe(f=&kodq4}Gy8^Y@T*eJI-{RNxXnZGN$IH{2npdN4ZaXUK`qlf( zK;^vzrNpWc4}}W`D@Kp;lP>iy;NbeKx(Z^-I+=s0se$S0N(kB^svFkSKpayI?RJ&y zl*AL{xC}vE^^odj4gvceQkV5=Qg5PwFZ)j>Ykfo9C(`~9>4s6)aD)klk%-S?5SHFQ-XQupnAJl0ajv+l4 zJp8|n6kkQeeVTeN;fVeb9|o~c$Cm3iAg@i1kA6ol?dMiCxqo^XuB~0|p1=}R%*`_w zEYuuSMNPccq49#5JBSykLmE7vbBDuChEf0caeLIs-LFhT)u-jGADW7UfdB6nd~_mY z0w(zh(m+r!3J5><(=q9$SrhE*DAwXk^gKn}F55A_BB~HUi#^93Bmb=)`A0GGKRQga z2-E;d$Wh})IThwVlfO42WZ#@D7i!sqMPT5sSdEbf4%jmue4^xun?!*Sb@d^~>+i$s z*TN-Mpq@*WrEtIF;)A&O8_dxi|Ai~zc3BCRgV3U9gChMre3!Kn6z~p1J?i*sY&1a5 zbKdGEclKcrbkK|q_3PF2c*QRW`p)AFJOtJgk~d0B!-NoTlDTMey!aWJ3;IDnK(!K} zd>H!H|Nn-5x65OjwLJdd__$~Fs9uO&Q(|U>$X6?_%KE71`ncKg9Nh1mjULDPKsIo~ zL62J>6rs#zuj~t4qmJmoG^zp|k*aJ|ZX|wtO``O%#q5sP&=qGsk zze|DJfWbfStZuqSZtL3~Gt?yhH&SFkuR-0a1EG;zp9*#}=%SGqZBv6-1s7P0a2lzF zOK9#f25Wi|8Z}bpZzm@z?&-~ zo7}q8lc}93p<7w$i^7eaz)Re2#`gEZoyQjX4B2wh`9yzJ=`1_9q zM#Iu<15}eyuo6F-fpPRx{h=@pkaS+X9Qf?Fbpc|)qnYjB|AV7OLaOqKl5qN2E@vuQg7&r-UsJhqP zwFWJ2LjvtkDIb6$0_XuK5?NmfTpB|W3JTX{hLjaZld=LC45P%on-K|u#ij?21D`U- z9QZp879zL>_2~dR0#oF1w>qdqlEHztd2qfTQ8(mZ;D}fqYIqD#H@l5YL?Hb-t!egp zwG`SFZtAD5W$ivYlYH>_=!dxvxb<*WVe{FD5y~no+^lN46-sg(+=7?^NUDD78CVE> z1Ci9%<@gF@uSCu_sXNk2)^yrI* zqlCyk-m7g!kvh1GL31}OgBCqNJ=v=*tQxyip8|DiJI^!MasUc%HqDqeUyUwNv(R)e zk{p}mXA%+<8c44HRN-P&A0wD#Wm!lS-5@}7t@*DvwtufKL)ZBwM`>*A|$)n zVm)AWb1&uy9K@O<@)1tO+bDUAsah60Rr-1?pGh=fiJYerQ1pFI*wv>d7&?-ogHa9z z_TFO-B?rnL%3&DFv!gR_4`b%-FlOE&6a|^L!*u2?e<1VraLK$)Q^>p>=E%G~TrzKm zCCR)+sU@9xd$^r>D~o@=+4I&u0D$H~c(}InpPA_;>BnJtKP0m0eqGOaCS}V^&rxUM z!hHyS8lbitO*_ew`ZgU?I0cn0vfP8MwSSA%@^^h)KSf;#qxLd9_CfkG8i<&@c$trWW2965e~x{CFU@+XSj^o zvdL3XfQQ`mee!p!*v9}hI15ZGNH>ON?tridsI%bxM9&%4c$P88+SCe60 z;bu)9i%U1X7U8?~rRF=o?Mt!pRuHN=(g#p0i$6*%xx&xGdw&Qo7GL}XI5Uqq2u~mu zg2#N%pW*9xPF=pbRlSr_g3$but?E6LBps}t42qoS4OO9iLWA%S1!SO$v$7m&2N(yB-7#L-xJjSIVCP{EidcW0j+;gL>E0Qd= z7ip3@{m;xI-0%EFI~x(XPtIIMWFjR?VBCkKMYJYKi=n!@YGgJ^rXsS|%p9o%nSPPH zK-`XuE+iB#3Hv-qP}9HnDCLkHjZbTI=0{e0f<7~YY_IbZtLkdJwN>>@QPYWH9>2HT z7h+--I;<1#aLi<{`g%`vq8V;*oM02|Yjnb8@mPk(y*kh@n{c{3KL}#I`T6esiQI3gECCj9xL5X51b=K(MjHJ&dNxAn$JSslhdM^4#Nde6vXwv;}Bu)HfIQ)>qT z`gqLm*pVUypd{Jr&#<#2=NayI1@Klif|^eTUFR-r3rEZFrq%viW|Wproq;o5DJ47H zKN$@7<2}GhH?acY;J^_WlvDTtM}?;Hkip1DH!Wh4LV>4|r_zHpNk&Xs4rK;*j%_$j`gNZn^}D56H7ooIn; z_W=RurLMsy5gN$r6`eT?^xs+20uQ{bS~z-_BiIv&@2Z@sg(L9u0r~lW#C|@2pb(dO zcvT2lN`>lRY?3M8cNYL51biWoh*@E8uVm2WW%#~>s6aO12TD!g!kgIA1>yFHV?zic zuuG28Ha$ul1sSChbCljgNMM@UDN}Pfno3i-jDeV5P+Ey*Zz57-HG2mT{5y~+MTkb? zD)nv+2|gMKWid2;YiQHd@1rWNqs7mZ-x#!@umkVwOhc1W4V=ZA*D!_;Lq-7VpGYTr z2jNSwSHHH4e8)ktF7=YT1-m)`K4OJx{5*>fUni9FGGav2)V1cZ#J>WCIeSH$^%3eE zl!0`q*D$7-#BWwu@qFea(hNjApH-|X>RY3(Ss|Cvlh2S#Ms(UcVy3}Z(bNF99YK4m zT&xR;vrQeFi)iN=%p`I@HY>mR7=@D5+!o+%tQVvkVoG_;Reg!O;9UIJA;?RFJKbI1 z{#>h0Lq-46)pciCeCxjY&O&1}V{clK_DsSvvPg#0IN-S?jOir02T}@1jg>q*jEhQ+ ze&FA6OyMV-t__H^#m?av(Sy_i^bH)WpcEZ>Qb_1_tZp82q|qr{?ZKVE=_PaI3XnCA zNnuyG@EF2k&+>z>^2Vp?4gWlx`4*`yjM^o2C0tT1vvKzgsYWKPWtx+C=zLTXa||;g zR@3~O7lb>|nFmqs4tG3+;>YCR>XquqwwuVhOYJlcDSU+M={qD@n0G`r;!WBMq{Op; znH6}j>v>moe$(ape43G&V48Pwno)RoB{?uQSeU!a7|hYW38*SQMi%A;*pBm>L7bzP z0+`C@IF;W?&Kf;W#|08u!i$Wo@=lP-@ zL>?pO5pkslsXLLB@_D| zas)WB2dUrI3ll+em*J+D5gBStZ_HxT?hS+-JRj7aVk6PIz!RfYvbi;CoXdz9=xT<5={>zO?raq>J zQA-|!w3qxq>X$PmPA`0ln&%M?z%O&p)zzh4>dRj3l;y$+zO@;_B_o5mQ-`lnohdD- z;4os@5rGW>-hyJ>OcHaYi<8owJ%~TtM<@C-YOq?~j*vCY_q$AF>nUrBNm{wF8pr(AISOikmR z*ir^xB1ap-5bfqU5S|=u#O5?<>RlucB4#Mu{f~2b)*#Dz7Lp$6tSWS~KJ^6uxPLZ8 znsBS@8c`M;r`$+IkUvOAkiVdM`8!^63MhaM#A&;2^y%VWEow0rjPVEbsA3q}2Yq1N z($(z<6t?8H3wb$UH@(!qkiD3kgoPu~gPKSd{zorL>H=iDER>mgp-_@y5erw)@hm(; zaz(y3Y3w(Ml$Wa#h96zeKO%K^80{Z{iV91&Ajjx@$>!XQ5b=K^kXZeemcha5HS7h5 zX1BvdMoxL@axymZrzZk@&mH|(bn!uyx$F!0k+m8x2Gui7vgzqr`1Oq>FP^v3-%-T{ zf4<`F3z@&O@t#~b!$Ce_0)jGuX# z;B%B zl^J$_OKX{>E<&A0*cBn-!euf_ad$T@+JNqSlcvK_+&>+d?*5+vc<6jaZKIu6vB|az z9FkMryqtpg8{{VNn9`NUsMU@%KP&Yu5{iQI#?YAhNZwjsCbQ^(bK10;r+ur)WnCR; zp%Yt=p$TV#3m>Nzl~0{Ud}+)V8p7JzWO#TO7jM(gIoN`h+SX2h+%(6I#*9*mOyOrl z?JdJK%SDWb5^B(R2$eLj@}S`N!v3oIY4mS*kLj4JT{g@Ty?fmodB}8Z(_*l4^>WU{ z53^=1x_pDH)u@~ju2M^KayzE_o?URG`e0Shnv>R}>wm%q9WHFb9Vo(&0i0}BlSOna zXh+Y}B`imgsvZ=PcPkaw8(~JklE;o8A~Qxnqe{CH)^SLTyZkV#UBC#Yh!pcKWSV#5 zjZD7stu&TAhta@>VL4(~8EkXIS05>i{N6Mex2X#0(GS3XETLuCs9=}50SLp5$qm3q zAUU9orx}Cl*q($0WhVp(lR5_}3vTtEn7J3P;)ZhXx%}!qSZl-7G2Cjtm=)e<7MzL0 zajb${6vCC)fFq=;dtC)Lsz+8fA=n@Xe?!V&mu|3(Xu9ZeX0gsHK3AYz)h#hL7A!q8;yd$bL@ zl!Pf0I`~6|5f%4_ezzh=w*x)=v=Olt*TBar8<`3W9EV!3?5;x==UBp8t(65TJ3}SDi1r<)9!xIM?5*mk({|0?WUYi<(Xc}|tPjGY5kWerOQCGAm#%KLNbHjK z)!ffqBP=`g66AfJ0u73cG4`wOldl-?;fM$IT{$ z!xuzu2ApXR3@`+KO#d_>SX<%vmf42eyJ!zZMquF%qs2>IgFcbx$CNc>xyPK@hegS}u^+ zZ-oanW-y~)2+{Tzw1;vBf-fM#iLoMFfjS~7BLAq1O=IUSh6#Cc$!5H_6(v5vL6-}U zd@2?Dy~a*>!qo%l2T(~$%jIa|2|R^gcM>Pqj@|qI1RQKTaN$282O1JdY70EP0_*ev zTm+nlza{vqbH?vQQKmhA;|H>t3oCc^QdLy_60BBWYy<7N@1^dMNJ5s5SH+$7c}!TO z*b4`UO3BWYF8hXFi14w4VjS{p3?yh2rb3xZMQR7D2XXsCSb!0Pue96#p<8rdTlz^+ z-v8IKazDYIG5{%%&+MAY*AvR^3kQfi&Xty~ zzUFX-tekx50i|&qJ!7F^=MnBuk(}aj=})|a>S>csXXn_vXK~lV^(gfb-LMuilEP+! zusS0*Pm1IBx7Sx&kA8ZXLiqPMrE*>MPXys{H1n&^8Oy^YEJykmW-?XW>@V zcjQw`ge~+@w+kHpl&hcyBa8x%xQ-v5(%XnVKeF7pOkudAQ6Cb$t4=B{LVNe2-_GVv z$0MIx&@f6jVom68{@Yp14M{UL;>(j6V&cu{TqRYttm<1)mYR8knIj7>jE_lGmoe%U z@IqRf{-qOz<?EH|#a2grxx=`;6v^Ch z{CmZ4nScBntvpl`62-?V9wGV%W1GfYt}e`X@XG28v~yzw$X(vTrGEMgWIu# zvm^0P+n}iCj5jR@Irc;GVal5y=RAgJM!LqIP7z4YX_DRrlay{2TBTk4W0dku@T`;3 zU$CLRnBtaLUoH7V;6i%1Ufc z$O=u+3Mvf+_OBDSgziU>Bq?f$?|K9dwkfD4G7!(2_9pcBboCXBPDLqXlsJz5IaJgx zS36bI9UF}G&tor8Py}TK_j99_6{VzZM<@m0JOIHC1yvp0y&H>)J?Vtzy2F=SijvhL zNWXG7IjuN&$R!2K_*DTIt_6v1K_PZypjLt3BJd3hh$`^oVo&}FUdasgCRDoQ zD)8kH2YpagiOdNVmZ)d$LIqwsv$V9*SSkwerBYnyZ78m3>S2L4?_Je2@r)^20~X{~ zYrw4%p(3XG-f6(kxmaeyPX%}sUh=mnUIJjs-KkDTd_gk`e8U4`G7EgiI_QcP<8YQC zd&|{1m8t@a`8c?ULmmNp(8y(IJ=oR(8@G?TL4@*4*i;Y&;#CKty!yZvrcV1iuplmY z4*dgXbrOBvDS&q}Ht`kKUM_fxa0xv01QTV`P$rD6ox^QFp;g0+0(47;?OOyv!CAx7 zcQAisn4d%tLLcn*#eu(8tfwbM(f>~3rOsz;51cZoD8?=*d4ex%!IzzdREbhw?&-~2 zarXnOT5Q&-wlqfK#L`r0>#mk-4C!NS#Q0dP8)OBWMx|a)@cN``Y-1q63~hsp%(#|i z-}X>u+>D5uM6kxih;@sS7?+BNzZE%KiC_(?M8AYZrBMx1Flx+Fe*FsVSdL`3`W>`L z)C{BPbr34aQ#RbPItI!($MHlW#!qxTVgbhR{ku>?TKN9$abu92?>8e-t+5+WhT6(H zK3YIK#Oi%EfWfdWxUY-KFd-^8KaCB$LRxj-B& zIhYL8!=>b0o+|>A!nOP|d>D_Z4bV z^QSih-ax?7YLe7H;EhMY{ge{T*DsW1-6Mr}2_=y8ED_ zKlwUpSqNV*N(^lTy0-|j(QGpIdte*D1d$-8MdU<>HYLC{9$wBN-v_RKtAb`{;u>V@ zpL4GZdyxTgMOnWxBa7ql2DmFA2iBf&!;EBK?nK={8WB__Ol0Ht($gS6jhLZ7^diAF{xVCj?!>79j*P9)ACtann>|OoUr42SW*EUPb|se8fC{N9-krkEU7?w z{#WP;5&7c`%A-tR;Z4h{gDmrCber&mJ1R2Cap&EwN3aStq=?xzd%R+S;<34<^(~E`gjnUYXd@yJEUs#y@cotYiISEeo z|LxafuK#Kg>Al!PmZSg1iX?OGnD)enm}zcS5Je0zhGER$ywj@$cr9t+_sb6mEy&t- z>SYOK-md8>t_=*z)380A@|iSNm4qJ6=MzwzToE^h@IH)w<`X81_`e(d5OQsEFbgEg z-xH)d07PjHfw&Q63I6{)4XLt+^Iyz~xJtQCeF~?1+$zCS@{c`JNWMtfHlG zW^Q2v-t;tzu=i5uf=TO$GF*hINj2$JKwHsG2uP9W^A1C5G3u)(YjDdp zG(J!&r1Vi6QNv`Q+QG^mee6Oge1|TCvI)@}sPC8MthZtl0m`?@Flql7#T)%&x`qY! zYrdt^-0km~J}xzirnU-IRbl@1RDM;;( z=&g(oWxL@sY($w($4BcJ92`0A5i?<_D(w&ll%*sSt50}@~ z)YR3EY6$3qsNH$(B=q?7^xbE^+Yj$PYd&`K-h`cqJ{k9ZD_=gotJamh&ZMuX3NRx* zm}REXN9BOaPNq6hcr21zk*w^@kH=t3+ACAoC6C$5+*%~{+KJ!DlU-C(QD5y1A^Ww) zQy-{m@P?RlYi7SoGA?dH!ZUJ|nTi{o2M=+RB)=QC#^!h9W=XC_7nvc?XU)WJwySe@ z^PO>t?l_rX1LL^tXc^5&!}?VTvY|0t zRyH&aqxbE_msQBVsg7)D++=4%Gv^*j;b@z!SQ*ebwlbjY8TKr#3-EKD8PJaVWRjUF zk6ZAJGZ`9p$pGssATOWHa)dx|WD}iGLd*`Y@=CiB0Ed*l(|u+FKc_wrsIAj4sK;io znt-J(`+evJ6Q_@V3Ju^t^{{fOj7$|S*^Vs$-O~rVXAB1CJ*Z%f@lZwCg2Eefl`lvA ztVI=eV+&N{?U}~m>ImS_YEJk6sO4F|R2Q!7RQ)8ld_%e}diXd2mL>d0N~Jw|f5)sV zZZ=jNio%HVhEF{Ke+yKos}c+soFpGwlVWUI+t>t@W}VAKrFJ9&76`ccmz zGv*F&_#*P}J-73_2M)_gFR_8P9H&9S^nw&%QMI;2D zZMxO3T$18*G=EIp%8$dSHk9Qy|Gat1sIvS~@RMJ@vJE$ia7l&D$^Z_r*Hf+JVP4cu zN;=~01X4KkAr4V5Jy39eg4graM^D8AkFE@{!!%e^MGVO?qiD`Y%%w5#jqrkdA<(d! zAU<;)U7d@v{J8farhoNr+PnqZsa6_g3mR0t(bMtl zvv8_qorVUVm(4+b2b_+_gou9!NQ%cCPq?e)m@Qf7srxp;ut%5@Amwy*t&TzdJ=@(U3_*)qrR&dN$4H|CKW~z4W?oR;Tkzw0d?+)o zOPY&}A60DGg8bu5HL?UjHeI-Si`@DS!*!ls(bmeSe1-i1;d=flyIR7!_5Yg_-n+eX$M#xdUWAbb(Q&fK}pcrnTaBnz)5kDy*j-FGd`T5=)`|adScM@ED-xD=5U)4vgNhNS>R7EibPux@knRP<#Hh;h@=9AsX1WSEzN=Lnwo=osP~zV(i}ttMxC*? zbFZxmRe7tcmiq#p>Z%|T8KZRxyePRY!Cu7a5;z&FOF$II=@KHIqjU*8Xz3CT0S!@V z=@K|hqDw#?ivj_8i<@j+0tH%3T>@t*@pn~O1vf`mR?)hnRv`5A`WQDll?k(Hsgi_C zmSQ1?wu*pnqo}|7MGPW^-h%;!33NOB42D#^=YV^!}=9pM#R3Z3m}Fkj7~tVBXAr>yhIZheK5` za^;q!CMmhd=$Fs~a*<=1Cio6w4{gzj{@CsBjc3% z^~1b(tmzXjqi6Dd(d`~w+Oly574;o*8@EMrt8T<7JeN-W?XjgL4XC4v%M!B*h2tpK zp!}i{xpR*^1v`#DnBrFj*v)qBi}x81Y9%aNl(2hTs0`s$!iZm50o-4%YT1q^*P@uD zgjlK%4$4t2bzQ7G^Xx$(9G0N46gHPau-GtaSg6Z``(HpB2;w!N(egM1yv~lSaj0*O zL$L!S`Cmp&eiC+4lBS|HGIP+hy2gM5x$8v)yU6DN@PuxRt+5#@dZ%o`fXWy2E9j45 zQ^b;~8j=)hFfmk~}bUCp5dBZOaw7rDa4O|22I;NmBw3DCx`Lj5D;w#}8@dEMAO zD_wSLS1Qj^PNVzJyu0Ac>5FW6&Lk(n8B6s?Lqv zR=4{1!5BDvFQdHAMI8~{u6*wn7oxq*yiVPKmF9l_>K1Gdg}O)t^dnOFe{Q#(luPr|%`g(oD*Xeb`ja%lt1pSWwv zX?4c*TdEc*>hqIDdrx&OMO)Qo6f7Ft2J_IR?q{aAQk6!NEM$F}kC{6~StsDoXCQZ? z0oqM3K=0CxNxB`F&_%*$muThVI#jEB9^6NO=-g?YMJXHfIera#?0H_88ih<`?UUN7D4MgLG{Zr z{5$Sd6X@4}sULTELfxn(CD+T6>`A}oq9=h4{F9C&m-;QjUHF3(wbkVw#e0{L_;U#@ zOqXQII95T7nV zfk4#4S1kIb!0=<}H;OKhlw=CB2f&!!KO1Q5oO%4w4R^VZ7lXZ zb>mR|{Mq{Xo9)}p=Wi8=>9@$cM~Y<%9da85%z9TMeZX~ap8NE<)t3@ld+u@qRDXao z9`&YH!LYvvKaq?5KTeT<0WK?)SmvlZmbW=PvvJKCCPUwp6{hp0n+a)|>KSZu*oLzI z&mg`Vzuk29HA5A2r#uHuW3LU6IMet)<5x&-X2jY%wo7Dh?T;uUDDE>g0ua#!O?O2w zBu)p6BrOaJX*MkkXrN9D16rtMVc<%vg#o3}vikX)X;PSnu=;rvXOH8dSS=swY@C*l za|v{M5P_xB<8b$SJZ`e}cmVvS9?w=R-5tl4?v5MuCqU=LY5N%Gol3gCq{|TNN5tH~ zVNxyG9CEqaR@*TUs85Wy=+{w`KKo-+lRktj{5Fx?e*u8WV+z+-&*}c-if^v_=sY{aVES8bo{|l@#@Qjwz~KaISIevt>`sD;r*>`U0}< zRtICl?E)1JsSLj9e(WFOLeV)Rr%0XIq<+|Gj028|y9Eb07#(z{Tn=Z{{x8G01rlw) zCpXvQC_VnxJu=^Sy?n?e5>BbTj?7xrdL`kFdLm<230Hxm;xd+$MR58-?S29^Sf{mt zC`3g{ty*Xu+D<~8j;8%sLi*qnlaK)H41z172G!V*-O_%unGy;E0TPcAPHkmsNF#Pe z$O3161y$g1ZWG{ORY#7UNzrhIh>1+fQm;|+M#IGG)X?sA@UxVhAlU0ygGm%U_|Wfx zDB>~DSoUqR&xPLd#Y??`iYPjY`VqMmm}m5rJs>KpT)Rnb(a&2nxL-WnYJ?IZ3K24C zE&)gssH&}`r&)+eIJ=WU;cR)JeC!wtqe{x6yx~xtS@j$92(F|h1E@8Yp2_tc^bBex z;hOjiy`PpKi1tcqzAx9Mc(!>X!~~CoOIr`))pBV1qH*041%PM*-r9<~8hkJsbVAV9 z&j?V2GjT=6aZVQ*XXoOIeB&yiB}esloUsaxd#l+gYms7LZO5q$eZ-Ay-NJdOs???8 zd5f>wS8kS#Hw6)Sfp#wAdJJxaGxo^y#c>icBVLf=RCKv;oUp|hUS=Po@kj}6_6_rG zqD~gS!R<0B7-<|j1t5M#b06zzG-OL#9NRLMZ!TZtvtt2l{iCX~s@BidVc0e4KdREC(3ih(uosHwG@^oXrf;QUuh}&FTeYHe&V(S1j*1 znzm<^4}`e7a5s)EmpTp|z#OIaL7(9<;$PcFxZsXbeM2nId<4*s7tSEg;aX?RR_C~K zwrx56^cT;>c7o3yVr0!4fo#w=)zpY0YUzIbEl}S9aXANn52k4UO+9lG-axqi=jkP3 z_2Hs+u;;JDCAn5ysMc`-t-h~h-@toRQ{l(z@k6n(3ZlFkPAr3Y* zw&J$oU&>9{3oK$hyL>{8ngMopRYHuWJk(LJNAN}bfBj?GagwW?#AP#I$F zsi$!y{;>Ac<4!$eoT_SfTyIxHLPct6`z-h%M5w6Vp?Sk^A2}r#M&R)0)Z$Eac!;`6 z2><4s{`uVDw>y5RL)wh{&Q*Py9=~-9>b94l=0ej&xu+S6XaD^0pZ^%D%l$}S&r}y6 z6Xp|acHiPE`Aofo6Ps}29h|t-RWf4zVpKlPgaH_0>1}{vC4j;*@z;-yYS@oSS;pel zsp<#*(mASs*0>R)RDGuvnozV;g?rQ?D1MQt4#_%~z3cD4?#Ff4m6jRP<_^C@4Rjqd zS5>vD!I`Q$OAXEmZ=eo$CI2boKf~cwmZ`zk^*N`*@q(=|`$ID;QT@%Ixa^-}Y#D{f zh|L_v^a5;^^P4E5|SyU%Tx8hN8K%HmTm7rE|uVF+2D9 zWlfmWExk}_8WrXW)S+3*V|0f95xlw-yNed6{>WqVLm~Jvj!z4zABPy@fGoVFq{g+t zr!rcaFDpFhxO)oo=iiD8uVF(X6nQd?wjFZgZH+{po=xwWe5q&2(Q_8$Zq3b~dB60z zC0+IDnYr$=LgVV0%j693z22?)g$*;8L7m06o4s3SuHyw1E||*4JR2I$9wjHfTqV#W zqAc{^&sH&4$5o1HZCP_70|R>0;-*rRGHg<>A(!`VM3Q1pw4a1jDWT^JSFl)TPijd0 zq)8p=XPgP*P3G{H&)n_m&`h-#5)ByPvtevHn=e%92h7_niSpc$njM0;)mi=Oj z+8{pi<~okxM;O=nAX>lb+ompCS%NKB7O>^}qP&CYDq`nPv16PGj4Yu zaVYu$WY;);n^8Jf8qVmd{8T0il_ey4LA1^(EoI33Yc*zFZ46#NrSuHrv}3dJ*7hZU zp%{yoO^Y-yCy`st+1F}Sj`9{oSv?9UYgn$Z8Vsz6w58Xfxh1uTwbohPc=_MhYK z7wg+1y}x!q7EZlf&(yHn1{ecBR!5=;TKB2Bm6fYYOH0dCf1*C;1xTLX_G>amN_Wr5 zLj6wlcuJO9E-@tlhh#G<)!VO@mW(Yurw|*hscA-Nes1a6rG;!o`T|<+T;8KHfC!EE zuT%Lzgxv5GP#J z2+djEU3pdM4eHM<>h>d7H8$ly7!63TOKlv~^Ze9`qERTl5NuZ$^=-x95`{U&J^?lS zt{aCNnb)j89-?f0?)uY=(duu(7WK!zs5irYtJlu3?5?XvG^sE+Z9~Z#l%Z8UXOOL2 zFaqoRnI+vvO!gyan2`O2D{NNM3idHFOD&c_>RJX+{o`QH%T2ZX!e)lwKMRbMil5TB0sAIJB3o%FKpatz?B-zbdEbm?ALY4sq%7qP-QiyGaGw1fd#ySG22l?XyS^2ZO7xsYc(W`s|J=#eLb!#y|d=X7%al5 z_BDMgx=$coPpcZ)iu#PI6`eb;x6yQdHL8W?j6QnS%+f+|+7E#RUIc8Af5CNom)tr` zH5QyaevVq2#mZB?+rWaePQ3U^qx$60!!JE~?BS|U%gNb4RPVZ4MlQ$=j~Mm1`KPdS zX<_)Zk;mj#&cZ+8;~?L2tME_hEd0}K48d)s*{G~u`iXVYaap~E0)y9dY|9;yJ4H>w zWc>jire{$@->qJ+A&ozVa?B`vQ}0*XR){D(gx5Z8C{b@WPzXIXfPSI7>zjC8-I-Sr`P{N+@>;);P_ zG%~Vh*D}u1g>*;x*@S{N`oc>!opRKoeFHg}57khnTgPk&#}mRRxZ15QRZWC% zpRUPKzli!O1`9qpu%#gw#^rz4l;BnB;(?*l`D;;&(jB^WU{}%bvdMs}+SCo$!@{i| zt!Yot(2Mf9*UPxQI51~4ZhW<-l}&!qKcwzZ9J!ZBExOse2SSr!LhHmxsne1MR+;sjTE~Fo3saJ-U zV8@R|IqGHH9pu~IIg_2)IHX__ygdc#32woHy!E^B_b@+m*^%p_O4JcN?oauq{* z*`X!Y4UIYKB9tZnMs9enl3#(IUvwyHuzygAYrGRfk-JX)dj+d*hw!&R<>#osB9ouG zD}#Q?!H@f)v7t~Mm4jWF3L3!L-m73+zd0Q4v{}ZF!Cx-%QB=Hr7zj_PO+Jp%xtOLM zLvz#>i~I^BYM|IX%I0>f%WFH;pI3FMbps33m!L7>rDV~jT80x3NimQ+`mzk%(?QPA zqkY?rZTE1kq@xPA{QZRg9xKb|-I`AI+`umN;VM+ITC2vk1+QwD*-)yUM3Ed-)QLT1 zLh21n#nKQCvGc)M?JA?Ixj_|nhOY{5f?}?wv?xytwN0FdbXLEwDN(NuWNLSBm(FbJV$gP(KQB7V7JYCbjNx zV_;)p;RrP;bmXs&|M}t5uEQS>Tzb>5Q-@@#GfQBitv~maWng8Q>Yvyf^0yiO6Vx*} zxFe&aNWHf(Q(f}IHmKhI6NjtAON!>72nQfkc_Ztd^*VQl$=oeRz_h28eS0d`{ey_M z1z25AQhjhhrrrjZ_g!t>hh>awU2@-za$lEuAMSe9@;N=7iF%>lOm*(?5dLx%zAX{Q zmq<=Qp%JODFyN&~w0J;0v{LB@n969m}p zJ*GM8KjfPdaGl_d4l+s%sV8zyMTN}~mT^Fl0PA+)t-{StypYeD03#844ULJ*O5iLW zMa9Dj2o!aOA**O5E<#T5Qvydi{ROu;Z#e7Bk;^@JKA%G@o@llgy3$m7X1%UHa8_x>S=FF32oQ{^R593uuJuC61XHsor=A~ zLbo)J#-7110Hgc41-0PjIkz;c{1#P?9m_+vsG~ZcE6fk$He=*5M#u3TNQ|{EJ(ALC zqj0lb;M=M zW=x$~n7LjTDJSCJM9eKKYZU$$ z43v)og)v}V@8meDYV4#5pzJ`%?+u2CG-s7FfsIpDe=7fikLN%cPH~mF`=e#?AOJ9~ zt<02v=mD5NFCW3+d4WJ(z{4ZYwA#ARB41!yeSMKPTwA^fD=fuRHoLGmG(m6dnqM3& z_Trzsym3gOs>o|d@px*HMdyvgb?2ai!B8d$Zt`U3V$NYa?$P?ZBQ#e|Pc_fm+(Vzu zoO+abLBBocz%&~7vIEm>=2ZS)%FLRI6OmGg==x9!wkk!ieS^FDG8i-Xx?J;m50w7${9 zNeJf6EuULhUYzZbtD&(q-unF6;|hXxwd3b|tHZuY)60qlqR+!UcIU=;@<;}uaoia< zzp!|W2Uqj*@?!d0JVBZ*Jl5l>tPOk0mo3X48^w0>XJ?O_u19N@x7J(f3uKSeKTq^E zRF%W!m6tcE#=8vTx7;VhR^zKlDfWemK=eYlDW18ZKr$K~?+?_~hUB?=Z$&m}6@SL) zKV$Wu@!*U|-UwHxcuuWd5=LHxzsgsk8w`%~%=6V}kMYd%R0TcNKJQ|mP&|img15e& z3xM-cQzQ2~zH(yRs>q*Pj@hlR#shd2Tc}!=r=Lr-xGKCMFZvy-sb_Er7V7l68X+dE zRP-rOcP1QN@ZQYxc`;R<>Gk0hi>xrY)par?#i8tR^>tY2q(#X=$)Af(WRJE_*5%Cu zImL-rE_tDW?9tOfBzQ@MFEDWi97c74Mw!CMX^yT?O3F#T&~yxUpsu>w7m)teg7(az z%pU8ns;%(&s{+B0r_Qg(EoD`Habs=yoQ3=vePbwlLTq>P%k##W^N*RwEBsZJbHVUr z7(?0idIBS=@QLit9t|3=K|3|!n!LG%#h#RaFX#(2=p|tDvUuXlb}U|@a8flogoi_U zvv)JWTp(j{KS%=0$;n$yelWW(G#v!CFo1MpO=5bGC(8KcW11k{11ETczU21>0az;TNWIc;9-TAc@zGX764vqr4uS#(4OgWc5 ze){}*oZNZ7N(Al%8pn(QS zX4lnnPKBEU?e0$pjaCJ*eoi3U40`5PdmD@Eu}k=zTF(hcJdgA*JAQI%eVpRanza>& z_IgCKF{0Hzzcrv*zD8O}!hK_SE$9J6F8=Q9U?{(MJUFr?I!x}2QxPd$=A_gr#|Nlg6d~*lsTr36%-=~gfCV2 zOa;J~2S!zsvdR)ZDGQ6ad;_Fvox4_%5(ZJtY7U?K7!RGlTq!JfZl=h>XFkL`NWa$hsjD^Q-d4d&tl7@TrJc zSmdp(^m(xGJl=|mm<1V81|Y3zAxWgu_Hx^n1ezM$q4 zRZ!sUQI4Ja>`4@fVBrC;Ee`dpWA#q3bzR3Q#45-e17*t7P*+vqvBdNuUo{9WZ@GM$ zExl|_d_39@`gSj#f}*3Pta2*l_*keKFh+yr^^KI^dU7a(POJ(b&I8mhz2MJzH5Hc+~RSb;^`tO97_-qkSximA&AT_UK9?6uw+lHTPnr^#ypxa z#SeC@woI*@It#S?S)M3%n(e8HhCKFld70Krj$_$5SEJZcd$(v!du)GKzS#`Tr^KC$ zw=(ykvtr{35hh;3@pBZVRAPNk!h#SRc~`4^PaBUV0Em3H4-28*TL}fo1A@oPLf)!c zSOLrp^>~A{Mrjv1)?u`4N9bC8;xUY3xBuA@cc2iv8Dwh}j4Rg|MKwl1^9F~uc3=e_ zMG1_lah@2#aZ;eF0@@~23rkQyY4dB|v!`<$LqNNlU@`0yPB1khZ*krn8$R%c5s>Ja zQ%l{K+|#tUt!|2_9BX1cd^jFBC0^rJo$4xHQvBtSe0>7EJpWV5U2`K^NZ_v5~|oY zJ7*H6%F^mY_}8X{>WV{+uzpQ~uEBSgn|5G|=VT|+6K`~m2T{zQS5zlB!;C;(jbLqa z0&|LmT#3GEy$&)ZRkm>w!D6av>Z`S&6|r=nfX1UULxHdlx-M~;Q({=oi9WwK zTpgNKMO=4&m2WAq-OyOTUJe^4CmMB|JlO$!#KEJxxR(ldsK!%M0WtwNW4DsxInfsc z6x2xNJIC*>4zjnJRlt_9!>$<*pFK9}=LD`g9}RpbX`NcTxRz=W^-+AY*_NdT#><0P zxoC?76G;MYnjbWAg?!-E(8htu(54(a2Egqu1U$9S>P!?&DwfeY3G+%oYq04pKiv}IL6K|9PDHfc_qQu@b?y1=};x*C~g zv8X_~F(!xka1GG0>L6g52+dNJ9vk!lK7bjs2e@+_swpsirYJKOQtz}b_6hO_MF9iS z!v`A#>uVNzZW~b3D!lbT%FK^4g_z&JD=B8XD)_w-&Uru?kg4#C1_0u5X#3gYFv4^E ze*B9`1&&ygl0Sc*2?^+_!us?D5Sot_8Xzha$15>Ed*CS;Z*#!!|3j0Ad|*ywh2>s= zY4B+1brc!$J^KzZ-owDxEvLs^ylt$lU=ZdN{|MTJG}1n;in_2VWWMhy7LCL-f=oR= zqVmZ13!964w38Sd?v#BKbTT$hhY;ZH_`x9>IKyKRqjN;|Yz88-US<&94zU>kF(!oP zQ%)%MHuz4dn?YX%xxA2n_N4h#yTH=`P@3R&y$RgzeU}^rK%trssJ&=mwrS}`L@&gK z@b2$v_-R`S8cw&uo+)StbowV~#MS!B7<>SeYXX;4UCUAJ2nHZAb9mOkc1|G55SbtC z;L9FQ8B+_TFjR#VbV^;`>|)QcGIOT@s>u^6jM?)8NrQyfvJu~Ii;HslwD4xF96Nn| ziM(L&H3sv>5oX0VXeLjghnN_MB|^M<`eL0OW9jH-+sUI{e=zoo+|ey9ga z%Pnac1M;6FKGM0+ertUAAP3Y>vQ7lY?Ov^bd(wui=V1tHD7*MUFGFaJ4ju>6MU61tBXasgi$gl;vxwaKZu|NCs?L__Sey3S1t57%eBu@z#d& z7Yd8eZ%L}?SbhR){6Wmw6JnuZB6ix(8)rdIoK{hhw+tf&39czx7DV*7*-LW*MxV}X z7*PP|7KST{y3VQhE(!aXSqLmT;4`sOw%}Y(F)ow2g_^ZwkDxAQMJE$GX%p`B{RA?&`#$hoo4Enr*@oAUX*Pv}%c|!56IWB5DE8P{ZLw3oM%NQ+m9dj> zY*lc!t{#Y?iHK0t0pzl=`=4KtvJh@{6D@?pr=~vCh$o!VYCf>Wx%t5>R?i;!%43%X zI2J=tqEL9#XAamQ4{qKRTs9+AWK8#33Py!RL5kXH1O?Tu2G$x+3}h{g>r?9Hl!vRs z78YW5W?%7K-x4xYhJ6)F%$C#Lw`%|@njh{KgNnXg{JxYBdX?1!G0?=3l&hQe`Yw&R zebi4J5}xw{6xWnpfpB?u4=`Su%&G|77MzJ)q=*V z_>T^fajcZ2>b@9#qH5~JOROJm5#M|Z#|vhUiRfEU^g+Pn!jUy$YfrYEcU+8T@X5Z# z36MBNiEWjShj+oZ3?r!(<08gAEviF_3(s6w4ca>qhSl6=@W_>mkcP4OfVGsz){ zdNckkLSB1LL9kq{I0I1N_cZ3?%O%21!#BkeE2g=bwR-L4V3{tvBNRNqr~ulz5vW9$ z|0a?qt1Zq8l1>QznHuAKKL*i(ju+a8B6gAQ6gnA%r5t@fE`cBABn0 zt7xj4JKdv0wWxo=8CVsX;RUh;mL3(hru{0m(y>eJ381oY7%To%zW95aK-1f{%7QHQ z?CD@>Dpoe#MErW3pK+oh5Jr$dBpuvVUso@xirM4+RIg27&kW4oZ*6@~r07IK!qKX` zt^eUXY0{oUM<`VMnv7E0_chKT-a;Ic4gF6$1~meuRg1hc=guC}5EwHdKPq}J`j!+O zN+y0IMjQpT_ehLi@%330U~kQ{Z&5c#%Zi%{k1T}9gmFSo!T*F?V*+%S#lA+3cE&>R z7TE2;2h7l>{OQ$Iz#{ZW&aA^G12WSV|B9d6WD?t25@S86)m23kb<9L?rM%io#P2TB z%mXek$RNoE;EZLD$#a+$LVJ!5+M*t@5Y%Q!nftvAsFjGRDy;>hKw7pQOzL8bGInW< zLxm-ZGtCb?DXE_*1p%qqNL+w7$@&6VaJ%%XmNzWa3L*>z8$%8-su9YK<-gFxd4OnE zhhjR0-qyb2UTdd^OrD&;#VF}SvG9p)T6#j3=h4g&+Qpr_wJIE~!lcllUa-@=%a}=^ zY1ro7$z#-hToEi2U>C75W+%)**UPdc z8Z(ejN3$Vim6=DAVlv67HW6Ojpbdj4`zM}ZMhQd9R;e>pxN z0kFl{8Z!|hKMJ^Vx>^Khg*}L1dCRe=S8%KeFX#gZ3~GRtq9ADiCsqX!l;1cbKs2uw z(1uP_WDF7322kiw9q?WRZ!Ikkp$;V^eoSx5?O;}NOf&i>MFQ1yx=~buVVqGAgBzLb z=X+x6+1dC?_@nS4aKI*V$0spq_f3XmGqb238CYBjNfBI4>h@~4;@9>b^o(Lbi3rCL zjB0~ZRwkboX~`ABsKzb+CZ0bTOeC-RV2BHh8bz!T@^FwX<(x$+(J!`_QKF`!h9nXG zBF^mkB0!#E4HJWnWQCHnoEGLD3f6L%5zH}?ewsm-vY5anA<29g z{#7Ip<6l627Vr_D8+a@V7zaeJGPUjR3nNOzTJ)#dVbWR{+P3xXSYf zwzR90r>hwP3YauOFt8a~DX@=?5@P(E3**4@KqkJR>PW56uK#a47N@w(pj)luUZ<$U+-o=pF znv@g4PLyqb60_~u*ZlTO{hfzBL@|qDn`8WRC~r|! z4MP%&Jquw-FHWfl>-<6_kWYukZIVZ_(Uv?MKw2Q8UBN?ZI>MYL+u4 zk7&J)3UTNQ2#HP@8D^C*fGz9D(4_yB`CLDDDsBGAPnU!~Csz|6n0qY+nGgyMcL$4|l zv7nPAW4cwfAsM0XO)fbCN3o)9dn4ii5R#z-5#~|(?z4Ht^~Y!v=%9AenOIm0;KQt2 zx}d5ew8%>QaMUkBG!1Pla(uxLO&YX2bbwJU@kEQ^0~Mi>St2pQf6uhyUBb|&|H?tz z*`pVE5!5O`7sFYzC&Z#&^t(H2=oG_D)w1veDihx*BS*ndY68Zmd#DLOk(H zU@RzCQ>}Q=s8(X&bzK6FwheVGx8N|E9mEMhCq{rJrQ37X!q8)ym>=(6Th7ZH8)x#D zCo-~i0=iQ)WRHV_?cj%6G{lAAO_%|a)XL-ujZ)G?R<0lJ#9Al-%gh)C1{P|yjGh!9 z51GWhZxkc8a7>jA2Zc;DJt?}!&TpE)h^A`tMJB}~GM4X;`y^)eQ+<+e(Byg0;MvEw|c3! zF{sy+IjMX9^|nXNnJIT*a`xg}4+o}MaZw}ywy}T_No*0rzQLkqmu=EI5N!f#<*IK8 zc)ayhvSSYBKce)HVmhPJT$oHK zI-Zjd52&#lB^K?a9<5V=30M*(esmL}Y*viRUb^X!m3hE30ksctm!FV~KoS6YnuQ6- zZ>Q~&`s|V0!({3`8g>U!PO1vdl5$>VgfMt%SO>;fHGu@VW+WAbPOyGo698jCA*#oc z_G~6Hqgav1SX*dAcmzVa$O~0M5Kf{>j=ONET5hxN!SyPVWq&QZm;tfs5jy53dt7v$ zxRxDzPZOpMi9DAeEO(v$u&W4={Z3OXe~bf)Sc%Co}sMA>;{xHOL!0!%lqj^vkNRnGDv$86cyaT*pQTw`lSd!wj~ zov24Lx+aTwNkq2NdkU+XcCCy-_5@lD2pG3bUJKjWd-{w7eRxA2~uq-CwtRg>g7(}K|Gk1c-zL%`bL zK7m$|5GQjU178Xt?}+rAYt~(K++>B@OF6y0Ul_Z0nwt1RWHfifhHL~j!B|J54kv&! z>B_yj4!}$wQ8&{iPVKQ4qXW)`1OOJNj9RQxSwc7GfPG3V$cJTPYwO^j!7h{9lJ;YQ zP=eR%sSG2o2w8^O%0A$t8`RGtJq+$OQ5Vd-|3swRmWNJ2{YZjwLDR2D02L(}O={gw zI6ZOk;awY-#GMhs1h`sCX==`lhzT%StmDOV^Jma;YND92n9Dxc*YPe%M}&Y#E2e8Q z;y%SrQo^*+B~yW|97DnE(VErn_gFT!aW`UNioNt!$ zK0w{GmAnI7JxJt{t-~C!&WgflW*^u2lQhd*E$CWi*qdg2wi2dMtKU7Bx64uoFkFUm*5ZU=3TfIBVImaFy;u571r8dT=ox8{_}pjkJrZ&#vWBOx&R$l+y&Cn*(6I zUPslz$tp48(@~k;jEJ0JRlSUHds~i2!soW5P1v9vaFfu5itIW~PkV3RTS-s;S}R&p zS_-nR21DAYA%a^iMR7BqaOO+x~#jS1ifZr$_+T(6Br$eF8tBHVh9x! z*RPS_Nn}DY%h)Q)8}$0&mUiI9`)liux3Z=n%UFaXy6&!3fI}0+KDyMCl!G=&qg-d7 znkzX`q|s=&gG?-jDlvy!4{0=d2%!sZpbLygR`_n#p`~?N=pEX2D#K2;XnXWoGMwPC zy@Lam(VhgWkFf^A^kiY5kPslPDui^RXfZdj*afRY)<`50GO@+DyJ&#Kp?&aA!F*$N zI5V6iCLYR+0MueBBK&k6TbhyxNRbj6Kvoi*H0>8hPN;3fM8#@HII&%4ItklPA|Op& zLVt+%B=Ok7dm=rTv*H1WHY<=2Qx2Y5fnbCaycHs75z1!NMmJ7 zLXMI>I;wIptLj8T>2>LLG<&RoBL&#sf}#`41^<&JwcohEUVq2x_zVYg9xuh-Erf6v zSv?M&-sT4T-770Z$Iji0NVNmHxOEj$o$?|<#P)lfj)mAj3O@?!hd^aHau63wfeG4! ztdiv3M^MqeSX%&w0#?CO%o}B(BZSr#gTgEKUg@-u2XT1ricu%iS`)%fPG>Zu#{`cPWqfY zJP;H~NsK9y%|W&s7x~-YT2*`g_WlM+?$;N1z&UA4BEMnp+BK|NRaNOn#Mll7nP>41 z;3W=!fodHv@okrSCp7mgK_x~<1TcgpTzCs*{vdS6#}3vl zo@nb+(^)Q zz9Z&fI-mZEDFJXJ(S~5CR0I=Msm}*(ti?na6SUiJz)VB2&*OzQFshrAB7(wh(M7lV zt@iZ-SUOuMd=u!&XLude{)1DvIq1$MFIqMO&7G|NMv{|=uNSO#I;9P{4+tMQa%?ZTbuj_L{V9AV5eXN!k2h5k#ukX&xw*67TSwknnoftujp&X z<=L+dYa^bh;Biddqp~W^CY)=#OEOCB-F{jFp5LK~$-M(C`owuZw87;DbQpRnWHq1S zam5^T7xsivKHTbwwuKxoFs}zQWSSPZXlghR1)%W4Aa25wW`YdytPWmLJtJ5$?u@n_ zXzYZFQRl}gQm=8H44(->`-7|>gK3P$WV33}L1dhoa);C_tX5ZmwKZTtl{Jdu6cn|# z4G1B=T(t~C^&zlb8;{wFn@6bMkocan1LS*Q7}ZYaID|&cPdGiuT(S7jK2L{+a5}p! zakRy|pCT&>IMi+qI!XCPK)i*nV5R}<%?-Ps7*WvhjX#P7CpW+8%VwDZ&cwYc$9_M? zrJ?mXFM*v%D|>OjH?G)Vh3L{$UX+6o-HHj1obKRSIH5&@Z&)G{YSkfxN3(D?M*qha z*idgPeFfRGYOn2cz3!-~Bw4sh5_q-2-D9V=tzJvj2Fm$d+p5Btl8+qSXBgmqf*-sY z)V=#^;GokL6u30&(?0^8`kqGDmKBLB)Rn3vEhgv;_CSULk`%&M4BRA`JtjBQ-HW1|`<3j>yg4snmF|!h5h^?b z2ORqLkrImnQJ`%?>OC+a%0f2@O?6RamA{fxmC+kqZG$wnTM9dg^fhXl3KG^6-E+R55NtZ=^twKB!5U?_$9z1Y7lX$j zgAb(u4>s^}F}~U!nI4zws98R9JJhj;R0p81?yof0lfbn&Ir0oj&pG;Gf!Dv zAW)T=bem3~G5s&UI?ddM9>&!Nh<-NHKeD%O6(m8SCG&5 z%IfU^!KZ5vU#V%DYIUjA#v0|iJL)q$b)ev>LJV8@w9Xb@P5XoieLt>mkZv6;&U?x+@$?o zS`)uB8^@?PKh>8y2Of+(5V|*Cf}z2naIJ2o1Mv&T+9!xKH^ZQDzpu) zw0UzNN-pUnx2l+~0J5w1xw7(`_h|BWabB5hF>; z8pj;M`P8krqt8@IKm$va2BRbZZOLtzTyJcCvWL!s!Dt_F=fy8^O|c3jum}9uXr&mVjTq%1z*F_wE)`k=CFq?!OW8tfx=tkQJ;Hx?WP;+!-E^2bb zCa6?}S;JU;yR6|0)KB2`Ad_XH^_oDt#1}}Npdd@tPOD;Si)+u}8*`LcP`Md7pc0@k zE(T)ni~7ZI*ii{BV_+z!ftv4tay2-m2v4;WkTw^W42?>&OU7XBR3h%?=|tZSRk-Fr z(5;H~h2jT$n_H6so4X8{9=`r@PH$o%HZHgL1!oDVQSz%-*cFj4BY_YI6%a<+!`l5bcGwtHPFj1XyvY zloV+Gu3ZAB`ajs;N}aisqukj@CB^9Xb5Vo5x#0Gm06iL1ZEkP~_TrSggg!~N#FL5P zp_6(=?kqP;qM3}{?t>(8gO;%~u!Ye36OE@F^E@~;#n^bwSt=nG zcv>({OnRT-e+6nQue&Q*DFjj^C?tFE*eF3nXPMe`_NxkPtB%K!D zAgKJWI|)RbHff%P8^xpT9OI{0B0F6k+a*O^483-%i{7)*Poqo3d~lek`8RV66>%La zBs{wjVovDL=VX;l6#RVf1krQOSKrni*~A7$(WU*ev89X(eIuPas$Q2KVrEeawBfAG zh$qK9@Ryw1RS7v$ApCwD6IU91XTK?AUH+p;sX@kqW+^I@8-9bcYwHc1#oW!x@f zR#&rd>S`8R_N}|KfV-pOf@g& zdBcNb%@_WvH1J9dmQ|b|Gno_yrop(~4(I3C zszf(X1nYT124(@FA55e!4Jj4nGIVs}6;(eViNiF9Hr@oe36tOvwlE~F?3LBW9{fo{ z?5ZGU9TESn>|_^IY>5&TXQzkVC*L}3Vi(!Mn)Hs2%9$?*J((ghM}_L4YR3_HE@!Jt zc$7=@hQXP6J$#eS0r2J3>ZbDfC;QE2v~?^dulJm&fDYg)>insMFSO0YoTlQCFH`Y? z9-(&MloQNu=YZo|P~%U3kM1H)Hwpu1<3uk2YC zR;BdAF#RS&v`7p@6cY-m&4h-hn@ zp9QXYk~WwmP_n^_IX4UiIM`qmzKykL)2oH*sm|(Ar1GVHPIPD^2R4I41kOmQPA%FupM5~TXcODN>xu-zYf(zIl@!F)Vo1I|L*iH&qb zcB}oudcDYj%(rlqG*-eKBO5H8nPAD(S#nVAd?MO?>&E*c3=bx<#H!5gw z2f@TMgSLVi)-Z>Y=t`g#X~+z`!WTrDn$k+!t_hq(>ojdfkbF}#CFroK!tCj?P1@v4 z+46x@Ap0Cb<_Zmm(zlV8<10miN2I%&Xj${+eXSHnge%%fCeFgQj8XP8+;F~`;bm=C2>CE9yUX?#Yk9pb5>(?9k)<-Dof7H5zmfPAVNiJX6gCuc)nm$^AD?EcJl?!BIk*zLN0EEHL+-!q`Mo8 zB!9nLe0dLwj%nm~7y=_kO-e&X7zDshCu~_`Esylf#Pws0&YB&OCpV!^%e$#v3`9Q~ z?>|@1a=pJ>X%u&_zzmB;H>(w82yVgwB&3ctQ$nrmNR*dZK#q|vvI!AaEaX{EiLYMAIXF$Fxv^^)tfi@NWbL+ zW$Jos2r8zo*UP>0SZlCP>#Hge4)gm=R~2G6C^2%i{-(-CD4v$J1OI+R^y?AtDgGlG_t5;x8GMr7PmRYgEAoFnUj7FM(A z-{-q)?C3=h18(HDBCXM~I77rZ8w zaWi;2GV@yo{8F&f{l12MrVoN>?od3v={Eg5Lu*WAE5WacP*yN!W=Sn9axbn4f?VKV ze3eST{q(%T0W}y?tcr2eTXcjL_d#Rm3q~c`AQ}zlaXPUWJ;gOtc*~Urk8T}B=Kv~f z5LEDxkWQWTwRQSL2sN~OWqS|~uZSiyu`wNuMSG@;wwzr7YXGiJMc*4iVR@pGo<#C( zJnHT=VasuunMPsi76q;J{XbbW5CIsGwJZc~WX5!ut_K~1RL%UKwjU8*`C^5be)M4v z#{+awnzF@=!}#F6fSPU{yFc&;f)Z?(Yju6ZnNS8W^fG4L_K*WY165ZA5uAGWP8eGU zE;Veg$n2KfWo)RC}ylB=&k3o37X5{(EB&r_1H0-2{;t$Pqm$l zg&+l_dd_)XnCm84Rt)tqFxBX4xkpDh42OVgIbio*BvHVGTEN4y!cO5Y<{OSb&Mb-z z5MmATRL?XaCSytMqa~+=+BUSZE~yArebB@cp~W~%0awA%vZ)|hBR6Y%2>QpMM~mBk z>`F+Bc;8dJoM>BxIgf{@FZ&NYqV(hym^Ygh-@jWb<(@6R=8bVq?&v@ThX$1tGV9G0 zT79*hyL(Bu5dRKwUNkm<9k(FC|CCN7;j6ZD2@Z}lGw2KY(U!WZp$OAh6-(S!!}0-9 z(`@$^M|O_H1X_YCdUC;TJUn@4vnyn6HZW6+a9l7~)umaL>}(;usT%u^;{-h-$HAys zb}0yaIq!<&wUxY`kY^EtoZ}Cl#$UE0Nzdr1gXido+K243DVeaKAlKI^2U}w>bc&~- zmstNH<+QR4-D92LXkizEwaC@+kZo-GTB$20ZiM#i{cj6QRcII1uRi$YB$eZNaW~3& z3!XJeDKM0>XV4plE;AFGrcdgPZ< zagUL8>D}N}?8bAHqQN~_e=$)3V-KVJ0-q_GZt3z7S}CHgyAoO?JB>9q!}+2i4kQsr z+S?tGkV>G+!deIM_^_Fq6-xjRELoS&PZ=IhBtx2*mGkS>CmgXW>m$ZW_g-a{aGUsT zS>%AGy%LKeL*m0xRVDgj(Zuubb0gyZa7bganpJTt#TBlF(9!Lt|D@8CQShT0=3ASy ziO}Crln;)gu&U9FHcmaUUe2HYOwZo`nLo)Ea7_*%IMXSpWHO1aNXf}doIyGwU`bGb z73HiF3LfDDvrA*|gGjvp5U!1h>IZc_6S`aESQp#xyK|)*?H26^S)G8G($+PslW&l1 zp@B_-g*PU(u+Zy*Dr$ zIbhD$MhanD50=Rx;dIjj&1$}#vb+olm<6Wb$^zA>(*8pQza{|ORB@lcdJcCtmgnm$sck=f!zVN%# z(cgX>pWB+`g$|lw9R|l^*b&0mjs4nb6syI){lVWs;U@JwB~i z3!%@;R&7{WI-0gBDfU{lnvDI9kh%0u3!R^B|FP!@Ghq&{FcK;+wTwFgdVO2o=4eZ_ z=$h3*i{3TbBq)Zg;%cD?|gsa;h_teKP8swp029~ED0D)E)j zlu<7Ac0>SLd+G<`hjbsPH<2E|ucWni$g}RVF|!U?pgYgj)A$n3GuqhtvQlvT`^V9b zIAiZgI}SA@;Ih$MbgzPPP`Xd3i@FM=oOKZAlCzQUBP;6f~7 z=pPM&-^7|)0+4qry_|rN!AC74Q0sbdVLvVpd19k?B>=Yrg~jVjXISVe`H-%ie*hre zs5{Ztc}^AV4z?f!4H99Qgc)^d9n@g*1z;G8#G@j9cd=ml$OU}_5)p@FyG|xKTYR+Z zD~FhBxD7$b{TkFvou${}J%nz%=>7EWmj^HZ{O1QJe|h?s{)2BX*PuP>xZ~OM!M8W# z&E)!r354nhKkW9)nf>94RME?C@#`!6|9kvDcN|Ai0HK;2Ed5 z4w8G{!is@puGd0^=BN2?a{cXMwOViSxzpiGewvk7Xl8QDufj!~eEb$~xI=7b*f^#x zf=x0_I?DMCHYSA8pCPoPVm)1bnr+^Wmx%KuZhe7iUm|DclIPN~gSf!W2#>5d{+1Q2 zVLQ6Rgr0b*DeZ^+l6bIC9y*osxzsa0+oywb<$a=!8CHCYkG;bWJV8 z@yQNmyc{pKvmd|vPQxIL+Z%&@vHYfw6+G(4nyZDH*G3@{3ihBSS9^wlW@$@70E+Y> zs=;JU!78iP4>_tsiX>A2M@EbO>8SE^LUY<__vr1 zZ~7(Za&;{_GX>Rl+Dg-&Qd9@Rw1DXf9@(CC{7IMaHF%+_kzRZe0+BF*EM?sXjc&%G zYmaNj*&p?_ECu~FM+j(Mv-*!d*)3H=ChGT znm`%?3hmb643N5t({}Voo-9m6(|udQHP+Cwvd~!KtuC`WFn5yzQQe1tI=-=_8JTNm zK8Hyjz!DtcYHK*9oX^7)p!AC)a9~9fcr5u_5B>=)z1lEI)B8iUHtqv|tE0{BdfnosXCpzd``z2KXe&J(KT!Maq}v&2+sS$@2ULC3$Em zcGX+cN!y^dWwsFySBkPIWq~yGkHU%s!b#B_dpUaLm4v>HYzxE(?E8(hj0?VXNP-x? zNLofk4-u7{2Q7L)E3Virx1ZmASMh&Lw}>>*RJHvt^Ui4p<#>aqHeSR5ObLWjTcS|R z`4~~zmzV4xX~Ze5netr_T+297M?L@w9TKNQ4ki3~%`DjDV;9mVl%o29d=?jfKxazX zoPQFD4Fp{KoWRAmHYjw<%y)k5ftn3$NwE?$Vz$O^hOMp zg#A<@FUH<9SZ2xC4u@y@03Z()dmyF%Q|vhSf}b{6A}y@yc0|&{;hg!=t|4v>K3Q>) zYpx1xN4k%MalDV=M>ZpKoF!C8X=XuXGz9Er`2v-n_^55tA--7ZZ>Fp%xOM*_ z5N+(S^eljreN!M4)Cb!U@}oL@WWZ`31RH~^fy`tZA4xr#`n|!+wz6-jr<5OkKKln< zun@}sN*XvYh_gT*nMQ8d%P?CpVV5SeE!7k^d=++R7{2{Q#fceCFkF}T1_C>=Wr3kn!7R|^nPWoU?e48y-Q^0S)`8Nk_KpYP2BCDXZsBj zxATb&8xF1vD>&8|QtvR5=B+r*U&k8;@OOYB@SxYrFU2okjS>XJDA9LJ2@ zT=Z@(Hh^`^av;qlZe^fJ6N_FIi$we?b7B}rhaQ_`_0MNJ^l-icbm15VIBd2>9H%;m z(>{mqetrIC_-gcF@LwN(IU9_Iuc*fY=CJP|cdr;N*;K2|4MHy)MbxDpzoOI2?dhxv zb8RDx!&}~8oEKk%#l@7NmEM9Gn6>U4+S~}3>X3t1CJSj)Ruu9x94ye z=rgr`o=!XhVUJG7&Bgp`uN}S=+v>5+Eci}~{ml}%2*Aq?j3nAl2_^!+1l0DR+h5?C z1S{0a&5M*H91RXQLz;g*MiubP4P~~ZoNVA*JzB{{J#pwv(W&3wRVZoX*}Pwm|FLIy z7kddIgyhRnrt_;g`W?vWvq==woEf%oGrmAym%#Vv$+^^z>*kQRFhw;2yo)fG*IoPj zp~kekRWpY-Q;Q|#!1UHM-nkjCOFcbUmZjaLv0wuVVp5xdd8`wYFw9ilAG=#JTL6>{ zYKz=Z#aKM+)jS9cK$d*t`~|jP(DDOmO?b6g?bk%?ZbsX}Wof=jAc=?I4D4RURH~wt z9#W|7XGGo*4oMVZpmN~Vl#G-P(0o02=pB!s)YqDjGe-?qQpphC{W78lN;?Pb-6u=F zrO1FV1X;L2zyT{puG{r^33wf>5{^C<(Hw)7L#FDN87fOy!2vxm2jNPn?k4rvd$L$e z=eM@FG)x9Dxuf?BS`Ls9bfjS@%Vj%1;CD(Kt%^ zi;L8S3n)k$T+_lBV^zs!>OwezVYqbELh5gR{9Mpd}4 zW<;UMxY_u_MO&VK9n?6|Vb=z~3mbmTrY1*VuTYhd$eub4RqvLV@^tCyNG;H?a$4JA zIGWU)PC95B+Vp0T(WrAX^AMWXUBHVM%i09EAOLPaA@?S+0{K_}*63y>QM578{P%Q7B1TbCz;@DeIQ*rN5%+! z>G2O7Z#i9+bXM%NO9(f){W$vPW=X_@VmUF3dCBgK8!8pFk&+#e9(aTkoX`O{5JSyGG4W zS4%GbZjePN6}s4_XEfvzeMv7yT|UgST)*# z;eb7m<}Bs_7Gm;dA?egktyx)R-Pu|J3~|^Jfy53Hhf=n6u^bE<#1E z`LEe(&08crPdzv(RgILE3aPYDOP`Fw!kOBFtiL-x8KO>W2fh-wIJJrW$M~i`KWm`? zz1g$q)l19xsxLi?R8J|P;UiK&?@Z}3TaUvm+RLL8XcTJ=PA3h<{d^=&A5O2-8^V{_ zLuyGRmd<6D(&3~heG_6?c1}cV$4k8kG44fJ0fmt%=SwLb`95oh@wI!PgrsDG-OUXwnTTJ5nIYCmD&~sUMla^=vD18 zmN3oNut|_<>S*E^CAbBuAkpO|2nZ1fCczV*MYl}Jl*)o_T|5LV2+$}}aRLoVDSMJ* z`2+AMD;>49Enp38V8H7j?_cC9Rm;pySL;1y?)ktVo&s31X8O_}R;zQQ@k-qr9zt&P zgQj}}MF@e1mbL{(^Z9mwmJRdmH7FdD&3sMre=jp|-K7h~RCFzWF#7+VX!N$rV6F^b zR6n+&y9=%$=%7Ivatex++wi1w^U(zs83r9lq;oSU2&uL|;uLmlNXlZiv7kR)?R0(! zA@(bS*0%!VQ;e?+^}|Z%-7-tnP8V1OmkuGin(41viYug8!J$inz~cDa?EwvO-mvaK zKc!DC>>$pt%5998;V8g3bW6HXJ(8qJn92Mv+gMN1RE3%YY5Qw|#s3lEDJ8{WeP4Bp zAdki+4K#$y>io(5>(B0A-x^g(?TGHLa2)ioq02c6wga7_jSQfnP}KcJM{*0KOZ9lS z{SDcthaB=~h5{#vk3Wv!lTO_`e((O}JCq<_!&)*V1Xf>qm%AC1ZuqjL<#u}d#T;b> zrqJA7UaRO}u(K7FG7c~;sPrn$IaXplFXs!;IhM%c?wYlidRUqc58pyPQI3B3W%+Rl zgoc|Pc+9OR1L;xE(GvrX3rsO1f@7BHOq3D(9P7JzzdVP{MO*(_u6XgzSvZ&vNsJ;m zLe@spqZ&R)>gN>pA1KO-d$Y0iRZ6}vhJV-7AK4pZd?f)KR86KQ3>{ffI~rdcqm0Rq zb#!4l?v1x+s}v|H3v6XVjVCy=KGZM<{cZ$zgHg%|;YN;o{9$9#J;oE~hrjzS{rdtt+Us zIT|-DG0t>1mzjRDSO);n9rIkCI(jz?YflrVm!MD!YH$irg~~~1#TR?A**0wXWXWsv zU4)CX8*?n7nW;sHWO6;4+>Y4n9h^1vHqe%C(7fMNBU>{|IvgpjYPH%+?L=@Os8Vf+ z5GKM-SQ?>7OCbIZyS1-x`M&wYXp8eakg`8}rgdPmQjdb$Cez~JPU+DS8XCz<${CwI=7)*4 z@}+XJaly_zi|>RKRFJVYM-Z=C&rv`K#qkN)pjtIMWQ{W~eRoGq3K-CtR~R*Ch;Uu& z*E^aU)=!@?Ak#OB>8Y<)_?e1fk9n_x;&t<9AUEhZb3Ya)Av@pCMJry?{ajYd24N9t zsBOXYi~S`?0O-c4Hrm3Wo54h#KGlJ*fmX!;3c;nA&LD@UJJ= z5ME97JB~7YzoGjZ$Xz3rEB%|1_psW~0#!AeIBK%N4(K|3@o~HP78MOFW3#i|%!V+K zcdIv2%H26k#ca7nCobc(&{7=0)gm!nTB6;oz~i{>J)cfh@o75JJV6S;OPSVB`x47Z=$OnHrriIk|4o8= z$>B-e_Moi#$KDmNOcz#&LA^7c52S1bi%%N<`i6;}4y$NmSWv@nLj*oc{Ot6ByGVuq3UMW4h)22DB`5YeW2fl_mZj zJnZI(kSw<{bd)rKiGmAMx7AEcidqU}s|c!RHB~9Vq-t8(ydblZSv|G}GBS23?_zB_ zFCU`t#EA`|viEe!Y7DDrxUGxHC6K5gH{eofk`0czr*qGt{EI2>5*&R<>G7}EMR z2l<-^f^Oc=0S;)T66>_p;8m&c?+%w7xo(Z4hN7fLx12_n7}R?`jl$>PsdxwNjGS5q}301GG;|GA&-9TEkM)zrLlrm1Yw9YYo`3K-u4IyxLM2mNTG@19&! z_;}J{?Y@En^ZM4$X;y~Tzj|bwOvY9UX!D!dEqo664jO0@_-r7*qfl_f!7jcjw}D*j z2s=Jy5DHg85F9_5Z;L`+&b(A<&Q%R))jc-nW`Bdi6%1Df?*%RIH(N|}m$vM1oh7W) z_Zsh~^VR6r;je?AU%egvgt0kVcfkIBVS@yV`lAst5tzMXkw@vypg}}06q=Jp zwr=EE+T97skB;Lvla}1}pHw7=AQy7R7Qx%CbZyb(ThQ7L4j)H0Xx!V(u5|dJ{3N<< z+dm3>`kANHKiQ7YMgcpvfwl!^f$)e_GcFlQ3>RS8?+0$Z5*+Lx+ zr`xho%?xwiO|<@X(=2!K4&joXo!cY!mC``IEix3LyGK~Z1OpT(HwP?hmjuAdNF(o1 zN}x*3U7=L&n-urrrpQB~uxPUDZ&8{{VpLKNj9(1`-;On^Ly(!@T=eDl^b_pC#F>EL zRKU*TXgmx)G{G|)&E+4s9Z$uRGHE%gF6XJqTU3346YyvQ&a7h2aXi%a5zdk5zeFGB z!j|cAu_)T;d@^3l{>ub)@o)cIcg@;Yha+U0_{64ku)LjbR!eDcuc@M3*l2pW;;t_A zd<%_Xr&jq$!rfX*xr`ZjjqsJgzdmK&6{a03;uSUYwMYXKjj%VWh|jak{9mBue|UcY zFkeqdIbf7VBR+D(Gl6)0w~G66m24^Q97+-65hkdrwp{}v*evu^++jYnSzt2Z{A(*K zw6=~y?Vxj?SCm$mt9l@7iMt|k@0rTRV}K+qT9UFEEpWR-9Ct)zt_1TZu9m`fPW#*- zc2=Wna>K^fq8lnQYCgpwP+@O^_8h9*@Ki2mzA&ka?p>VJ0J_NBHBZb zlps=rEq*)NBWq+^VqtObAr(~Du(YD6j~<@Qgbo(v9}id84wA#Wgv)im2Qh`YDV1Wj z`%N*mZWhc}vmwh4XBp7Ck<%9uxwK58@aJ zu)sQ>_G)c2*&8{~LFJiWgnK=OMym?;AV;O@OYo2-QUPD0CcydW)yt!Y{YS~kYhFEj zAS{TL>AS)KO8|wRb0Q^9s3ycXW-Uo#Xi_>`&`32CDCnf(%(e0;7pe_|_M6_$c#^)Zm!eb^FNWUMnw}B&pupX48&rHz0 z9fQpE`Q!xpS8oyWFkTqGwCib7flr>GmV#tqgie?qx&|+7hYY01P0H4&NI)eHc+aZwcR`e=9zoXVV7RRz;pt4fE&) z&jL0IO(`&#Z43nwfo?BdQ$DMu zZ1GP3$93dNjYQ@Bt zxL)iYIQz(zpo>q4cSlV%noeYpC^Y*aWqnZMaegW^89cZeWl79hJnbYvfWjIT;KC-u z2Ac-%8XP7`UtGzde&YjZLRYiR&tudKPEPk20fuk!Qs#wB0uUGe6|hPf9yzg~T^@`qn)C?GTqeLCjsv0Co)NktCsMv~7IkQ$Z(7Jcwy zzr(=7k-HOMamsJo2^k#+|oHj?Qf>*oAWc_jDE&_f-)m|e}6L#7lsh+LLJuOHN0zd?RU zMVNH^Bcb35#~w0-c3$STaub={_ZTk~{dRz@MsclGyU#zP;i?hZ9w^{AP9I3F)7S7T z`P1sdO5|bm+cAfrD_Scz4W4f6Z~QE-6_-D7>~HXC`5kimD2SV1!Z~!S;zaPLJw#tu z_m{Q%GtWaH`Qe_8(CA#Iu&$P`X3M#pf1W-pL2zTxl_#_97Gt^aHl%gCx2dWfS;c3A z>L2(r=_!C`4N}B>`W!QI;-<6qUA-Vkx}M;)d#_kUy_V=V&|o5?W?xt`un6Ah%^1BM zuLBJd3YOmc{og1sBonx|jdp|EE-(8u-Z}oB@2a90Ue`9bmuCzf#=dLtE2ss(UcCfwmTYrT;9yNQS@3XI?NNAC=F6sN;;SQKyMjfoXy$l(#IuNZr^Oxyx8kRr%-{@3 zjg*(0sv$GoU5?n$*`0HbVe(s zk8CWOtnSakUhu&P1;;%-w!l0+e;r+k5vgBuw>zOm!wcwRy_vy5f(~9zFTOA?#2+Fp zVV>s{RjfBN@6zB7!D=(^b+<{a#s{$VLGa%oj&;Y;-QGFzMk@xMY+yWIv8jT6Vyo`Z zVp<}pba~&P`UW57s#Kq{w>6luexR~!YN%h$;Y|=0FZcmwQGR-3R0U!Ly&ai7yx<>NJ*-daevhw)zxPj*+qdB2 zy6paldM7)2S(WPd``!D?pQYfHOIkT4HY75lr=P?J)4e6{)cHBjy^F--H{!^;5X*S` za(FYoGFXn?A^(1Q6YXuSG8MdC<{cay2(qYGq1D5eDo}UTnL6RB7RCsv#pZg)3!WOo zS0lKFL{CHsTjczdKtWmkVz<&LkkgmOwJ`6Xu%)77MsUqtqL);NCve2vbBDK2a00hQ zepx-vrp5tQ5Uu>o9sS2D@rt`0A~1G*a&P?WneNVTDzR4|YRvv(fXn(zn)lb>+MG;$ zAYCzF3FwaEmmOGR<>`K2tv>p5=pM}qB=7_JOpLENo!Hb7ns5mhQ?bR@;4F-{aMsu- z$NoAL{t@vxyEt|qskZd(@tySbQty${qUJQv$H4=O0&!-l$%A(f>2EsKcOba)lB??{pd^gqjP4I|$tn%^SVrg~nE_Sx`)$Hq}T`Y{%EZa)jG2`pLYhT`9x| z%!!Vr08??<#JO-Xg(o1OCazNUwTyOh+CP?E9uO?hetawS!*p z6@wobNW`pWd@0JAJMF>a>5G+RD!@bI3*wa{1!DdhTFal`zB11uAcc`%^D8`1MW(zr zWE{b1??Un=frH4y9SErn{eoAjt~j1GFwE+s24CF7z%M^u zELtMHn9-shpG!`>dk)B6B<^ON_;7nre%$5-zt@aO_1MV4Ph-IFM%CxURYT2co?U%` z@DJDtyg=Yw;9ddtfj0=&=DqavOizPfZhYG4P~2W6F%lzR4G~5^ zktZ1^lKe8rUF9px3M9X$_L2Q`PKaMMS1lZGN$~udE5ap`tEv-+M@rI6W;dV7J!N03 zPXsy&8wDU%7>!0I9z>PaN8Ba2b0k4Z=+hU$;|CuzN?|y4;^{sWi5(-69oz<=HA)hqvqRm{Z%1r`9msKL%w;bg;R@j|2fa*w%4|;jD7bKd?%*S_ zxA%(vv%Y2gz2p^=*Y!L2VRZ#IphiPytJTe~^O;YRRssXuDtrxATmkxd1Mt#4nX_y0 zfuq=&(-SNud|=JPykw8`;2|>y*d|f+ZT%a(+TX0jdGlVQ{K#~=IKt5r=lmM1v5)YA zhlq~~x47uR1>cJHK_wTW0nz}rWWV;&s=lIQLL@ARD(?8dR!|djB=~dNO)(Kpf`?0j zN6Lgx)gFMd95^Q~L1tBByi6su*9nMOAHCJt3c`17i66WYR!Q%G ze@HE#Pajy}7c@#>XzqzmrdQo9cT+DeQ4D26KHZBH^ZBrH!t5?YAURl0%3LI0#>F+i z!(aJMkx1ZuSO*_w!C(%^Xa#g?zTg%CFDT0#E<$j76|c}2#s&Pl>Yt@M6@xwrpUfTT zr5Sx`PC4}0Nt9ZzQ+nd!CX4~RWvCaut2JvApEg-rh6QGFgcLFEa%85Y-dpT{=-uoS{-D4_fDDL|H1L#Nc2$E$AZAnJ$_JNK ziF&^XGba3$0sAVS9Byr9!ELP(0DJTzc@P)*SFoV?pzhbTvP$02|=i)_Cad{v8CsnLFl{ zbvOQy&=B$6U}cT`YS?B&WB2Ih*oMHIN%jPn@S8LGJ0^}oqTr<1)&(ly?tp!>`l`pOphUOz14DxLA$yt)Z2z-nlsxuo$K^U_6xh!Ixq{tXM?A8M-WHM zoId1Ewix`Ky<`lO1eZ*#9PqgiD>fI)XS#!{=wk9D?YHX4;hUAGE#f$uOk=pr$C1T! zK1Rf&GJ^@a@Ph*9_<2DY-C~rXGAV3 z6zr18_t_=AvcDzS2Ft|d%K1x9%2LA`A1S-Y4DHo^yDvHqQD~If5ysj5^i@IJ4GyEb zhCUgPBuBVQzZkEPJsNmlHn7P$jK(VpxLVST*nX9~`l}5~Zp^zyF`|(%hq0zvcpLff z?Be^u=`a{Ko~f#eR5hDFMMqvJjQB%vAw8Z3iwJ&?Pep1PvKz{)+bKP_@>iey46YL$ zf6qtq5*>W@?QFTneeJdNt7kyMon%*E7TTeZTz02N*9ffJ9Iqa*@(yGGZJFDD!kYTg zTS)cu3yhhDLSZ=+y6Ur5R$4*2_K>EpRXX_9j0O1Sft?Qkl8i5WM_(S$5BIyR43%Je z1ytRmIe;W#KV!t&&3OBfH6_;@w8cWhGyFKZn8U~0?lv#A>z9`O^P2eTB@+dBviX>8 zs``C-esv3NAy-3FuIXSJwB#C%7T37h>-p!|RByz3P82+IT0I&ta0c-3bb`Uh4@VzH zXmx_SNS}W6@fx$Ll3}MjghUg1h(D~TL5SLD^Itw0tC?9GjxuHR@D%vO^}HE|WtX|Z zcG_KTa5En)urMP8Y^eVoP5S(g6dYF`x#blx;t6l{*uE8(?%}02taT5^4se+LsO=oK zaHx7uUU3=`7(epfklw$qHY{etgiGX=*`#hdM|WY6NiOD7`5od*RL>#Wl70wsMPxS? zA17Lv3SPs=NQjZk$8zc67Kh~pbjd=*66^O&e*eGF@y*C7wnhJM!iABG;Dpe~y+UfA zZ2K+0;<^BGKfj+KR!40+c6~AXWwX%tpxH%j9(yz#Ka$&^Y6UW}!8P2Q;ppu*TcBTy zFXjQT1#7v%=p(n|<5AKpAROI@hTpi7co%w48gbM|^`?vY=#tabaC37e@i+_z0ULs` zE{$MD%f5aqSQbBR3K$HCj}QLu|A$h>BXC264w?SZ?h}G0G?2llTF}ylH*ao^j|OjU z9v_|HzsJv>@V|Zh=jhSnCnryjANL>OhdzIEa`f!v+2bci&-fdD?&$IH<7Y=tAD=wr zNBG;5het`jb0)#bwwfdAGd>g`5XPU2{f(5s?r09 zJ6+w3#uIW6B5B5qYlxH?X)@<<6aK7&uQ7GN|L`A>y4_|u!B$T&%sZ-@9gVJ*dz7Gm z{_eXG8jBF?aW|0#bJxqa$dUm}J@nmYzNDuuKF|ix6qw#qLsNYLqnX{YU`+GxBzH1- z@M^YX!7gXTlV8nFEI<4p3n}y7?4KbYdttir1@5GtT{~z@3JdMWXuSX2R>fBoGEC9v z5~v@}F>4<_0keWupcH+$Sv!^##2e*>c$N8bB}VB;jgp*(P`qy;7-Og#o&@BV**Cwh zN|k=ci}@0m53edFYt9QgrLFBk?kc6-2SvMf(t%0ll74^JN6`Z#>hf@#yk4`vfgrzh zQKa7wdN+w)hpiMPL$AQ^6;|BZm(OBxW?QZ{JubJ{Y(GOK0K>6G7{^#)pWp<5{ZO`c$TK8=&>_tCinJ-8`5nX-V7!;7NV!$bf2)6|LJ zbTOVzVRC;#nnbX!(J9-(UauC2*T3(>6R}M~1^ve~WH3$E3ykRcchckNnekcLhfK$( z(#o`^x6Rd7J#wjxNTBtRw1KId z9A`a1R<{1f5BH>iu$PxV!!o|t*ndTxlLjf8^T)=|Fi5|SBs4v?U%kq?V+(Q?CQLi0UXyjnmg2=E8wVF zpF(kgo^2nus-F?lp{yHT4Bysl?~$~_R{gg<8ubVIQTwS6D+YpFcF&eCL48P^<~9hb zRssl$pr8eJ6&v&!r`BimqhftU2kwq8=yV2kxx1bt_TDeG*3#%dD}1^r^13`&2%f1b zWn7S7t$&Z`vHuX!;tnm$Vc*Plg-DewR?y@r>9qEHH0)%1HvS~;PRrsumS26pOQ zm}svh;uS^o-#mzZYjfar7da}g%rt2yH@)ehGn%YUcu07vZm4R>1uuk;KO!E4g;0MMxI_RV_AXcZ zjXi#7a+`+}*}C`l0cq1#m zZQF>)Nl#q}h7=vpQ-Y8M$V+{AQ?oHPT|@Wv<-bSK#t05) zw7~Wne!tD*e5PWP`ye6AvK5$V)Lm{h!&32f?q`2x{bC#wkHEEnv@yrBRZwJfF}uRc z&?0KcgFk!irjq+o@?`+dQ!Wb*O=&RKpwDG~&J2>`_KCHl281yI|pMYUVHcWc@ zhB`T$Z$x0=dd=hCGRg?)9P>JByu%rmaL4PL3v*C`?TU`Blw(Q;79S`RXBS`@8ctfx zoaY}~4Q>`Rm#&ZO*`q1@7nz|uW{sXnf}I5O0pI8djg|36n4yIMIN&=VcNr~Gw7h*p zn(vU*eTn_R=SRaK-i!ANKlN-wcu5vL+5mj)eAn`cjxbHzG&G zFudVu*jL)UxOA~!uhud|jC;kG3P%SaGr!gi1}*pfCC)!6f|5LVdA|FC(iD{^!6JoE zgpa9g!7G1+c6wNTr*4b;z_!q*+zAO>P3pNO*1*95N$+y5vjFf=uuNeWv8KzSkD; zdIG=u&WYDI4+?+ykK$kcBwl+L(bd5YK#kX5pyKdi5-QB;fz>@liF3`mA!4Uiy9 z-Uthfd^zg;v}vljvavQzpRT-7UJ~sQvF#ulalQV84W#%+oo3l4DpE!gvelGh!w7<&~HgA{CCdQbjs;+`M za%#z_(-GLj|9Ugl+GhCH=&jx+3KMhYKX3g7k%bw2!{He4T+Wws3?|w+Ki7Z?UBxUq zF!{rEB*T1+{x-)%47V|qNcXF~p`S6#UqcL@^^b>bDlGH@ z87v9s;d~k=ApcT9&-2jaH>n+&W=G>M_Rm`X#zSK@wcILR^Ts=J7Kn!*Wc^QR_-~RF zgc?q<1DrnMNq7hjly$~=VhG|_yr=R5XcV5u`Gqa!{U~c2}jGkGX z`Il=%zTVr#vRfZj*r5;d)=N=w0(uokI9^L^P1IoFMwUmOvZ}bl$HqZ9?QvF`e_s#MXr(+kkQPtMo{8jxD`wcRBW_t znaFf}&a(>3ZfCjbKtc&yaU66)O@jgm#zen|uI&N+kSF7=g{CQiip#4Q&P~TD+G1&V z@_D_QO^H`FNj_maZrp=CU!pW?=$$t_FC<(%Xo& z_F+rgl45M~Jh7TAebqkTD@GhxHS6z(fhfJ1=wLTpEFPlRTF>B#{kCCnoeonD_AciR zGEJO8gDiJ~C#kib<0K}DR{6%5VKOZR`!@QhnCKtr7sT*F61BQGs~Bz9#o>uCcUusp zSBlc+R>#H{$CgFx;B$glUJr*A?228K+K|kILWN66au9Q3p;rVuIBfl?$l7l@sT?>k zp~}fEYhKJO=oo5%rqj_jAQG);GSeVTX#XVa8wqxuj$?$u=~V+=pI2BI1Q&t~jjq{^ z!}dZyMYPHbZN6JgFQIV5qr&<|{bM(49W?!$kbx^X!sCECqZ2J z22}=7^1IPFZQ0wLk5Li&qQKKbCvYQc+(A2W+)LkSHPVy^EB=940f7zolB=k z?m_x^`*FTLMtU;|PRL=Zt$oKwWRu?T5NC-Zx6x{OVHW5}G;_Gy@T)hV61wowx61%I`~s z;i(OJd~AWUe7+46bWD~$le`^yL3-l`JyGz9!K^UQUBiPvbMPDWUx+W~w}@V^C^8Is z1cq`xTVvD#5;pWQQIg1TDV*dfA2rY>Rs?D%0-f@*4~NbT>`eikIM0N%(CnKBwMqNZ zYqSw_%+=NX0DRO!-`K#()@)ag+#qI$VI_^2+bUIW{KO~Mpk*xOgBS zc{6T6-W2^g2Kpn)>H|~?=AEOx67Uh6w6_*?19%N)0iC1zkh#vYZkNjxwIlIykW{xh z^;Vb9pU~W^h!{P9Ro?{8K@dUy|T471Y2myOJ-Apm8N*RylD>Hs4+$7nKhjF0c@ zUa6}~AUyCcpnye>I^YQSiiVyYzN7I)YYX@k>lCD^BtBu93MN{W_Z+P!{)tJmB9B71 zPzBlHk-VPDX)(F+=19C%U(5Ot9 zE(z6wqziMei)C{845)@|Vy|Lkv3ed6l@u2;RVf&ncUQz!w zyh=DjALY$b$nCPnts%Pp38T3EB^c3KZqvq+;Y)9UWuj=MC7Z&Vv@B*^5=AFf{^ZnK z*p22o!Mhan3+-wNf(_7Af}-+j>V9nvS%f9#B8V!p9-`tdP!o$RFo*vIXoyb zYBn^=outNvP`nNm4gNS+x4O+$;%zQ{!y+nj;@WdM3x}vZh)r8;0j#eZ3=}@T*!{qQx7BYl3FTd7p9dn#md^DSuO(dnv$xdhwIVBK3q| zY&7&x)xwq5x+vP%1xm85_-|>29!=1q-SJNzD_jLngF1q)2;GI$(;Uj52Dh))??2F$ zGVVmZKi}{^wK$pcX~7^FS0k(4~s{;7hxH3rXcKqSj4Z zvml~V*!0v#Kn9_#@VR@WxON&!Sh+KCd4#OO5v!6#@;PR^E)kmR5!qTF-9 z9bcyDDq)&F_B=ggkDFL+_&~dO@yhb)r>{*wd<=u4!H>fg8<&rS{{4L zzfq6M`Z-vDK!S2P-2yUX!!o~qO|SEKVx7A6Hbgq@QW?(A(UTgVFUkg-5qmxvo&BDT z?M7pb0a}LWWhGnui?#nTGTXEawX8cd4;y34C85{ps67&*LL=a#*X)N`pir;n_CJq@ z4wB4Kl`{AU_%=$X3{r0?f)}0M%JNm2wzGt@=ny{PAvB)c2bS%ibxc?|RgVwDf3p}B z8d;7PpT=LdZ~@Wzi3k?LjPXKcsL2`Z>Zhsim;ofL&}Lw$q8M6ly!st0pj8_m6BmX< z?$Tf|xNRW}{n22cZonUsIgK_nHiXW49gILgHyoy(;AFLAVE2zJ{J_vEG#%&1E>y*{ zI@O+E2bb&0cvuC%qPt{qKMq?nlOxCXsnpvi>CvZ|mMx^h-0Ryktm<({&2DK7L)!gl zy1GjMI9;HzRhMEjrN&!koBrhJZ2F_EC2M$d=bNy6Fgk}#QY)zfi$=9BA1GBFKwJ(1 zFSLf;ADYI8R(H}U(>Pts8BOpelC4`Kj;w#tp&vdwLq8vbZCKjHA4k9 zrpT$&-yjxsbf$k18e=U_?aQ^G)C4NEQ95Fq*60dZC=+NY(khaTaqHT2ueLygy@zBk zGOWEIg_8ekH*~M16G&(uAPYKL!r4Ip)=6^&Ws>YV0uV)MUG3#Rpdh*h&)dsfKu_+z z>9B;CP!OdZ09EymfS({+FrVx&9CC*>=^$+>F+T?1qe~Uutx)sb$u}>=W^m5?A+75P zqJ4BUbye2~z9^hT?KfnX{^aN4n1>6+OYwEYi2+w5AC8^d?HI8#-I7bb8Rt* z5CN!v8+@L87y~@K;wDD#kz)#I_j!GGb>PX(<21*Y{p;SNwo=V_eU6T7QN3eK{A_R(9hbp zY$~{q4ohws(_1TafO8_5Y76Ro+w?rmP$tiZ-Z zVMNZGji1J0`3RX%=G(TGMe`(u6eL1`+P}kC$?{|=2kbWiCbq1=br`5g z?sSb#^&P}c#7Oh2hemfDq{Us^_JkzawB=x36v!f8r)tq&DZi`<7z3sP=f|`QI}1ke zDk0;83x9&L+Z8+M4;Pv^YR23(X5ajm3U_m5W?Tb9=$B9C(w`Ysl^Jf8bt}mBkGfv-0#R_84b(9`BV{<>A~)1)n`|&omp}kH(G>@<0IjJ zT5tS^5`wUus(&lWVs7ES>g9JxFyYQ3mh@B z6eK+(Yn5C0()M{zi<7giRx32CWS&P-*Fg;hwjfmDC;TK`iX_KUi8xG>FoO-0)r7tiNoD5|@KTuEtlUaD43=6ZP^B^BP@gp;x)+fK*U|f$M7U2(3~x zZ0*~M-<-eBVIH$H(FM)>7+N7U%%U7Sp-FkaF$I$}(~C14)gzV8uQLvHl}Xje1^(Rs zw=P8S^jl1!WrXgd%0Nc*&Oip{iW@#7?(N9=aL^0n!%()QqEGlW?L*^C7Q$BmYI9PA zKxi^N!BkB(@I-?$khb(KrZq^~@|dR7EKWv~%G#k7*np6oRyeO+&soQ9?N|ElboNE; zesnI>@%xt72A*d_$0R+d`R~-URPwiLI^&jb#oLC)Sb7U+_o1ZukOck5^rQYZ`RCz& zl;t7?M=a-r70`02*Pt=~^lGyLwQl+j75GxbYG#cvTOyDy`SrG)qo;4$J}A&xhx0g9 zTSqFj^G-P{(X>&5dl=fkWx*1s*S@o*qiae5LsvJi$f{9|tubpUj0_|^0;73eN{4&F z{L)y4o5ADY)7iQJ>sX0R_I_Ie!qc}7N{1XEc>sJ26B+8XyFkH*Lc{gu%o-`uqxLq&nLHxGs7q^X2{K0j0VYeS!vZ`zSy$! zTDv;nwEk?dT3)52f_(i(t+#qlp@5OeT2!yA+?vmO#dJT4B(l@N|djiEl1<+Bv)_AWB(HvblwV7n&bnyZ>2ipFJ(K$MJJwYdr4-ZEupnP0T zS_RnoKt>gRmeYe7IuqbGOK{-+@|VA|WzK5(*V~Qz#~RaOHl}slUnc7|JPp6F6=q6k zcRPgXHd&&+v$(!#3pq0q#%r`LdhqaG+byBMxM7sGT%(F>I8ClxQxop`jZV030ryBt zc)$|0t+5MU06?-_6l*!_=Fz$xic+i}0!TF-nbi$Tro~vp(OrQklf+`BB~z6|=}iYe z2~M^g=VhyzVxa61+}nJcZie6=HuGC_FOlVDhlm8l%`0QaHfN21#-;8i2^!bKbfnEV z&d=sAdb0h5@e60-NJnKK_h~B24QWaX?(Be;Sic2P*pEjl(6n-JL~YJ3I zqK7@yFEB&G{k@ttE?*TEM2sCQmnRuFtXdr|`?9&SOC zR{>vmyYp#U$7(0yQMj~GlWyzIzq)v{LUR+$lhCHsy+2<5dPcv={UQ|W{AxFKppYw6 zvl^vEbq)r?o3z^&3meoUi;VbFcw1J~&Acu4%+)=NITZO<$oJcpu%Y8t1zqjif75t+ z%KGr9AJGz+1e=>NT8E+4GIhZ4v=C?nz3FqD0L?GC%TU$Mu8=0FXMp65T?eHK^vlvY`fC7o}KD5;ZtNiMt-ZPD&VWP_G?IKbd)`KU;Oe(cy&sYq)=IVMy@!^QKp{ zK|$_xv|Dko4mc3Z)$WimJ|C?nI~J=#E4k-*_I|(7^VCl}+DV+$AAQ)PvU$Y(^YG10 ze=tPK?ZlQ1YNH}E*SG)hCEOUj82W%l;sPwk&_V6A`Bi!R9qwuGI+h!}&(# z#Jl7~NFrVD!m(sQBKT4j$jkNX9t--__Q%{)K zaWWc2#fSM;x6KcMf!R1HNSckAk}Rc;0#{$p7Hfq)`n*MUKT$;xu;kSUSBz*nvf~)xm4( zzDPZXtpV{0=;TOvm1pOV$lhzHHm46tev1eKjwQTgbSPQ&v^noN(w3B> zoPp4dvh?!G0UcP+1~U6_^fT16${$sGOU-T?16buw02ij{W;NX}#J-)+ab?uW5D1>^ zhSLE+-uc-F!Gy*3d9k!3L0_%*=+higvI1jh4$Nbh3O8k?UM|b8TdN9$KcTs$SQUuh zp3{BB8(9ZI>#wci2Kc2rtR8}OVD+amVXc1*MemJibpqe!XeI{^6jt zJ)DUQ^N2DDKbk;6*d)AvPS_x(`^Mxz((ohO;Cu(O4#9`<`VxP|zC`77AOPL2=2K&| z`zK2!iH{a@Oyk}{y2x+0=R^JDdlT&p%jXEbH#C_-DQu&^0lqN7pg5hGb@J(YOpfbj zis*PZ>#fIgGj3;eb^)=S!ILtfZpo=3<%xaD?R!I?&Y_2J;N5A}uXb2CDvI`rERuLn zkrW%)nrM7Ib^#iXfo-~13GmJS7DUr3NdpPjig5!5n~1LPij2;T-zCsS6>VuxwR8KU z2P=DHg=Z^&L4e|JPNH4n%2{r*DLBP2CAk5=X{DQyFcmk$h<4%|Z;mtLR>#>Lc7Jf{ zuJRYDLBrbEHm7&e_eXU7#Mc;6Z`eLR#+9L)7q;+7cOQ%t(gU21G8a6QG_z@V+ObMXhLm@>J3eLM02fA(1&0w##6A_<5D zW{@Z-4KYK`f_apcVR)FoNZh>oMow!MS%_+GdiA1g2JbCpA{a@%W4zV7T&ytk-Z%(b z&T#K-XS0vfx#6JIg_z~L)jE};5OPkX9T5Px7@mtNRp-*y+eKp@Dt6d!VO18a?Q#_@ z-ONi{(8K1SfG+K&3tWw_;U70RU{2y>u7_I?+d4*kMEBbk%QV~$IECxoYWErf3k+By z!-q(_qR?Tq-fePl6^>*IY6%q1xo-MS9j$nd+)?`RcJA$FEX?%ntu#UR;28+_*K zf$ZA+@0=<2Vq89TR@d9((e3a>owZzc^uA1kucYfJdyYmJ26hkk2vv0ZgXpeha7TW` z0lv-?(+!BNOwZxkeFjEyIo>a*>KCw8=FoTcELa0?gmflF&I~Ari8rO9_a_LosZ0r0 zL-5trb_DrZ0uh;!_krUj{wPy9#tk*csq6#B4KvE0gD=0`Z9ZRa464|1L#>pSm4xh0 zltlE>A1HBaY!GF3?~vlztLYKV+@ac$2CKXNGP$_RGa;^3e>`mIt+Ua^`uxH0c?#KOc55@@1U{g@&ZSDFTED{O5OI z&#(6DsMfyflqTs!-wNP>Gh3JmBiaqwA~zOBcQfj#WQs9@%IGpZ9nI%fioKMuhw^E% zcIqoe`BZo*>A^HoYGp#BN3)T1Vr~oQL*dg784>f?f8v$+i~W3o!9eiK4o?K#pSxlW zc;*RTvO$s4u{DaIs8*e-AjBC3VQ3yj_3Z#Zf1EAWM{g-P%z71F&=||rqT=fD@!F{D zQ<(gGYtN4@nh(1Zwj2g!G)3NuaeNR+D>zXJM2fMJH4LsVDZ_)bsYg@JLUBmKpNGCs zS1~-$ZHvq98oPsqcZn@`D{-(rgzE+N6Qa!+oED)tF!BYH%vLrSUuMX>pPMgwn7oD6 zUKKo34t9Njq35j&7E^9$71gg)v8zAny#lBL3POCwN>-|F6EP$05nNX@FGj}1(ARA0 zu2*X#6eXZ9XUE@NAic-r1g^}DiF_GzWHT<7umy!TN?(P9ei`n9ZT4n5Y9N}BkeZHj zIxCQmcEU^vxh1GUvxuTel#q^aF+e140wJv0Zgn%CK;whqz&8^`yTRC=sM{w0(p^zG zs9(R`KM*(&`0SRco6$$~Gm27SM|%vR1y*@Mp3V$9P3yQW=d;DMnwqPGRun*$IG3pJ z1}52Xt>6%R^T3oApO3baIVmBRSnPuqGfdD|Vd==##ZEn%>`;+3oDBNZqn|L|dMRWT z91O9s0tMyM5PB*5V)~OyIGFqVXtl(ldkPVhzR_3;22J>vS+e93rn zw}Q0FMCn$%g2Gl=hgAU^b6$)uQu;~>OKddZPcb-mJOMw5ib|H?4&*SqmboXdanMav zRPZ2b*WNOSi~dK`xBXjd3l+lF6<$n9o!U-al2aO-a+>(L?Sj`v_bKlh=3&1B+Huff zj0is_Xb!_H-~U)uPOuHmJtpc=_tziM;h5w-tHZ^1yMzIs`<@Kva;5c}LM@k_p=0T2 zJlVY|d)CF262(0B%o>l0SkFu&MLu7OF{|Z@iIZU7odSFAU5~e(ya`jcK*atM^a?0s zL(6MH*eX8lfL@ztYiZMAa4Sq}zlsxIJiNlzDv=FP~$XJEtge{KN zDu0H4&$))~>$t~3^b1^<{EHB!ZzHtjr5>Pyq(VmoWM!(_A-z%GYgy`?UbHKag!_L2 zVWieCvGn7c2hfg+e6vAov{c!P(p6__{PK2*#wL$!4 z|GqV9fTQe_Nmh?4d&@Vo<<;)mG(KJF)8oHQ?N3Xm z55WhT&us&aT5V-&z0xr^`AUGLCXSLb1*Z}*;zKKau#b5^ggZa`hxu&Y)VXg4XJXx%!%I{nll3Oy1zcXj zVMOK1cw=VB)g84O8w(c>@hXVXBLkh2NE1v`zMu~N@i`zy491-W4&Mz-# zAZURxnt8lus(p~S7)~G;{lHuz8XlamfCo+?B*v*J9C0La@NqQk((UiAOp=}=y1VU- zkkoi2)>5>7!|TMVy#4)}#yH&3Nz37J+wEk$1ka0*6Ozhk2EuA;i;6{#Ku*3L;E)xb zg2t#jnc@}ZxJA~P7GlYt#QG+>v0thujMJyTvUMtlov~!FkbG47gD@n^kqT+8YL6B#R5DkBYHiU_k^3G zuVR+Vde|kE-f&5SEVN(j5HClW==b-)!C-iLAlBLM;~5O|Vx!1@!XTWD>2XUYg8rMTg*{hXh|TAdFX{~ z!+G{Xh1$+fE_s+jke1*7y-LW%mtQ;P|85zQ22A0 zJr@FZZ}*c4+B076E$QyCYbj9oi%<6*_)OB1y(QvQ=UC8wSK+2~YfW?MOeGT-I>@41 z!fB>}rLQzwd}hVtLrsOglIX+i&bF85}3hCR{0YUuGB(?T2hW!4Tr4) zpa+r`5que52Kc4#eH-4*Bb9-UZdZbA-?ZioNmQV|>jBO;+T)xTsuK{qO|kIc>73*L z7qkD|ujqN8`^QJn+86VQbpB3-Pr!s^9EL^d@8B0=nc)VT@KWPSIGs(CHAXL8o2l5| zJ7f;iHweE07SVUavl3@_Emt1B04?2zpRM;KDxWgxcd*LUtbf2p83sZdoKYKAq_i zpsSEJTrP|1kHPdEJftd%gC3P~F09$NBUJ2LSK{#9DC=4%f~m}&A1|WGpUrZnDx{TA z3KER6SZR2h>g|VEV3X5fLnlBvbdn#NU&;I!=6g(ppDBKQYTJ8QZI5&3kIexMJ0zc` zO*uL4Lj3WJgSo1O_T?L6Px_}S5_NCj1xMX7rh|tu*w991$qR2o|I1X7V4v( zXLBNA!o2-@|0tX`hiMEEm2R}%*tAxsfZ6FtVp8%#b)w|oFQeSzBG)qQ_|U$ zQ;u^QUy8N-I=+qZdcMxZg|W}37mHhBqwIWPkbKSNRs2xp&-v;gz(ZP_B-C*m#DyL9 zn&N<%=up-v1{e@8BSVw#lc(u5FOGb!6MOmcKN7H;P;o-q^d>>euP3k3?FB6tW%m`) zFfGWIvn$VJQ3Fz-dAg(=LCyYs6qc3Tjygp4#&mj46SPHbY|nYf9fiIqoaTmGcLsx_ zVnLg*7j(#3G?y)^ShT?-DZi%rKOaf8w9-&TpTsd#Cy;dF}uV=Cp=|a{wTJ<#n<(Sb`!fv{9K58ZCY9w#S*m% zA6~tkN;Jk^uIJ#m&bIo2E-r!*ez>_eJvI3A%@udMO*+#{ zVAiOUd$2`8Eb30B1>X9LIbvER3rZGJ<>*z!l0c)Et3Hlu`l6@|T%d(~f&iC#RlQy; zZ*`Ar)qu+*>IE7c*GKa3*sbaO3cy$h3;WY%gZnr@aHrfO#TM`l{$!)58vLQWGy_&* z+>Ad9EkV77A&aj==e*4}*WIDG$0OKdQgK5jJr+nvX^!Wa+oj^&>=tDb|7!_sN8=58 zZs3|-4$i?`HW-Y6j$hD>=4G-9+J^Lr9yofUJ?4K=XJ-Hoz0nk#B5GR zXTM`z34t1iP#l+5;E;;}56rweo2hLMW>;vWXe>o%{Pk&^$Yg*F&WR-#bw9|-1f>Gz zQWUm9z}K%ie03@Xk-D(2@_j&wba|RkgD31Y0u;grfhFTyQrTRpl?rl}U7N)Z#K|{V9F0yI2#gUBt*HDUN0BVs}?A-$cO) ze<0i+q%y6pG|2Tl3c9f#04m=MIiloVT*Z*&z}zHOtwD5cHtF6nRB8;ll=&J^ z;h0pZ+=*x=iX?_ktS}}YQrrYLt}!%44FD(>9Y{?u1OFfd&+sy_;VfRo>XFA2N$z6# zh45}$n}1k+oGssfWYy^GGjNvPr80MHgXxI-Eu}-+^Ni9_L%B%PnSpMMW(RDS^Yxm} zWSSEy*rIM8Ab^s1%o^SvP14r6UM;q16Lt`3#@HKUmx^q-9R~ovD#g*+W&1O1Xz=Yc zMz^BlG+e8&p|c|9Qdn7Hhj!`1pxwFT;qS(YKv_vE)h^&sn zX#!yXBZ>22bozRJifO0FR}e`DLV(ugXe+$kA@6)OxIx!%=?NcP=Dh9hYsd_>k6;BYx#}TVxId_6=pvo(p9CduObha$I?s!?xA`n^kH|JdB z{wUpKMTpvqZimSya^(Yk#C~wNaj>m-_5JtIJnUVXt)C3k6Z! z84XTm#|{*c#U`&P_&k=A&iEWOx>^Eb zUCz-j*c9T1?ReVjj>hqD)qc}iwZ$cb`0L2}G&};PJh>)C$YgpuzG~O9Pf22AwM*lw zI{Y?Fd7C{`RYpJSc8tOrG#AmcmfHI^XC&!Hp}0iSYwIC3h_X8l1lT6G7rch?3zIY8 z?2(4F6=%QAYn-@l+VFa8BZvm|YKfb~=FUOp+b_W%z+4~noix4glt6c&aR~cFU`&p5 z*r|_=>Ryx}T$qEfV|b*bo^6t%l)S7ys#3__&7aA5(mN5KJKTAXuE z?$=Jzj}!ps+J67wKkNc$K=_}DQyf@T~kv{-!&=#++Ll40;yo1|)u@&*8(=La0c_+YTl z-otZfVg9djYH2DvEv-9wN^>6>P}i1Y;&O*11sr?rz;7F>Q2Pid8?KrVVl>78UeU@m zQc_fJ5RrWUjArKt0+nUL zu8tcq`2AGI2maW@q+4{{{O8POOO(ekwR3U#c!!-SlX_Ad-VEHev|bG;lH_02WVl7V z!vbrDj9SJqJDWTlmZxvOEGL80$xW^#{Ya+%!m#5)LB**C&bZToadX-dAnA(ln`l#J zj8`rV{mdM1SuI9{00{I2RExBXkkuVxeC%5_)^14_-Oj0c2R0oD0XuR*dC;hDfIq$$ z!{jPRJHT?T2W(N%R(wG{UG1%gCrh_>IDxaEVCR+6=>ZmyBf z`%+ane3f)4(@w0^XsA*xX=BFRQsLrRgIKz0oML8mTpysdAMBtE@1CX*paKW)-)JL& zTEB@wtl-|rG)7oEi4)?}d%V4k>tx^9DZ7RwX)cdxuaT@8_MVk|+xZoB{PN0H^W7P! zH=t93xYp#ERTH%rbfu((je~OSw7WzOehyES^c5(rWCaVnuksf}*Nv7(kddwU`-r8L z+&f!u=hAyygvWBjIv>WY;~1jw-TkqaQ%1xijprXf92ih5s*5z(ogH?p5GAk*gtM17 zyUWG+3XBZQ_%W^qtrh0qR#Vum;yI2Vs(=gnsG6VaI=<}51_>>+DGo4f>G*4Gq2lqH zc!-1k!Xc!(kYKN&^LUL+W!#^NoSOdQ^5&faDkk#r{{tz#pdGC-`d&2!Pa7yM8xwRU z(;?meRv=6$RmP(g*ZhoD zn55qO(Ie2BU)z!fSsYW>AQcjN4$MGBIR-oz@J)q05@0;p^laUc802OI6nJ3@B|cw% z*~ZY1p*t7~+r9WK;Jpl(GlL36PcZ z${$=1Rrw1KVh4Ui2u}wu<(>dHYWfK8s1*TlZ{Q5IodX!$E?q!GG8GH2#0ddlxXtuB$w>HRBLj2AqgThzSXH9$bkV zNDRSXNbH#K5($@>1cFRRt|4E7xK4r+NUlhDha~r3Yp;Kuea_jZUNho`?;7J-wR)fZ zTzkFt+G}g&vC%fsVOo>aTEApRw&fDeqEdHDVgUnRNve}GI2)p^Cb5ed@pWbq0vqlFkyNPP*- z|Kg2@Lovnrn>XTkRkx9hc0q5Eq<*5uX?DA+biruBxelrD7FRTRg=`+{t%y4cS7qmT zCJdu2Q+(r&A{#AD(p2=J1KW& zR$`z_=yf5Sz$3DMACH8o$e)|O<~xJz$PIDqwh_Fi(c#`Q0^640pS(EX=zE@Yfcv9qi$`>v?dLhv&{f!eRZViUW zy@MUR-Di*3hZB_WhJ6q&bFu5+zt?k`00tmzo zL+}_qt5i;2zdjp&#ZYMS^QQ69_O`xdx*a^ri zF&;&!eK+MkdC3h|Gx~z?39<_88Wojp&PFp`u`J%uDg?+%NI0jC4BOIY}@TI#KyGE#CVzn&lqz+6`}jZSP(jY}gaqy1!@N z5$sVIPD8*%vxLDtir`!o4RT`CZgHD^S}|Q4Q5qJA{fPP#?WpUKg9j1?FdYzyc)6;#y?4n@0A?pcB!n(p zwdyuLP|+Z_|8%3xUe)3Xe}hW{9jKm-9ohFR)y7IHX2~oQPn%gzVrdRo?x5aKLbca> z+w%A{=&Y1zdl7v_E?&tqGa;!(k<}utSIXY=E)@sAbHuTStQpOlxS69^qzQx7gA9mx zq)L?6n9DlsHMf#=pH=w zD-R`{&>w14V76!9CBckPfKvhf6 zOjyz@Cg=^$rm<4W|E|#&DEU=!0bX`=5p+@`VTk#Bcd#kcQ4XjI;w2Do%50AWOpRy~ zbXYAjy$Giv>2_=23R9nVs;FN24$A4`4HQg#B&sXQZ~MrX-=joX_j;=fHAvgt3%3x$EKV)((KmqiURJ>OD0tWK4#Wawo>|8EN@B)h|<+ zZQ;Zz@vf+d-G=iwbzPaMP!iLV%aiAXOvN}jLyA!~HzH1o1GdfGjYB#lAyTH~pWDb+ za;)g16<#Ckv?{{vftdUChFVE_Mfq;rA2gF8gzmofwYT8ddw&x$_TcI*kBpF9VQ=pi zWE8$-d$8V>--?7fCC41E#UER;i~3jgc8B72Z4ez3I7AQ?Wonyc4@Flk7#kkgKg%8kpwc1NDQHSkj$f$&7Sv<2Pc7*G)@&=pf&5oInFdU z;FQ0M+2hGLngy9{w~C&=Kp4yeNN*#jO8BpBg2XM~X@Z=W*Eu^=qBP>5hz6!TtqA=| zvr}ymX1;)>cT`vknMiS;2yU60+%$o`fLFIj;vq^8tRkN9;e1b2U?B{#thyn`M=ecE z!<cQT2>XBSMGhA9-Uta4Xr_&l<#YI{tJxn~wgRUe4si|ovDieV)my+1_6a`Z>!&Cd4 z2qwf}gRgx7O#@O8SDg0YVHSQX4{b$`s|8}0Ezlh-d%-Y`6Z&2XdeQ0D>0dk^a@J9i zZrnT*eNtq*5i>3GWB-Heb+u3G^3Xp*ua=QpKm$`v;M70I{@ChmkNR_qMfme;zFSQ` z2`(Yq_qJNNj82m}JA#Ean|>BDH3J1jQBce(@^PM+wjQ4$kSmnSTT54viO@L6{KkT+OuhvW zXn{@aw{{RKP0^cHBn$1ierOrLjJ4=~4sW%qxiE3@Eg%hy0~Si{$W5O63A4WN!K>_` zD21l5xof{$-f&H8zqdKSReeOC9PYcd-5^4pgUF6m2We`EQ+HeXVA+q)m^Qp-%~m9l z_MzfcP@`JA8B#EtRE3E(D%kx5!PnS#L}WHUoQJt+67ro+bVIKs=+hcg+T2&&z^~kg zU(Wi&&zs~xTorXB!+0Je$>pj)#^+WW#kH>1a)k9fjf3x(a*@RB)s;Lvo$3ieM z9W%fr7mdU-s@t;JG~}a=Z(BV$WdVuJh0me-Vc7k2Gw2BB37@3l1=Y(3B ze#51FP0*;y#4(wwrkmOs3=8)=^pM`>BZs2{dv$A$>t8i>q0Sm2Yu*1y?$8ik)VKoS zPNlBdBA@21EhIWV1TiH8ACogTD)z+BKjdLUyRv?c~b*MV4) zht>4~EBO^C*bMje<C2j3j**`}?Yb`6Nbc;AlwgEmvy} z#q}Yt1+MJkipbjT`L(-G%O{I45#}q#Tp<%`sHJ*wX{3-yL)}n1w+!iKTTr4^u1OpZhL%upgTiSHA+qI* z^P7;i3el~2&0HcOnUBJFrmHvZHBW8ivSU0|0-ArkIZ{Qy)uOAr8lDOQU*sy6D!vgx z#MuDu5;Nd%*xSF_-9pk;$y(ars<*Y16`Sdf==G(Iih|uaC8T_2_2BAupRbL>v!Z)+ zEkXGmjqiJ4{Smwjs>c`;zrmb%!Mhx4TvO;Tm2I zM95u~U)S#Za zf1f%5SVW95z;D)2n~+2w+1v(KBt#&}z*BvlB*_yO(VukdTZ{@GUy7S7yQ#yH6iGDr z8;VNR+1}K-!rwmOruhuaq&T0Uzqo9xH!dvo^5|4wB;jICKDoqNPxmpqlBMSee1iad z2C1v#An?V-8RT`?<4G;_WVo&c!DjomK@TW4Zdw)a3%rxISW!vBqdoBsI33UHI0qHy zfc19Hg;w+N+FvG_rj5*`umsOUqaXE%n6(=R_kp99+^AS3QPyHDa$<^Obv{d7nhIGj z9m<8{W15lo0S5VS?Y-Iw_f(I|W1pax_zF{Mi`Vqmnq}ffX%XeI;NF8SUq3*InAdva zxnClBI$qwSB_>NS`^JuA&F3<^X!TTcF7d!XLk?WSm>x<)k72Y}72A+br-Z+920qL) zxCT!@tt5Z^NBi#-x41dPgMbAYcf;F53CReG$oZz+_l4Z7 zDj`!PojW9hr&ow)yt>!lKu*)Uw|9FGIurw`jW~&YQd+<{Huysr%d# z4&7CHS)g&llJ(XUhALG+2SNS2SLgD>fs7>hrconsvx)t4H6>(F^2i+;M3S!1D0&}P z7k78My^RfdNRh%qZcM9aMdFK-5_%wxTFpI%G^?rP7g#PlS*UzIO4T&G%AuiS%w;0U zTc+li!9g5E0$5nl=Y2RpMpL&kJa5r#(h8)i!QVRiCS6zEYC*3}GHJ|4>ON+Civ$59 zk^q2&Gq22cpZMG|JGemWUhS!pxFNdF)j7HibtsOVozRUSXZApn!6Jkn52Lrb@Btvm z4;~`kvpaw^jO-An4E?)tG%TG56yb(Av37Fq0~8g+LL}EYBwB>h$~QI z{Krx9_(F+n@Fm#hNIDYyMeM;o?)a*oc^26_X`YauC-q*;q^R|ZppipU7?`|jH#;My z$4^MH66&;!2oTSk71Z&96pZbPmKUUuZD+<3HeG0eY=g@htAAHX(oWcpK`tG*(g5E! z{;%Tf#?y4$5NP7}7CnEYPq+AWh0tw97jM`#P}lm>18dzD;vnzX-|t-w6yG_{lz)h| zgv?nMbtS>^J4d|SE}ZX(LXOYUJ9y*`>P$o|b6%n<-tP3!x!D)m!$uQ(c&aSG#~5)# zjF471dq<-1Hon0MmNq3={kR0XLQTdCCb*Bbfme{hJVySmhIRpFO^8mAlfGJ7ooFw+ zB`C&BacRO{vxefcvAeBrl{VYR6L)iTs6MZS9bUK!=M(kmp25Z8zMP$_7+NkD8e9jB zwO`v+lZ?)ZV_Z6Z8hYa1{_b8+veU_1R}imqbOn~K3TTMnmYb^P4nm?#d?H7&x=Um; zRE)=?b_MnPa3JUMXYl`eHeWj9JBN5)*q-MeY1*5i)<&8JuPyD;kP1V{+m)E;EG)gz zCwqd!@}-5Bhi4?V;iL&C&6cvkq(U|ZL)j*HDcDC-*O1*_Fe;eSNllp%+nlpp$X?qY z`VhcoqrKQ$68K57WdZFuPAeARLT$dhs#uAKW#5#+z4 zf>Ku4Rg)~VPW_|a5sy_&9p~#_cLpY}IJZj{hdB#q2YW7=E)0ZlrAF3p6}|zD1gAM> zOS#fJxOB(4V*-0fRfZ~{L8LW0dsX%xzjNgcFG0>N$w98ta)ZGUxLQ0Y^TRZ4 z>6Lo|hp5biC}EL{Ub2LQhqv_(j9VD>=0x{0Ru(2s2aC~kj)J@n26AB;>%SCo(<-gh ze9CV?CB1#gd1wx*n2_SJ(T`Q^?#7Zn4J3eufeUMqc@7D!6MU&MQBqz=2C>}th3utv zS?2*%BWny@ynk`Ow;kLFz2U*~x?Zo5X^OO;gqy0NhiK~rh_AOj?p?)e7VkLhi7s$} z__Cu?XRK1C_)vPi3qwW%zcD7nJ1;G%?9LCwYS5WTON9mkD$aR>y6iV768i-U?(-zM z5v;lDwK-&CNo~oc+Or=xLESyTWqpgES)}(yQwSi$T&TMuq`L|>{e1ilCybWQqDh&d zCf+bWT@D`D%t@5hyywEZ;5hDuyFp=UxG9oLNfIyVs;Fgo2)1i^xM!-M;k6gtKTG*t zdtz%u;Rwnc%KWBrd&_-7e~08+wiVyZ)e9a;PjmwVC}o<6s1!b`-j#d7&S2s#4-b~$ zrqMAK>7U|3Rm5bFT2XDMVMC#olgF1@%Oe2FTIN{8`Ph^s02axsEW5Qcy2$e;E_VZq zA`^{ob5G?Y=mfPG+etjxsjR=?IUD-M!3?hhbK+3wai-sPJUF+ z;PEo9+!MwYD#yd6lN`lMTM}F@j?yf(VJ_y*kv!u%b&kf-$;&|k`i?BkGQ_z)of}QO zFnXg&+=lN%X_M*cZ9&@+%7msfV>eE3^!9oih}eTX%OxavZP!RINT13{9ir%(1VXr^ z72<^%Pcuh9Fd)rbg?@yVPr8ON*&1@~EuJ1~jzNK2nrJL4Ye*W4a#n;WOpxC`qCH^F z;-#R2)SUy(3vzo8r*I|P!P!~Ak zqw$WKF?C7&iR{7B5k$DV6z|y@I}V4M1w~I3n5jbpk-o9txM8Q0gU)PSLfJe4#wbKm zIB~*Dy1JdQBjNb-H+B)0B?+zVp8p&|HlCe$G9|RI@o!M)D8HSR_z8KKF=2sSXohC{20TCp@|a^ULcOL*6;;*u&<8s$!%Q%c=5 zO7HBA`e5$hc=0QRjWb+}31}?oqK;Bv;+~nA;5+jAKoh~kB1=CfRw7w7Ra0)whE3^f zqSpiOl|0t!Mwx}IwXFpe)5fK&N~J*Oj=gSV9|d!85gVq+`PN1hjUi0QI~57ghB_)K zTqHkfNd<9_2*?%g&qwZu0ns^i7v8}dY{0{?J6zcXbae@-^DZx9xK=zLe7#keq-l8x zw+G~r7AWbPy20Lz>zMt0(d4_^8(lE2uq^9?%>knJrN3|vP^?Pqfo-kk0)cKLV!Bp4 zAE$Wd?%8hPbuu^;?(GjR9$cC*=a0aLt|Nu^d^1GM070*eV~D)xh)!xj=;)9XWrbzmCMoYRv?ji zrIRm3@Vwm$HTFCe^U@9q8|V2Fk=G&|XJjwO_a!$Ayk7G7U1?J)O%{G;Q4?hvoki=_ zOZOB+YI>&=S%)eJmxt$i!;Agf2E&8b_*r`C0j>0bR#g;h(8=P#88Nlp6!Z`JJ+G^K zRGECRpEp~F+s*}MChml90glQh7bqVWnpZa9;)Q8;U222=^xQm}wf45^8$(1@&4Zxi z>_K|PrO|nJr+XZD(XrWh1)Bf^m1`gsr9CL>TL}2tZ7LAV$Pv_bl6U5`4&s?wrM|EjKgiqM246GZ3~$&`jvNMil>!lejRXsS_=h(!?B5&{4zr zYIpaLr!OZ{I(u>!Ci}D+10bd?MmS3>R$$5^*VDeI8mKD>j4bne?QW%npK^7TBZSvT^iHAtsIVrC` zHH!&0R~|S^4U|Vi1J?@d#pA+;S(3K^pyBACtJhv8I@1e%B%EKCMa#6Vq^}swIFQnz zqj$cxkrrf$m7R9VCMQG$H=V@>DHP>fOESuaS;6Uj^7TpF@Kk@+iClBBh%t!UUK
      Xnk5BbRKRc<;(VXd_`>=QC2#Z6+U)B)8OLX`u>J`UC{w)@e4p;OZ~Uaa|0V z&muW7VTN^`8d5!dS zH=36iBzh@OTM=p=D76v}hZ85`mJ&Dw)`-1WG68TZg(4vy9dcJFTMnx94LzPZUxJH8 zEM25yU&fg(M0;lsFYETl16*g(y{6Z%4vMS_qE*59|EBIT5^~}{Xf+jLs*O+36Y%#C zc5LeDMzx? zPyPOkNL*~;kaWp-c&sUC{tDY&1JEUohyqb1kge+|Z`w5{5LHd@xXN_9dM5Pzj zSZxhU+lBEtvPwms#z-c`v0X{Ig!oRSiW!b0N+m@b+_`!eZe53`Q@Q1jsS&{Fr=`vM z0K!x(Oo|}@pwdhc*VU=~8FV!GRDcgRKsuN1x1r#NoApd zw?bc*nE%azv~y)`)vOd1W-^0z*A3lQ_{YCU&naYslGleK!LG9*~y9&YtW7(VW5&GfHhh{7N2V zkl;iOjJ~@j2krW#)oq=_ZGFsv*R@p5kL6Lya=R7@2?7jE=tvQA6*y4k^1&3^jI^0) zQ7KI|c_ecw7G193qm$RW(p)c0iw;_@e4eX9M^9Cw03-jJ`|iqG>BP-~lc!4ZwvHzy zCLe5?J(&J-5Oo4(zs7iDSWQNg==h~$gISNb5+MT1%N<-YSw0#rphZHo zd_91cMv_Y>XQ+JWGt-+mW!nyJj5!>Vys10mq@R-4!1m#<)u(!NKNSI6dUfJ?SPl4O z5Q8cS#c^{qiqgR9x?2g6>~I~59gW!Z81LsubJ~1NA1k%ZcJdlsQBN-SqQtn+t#CD) zN@S_3SBN46BNwYm6l#kEN*Fgys*+pJ$w4-3+6G4jyl?KPh&*&*je~e9ZQp>J&)UD{ zaBEL_u}JGaTMJ%7^enF2ph>1dOWPd%k9rJcAbNh=usGDZ;7fucatTKSm%9hMNI)#< zU4_wyftzij3RulXgXs~5D*I&~LD1lwusjQ*qqnw@73RQGV$H5aMj3w5sU*23XS3;W ztYIeP98xyX0=8ZXY|MaqSPKOLNEFpO^r zDmR{S`I!a*8xeOpblpRev+%#V?vqlTfn0`65kDixG?iy|7P|+EtWA1k5{N70d5}PH z9LDKzjdwyT$;E~3HC3q)4ZWI#v5}$zNlnuhlYJ>%`f}O=eJWhjmeo++suOx07;ids zV-Yrb;~S(dzx^DIdLA`a6^W6?m4)OgdsmC7v1SiN`cQ}mR?R6EmgTZie-!T17jr(1 z3rh+B?6ZqFv%1vZxC~VbO4shTyb0Wt>2ZR}6S2!QEm%lk#4IC*a>|0g^$6#BG0_qW z#Xh=68$2$&Ui3>DDwf6P6>Y~Eg^;GM;80!U#1HJLd7n&(WRN|C>lA?^o#3^q|3yPc z)z&G?*J*4hFK zs)?XDbe1X~#qPvy=Xcv9e{D%^=dl8#u~m(?QT>sG2gIB08uuD*TWI&=^bC{sZJhIZ zE~T>W#hZ`)YCwOu8@)8mAp>WGh9WTVr7Jc$q6x$N-h~-p1w9X-uVD&?)Dc>YlvV8l1*Ke<@iAN%!VNc2rB@Al8njaFBx= z4ZM9`1ZHWs&oc>8{`4>v*L9`g2$Ge)-0y4VO6XG)B7s~fjC3fE`B+jtJ7lXnnYbd< zNI@b|y6cC7?E^d`iEx&UOBT^m^Gr3cilx0~OKZX>c9=0Svu$^|DZo{X3OxSnd2b~w zc4F4C#__vVN0HjlXF4(%JAnNZc17g!SF8Ea9m#f_i~&h*kN6$Tq_)%0A$SrR?u2^R zN~z;Y8@9H%ja}oR(~%D|>RC2pAQ>lCM`7kh$2VG)Y(C8^o~qiVsBL(OxQum_T4 zLf?{hq!wfww!(arJ;PJ+mC57zz%=%p9zdb(L_Uk4?btRC&0!BcAaAu|OxL#|-DS#8 zq9YG~BR=h4Y@pj2oIz>{B`ty25z=ImH?}*+(NMS@7X`~UFnR>y7pK>>ub5b}k*CA- z9*kBH52w%E$;C)fhRSI}>RRe-VKAx`CY*{*v(l8$zjCm~Jv4I^w8e;uWe^hfM9!Fo zzL2B2Gj=d+UB3S?2Q6)R?L?wI{U>4M4}^loHJZ4@3awbn{1PSR>|@?u5DM-B;+w!-+}?DLKtRG!ss5 z)x3%HpSg}n$`5BCWRN!+(@KtrC3mpO9-cAECVhqRl%BHAa(72A0Ie?B-5ruINg*g6 z$`#VV)`2PthB|TTDK$z?^CE~dcK@>8)Lj^tevuTbxCcDP0QR9MQ^DUdNsa1O9uJJm zR{f2yxv}uFXdm>{rPGOy+m(h8i57A~myDxpbOgXz1^RSas-6)yXhddvcdr~aocvCV zOE88ybL@DH0V@U7!X4(VR>Giz=qP60)E7PJs%o0pbNp|^sIR$8;i)zy7QGgC-Ggqz z-b2=;lFPF~k)>k|oucm5!&V$9I*ZFetl*inmST6oZ5*-3q~ATw5xk-J?A+5VRx<50 zr^l?z{ss>`XDId+D~~BGv%&&{-CMQ5QVoTuo|tO|;*2Cw!)~N~g5wz6(3A6NxK)Nr z$ZWo0R@Y4H;L`8R#Ag`leaFaS#l2pjVY+6@vs|xDJdeC+gmhLj-7l)w(y+2`fK&OZ zX5=WYEm?-Rn1{y;539L!m{4yE6BIuJrkk*Q_S0B*kwmC+*fyOO-l9){YGk)khBySe zdPsZ@E?~cm;+G_ATwnoaVLZ4<6tsw=(M^XxlC#vA`IMgP$Q=)P+)ZC+3isc;Tk>G9 zyqdhggoW6sNcF&5H{09ccJ4G@*hB&aH;mG%tA4zr`(|EO3}1p1|3T>j_zbF(xy{M-%p#%*c$=Dt@@R=0HkI zCo>gJ#)(s-wN01-$$D^bA)~9uN`-qzQ$=UPycOe)Z$7y2RA+WoEll?>JnDt>Z9b}M z>PzFqPly5%mRUB46PegdkB!OGU38YNMoBzM^t;k9>y@J%@$1U< z9i)WWnxvX>kIW>{!LXp)gE};BG;BCB`SNoK9_WIbiOR%kx;bMwXKJ`HMUie8oPrfs z1QIVoHN260ZnZR!SOQ~KXku#b!)0APp{x>7BP|NSRpUJCJgRafv0k8NtJI62U!2YB zOSzM5cbxea-lXCxv_wB>!p1~5=V6NWG7`9TL$(P|SbN9luHD1+Z3IqM)bgMZMJX72 zrHv4;_r#3!T%zJyZu6RB9j0AekR5mD?(X)qhuqREvGJ^VYxfXLWMkOd!AxA=Q!$Hz znOUOIk5cZ&98yW{uU6iyQhA!D?xu-qxKJeb$QBDcVd_b!EsGz!OTa|9MD(V6AGq_5 zd%NAy;d*zu`^X3{LFSUs>$Mwud(n-Ig6xzP)m#GD`+v>28KAqMZi zM8>F!7^@#T6Gj4;B2$k`h=V-3YvJG?2F(H@-0ZetH@c^AqX#Bv=u-c@FG z&B!L_%saJuYj?Uz_L>{HvkT*O3X_SHoSDC=o$UqIcrrZH2VyB-{V8rcLuDx}oa$xg zldd5|nZz1;U%q&bY{M(}RN?^|K6F8iyE}ONB3un$jPaBY9#x>jo1=+K<6U2(R*=Z5 zcz5;X4HJvXN_^}kSy}#;#?g!fc2q7FFsh<(+G5Dz(UW@+BP>s-V!P>!s(-xl(^pRp z8mHVZjZ+&4#M%Lm;~SOoVu(`;glR(oa=8Xe~C86H5;eN+vW8>z5xzd zgh1|I4f^hNP=O(a)GWN;Tr`E+Fp*m}izDGcvsMDWq}g0%EI+G~#h3L$yoWBI2AhBs zL#(d`n!sB3BP8e-^1yp6p*7L3_!B`r$}Ji*nJ1PhMN3ic@>0VI+f3V*8w98KcK2}5 zgR9sR1yO@~v}m4kb6GZC;cMKm)6!UiHloc06Bo07tI8koJ5p#T*-w%hr)HJwZVWe% zR`!bazBn%n9DA-|^^J-gzde0oOBk&cHlxlf|HB6Hp}^)^BJqSsbqZ5s)O26(+5 zxgTFj(6+!j1rOxRn=QIapz}M^GgrI=dClHezb1E$UR;qR^N<9&;AsONvDjG2vKm!hcj$PT6<24~1O%*WL$`v~5oO_3Uhv502 z*^1T96$Ctysv0gBqQ%k$>6y>L;yilI7R+4o5PX&g)A5d)w~i9mnmi||bYXJcVP|i< zhupG$-rFR2L^4!fqSu^sW^pvc1zg|Q6Ub$~$6q^-Z|d~(`*vnW{rRH5boW5UQ5>1aQEZn z0|NEr|M6jycp6vI;8qrI^5)#=?e#Wr+$mOzIvlz?6Xpa*GTVK`z1BRsB;$#Vc~I-b z15i`Wu1$MSX9s}N7SaRM2z3gDtE+pnZ)DTgtDNRJyXJmk;#Z)mxe8a`r#d5(ZM)>W zBa~Nyrg)w&Cjh}XE$TuTYEzu~Ojr33G$pAkM}v#Q{$z8dp@)-mN$_njtXC>k#`Fv{ z8a@;GAv>ikN#Qa)F0~`Dext}Vh+hc1>J2wTSm&Wihwc&ESG804^vLuTpfVdx7Nqs6 z{I7bgh8`F{^qoWQ(y>tFASf)JDddh>!&X7m(W6De{CQfQHGi5piq)2C?I9>xGeW2x za(z{=N*32vY{a*^h;ACexgr0Q!X&~@tO#`qO+}l&`$u$xWUBp>CNTH1$Jf?q{pc}m z?KRW}`dF$wcN(q)1XpI9Xz8d*lWI1+Fr5$`@L0VSAvXPe2GR0d9q-rl5Be5@9~YEJ zlfme|LrH_xzhi&DceQnKN75m;HbPE{L&&7P{>GrUeYaeb85M4ulc6b1{)8T3*#?^d zg(G_njSKz1HE!=tWZc^9?{_+Q_TsMoRu2u2mR6z&9@yJEJv=9f6!;S z!lj67m6x=Rm&Y0&WiO>sLF(9{FeI>`P$we&{hsggy*o$Hk}|^a z4XYE5qdTeLoz7)4dIyka(a?1JO?e#bxI|4ZZM5#&#iP<;zgD7W@pepNw8@Sm&787n zx4N#iDvUkU<7h|%b@s}4UMU1We!Np4l_x1KKA}L$z z(RdY%a9ZQRrlhpdOG2Vp0cQAQY1K~Mjqs7({i{sN5_)`k^+0+YSKK)oa` zHX5Dy7Se#kw3puDc-Sb-h!Xog_)2w`hdhnen_NQM*LKey?j9()<9g$g-Y4#YGJGXE zr7aWE_%)D;O@-WVQbTY0W)5*+p+6C&c24i^Xj*%8>0St(yZg{@#YWnVHr+AnKPF3h zj!3Zi7p1gMObd?Y^A@}sn*-4UdfOov#~eKm9+4UQ0$fDTUfo&W z-Nt<7SnSunRaG?U#X%1W{Tckbzq@?~FULS+_4khi#u-SzX{#E~3nNU3D7|dJ#n=2b zz5RZ7gjkrceQWnxYzk@z1cs0NI_M{~MrxSXUXi&as+(*+J*U`UB^AX)L=f?1$(E9$ zL0Kq>TJvNi_79gZ$3zi5qi4-eEpO0dskM`I1`jxDe&{pf+=Dp-pQt+vTzoC}M(jeH&a zTC(ISbtkvt?6V*vlc`6KDiVEuW)o~dQy;Erj3M)x_G;mI>U6{>5Ul+Dp!Hu^c3SaaS~W8fLuALT6?^NhNM*bPc?;c}TiL^Wq+M?s6w7?{XfPbfO*8ua8y zUH29`(Z<$FQ`-jas=^yne41#eQ*o2{bR^2osI}lyONdnLs>if@-J~206iEOCe@KH) zCnK%zz(vI=_cUbJOn%bbRAF`MwstP7uPUjn>Lb~NNPEWVV5*wOo9|#u&iy%BlKYl#1AITX&0`C6B;<= zaQuun%=#Dm`?qas&X>sybov26;1y*BV8%liJ#&fQYbm+D8fjq4grP$dPH|E~{!w$@ z*if#)h4+Bk4j!v{fO{ekrd4N9qnAkZv8pTIxZx^-*2@%BC@^IKoD$JEzl0o|mEd95 z!b4uDiP8CBS-jV*bWfL+*yIf^p~W~$@sI-28dkJ{>&3l-oTNE`S{Jr$f+`AuE1FAS z8;e&~4!fMJofhsY*%j9^gsL$L3(^m!R}S#ZQn$CU(ce=gC8&xC&8KrTWb=~S?+?gx zQQ=HZ57q{)LolYb-HMB}nF};Bcno#&tWfYp=a?(2yFnQ>-61-sa<<*rm3j35cCfse zCOhRAvOc?GBz7Yvw&VP6N;OcH)dgTq@0bXDnku8JD8}SLkAh-$dLs)2a3R`YEem+ko62%WcNhV|iv(+GFzV&9EhbpxcO^_5T5?w9Pf??5Z?>L-q~XFgQ` z6Gec|{UIyqy`r(HhcN7oFe!o5gSeMjD|Qr3(y}VxbQ9Sw%KIgW0C&!vhg+DP)W~EK zd0r4j&Lbcc%8%S&ORFd8J=?g)W0Nngu^3##_NxY^Tq~c%)e()pgcZ-tQ>PP6?wuTW z!8(=hgBukCD#F56M-q)TT3RZHBP176O-%iI!I&364K5Vv8Cd~!>yh3UMmB}s0X)2N z=Gr-V=NT-^LI17+JmeBsA*abZ-Mzcv=)0?T(1Z20iCD`!G5Epe-2)`BmV4KCo;lpd z_B&V}okQ%*1HLiv>IFG8x&q&= z{FY3}Fm&NP*+9_A?(mj;-vIRE02%*A>MGgWxKxbd{z}8g%iRr5oO{ZJPA!jgO!CKA z0Y%0N8I1J~b~h5cV!Y)^62h$1cN84&buYZMBkOFjjeO6=pYstz1!?sip0)ww74yl0_KIl&q}pO?y|o>-0h0J zDkrn}5OfAADo?sT(A&i7F&yTPn zIiv)>OJqAh#Hp8p-HKHRhx~c($^-cwYo(?H-q7B zVwK~~8M=aYx^Fvr6h_C=Fdyvi4&@HPTYCEgIUNNPcDxh z*i*)G=Uo~!DpR$*wR8m=4goq)b+oeXj?~tbke$xyH-W{-w?fuIQPJFkx1KTFzS7{u zt`@=J@H{^HG zA>jzY@maJRHowL@bxy7xzzPXdu_lv?Z4yn)Y0T{!0xTXXH+(Tt6@n)ZRpbOc!)iUT9)?rcg5ZTS5xiP=D2f87INd#?%M8M{q@6(@UWoO zwf(Em{j}V)&ITh9?FRv}3sQgW4R0eb$ za5P3=2@L9;t$Z{@vc6%kKdsNl@PTmBcVajqdhyT2;o$}{G<5?nj%q^#B&X9{IoS*@ zKD%9S0uh`#;41aC zy@f_|Wz$#Ejd0toL z9Rn$g8IX$KGHvZo+1?1*O1XVQdxF7|kS&foZKNhpq5OG+mz5wZZVJi~^&Vk*d7d zS`}LoXZOlvaUltYD&}3)OOdov=ni`^v{feOR_9hOrLuZa$H897C1n)Ty3HM%+>ou% zH!g*AIcPFivDRoEH|BPbqp-h;;RrvIi7b{2`xSUuI2q2ym0tJaVQ+u4+gsn=KM-nMWT5-YcePA(%eqw zP$6VDC||)s#HNJE#KeXy{I;4x14Ld_yY)SdAOz8V=PvE=Csw$iPFXkI*k=S zBXOU?s%(cZt8IP+R5KV}79?trzu(^uv2{gdM-XyMdi@a5$1qwf08uTVK)NsodfUo&MwbTolUUqWTVZlA zb3zT!?N;EYgnvnAy*@i|Etx)db-3}s`XkVXj&{Vp@s6+qqCKe9Qm=${oIvlL>#X4F?1kMkAHxs-T}fqYjN# zxxsIi#me1}tmI3p-IYg}q5U*lU!Fi2ouhI4d=6m}EuB2qAE9#?=fo*d-!Tahv1{ywt;s{W~@{TX$@{;}EK8ZMnUTV8>eW$@CV3 z10l4bJGVyKxDyD?uXhC;0cLk7sd5k6$Hryh_h4ef`(W}8!rMb5%WNzHUm{X5pzxK= zLj(Wt>2*?$T$2(S{jZHqa`~7*Zh9ODTa4mJ?M|X$bzk$ zqQt3VS<%V<`B1*l;BTzJ2;vj^VRZm?SNQ>^Wr5pnH#2I;~)LHr}PFJ_#?%04= z5Hkl4sV?M2C=kNrwl;CEoVyL~-jD_-L64;g0{JfEE_6OXGyIr(3Dks*%Np|-)=gx( z?T~c$xzxw7!l?Wx(4?b>gu6q$Hahw7N~;yj^Xa`>dx-rXtlP% zMSz0$;&PYxH9;B(`CdeDL&ZZ_#!-GMXWPpNRa`>Y&zb#=V@F%-XZCkTBiQv~6_1ee zVzcz<#T}onyhaLSMzMKnwAxT3~+A(S0{z@{j=U z;41WihMrKjb~%6QoSo=u=wE&0B!_UwlDD?^OeKM1F`RFGwjlNk{ z7AZa_DjY*toQBmbwDPJw?{tTs9ksp}*MVH>7e4p7xUKgEeO*j!hWxN~dx&ZseH z69b#!<>7s}L>dYh3i_n2|GjXusA$|X$?1GlRGx5MsA0q@MPlb(IACEyi{Y)Dvf>%DBcURplcg1~KO~Y6>bHp~1}!`o+BZ!q4E=BM?F%#3-7pOfN{!$q)zN8#w+;_O(-8Vyn)USi2$G1sa8iIC$0SyN)xip0jj2 zEE2Kr;|2S+=BO?d3KgxH(L2Me=``Fo7~VD*!pfHglaouxWRYdcSWOPeJ#kq}F@7$6cV+Ga)kYbD7g_vKxJX)V*j_9cQs_-=mLtTFBeoq2kghzqkX0a{( z7(g|y=B7Hw&-Av%pS*EdJGMv@jWj^b*i8itA4?v1L2Z#_XekO$$zT|X19Chul|#@# zu%ksbulDjjgaX->atAg20s+VZ!sUyDum)9{D{)*reX{xP6YnN8axpMiD>#ii=8S-g z9SaH358)~}Ji<Uluc8#H!4nV=udk>r>%{PK_5#^4ZoPkv*(!BU}ehW2}Q4I zcwD-#g*8*SIggt5K|g0h!{iKfgGk^^puJqZn!*3XNgiR6#fF=}F^j&q(K$i+NRbmB zj~%oQ@-EhF12TOGwZaxOm_Ffva{XTD2Vz&M?@NV@p2M`(@7UhHBbXsm#;iM`Cf{(` zL~jh&x2f9`swwNJjBADdnXeS4HABPeb&yCp;<-14$<#({Mm3^v#ISu;h;$eZ5{%Pf z2Q4%nWDlb^ugb!(Ifuc$FB*kdaT=g0PM3zJD*8`?$m&B*snIIikoGA!sL|NWpMhf; zH8`!~BzXh=H$;_+C(b#7szvbo1QieNtBb9{-bT=*(=Dc`5z0anIdCnb4S$mRh;BJ> zj?i6|enD%mD6kYq4O7k?nx_o+&jj5DEvilwCh+=uv8#;EW## zM_$u2SwtX<&IfjZe%N}k|F<=sN@)y#f)GlbI|0v!3NGjc_w|N{JvR^2$ zi#p8pN)Pi#H6}WmOjpZVJEv+();MAOrqFGVi`|E<9U^AbodMtc?&bbaP0qb7Q5NV7 zTOO&7g{aHQ+OPTXVo|dQGKmS=Kjhp)65O%1C2Z`fSa4#po;@7&4{&b*&NrS+L{vpJ zH$4G$mropKx&sf4XvFcJy$#vIF5Wm03zB-kh8mC!i(hZyR-b~#IWEyN1_NKVa^A4U zg{-8E?eE~!o~*TeP$E+(XT%V0s{AzWA?|v2ez}LXQHf5mzDU4Es{lrUeQ&&dSx*-d ztgSTcnkphOxn`M_xEPuNe+j34O^YzOW~l7Az6c*9LM|+dD$OkFw14z?lc~0Z(9ASH zD3n4M+MSv^x`|(<<{Xb+4_ZS#@KN3b-KZOmO!xdW67GjC0?v1og)ZpI6;Wupb!Rd3 zLU^HCd9xRn+Xg%N4kB!2D6swx%zqwEuf?C#=se-_+`2}uHs+;lM3#;*nuTvQBxDyR zuH1yWu~A&#G%JIFpG)F=;WBKXj*3=UiO|^T9t20hCN87*wh^S`eCRSF82n!NO|J(v z8V4o3SFpd3h_4*M0i3I_1K1`F1Fw+*#S-eBQ@`Lqo^`AaZMJID>p zGGS_R)jJ(9M$Hi0ej`jBq&FHCMo5q=#! z0zoNgl=DuhzDnRoup{LH&uY!zh~e%G;m?wP5CSRx9NPB4Zle#lzF|l#QwWu-JLRBF zT&;2nIlONq8$`1NcGvfJdzfkR!+8n+Le-H4MHVjC?_P z?wNw2`ZUZRxic54a|FvCLd}K8hVuxC@7WXwS=ogH#uZGOM;SZN&jdRL_#z zTEf)cxr^MV=mJ!%V9w5>xD^9`V5nz^fkWMm$Hh>|=qhf}q8*J(6cZlzdrjV8uv>%v z_T~t5Wc&I)adVbA_LTW|FNN+V+GH1J@Xc~U+~T3a3hF^%JGzx7n}+WiGaB-$9kCmvW)2b6PXNG{{9) zIK(%0;TpyLUtHR3m?$!jbam=lw)JY6>=FsHySGDv53vK_Bau@`JV6=U+2) z-eX0vO?j&~Kt~-q=Fssd2Fq?9Hguj-R!sI$#FqNzsm8~PrYxIx<5Ec9U!Pr8c*@3# zRR~9o2oKZs3oM=#JnA0|angY+VGSLmC{blaL*3MN>LQBGE83f(2 zKFvaEz_ny!U>!Uq_;k`o>;J7UD*+H116tWCWvpgT&w)QYlf)N*-MlPx6dgQG{&YUk2GOyqP& zi)wt_g}Ex}9*=Z8c#(;L{Y&DokUgd3xuBwC`HV5F)O4ii^CToREtL&R)bmRhGPtYY}4Br+3HXf#76IUXnqo^=@dju>KGY#2M32 zX^|!kZTQCZ)o_-CNIvxuiQ};0>yp5MwiUcs7rQ3U0wv4N6Dc0zOW^^OPO1fVh)XAWIVve@=?%3PgMy?78P*D#@a?1Ik=5yMQ zHw3of7DG0%k;9BjcUpUQNl!bc;~BRAFH`4So0R*Paw#HQjFK1)cPL<;MhBC8iJ+N7 zrI}>Mt6Q^T(W3V_D_5wJazw&UFz@(|#%#K-68l!uNXE%xtCuUW8WTc`uQ*?U! zp=t<(b(0m+!($DLw4-(|XA7&dgQ$#3?~pq|=2ov+7bTUzT3g#|a*?X~MVY`fvZh=F zJGQ>SI+czN)1l-6&!F!cpDZi@)+|h6>tF}8jf7#SqD0$vl{xqM!E*`POlo87v<~&k zbs)*ZZJke<5U4|zdEu7B(f%!?{f%4jZ1d&b#s27)JI^oQd)F-&H#TlQ{@T;>|F7-b zqS=vexpMks_vG=Lad++T%FRfFbIbN%9pzd(S2jlbvaP~@rMB=FTktC)`_iS?;$kb}HsmMbm~a;Sru)y|c;-fJ>&BaRtt+E_ z;E{_0|9fya?7#kEABh?U8~7=A<6n=i-hA@-jW=K9e;+t{p_B?!%&dFI2|u)ed|+?KEYqV z?342#!M|m_3kCV>Bi`o+34X_mLffGrfBmds(IJArTPnz3ZCg$hB={MI3N`XqRum-o z1*L-g_2!}=!Aqrr{6$Ja)73SaJlj8A%r?QFbJQBaPdMrree?`@SLYk^$FHs#qR(nJ1nmT-)t4q*xGKTq4g z0eit#pX;8U=l^Uo#c6zDE5F_6G-~EU?|OpGoGY3EmcQO&Sj;TJcb5wC*L#YB1i!CT zkiR}u6eJjp5KSjW2yAufIl|wyKitqd|4mjis|D&G8Hz0cRjufKR^%i0?+aU>`ahqj zey7N$FQ2q8L23lqg%`FCGq3EYi*f|nFD+NC|F2qkR+{WYwGcW{t!Jjeun>EOdI(PJ zWVKMDeJ&A+vAn}0YQzpFHF7OM-oSEg*vWuR5K4kayuic(TmS!LD@4NqEhmOEGu?AI zFLfz*{z0P??mG~9b!rlHf62aL*Oa=d-z7EOdI%QZVG~!ss}@SM&m|(|O;TP+_gqU*I8>Shp#WR$ z%I7?f6dv`bk#L*(^QQ|EXDqx!y>%+y)=3v-Y zY~yMN6Fd8RY>*t8?w{&+$xX#Cf5@llEJ1cbcPuOWgQ6Tk(rj{P{~asON|T+a7E0_a zwqG=s*x4+^o}nIs#dnFFT`iPopG#EGdzbW1O1`1hB^h%Sfg&N1K7gtc2T)bY__6>0 zZDUT<^Sa|WuRmSvIJyS7k+Hq%3sf_6zT7y#o9$nv>*{w&V&|7forjzy$S&wkVr7?$ zasW-!job0Rs+w&BEf}oBS{?Y&_+X^P&e6VxhXF+O>Xl z>;3Xg%@(6gT{PFNH&@%iZ0=<)Nzaoztb4!Dzt_NmVbmz?D=VYb^{jrETx5Q^>g}B+ z$Sx=av9fO~$`NG0l9YC@m1m{NPE-peD2?qGjU{+H3$bUYhhXttg11)-CEBMWmlXTL z*0;X@Q7$ptRb-W>-dUq5r$m02a3J!lzgdt*wY7wd|E5Y?I@{Inl1soZ-|y|6CCD!5 z`m(aGE9ihAN0X$3Z?$?^X|fa5LWy-?`$c03I$$C84D}E!zDv+SwNRq{kJvcK7Qk)b zO(ch>01wzICH%O3O9eV`D*mDl4Ywb`s1c~OiAI2JYJ_!wN~#|w2{Vus? z{PG#A0dq!>T~LBxW%m@KiXdk#NjSe`^|I1rC#r=K3&-}0#u9|XLhKppAy|BuAe?HU zMEn2T#1n-^l2`DLR2S29#J^Hjpj5)|pV=L*O!C&;=Jw%ZGk-FBrcc0^pK17iH2?hDOq1p@=mO%G-^JMf7Z%?+6aEFqt*z1ouLA4@E7Y($N^S=wWy0A z>jZBj$O;1$@K;g&T6Gqmv}%9A{*_rI{38V}Bm5JN%QM11?YR2vu>KEQ8H|wNk2z|M zAZrSM-;e!NOXDG;DpDYRz{Cw+cD9B$NK|(E`+?971 zEf9QN&rcJUoSeviFOFsiEFg+;&nYc^Ca zfsU^_&B;OkAC)h$LO<}XC-~{n{uQwVN10}dsD#%|uML~k^D;4Cg|Gg+kknT2vQ;4cf`tCQp*Y+GRh_jW?1Zje^}FPP^2@hb4Omcu?1EAYEBgmU zIfCq0lB!m%JS$ChqFN|HRcya#EMexc5PODt2o~QZ%)Dx$MEhJKiXzAmf+Se1G3<7- zGA<+vk{H;%g#7ub>qD(ml)SQ)HW=qXZ=u%g|ORhh^ zJW>!BL3TljiVMND$X7ut-lP@vr^4}Hc;{i^*dswClmTi`On+n*Y05EYT|p5w-C!teRC zqFlAjFR}6`?cao6{NJqU&$J>4Lt1%)Kfc(%TO-J>XgU7a@sA-+CwxD?tWJ_rF;V1YbYIY^nY+Xlt{#$sX4d`zB_tRQ0eCETi(uJuhpDe@iG!O3Q zt+rcjv6Waa*^g+V>m$D3zKq&C{CpqLIfCqh zvPf3;XNqzJi?vB`sn4?VtTfq)YM}%xTeN*nZA2R@HQLbaOVZ#9D3a^Q=93$}`#jPg zds8MWb|+0%?9XOFRvaA38Z=ZLT7sqt*!ifT4n$j=w(a1|Yr?;eT4-GQz*)xI82LjN@>wVDPUx zF3$-6d&kuW&whNu%3$yW|Ba*82>yzp!kGB$-+96F1leSI@Xy%?ziI!<;0ga$fy)U0 zw&U`Q@EY z=c00iZ?t1yDM$F#jvKcLpK)BC5ngc|#$oUW9hYZ>Kjb*DWP?BIxI82Ll;beZ1~d9r z`bYSgs2t%J+L^ADBiwczPB#pGwd3-P@Day>UJO3%xI80#yW_@f!f$q5o)KPg9OlK~ z3y#Y(!Vf!c+$MabB@b1!aPzJc0l-*elVA3gpW85{ z_o8xy|DNN(t_=RDCKez7@Iq&~u#|K`k2?;>#|HmR z$K@H}4>=C(z~Gm=7bedLzru0jHeq_cWE_NVkIE6=a9o}dzT`L@jT`(I9hYZ>-|INA zU4wtnanK+Q{;1<&j{b>I0Ts({A$O6O&WZ}aiCL!Pdg55(%{=22R3Q&n;i!>Y4Eb+>THPn z`NcMVuo8lw>Zl6@Khscw4e=N2Pq3k9jqF%-5*tdCy}gMIt=N#xMnfY^iyzCD5&mH> zmuG~ZavY?f!N2CXJR|&^<3KJ3(}tDpLAVvG#Rj(>2XZm^Qyo`d4vy=4tQ|}#!4Ep> z0>OV^sIVOT#rhM=@y+(ZhwWc1$9LxqQXx_HsUK~S3YiV*Wzo#}Nf#5e9 zDl7+ovHrwzT(A$`ZU169p0X>^HNl%GdwbJzJY)6I3YDP|{*U%I;4;E5b-M!@KMZE- z5BZjGVPEALVcJzvj_}E-KEkIQSEqXRmo}hGl@IgsLxI81g=Q!vs27lObc}Dmnj;l`z`|$xQ zgRT<%K1W?3$eIG>RfxFtlzs4%QG0~{NrB4jD$lw=!MrcXO5pFvU zx}Cuz$K@H}D~^LHYVao=muG~Zb=T_}d+akUE2(blkX2_`f?Y z&j`2vB-_B+7`*1VJR^L;apN}OCmfe&gr9UA+BNvs90y@z@N|K`Pdg6W(%|f6MZ1Jw;W+4u248R-OfG{Tb{tGDgD*J_ zCYQl`j>BFt_&XezXM~@09Olp9zvnpUu7WVDOtA z2OZGh701E0F!+Mwux^Q8O!IvC|bu)O+aacEluQ(2-vcZoz4yLlfk2?;gvcd0l z9HhU&?{{3D5q{EfpaX+H;5fKy4E~VgVEY*SQOCg*V(?RrgEnFC#~hbugr9aC=*8eq zI1bu`!Ou7jHi*H`Ixf!$Kj%2?bAx}+aj-!QZhdA%R|dBo2c^>BPjy^fmXQB{jqz>B z5`uq;tX!ke`HPh${yWrR;V4tv4i z+Z~6!VDOtAhrM9%isP^s48Gtv>;;1#b{zJC!IvC|yV~)dK zF!*W5VJ{f`3CCeC82pUmuonz|)^XSi20!OG>;;2=&vDob2Dd&d+6xBX4__2ih_ClH;j`90&en@MDexe=_)S$ALc?{9ea_KNR?aiBkgpLQJR&)`ou4)ka6GmZoO8T_o{Kz{~5=Qz-x!LR%r(i;5B z27kWe>U)&?>NBhi_9(%ZIqCvI)|B3(H`)hZ6tzeA%L-gZ_^RXbjPPTQ!&)2sA03xx zgr9R9#%}OUpIeNb@Dayh4;Z}dI7IguyyrO3qQPJ9xI82LxZ_~A82o<6fyNAe(s7_M zgFoOn(3rs=avW&P;Ey^EG-mKqjsuMu{4vLY#ti-$$JN)G>+`Q|zOdE=f7MYJ2>!aE z!dmke>&LfYvWx$H%06IGs9?|9(NWE7lqh@q4>zb_Puq}wD;gT%|5@NN!moTqK?a1s z#Bud$Vf~+FWiT{?uW-}_f~+aM1^%n`=Zow^%)!Io*`S6d%0BhchB-K5^>yrDasLp0 zLxIZ(f3@Qv(hYvtabU{^{}snUq#OM0j;qfV`|-Gy!CVpiW=CBh$ePk~^`w39ol$#) zzrVm`g#W4I@{I7)jsr_I_{E=BtUuwGIIcb>_T%^LdyI+TA3Ev+LDrNWQ)cbFENYMN z=N7n(@M*_E92rQl?H#*abT4O zKjk>EN`pVy@NW z(4xU@$3Y!5ICC7-L4#l6IH-dL-{?4~g9g9aaZm>hKH@ltLW55`4)ka6?T!Qe8T^Rj z;7&I9vg7J|DzmXZWM#0Y2=*Lxfgo#2@2Nfe;2>&`@YfW$jPPG`T%HmB>y8_@3I9#U z;b_|6?{eI@P5Ap9muG}O=(us4@P{1-SGvI;aoo5~_{SZWXM}&kapN}Of9$wCBm6PP zAvVz9ryZAPgg@@MahvcjIS%oH2LH0-#%;p?x8w4R@FyKNZWI1>$K@H}-*DWxP58GQ zmuG~3+i~MI;s5S9xVsJhAC4Qh3BSY=wu^h8@TWL#+$Q`d9hYZ>ne1KUC*fB_FE|dz3I;#yxI81=bKJO1c;L7^Bm9Wt#%;p; zj>|K`Bgc)~g#V1=@{I7;IBwh~{Pm858gKA>95-$g{tJ%FGs55ExN)2Cw>u8UHwM4Y zapN}OCme_47K5L39AurrA8;IGox$JZxN)2C4>}GZCahveZIu6Ga2LGJn#%;p?!g0uRV(`Co+_+8n-#9MM2>*)X#%;pC<~STf z8T_o{aO`35bB@b1!oTS_gb^G3`;No$h{1p0xN+OzKSlYRXD=}Lg^nAy3BS~FIGr~5 z(;YW%6aFm6;kd=%&vx9nP528OmuG~(&~f87;V*Suo)P{s$Bo;BZ*d$VV+}syIOqTd zpLQH{0E2IJ+_+8n4#(vg;X55SZWI1W$K@H}dmJ}z6JB*3BAE?dbKJO1_(8|z8R3T< zH*OQ|J1)-%Z#iz;CDL?xq%G+2FD?| z#Ncmq+_+8nFF7vH2!EU7#%;oX-EnzF_-{CF+$Q{8j>|K`-|e_@oA3u6hsa%nzu$4= zHsOyrF3$-6eaDU4gnzb=U+1`SoA8~E%QM1f95-$g zzQ=KSM)+RGjoXCR9Eb2MgU>r|+$Q{x z5&jOxjoXC3+i`hD_-{FG+$Q|}j>|K`Kj1jzdo%d&J1)-%f7EdZ<1+Xu$K@H}pLE=~ zP55UVmuH0kiQ~p?!oTG>_)84_ZO7GpZS;@*nw5dCjo`04>HVb;U#y{!+({ z+k}@LS0526Z0#)rK zD`Gbm?$L_1an_dt`4|m;Yk|uMKjb*bGlMrASKn`}f6dBZHVN{xG$VM>K3KPZ+pWD; z`^Hxt`SK^KbFpV7-eLa=r4!BzTt@g?90yg|;P*NXTiW2CbX=Yh{)djM50(9R+{$36 z1pk7gRtf$^Lxs`v*HcA7f^0H9P2X!DurvsP;N%aVwhupU|0<(3_!kRYM);wx5A!Y# zdctpaTzxiJ|8rIsm>xlXCL^k6=jDgL;UAtQ_@K3SL+ha`5%4Rv@q*T2i}2gLn_tr+ z%s#vTWL5poORaon|Gp3j{oDNU*^XTOwl;tKDMP-vHM-%6Z)@}Cg}7|BmEW}Su}9eW z1lhSncBzN0%AWlz%SL!m;4;FGI1YBJ!IvFZU$#B_+dHB%gbxZ_M)*DN3F8v7ApBm( zVKW*0^M9@=SDgvA`H!rAkP5+9+2Jw%Wlm%7eA!C!14LE)_aFMIXp2>ugCohSGUjylV_ z|Au$s{0|%W(*>%!DF4hVC@Q)@@Th%->{^e%i?y;!MRKx#z~)eq)fPTzE&O=VRf1gp zcI%+^lD*a!cm5PH>_fXXvcJ@acedIR=ZTg4F(t5nZWDE#=AYFa*mAz0b>xZaY6_0~ ziL@!W>I}0kZqjJKvih)TstuqZ>nG9tQSH}Xx9NPPZ-TcIEc%=yX=c68Z)cycIO~vt z@3mjWNCeAY-{}nH?F7kdpr4{3cMB&vV5?KjZnKYg%%I-EZnc9b#on<|psFn<9!B^d zHcKz{Sz06bazlMeYrnO3=_Oz66ZL&XS%QDJTDCf@wiWnH`&X#!dkrRUc|ogFqrBh! zj7MJW$FSnu~NYxaie)V5?rispT2BpobKz4=*){k}@w;G|Ey z%LUngvA+f^fBlYOp&SroKSIH3R|2-Whyh!rVRq=8H*%gd!p2}OvaX--T~v$5{w1s6 z5A9z~MOghVnV*nf{(JAjS%U0>CO>3lKjfV_OOX9aCQ1AitCy7~J5eo^c(RD?7mX#7 zB(e~DhI$AV-zAbHRtqKC=Moik+2v%D9wK2{FySs6{&}CcZj}t)W^+{3{q}m@DVnd> zU1RX9d&AfF{7u%A`@Ki!t3(W{t9J6FmF8%5A*M2Jp1)3U#;`?ifUBUw$f}~*Q)wmasm0}XM1~R39<`H9jxph z7Uc+X3nr=PPgr?Yn(RciP+}DqZU3vS{X#jY?PdOn=0!r~;h#vRX}WmY+WNTtt6n~X zf3d)2gundH2g(w64&j>|H*OOiJFb2Tz&3x^>W4rj$j{Oal=_EfQy-qK*#P|TS#R+i z!B<;HLFxoK2I<7PC-{q9OY8|&&(7S?xBgi&G!D_PsTjfe@ z`ITPXc@BZqLjF|iN{J+^fSu4STm3G%k5Af{Z}cvlCCDx)lVD{#MLB|;+9WeMU8z6W ziE5z)Gg-9#^VUAUPptoAR^;9GukZlEUti!d!k_YZ!2<}l9fuG#gTKphbsoSrf6(d& z4~_Bwkn#M*09 zeM(A>OM4&R*qbiW{phHWT1Utc<%p!{gHn_}MV~Hor9?{Z6}o-Ln(y%(bL}z5+GjiT z{q^|y!+OoJ#(0g(9CNuZY*8(>#mTcnQSzkE7*J1)hM5%uW5yQyKvcK`BclZ2_%HHr$F|JtOumx;oh^J>O&d^ z;gy2DXI1@E+Ibdt2gt-%rxHd?fXvvk=`ICj&gIJMCp@?q-~F)qz4SR&`YfKp;PcP9 zmmvC2%e_?+6^G*ORhyL4jCs3o8nN8j{564uka`5NW3wKR1s(R%4yq4n7=%{}dI|s8 zS#WEG5|IfHFxv&UR$eLaznA9mM$5mLP2M7kpvhLK_4)eRyJUhd%(4b}-}mK9CU`%S zP1eB+-=FpThK0|YE%H$yX7MGnG;BtObqqzi~;c~8;@M{82vCSK3*qgfxgNWZfk}3 z3@&=lQi7xORp>u5-DPx)(T@W0SSfm^mDKyKq<#)?y`?#6krvM6S_aq4EUjWodXo~o zOJCE%_jciKfaMVuLK8>`X{&*3TMMEIB(88vI#_uj4TJDX!Ipsk>@3)lP$Dwn0cN{k zOY%yAf2L?}t5XNal*t^+1(7MBOJrm6Eg~YqS!m@f9v{3wJ<HCAbUmbEg;J^?5&R} zFQj1*UMZN{RrUWf_5TOUuUO%{^;c6VwjJK0dE;)`Uu$!KzNT-mDSktiHNdxjpz62Y zBT4XGCX-*~P<-8ov!3rze4e2E@;CxG{-H{_I$JS1M5Uq#gg-un;o)88p$YuF1}I;3 z`J+PIhzN)qnN{E>nvrO2uJGAe^l62sWsy&NZ*_N@MbIIFKW7o}uPW+&%i>udthk=9 zuX5c1zEDL&wW;audvtJK)&pK>dPh%p8IY~;J*XunH4*KisgRn8zN{juFCw4i7qsM; zSo3Vv1>a%QF$TOxMME`-i@`iA#~5XJx}`J*q$+Y~r3w@v*tdw`x5nKD(#O^9F(c-t zIt?(&C2P|dxnylhmg`e|f8yJkFa?lMfq&_*#T*hJs!dOK=a4!s;g_e9u;&`KOQIt7 zN9iPFtDy4Zz9UMjx%k>meZATyej$)q4xi>>hf?qe_6Q zk5TPxHMUAt?b50!B|g~3gKRB${rUyj^%Nh2`<)uL&fCbfX5@Rap;6 zT;UDfwCY0|2H};08@g5XPiZ-DN;?CY%-PPKyJ+}KiBv*1A!N<=0+z-$);>6HTi{^S#Vd*AB>UG*W|<~dK!c7X7@tJk(Jjt-?x`R6QN zCkTr>ak?*1;m({I$2;zgI^8$vYwvjo_~tBYfIs<>YTfmohk%!vOn!k*@rRaVJ-<@% zxsK|}V-Da8Of&}E(L_z)sVb@-hA{f3DUJb&B7SO8#?d5>lZ>ka#7&Q@*=2->;K=~= zYZ})=;65g5Lqy0jlLu(+j@H*;a`#Yz_Z!hT1X#;S2Z9`Aaq?(8qUxIyaIK*cR8mH3 zT3n+*oK}k7Zzc6@fa?P+ht`b>p_LDjJXi1?iQCocu^Ly}vbAq|7@O2KBfs{RjF|3_PX#j(0n8SxW!#L8K4ko$3r*?6JVY;05^ z-4fi=AFIAH(RfKTUJ@0JT@tk*+QuSkl|;p*`YEbS9%&A}T{y8=ZfgFTKtf1e1KHkL z4@jlL?s}@~LmCF*m4fcVe|8pJs!<{`;Q?m5;8N|C0{<`8Ja7@T#eu5ALI`f-mZ-`J z`r5mafltn|2Ka*~P`;(1JV`?tsvR|L4#+AA$?LLy%|UcWe=o7Av%0t-fTEZk*~e8np_fu|9CG&ZhO5gT zxBLHaMI%X>fppPqJ$0qV#yp7m9J*(*TJ?GOe%Q5_O?B~bi`q!`B4u=!N+nw$p;U@K zno8=cKtRVDT?@a^$`0VUf)mTNN1%JV2XB{U4e$$0CjYFc;_XdV{tn4b`rgicI^f;2 ztN}jBWb$uNC_dR_lXdX_m`r{TQt|gpCcg)%_y&`eUv4M1y;Vor3%H+&Mu9NJ*PON* z5OcMYFv_;kPV!c@JzQVK_O7WeqoXX8Ch+|;6#bM!hqf$LuL1$_J(Oratj_yve>K%* zbcuy_g6uGizG*p(0{coLiatP`pe4e)!GR&`B3>Z5px$>d)OxGJDHFAUL?;JSAkoQ_3gGE#*oy+3gD;-mK3CO`Fn^try!i6P zZmLbRa;_+?Mtq^XRqxTDH;Wz@dONvK@n*rT3s%%!$_AwFQZ``U6qMXW)mCW!=j&^4 zX@M`yvIcmK6Z6sn&o^0l9fbdXluMQo5VLq0Vfb}390kr(e^M%7KUevaY;av?TutEW z#?=P)bCq8@zg{_RH?Cn|&A3K+|oqDKs<_;clToFuD4Y2*EWCq0N-e$Vc^G2w9i8! zf3unm)ec*&%iu8M8U}u_Uys2FCR{Y#Wsn0YcJnh-|MU7Phn>r&yNte~Qn^e6e?LRf zS6gmqZkEd@`dxI1%~Cf_e8u zYt`;K`)8|H!F$I3_dIp~dp>pY{AErZYEqRHJ!6pdHS@#>=V{&w$H_#!8~O%;r^E-XGa) z7SGX3m15&6Rf>qq*)LRxA(weB8I)FYX{(oLU%p&lA0=OinySffts!8Wo-c14E&G9Q zu3NNVEdJTnp4SaN_8QhWn)=$iQi4abtO5Rv$tD`$(@j>Mci=x*b>zGQ#4JAVVE8&S z90i_cqA_4US9#u9tOoBk!(rg3OjI-%R!dZ+cSZr9XlBE}u8G<}q6&VSZG~!|Z{%{$ zRD5BUHNcyEylRBrEgX1LlTFsaN1CiWq2Tk|$}e*Pyv{_Uzy-=AO#{S9HDio$8FUvO z|2xwIH#Yh)AcWPKh*735c8DJ+?S{rR0;ERreW&3r11RO2C_8l-w6ZbqAQdG&204zR zQ|hXZbGg(4alP_5UX$Z^tHN1aHdLjLe^1MEXMMBx%yqiUXg6~(3dCon=-pOQzX9R- zNk-SAl+a3Jc`gxoqOFvGAktG5Zx=pV!SaO`!a^V+q~|t}9g_8cls0_6v$g6&8V2E& zf*%)LRsUfh`tlv4K_08Gy`3BU?ksD7e`~Ud2KX+M$=}^5-tnZo(+u)?mg>qq4)Dh& zY6EXkQMH~KZSjeURkjP@VJfN=86A}sfy7oR4vKDxh0+AxY@!a3czRsTE+aey-#%HU z9Hb{FLaf%dP>Vh40=2qEUstbfUpVW@d@|lnz9!YaLceE?TY~L>Z)H4liy9BJB(|C6 zyu;w!OO;~leBR1ga6n&32Dhoz1A~36Jbx1U%HjbA+2Xui zuBV2I*tNM_JL3pL0 z;qjlH1q%)(A`>29whI=VR|@>ksnuBr+u9N-mf%kM*3SCcJJEo5&$0&iy(XJzfR~s| zKGssa++^}^H!D8dWaT|8ag3>sbTSaL_yDq(8XRYa?c)`ml|{bO_tdxWF=uxx)bMVU{((zcrbh02SY5GC2V%uAf|m*t^#RuW7QfURSH#&-7JpcW+Vnk1Xd)qSG>q%@-O8nKFMVA%>l(Hn@qkrp!oA9EANzvZ7bE0ZDl8g zZ!powK?;w|A|Ou05Qx8Ex5nM(Ml@OyjSec{^UbOW#JW1$G9nUL!a#zm6upOMEAw;B z!zl2LCTf>uXnXqL(E#<_(};$F2byRM?!!$q3?wVLmY42|z2)gjK#7NHqf6^PUzC{R zp_=@gK!kw5B=jDWa1b4q@~H0CKkDOkPtgC~9C&^)3y;0$c_{fKlpb_Uo7?~cnL+uR z{PnxOfTHKKPkJj0R~Al5HR7p)-OfAAW`r7+fLyqn}$wt85GGE>}DtMCJ&`ZkW`YtWtCuUg# z{6>?>KdGvCk;&u&p!hhGO*FvoHCcK2B94t!N3OrX|1wb<_$C!qCjdt8$%;T+#zzI5 zKFfDN15ZrGX^}2C|O-Tfs}upN&dw%Byfk@ zCFWVFRqm-Mz1{*I0TNsAc-;G!OBP39qpnxo@^u#cFpwmA-|YpHQ1p+`5d^xj zPXRFt>aau|pP;Y3LlXGJENg&APpP`7cXR{qW3tIQ_*I|EdcN=Qd7dRb3fxes5Cw&)#=1z>l%qhk=wuo>LyB@2=>x z1mA9!9pI4Gr{`d6#V@s*b^b@;4%#8&07&A|H@WW6;?Wk;-azUm_xbV@WQ^z(`H)`4s?>h-8 z53ZBYdrrbZj-PD{q;hBnm_p))hbRxNKbVj z`$pCSQrz(A&&O3C(l7|G6g+*we|8o;{XvPyga?@If~P-TDe%t}_4UZLQIA|6^~mK@ z^a#@{?QnUqt8Vki^kJWms|Wgcac()9`pq`AEgx>sa<5ixwu&^d-Y%SNEcY^hO&}qp zR)TCQ>j86$!EElK`jCb}c%@*<@t>UqEr$}32@f#a1wneHz`wsVggp}|U0Y20lukC6 zm5_-yxzNZq4dg;2_Y6R;GS!aChzpI_0*7=qD#hTM!^-4(QYkXxk|K;it|yfuqgk#l zXKVT#KIHrL|Dz%T7ZC>x0v1sj?Ksh9cf}X2N_Qi;qo5C^w!}q2|Ltpg{ovYiI(x)w zn=Y%jI)_O}*>IVJenOMbPiYeROEo_3QeUzo;^A|4&}x;Dus8{bA*WGz`Kk1^d>j`Y+eb*b_CRyiCWa8}llUar~@` zh&g2&5s{x!?=DUI)11R3^e&UoJ556GHVM6Bd~9y>*uuk&S>*YHOYo(tO)1iZdAo2H zvAoLsEd&xmY7xk`wM+0qAg6|~mHu0KAq|7@O2Jo)@SmLpmtd5LOn89VF1Q4HrNI9y zH4pl4?vor?UOpAHM|ld|Yc`(`=tQJI9;XYOCJ(!<Z$g7iv(e~t=$M;X5f@z%^o0$z)ESz^**WyAhWt42a$8~Vdr&|t$lTTOlK zJp}~son;O17fd$M0Ix9FWF7o1lT9?hSDCDQQcfJNQyn?=0zYq}Ht;+ZRZra*eKRWp zaT!0J!|9=BSUf3Ts&9QlU(=&u2Hk82q$Wv^0RhS+l~2m?07LjZyi^LFhof|kg*5^s zg5WvuGSw#7xkrxW=gi+Q5Wl@g*kEFa9$`a;uAH}lm<6F`ioHh8hgChOpzpO*Ff>crp_B}yfahk-|^sOmpP@5+k6L)2xZ$mmFw3L}u% z;*KV|N12Bvkc88NHU_YT+Xu0I(8z{?%S_aMP~nF98IZ&Z+(AXXr@G*sO>LNe^74m$ zYT%o)8t^YBYVWYDnwB&4wdY`-*6NA++LJ9&{M|m8pU@|1{0CV|BS5NDJzi$SELOL| zj5bym(z(DLRa7bNrK5wgB9Q5>6yKo=%#ASmm}xHp6%`;+&KC0-S~f~1=0x}U934fQ zC5~5U&E96U8v_!DwA)Ty1{6yYT`}D)!x$^W7%RgV^W`9n*H{>>A8LyK&{sJ)mE6TC z>1J1$bQbY;;Qk!KHD1n&EC ziD&mcO;AhJgf{x&g9xTh|N&b47!F;pfT=X&8i83eJ1@ z&(4C)3nd~G9$>Z$g7iv(|3~WyHRNk|r~p|FWLg5g;%@i@nWh&;cDJiCZ|sISoU_nfs1XuV0bBxfSnVOd2Pl!2mQ zm6G#zVa9>w^;3)0Ib{&b>!+Zj5J~7uk%Yb&N$AVr9ZSW$TM>DuBJwUp6@9kd?~(pM3ktDS$TzKX~f;y+b;k-nx~ z#oL8j4VL?vzb23n(tZcoc@{(yNL=Ana-s4<8V2E&f~zF{v$J5oLy5?Q2bk@G{mv@| z{>#oDJ9ls!FpDzhObIJYM05t>iiq&OYvnCY_C5mX)@!GH3`s~c5=9dFIFisul7v2% zB&@mrd^D27C97Hw?@+j$x0-h+FlQf>MmEd*~Dt`00eVE&pwLP$#wvdgT8nn2nrT%zw(UP!|ryi%}4@SmLp zOB5v{6CPl;3zn!?3jA|nqXU8qMyb-N<}m;NL7nJXSa@p(n~>tlRH_t?o}t#Wuslj< zvhU1OeixEAw@~G9x$@@B=P)_z3h^#Cz486zQgw8$^;xl8Z`8ML(%0V8Nbt>B)&TGJ znJR$Z(@5~J$tLUIgH1Nk0Kd&-<)d`s*im)lQ95vU6;%%p8MU(_5dQcn=x^rL_g<5h#8mB zD)u_EijREkfK^PC_gS>E5E=YUh0^vw${a3O$WRVH94wWB<%&{Wn?c$XNCd%h{kz8d zD6<*{V%=LOV3?wH0u{P*3xKU@H3hwO0$wxA8sN1|Hqih-)?{V>>sz(QD3C)e5VKzY zm;VApLk%9+M-E;$%NpP(m~5f}ezM8Rz~Fz9>PTQf%w`V^ZCMDwe#7#o%oeDpjryVj zZ<=Kd@Y78;(EvZoWMxJR^u1^5t7HVkEY9dgZN8iIH65%J-<)L)@GfUm9(sEq_!TCb ztb_M4S@~z$_`E~;C0O9jY9@DVKp3m|8Nnai+Cl#pqaOvO#mHuRz!PY8VqjvaWIcqR{Nxv>WcIy{vo7fAM z+pAKvQF|TPsQ>un(!wdXzMFR$z$*Xv>E>Mqkk0RIa+_@4WsH-g z?6ZJzT@6{zU3+#JywLI(2U4x1$6#Fbq=>)eJ>O*JMTD zbu$zh{lOH+fotegRxvW7Ho@a-D)ak1zh@{d&SlE)R}q9F@+DrODg>9FPk6iVp#_$g zSUOE0A*3fFko`650f{Soa`HvhhcpbrEA{py_aFYVv*5`IN<=0+z-$*hIq^z?f2N3) zAf3Koz_M6i%Yw;F%FGQxCLv+bBuVH}uic~V!J7FuSwLi0wL9st7^K~SWIX3}LBfB{ z>w@LY>Xk*{>4SCgF6}--P2K11!j{DH!@1vqgpm3jvOBUKkhH^f@gCKOGz`Kk1$~MC z>?~LpC=r?P0JB}NF1%9UpDF5F7xe+_qHgPg$&_xdcYWg|VX!Xh#nX}@t>LKEevAte z9^^3P`9)+`q^oxSymK;9w_! zh^nOZhF#u$gT;d-Aq>?PE$(88$0YRmU^&C*Af*}fUTIG5>Y6<<1*?@=o6~CbL16qc zE&N)wsrBbi)#q=p{Zopi>2-q{*->fcLg#e@x&@m3M*7-2pMy8evIh7%lT9?hKQP&3 z9em=?t2*?~@xCJXY^t4v1^k|gIzSk!^Eo5fK|53&ASXB<$TT< zCrR070pq*XT{>PcINS0V2VU2&$KWR_tgi8l?#$M}|Im6?ij3A%sXTrFzI28nqnBqz z;O;XN8NJ>V$AL%BP-H}Hg7Z0*+1Ju&ZJ-=DmnmPQA_#-#++0-%F6}au?@wxKFhVTX5f=MR2z)nHJn9WRdR`h^R_h zZ`kGCH&{Ga5<)tPV~NM`e2(P|pMwIMLGP93Fo|uBw%B;<4wfZ11{-VysZ0B>Y z8|=+rP@1{WdEJ0+e|-*rfIW|&tb-5CvIh8Ilgam36u;MG<>y69^t}`MbigNOSp$6P znN|II=X&rmlTFsa-(H^ee8pEN@3-|;J`(+o!rQax<)5wW#`IOR-lXt7S>(ANud(c@ zukwd-FF&hNI$d8yw4O%y41E>RUJ8%QqOT|<7ttEz?wRIp1V{w($2ZHSyFLgxG%T6! z`Zy{np^RB5BS5076n%h|)W^8ts+Ppl2l+qOaZ9ov$;lq56_>dFIn`x!h|R+=kg2H@ zgQ|$RkEYV~$r8|ZHX$uak26_io-0^*duo(#*VnYOdb{v=gJs+DYyt@(ot+@N)TX%! zq~pRfR!eyy4TJDX!LGTg{wXaDE>}T{#5{_~PojwYT$Rhv9gX}w)oZ!AA-{+d8SNRtWKlk%hk*^I(Tf3NaF8V2E&f=S1Jb{3os zP$Dwn0cN}4VC|Ix|4b3hQ|*p^LcLb-l;=h*$bDAuqQ7`+ZLM{@J^HOR*yX0QuTHl9 z>HxV0N*=PGGy0S&ibwgw%O_}vY($dHks8wbtPP6K``@V?A2X+IAa3N2d8f$dipXcX z^jTca@c9Ar*&_ItSe;uXQL&IVaw(^F^>$$oW4VR-YXS)&EfC0#vI;hV6g6B(n<+1( zVGv#^Xk`3nXTd^3iO7TpnC*gv+B#d~ z&BZO2#=UNqQUiLsuq&~wnZG8G5K_xScCHn#2_&v?X*{5jK^g|(m4ep9e|8ou4U~vX zc!1e1SQ=g_@Xr*nG^%}{PGHt5sc(i#`aZ23K~_?~Oln#${K%EVI}wrhARm!8!Jus!iHyQoUU`(^&q%{564uklF~cQ**lksbAP`*C;QfVGv#^ zm~Q-MXF2Kdh=E1$>J&aOPJrmsDI@VqQ*fZt}ai3WI)$>bkZQT(=ZD&Fw(c-48czRKqY zKq#x*8%BqyqRfTd-Y~*N@Ug@2!}GB7=c?cj(O2=XqvrD(eGQzBs?)bvS{)#Xq#Gy( zvjx$cE%;VRRP11TxRldA;qAiB1IvBQUlT|OX=j3LXRBZn zNKwNbY(#k>4TJDX!487|>@3*9P$Dwn0cN{k2lGmS|K&PG*Vt5bfa__B^4CJYn_{qy z)w2U+YLgz#c}>4DgYRc!;II4j*3wCMqP`}^r|WcY}z`&xAhzQjf-@NSr!Zt z6N!j?93t{jh=>?)C?fCfg8vuQ_0c}^Rr|V2quLvMpU49p-zAlzZxm6a=yZmNd>SGu zi{7E=%y#90QJ#uoPx3j)sfuWKw6<({`ruY#W7VdG(#rRC;dX%KmgcVsB!slrK-RS8 zZURX(+>uOn89VF4&X2QsCb=mdvp{RrD=WNqyH;Qr|e0 zl(^oeb*-d+&Hk@8JKgbcy48CWu0ig8ZX0mxG@Zw9TA#Fhnn7QFUbR_LY4*Kc*b-P? zWd52!LP-4v**du|fqBOcru;nRg)|JpD+PUl|LiR2OO%LAc!1e12+}JB{%;%H8BAHc zY0aSxN^ZL_W$x%IRB{(rq5I|(cS%(A>fapEj4M82CZQ)wLf`t(t!91KVv&C`i#%1( z`tMNf9D+24w+p)t%j3;o6G#ZD^&vYTw?2^FB;1mZRbEKLAiPr0daLT6(&o*q=#EmQ z_;ylVvzUeD2dcs;Dx7fMyvM3t+LpsEhQiL-ng~{Zn#uYFALe}%${2ApvU3KL-77$9gf0R2#M(3!aT!!SgMj7EEcno%x zdU!xz<&zDp=6${jM?@DZye5mb*RXffSJCp(m)z}=yIpd(OYUM$e=w)GOQIskn+l>% z8Dys^%6-&Vq|BN<=0+z-$*>biGpGpDD^sZ;i>61xsZU&3=hhcYJG| zB6?UB!L2H~FE5n`6s~RM9^XVENs1v!?US_*RJb^c{2D8RYL`K^%b?n2Q0+3Pb{SN= z460b1TdZoO$_Q4mEH5b{=#*vYlx69Z5p>ELbjlhO+W`^mYTeQzf_<$uS|xX}9qg#u z`|E33blxspiCDhc{564ukd`@QueLU80%^u@JJ>~eAq|7@O2Kl(e|8pZ2PhGl@Bp)2 zupM}%z&}&O!mhqKL%mts)t#MhnM&%rrjj1$mTx8XEBG~Kt9sXR2jKmR$U7C0_b8%4 z?)J`oiM!*iPg*5W(U)&k?GNi~ntg8i-Spj8Y_;Y0fk1r?2F0m)y~QUv^8eZ6C6#ar+=A3!?Ed$mmKri0GKytPp+C znx|E+jiOmkQElp+~lXdZp{$9^m0 zEtX)=WPekZzWW5v!dn|^q2nXPGxXiT6vQl4fo!bMQQpQwj5&BHiW>#nH6kvpxc z75*%XcGIx;(bwQ6B&Zlo52w8g$AU6x#t2>}B23B7%eRc2IH`+rev8dy&4TMd$6pm5Akj=C27P zgz7A!?X{n^SrbSzhTFlY@eVc%i-T=Uli5<+Tf$lj87Y9K`ooBtWg z3uzdHR|=XB|Jhm4{3sEb@Bp)2(EMI0@PCcw(RY9Bw=&*h2?kBJwpOq2KEbo_))uN7 zA1SuecXzYtD4J`DzIB4W_MT>dPt39g_^vNjq4b_+fbTciWF36LSF)ZD9-m*auttHm znP>#~M-z<#k5TgKXVDqGOQrH-K|rF2e?NTkprAd{+KWC^i8v0U2Aiv%RB<(69^8UQ$Ur8C=m`im06oa)c?hlI5h)PpX3|>D& zmC;50sthQ66@agNC9VAC|5N&>+Kjh;N^LCh)^l|hUt$eaY^ArT)tYLRHY{%!?qXQp zs|>P>04aFdA|cz#f@lJXE8I$NS6(Bn1zVt33br!*XJ-KqN<=0+z-$+6rCurU&lKHe zQ`H8tRAk}EMU~OrswgwRY`V*c>6LAkxjOYCTD%RsO+}S0BN|_9>G}(_zeNQ6QCW((_>*1@_wPtJ?`shS~9gD?M)aaQUZoRXWK%Q_q+2RmoBg~ui0dI8 zZEKszIB?Cp5r`rqI$m7U@9Z2R0Csu&qDr^5IW zRT!J0$mrnA=oeqb=vUu%4|y-3+-WgWZOWB|6pW~okhqC334M%7I4H!ITGzGchHb4I zT4haJp6CgxP2;5HYqh^Htoq+t+VDOjNR&(4CY zKT1RZUL;Q!dNn=ZC}NsM@&z(qi5&>|ZReFn>)TA*96tS;O|SCNR%z(4SvbUP!|r zyi(A__|MLQMT8QO2@f#a1wneH!2dJ!^2q#1Z=W=Eo$e49pCxR*=?anEsS z5cdo0SkmISu%#UrT4Sy*!2$HKs?EtFHK4Z(yAsO{%wH2o2x)0Rwtrq4z&u|;*F8ab zAq|7@NJp!z^&KSV{eosiZUyp;uDh z^_A3ZthE!gZFp)U3nsTcAtj-YC<%Q)N$BHALLW{N4vOZK+{|y%$zN*C)$&e*WP8>X!)#`v zIVU$Wg*d>Prgge*h8NhTSR7h*R_z?DOtrTQ`v}X|n7<~F5K=Qk_E`&}2_&wh=L`Ny z<%Kj1!Yc*Mw5tBUrKP<^UuDLY+eN!?_sVBxJS9z^&UGc-fX$G8?4v7BtLGL}S@Fz3l?ZRot@;TH*N8cUOk|`d*^J$dy!jdT-wtrS1&?F%r zP4zuY7;ux}oA9{O@kx>6lOo3_O$CnSwn`^)9etG$%X=*x^QoY;9r^BU&z@R7+n_nO zRqb3QnL2M5_63$Zn!klWLP*UC*{N9%m}eoF_ZO%>q+t+VNj_-xbA_y%0mTzFgsT&FQj1*UMZNuIVFP>usqxp?0@mwX`Tpq7wV@Hu&1-Z-i)BZ-)I!0fGs=Q+I zChJS6pK*)MSO)&&tD_d`6X=G2kOANoHB}Sa+E{*5w?U zG#UlRJ%FVm0-V8&;$ebKDsA#-0e`5|*(H2KkSUo_=(5zW;amFx*T zsDG24e_KAW;Ii^c)y|LiWl!*S;c~=s)ciGpgpl?G$ab27AID$_r^2gjWjA z9Qe=9g3Ag@L?%4IY!?LSl>+}v(I0K9IzW0!K8w9}D*B?usZ}TQ`1Z}m6UX^yx z*VHV2I(hRosuY}%c#999<>PYCaYL_w7pXm08vRpL>x&5FQdXDBi{J}Ux0G((XQ zM1fB zv$}SGOJ*oCIwdOthpY-cMn>ycxjH~fUM0imm01x;$ty)hAIOS8N?j@XYJWki{9&t2 z??Oc(USyqk!sSz4-?G9eQu>oJRZ^OfnpD!Wv@#T+k_IUWuWyw~*T;Xk#=k|5|GcR# zqn0(nIIu5KQ6$mTbE4g;E+f*H&5PW-GZYz}ty1~UFYtyLij01f6@jdJ$xmEU&6niP z5-FosT4#*{`^qkgLD@x0*;)9K5AcsO{4n}U_5JVS1}#H{wGV8>0jFxP;q1MUfmDBq_1hMc)M@` zVY$S1)P+DoNUIaF)h&pHK;jBl@%xk)(l7|G6s#irXJ^4GMv2IT2bk@GRqT}l|4b39 zSf17RB`hN9&-xV+j%h*>`IRdozidV1*Q|*Ag1ue)hM?p?cky(zwJe|R`p{%!5UG!@ zlKKEEsgJRe`Y@3(Z zP$Dwn0cN{k$M8ylf2OE!ajpm#r#wCm7Mw_f1t-#A!37VX*U%&T7XRV{J&|(|{{Qey zOv;b3yOkDEar%~p;L8`Rjq9{yIa#F+^mbueV)@J5^FTsKJrCIuyU$z*Yvi~_4G+$PamIqnmLdiR-{2si_~8(cqsIIo606vTW%_Yhj*pbNNH6( zD8Y)HIJi?bhnH9@jR2`=GMz&dFI89E zyUQA-iaEpaFQ_BfMXTg4o<738n`PL7dvm)$wBY`-CDVfYZMFo8Q!PXUnYtZ29@T_P z082s`svWl2S`Uv&=sOR~89oOo&7k*6a|#rtSz~&YmT1gMH44mji&raF5%W!F%kfZF ztB(_{{dES{u1zeTo-dm7H`x9u1GV3f=i3uPG>Zxm@$7N7Cy~s=JG7l-A6Yil<=n!N zzmob;KB`gn`H`npjCjUbo&E6hU)hhG{TLl$%{&V13rG}$fJ8bdpik!V;TKxDAbGCf z8udzzhal22@OI(az;Z9kXd#dg(zOS&d$JyoqKDV0JyajkFbJ;{T%+)xodxGNl!#1t zfY~lMzj>v=|AD$!@n|USuyu4zF3?xelBYX<+Ig1;(V`VRe_5s+r|E0&LmKcIS=Io5 z$7B-?@U1RvWW)x7L%3#%qDSMsycGJ1iVH?y$?1D1S(zzujH!-f3Vf@IsstEKW{ENg(zFxf-{yuxJi5u@S@Og7N~Uud#2(`EYJx%wJxo|o%e-|V9S ze>ck-;2)W6q5;0qWRrF9Z%j7P0N-q~GSutzy9sGEcO*Fvknyd_VHGOX#eU)I>FM?g5Z*J5_1l}ym8sJfrO*Fv!m~65R zKGb9r4e((mD}yDDT~$Zg9oSM))y0fnpA~`d$L)@XP0g?g>^E!{CE8jIb~VFCI<%L~ z)kDqwhvBO%v?h=`tt}gWbCcE9{-^x+a?SmB`a|*LY-<>wqa<>>4J4@9Tj54Eyh&estpL6?%NpP( zTv1E^^)B(?1tybAyy6#{Y@z|)!DMAC5XYlbM_K{6o{Fj&X7uc=2!uaw1w7oWSxKpY z{f1>L+^Yt}BeT1HmjU5av%7wmF)<}&2KYg_DrNrvkmdyWte&!2g)n}!6{ZO!sM%X# z+0QGY)AY613g9!ctO5RyUsn3PRscWVWRrF9p})#{70Um|=P#9CP65DmluABO0m9gu z;8vH>dZyR{;xhO!#(SJsd;8V3u6H`GcC<*n-`>2nHrcK4Tyc2k6-UmsLYHc$YyYAe z%NKD-U7VZe{ zPu2x(;Dag}svWhsJB!1wS_#@f3YARf5XJA*)juqX@zUY=`RWLEdHz;%kNbkceYbJ9 z;QlX*yao3~Sp@gJS>(APqF2(LJa)83czcf}Aq>?PE$(88$0VGS&p}Ev=)Dr|W(^dj zS!4ROmI$Tb(KA!Km-cnFL>YZSr9-u&x9T!@Fbmi3GGJpExHqwsH_@0XM~pUCX>!Ei zxmmb=mjN?W*)zlM?^k8O(o3XtCxuHwO1zG4$Vtdx^DJDy%i!fItlTr&w_lY3TW+Q5 zXPLr3N~^hc?da=k^JR}sPcNB(aeepEwWBYWcehG!G7(?aH`l5iz4`p3*H7;;A46IY zd9N}5=!$e@Ap|#^L+T=q(i3{^fUvHF^h;H74fgT+T3uDP>e4gJc~WM|=RUhkL^Ag= zv!TC11Cy%{ZfQ;t`R)^u?+6k3nHSL@cUzmgcImD?$m+mZt;!(VWsvPM$if}L?UCI9 z7pf>-LS}LJLR}GZbp^6mlIa|x*hyWn7Ua58Ivn3h9l4VHKeuRd7L@Hr^38T4LhPVUAudtwSM zEX*34Ra$%uY?rDX{SYo8tVga7iIM>o5aIe=_6V*7NyuRC8wXc{N#6s`LKJA-BL_Q7?5e2;vZ1A{yzqxCd?us23tIKD#DuZm7LAJ{v3wH!} zW_AbsoQl#eJ&VI1**4h*=A)I|nam-IlhhTvf^6NT!}0H`BiKc&j+|3#&O0&lF zfL0Bq;3~k>uG)sr`V99BlC5?fovnwyJrLo;JxqI^V86UTdogn5XUXdZbQdcfJMO?+ zFJDGc^cTpUtt+93{MAiFK2A2Q$Jz?&luEI$5(lCGfhzPV`T@dJc46H=x@|pVz-a zUwe<;!MkNy1H8M*CK}*{CM!Q#*3Hwq+LkK5p{n*83@Kf|t3YPSxq57t4eV};7ekc zdy&%N_=EaxCK|7~|K6l3Z`D`1BtrD_EQ08tSwxV}v}9T}_a8*Js#SV|gB>x2k9Dvl zgrS;rE0%anLg%uE_5ziP6H2KW+_P1eD;n{1*{ zl_vimpNFcBga!PviN=61_AVT)E+hDZr!&y=Di5!FeKExsqJyupq)UYE$)YdHwSaBztcebX93J zyt1HV$MeKPy^sdk5qETMDBWAoM_Ga8BFf;sDwNIv9-s9Vbs69@ZP|kYdzX=o03ns) z0ijG(4B!uT|FFHnfWoS~wSNr^!wv#R!y zEh=XA6wQN`Dr*tQTAA~rh3g!fj3yjcWfAaN6|G)7y3V5eU7yTP^=I@wb}ado%keIQ zyo68Kv&-P;=5!Rus+M1e+q0+z9&-FG;>TW^l~|z)He{cooD0boqV$JcQ2p8hZ31Br z|KRJ}st;*+ZTCvSW4KlIf0z2dTVHz@9PoWv)&Sr8>uNH4&lJG-n@s-YV8u86HtYH6 z$LE2nD`f}XVWKhMeI^&&?Q)0S_}#3;0_TjR9{nQ46@I zW+=-Hc!Y|oWya`pSrJHeD#ex8XO#L-a#=CUrx{QdSqUdiGoUcC6#*$s(qnL`RcRDR zX_6iTiX(hLij(vhP#)0(l5NuS$*!-{`wE-pQ6Ne8^~WzwYphIkwq_tV2@6POGt%7O zCVCV|x)KKP)21~BB>$BaOXo}L zK1~(-R8{QL#n**a-{7$vO5g2QVnCGXfu4^s35oDQ+o!|_17;^_`k=#ygoH`}^3(?Ct8m_Y43kX0|7zUd&NX z#$<9%>B;;>ttazNiT*{F^TVy{lZ|NvxS@$gflpIW+VmN0Z+fd*!qt@_PsT71CvsH- zZe~Hq1(Cs?7DSukzrp5l7|1*dn=dI2$zB=)NcM8|1Cn!i^@C~?i)kFlgbmeXuk|79 zuKIM6?7aj`BT3-&(c^5VD|YCTs8bSkAfh4V(V6c@5&3ou9`*C3AZkG{RC36AVWdYh{0gB$i-CJ`3fJBfQWe&+ewaBR2z)U6I7lZ0y z$4(nPVnhpUrpAHKRZ;4C2HD|wS@rR<>P45Yr>uC9rQbJmnyJvGup6@ly_RB3il8T|P~`M3RKWf{P^dPLj}X zPnT;;<|2*bAy;JF^UJJw_TWr;vT`#KeRG1_Iak}q4L3x+3n~Fqn&={n9gjHV6aj=v zwquyM6+`KtyzMF$Vt80+r89U?)(~^QD36cWNizfSF1*RHznrno4AppFt>#1XP+HApJz@1`+i^yKhuNe`0U6|&Mwp&2W>cTfxV{CY zlpP3BcrdzB?Y^t8@m}V&g6)ECUC$b=_!da1QnUstc|#j1H?$ElV#5r2j4-yca7KXJ zswmY1_Mc@vAlpdNn}f^El;VX()rS45Ec%{8*roYP?&3HD_j8QME`49iBDjB&MQ|^% z)+uhneURyX8#_uI-h^XG2p3Kw^Z*)Sit8hm8=uswkoRjDn`4SVheb-iQ2%+OwC2IyBQDJ4xh{%&FgR3$na7gQ$^cXx< zg%u^Er}wKepbV9&pP^T4y05WH34KGgdX4LK9LoEnK4pCWn)4iC2&#(-Z_ zQSZk;rX6ZoY2Z9UvuLyLME4{!#Lkux+04yiJSe8B8NfY2d2DDIP@; z4>^nCGPQ$7zfyW~W2MT12mXsZKD>lzj$VIxrk>2#Cc1f{IM2(I=c#0hJyY;-r=?Y9 z*GVfLDmIfO^zE61cwmo6!f-UJFfM ztKfTIUoXf<0`gi(K2nkwcbh~`b>u!WA}0$9C2IJiKEWL*<)~TDjsVwCQM$7X*eTKD zZI2iMl2tNgLC+G!U$lOtD4YGBUGFjp*HUNMgB)zVhjgv*4SM=_5c$@3uT!_kCJbK;0s2WKpV)q`K4n&ccbI4d zc)yBz_oA&Xqi3j3*=&Kht`r%)SOXD7U{ghvA|oOWwr>Ky)}k8)-e#gPAR$&a&x{_Y z#gr2a5Ra8&u1|$3t7%nwp*d{>*U`dNii|e5a<+jKuu^0+niYZl zX_SB2PO?w1P=!f6%+e#=6EBef0f1Ag#JYqXOm`mt#ws# zSbMq>yxWL65ba|`ojVn7Xha>j-=9UNDa>Ulz6*)FM=b6>BH%HWN}E*rYEq`sCY8Q2 z0dsckGP`2yB!d6S5daA){j^IE0}cs`umXs7N0>MVPZ z@2-0fqPcw9w>LfxuuNNcXjld<_}`dCuwR-*o*N>XEuE3Dqqo9?6PARK&PZ6|G5q(j zu$m<}ibQ`id$2ke0o7i3jJMroF2!*KvLAse#Ew|a&i*?1+t#u!_J?x|qVca3MB^n<@l+C`uUJGa zh`z3bav{H3;cZz2_tq9<@stBAQcJyv9m$0aiY5M1gJOxt@MMqW44=ODP?|ySm2fv} zpeW56(?(h%l!BXJnzOGlZq^ye{n|OMm}2Xd+?$=U4~zCG-Hnv)MoM=h&DKBnltM}wBSC$T5n*2pD?0U$=!ncjNH~GchS~Z<%mW~t0G$} z);CeU{6n*kXr~$NcRs_O1yWy$ku{dum(zlK@m125u|K6+u{Gf`` z0~rRVWIdk=Ua()ic6bf^0W&Mw3bT)?%IdWj7Y_t@kIKxsNZzpbcdn3}t`7BMF`o{m zs0DZHmn*{+7P{P)D!wwy8sPEUDkr@Ul)?L(Y_bkM)MWC{J}F*ovdKF5Op{GCz@IhQ zWF7n)la;?AKn{0kypksHPbx}Z@M2I?uIgJ~I#}0)@+T(@Ht!cQ*uG!LU`G?mSHBp% zqF+d57MV~SF*wYG@_Pad-f2SN{HhMF=ofxZ2S4f;`YtHTGg_8MeglE>5PkaQ9D|ps z2l-C-YZSIk)FHRGSse272|f+k{>kVw{dx?T>hv=R3_fR0MuD_K@ZlS&l8Rief%_Oy z8%WgE4K<^KvLcX7Dn&-0&Wb>yt`r&NfQ#*oiJ*;SR{*|P>E-8Lr@IXHHJ@X|`_?QX zvSnFR#!%eH*HrsaW>x%B1uCoy`EVUbxU$98yA0?W5gynj&;yk}X%Z?Oku-hh;^QfU zBSVG7DUksQMyMN6WQ)2%5all$K)2=KAW$J~3Bps0$Y+Q4?n*45!+4b%-AgX=Km~}o zq_=;U0c%tAeAz|hgG#2}CmnPCEMcL;rX<{+<{~vmMLwiD{n~k6s~V&8%~@Qc!HK2)NKhqx&kP zd_qsnF3DP3>7>0_Uqx%s+&#lWZvshFwgDiCR@Vwf-^sSXw^)wjK(eT88MQ3haUeNW zij0_Pi3Z4|SBgHfCuvkW>ub7yC*-U8g)6g^ZvuF`;L8E{qxJh%0p;rj+Uk~E16D!Y z@;=&)HI*07mXcQr;@@g6JS4|bk%vwPsvS!ucn-Cvs*LEXtWqF^vsh8R^u&{Ppxcws z7b<)pyuaXxxVP5r@LWIOq>ALSINfEC z9a?7{V(V<=-3lq81YgEbTpLLy&wQtx`QpI{O_3uSFH109x-SkM5U~-<6z|k!u+-`@ z3dCX3^DdLnJ554A(Z?$@bh7(+G7)(y5qYAIC=v0=RR{?8!wj|b&(pZ4*K+vU?f zgCz7hoal;?0`}dMgaO@7#UeV@(aoz(TsGZ>?=0=oO3LUQYvWNMZCojO&z00?;$6#L zjbCU*2%+g%l*Y!bh|0#E%S^ycs|J(h zRib0gkajq&ER6^x>gw!GV{?QTMIgCUioQVc(H*}}vK7_@UZJA8Jb2h<)82Q*@y$ZY z?~J=y%>L;u!jldtK|&#>lcy(9h1xl zg$u1*8-Ro>f6wQsg8M402u0=_n4=25G>%=<>a`F^0O5BgwpIPz&91oVFI9>i_+=|+ z!2!|8M!43`2Rto1MCo`2BJ0Ah&S0rvb-tz2Dy@n$8CEQS)Q!wF_DRSfukq%bS{V=1 z8kaslV#qU}p_+6cgB*vve(*zAe3LsTyu`Z5Nh_6*nYU5udar5TfwM&#^nr z=42r-+Z|T^@XdQv|75c(+OkwB+VZ0-XTbr{NLya?ivexP)nseEQpmkGQ$qS9V&d$(yPbjCz!4QC zQwAI^gLLjv?>y*~Ww(a+<(O}9~B;2uO**V z%|AT;Hv_zGa54W6?Z&6s8Z11bG8d0tH}H6fdg7Kp^`9^3FvR-QfbNR-Al(D*BW3-IH5M)I67oJ8U-)fKZz-pFZx{sS~rYot>{(Q~)n*QuprW9m#@mzRFnT02ZrTf)xO>2bWu*7n{QB|c5 zKnQ~mL9ogyqd>|m>z%G)Rf)(~Q$)U$BJw4|9o)U=Bc8k`^XxsDr;nbkz)$9J5y}k5 zeGqa7;A0Sx47GdT-7%%&vxCL2X2`O=~9z;|o zH$rj;+4eR9WakU7>7~O*u3t7;)nt4vpY4dMPcWGEhFxQOAC@p$*9tKTWC2v>zKHS1 zBHp#^WcYYr~o-M^|nUv1DccEmH>00<7J@Zs~Tvr6YZm(DMIg)3s2sY z`7-om>^K}sdNN-K&oA4Wrxy|I9K1yY7#@D$D%2StpZ_%eNKGpvB$eC37-@`4H?SF4jax{$SUUHNAXJIhA{qF^_ znOzW@z4uYwclu(p_k3&=nb>4*d`Kelk%))@=mHS|X@P+a;R6&~AJ=g@XDrh>s6;0j zPZK`5`KbEhra+GUK+4ifrP=k%ypop18KXFKjxf@nOiE?z(61HjAiH+><3HFj$LY44 z!H<+IeQBP-Z~KLQ$~>K1NFb|gMskfLpWkJXC&CJ^a^nNc0m$v*AiEo^4ozULL+~Na z*Hr&Hvm5r*rAqN&{5vaW!2!|89(Vum20ZoV;z~2fK>>J(^~Yg#TZ+_GK5nXa8RVuJ z|EcbUzt-2J=hMXL&Nex%lBzsNYUcFs!)Rp!pkdO35(dw;yyb6M7*Ledr#{$ZJ}60O zrLw>sEpO}7z7l#OtO!N=6qut5`V_n8Wp6+N2p>d0LG_<$c153-Dn*}eymA&CkcIT= zir)|D(>;`qrj#YlM$K%9$ai0GST2d$B~iO1Djo_zl(*=JsNA9pB2s#f)w>ORzlzcp z4HdCT|Fg>O)zu~<;NNWl%8y+$;9?l;?u*schs>pXI^$iYJL%smGh`xMHtm}hx??S= z7G&SGU|Ue#nMH)UzCIfd?kFLm5b3@RyBt+;6NV)rq$ht^;xT+2h~*5QK53L@(0iph zxvOdR4XeT^FozlZ`T(<+o3c3Rq4IH^nb|(F@w&led{k*ZVG~_=L}e}>y>8%fGi{c9 zOFH+{*a2#r4~j*!&~Iry+3{A<$+t9{3$t$yj`Fj_H>amt3$$-G(%0T6R^UyutO5S0 z$tD`$lT0>Q2S4?mD&pQJTRwJtzEtgG>VO|G(Fky-;}|*CLCK@XK+zA23}=)^2yJ4ba031jREg7 z(I}8ahic+tP|3&5t_dXW>b{538CelXjFloIB9<#CkRU5XM)zb!AR$+ZKIUE3;6rBE zCOQm*%hTIbd)llzWgResyLI!^@m!m+EPkP>I68fyYTUi`9 zg;YeID%kygtkL8Ut)c0tq2KCWY+ry6~h0fJ{*MIQ4qvg)|JpD+MRC zRrT*TjNl<8jYjW_ci=@D{Ytx=g&B8u>7m6;VHiv*Rsay$fwYSNG zf0$(r@b2HN^n05(_*EvGtb;#hvT~Eh=bg$g$pCjzGYK9DW3N`NE~7{HxA^WW7b ztqmk8DeACgNCZ;Uoh+P#v$1y??DgBJ_HJf12JCaWXW>$cDxZT9K=wIS`Ye7#0G}^4 zpDlfg6vF!Rea#MAV(x1)j2$g&1_lW*l64ZNwzChOosOjhn_`23dg%Z>)zK+Rm2Q9LYqjB0OeRvjQ-#O0n{26(CV zMn>6Zr}SAIneq8V^Vx!Emn(7Aq+P(;6dX&8i83iifT_3t-`U~gQcAs(u)y}c29M3yzc_nK^?0lv>0ygmtb!UTr4PDr0p(tvY>Dh?u|dz4DQfZ>1ZIONP8m#B2RlGgC|;>w9Aet_QqeT zt9#642Z)!nH!{FWwKp=#K0Bq)VsFIft>&`@(Yh9Vt0XG+#+qv5KJ7r>F5H%|T+{qD zfrOCuJjk}qdO+GG+#6R{eMrL~yi%|?uBv~(K?Hl_0)14mkv*Q2$DN8d&9Vmg2PT_n zfUh^%WF7pV$tD`$+P&3gaA>?^74e=!{qFirwT3Tmf zXm5E64*a<)u2DN-#q`oT#h+)%jZ)|5XAyP&R2EUFUt|#l_;VJOnHGP4K&E6On+K4X z(`B0hlKD@obtdf7pMpRqPPYP!pS+KC<=e6Q+>hp(FRC$sqfXf8W{{!dnL4gZ3(6Ay9hJ;6kvp*gRH! zQOeB@HOW<#AIW5Z2hpRWS(qXMGIwe1F`&yt4@hdFx2UMJ=mmA&zo_&1x}tJuMZl2_Rb{q((WRH!^S zxTW5&Z;`8fL2AFh&-39_V{}%iO;`f2B>8%_PpCaSa@|_FN|78arzu--y!o2GMIFL` zQR1{E0R!{FOV&MuKbXG}ApF5ZVwF{jTuYTAS5$5?-^C_*oxX+YY!kVY-fr!zuf69y z;9at;0sfT9CK}*Rn{2WU{)x%Tdk=iRR&`{$fTx&f1PEjGNQV*pK~F(HW?Z8{ta@Cd z#kO*o8oWzi(@g*lztJyb@EsM(+4f>N+cLyW_)KkE(TOUR`}um80S+rwMl;=) z`Bd88JrhHn9_f<(A5DOgOZ~^K{+C#GC+yi}Km*8q4v;C4dD^pREj+wS$)x2e1@)eeLZ>;LWnE z0e;q>s%GhZ%K-drlTFsaA2!)U1N;$_P1eD8m~5f}zSCrrb?}1wvtQq?pneG%W5_|1W!Q9$;rt<$vEK5Uwn8QAAV*5l|3O5^zCa zG^i+ULwCBb2IzF~Co1Zw0iioeHWVZ-tWiO6ym1*tQ3e%(aRbB!!6oR7AZ}qqVO()s z$RO%_o_fyb)N@ar+v$Yh=sS}?a=&$+v(>3nr|PNaxwq%3i{CO=7ZI`NXs=}xOK?7s zNyOptzps4}t}iLPA(Q6ZSzmpzehSyy6t2xA-p82bnp~Lf<9IyVxx1V&VA~&5YJj-h-=k zpzd##aGZMim`nmvLT9#?bm;vHY+T357(AA9=sVQ~)`{S)LR@&D*&74yqNG`^7031P zYyZp#Z1~l}uP2#bBfu9KX$<&EB_#``|6`^9MZv@W+brkDfcP()`i=A+zeKY1YNYh4 zD1x}KjYVq&h*wf57W9bCkrtZ~AU-6%&ErL?O@SYa3qKNP;K|~i_at%ph$Ny<_CM(e z7RYB*vNc zJsXMf|5mtzjl?+R7>9$RRhk>a-05a+40wi;Qk5xv7%P1kD}5*m&lEl^$UXp1Gtvki zEVn3(0drtRN~cCjr;56Rxs$UwARfrvT+qYd+sua%AU-6%&ErKX2Z0}p3qKNP;K|~i z_at%ph$Ny<{8wr$&eYGe`J!=_66+H477a&^fs~livJk!HcteKiNgIwXCeE?QcQJ5Z zn*&|c|00uow~%7yq{4$7b0@4uNMbL2krqiTrV=$Rn}eA8)O)78wfisy_xyM?WnW;L z((Sit_&;UCFwEWMO*Rb0%`8$sGpTXlFO-xj3durPrCu>6b8PsEcW=<1eHsV;*bI)K z8+T8e8AwZEP7)=e2{PbF6eE77ikIyek?Bh zNSxjiF}rgw@MUq~OXBot`E`xOZ5ER;Aom^hOfQ2n_7e>T5s-u6qv5H@9?Fl>&J5@HD_P z1@=iA5>oPQ&7ky@3k(Dv)$BMyO4L-Jv`1@Rl9ckgF_4t(%TH3K&QEVyq`leT{bg(( zYjdKDqL3AA%FBc{Ok_*h0CF+&GIdl z_igTeqwpeCEU#v+S<$0)y@hue$gHUuX%SwTHfNXL8pX)ZOx?yzLLb(DQ!Nbbz~$2m zVt#8&_F@rX#P2Xqi@h9L?#wK}yOku#v!q8OTPsvy1^Jn+SGT}_F!e=QKx|9x$E;Sn z{Cjm=ypJ-;-##wB8sd3^#c-WI+r33Ut7og=TQjW#9=*1XdbMQ&FEH9<8$9c4na__C zHfN}uxCMNqkro2GN~*U^v^rm@wMuygZhu`(su^kRt5jhGp47)k>(a~!+~WGCMp}m{ zRWt%8`xt5cJTn6C?qj62?^mrez(bT&cZSwcnGtwvA0w^bWJVw(QfsUY=Kp7Fl=rm( z7y&ZOQW4fI?a^W&q#~?c+N1T>EDmHKYDQZ7S+qxhbh2io^>pjW2#`+JjI@548G*UW zm5;fzHQJc|l>=RAEJro6^8}3vk*g}}vM7#cFY96F6_zLG2$k0HmQbTWa!q0(jDbT! z^&Q8dc{W&G?4nktq}LS`k74x(C(m|31wCGf2WLeLfmZO@EEnXK zXA0~yM2+0KWO-3|0@C5Y89lYPE}&PECp~&+pQIkKu~+DrDIW*(ekUz z0{pF#(j66zY^_j*738ZsD)4VieUa*jwX`4M9TgY1Fs5^EU*;p?nSz?VpUQJ%QLSD} zd(&GY4^r8e>!--dibLyFN|iT^feje6ChE8~On4@GfLShB7(7#8{}PRC|0dkm8m@AGA!95zot|s9 z#t?UdRO{$r%no)aGua03oM|2KerszZ)gcdfj?v`D1QZ`|Q|9w-Ve_%7U-AripRd=< z;wcb~_2C4q>(!1h0&lpXmaQ3S{ZgsI2;BPLn~by$SE?`qyM2tbPRWeGlfT{6NbAi? z6^+1uxUtDd>n%zZM&SGU7-?OS8G%>yG1A&f!!H_vk5Ez_9$Ji(FxH;s{~4x}Y?wxY zud`uV1Y}?;^`kvn&#>q(0=}*>Ort$ojE%hV54`U;bF4;tv@TbwFalrpttKO_l}Z&x z;6eY^WTbVhQiT!tu|7sxU(1ZZoBJ4Pkrtv6czGk0Mtih=XQ{LZxJM(EMtii#AJGWB ztdEh_Z!PB*0k>~t$Y_t&E|yA*fTUwRgtW*=F%2XgYergRq%Z`CYTpTGM2uLB*+thC7I#7cv7u32d{GIG^4GI9YKNk&UXo*kw4%4sM&5@qkTLcS2#OztBs zxyd|vvH>LRs%{-=^_f~LjKI4a_4&viEmBDsft1BsBP}YUFajxyH6tx@Ll}W1M$Jfz z%n(K(X;CxMA}@pyNK({{v=~fb^p$FbE}!SwGCBlo4CM!HC|QFfh0a@cqOLDwT_Tcf z7)``MW?MSK>CXZvW@}abVKwkaEfdDc05(>YD44P&`voBRP_dB{485>1-tumyX`reGxA*Mj^#aC@3Ns91CmKKBP|B9I%W`Y-7+&?a%2x=*lI>vc@W2d z3}($pi_s8`KnA5|q{aLdMj%5~Gt$ZEi$0eQnIO&*gDlySzv1^LFz(3Tz~RFa`-AR1#p0-AkM! zR9Xkyy~HSx0xF{)>?UIr$mFY)2DvBV z-0R$4G02-2{&UsmHbTAe+VdplrU}7Vs{;rc-i);d>Gso*kuL5`uI@ z<>kV2D)!}vJYfFAhSC>JR4Jfl!i`trr@at_Or3z@C+tA6FtBz7aX2> zrojI9UEz^E@~UNI6JsyirS(hw&?llFdDO8-lGPiS%Xsz2BfN=VnHQ2*|MSS(8+9l) z-rGB!I$2?)5}}VtQD;6a=7l^q0AhG!rU<6lY)bND7qvq2F%PE5kBZ()0(rSGJCXdQ zrT(x%tph3bQT9kH4#Pke@NkO!SoNYbbiy+Q=ewI~|IxbXN+#|-DJS>C%? z4+1y}lc5wUyEV?eYASni4!LS-dA?O?@Y}eWmpvP&05z4pHFxnfmErOiv9RePqcivLnRxP8^$O@4rD|WY&%t|M%N86F-D6o+} z!btjjuuq)UMOhr!$TJZS@=U1Y+4uW)Dzt9TI~5=|6Ov9M9wekteL|*~kdODZ!|_T1 zt=+6fi~<{pD~y8@_c?Zl)}=4FDn-xx7u3OPw2yQwRU0oCmLMd*Zc&;K#D!GfQ1%Et zo|DxS$V3k7;1^XdN<$|+Q?OKHKN}0S3NYc>be)7B<$?Vd=@7ljhH3~%i4EQ&LkgC3 z#_Y4;W2%xHLn+mFEVtW4Zo?&4WunJ-;PLG?`*BjL)_^#{)f%SJ ztH#Z5qgQhC8}v%3L9c`w^h&5fuY?-(N~l4vgc|fpsDpa7?KkQxvQ5MJ-`lgRaXjzY zGo^9dewWR&aeUs^rc|-zBQ?HlS!ZW3*<5k%fK2yFH;QmF6-eZWdRR4)#D(r?NUFgK;6 zFiq*xdW{-P!Csi5eV*pE6iO*6v@Xt6`CbyO9qdG9V%3Tst?86nCfJ|s0d#dvM{9Q8 zQ=Pq{M~kCSDT(Ws_XzLj?14r_rS<(x6%Dl5Ux@~>Mw&KCxM(2QjS?=@pxB9CiroQv zKO%aCN{fSu+S>F=AfvFA#(Nw2?c>=KSFD)5%YhHE!C0ghx0TzD6|?1wV(BV_a(TXb zzFb{ZUuAF}tV1TUE9L4P%ag3nJnu%ZE1IQdLQlOu&m8D$tG-6|NT$(hENK#9vZs*| zLM0;_qb$^5l!Y3MvQVcU<;HjlZ!n%h^&MxGI97WnOB&9T>_YPSDI}jnLh=@cG|1fJ z%-mRMuBh%fdEAszrITZ&lf`*{aB`1x&&}q5^Ocm=r6~+P%?=jEfQ(KOEkjjwdY+o1 z!pUM)8eDX+8bZ5pmAZ>14c*VQ9(K|F`@E!~d!BWsi|#d<kYm>vE@?>O zLR!6$#A3LlA=zhhkYj!7Jrm}pbQGp3eL71+1XHl2F|<@hS<*Jk;>FBmVXDhMtwvGW z$Ym-hRhwl&@`FHJ?)`PdTMFv_(K<(BXT0m4J5YFxDrD)9QJ2jLt;Rwkv1KIVF(d6| ze1-QOj*e&uwhKb_U8D+MX~kn4H%T$6{C=Y&B)@tI$y*GT49uNj=Eh2MMfF7LOH)df zP8Ls)8_$YaO@bu@=l(gH1AbUZsqRlfNTA?Q8D@jQin~3hM0& z$r}}tw-}UO%>B&f{8(wOs6t5XZB9l~rITZ&lVhcmg*lwtGMfW#t)x^xr!e?YJF^)B za?hPar{TqV4G}X@ifUXizF7q(u-uDO`qy8^{Mwvn48j3n5Oh;dkqmxLFr{^r&AETqsUJ0 zbi;E8)oCZqh3P5u+=0R;tHQ>+MOTF{mkE`3iw@URlf^=)U2SpLT~mWMfrQt`=O6wm ztn}O*^ zI>Ur#q6e7ef^_ywf&JUGAH2IFqqlCEeZh~4T2r}Gxi~*{5nkR*;c-^Y%L^xbfuN@H z9tm%d)KtEKN6D+HlrZLUP37ePLQ+$CUx|~An#zqe_k1DST~O43BA*0ObObPI)zJQccAl53C|R)`q^{z4=CvoH*Pn>qLLzz_FWOZ9y`sfV zQ9WVtmUkm-DlJ}*lsgh2L8}>kziR3r)333??P3?TGU>doU>=^~MlNN$mkXx=lIL5o z90uY-nqMeeoB4p`MmP`8Qht<%PI#tZyMp~}ESQHd;hE?GX1QP&C`wMQ zTE>`THxaSKVv&e`tw=omkaY1$zSKm0K|nf8Bq3Y+e!=r+1!Sc=62PK z($ERd6eKP7v$0^(z=UU_2bkr8N#mIU`%D(z(cHQbG$;QM*E||DTJu^Re z$ImQPEhhKwL;Ug|ahkPcaO{uQ2!Ks$P_aPI#uESYkgL3vv%8 zJQF>@EEnXSXA0~y{uJw}_WGVz(xXf)6!CarDutdm$eU4}bs%$+l7DB zySct+exB*wng%REp}EiNp(fwH7pC<~y`~-XYpqk9x1FtjI_4bv6Ec%+@LMyj173Sq zZKV2HQ1DGgn{0#M_=n8r-NNS8s$Z4`;Pt9XeqIZBgOaM>;p+Bi{lXZ#z^AK8kp;fM zNL?U~1wY`0Utcl5MuDfOIr$ps6)R}qOXb;U;Mpji?WS(jjI{PtYSKyLNqwxe=ucv$ zL653CDwU#hwILt(Z)?9!wAc*+zhR_BKzcW;iaR~QA(uR*cO#ff_^_=R90DGt zr0RFFz>Ac&b?f-n0edcP?Y>952aREv(K^zHR7jR?p~G!S;?;H1BEj<7GcmR~d+uoqi}1(GNx<`r$y`f2!Kq zt;I6xyZ2~6#8PJdAklj%Xg^br$kfn%&lGI3?w*bwj4(B2UICe!GOvJ)}r}YMrp8=eZ~qNz!N7Zzb?erDo%Ih}*0y|cX)`Kqk=VTJvmuHe64j-L#H-sDu zZg`7?BreQq$#g{$i-|Zbn}eA8)O)6BnLAc{k59o8!{}{rCG-v;c(D%6)~#io*~?nt zH@H1-Q20NrYCd5jUHo1yEYq>*c>{~{^k(N!{jC0qCHQHX)&alIXcHaqg+`lfgFo<{ zI#ksij}IC)7pa`M1$>v0Mu6{EQhg^w>qONrvl;kCCDn|ya3rW8`0)}mItpB4q=i5% z*LMlDvif4Ama2|(^mA5gXm$G_b@GM!nTRxAp~Nk#A46E(rVDRx^7>%DTD8C1JRSow zK2lVMdNgocZhhzVXyjfLUp6^T^)ejtN06><^=P4>{^P-in?lB<=B7o5;HHiFn%nm< z@Id~2aqPiRB>pQ;XFZa)Ny2iXN>8 zDOGM`fk*c-(jvEn5qNwbBdwKLBQTFkW!gstugPzj#y-1+M1)D=pawl%EtCFfx$$!0 z8ieE#=KFjgolR$eD0@rh1L9YBR(QDbqcn8FGX?7l_Or3ztPmzV6FtBz7n~J(rojGX znqZ8NBrw6os*te4um|7z^@{2li!Nr_)U)23iD&&)>hf*+Db74pM`Ldr#iCjv^(~Vc zLTXQw8Umt7HhcPFZX?H0g#)#lXhSr1{)=kV~!89Bxf-6o00Q zDJB~%EvT;<%K?na14bxMGV#4&Pzzc*N?1%Y&dY_<5XtRqoQHw9kmfkb-jVr$Bz{;6 zW-C8RLnk~_a1yqu_L*Fb3F{MP&Q&uKX|8@&n>p~onbrY6*=Q3T@I0eUw!MC?9opal zKReSp;3JGS(E$$`t<=x8;RX-*=uGQ?$BZ`70Uv9$!TMjQJd%Gv#OlqX@AzUBIKH7A zd~&9Bz)Oub(E*=ow9+y3zg~I7F(6{GV`uBV%{ls6jX3y%OzVKJGTKB3e6`U^$I$;i zH|S^8N$__wtplEQcRha9y$85$w6c@v|B>pF zP6B7DnD`3Z%1B)x%Hw|Dfr}=%>AE_qV+Z}LLIK_}(>maX{V|6Eyt~mR+u$b|t-M{s z=HBN2DDb&P8Uv!Kip6NLXGGUiOmG;uo4O#!v_QP8bPe}tVIg=<;?>V=ozz1AF4o0m zEifu)%Aq+J^)p+`d>LpxRo$kuvfKhcYCReOUT&l@V8=RH9E^G2B@4al^5DaJE@!gd z@!;`D>Ew9nQSsAd$EyGTte-Pm2NeVAc>?2$otj`&|0p9afh6f&= z`>jrA;2A3DVBi@n?^12@_5R~}G_qWAMEqIh|C4?OZ`YPA3w(zgC$+q5Fl?8H5fMxqpRcu>4N7rO?sHaz*IwqjQA0QhB*lo@n`=pRJ4KIgN!C z{MJnCfNwI|Lu{IeVqDw0(c8`N_!(r0BSMw{q>Pc~Yqf2Ceq)!+f2n`s^JmyI^j0bgshQvdt(+L!b*$ceRj>AMXz;M+2- z1K#sbb@{IrU+~^Wn{0z0WweP7cweKHuHwh<&DBvLVpWcncPt40(FBKqd#JrFqWi6R!`mf8vz#l3p@zKbB6!(=~<$qCD z<At4n$fG{D&3WO4y3b#d)`xP*O=9jX>{@x%H7a^M2`lM ztxvBp@EH}UskE*#v!g&fsTsX9HPwdze3@{v-1N$*OSI@KNPQY3PJ!3RZ|swI9w0KMr@OlfTx_s!)RekZB$8+&|YE zs^tef&uEiv@KcR8(E&frXyx*=gi)rGtCQ-0i2{-%dEmZ`Qx#D}*wiQYou^jUg~sv{EB zOV60tQnghya7Sr!ba|1&Pd3=VpUQ0BBE7=mU;QxbrhR#3qo3dtte^7?rSi}X{DA!qbxyw3QB-lXudOagwkDN5tU z%m=*PNTa|zvgphnjsG&fAt3#f*K~Zg`)E3E#Tco8Ub#t+UrG!7W#v=q*OnO`nKwl`#K;BEA^v2T3LPZxZtzu z;_VilxjpdD&HW)XEw;1oY|V&^YMDOY9%7lXCPLl9h_^`^aE^s9$VP+ zJn{w07q1=g>nxr(7>}Q;$v^0)ylXwHN8`_#IJ0nMH+AwzbM}A@@&pbXtm226n*Dp= zBaAk;2hQf^^w#M0OY}3mdpJ%n!aTE8`ssNBKVPqE&d|@9t^Ir8^NcpP2hQf^6k%DX z{I{6gWE*^IrggwOZkgvRcxR(Y)l$q0OalInD( zwVN?^ftair{e&rvj$(8N(=`IbOkDwJJt#8*F)nK#u<1v6CO1cQJWfBW;tD=6(>ma1 z7;T~h9x|FNABww1o9KX#F+q0Q9lWlOvXyttwHvgcyB$I$!s#u+cv``jox6V@?mzu5x zz;7672zaBB765-|q@mK>kRP_d+)q`(Z#GI1PF`bDN8-^>G70z#CCzLtX_a0c>AfUg zJJ=w|qejI$W?Bb)p3&rHTk-iun{0#s$!O)EV)J0-k+A|k)ks|+n(A>LE#VI;K@wufG;)LL}mY4ay@~21G2* zSOm{7!C~MhlvF==qSaJaChb`&^G^M2Ja_6T=_BPOKaH+ZmaFx%N*wSPGOYvdw5j70 z9q`UZliiQvrA8~u05)${{j$>mZl_{0g@8LKsS0YhM+^PITtod2O#LVjsd#`&!Qn`- z9EwtKK7!j@hZX|qLgmE#phFA&82wN?vW@8)0Wt*X=?e`Eq~}RAj>^KoS1Bp+(I7;@ zuKUO8$L}n##iJ=$exWS&<0M+YHNh?rUGZ}#uF_p`3P@)M_k2I?-bn8GG&=c5^|7J< zh#n1sSwAAez;o0sX#{wtlIk^();6lY zs)`DC&`(_~wY7U@1n%9(NDGgH;{SYg;Z6FP9yj30cB(BA@nO#<(OU?gI~}jOi9~gH zi;1`CwTcE_qqOQVff_qZKPxuyvy>)meqPWkEdJFG!zJ3~KQ+Q(*!nr2a1)j)9E5>E zu4q0UpH#KKw#XJI{iu1FT1z8I<1N_*uX>GMdXIiq^#y!!rggxN-zLvS@I0f*gL}na zFxo^1{B@&Ew!uF(S~(l>?JMT~DDX-ZtGA4_zO7W*`~%TnGy2|Nq?&(Z7KVVoFw*Eu zRlAd^9|HcJlG4L28js6-Pf<9LNx)@IQ5tW`e89ITX{+>TXpb2^2b6s2uKVicED@0=!_nXuVqmnV=3E+D`wF6cIE>z7GlB=1mjBd)3Y}kc_@Y% zimgriFj0SGCK2_+GU*tFFU%xjzA}@5gt&ejM|3}u8Hw6wGpX!lF-h-G?)CavO*X^Z zGO;E*GZpV+w22OQj?rXEQ~W%mO?1G|H(I${!4K?2HD@c8-%CHG20uz6s)J3yG0JkB zepWpMpO9%C@H>q*(E+b9n!GHc_)A8U$JmO$Y_zh6_<^0Mhm$IQo_{7ln7gr>FI6NtGz@V_ff_6oo?7O%NI zaCV~DQv6awN09DGy#7_4{%`Bh6N)9<^T;#Ew_Y>g8Kmb8hG?Cd`jvi4HJ{z1@taKC zvT)?#_pQVELj9~B%K7~AJb?rARQy?{W^NBWVzfCuFy_L$#x*MN3ll6K;(DH`9^!i5 z!2d6(sc-3LdWcKo#!M_9;;z?=kF&fiAC7vSz=8X#_}`hD{d?fOj5fCi&gSOymgx0W z`WXgwo?e7GdWh?J0zZ#dH80Z7Dqp~_GTPi8IGZc?tvl%)9k;n!P882G)kN{Uf&25+ z)DilbCJK#_Oe`nLC3^8=`dJlr@THm70pDu0i4OR7qfNHKKR4P$2mEWJl}i_Xd`Wqv z*aLrLq%q)+l~fmdT6Y*@7l_H4(N}=d=qN^SFSr|w;C7~Uzz;OqLma18f~HjUSPDzHuz|xO?1FxMk|AIj9xpg z!2^DIrggwyHQGc6e3Q}S*SHn0Gg^5Mh|TMjM=}Zc?@Fq(kQT~ap%v;g=;BMp`2iY-TA?o+DZnvGI~ldDbYNIbeMlYpO9QuV~S^s;#3OuTL}F*#sV zd~2q4z%RKU+p~!d_&B4zihN} zimugbH#B&_H)UD}{2ilBbih9_+Fivy=O4otssF(~m5RG-mX}vu& z0zaUnnvoWc1Szyu1#ZyKDuuw`$+QmmqMdTz!5=Z&WE=bwqm_Nf=1)|=^d0zN6%$W^ zXso+L>t8Y>@Jc1sjI?kh==&Wi@N507`VRhMrggykJTUhi{3xSMw!zOeTG@AO-d}m7 z@4$x}X#}{JlH~k#Nsk6*>VDF~Xt0Zg-$ z#A40pzNy}AWPW%Zj#VANN9{vVDa zFKGirT#iS8XbO_+Ms<)t$~*%ieGg+gq-i^>pH*&xM>DMhe$9h&Zh}`DZL$r1+b)^U zhX!qPDos>xm&on;tJ^28Z>?@aex`gqW+iD~(R@~hiW&(f>+uN{P8w){Di)om`W?)LyDaaS+A zH?#ru{d!enBrgCb7a%j78l$Y;55?U&1kY1_a^CPS-_?UT`ZMy7I?tNdUa7QQH3ys5 z4p7=5!L{cq4F{WY8}dzldCj{dB=3okyaPh=c7^24&Dgo_CZUj$T$)>mx%+BIgsaqD zyd8z^|4bn(+9}LJ+O%?rIZBr(0#dr}{VFys*NbXdcl zymm?2^_IyLdu#u*~$!JimSe}K%G^Lgb$r}`sH#cW+xU#v0rMZQr zx#=ton0sO_+yD6Bdg*<;e#%Ydby_KJwu)Jl?Ip_nF8xf!(aVJu6Uo!f-Y^gsQaMK1 z*UX7wAby2qd%5aGY3PJ!3d$z-v$3FT!-Qv|2bkr8vhA4y`wS6@*jKj6jZ~q@4n{H& z85lA&5lI@{PDC8NO9P#VK6Mk(C-0#fmAtqo6~Q|vB=4G#ykkQ0ZV73SQ_spN-qw`Z z-%_rNxic-hiWJ{bxewIOlt^AK%q}GNFnhy5Tu7;lvQx~7VIY2mDgI#9i_*{u&lIE> z_Or1d#bLrT(F4qKL5h2(!2Y<)pXLn-Wt~iKUL)Zd*XA`wi)?FN^J&+-Mqij3&1*gp zo7a3sHm~{A^!=6fz;{zfzIQ_Mof4Aoi;#R5gycOJl6P20-p>=wdBKnz;h(7*_=x0YFGC#<>MD&@Lh<@6v`fC^m?`bec&USuE(DV5~ zBk1d*ps!mV1byA|An5Cs2SH!AJP7)_<=$(F@4Dh96Tjb~{>x4kUtVl0ZTH=}m|kp) zYO%6EO}SYk()#J;!bKIy5wkZ8#D%nCqwGEA#4r%Q!j=75su!i96P_tpS+Spu1uHvD zcqV#)SuR-FJyT$xA!73?i%hwKL@S-oBN04PV~D##!aWviA^Eftl20lj`6>GzHx*>I zlzv7FLFwnh($9sZpV3NJ`dMsh@$P2bjgl7s;5Bu3zkoqv;ndkv#xghmDQ(*sE9U`8Hr0VL^ zCDpf!H9}-@BKkZ|M4usHdGv;5C;C**;Jp3jHSb3An)jx8%{$e+=I5FBtvX}#K2
      oX?$!W#TvnVB)<3U1IZ8W8`2eut%ix}?~eHetx zM?pxXQ$^kQgG)vkqr-hp5RB$E??CgK_oR8vyVShq$H)72FOSdk2E%uJlOw;ww8s8k zGnY2fq&vwbWn=wvZ!!`6m?okh%tZ8~xYM-y>Ge-9dv|rZrBmx|r`hP#?a`+4_T_>9 z<&z6+?4`D3Q+cv#Jr-AZv;picGx!D^A;zCLdlzl&^5D>q@6uMaTqBL~EGX+D4 z{cJ2qA(-$?^Z>J5kV2j*u+K3Z8=Y!r=KgW1@wB8ofB2Zj?>dWPkrgwvH1pgsNE|LT z9uhleT3q4@tYmVzaE+=d&Zz=ZT$->2qv-g_`e2(EytZhaD1Qx|7VlhbRlTk@dykL_~+EMa?@+VW}<%M#5#%AzcjwuYz zGatr)Z&y-v<^;X~m*sDJ9k8eT>C!!R?m=U~X0(pPy=Ufb02vtJ@}tq{#NAmCNcct2 z$6QE0wl`~b{noN<;bT-M&PgpGd|xzk3xR}l`_`-5vtQksy~_cQIKH*(+&zmDLr|GH z11Ax7F)EB0VKNB`$V{pyAgw&OMMYk(J>8%m#NmJ1kH1hnm^W1#dy^H7F(9Ixt)Q?y&rAz8>uZ zl`b_1cb;aQExu<4(zR~kdOv>{$?BLQ6T1KwN5;)R~j7k1`{79S?dyU zkkKR5=&aW0>Nbt#MjT$vH zUYD%_abQ;Kgi@}n{I4~+;^(VMmg3JCz07HmpIPY?E|yFuluRc~M-$HeN}1*6^F!~_ z8&h(Wq;Fm$hsgfsH9w;7R^8;~jMjX=eUO`kHY)QxnD3KPBsZ*lI8fdyl@FK7i}5Nw zAEpxoOuok$+4Hdzw!j6tiYvkeWFAV^0*Q6-)k(a%O+zg#z@IB=R%`ijy}&Jec!<@S zaUi}V(M|9|b)$&sm(DSfBNxKMO(bzae!?fm>?vwd3jC5D z4crJ1R8iOG$RKa~YO}GOs5WECI^Ry|SQXDvPLtH?VktTH2It*kc zIJ~-f!~VhY-^#iz_jrdtmZF28XE~9Jo6#6~-nSLff@%uBa1HR$!@}Uj* zCZox3_9*_tu9?qgBsPDm`sHT=fL~Q{xf=m~Q%Uu)1g);>7e?T@N~#%Yy*D!gf6&KB z>qnUpNGIYG5#NpKOW^e5It$6t78uv7FZ6@4FjMYu{6DW>riNE9`$Df>?uoqeVE6cK z4gJmfxn*ml`ocNQ|4{NaiQHbax-H+QhKLi}*~Rp2bjVN8uII}WXRlb@hJ3JImZOUL zyXc}kF>vA9SRV3Py}Y%2(;QJ~B;;1D)jKDh5Qs>1;hdG?4TM`%+YZ(jxmoOSG7G zTeOzRLnm4UY<6|9DUX(DGx=(6S~v?gZDwH2O$*=Qrp+|0xoI(F;GRbB1xZ~a((+heh+;Q*9M{V?j*&@#^cJ9%5n&zSq7xz|b<5c~WDhvGA z%(t`km4r^hzg7-XHJS1KOhg}k9L&B<%rjrIVIh)245<7xhWxQ6uWxttq@nNp6^QPx zvqYY_ty)pKC&X!}%buXF_QdOp{oAMXZ&l>q`sH3<_?QrNluIf4jKwb6Ss{5KA=VTWK#B?yr&D*6a-faUpG_QTDdX2PF5y4fibNM``GUXA0gRz$WJ{T<^i#N%e#(ZX4ZgqWI%#pw8wgSt^*AQJmr})68mR}FHR;ag^n8%6zRL7m zwH}T?l`fU5X{ejm3)JOug}S&fJwm4$nUIW<4v2=HAjux2)=z6f_0DRo==5luoQX?p z<-0KxJ3SgKe?fsd3+{Qfj1>DsEVjVyNYA8Ms27m)EpV#7GJW z$jFHxkW35S??N|8BrL#2J{?!&lkf%EbX<`)(=fR?lGyh&OxKrc{D@=UZ2YuM6xp#{ zrwwA7I7=JB-Ub^d*jRNLt1B`I{ol$Yw6D)3pHL{uuF7JI9Ag}=z&AIgX?(rWkI^2j+ncO3 zwzkfV0-vU&`|cz042{6EED}S&G3(wKke;WP(C9P1%T^1Y zu^H^XrZBkDd>8|MTS?XP0`Pa0wsqqrG-wQ%yb^|cZ_M2QGBCpBN2Ae+Lu@R@fP`NJ zeawTG&>pOgKGyoR@RjNe&PgpGd|R5ig+Ri&!I#hoDl=!`B*HF6g%Kl6rh7844%D7* z&=2D9Kkdg~C?3q4DviC#ipCf)Z=%Oz#CF{Bd7)P&+2l0|$xr!V9VF&TDlDjCY9ykc z9Epep=0YO+*^r2X43DYWS#aV4P4E~-sco1h(SibvcG5%EXcUngLP8N)AS80&I4fkub_w0r+enWB zF_+#WD-Di%gNYB5taXVvC|qZ$(exG>jn5fTUP7bs%_hdlkHdhTP|~H6RXzFQL6n`9EcH#Y;^kOYu_Ghn<%2CA5+$cnR&})6s;p z`{@Lb)2Ll8(UU52l%#K7BZtWT<~5%+KTt==OSyOT+lT5UG*sq!FyAL-aMxQZ9}bka zO69|)@?yLK<#d98$&puN&&N*K0vG5it_T;9c_>*6B-X;^LyT8@Ssfb(?yDquQR}!~ z;1)g{ZM9|`h%ZTW6TC?8h6R2sDf~#B-jhTOd|A@-z9dc`lU=prjFhYqM+An2IA6P- z`z!C8l{SKx(6F(G#l1_2FU=(MKi@*!Mf=+`$@`BYre8Y1LXKPrPqmQ5g>-<0Q)hl71R~Bop?m$&@ zs3kyg(+taWEPCF+;&;{3rfka&(!f%kf?Isl|HwKt=B1)tb}3fGp=2q}t~i32!arD^ zs9l-*B{a{yp_kBF57h$}{j5$UXDHqx(>ma}yX8Y0@PS5?KYpk9=!a!KpF-Fi#dd2H zxUY)K-3V}hCDq3gv_6>`f&bOVNNc7#A{v2DQc|sv)>AVhkWR!WBEB2dOK9|CAN8er zxeSc!)k|n#EJQD%dHpgqyn5LedhPNOnpYm|9v`ovKS)3IB{Z5(QF7l)Xb^ECzXp|F zLW6vs%I3@IeK5!u=;h)iG%oC|p>y((=ji3;OK8wYNP7tl0uixSx*!~?+JcwRxO79csMm(U)gL%@jDFQL(5-qo*u z(IQ~H`bC?`S98;{6P_t}2@Lz$Snv`WOn4@GfLShh3C%MF_Jd46 zf5neA9U7T_Ptw)fkfq#P5Yql`tc66s>1416KsQrD?jX-!@oTDus!YT|bNm>XTV3Ew zlvKTh27a~DBpVj@yn!Hfy<_5gDOGHxk$R0;3tmEl33tUh5N`*1J}3%(mFc5uJsf{3 zU3#x%8tUft0(H4up)M{=Z_p7W6OvKV0nyMCB-w-1`e}XJGDBWMqw(ELTw*KV6Ld$N z-pZlD@+ZV4!CF|ogyz@6@U0#SB+-{6y02WOM|;c%DrfVW5BsL@vNg1q&>&z?!dkwB zcAgs$NozkG!7OD3W*FsotduHF%u1<|QmVLNMT()8yJg@H)p>cb3q_2ikbsPw2m;Bp z;EgbJlSIM-Y~<5%MLr2%kWI%Gc{2@@DYXKl8t`)1=qY@*1HWgl%2 z)5KZY2=+GE_@<3jm$BN}Zf?8iKOmFPz95tQG(k~zRTf+17~^myM-ms(aUGIa3|~S+ zvd`uq$NJQJrfHdby7nHQg5!8bFHgo|8G_|@9fYY~Li4=AT6n9fnT|To8>qWP50O5m zpVe^>`0`BafY10!KE?r`ZM4ZYc=2_a4}84Qx@?Z31fWwrTQW612H|bH8Bs2 zN|_&*te|m{>K9ocCKI1ejMC<)x0xQk21YLojE)9IFD%|heys-ZRQ;?EU)nU!G_rj2 zZ*_Z(Hb0`DTghtxtE=w?LU^h6xxOHOy%qvNnVlq7w?D0n-|+$v2$h-e;aaOhv!(hX z6&ARik%oZJFw!F6(MB4=J3zmZvt(Fl(Kt@SM=aLmP@I_PwK9mNFR|PP*UJcG{ z&Fz8jHrkvX+7H$4RD522Mf34{j`9I;!10fU@~gz9`9z$8xNT}G6& zp}~+RafbQ3#wmupi^LMIWHsBZ=!a(tp4q`dsO0?h!LIkgD!FQu@8E=DqsMmM4;#b(_KWRl(KQkQpJmE#}~Hdm$r&`QQoL!kQym> ziEFOXJ4l~D1d<{zQ{ciC2ojA%93;u2EOXk+1=HNytDZo5vFNF!mrGOC3x@OeGL7Ny z^|Md%>$YM@Iq*F!C714I&Sps=ZdkGr)hsDQFL|AMd7FO9Oa=bbNX1k^iayG1DzU*@ z@PPO`s_@pV_!^BzmfE1LS*__t1ut(hd!vK8pIM6M^tY&V&{w<<`id06oL*cBdA2n~ zT(hkrLU8xZDc{q8smwsn6m7jqo;gK6&ema_(xZT>^r)?xo}4F6nZ)}{hiUF~m{_oG zQReEl4t#5-b-*Ln=i4>#sL>|d;Ex-vyj{cQ{gp>wp@eW+<^__L#ycoC zCoDHdftMR;9QbJ?4FSo{>ZD;Q4a`>eVoSZr&8qC*)uVOUGvF)sWYiV`@lTvxYtAx_ z#M!Hs(&*Y$Sp;MjB|aMCmX(WuWOm}C@vk=Ei-3(FT~!2Wr`>Dk=jo^HpMZ2?3;FXm z%d9%!r939SV`&ffwznBlQEB0+DE0HR7RT#ztaoETysjDj*y1(;mqi_j+Zz>o`jI_e ztm$#tIP-_y(Klp4x=!d zr+`ptEwIcU1u|T~C{RN3iVo7DVT98j-php>dn6CD!5s$TLVCLnWv6F8Aby2! z;T@vR1Q9RDh%N4ajvPl*( zT2u;|Y?O%)**qTu{w@~;k)<`$LO%v<6a-=PGrBfS&l{;Iygq~IAB)-MTG#MU^m+Hv zx`ub`8H5jr!->!P`=Wa`9)DfIU#y*Bef#TN?T8sGSzRY-v6#vG-#}KfnvoWZnJ@xL zlA6)yiOdzUgr%rvq{V6^8i6cDH6txnBVh!x6xEEhSdD}c$Wl}@(qc6dMj%U3%}9&Y zNEm@EMKvQWRwH2qvJ};fv{;RV5y(3C~0iFv|rC zlV=L-zf*_kS{te{U}Irg6D~}$Trn_sD3cA3n3Y2EQ&JL4WSNx|>YC~+H4bjl%2K+w zsB~}ht}GwAX94Ae>D~+IrRv~c_i8~LDEoCyqDAGG;sqpNHKQNpn(FiL|CWZnTamxS z(m?iIZS|(hP&1OUH2C2Q?pbco0?fFl0_^3&s*L3Ka>)ncLMr(v+tN19!$4|VxHNoA z^`bO%!ZQV>8T;8-ur$DgXQBs~<$|TbGX?g4phL9n9-I@70UJxhCE?N_3x=O;G6jW7 z(O+jl9Ru!{@7;xw)**K9J_c+o7{cfm4BXzN1;aaik8U!4ac=~W<9?zhH4I3|>PXWf zYQhMdI)Ll{CKd=kQqny_!^XZY`n1^F%bEdXV_!4UVs9^uKsNR@BQ5s!!U$wzUo+BT zZ!e5MHug0mE%x@p2xMblGty#jFN{E{cg;wPy}d93+1S^Nv^HUzPoivT1)|Fk5Me3Y zWgZsW{Lg4HAdyqW^m1VtMe@s5PKJTFkZLr__P1&>3}jM-wfu9c7p0*So++rM*w4m- zS`HJQi5_5<3u?J%3heK$Lo{SVH3n?d@~gsHE*0KSHc1_!GFwjDsoMwb*?4h|IYeMRy@-teV2F>PN~ntka-&HwYSkg68uyJyg;hE?GX1Sm~d#1qti*<?0;B?=q4Mg zF<_(et_v%#)Z?J?3YFo)Zz&x3Im7mzW57m@71?GURTu|1UyUujTZDHTTXz5T-iRKr z6>g5`eL)@kn=7ycfir}3p%8$~}3C|Q%Gwc(DP!CMzS!>wfR8D%P!2U0Fh<34eOUHnXYI;Xl zO{K;L)l{f-W+<0VU{6U^jxFoa`bcI3HfpRe`WlPdo3F;=^Trm`Ki(SwSWjQvBq*5tSW%=F37{Yox^&BZLvyD4k-& zmri=J`ATQmjYV{0W2@<*_ePlcj>=y&%+L8-EwDt39c5i$X|btn>@Nvx&B(~J&#bAm z*lOMzyG|m0WUi+4C41e)znq!H)2)-WX3?=!v%Fkb$dG(Pu984pNL3PL|C0HD_!U;u zWy+7z&nV?i~A3C~0iFv|ti)H4P4R~FNJk*}um#f~-6H=52~>T9Vy@;`ei z9#Jgiy<#AhGV#%%Rtg`GvYGgN)x=}U``|DA1nymB?lo+bUy(X%vqz=;(%t5b$~*s7 ziyVQWF8$@I6e0Uyu2MLYi(|J;)1peYmFp%b1ds1n%E#)2vZ6P}44V3rH2lxGU;AExhxb?v>g;@1`Yw~l2O<|~K) zzHz|fzb729_-_aYEdIN}0gL}uaKPff4;--gZvqD_{yV@@W_?`zw`S!_5NlTS_!chT zd6l1K18&lWm2G$)!~dDDzh3wM)35b@gB2iu^>R&k6Lj|S=q5<0)GsEolwzSWcUdrN zs?VVxyA`wg?J71Bd?{2`>YJ7Zhnd$FUr~Of{&v9=?KcdDfDL8WM#`=zlzBI*^j_Zc ze#G5E_CO74>cXft8m??)zZ#NjqfV4NlJhhYm+9xMmi!K=9|XeoRArK$Ubv!ngtnfi zpTTcAA_%Ln0Fj#6THXQUzOeZ)2FgFEcK<^^(}pdG;o4&4=m&P?@1*V4qj9vUli%H< zajp@C(}(A!dU2_K20tuVXtMa5Q&T)Iqcr5|1M z;|vqlCE>1J>g^}uh9svqusDM~S%tl|U}65eb|Fg*l~P4IVC(7}Y~P8Jr3-hqHJ$Oe zuJF+Mb+neipkJkwO^z&8B<$M4){#UbOC9OE`g(PPd%?Q2(_+U_mv(r zvt9_?O-YH5#>RPZp_<~?9wc4bsx>PrzT*}o6^cG)-RYv}0p@uZCm)wdglf6Ho+-7xj3_e_|Z(ovYE^y#G_cr?(KE zHe%yY)gWnug?DEX`ahmYXumm=y#FZ5uF9zja`ZbaJV@d~sxe4nF)Tbt_SqcdSf6^& zG%a&q)ZXJ$P*WH^(k-qYaE+_NZRIO*%V*2|X;?ixcQDzHQbp5K=(z)hS6yF!*Y9fm ztbYCv{FO}WfKUHw%`d;o-T|*N+GHF2pGGTxq7|DrseW+__&ODnvH(P5{ljv!&>z$f z)c@Jkj{=`$>K6e~Sg9ZF(aP$JJ>QR1?XIS41c=V9S}R(QfA}6VdJs_Cu8gEBP%va7 zK4I^tW==J8<3Mz5S^aqJ9(&V#Tjuo2cG62Ljb#i-xVLI8yS6oZk9H3N*0#g<1NL0r z+Pw!EtM^Gx99~I6qHn>@=uQnHM()XY)2Yp=i{8l=8Az`-KH8**C<8v;24Doe7iW?m zHZL`+)t*;GIT1G`Ssid;kl~4bu>EXxW(ucZnIhd_d6#u<9QYn3$>GS79t}JSZcMO( zyd3Pbz-vr>u}enm17=Pl=YzyxFw%nueUK!nCpR4(n>fU|`irpLJvxQiA@!+izR5;| z#<=xq2-q-kZHop*>Z~mOmJk>K6jBTrWnnvijnNnUMWT)yu8T*(-XqzW3-lKvIB##It6k zg(ca=tX$EfMfXG;c&+unVx)Dw^<)f)&$UJ$m2LN}9m6ZxJ9m0CaH_gZThXJ1Q`JVR zbTKIioD^2?WMU266jtx%zNMRU3OD6`YhL8#C83w{_cAnC_$3_@R$4eFUe4*!XarMO zy_dtz%fGtO#zAJ=Uu5F_KaC1T<%iijJsKnvrJ43cIyQ-!1_K5&ZAK+A`$0LaG(Ts6 z`8hV>uqYbm^k`tNHlOpSVZJQgm#g_ZOCM9^|YB`^}Q2sMN4L(~9OWknYIe;PrmC4s*sO(&v|R)N@Is+eM!} zQ}8Fn@Pt~qk#n6~qT1Benb!3iTgH#nzB8@1XuW!EYe1F{S>YpbYi=LV7nC~X@6cm` ziCRyFVwOWPm>Eoso|(lz0!}XQe3LG(OxpzS|dl7Hb>CVnSGfX z_)`AiKho&^dE|kpsyCKP=-IWI^ScUvkV!s9Ucanr?Vh(#-#IR+?i{_9#P97SqPO&^ zVl)mkZH(j0)`7(+mU7b@MSAvQwJQ@5NdGprv!cRxHK=45W_)J04zZ3hI28?5x$}n< zoiBCe&Szb70$pXn_PrO^2?VZcD*2&9vN0j1nDJhEmS!Kurf(O?hTW;Ef;ap#HT)a> zl#+gv=V=8@YYV1BRYSv(HG|5NT=4RUzgE>qK@l!m4W(-bDU}Oe={*$po0lMwS#3zv z;O1#Jy}^5!-RMoW!H>$c4)}~Y`GydDrqL$b;ERk_9!_HOiK<_29Dy%aF&XJ4JsRk$ z?+ASuM^wvl(>4Tri)xe5;MX~s8n zoQyQ^79%YLqOl%lTIdgsp;3Q`=^6!o)kuqgD6H@NX=U|`d_wH4I*vA7Bfw87=@D`a zedmF9&i(D&&P5-t|Dk2q_PjgiKK#xD52#M5;s314JxJw_Pttv?u;BJ|O~6mb_Noq( zr{fy}L}I!I=_sE^Xy1Nh;Ti{GLJxLn{x)->gwGMZ^h0AA1ClOwj1B>{jdOBH^erfo zk5vn3kvsz;J?(_VYZPn_UBpn1Oo8~d@!=$YMHz6yB0PfL?Q}{9Rm4kG`yj*!az$et z`7Gt;1ajq`=U3|86fVIsMK;0m2kYxNu%&%Xr{px~NpMPz738Z^a`2x`eQ`>T*p^l; z%NQ{d4D;X-C#rlRN#3PHavBT|hbsv2`4;v19Q~9{^^zWq3$07TK=g`{Yg;rhQm15b zNRAEI(;+zxWI2ApF+LxxG27i@S00iFJc!%pCAx%uOh2m?5PWH-b-;hvKd)@yyNx#4 z2Je1A<}+gouz9U5-(BGERh7&#AR6m}L+j6(5xBjYtQl$HNHA~l<7)F`6nK}ZUkJo< zy;Rc5>Wf2iLUyI9ug|_|tv3r}K;l_5(!x@GXhQ3L+F2>yKwPOAebB$BUSLczy3?b9 zt@^x<7Pds8oKn-mTv9-zVOvJMG|^{?JP#q!72@cNXetk^hwM#m_0DlW}FkVALedpeoikoKgY%ti=uH( zj|S$bezY6r%VqI&HUBW3S#>gdCp}l#6VD{a!28TD9zxctZ**qE!{?GIIDGa@V)e{H zR=3tp(%E1WSF#j`&#*kmiqS9-#nIvO1DtV*ba43Wxg^r%;j?E74xjOadApHQnB1XW zOuJ$}QhP}T*C(d5m_Bui4)riYipIyx2bVhK&?(k=Or$e7W?oe4lmjKN(~g+~M}^%_ zle0^ua=H^Ml?#K!zoTmE!y#IzsbVxpX>d4n55;|P38u^(T~+7W?q#wKetf2Nz;Ae5 z-sON#H`-(y{86Ko=KrD==H)TfPJC#&3(!!BoH$9Gex|4fEw@W#(h+%JDA! ztW()1gy#x-;+bUI@Yrn!Y*ywwvnh+c)siXLtav7|dj24*r#Y)Z|Apo0YSjaf!5i&(rtWb4jGj&5CCVHY<3-yxqttOzu!FL>x#u#r5+2+DkIH-hR+x z`mkBSOx9UFLH9Aatkfynk67n1y+CKMS-H8?DZ3A^(>5!C(qOZ)jjk@JsdpQ+=zOg- z*sLIav@My{lPp@OsW&UM`jrNom3t`ei%T$NhVww>Cw22P*ZAP0c zDhB$GQ670v0bFgQ5g?lC{f1Aa1uB4o&8cf<>!btGd#v^6)dzYXUaHq#p`Yn1A2e1f zQHlzXo=GXVwnc+(4mi`p2JC5}pn)t4g?Dg``tTn8tj^-V@6WUj_!mZ-=z#Aq+GHF2 zv9)=ZI>_b^RZa#5c&m{{fWK5yJ;=1sA8ab=5<2Avw17V`^6zQ}H& zFk39XT6L|e#f(V#KEraOc~E?F7?!N1IKAF9_a?LlAGS^{{Gq}VbeQA;3Gf^xZCj<_ z>=RqN9PkKvaCV+j-sJy z^n1k11=Z3^Rqye6vFP2tAbWjRV0na&gyjr`N9G{{9_o1qDTOgeChRhRQQ|yW?L0oa z07UcDS@K*J#7GcYSca8#rtI&1cRY`*g`S0S^#)ZlTb^_-ldq-GKEt}u1u_R<9i);9 z7z7cksEUI48nyf;^I#Z==Ba~7nP>6@_0F?M>UWAM`#GJmSx>Rpc$TzF@^RTw^*moc zgF*Ey;djwIQ#64dQP?W>6|g+s+$lBY)2wm#~)IwQ< zsXS=7O7r1r{j4^X;4f!d2YlTPd9w(<-e{9;@MFH2`M~=bZL$qM(`XYN@L5KiY=f`* zx2(_ils?>Px!naK7T^2-hz<4`rx*h&e9iQ0cLX}rMVHz-D=?;1Lkm# zlpYiZRhT>20y_enrzDxr3wnVM82p3zFapGfB)SP+h}_P-z>md+ABod@l8AvXi+kRe z#OX);G1_s4Kn@;{C=AQd)|D%I|K)PLrg|$ibSSm?V%`7<`Lx>&f=qTEIOLYqa! z+K(b;X!@}UvP0M0;WEjo(UhO^d2UB zo4%t@)UMH+8Lgwd2QScp`h*SGIQ8=DnFOSS&TK8|(EAxSh~rEVJeDoYdFld1JJ{9W z!sTXf4EPx(&1$VUu7_XW%zVIxUoHIlf#ur>a7%M_40vB9B@3nhW2OJa&IJEY&wc^% zU-nKL={ z_q->G(?=u`eX_q>W03UE?nVl)YYyuBCLaqe9!{l#l-I{#$62TmFpea zFUusa8!0AOs&>dR#ljMZB=%AXL=ua$S|`Ylths+k_StkiEtvY$d!}ibd#CpPVvE8k zFuS>=eB;5F3@J2Jheui1$C>s|wn{Mm4uv1fB+4-k2SuwiH-@>r%-k68(Mn2Hru1Q~ z^kJ;@p(s34_^{rRZw&Zwb87?-cC{{#0drtRN~cCjr;56RxrbzPKs=DSxuA!^$C(c! zKzvAio5zb(4gx~#2?@8kH5lKX!`1jRVaG#boUo`g9i* zEJSZP-jHGXfi@gnOw6^&cQJ5rCZYZen}@}Q3@K(#Dm=(Bcfx9fB=+P8c1aIOET$6W zLy2Uc%|T3k>OIrDw68GDXwCO5cr;~SV4BkH$7%SFvSAqJ?sAF6yttV~>dhuK4m?9i zsiKf91V`!>@!_T_C}C*NK8*uUGlL`O#$DNv0JG=g!0f?T=|NGzFn4k`2gC!JPYZg1 z4;VblqBjP_2YKUYL2nbhNK-iQV{zd};`E+~*`0fVFN+Ib5~t6(S86Oyx0s9pxuvLQ zdKr|lH)t@3fQ(hy|NoD>Gmn?6Eb@M5AvBvb$|zz)c2N{=hzq!a0-~s-@9owL+$64u z8zw9XNVqpDqX;U5Ah^=F%c3BnFb)FxqQfXk6qJCd5m6XmSQG)3k+;q{^{wZ0J=Hf0 zIQp6VkyB5ddVckLs_J>pb55Vzovqk-Tx=e@V2@dJyI`M`RAB#SQu)yUM9Gw^0sW}W zaEYKN6w1|ro_GwG2zvJU97L=S-W%a=Qlc15%IP8v5k|pc!}jevy5N=%3RV7L(zTG! z{8@TnhukyW;wJKDKTmdkfcU&CE%JzGD3sI?;-^(5f0neMM*}z213+3hmEPXxP3j9r z#Me0bKo6Lm>NrJ$p1hX#t;$NLouf8keY@tOD}#C9MZiZ^Y@E_{xwL5eoiv)zg#D zUl`Ya7<|{m2cOcMtJXi#V>!Wnzi`&m^CI)tMub9HFM$0e*&#B}@X^gz)E>}~gf|Ml z2NeIwS@0V(7{N?%5L3V4H)gz1;Gd#7L&qcac0pLQ@*-7Sv|>(r;8}q{jY6rkzLaOE zV@g%Z36VnWt6B=FDn{>FdV9A)ed2RdOL`Zedy^^$$~LYys5JvGtHAdQOM{*_o4+<9 z6w0~-Y<-=Bl0rn{8rJ786c^Btgf|N6V_p4kss2B1;~PVyjEa@8krh?75Wg;adf)+N z&ok5uAeRoR(^K+W{Q$ESVan@|kf!`9nhP?TLyz{j0UTA}>b-GVi!HouL}pE8NDJOF zZBEHwnti^)F!R=K68b5J>CfpZ|!yx9&Kx#N!!?VM!pn8<(-qRg*@Z> zwCzD&-*k(c$j6v2|I-kBzFP6+Qiu4ksYVdjQ>1cxL<2X~_J|fvgYD4^6c|V4GC>1Z zWol^PO14Lc_+fiQ8^7W9$a}7~N8WX{v+=&G?U8qH+avG40`V!v)xjEq@&aNFjjq)A zG!;o}X-8vgJy~67Xw6T(5#P~gNQ(#smmg10s)2FsYVchTA8d~vr`FHbW4Xxte&Nbb z&za`0jR=LZUI2STvO{E`;pOLF)E>}~gf|KV(1-@Tc8uWaH`D-IWp{zT=-j(bSiECJ&FI9U$LlWL7sE>8^ z|87ESyvL@fNEubzBU8~_P7DO zM1iYa53TEQ*JvZMyjO;_2yeVS!U@-l)m=JjXu&rbtWr{}B5QjM_DjTV4o~(1K$Dh9 zb`lR)(~8Hy#~C zcvOaia`hGS&_=|0(Xnk*ewPdpab6kH!oMteh;=IM?7rvoiu^_M&_P^js=2WGZ&ekq za3bScCf6Ps2wVo&sDD$0%M5%D;?GSr2KN7$Y7Sy@HS#IF*BXinD#7*I}-J|tHbJ|8^xRoKTo01_Sd@4g)cO^qa2v>%_9F9}2*BR%z zh$~fPe+yCmMIGE1nWwq1yeg>>Z&g)425g}gTz%fJ&Oc_nh7sW>U*K5m0=Dg;fN(4Q z31D$v{tOV(L|IlQ#KV=L{9M+4$c)WA_z~I(KhE4WVk(A35IU+?`g7+};UL$$0>=NR86+0H+E&5X%lASna zOAaRcYdy%P?9CpHS6h*^5#La^^SJ>GqaZh!Kq<=2u=+SSxkm(f!^Q&n^OBiiX5OgX za1ku{n7mC*qrXrKZ2Wi|%-&UsGef3fam}RtTN^hiuhSmjUa+pT(rAATHi~Ch`6i_eL8TulXdJMe$iBO5ph#sb<8Oq zf{XMl#elU;Rm3{hBN)Km>H&&E0;Pxx^DQg7c-KH8r{Ija6c+mQb@{zzHPFI(eA+5bsD~5=#=`*ASV=?sW z3xsbrb{)ifO*MuH#cF+_wXYE#L&RfcxO%5;oc_t2&O^jafz|HOT4GM;A=aJdPv7#9 z4&(HX=5#J1ZVIQv=JZr^Iv26-bU3?L|AityU>@d!yp3Va_wm_MPwlG58I2eAmQP>4 zIqes#expi1eg5+1@+Qhx>&eHZlZ#H6n6W^1Ma!F<99E-^lhK^zO|%R3>|^w-e23Wb zrkqF5nBnF5Lj}C*a|Bvbt!(EbPP4KtevZ&urY+vbpz3ihe+@jyuK_d`U6SDFD4$;h z---549W!H;turF^CASlZ39G0{&jYM=;c>e1AT%;e#2Vacqx8HKOZ}k{t5tEf>l3hA60VVeJc?C#7*}!v?%oje$ z!dfQe@ftjWCEb0bf*9bmmhxI9GZm^z_8uy&cM@0q9U7vVpI(|VH9sd$^zbt~O-s?z zdae~*2azF*YcUK6iPqN#gzmBAckv6XTvI)ks65cNF7D;0*S=r)kv2Vdwh^@vp-_Ha z4%mUo4)Kku3O`rhUQYrVlJG{s=j!X~-|rQI^7AHf@hs4REYxGM5ko#Q=~~Fo-aT!w zkoPp*;wJK^OqXx4@cDklm&_v$X*ao1MtqK{imQ0HM+^Mmfg11^8+-?mUh$SD@7Rty z=GTh6<1ihsHWDL<|7BraGzXbsRa+HWue2a8+Y`AygnX~^b;ZWLTmcd59Xr{ar6W0& zSH$+~(MVmF$qMFYDW$PQealWk-UgucEX(LTL|`jJS`1q1RIZG)a2-4b#4iAALHSCh z3L`;B1Z_>o9g)U%vWk=N#VLg?-!vkZTv`m63p8zfRMy^2rS%#4nGSEu#BY$vW6UJG zt?($ZuN&1@0?NL=E;q@1!IUhlWkL?nQ4lQY?jscx5Kc*XUjY$+DMzV!@1W9pAC=aJ zdRrxj8>y`GCv0xj{K!=sKkv{!f+$*A3oKb3L`Ga0285*hAVNmvUXZTO$U~-E+(d4@INAC7z~`?NUowvfq)e5S$I<{xz9Rmr zV+VoVXkZ=0XFR{+Ai+W0RjF1NXj;!ztr#L6`ogMjWk~A+)rukFsy;(nJHE(VBhFJ* zg-B~fGDKv!mEoZA{?NwTM*P|Ha5{#_2n(!skJejkykm&Js|};wqjj5&cMS2tK0{i6 zO@@e!yK+ry$i_Q{xL++W?H;ZDlOZB8s}O0uIT<3J)`v*zjAV%T!#+b=KTd{-^_=AU zv%54Gf6(K!hCB$N@k|Z&w1zx_Ap_u*N}uANE6ndxiV=6P%#9#2OJvz!wWLQ2M>6YI zEV0DnHh9Q~QznmmGh7Q9@4-ifLANH|ZdU&C>vv7$1eM*55k&?jBoP_aBOD_hYH(K^ zXCWgv60!@9%Pwkr?NLoGC_Vb@?obbx=v*p(CVPd-%(FtrRDy5xbJ`wDzSQ;1m*`V+ zk6AzGvFqo2nc|}s&3jS-G75>Nl%@AsX}z~f>;1e~mo*Sq7nir`^eya|`(Lf;{5l)O z51)^GY_O@u=J{xJlpPt33-u_g!qO!@T1Tr^7AwSB7R8Vj^(1WXIW~)Ar6rbJY}7W- zmmv7Mh2|q%F`y}d@Uuu%o?v0+*aZ<+is0Xl?a}(IMX-%{sBWbs)MEG!y$VgW zy}+`&j_vtPlEg~1?1&!hvxQ?rw~3Xlk03P9R6=qgX(7WbxF!YNnt8YE`a`#KQczA= z(xdhNEGS*XT2RC=2#OS25ERh{K@n{b6w&&id`^kfy#Ftz1nFDe7V)n`J(gOitC3j_(JEo6gtnL ze(hoY7dr3rN=?umdXzdkYe|pR-&89Fh)Ce%=5fWbo}Ju0UU4k+KCX*Vse~UlJ*CnI zr&K;-h7T+0k|B*6?b{;SD~l4r1+cFNWT8)!pY4*L&KtnC=Qi238*b+@o6-mV@9~;7xANQ9g0={ldp^^!zUy zQ5z8os_nX zO@K3V@0X+pmo@M5a3=6B+Q579Ajb_{ya$hW&UW6*m7GA}yqsv>cQqw-*UG@FDd{|i z^AyJyDgl{+&rz^9=uuRDXu&*viCR+zYyiqVu)@U#o!K|34>VHy_-YD=-iYSXUnIGhGZDzucv=koUdVuRSoBaRdCV&jC z_PGHwK!zco8%))J;-S(86D|0RVG~`nL99Q0_qg?Q9=-3JTS_)lA0%q^lbMmM`Mkx) zmUeOLBBoEnm<_N+dclfUh4A@5{5`9>6#-(tE&E#w8JTiisR zzE{HYJHyeJvRxGMvhg79*0!|A_U$dMPyKu~VIfjSH7r#B9%5as+7;nh;zrd4F9^R> zBS0jkG!AC?DJKV$3kD=si~?Sw@?=DnGdS4K0p2Gn|Kei-Et_ERDRfW`K$2we7f4mWeD+`rW!%KOjX5#)a}u_I~gM4vNB|V9C7+&>)1iO z)Kv2jaZ_M*%qbp%7aR9ej4vA22pD%J6=XQRQct}`kLwlhXf5A@=Id3xeq+JW@;7kH zw*d0WetVifP__I4>QG@$`|5skymR#2%fFh%73@nTJvjQFvV*##t8espfciQ5bDX0D ziC*1yZE&zro(Fu^5}UdQ&wo#y*gZD|Gax_*0_H>#Sn z(!QzR9L^kJK~T#K;tKX*T76H6(A3vzT0KDh9G*F13(+tg-e@wwGjzlZNn#H+0}9eX zuTS^Ki{=+pZRr5=mVSGhx2u|T(1w9dVuHXC7H}^kk1P6y>F_-zLQfpkba;UJIXrXp zwqZKF(PV&)m*~5_dMs{=rl>qU=~~ENG2NmT@&%?_+(f?Hbos>tpIfSpTs#oJXsQv! zud1rLCeZqIGDO5>eDT2PCf2coc%G@|A>yXGc+kQ_aPin(F-|wE5qjN}RHTvP3-r{! zdepk3*;cicHINte+td7(swr#Qm-d_EoulVoRxqw$AC|T6DU~+oAT4VTP(O!fj(aLW zqF1+F8ysvIa5z1@QQaAYIKJ5tlcfo40u!uO^m==L+-V-6YD+7SSN7Y}{DG=TEA6ZM z&Ed=u76i4-Ag*8^rq%b92)*TCO{)i}pTjdpY#|z^!y8Qo_yHX;Lz38o&47Y*(Cfqf z@uK-rRa-iMysqD#=8dW*9kgLE;Nk%bxR;T~6@9~W_?{A>@iDIDN(O-XInux}cP2l^ z$4QRfXfnWi)cL)7EG{0%_a$8mdF-X>2^jM0Ot-j+Ji2$XgBM49&e48y@j&dFY6Nkv zs;X-Ot!F8|)C%IuRaF_%f=EzQ@Yu?nb`W1{sxd@7SJx9-CniJ0&zh=(m`G$_F9Zo9 zARnM0;-m1`?$P>~!M73rqN>V})0VSIY1#m4uk%725N5J&Mr*JsS6_QXXI;);t^#c{m^o1Rg+;N#>b}3O*cvmW@b0 z7V-VUPbBF1D#8YbE#wXNNvkAs%XEvI$oHBq--_e&cnfG3aXsxOUz&!vk*bPm*6q;(KlqBb z9KHkm`UXD_5x@ez6ToMGpq<0FfxpZKG=f-%ZyWrZjK>Hf11fmrf0UOy9meSfhBY6t z?sV9k;vx9@iyVFw_-O_|hFFIm4dAmY#;qEchf;h#s<7WT_>o&wOgyu{e81ZP$!FJ> zPxQe0rUF!2THiJg9YmZ~hTd=21<_&M(9)E>}~gf|KntabJOBlUl?9%aGWGrLMO_SI(xdMuwEs60LC zTF6g-Sz54=hfF7b#;JV^`EaaL&P04ypHUVYJ-th|b84LP+#4o67s(h>PcU0cc{LNqL!X``hMH(vt6|CZb0ywp?umSVE z6ui(OzshtI6MsZVAb;2Ozg620nC-#_@?T9iF@e1K%d0WLe-CZHOpisJkoPy;#02si zT>lSf`wX*P*g*cI=_V$SFLeE{*Y>SuyRdaZa-NXcP z$Mru(+b5Xq!Upo`rkj{xZQ^*g)(iC`D^fnivOUz-Traug%2%)Wj+GWq9O-+fV#p%v zI|f(XA2^TYwaxbnFL?C4!Thxmp-^5;0eiMBL2X3Vi14brLU92NNqD2+rNwpie~|h= z)5bTSwQVn3$mhRG#iNsoRs3&BwZ1M=U$%vPK566VfugSx_cpK5Y|(%Tc8c4p2TbI7`*{oW;XVsB zM{IZ2J~L#?x-j_Zmz^ADzzhi72Fx(oRng?z-Vg23Nd2;xtzM?~>_ZEd69G%kv)`QB zcwQD`Zxf7!Z7eXsNRC%Vm`IE-JbXZmu{}xq42tmy4l`f|1a1Rnn4GL=WsGU0ep!q; z#a?@A;{{plyiLIHTy+af!0-poL}K@jBL~C|+n;EkL9zR>!wi@KF$ptFex_(;>}aHZ zS?oB)ea2Mzrg3H%M{g4_m&pFaK#rZxm4Ei3K{)_0RT~Lp|D^Dk7Vw30}3B}VDyk0%f}6fcq^Z(;O|K`oMA*L zgil}osJMWJB)n1ZnFs!pv*54uFoK!jAf|r7C&}I@@Xs^f+CyaS3nzJEoc9{Zdu5-( zU7J0yo|pH^p85U3^^!?C^*uUC>3+FpqkhiUA2@$jyg{qq{m!4v7u=+XWMcz0#c@r> zMz8--pXC}!BSE!u0@=(b1XpS(EtgCRsN>w@=x^f`5v2nUBoA8Hwi!D4yr0XplsVxJgr8#Ya}l9f5bhY^1fTtc3b7s2c*sgBKj=ei8}l#^k-%4mw36Rt zOD6)q*&O>A`85wCV2mZzQWXia#0T*tJyoT~PrXkm{5g8mmkw!uL)G?9Bfg)ZsA^Ah zH&ydaBkkw*n|l_1kmc)(xMG;$JB_}lEHh6yUY8&bP(Me&h)(^SXLpuMLEZMz@&OKk z3SV*cMs*^d^nW_iQW0Pi&|nhL>ze*@pn1J72O#(E&o9kaxN@LeI&fGtGBba^B|WF z+AtXK#xX1iY8iQ4(Kk$o?L-Dc3N zBGNs-LS;+&h8q5w2l@3VT1;;Ff`W&~dw4iT`&3$5$Ej9c&P0StW$4*dS|3&jJYwY&=Z$w(7FX!0@944E-63C@bS>od4oJH@|MzR3^~kCmaHN4e8BP8)_b7ZEoFR=Y>*56KXbxKxI;pc1?$dz%jWZ#MWb z;I}vU?4713>#5m#0mtQr5P19Sz#ppBGZ0$$E3iE2L1eO2hO~&kETyvXr-k$2 zK@old5IFfIC0cY8xZsyO->$3}zAW^JREOjr5i)CBD8NHzZKzEsHKMhSf!oa{`}}-b z&-XdRDGNyTW0|xVKffJD8y}UmcN72M=E*v|>r-8LGMHR#CfS_A1eDmn| zf5Gl(Q49GB)5$lQsJzil$Tn;sP+XtS1Se{ zgV$zGP?J;jSiDh)e6dj&0qJi^g+GqOiyV{%PlGH>YaG|=(O^8)#iV61gKlXIJjcMz zP%m&ZG{DVJEtoL%FSP<p&U)@Xqr+_nL~ufcZ^*EjevL;$O`idKTpwn!t2F{;On z8^g<+-Q~@Lmp2buuFs>$RHL!0l7NA1z7b&{->Qa)`!yy5Ji&S-aT`{uueZ3(N#m%b zcj_tlJ`(C+LA`wFM}t6A3+GUeHhBr35FV@SCiJ*rqfE@Gd}mb?-DmaOMt1JN&drab~;fCYKLHyvU!ntQ@BSynM&;RpW#3Pc{4w;+vGJfPHL&2Ar#_5v_;JblC|L zH1>XN#ji4@^FRZQ?3FtY0{pv0bZ&f~c z92Us;{wWINkm0I!S5MIgu&iMpyi(}{S1NtbN~O>DVanzNJ<1*c@f=gNuT$|?Nj0R4 z_&$0J_I;Z;CX+2sA{y;?FE5pt7GQ$<7(&CqkNu?zKo9acR()z(d2tV?4 z#5)m{_aG_{A3Rn8o3V%qVsbZ3glcw#wb^VoI&=!Bkq1^Ng6?1p(C3gjYs#kdcEOpFW0 zM|9|EyrT5uEiDK6_z#PF7Z0Oa!m>LAf7C+U1^xF)<*@-`4wR4N>6brd=4_|gZD;jL=>Y*Ii05=y4*t5K}`LQnUdX_+@?8sTG}wI8mI9xRmxOF z+~4eu+o?yRo9ws>o}MlxE5?t}t?!TZD0ug&_<*T8h>x`)%td^>s^k&#PCXi|3xY@sC=jy6P(2a5&D8Y+6%Zs49C(H5e{Y7bzmX=w#dRL$^{vZ($X_2l>wIpJ8s)}jYSH8%*n6nz|&}DrsY0FnfnOlBt8~f z+`D+V*h1U||1isG7xd5Q^97lvoJce_Uo_#(C5$l8Z zMz7GZVie3I7)?4Bj3%Yc?aOb{lcg2oG#*x^OdG^$_E<@-f;8C1h#hx6Z?|=IF5+_J485?c8?B=a#{sE7Gyk1 z%Yey(o@Y{8`iPWDACvnvZz%vW0T0per_qWs_aVyMM=*c!L1D-=!~+Qz75KMXIdnn) zT$<9JKfS1ga;nmgS_tPaJ@HpgReItvoWJz!^ErrEAG|mEiH;ScVE)2r(y?GPDeaHw z^4a&G!ZY$l!DqafEVt!2`>ZlB!TK!gHHP>FRmq3_NB3yJGWgvq4>eUj$p`E62A?hU zbUQ~)qL1$V^QMjE=Xb|Xo8H`d`{vd=+A}k*Ya7cC?xwT;!CC)VR!{Ey`p>c!a<|%l zmRl-np#Ln3H!FPqS)X7=$OU_PV_Y64vy)Vlyf!fYpopk<(_70;MK^w1 z^$~Sxz=>z8LD3%r!9l%y(0|d=iRDdByjTr3qyP9lB9$hb+NXvg(8+)kudEpq126RnkD~mzO=|vBYs{tpNcAGaAtt!r~DE>1mUnZM3mK6ret|4XPZ1@_%nNU~Vu%`8apSv-ER%pX~ZMpW^yC zpWXU7pVRs|pUL_;pTGJ!pS8c}Jb$fD1^L_-kw@X17mMBunZ(7%en&L6T6D>{{28|& zlyvmiJ1QpAC3s5imkW6U&k{i|d1|?I!b8&!qsfNIBL06VZH$FaD*HYkr54N2JosRc ze3eQ*7^M12B?}B?S1P&2Qg5Y_<%2>im0VHz(6m(gym{XC0U-l{yM0FI`P&IU20P)$ zVJG}p?1UeWo$zC_6KgoG^y#h}*HCZ3xQ2QI#x>L%Fs`BAfN>4=28?T{H(*@(M~blI zMTs)0o?)r<>`J9)Rw_NKQt26$$}GzI00TCXj;qRTlV@ZnJS#ilnb`@?&Q5rScEYoq z)~!C{oT10!iY{9V+2P55#U6(f+p0ma$0_#$$%Ipvzox>HOYjNO(^+x$UbPB z=YcbnMjS9-Cqck`#l%3qd}1qKOR<$Ntk}v|nV*?*1-$k%x*74qte^AatDp0us-N>? zsh{&BsGsw^nH?mmZu`&7dkdYc%uIO*gV@$nGj%zdQLajd7Tcv|E5~PSCHK9uVPdkj zw1x!$k>Z^kz(+>_d~koKlNi8Y$K@9U*>SN1&`Z|de8)vUjOuywGzbhsE*En;lK4{T ztFcu2GAxz8{z|1Uyi)1eJYCa6n&dC55Wk?O)BLVKYj?|N1jr7C!+EmMCIXw z$6H`C7BN9Q#YQ^kG!+wrIWXAX9$?NvBmCp9;MPpO|~Vn=4`h`&$B75J)ctP<025ndyx6N&L41j zlmOl~4y#()ZX5qsmypsD=e79XmVKs-k5oQgJTO#Q_`pv!&;^~*1j{2piK@IiLchc+ zc%g)zP$(aD(-V*3^KW|g`Sep1qds_Vgu6+JVl*kIUubsjvKiDtO#R-Szff|%=Ks%n zl&qdGL1PQO_Q)!UI8#;A8sj_lXbdGge@T#Qkze}-jg|jD?SqYZh(A(Q>43&f$&Ty8 zUA72h%Qf_&Ck_!|D(IuxO;(KL8I!Cf@X z&$k&liuig{&C4h0=(U>lTWzL|B5qP7>p$bh>((+9qr+8 zT5^a8htlrRVNp(#fX9N2M`;-_S=1ES+O31ja-sxI7i3OL%fRh|o_AYX z`ZD;wMw)@i9Aa3{v*3=rLPdrpRvtZ=d|;DRxx|6}OvCPiO#;OV>`nEr^hD)(0|d!( zp3#rohLew;P$=gaJ@FV$K6>`~97L=S-W#ovyL)x%fm1L;kI-eU?@@$z=8b|(VKQOM zA4n#MA5zt{#>CM*8c+(p=>;$JpDMorgM5;~XDO%KGBt@_+SpnvW*hta&c#jS z?USyB{36pWY9YVWboq};fInMpq%skAH`NH@OH9>81ibiD#%}gbdk)_LzTPqa<#k&o_{Tm&TK6YI#0UEfY3;7Tl2Ie>qpE5!v_6y!5zp*1q(%6HrG)6e z$)evue9U};I)?bf8sScl)^lxSV~7m8Al&KEVubQ$7$VdvLsuFN>TE-$BHwYgbi7CF zf2=&_AyR~uAuY;8zN6}%<9f89FZ%#Q=vRic4zuyiL;Sb}qCliYO$Z_)US#ByhPRZh3Ze#;XYZ9YEN@JRr7`Fw0G(^ACyO?j{H&FQ11y^u~+J`RDMwx zvCH*XDsR`u5pSp_VX6G9HYm(e*-;)We5H~G^~yKGkdUUX6Q%JW>Xeauy7HW_>Zf@W z6M3$m1DxuvpYuL?nuWio4-!kJ!bhUsXfo12QqpTYHvyNrhXk1s6(UKh<_r;Lj*1~7 z6Lc-7D|z`}orT2e`uw(l3-*VFT@=C6$ih4Pys0sBm{L!@BCuTXuR+5;Mr@J7Ks`?~tSGS65l zfW$n=weKmLM3O_lVBhHP0Kzh2N>R8QHm2=#!?d#4dNbXQqkfKQl9rv+kEI|jJL%ka zby}rmC!J&2VJlMi_iRlbcRKZRJ{I+Je%ko)O5FS~Mde2)DnBSu`LT$~4?$F(xu`s0 zQF)$zUntjnzbh1#-xG=|r#|BMgJKnLG;;RY^Y|y}LiaR1>Q$EJvs7(cX-HqBwWRhm zzolxn(zMz64!DT>=#dzj{Tz8t z^Dg=Gsjc_(wf7WvF{|7DGxPS`!ri?$st?Ww;>9iy@|42oMpQl}qVk!jJ>Fn(6V)Jh zX~WV*WO@FF%z1W6|4yFx z-b1DJnZpSfvM=%-gRRp3*^p$b{na+JZA9uY+$yyd7toM| zHwv~&_)pG)7aK5wncyI%e!D|c7E zW4Pt=J!K{E{es0I?=?cN8!Wp6p3ZshbKRJ041Q`@+46L#_WG0_Wh%&zuFyJ5wK9_s z329{rTRc=+PYowv$h7etgPHUmH=wd!eZR1X>3NFLZzDpXoFRaH&*IZYWI*9e`hemB z8j|ovK_%lqISXbIMlcf`#MCdCN!}>%zrI_miYei*a)pk`%*>6Zj>nSn^H8GlNWq-& zKr-E~IxdHrn?q&aC*h&wLJJUkj8d&6_v*dR*lV-4HCEfmYz?s5w#JaP_71m?U(EjiFmkbJYMYq4M}*TVAkS4 zISW<|j9?}>h^b$&YIvi-|EaoauthFb10FoGSVb#@?XniDmg`k+Bz(VccR|lTDT36!?-xvkYcqdR zD864rd!lP zzQA;go5(l6E#Z0ka9gQ7q|y+du23>X5b<2iC0gesLquFxhO|ypB7%t6Q&nY1>+)oX zcuk)nt(%e|BBQMk{djkJa}|qyEKaj}$cNZC<{+MDsxd?cBOe$bP8>>rXZ4UzQJvJo zcU4?zsyT>+q4+@_27jK8snA`j^3Q5IKcqV~b?fQS#3SM+s**j%1rt3eeZ_c;Awp4V zT($}@z=yZ5J+=AJ&SyJ+5a>rX4q-CbH~!(c#KVFCBPw9+?BtM4fh zn*TkQRsibfvgj#sY{PUgc#I|keC^@@^dDLb-c|ja_gFvY9oNtKA|j%MC@dmxG#TK}*S3fNU*{si z~QY z2l{^D%^^KsZzCE;ghF}e3D{?o9pZVa3hz)4(vyIOB)n1Z?aKI1&VoBsj9?}>h^b$2 zhw6<2{~b-yTP#&0JPzOiO>p_6*F5dDUZX9)dbtHn9v!XUkk@L96F^?A`)jqQd9A9s z{LzMin)@DQU2v_tCFJ8WwMpff{Z4`YXc>}kcU!&%&A+MIHYl4a)aH8Biv`UsRZWIyLu$aa#Sf=U zh96LvA>UJi_NA*eLmr@h&WEOc&d2D#T(Il5kCqSON}$3kj5n$i@uVNCl@U}3Fu{bS z*G%oL`J%bKs;wLz)}ou zRxh{oXNczQE<>~-H6TNNIAt>YfWi#CI9O!j+e>u?nnlFcIG~d_tmjlfkT{+N(!GLmr1p)6X2l|HP z;Co7h-u4q$4gl28`RFk&Y{PVTqsaijH#i-@1nHpHHT~(JdA(1^F`FA0p6vNo2xr=iT%kM9AHGnzLSq+ zgADyaff}~sFZZ7`H&V5&pXaNWi~2J}^II-Mv>`PhLw-1AGW>wT4EdfCw8vei8S()2 zb3Qcnb3S|byI|LCA1xoml|Y3R;*IJ=Jn5%s=7I_VCMXAbJ*~eSXwLHG!0=D&F9({R zaOFU|*KfW$?tSF|`>-6~&!{CrPy3lG2LS5lJOjoB(J&p}XfnWk@^pX=pCBFdI-oxt zG+*n}0p#cV<4f}#mk!!67%)3wK~T%cF@ycb3Ps3HcW>%nhfy0 zdQ169Jxc8Pc>5F$YLJfitMw^*)aM;EPgAu$P66_GOJDi;h2}}B=4PEX3@Q_v*2DeGU1(q-!C+ z;~l&WwWx)>z;uh7$S;3qvK!=clehCIsEfF_LP;qh?yIWmb1qu1Nrs5;>@%cwb}~e~ zz0Z)=X3AJxBkrQA$~CR$B|}6;8^4xDjAz(*JBag5HHHYE0;|)b^%!$HhFEu+e}mOA zihP23=pYh9dEiczjL`7Thg47f zm&P=xON{+!@kCIBwa#ft}n8}6@A zng{s`h0!!kkya?p4OC5q(q;eyHZ-vKM^-2!gX-U}LK!VZD8={so3!{mi~2dA`uaHv zfZ0($=L_2V2xo{lnhfxhS|w-eG59`|3-#2>Wb#`TAES$k^m?+2PfsdVnGYtFAI}{Q zX!FM54f);AJzu^3E~T*d0o(7gW%ly@7hErSjTrYVccQ{Qxe}F6gQ$G;MdeB2F2$&e zm;x{Y0~X?eS3`KQ-ije2RI3T^**?Pc;slM_KRv-ym8h;bG(VwgyW|r5$7+44JYxatw@IHC&!00EB`3}6aiTcS43}AAFLk`%N>1WdV)HF|Yo&7EJsRRiPFPz{l@vnu}F>lsA*)Z6jK@ zs8;^^9ufG;(0iz~gPedN?-BWq!K+2zcV$w(z~lRcZ}rggCq}=G2!-;MA;7lR&7}N& z2qJe1;j2YgDK4NP32zkq@d^Huv*6Vtj9|8=B(VoP@IOb#-PU9IEzByvCh1zpn=eQY zLy-T)bc>tFcOIGSd@bPfM~W|rN8C)IO6C4Ulo#rU9+eB8j=i1Zh*t0J&V27;|Luwld+*liKm%7I{K z7}zM{7fm$>k?>2Y-!z2=&gI7eZmN=58~!!#s#MqNQ8v^jS`NpKQ}K&Qh4@WVjUZlT zs<9mxR`Ac!qpYBa`)r{E9}87I<2fO9xh^ zobgpzA=QFeih;jX1N|)+=ugfB{shVU+x)O9#Ej_gJ-)!-(kX-DIcMPbX23fUmG>Yj4=<`g*o;L?5Rz~M?u<_IDj%C76cLi%md3wSKZc$Ai& zNvRCDEa-VIrKQixVLEV9AeWv8$9(|gI(FOmH9GV(UQy;gL^;UEVvBnh4_jJ1yWn4! zRG=TPMH}q)0Adc5dn)=-?D0lRXV0B_oYpw<=pGGtZQMAbaa?2OL}S|-yU(i}Rska{$g}kV zE;aVxIJE^snb#ZYrf?HI%B${(FErK2Au4`4sXQ?_+?hBaLQ7`IXfNP^!yOYkA{@%D z>%gL%lmU+g8IRJ^Gbxn;mjyk~rL^=h`L)I(1wdxM4?sElpR7YqIlWbfic#?QAoptc8@BmA7;zg@*{pn_ZL1GPe50vG4$&o=E3-^fmfBk^r6ap3 zDN1Ha<6s{F7|cuz5FsUXJKBT8fr$emv`V`*Bepsgbp^cQV|ZN-J`>z zoEZTR`3X_SqnblG6Pc{4Bp#)uk4V+sRl&oWj}!ozLl3CqG+I&SK17-O2&N!Dnilsi z9v-qZcflXCsCPlXDyba(2EEeAY@;V0!zoD5KA(e#^}&0iJ#}Ch z1rrBGla2+WNont@E8ru4qQTP4q^_Qg@IZk3luFCp3QJO@Wi)qc04l8y4~);WwR;5D zJUWv(JgC>RtXKB)BLLS-5cjlRV~G2xYFcB-(LEa1B)gnb_UO%{Pi-t|0Kc~(WfvH_ zy+Tc*A8s7ibEg{2yqwTHAEfiung?~|%`gpaSjz1%ktW%t(&xHV`c#)npXpLLh|Sk+ z3|&O3bsZmhd-ek3xr@p(7nSEND$n{?%Jv>T7DYUzhew{|R$AZpy}A}MS>#i>++$Wo zCu*$|qTb`XKD484a+>#5-c40#mcI|ffDKIaBhuDQNnxDeCxLZjbC zghKhC0kB`&)u4^YG7>(JI9qW64M}*T;1TA!`fux=k`*v`Bjp|)(!F{t-_2F|zNBj* zKkKOK5oht$lE{0QF8}dW@HbE!$sgjbrW!%q-Bevfz~eX9fZxnIb`a|w^H*2%j%_;5 zGORH~$jDU^u@0aAL~9N|41B#~{^P4pROe6E^ zZcz*QT+=OXBLB^F@|(5pA3hIO8wnWV7fdx55yYxKX@MU+q6hxXhSfn_VyZ48Km~kW z#bAwC$2Q`ZOf?S?as^hqM+*um~^~eNys&R&mN7>8M84&QdQc~ zfS_C}PcqDSi* z^Uy)WX=UjBR$5o44P1Z9;JO3}SSekPB`Obeu>wG%yiECi;kApNR~Ut1L@1OOM!@b% zc8J6_ynz0j+5;Mr@J7L{%)0u&N&VA5D7sUASzQp9>9JU$kWWjx7V@8dl`f#jjbEda z3#iJwnl4|V@OiG{OHL8*RCu{NLA+m8)e1!m{NOeQ`11|EgZOh(jUjGTgYWccwT;IZ z;?s3R)lx<)@yPa^@Yuw#+K9NRmNHrgCPPGqTN%=tsZ``5iU^;|kk&5A5D~(ap`T0N z)&Om8ROTXXp(^>f>#D|#BO5bk@3`F*3)nYP2Us@E`CP=Os;VCYwonVMI^S1bD=mS; zi11rqK7^Bt%(gug5N;*H#rYa(qAXJm@j@MkY!LTDW^CrckI+u|aptZWE9nr|hzx&* z3}i`T+iZt&n~t4wk=gtKWqX%Je+&_h>q$_$+wDXX|G`plZ;tQF1Cu|gsjPa<9*qYr zH(f+huzs0>?V8z`0K`z<1{~y*VHaNu?rk1Y*DZ@f7ZGGDx$T;>cgz5G)sCcGb`wO3 zv;-TByw^zHD}T)5d`)c(^?bKN=Lbo$6US`H!Q>=$F|Dzn*`x6h3r-vHvvs>c{xAx1 zgFh%mxj9vRd@{L51bM^80=Z9^8D{2l+6@=Mf{)2LYC5%XMD}M;fsG$;gW0>au2M5( z8XhMTk@j}Bpmh<+8>Su;NEW^zhL`{q#c)&g3=_FxB7!`5eY1qII>_`#WM$BW!jFKS zT#n^oc&kT)zSRr-t*m5!s2RDzaz6(V2*JCmK?6?BD)RC=1sXh6Ecf#)aRiW{4h>+L zPpl!0?kqhPdm!XzC0z^oR?{tNA>U@Y#ZBbLu3}%5?}7074(%ryMZDQmBZwdt7wvA3 z)_RIBQvwl}m7$LkP7gH?9mL<8YAzyf3apMf#Y1qBUZ@zb7G8*TtVb|_V z!y2&#>lPdN7#L}c*$PW92KMNW@q^0eTgGc{&MSL!F7LG_qq$6dd{>X<^@7Gvj6fTa zQJ0gJ2J8k*O?+TpPE8v0}HNDIb-=(7dk-HcraaW7MiAwscQUud143=#2I8Lr-G8>jmi z);vVq6j<#Zt*etEV%=%}fHWWJFiu};SaT6^Q#c(qr#B}<#Jbb`vDD7m;bqowKFAA` z%E#wzdTK(CGa7sLmQP>4Iqj2Gzfq;1K3~2nw2AUeJ^8qFQeM@Yu|Rf3%bT41tQu{c zjO6>C(0)hHK1R0L1Sl3672e_htEQLHF<5I%dWw+df3w3Ua;*WP!se>y11~mp^czMdYg$e~x7WAC|`d{ zrPHItzV1_B2`C$QZj$+eDOp&{gdC!yAXw7fM=GdfoYqoat7H;VRkHU`X}y!U>YuOd zYJPfY#?<`CN3ZyKpY{<%(bD>WWvhe8kSoK0kaYLShtQq|*TpZea!vJEqVhn8D*z=3`Ms_+r>k$Mu)kc2l1K73nO|9-C!l%F?=i{}a* z$anNuY{ZbSOu82GzaE`7SjeZCZgCU&PSfQZEPVc4@g?(!OSPNaC?mdKRmD}j+oJ`3 z@IVdt^$n|oNUwNHlXq-K9rJ5N-f@_YGmXRu;vTA!XPtA98CJDbq4g=VT(&22eF*tp zWt#TDy<7ni>mBpY1nEdlv#*mJVanCLs|@4 z>Qt_bv~V3f2E;D_Ye9K)B?TivM+9w6$o;=GwqL6_316I2*wY(J>cf>BZltp0V_jM`KXTQ^&!yT&5JgMt3f0Q2Mr6d5VL(W_ z4}udDwbsDJtg)#pv(;<-nG?$u*)eMY`7=~~F+?@rfe@&2M21K5(Ojq&odaMv>Juw*~KB>=;)>g?7ahET%xjekft?6>7)26h3V)~u1l-Nd$e#O z&-%R!QF#Z!#}dG&m}Q?a=O)=LASTd}Z%(?bxj{7)&#QjU6Re-}fuNlJo<5dnknyq3 zVFl=e3Mh*+BG}U!6NlP#rR2p9F_ntg`9KAi`4{N~O8w+-R(!wk3QNzI*%TZ`giLw) zrja~M9Bm$!q|S(}C*ie!PqoKW$jloBuYax42r+`0;2=&)(i;W-Sz+F%%gF}valL#u zVRP#pd#GwFjW23?f7BMEE+Xqx@ToYxPS#$sCdkbgt<>>A#P9VPdJXt2Zbo*Kg)fMACT0cm$9kCWFF$_W_+8|V-4MHW_AXK6aLM2)ss&kZH zjnh9oeQ+XP^1UyEXcJ|r4jCM+)Uk_L8=n~dV`F}~#vE?4a3lUR(uC87jcMPza$1>* zEP(ZMzI5y7d;!gBSN?`^pq>DCtYcweYq~0l@{Xc)+?>2UTGgO`G@*ONsA%Lrpb>- zRDLj`VkF%1#Ul|zKMYa%G5kR(K|+e=HIo#uo%6Kn{oqHW>*svD>*qY(`nf^8sf&No z5?SXQ`#7yxHn-9Z2HBKeYgSUY`-|;H*Q9u!=G;jko}VrpU)KFirKNSD-79twYa1Zx z?klV6?g>^}Uon-|*9tUuQ@T@_t3-fj*?%FVkbW_xAn54LLnOZlfPYghIL7 z2kh;ZhhaoEgyCJmsfr6|NWvQhyK?*|XTdjoVgxh6K}`LE9}o6Mfqzm&0ZT&VdO*Bu zg(BLZBt#pOglK&xU+5}VCW?0=D(_*j+U*iClxGO)76^Ml)3W#!UWQDGxIl$2!*mb z0GnlxgohD%(iv9KhKdVlNWvQhSzK5DJ7^UjYqMnRMx{i}1s}iG>L?Ka2>4GKGNsGL-}(Aq!J|fZ_rg zlJG`Bs_~zk1q%j7FcTca)Gt^tyiwrae;gCk2fK21zj1;&3sTiir`m+2O@kQbOvesE0XpPDXz6$Wn8)kaDdaW_>J zAAxjxv<^vzi1?`tX-yWlazRaJdyF^u5F@nPluDI3Eu;_apyg)J$W(inv$WMmy6kl!#~ z!@eF4RLs8__LzyM(ORmXjKT-}^!gisYjS z1Ce5>@j><35R2hcJi)TJK!<&i4ga9L*FipLC#f}IkgsZF>?t7!`+?P-2O)%?5??N9ZadlsI1`FBycf_H#ErcFr@v7NTJ~ywPNUZ_yD$Okxi<0}9eXuXpyxi{??P zwsZh_QNKOSZ>gGe(1yW)A2EXk+{?)0ioRhwd{2qc)1IX1@BsC5J{{gROoum`3~+@; z;wO46E*{9&C0z^oxTWdhfxOgo@+O|jmzyrXc;NGP#g~f*;v(%PC4e}ts_L3R>-=Ph zh|Bomfzw}_(+=Vi!|_NV&ISI51~Ag*8^rWO9R zbS&CR)9L{vdUnn;z!sumI=sij!;EG{0% zS0-Hx`5Es?7Z2ni(=Bcy@ATee=Ldn$t+k(AJP>y<)d=DeO^k72}m$NZ1G@-d7?V;HqDEHY}Nh_EiGjrM5$S29Gb zQyI-_|2E}LBBML|zp4!!eoK#H zbU=^BcWlrd#F~c#A`b^-fxrU@GRZtMQF&fp$VMa&>3zTO699UC)yNMcLZSS40kExX z0uLjmhy_phzofW;h9taE@G-!;`uD3$nARa3)GR#~t10rclCFh(qv;m4kXM;*aTEDF z?;E_D;X5Ahw@PiL2a`+DL*BksiL;wr;P5__%30@B02L2-k zKZ00?ZyWrxG&-`xBQl_Pq05~Px_3T zMT=ixMdh)A1#6-5fke41_RYaD-9Xb2@^EHs+P7vX!jdh2N3{yCV*JS%0FU**#=5O_H2lM zG}Q>=|EQ{3i)eK;8nS315|ql2R_B9Nhzdg$C-hhu(pr9^86w`Ts>+bo{mBsV!9GJ; ze@TXj5A_++B3!{H`|&#ZKUrYL2*K$Vf-wf0fU;$;qW}vHXg=ams+uZ)h_X!Oo08ca z7dBb4$8{J4Dpap;RJlk{=6UeVr9sLi}_F}VL*g!tkbQ2TEr@Hf&yluxm2 z5A`0`OD?(c$MwErrS%@^d#Pf`BI`Q_SKUuIkL9(^_X{t0^gP@AwGp9EUQGde*p{F+ zB5Oo=)jdmb0S!rbqu}rB*VX^i)&F5OzWJ|H&%umsG6cKTfLaRXp5cFyE)o z14UmJ>urKZ->}|AS(keS8nt3%D6FUg1#ebVQE{E&nz3e83^sJ9HfCqr6>k#^gpwWs^M({7;;5nO>N|{@iqa>N0d#1 z$z$Vf0+_F7FnMgeO#lN63UF%USy{rpO#t(IWs_j?^7A$U%mzAF6HFdrZxg`mn!)5D z_BH`bH-pJT>}>)V7PHz)kZ%#!qQTubnF&4TBR0*c(UgA-7^NvUBX z!JGA>0l~xex2p->Du)>`0|K`JGfZx+2aiVTmj#bgJXw(7<(Fe`6j0=e1vml4XXrf( zCK9|mUOXUp*v{5IgSIn64l`f|1a1Rnm^@d}%4tg@^~-|yZnZyIkK+A&-5GPQ8W4J~ z>m?6R@VEFZxjRguM9SVV@Ix?xnV}03iOtR3nJLQ&sU9 zPq#;FU&WU^A-+jfl_9OSBtyiv_8HQGaj;V6ggX%awGp0+2*rX&#|S6*?C&Ir?Mxf# zBKgS%TE8(5^AHKVEV*JxEBRfvbRzJZ&9PBM{;qi#0b^#0+MX&B=32z}?+c_)^O(ZE zO^^E0AYhPW0JV5;% z0V6u~bDrJnlsqY@+df)8z#&lKE3V$CPQ;V`pd&360X6{*CK0_(?#~y^GgNKm0OWKn zGA$pP8>*UepuK6o`Rcfrna36E!*YOsEmiC7r{&-QBzktvGr$(2VLH6gWPs=9=>VGn z1?iyI*ZR{z^WS_rfZV)4zBIRV>7WgR0dE|`f}oa>#}$3UboibUp_wn&ba;UJIiC)1 z8>Yh>O$NwNSghsIEg~!RWa~DAW)+d{`4uW#%738gs(Fy#2cgB}mT$U#c)W*)Jv3#N zmevbZD?5Bds8oiYO{Mi=h0wK1Os?_x1y)oZOH>|cC*=c)a?9=eh5K-N&ax4;5us3S z@&S8CvP0ye9o`H)UF`u4NqD2+qu6!z&-I0!PVgDQQl-`( zwEmn75g()6DnnW@4pvMEpKt6sh~G8UJVYo~yFgkqjK@4gJXVH-qJ$@@AH*xn>0CtI z6j<#ZtqaZRTtwnh8PbAE@S5zG)!Aj{bPV`glFGCHrJnku9{J5P+7GL~@3+`cK1OM8 zmVRb!iQL5$zr@C=r>F@(*H-@48b+MlRgL<7kZo*v6aBt=euK)-#&QZ30fDz4pQlz0m|!) z#Ltt#ME%UZJXKjU$ih(Eze=An%YX@s0E-a{&>bYUs-TT*dyI zxt)gy=2Hs~+imo~?hnkmZ&vHvbE<#fY}MTJfmu5|u>0&CdK*clCPf@L^ihK({Yqs8xiqq|wpZDi*TT;4>9m;RKZU8D)` z>x%N2?4%R}%9Ep$D5)oft;z^xTx4i3%5Y^cC<#^nU|2&q5|>9Kqd(Tz5>ELXn%Et$ zOhx6%2cK3SuGW|a`$6KKOtSCu^Ct2P_x6rHFlP81q5R)g9-X3Uq;w>rD7Uq6%kPG9 z66KD1a+Ah_o#cT9r%@A#jf&qKMvaAHx#z;yBzwJPtjJlVmKBR+qj_;OuD ze1~?I{VgJ1nhp83-Wkm~Gka+8)od)gpgMyF@4+@1=Pxto9YjdT#RUO#c;IDT3& zK5JNW5CIr!9JO@HjH6DNGGpfK9TzsXI_hK6dazNnW^Xln=5E_>d(=IR8Aq)uHF7?G zH_Q{B-Z)BrTVa90M1tau;%s)atEwa+Ozb*DtfOUCWY! zqxH+A$O)Wq44f^Ul8r~44GnTOG{{-L6^8Dur&P4dm{27rX|a_tx#QHzVpA>LFi;-O zM(-hQ^d8nu5Dtz5poe+`poe+`pz|Os(VX=K!S@cw>w9i2f95)V+I0QRI1jP0{LXed z%fL8#tm%#M|4-ig2VPdq`~RnzX*wnBh@0v%Dm7f(DYv zqy1dZ_4>75>$TQid!O?@BSq$I)GRt&SL+DgqSx{aA$JM6XUV@p3Hej)ysLCB+bsX9 zyP>zn-O#s2rXg={bjrb{HVipcYpV=OIwdX%3i3YMSq3GY^6z0*-Ox}?n!pfCUWVhj8>GoO9Dj~bSvmluqRo9VzEn|;69 zn7LI^W);b;id$~Dg?k@%%fcys?9SwUS%>#$9n>t>AwJW6+xeW;AL4UXe~8b#F0t@m zdLN&BhP-Bd3-XTR8`FpN2yvNS^~N-BRa-u6g}g;O%ME;Gxx?4p&{H&G*A2a^b`O|_ zyld16xqqW`1h0_fsc5adPC{zLgeUx;njn?$rjZjJ;B|C`AQ<$4(3HBiW4)8H(b45NS9n*{twd8PG~I< zIzQXH4_8ZzEPq{K!}z(G-jc~g;Dv(MnkT58*O>nWz~p~Peiy*>o01-IwNmoWSfA3T zfwAC|GW?-GMgE2syvodHTRv)URgq}RpQS6}V0%86ADUBqXyOX+GmYyN;1T2G<2Cmm z_MfCO@@x$}!l)78T%$&T7_VPLJL|37d>8Xg#r&6-a>Y)h*vW40C_dIgoeO-1QDZm~ zM&Nyws$-;e|0D=Ja6pjO(Mb^aiUC1dA5Mb6j|>RX+K>c+*AEEN`gsxr{$W6n7Be4g zZA|=PoA@s9zN^XA7;ueFaha=bpVnt=;>Um&G_v3A(_$9n6b&S_+M+K@N_=k(MZTW0 zX=$I<$yS;3fz*F3NQ(-UuNQ1w+NVYM@0CwID6h6TCHikIop2a!1zZUmEi{+GiLn%D>+FBpYIp6tMh+0+NdVf3C#$>wJD( zulg;1nj4h1zuBN>FV;C!d7AH2n!nkg{oz4zzv8GWR($=@;G656;IX>kDw1V%MU&j; z{95usdaWcc*9PmUB7dN9aI2_D8Z0wDgZzeWCsax$OoOsP_+h#SvK?2#G}w(1UZTPu z&}${kPW-thIV@AGAvst-bD=(Du#%|zW*-ZHrQPiFK0d6IerNiijwp=qk21W_L_uG# zK~H*P!nkY&1VJGP1*9hG-GL1MW9(II*HoE=4W!`euxW7uD2J>?M$y%Rv^W8XAduUC zEl7(KfCvJ){nvuDs5=q#<;KkYd~ge*`5V6lF>;psoPKhY)j4g;# ztCl(86Hi6{pWl~AA48R;`l9FSzQl-GOU*u3RAbLFJ@zcN+NK`0PhBZyC*Jn7u z<7wI+Qy-^M?)=SIIDB#sZ}$1yb+gYeBcCV9w?CZ=<+CD`PlixF2SWLw3*|>Flpm;2 zetbgtVF~3&bCB+N%({q7Fq&iD!dr^@{^3Iug8_1bXOcx~`$of~f+%uIV*-WRRo}94 zI~2+f@NgaAadsmaAx>^6ayZ+h_Y?|MC_?8*EEJH@)MvffdZy$MDuO`juoh&7(wIgV z6AwS4>j!Y827a_&^&m&{`AXZPDx>?94oT%{UZpgTsV|9GP6}lDaQ@Q;I zJ)h9Zf=}rkf2Q<9lB3VUm+0BekF43}2iWYRXsD28AH$+3nti@Bnti@Tnti@lo}tx1 zwKrw|ua3#b9X>OAq2|DSlK$WpyX^K~xLWUY`2?oEd;(KnK7pw(pTN|&t=Q!4tq(~k zABj*t0HM5Jp}f1h>Qm#R^(rq!doR`)t^$si2yR1m>v?9IRiX7(n-z@Q?7`sH1 zDF=IRDmd$(t3y;}ot}=feAR$y|eT;o9$pN{Ug?}h{j>=;+48jWqXKnl^ zXTez?AtDnyz@!(P^}SHwpDCgw%b#TTB~o&}LZY8;_qOCO&%7z2yrtmp(=fyWu2&N+ z*6?3tIs4MZHTl?)6BHXpa0)uwEy;RhJ|*$)vB2pLU%7rzXkL)kqjwoBzEd)PQkq^b zta~)iGJhQ)AykVBV^2zp4@eHf#kWlDVl)iG3kAiG|Ku!Kd_ZOyK0DPx+~=nv@sGiZ^f{_XpQVcQdE#*I zGgS%uY4%ad(Qm~o^&IbmZT9(?n|(g?W*;M9Qk#7~;AWqX`y`!2YOg8#j~utpTX-J# zLe0VXM67a&kagVeZn~=TRV2AuBSE;Lcw2yz>6L1~E6x>P*SE zY|dR~bMafXB`2O0%lfqbU>>?aoYsOqLpAGHh<7b#9I}mBp}ei&B=iG~hajr+hSv)Z zA!z>0M$`ckLUqEy*uSNd5RltzcoMo^?P4?x!V3i_5&S1-!AS@qA`?5nq!*loyinku zH}br14&Hzk`qGw{w{rYlyVSoqtw>)7`#4Qmz+NxdU(uRtFN;TWt?bjOL!GZ`LcCr$ zOK3jH{B?kYP?Z42cGs82l1(7*kHb=VwA#gJ7=#xJrfNt1FIE4)&}+HX@+kqI2bCOe z`|%TP$=;Ss`;|+*v5NH8D$*B-Hz(ELjS1yV1vQf!8o|&uzjTtD&)%V5gUDCQyS$UcUGDEeXkE>>V3UPuB*+so#u(5u@4XCO~uNM|7n%7$R9Uvi8s{mtv zN*gPX0t;8mSJf^?!yvp+uv+k+oCO;zLPREZfJradSiMl-pR!|x1x4$hT7u(-{~A%a z%^sz9dcIdHdpM9U)lT#kTfQ&CEn3w1ng}SZ3S!NLmCf3R2As;!m>p3<2IrWkPxbx$JhhY z+5nRAaBZwpyBH0F@Ipat;y*bH)&@dECU$^HFIXF1DDeL@eVxFEF6Etumn=&(Cnd)x zwJg)le)n%wGpc2-V`i*zsu*0jZ&I z5v^3a7!8B)LO~JZKRF8)5kf>Jc7RDQSVUeZ@c$Qm7t1+Ec18Jn312O~rh?nh3_Z`@ z-~QxiybV4eaRvB0Z?C_^QT_`i;7!Jjx52NwILZ02@c9foOOFDtQB$%YfZtWBUJ$hY zS?!A;@F7aog0!BO1c8eN1Zj;YLEx(g1ZgoeaqUO8T1WIo%gDif@Yif;V+`WA4KeV& z-@&(J<^cCKY7F>|i%9RmeefpbWR~yo&boW1Ugdj>z^;y|{9QkW&d8#FM|z5enrqbtp)x3dB3u^ z;bC`6<*2t6?0~=0Brx)7pYeL(=7Z)RER7u?AyhjX#+F#wc7P-{+yS?$U5ti7c%fhi z+EM>+*Qve2isz(_JN0S(L|M5-e^LXbyo0-Tt~HWtWs4N8tJRl&enImZrR_UWn7mp8 zLSCC+(JSAHqD|aGJ{}W?Xlx! z!&mxVsOiiH_RTD?^d-%0$p%%jr|z=LYy%$ovo7X+-o<7+@*steO4M9kT5OrYhQF8E zJW#JX*)$JU+G=TcwO;5|XtRe6nLnZ!m_J;h8}1BVQ!;ezYjmo- zfo7kd4lf%{hZma2;8S!%|E!(TM*c^Wv$q|PvXj8mRQedbYQAW`Kxx~(@1myeu2+?( zc`v2ey=fD{km>NTSDE+GhtuITB|{5etJC2PH2eH?JW~fs_L{QWV~6}O;BZ>KP}7+Y zY?%v8mK5<|CRk-?ojo|MG|%|v>#D)&p!pR) z9SreXgVRCtdu}>t6Ty(_APUyTz;vJ+u4=C-8G6+@ZaOf~?DN@UT*!vg;e{qL*y`6W zd)Dbya?fGlM|u+zicOdo7DDlwoR0;B0`e9#{t3(L;6rHk`AC|51Vrwe zecnGlNKsfsUT7kN2j)eDZBqGHE+Rb68Z083kM%`FIM)tV1+1FAk$@_OMXO=!N+!k-Hy zgz94~j2&)ghR;Pv(zp|!yvp+@UQLQKRF9N@JEQq#11g&1t0i(p}_xVbQ}*^ zW1m?3T1%hTma^}htT+2rdKKzWO&AAbq5Pa*rM5TfRkr||KTz6kQ#jr_xWmxA)$K5} ziF3#f<40I+Cb&YkBK;^U(htg;ll6GYn{?CgR-1j^c(c#vvf1bTf6+}?Q}%D+-}?yf zd|s#-q#w|4+<@Y88>aP#!P=s^la{m9))`v4XX{mqh2|TT=4}IQ3Vuj!`Pe64MqX1g z^rmyQjDk|JKA#81MWEqyc%h~X%dne2aDYVmw@u(oJ^($yAi3Vuj!`Pe64 zMqX1gH1&Kfqo7o*&*y=05okCaUa0BJ8{9`T*Vqt<2QxB5!?Yft+L|w#5AoB1$x8;O zgXRa^bkHV(A=BYwAD9kw!&U7yB}03^)lCNmnteVGj0@RtI=s+C29MIr@jXt-J+It& zh!l#a8!QV&LGY$tD7I>jd_wv7=cv2+gY!u9WquxU{FcFar1^F?kF<$%$UOQ%S5xMP zU6J_5U`6_&hcoVd$Rxby0-bU1s@dl~Hv7EeW}i=fv(L{$*G+m;_U|2=AAeZkUZ^<$ zKiH*iuu_$NjBz;+Gj!Hq?b3XcuU%&A>cQHj`4v~Yv{_I?YS#~EcYf@9{!$9kUgY!r8qkjIVlAjE|4yAdMdmT!fZF9){ z5d|CW@cA1SKbn%EZ(lfks;tl3VO#_nPKOt2I`anohlast9Pia{z+RJV z+$}z+(jU{Se&>khCzZCZG-2{uo8js!O*DU?GzWazL@?wlO+NN&#&CshxVXHgByssW zbjG}aW}i`h$F0ze|F^yQ<4tkk*mPN^t_u84#p(X%Yl} zeL#@b_md!y(Z*jkAjg;3c)P&cjT!?IPid>$r}ZIoItFYy&HrV-`)Gn@TB5o@aww~u zEbVFL=lR*XLPKOeB#}T2{okFMPw3z_=vB9Tn%`2|9uk?3)tWDrr+I`%1&gW|(d z%$!wQ5wk_IE0PA8=i42$Z`Rqagqd9Gz9MNb5-iZBx+>w%Y21`P!W)&R{wrY`)Fr}x zw0I&Z;oZv%$sV@pBHehs!Oefa3S|srO%{jGS-m)X#zfHPE8aX9+}6PgrTIr+p+xkq z!IGo-UZtr}+6-XGnTII;o)yZ-2=&gZP)17;O7ZRdE-gMEMYGROeY1}OV0AS6d_j93 z;R^9W6B&GrZVN}+%^>^7d**7_DM{qD3O|&nPb>UNqS$2~sFfA`OFXZ4hW2co*lN!> zVD>W)cxVNl_N)UQx_9;s@57yz{H-|d+3tkGJ#!_Lp9Z0P_J#6E$6d{pgb3J( zhu#f|>qtw>kn@L+_73hB{2y}IMje6-Sb%O&}j4a(EJQfW3c+Dz1t4b7*i z+Dw>K%8NUgpUX;^iKXxm_VWo(39{{P*FBSPiA)yz^%v`oM05nw?DN4i`v|D9BbiOV zI3BE7{(JeS2$Wh_LFZ{M8nkQKJ9Uvi8U**Ku)kzM> zlS25F&zGt^M#CVyQ1A;U_)pG)uY4jzWMT)H^n$N^dZEDo79GdUdM#g?fPa^`0{npY zrk5t*S;mdG!S8xslJm8I&sV;OHzcFL1Ju+`tpz~5v|GK6%ci$C?%RhsP=(vAmFw#s z7`%&_Va~heybHXCIiC;2V7V~6eOeomAn+STEd)MRQ&8*DI!;;n!9(C#1A??xCqW>? zsx1y1*`sV^9UvK#AA4TEj0V=^H`&%L8)objGd359z8JeTGPZfBu}7G(V}MUFY7UTE zkaf3tCmJ}P+FHK3u9`-~A75KjpVq6K+krD|UgjOH@ED^;fR`9G4|s)9BR~=s?4hsL zVSGWa(^|_nw)(Vov$#fqRCg^%i_~hZuNYeE(nB#4Rc)z}l?wh;1H!LtvOt{P*&+Pu zA18!A+4Ph@^+k(>NZA0H2&wT6QH@`j)%dO1D7zTDua(jm5c_holwUQY#gxhq?a42l z(qe*x2R&xDF_kNJ>eIrkR@0oJ)g(RMnG}Us^3`;2Eo400*`-x@FV%Z`*8;_gz{mH&h+oDACPKMu87eYHDlgDSaAjQ?h^L zqsU%X6CWn0w3fEO4>ph4uau*9h>A>UJvN(0cB{rTZfXrHn?*y*MtT?rxsrkqOFmJH zb#1VT%R&Q^eOYK5qlLCUTWGJ)ft_wSSU?o1CbHZ9`6|rKu>N6IXyA_LEw^{Ky}CsBz^a=mG0A-%bmo3vXGo4x&$8Thw6h{ z*Xm18idQGD0N-R>uK@qTxbZf4){SYW1V7Ta@izEa4;$s*_S|xc3tq7~Zx>HZfS4U{J)+7*syv*~=od8jC5{%9hEqwUnNx*Inex zEK6F`_v=HjqNhv8($;?2>5u+}YM{LPfM1@t0(|68(_IDpG~>qG;Aa_^-&OGW616XD z8+bQW+o|4Quw`)U*-|EwbN&a1zyPb(>QfXq@YNGnCZ@=eRKs=&$q>SXuUqVhXZ?HLE2 zBsBz!2T8DBNf_9%;U8wh9|Jzqs5wA}5Il6uRB1-LJ!41r3CSanV5Z0#0~5^@Ns<2# zQ^-oBK-A%d9B))Sq5JE zfm%%}7>LDsmD0LQeTpFP&`WFGT9DRblodhX8wLbvy(tL-KQJIj>%&P9_}KwLT301O z;EOJ6#z^a>%1Vqt@)z$-Wbn(D!4B{|%itK0RFt+leOf=T=*ECer}-v^)1O&coZJFa z3bGuoJ8e3xWN+n$)290}__^9)qNlY^TC-E178AWo`RV%p(gDGA*W$Dom5D9sg5 zCf&p#nEG0r7E^EH5EMWyPKyFCaR|zw7Na(dt0q1yvHxysWIm9Yk$Kv* zq)&^~%3IKlODxg&37#yOIt+-p^-IkhieheE{%?Xk_Wkt|AS5vlY?!+v(fvj}{Px4O zrzx#R_Wx;JjbEWvUvkVjlUZ`i6k{kkpI_`#s`d2HBAGTl5R_^yPKzK-oJc8P>wut! zYdf?Un29qwYPc4s#h6W;fm4*VI4vsD#33lkTAUWyGx1?5Y|QwURFC9D3P|dJgfPOI zWq1svW*G$m)U5ZupYD-NSsgqr=F5VIV9IK7S_Et2#LIkH2Lw}A+o8qqOq>xiWwkgh z#%-#V~r6N2BY zWyOWP@*zKuc~-Uu_-Tj>jqLwGGa^!J^Boc2R6wxd(nU>(p}#salZM*K{`(K_HV~3;MbjLB{<{J8LWezS2%YWi+%X6Vde* zx7ID%^4|(%W&XFFKo9PN8I2sO@*#}m!H(p?j<84wuk`t94SY#Dw4JZ;ZHfAb!jC0t zqrz_`>Q@R|dRmrP@1ZbdB70N7sF}jQ?}Yjs)zOf#G>mLQ83t7(WuMQ={CrmC<1yLJ zKKFRL76ip`x7Nzmvext?_MN`pZtHg1xBql4af-zEpX_=l0;piOO*8~Z@4hdK!l>`erI(!kD~i0tHbOq5}71pWt4th zm7Jf#l8Z)7KogA`pN&!Da^g|%*buQz8f7*5(Fo-SBh+7WOJG(STLQB}s>GwOk56k6 z5c+PdsrUKb)JiIwk!GJCOtX(&jbt|ah?2r-_W5v|ecOs#KFMEqnooK~`baC%hggw5 zw%VrKRx8p+^Cg!>5n3BXv-Y$gnzg5~=aaBXJ%~nZ=FzM@%}29YquIl5yxA)|0!Fm* zNMoz&%Z9veNuO4-HVV9lI;aI{QA%QSeUyatQ4-c$61eeIA^BTh?I}o&c*;|=K1FqJ+z8;>cdHP z<3Gz)y7;^@T8&pmtMSUyxHBT$MeSz>@QEygi@IzvJzWXt;|=9jrTz2CGuY zwWraT^!~z4q+U(5*mcC__S{mq%ky|u#mP>7r`~7Ux|j)EYV5;57+&wz=j*7c$A-g_ zZ1(xOYW4;7ZvK3o5qH{z>}JnUbcfd0qCBJ2tPj6tec(0gLsq+PG1RON^A6U9cU_m2 z^IVbM@gZ(rx3eJss*X2A+xdoQJKu0x;8@i25pT$L?nm6Q5eGi8k}F3sTwP z;oq$cMjxSZKGkMCE4vq}^c(bAO|I7qXB^Fw%wGpc2vs>@?9moP2S{9D*}YutVl)iG z3kB1T|KuzvJA{Z#>;RKqPYkQ+D8Z{b_;Ye3QoUNvSxm*2(;x70akM73_)Es`Q`qT9ts;3+n>SpP0W6 zkPxb(!`RbOaRO6rgL(hH+Qn!Xgck~mV@Lgy+D1{Wv!Wu|QWfh?BX^BTTNmB=*F}}K zF1yJuo2aN7j@L(yx2Mv4HRJfKR8-XRXKa#34|1y|D5?upIt45Hf!7P?6V3OVzYdTP zs-nW!gHlle(<%;%>YZvAqhSzUC@3oYCuhNqhY*p89bnQ6g7iXxf2OEWoL5HWFyw`T zpZW8mk_*auNOcV}_qJ3>7<;IFhB)f?;-HXrSLw8}B+XtgoI^DCF@GH(AykEgu^%Qm zAfIuDx6XU0JVwJHyihQa_)pG)LPChh#11g&1%>2=0{?ve$Aieea_m)*Wsi+KnEgkkEovaFB{TU9VNGdA+az(LBWbb%2CW zRX4_-m*jxN6|RB@sys%+AiPjeh4@d-f>nSJk%=8((hF9B7Yh6{MSO*AJHO3FIqYNU zo6lSkbntDEn_Ric*Y6tNo}%8QROQ=K-b2lLCpGKK`nKH9mFa7K4L|awmcWm&fuG)cu%>>`{;gV7<$AraoY9!WFMr{ zyMyb|n_K8AbMT9asNf4^*oDzB(=J2YZ+|Kc#hY3;PFH zsLNYmOqPEQ0ml54)^Z=hlIxI;jd*v67R<-3<^j5WDpP%I`q*2y5b(^`w=*VkxKzSCOEgr&te%ipx^?mwqb z8>hAOBs|IQ9R;3*jXfP3c?y0r>A;WF1u{)@)clx;SYL8wEz|5LLCGe!d6|!HSxvcRb4_MZW3g-3o=%@91!a^45hK zX8TNCcp?IPzf#pWX)rM&M+{F+4uMZqY9Jfi7ub>8HR!8S43iji$Jv$dN^aSL^s*56fn4Nhgps`S}O|66n;rM9IUHb>=f zot48~HB&P4*G1)UUH1EJ-iK^7kK_9#ETqQ9W__$`JT~?2rBQ6vYqQUnqxWBahr|0V zIq$FJyr1a%AG_sC>Tk0-;+Rdc+O24?mHlmYwMp&p!5;i%m%GN^N=XRC%xvE_n%iFB zr(KSLx$Omh(u2byTU%q@q&a7^t8M}8T@0rpaoX5hH``)jxmS`ba0&El#fBEVG$gcw)_h;3i z7R|SrzYdTPs;wMjFR~yyK;jCw{PWZ;RKqu;qK9z&}&e zDBZN>Q!Y|w*Da%9n8}J{VjA_FZVuE@B}pYQmWm|$%QX8Hd6hP{Hc4M%Cv8`e6SLH+ zk60+b{)F<;3gu%J%10{HusD~brLeD-&Qq*3M^D$Go~PGfDa=&qqx4!8oYxDh5Y0!J zzYdTPsuIW8nHEF`NL=Akc&OUNXc&YS3Q7_G$yu-z5F#?M15A3sQt(27|8reQH6MYv zRj?wOeJl*-wb{pPQGm@pUy02=Uy{u}Uz^Ro6Ls!LQ?rl!T&6P3zN?hm8ua;+_IZ+n z#uhszk|0^hn{3M4#mBe!Law2U?MSglk<^xxaCCKK1|l^ydS#vv8W$1^Kit$m@GSUf*_zPBUnS=v3be^7>wo*Y|?Fz8B>6 zo&D*~=lH`q`>TzaKHeZ|X?p{6o~I+NovqotntYETP%gDUVTU?zh!h#Os9z6f|FA z{yIQHs7^l^d$$GA0TNeuN}8{BF&YNpg@RKG{*$xdl!OqGi5+0l3rGi^D zMe|$cuLC56YAIms3l>BNNL=BP`HI@bXc&YS3Q89L$yu;u5F#?M15A3slJP=;|Jz)Z zH4omt+?svdfSK23AG5{Ly4mN8v)SjXwAts&wb^%~&fV#HZT6j~+&hClagP(}Kks3QGdRFQtRD$?&qjPP+fQaS$+ z^}X$&KkDrVr=(l-EW-V^I*WL{@PLBmRP)yX5<+$Q!PuMiPALZoAT=7ElK#lKP3?z4 zc%k5wg8$?!I3*!OWRndNd5j1CnIi6u+j;j7>TdJ0pzbzD4;GuF2aC+`_&-jkh%WWYQOUZQ<1)8D)O6}%dL8?NWWcr$8ySl5?{{n{+oS1jAoyY zrrGC%YW8g_w(`ptKBkiMv6P&Tq2#>plJh<}#x^G6)@3+7y7|`nGI!3F^bXl+yx&T4 zm}9%)sT79W~O`M@r6r71IZgs%`1)9mvBH2eJQH2Zu= z&Ax5LRwa!L5mc3KAI%+{t;tP{ce=xK@L4wpVu(>P`9j@^?(A%y+%3r6MF(*|oxzuB zuHMnn<+iix{hG5a6|%+FGlP+0*tE+@$ysopMTp46 z4lwBj_gOC#_-BgPP^%4tbT`Ujb5stSm*IYEx~1mF!|Pqi$;$K|;>GH%iqI&}FtBLY@;q0M#d)lplgiw_R#(tW1D_~lI!R-7_?P4?x!V3jc zxTF3#hz*=T{8Fa#C7SfA6ui)x+IgPMOtvM^b#bzj?@3?Q&c-)ry(_x-I}(W}w?il2 z_Z6Z13*UR`bfu5}v!LlZEN!HlvXVbiJD+dUpV?t?@d{zL*48tx*|i>;eYs~;=;}kMBq#sZ%$aW9+z02O)+g$3&hDhw@(%;S(-K#J_cpFqfcG(O zyzK{z{X%8rj{t$F#s5Oh3{|*)!#MbW#1-I2f4Uw>`LFMSXB#)(2JiLRBv>$;{Wjr)D3c2!%YwV$$;RT_s3 zh|)TxDN5ta0a02XXo}MK{(va0TbrUZ+M3NeR$6-~Tg6I)#Mh$3QvWh%dk6rTI915r9nDt zQCeiQ5~V>xYf)O{v=XI3N^4PCWVI5dK~if`T9j}lN`t)DqT5dW+#vO9!_?1>Qh$D! z`ngf+&tDRyer}Zd^Or=apW6>ofBupv^>h0{>d#*irG9QdNd5UsqSVjr2dO`QNtF8h z-#2`M?iY`;RldM)2XZ6y3tuQdKB4?Lg!1tU{oTOzRosnaYln_s73vFYSs^l+w3EBf3AO0f!4v6>JcFK z;98JY8fW>_BD7da!M{s@Ukr%34NLp9P?TRrklz*YF<+*!5|Wq)V&D!&H~W+It$I|` zJf$_e?&e4A2Ejb@8wi=<`y2M6`2N~(+C7F+!^)n-ISG=2tWd>1!=ud3r+%Bzobv=I4i?Z z;A;m2X`Ph>f!vpBi?rAs>w&W?ZZk;|Q;;NK{bW2|3j>S63ZRR*kWhkJC$ALv4%Ry3 z7IplwzYFEZ6huoLOq5Jpqlz&vW4MD=j2|lJAGD5q66@;nd8}Dq8|;qHv|{Z5Pe@h$ z*(LqoX%XG3S1~8-w#{Y#u7LL_=bf{c4zu&@6oaf_T0|!Qo~#cm_{VUcr8dy2Bln8& zc+h2~2mek2A_OOfb~x0Z={9z=UgZ@I@a}0Z`$nGkTrvA6iM@y%%Foa8j?f>{ek!+6 zTEq|}d8;ZQB1sQ-ED z{{+2C0r<@)s0p+!qX^U~rzQ=2Cwio0fS)-*Pb3=(jBKPBAsU{g*A zw?m2}9?Xk$ffJLwxqZX0^sTOstl8(|Yxemln|(g2W}mMCVtbgC)R+%Ra_=J%$_F5n z_Zv*w@tO*zsoq*?k)XfUr1^m2={YrzX;WB8QeNcdqna+UC@igyTN1m#M#YIBdAwIT zMhQ#nKFZ3b4s4XB2>P7Y-h)w!te#8iGz`KE1zSD-le6HXR)mO5>;RKq@L`@83j8xg2U|I9 z*GmOzl+u$&s9QCY>{G#0)%){R(0Hn9tW0^T@*boPh4oHq*4N>ub3cuD0}VfND+>Gw z8~6!sTN`pech;&70tyx&0ew3yK*q;rA*;>X3Krm7wJez5s?5D!So>&RVujTK5<<1G zFm_v7fIuoJT!4MGi_tI$FBB{Q{3mC@0z`< g&1q;v%1^$^L?n`o)8oCyIeQ(j} z-ND7{&D~v7+6blba$Uu} z7kohC3h)<=>lNTH88_Yr&s;yjhpH<7c)iM^0e;q~F(4M@@e{Z;Ndfm!f8}Q{qkURL zF~Pu}Vz#=#FBr7|i09ILw@)jXU*Msa4Ute zVtEim_G#a7YI(I@<;$#J;>)u>U;;f$Wy>GM1;5@R%)W+$X(E@;9D#&AnL+&0Jj~DM zE*sZ{D&6q#rj(`|wO7(~`?5Z*&E}yC#Az+){no5c6Rs~ZbE8ZPW~H3Ht>CusEj2(8 z)#mHp& zCQUdKATuVb#m|`EA%aiEZ&y!59Gti2{IuTBI(jYlN$@d=E5Oe&u2+DcYh3=Vm}B)7 z;6lAtKgX^3C5bD*BS}s!X zwTUahzc8*>fPZ6LzDTjZNo6F(z?+O30sh*kQ6R?Sr9AuTQ>v*yOs{45;HM|903T&s zuK;(A%frY1h{{O#K-A*Ej#Y()4ddYB5?6rFFs@gCUuRq%81_$983_#dTBAmQXB#yN z#CRP3xvH>IuVr4rZ%bSOzRr~;=hH>yG6IXz*HLh2H zzh_(?81}!SG7=c@TSkoluQO^Ci19f5bM@e|(w-$GuZmYEt^i+WT(1Cs&$#h6c(>0D ze>TDAWvVAb0)E%15g-=p_-SE3xM#diZD4a+>*NisJ}t~nYn>!4EzH(;jU)QBaZ^kC zO&yygqPlI+_??DP-8N|a(Z<&W;-Zop=HZj3H%e&eOZNV(y_gcp8~Uk={Mrn4fEcQ7 z2bgN<{FOVqLac|kjh{RF;cdeU1-FeI^-qGBP^k+b35yp%p`+Ww3U<5=-ZOCp_*mn5 z1$d!x<8APH#^r}5d>*1QGGD+2MvVZmSjSHb`@sTuklMgzy#Q!owk~N}m}LRb#!b8c zut_4S1wdn&hEWwZjni#>T_7&P1%QXgnBFL%p)c7xQ+qKLEPz+4NY4y)fEcO@8&hW| zIUv@<1#rBxA1(kd6fA%p^-qGBP^k+b35yrNy6@F{#ie>J@2udDB(4BI=livM`IUe0 zbB!BsgZKSGlJmO}K5tO_GGD-Ft0{Se1Y)s{pBDCmXU*@aS!~LL&Fs^_>eSYIApEgb^VLu8i?x`V5^*^gm<54z_1wgV@$IvD=aykhsG2ewoT+Gz`KE1?wIE$yxMbU!4(|*a0TJ=*7P3 zAr$y$idYF!=`)5biy5{on9NF;xnU#~iARd0BK-o|s^!6&`3G4*jIJ(shR0%%atAWv zNv{hAd|O%!LkmU9@doFqu;A?Y=LZiVW68J9}9) zRdd+2+|T2Nga`RcU~gY2Z$0??a%}Hywnwnd%_lfgqBSSiN)e6Z5sl;#jrd)FNM56iSgg!U$udAnes(SVK6Ap znJPkX)$ZfEQ=X^mIaep2{ShYS&@WAkyNB#K+o6mV9or4EFeZ#uQZ0o zVvuqNGU8g$4>?#D4EVUTE?C~IURea*e6TKVQv-xrRiD=jOA^iLsosHvP}MueUYz8B z3_DyGf7Zw_8V2Eog1W?iau%!$gosS+0Fz#@F1%3SpDAjri}sLp(YAHLWJ`w@B)X=u_7G-QW}-&B%*kWy5eRnt2cMJV2(P%x=7`=v-3H&FSHSk zV*6K#!uF^QW)#~i6Xk0KLu92|Z|J4nH&{Gq5<+zpM-z|X`5eswpThzhFz1TXentuRXXy2X<8Spo1MS;!n!=rsI+yNN5nuQaY#fL~=?9xL`2 zsEou4e1%aXKrF?vE>eXP8vekG6IXygWL&QRf7rP3Hu!Sm^5;T)o~<$xKM=KvgFVj_ zyFmPwirqdf%*k_;-ww`H8yF~mG;V5Mz@bCALtM@1Wnd^e(kWA562)$F#il}C$0c5F|JpDR~VPur|*o04EXhlE5L6su2+EHZCq}Do%VgC zAp`zI;tKF5jq4TQFB+HI->7}pG-SZnCawVgw{g7!e1mbh{Vm#eOG5_y`@|LCKN%+n zDaEbL!w*vQO>4-2?~=Fzyt{F|0{j5u^7vm&45kCZnlT7 zS5Kd71PZ=7aRvAW<9Y@7$HwJ@#QsK=kwF4C88rgLQas4qRu@}M#e9%k)YHw4K*6^p zt^gl?6DvHgR&3pF(T@Tju4?jEYCtT-1G=j!Aidp+dzi;LKs-h(L8Uu-t!{3LyNN5n zmm8O-VUG5lqgR<%AZqcLQ9RBRyTGPmK8fp9;d6Q|qX%D|xB`5yUksl_Y<@ko_tiN_<+O};HAd(3h*-H#@paSemOi{ z_&iMYWU_%vjG70;Vx2Bp|6zioz@I5q3(|Us1|sh*fy5S10MQ+89=gC67&QibiBjd? zMS_X3wBPO1I>(f|z_mt=0SUX-rA6dY48Z0f^6GxPS|;+Tt;IX{X%PF=){>q3Gzfkd z8OZ8s`|sR`ApY`m%&zc0rpk)HfgGj&F(QAZ3p~XJJp#mqNMU`7O1ll$xTutUX!p{@Qb&@S75Oh>&Q__z^jhwY;3p@p03T(X z{7sPJXBd~?$LDBYry&DAI&lSfo^ibb{8Hn_+u)ZO*DJs;H*Rh+#pfGUPsRh>YScU+7V9C>!hY~c z59Z%uwz|MAMvVb6Snp-D)@b;$mjUru3l7U8o@6ZoZ!xFyfw(Dcb^5gM5PY*^mD<3j zq|8U~Rt@><7JBxH(`TGWyyIM^zOG7f1AlGQ2#_Hi*jm=w{V%uQzI<70{}ueV(;mXy zepcCB{@|HAweEe-KJpBDW|@LYQLYneK2D>5avC7;RZ2}Z2%kHKOi{?R1BtVqc4EMx z2zpyz)f`=KxtfF4b1d@gez8%dNvoWKfMjg4gF~LkC!b+I6oMibL(?)$v5^BW@(Rrb znT)siEh=@hUd!zXd`sdA@Slv6cNdCV|HD?4Z>{v*r6B{pTjC1vJ&fxW-~){tZhtqG zk!=BpTD=GO^bpuCrZ^YaRLp-be3mL4+=vQ%XyOX+^~T9NWW}3|8*hW}_iM74KN#Wj z1*#{z6L6JLW59PCH441Ws4?IVl`7LS+NX7+3625@ELe)f^%B$S0>5L_2oN9jN~g6s z2?Ft03;LN`pbF=h;=DZ6?4M)FwdUtq*^i05RDGOkzUH9y$3*!EU#VS<2)8Yg`Nm4a zx3@AwYvur}o$)sKpu`p6na0USpo$-5T)w(yYu{lF8SqmRSAdT(u2+DMHEz5OUT9pe z0Kd$*;c>iBWu*RrsMTfc6NJN;nqtR`EYhwM8venH6IXygWSo2)srbXj<*{S`9F>vS zfvCl?uTzCf8^*yONn8Qm`!{I=0nadQybV6zxO}6*=LQS53q&nml-H=jebl&Y7C>T= zFX0{Ar?HR9$=^=S>C?bPu+!YA_IEM++2PBJM4y}HGKXewFNvmOuEx$(I6;7qSCOOi zx_fJJ^%(hty-#lKH`K=*^N}4l^DssT<80F!0TNkUN(9G{rnC<3V+_rb^J^p5J2cSC zQ|R^Nu!TDU779oNaqP$HU|*=$DXo>q_&AZlN$`rxi$v9t%N&xWWQ~S#v4u0<2EQ+H z1^E5O^$PH3jLWx+cWK|p^eS&dfS)k6#XbS8_1br}$&9zb|CP7`{B`5x6L7^h7?+3j zdF}hYUgewxyx!FEu(oL5pG;=F4Zb~b1^D1CX%7QG(zx+9_=(2#3h)uejkm!a<9Y@7 z`NrkLB;Ma?Y_eGc@2_eyA;7sx)rCuIVG;!5GOlo(?rw@*AT~?IZl4zBg0B}8YGan! z8aqVcVTpQ@!a0fZ6?ISTdZ>wvVCb=l!qAb4@`m=)u75F+IcPmIQC@42cAcQt>a~gD z#fdAxpE0gifY%#0-Uffsxcuga&wp1LnS9{8jT-rY!jC8FvkEaDY(Kf}F1FunhUVc0 zA7Tjj=_CcjtyJW&^x;F6EAW$MXbgy)jtoZ4DC!$Q5fY0>9mqjuh`*Xj{h@gEacfLk}GJqWzFarvHs{ae(QlnrpY zs@3bB7RE$ySggM{TU{X9^;SSD*~-3d_7k=77qgX}eG&PYitO4tv9;^w19ttzfqf{l zc9+)T_UdWc>BGKV^>^0s1{FC&yYAn}B>14j72ui1$)k$m2O5{p!Yu7OxFG|6MB)nY zBaQ17;71vk+n=p{Pj1M7pPIM=e1vhm0(_Klx&1lXH`ny>YUkD*m!@y#l<^xbZf4`qs3nz`GbXJl+qhEmxAF1IiD&Z<^+(rbB}0Z&U@ z0e*^cy#oAH7)3Q|tl{H);&nw3XNO998J(wH!D2=)@J^ z^Ni~i;8n)uo0Bd~AKw6uZEtVxH-> zs(|M^62#Zk7M^AM22LEr7FFEy7Vcx?ZSX%Ot^n_4T(1D{Yh0e`8QS-Nh75RS;tKFX zjO!KPBaO@L&(Xfoh75QtaRqpuaq?Na;?>6G_Pg5mGQCchZ;-U*I~25Ep?teMNA6Vi z_&e+IDlx9t;1Ib+yWXwWvfRNRNL&H_pmB1KP`u}F(**huE>@Y3>y<&!{*>~=2k}{z z_>x|OLHts?Zc8G-+m)KqTAcl~0Wx>d_{B2t?lz>wd-);F(7p$l%y=6-GjRp@fyVU; z@Y9UT=N~P-p%Eqcl*AR_R~y$Wz^59Qk8p+dy`~`pJ|l4j z_~*v;3h)-=#@pcHR+d)&as{8?Q9a2jaOdCEYIU8^dYQ5!2)ukikk;)<5cr?bK@N&G}J}qLGI}(tNm)Us-V^qZIz6n$v+!NRpS^CV@=;fI1{8y_-yq{0zH=?rUQ}*;mO` zI`}W>wJoV!G;{T|efuz9)gE~<=K~kY+uN+tf7I)Andj+`+_#VFCM&WzK+;fdI^YYn zBvALI0zV1&vzzX*zf)^2u;Ho_4O~_Hwp^7T(`?q!VYB4Cz3Af{pS7v2d8^tOdzI#* zB55o$QvPz125u`!@3$hiH3<3Y&Ftiv6jgtoNdqUfsP|H{+j29tH9vWIz70i48ZS0d z#zzC!mAdy_k=`*ulOg%M7I?aOkk_*`@E~&De(+ImZhZvn|8Cahw`6D}>m#}K>{H@< zstHU^E~Z>-GQJMUeC?RlWU@Aiq30smi~X*PSpMktns@6T@A@jBsK}(qetMX!Uy8ER zRLlQHUE0j~UttG%k(%UYAzxtqypDaCq4~F{p`?|4Ylj z^FhYt6|N6I_#lqR(AuSS@~*3QI(Y9sx*P!5`IZ0C{c9y36IPjh$c}crM0-u0S3{w4j&9>&pqrhL4L7b z@t%n*z)vu)SAb_5mp|5E|Nbf?$9Lf4jT!@DDSkT5ZFRBrXtOl}Y}(2nSpP*89+eb* zYI2cmW#i*8wNk$O06#5p1$e}`UI9MZxIBBDKmMvD1}7OAHb8c~5y zO`lbGbPx=&d=pW=F=lWZv>%=}BTcVo{U}q9k2m%B=}0|( zR<>rzp1W<44pAPVX_33_DSe--iuA_*lKJ~97$c1G3ED>yJyjFLQ!Mx9jZR7B3J7* zc#FS6yD%(?|MG`4@q|iT%|1VYft~kEV8{A~*&%cCj6;4&lTbh+lYe&88)^~J>vV+n z!~?+%q4~svFASTKH&1+xynWw~7h{q)>zjm~D<`mHeZ%a$*QR=m>7!8OQ3yz6;iC{k z<4$N#JQzgVI(#sN-s<SaP z#n4s0QRBWrujQE@d}HDY@I7x!XLayi#*MeZ4>v9^4}7*%raUhz+*7Z0dC=M?2?DVn z*AX5LGQ}B^EPLuLc9f~ce85U)wH^d7pJm#ff$Oy_Lijf zj=fB450mIO`}`up&Yv|hSqwntr>r$^GFUTMLe0t#U8d1GAQ*4+mgVD|tr>fzUdx&V zFHT$mKGnEh0Y2TheDlTr3sgqx6Np+|cE_p$(vwzvg({w)*PY9MZF*Ik<|#^7zy0}Y zZ7elX&elFf-k?O18$0=w?39Y$3Ntoa6z}vW_S@n1zl&_EV^Gz~f#=^~EVOrzhH>zoi7UYWVqC8PKiIfDFznw? zWn@NxsKqmqD|S(Qkl7jmHf`kxnpvvw@J68EM<%WSKgzgX0e+lu`5Pe!7F%k6J%?ee( zz))LW@j_MnfCaJ8i)_@cd;K}B1n^#oE5Ngi>lNTf8kgq*`!iHVVh5rY7wfGW7}Aqg ze1Lj-pn1#&JzKk0>a}{+s(5wc3h?`k>lNS+8J7APQIe6`2NP_gT{VaWh8bWYVn{qX+TIf6z`|DV#T{^ z?;hqc8}uygI#{pepuvYGt^m(5u2+DMF>bsKUT9pe0KeF{JUPTMTV-U7z-JjX0_-SN z51ZDpNf7uVqeg*55vT00X={->KUuG3Zo#J{t^l8AoP1EDc!hD}ZScPv*DJth8JFjl zIF_r7sFIMr9-f;0B{cfLMy> z@&l^y`K0KFvr)Ugt=Dpjz}F?N0DsT8UID(|xO_O9wC|@48Sv)B72unU>lNVtF)p{i zMf-l+kOAMCxB~nK<9Y@7&&K8UTesKy-cEWg^8=oixB`5ralHaO+c^0-b;V~Jmp`B5 z^Ij?=B>?h@`M&1n~idHIOzrM{$c`yK2b)QGjy zr}ap)-^pEe0++{b+vQwbVzC_3++av^1N+%)?gbj*3-l_lx7vLgud?v7HxuV-*Gj#X z)dOCgxB`5&alHckW#jVd#QsGpBb5UDoKa)I4MvRuF&^(9nE#+Dc7azIH3Gz@yfpzf z&F4=Dx%m#}KX2ye0kJ7xaRWBZ=TBK1)y6e?Et3!aUg8Sy_l@fn;GYS)cd2tHmekRV=<~d7suo8{7h5!?g&~I>*#k-oC6)i;0nca}fB8 z0YO^7Ha}e;Gbmw;MOw_DSOgwvGgk`IdWPk-3v8rE1cUSlJ1jkWS%9OAgh1u)MkoiG z)9mT!TWWxTRR8Fq*9-sUQ8a&OA#{L*Q2n!}7~9u^=m3c;{O3=Fvpg%Onk9lpp@{5@HJ>NxwU+gT zGDEY-%DJ=F5%ohNWg!qYrC+ZYT2#MmsKCbfCcO|C-vg}*NAZhUSqMH?Lit1;qG=?E zs@%L@Sc7OjE)_VC5UK*l*vpa}kU0z&!l5dU(J%-v6cpl)`X{xG0zN-1;IqR57S`vQ z+vSsO(&ljAVT%qv|IM{Va;@xZQfQrKzD$d?CwI}jd^1A?drUF}oTrq0eeM*y$*fOu zKpa+blW_SgHNibj78UtfXVw>dOd-}qD!0AB&jGf(W@r@Kmm~_?pGp+A?`~zBttAW* zWL2@~u|tGqj3yz-KTLOu?TUD;NIxDl2Ye0_8ZhsLCKV_`6UOv=%^E`TtmmCEwejMj zzGdqSmJzxyS2w%2dTWlNU&#*MeZR~RQB-6{T@K(?}2&^rf!aQjW*1H zpO?4-yvVp-0bXI8d=#MgKaA@Y;FZSZp&qAw$Lm#YY`~LDZE*{HvU1fPLF3g*R{t)i z{1v%hg!n)%NXHsAvDSP_H7b68;tKHP#`OyDRmSDR+^BumHDtg)NL&H_k#W5O{A=TK z`&+c{=7tRTmc$j{`%FvE#NfS+8*YD^%18=AU8d|p7|T}TG|KyJaGm1aYv;}0YBcj;r4G;TarZJV^vN5xf&pr z;v^C)2BcDeQ_a>GaF$Ucz=s=^z0=4Ijr@~JC#~$1m}||?wX(mV&b8*{TG<~Ui zyNI>?QYrXIk7$>)I#h*2Ql)O z5Fhf1WBzT?*}6Or(`z{+;HM_80H0%AuK=HG+;|)OcH?>l_#MXOYlt}JtBhnHc&1WS ztn{niK#uunU&lKkXmnb#0HMXiv z<1CXK!{=L!nghI`sp=Q+aoS0u2C|0HIBTdLZ}#OMho?c@azg_Wt^9#b{>O3{Bct*c zY`|s|dCsdaKvLeB^B(4D8Z+g1hgJ&2g|K^I~rN+sR;VNEcocx2Sinkb-?-9g? zO{r4gsj4Q68i>U@+q6EA1cA7Wrv;~vH^naSiAu@8>vH~58aS$Jm)0ATHn8b7pNDs= z!VgR_JCJhEJ|yxho6{!RQ@ z+POrp@;7Qg3Q0EQbC>pMk#osMuvKG@!AlYOSQ+Gl)MIU)7S8Wr93-S`!$O8`za$96{*XnM zdFVzSx_vy{&pdR2O%M5c`ZrZL&J?p-{qvkie5=RJYgD?N0Pq=!E5Os*X#&7I8z--O z6!(nFCjg)Cw%|t%s+v^eP71MDr<&GYCO8VjrRe%P!{g`8V;6Xx4RUD`|-ZM5I=N zz4u!6a*K^8GlU4447Q_-oR#P|36LROg<|DiIHc;ID5 zjRCP#CSo+pDz;XeVi)*sqeg&DTlq$Hu_~-H#q3Lo>$U51dM#4}{!-!!@U_Otlegkc z#^tHO{x?-dQUgRS&I5{9n_?H(RLlqcEmioDDQ1Jlzzr%=4jTOP#1-H}cTM{)_>soR zKcuDjaO3iQ7oWFUSfjv)shaGaz=tbU=Y|&cgH1L!-^Dyy@xq%x@j#1f&Or*Fm?*!< zw&=iiRgvlkN@(oYBxzuD=hjJ!!khFuU5?g^@U6y;x50mT zW|H&U-Ws+0BfZK50dG=MQmDZHRjQsdTGy(55d_|#R4qu0Ktym@9RFi+bb(7Pj`=`5 zm*%^DTDw^sUEm%@%?CcY5n8uT>-i?w1)eb=NULvx^MTh42+~S}%|4dds)O9aMm7id z-$soANq+el4`#^azj`prU>S>S5R4%Okv*DC5X1vh5Wq8(DjyoauT!oq$L(K1`bn+n`yP7W!3Sh#deVH8rDVuz!YLkQk>G((5@)^TVSW!Q z%OU$4PFXg!IxSX?_yMwVYC&3zUIhKlP0TxM?Bzf8vs{iuwAmA6RT4ETJzUPg+FdZr z=QfKOk9Sfr@1kRVpiTVzAhnZ7Vs0qd=q8gHBH`vC+ar)U3(W zyQ)p&Wk$-U4m4IYNve=oD)nvokW}NLXJeh~O^K8@gchO5K^K^!I$=?Er$X!h|M}1PuLT~m_XcTd?kLkZgr@z_f z6Z<;#OP$HrZrRCjFKerfyHwY6@j{UWU)ar!&ku~Za^tphC*#>3jd3z3+jwN0QIJFt z!ymZ|?i9g2fefv;l9&(tf>Kjk%NF$mhh*(k+XChTiJ?+uv`kzO#mCeYqn6JnpOv|+ z$P?6A@*sa_<~@kymCJoi;Nw#^(oqI=h>c(r`@KYA{fmk6wlTzXRNrhz?;6z$zwVAE zAynU5MH7$V*WJ+^@Hs570rOr6cM}GR(1bC)Plx&mOH~(`^j^JFwxKcaH`&|_IePoh zQM^VKcWa$gR44q|`PbjQtUN$_bN{7gzM0|}CNde1m_s)3c%Ej8eMcS~n1*dWOZ-W7 z(~&QGSjYSYHX&nPD>^3UYLl_-Q^m`K+tj%|e$C$J(ERahy}oYwieAfiD&YT0Tminx zIQiKT#aoP%f1ywD<918$RKQO(E`Je596wV1@;!^fU+T3yagX+C?WV>=5cm+I#(;+z zH3}q(+MLf`9!DpNqx1iwj02DDETpS9?H@vl%+u^ zOQTSh2B9pCLRp%v6nQAiqEMCvp)89+Sr&w{EDB{=7Rv8+G%U2bw}24LlqW3z53@ho z_!y99O~sN+56V0Odq7rcD5F0yHuq0t7N_#2Uc@!wK8pF@)zK43YFk;7+I)c?g!@cE|J z0xq`L#`jTppov;OdwHrN_4k?9c%J$=sgtJ|0!dbmd4S{{JhW}CA(N?mpaMu%GQohj zt;$M^qKhJsp;9UON^h!88G*7w02zVzWia}jK_~H0>pwOB1%Lx!X+lV z-M!oq^}mec>lb}Nhb43$TM2D(oc_MxI{~8WZ5YTW&T0HXh0-%X9G0I2zaZNYUaFO$Qe~1fsMY;nw(o49 z+s$-%+{fPfy}At&`-^$#;0zCPnB+%@i2MK%kslwyDbzc(F7=`2&7xs7s(ag}Ui-UK za68Eg@ZJwhyHoHIlTD6*?=@MzJH_XPwy*90pQ&cDcL6>}Mg7f1r$?(}iXGsUCK?0& z!bBb5%_bTH5^LqbuO~$NWs9~Ae712-0Ew^K3eh^)6x%>Tl)eNKqRcWNp#?pDzQ*$n z>!tj84IRo`{!R)F3}rv&bH;9+a?5%3pKc!Ty8wai9qZFguCtG)c)DoNj%zt7oZOl6 zf@OCmtWLJh7zHMxR!)>1AH7Zqu$I5}0^Bg7Q8N2-9HrFF1uefHrK~$ zy_S#Fif1QT0p7!8@|SWIKgDGEQ5yVPs*X%b;KNPS0m2kN0l|f~99{wIhWX)DZnzY~ z-7SbQV4W*JeR_l%>}-bF+*_nCE!Jzlrr^DktN}Ma2;fZO&|n953F-43|_1Ygy;O{3{0Umi!+WCPuHCaBG;J?m7XajFCQ3nW9Jec6R(F~iw zx?x^G3~?hf8@P$aE?Z4tohu(X*Qj$m%PJ168|FdeX>WWGaQ#w)u@4?2AU%oB-;=RT zD%l5*bCn@`=rXDMxI$mrqBdy2TP0Zm{;A2j1^8-{Jyl0mFW?VNGzNqz z9&kBV6Rx^p-q*R|QVhwVe})W(Y*yo>{9XT?%Yt}|CA1v)HWQ5kzht82z^|BS6nK@1 zvZJ?M^`+(_1Anfjizoa^;&K$70*tx0{qV=>lWaZCYu}q|J-Ex6EQxwQ5|_C17g-6r}>vJ za>F);D~xL#_!1RWW1bcs$NH#p`S8E>O=LmQWgx8$E;Gh)fiT|lN${XqVm+)2jK1Ep7&bA zvQs@m3Eoi6RkDwIVf`WNsfo`i{ECUjfLEJnAQ9G*238bFM7~70{iqU`r-3xiHE(So zl%*bxubc7exjjO>!GyuzDZwq4GBmJD!Dd6_R;9d6ul)rDd`FTM;HNE38!hnDO_tyH z;QzC7$>IV02Q`yU2Er7ND!68uVYWqhsJ^tdsf+>_nrIBTmx|<<(^q8A@K6!k&|zW- zd$4rPQ^y1%qX>vq7}GU+`?yxG{oVp!pJWAi^9QHi0v9HeAF5E?Gg-d;?5Az+wHbMB zn%75|*Cw#;A>V%G9+pNPmYN3wmj?qN9)dyj42|bmdM*DT0}bqEH74@E3o}nG=9{Jb ziUAEg4_`@7*Z-q0YkKezNw7;IgF`fq=#Lq^P+xnsUS(PWUt^*UaE*#21o^w}zRTf4 zD=6xbO0Zh5QAm?R=$xTCXBv-u%T)0PldJ&$z+~M5{9}{l>n!}|s*cQ3;D4ED40xr9 zIzY(dr5E}yn_(MxiHTZ3IOQP+Sf|fV1akT&^xrr7aUh&BEr50UVB#sqwR$a=O~t=V zvI6`olXVO5JtoVGe~rF&w_c_AK+NK@V)%12Yy<0tdBHHe(+rzHJWF+eb*{WRjfdzn zg8vTgxB!(@{q;Ju1;^YJqepL?jCj1=JeOf&&}zly4bo7RU-u?;-e zL=(Von5YdTu;5XSxSnQKP2i~}8V3?dKdxqv)+bG|2_zU~G#q7IP2g8L$IU2Ji+fyb-6 z^2;JLh^6WhT7)Bg2b`;6REo6bskG#z@r)^|w8*Dar9npG2uO1AAo-!@b(Ga^6nL45 zmIKMB{4P3~5RhzifP^FOE&4Em?GQ0+ZVpF*hp4DO@xaSfwwZhrefN3tCpoqs=^>*V zW;71=B^6N~-obtxUZvzDCnvZhLngtYE*UUB2M$$e;S@z^>8D^2enUIyFHBGG_KWQU z?aO?m(Q0^|hDt}2qtkaqDfFFD3VnA#_Y0-%f8$vG{y>lR);46aZy93x7b@DXG$KZ7 z7`|7My^7E9-eGuf!qk*`1!QWc)Qz?9d208`ipb|EA|Dam zeTwx{3;2E&$+`70woVhSP_b>;!=_*hNCu_p5K+8SU6GC~atCHEOW{uHEP0S`(0UKy z8i|j!mZ|OD9&8zO;9rnLu&+)cUqxz9b;@thV#f_P{8}xRgiwBi7E3&aU#rD(iqAoT zO`-QnL%DmgW=~APEr#A(@14*GfZ->#Yc^{fTg*9D{`^hw+fZIt?ggIiqe}A`>*?(I z50zm&dfmX|3VrlBwDx=jesPi&;Ln<@TYxVxnfxq);@>`O@FPDy&s1I6iUU8VqG~Hn zYh(*OmuR$rpV+bzRf@Ep|4>r|{^M44MOtU5R2Bo^MN<@MJy7!yMc~U+RJo>gOi~0M zYoa#rQ&Vhdoo|XQ;4h~r(xR%ta!6rL)moMBfz#-jaP;I68f&zKr6!HzO(>c)C~v7r zVOMIcOX2sl@rSz57p&CuLw<7&E%_Kfc_jBCLVWzxe26gjAwutCtrnAdOZlkt4^rv9 z)i?AdROA@tnpN3`!?~{%Ca*RT|WEMScHImU_s#`X2g{*8Er29ivNhpfJXyT;2+2sPrFn{o2}>`DHYE zAigAvU|AkPwjs@}CUUFneSEBlTMmAG*dp>#2gk#dYqr)(RDhe>JX?K?73Dp4!tgnyWo1zf*eLv2)}P=!bhzuN~aAwo#(_dX3$pHJn?o9k^v5!@fYqFOWq? zJ`izCj~TpD!z+c{>e3cLH0il?Qxl=@<^%Kw#pbAgS5nbTTN%e5rI35FX!$rqL=<;u zXd(h~+m&Lc}p^tra(8kp%Tjc63^bx8!oorHPUDjY5~hod;$(;SWhiJ>%IUxsBFh@@!_)_>THfB*A?l;%Ytj0B(Z99XK$_DJeMS*= z2uAelH6pmBZWpXNOk;w*6b6I$f>qu_sp+%E$6Kw!9XuRi74E?Qa+{|e*mt&JlRcwj zl@^{&|7HG=(qxv$l$|-rfy6N6 z#PaDx4*a}|%5!Tx?ruBH7Le+fdUsSG?Asgr#1j?5E>ABxclIy__a`l# z4&0A2?hf2fP9nI^Pa;2^AtK0fLB@{37Ov7*5<J9C zrj6+XS|XH!!*9BF>U8zvF`k0hUZPz%^{K;iOnucS4Of~vLrv7LtLr!f?*#3d6R+}9 zC1lSo3kHxLmSO})fs2+_N6m}%+W%A#c<&@Dz`rwDw*WU<6-VC|yx3&im5c#3=A~6O9A$TfVpNJq8~gnTGxR#18zfiu$*V|5ALXsZ9V0LVw_4h%jbr zO;D9Xx4bmjIUK>$!P135La6#0S~!EgK2p?z2+>{l6pi8QR?;?*F*azt zd3qUderChY=;5<6v@bEQqd8kvd)V%edNI5h#4=8Sl&~DnJ|pbDX_0q;DVeMeSV0~A z@e*_rP4*cF#{YT?;G@RyCmOZ=N#WpKQ?DBw8C{_?S6LCVZ44^Ic=Wn~$5EZE9b3pI zN5IRHtN_2pWZeRMoXO-z-xa^vWZeS%4wL1dd?k*ztB!;U#H^bBz6Wx{c4U};++YqYIT+nab#-!q+E}j|i(ooIQD;sMaUxwfxkr;mCRM(wJNHLPV0}R*a04-F2xpjgo!#p0t@b1#C5U7)ds#>-O0(w z7uL`qmVRXI9xcL=wGy~M!>AN#?V-|=lg0s4RB4eDo4KVKh(TVu-c6R z|Jy{%f#g%Jkz_(Z@{A579J#srFoGv}VtAN290k5wMg4mi_(+wFRG+|>D&!FyzYss8bKpRQ7EV!wmR<^m;5W33{=)S1ZNJn$(7wz^ z8f`1C(@^P%a%}ppD22W=N}=x#=x$V6_7SwVwE>fTbP&_OP|e{jmfv3MXTia_sw$_>2hPF%?wpIX3As7MYLSK2yF zxI)FIVQ-s)Eg%_`rb9&0Q&*%Ti`;>k%To9>b(TEHmdJYu*GPPP&@#2X+hZ+*4*ZLf z2=;d*kslz`p6Zmxkl1mE9fQg+9=&eh@eD1_hxFQijsc&YWCi#t zlXVO5O(v7)7{#}ltXqJ8XR`e1kvQ&D9SIePS@j^}OO_k9Bg6dZ@ssN5X7iXmJ)&}j zsf=E$@Rv#CBf=^XXZ`#cwNAvD?_4E2^!eiYS&qA6Mj77mdhK^F_zg)`fUh)Jw*ddx zWRoM{xj(9S`(Gjj&o|lR2zbCK@M>U#qD9v;)SqJge=gg}`O-`1VC*_==H_0)J?t zF}VL|qETRSHRk6ZLDK{i97@4f%6j*oC35Lgp1pIaD_@zY400?gC1XUZcSdrs!qm!XnbMHGg zAYQ*pwl{`lnxu%KmQ>#3*`@)j+GNVDvT3r9PTc+Ux=G_T@`K`Yw(B8aM$eHKj*b4{ z^uw#e%o%#^-+jQdldJ&mWwLGoUSzV#5%3F4)-AxxOqOph8v5GSdX@POe42`?(M}68 zQS{yTNHy5SxH{e{I`zS9do|mtv2y;}*_+-pZ_{7yu=$_m-=mL~0uIA8q6}MG02`mo zLzIJLYT9HX2L} z(J#?Kh3;^n!+4Md&;l+qQI_xued$oW_Gdo$#Yt9xU;T*mwg-5n$>cABD&G9jNzWG< zpP#a@IzT9;?q{!|0hbJ*Q`W4XtPL4<@hv`&qKP4nC5jWGDDGPAqj-y^vd&T(2e!2$ z(u=@x6OA9P@E1u0-0qROC^uTb9aJQT9&36uUY+!SN1A9H_)` zuTP?nDExgA-K&sVOP0PiZ_=8))KVNH>o*$F7~JCByy z=!XjFuIO$xsyc_7*#!NzzZG)ghYD{@BA?$fM6ne5!xIQ{rpds7Gg6Mdv zU>V<0waKPD;qrFju@{#AVE&pwLYUP!y68c6WzqvuuTsyaxQpsT8V2E&f_F{upPb1@ z!@V<1fi@O9K!#_zf_wH-==n>b z&xXkXZIBHrc--i0=4kgaY=eYZTA8T*PsFg0l4SHL8E+@=3%qeBeLun5*I)DH@H|qp zyH-PRxAnqOATgDC>m#dHGuSYV*SH{%Q`TULciC+LVGBF?L=Bv(%A+4t*aZg@-m0X= z4!^^OaC#nsFITRze0?fmwjWYg7g={@&xE;3=IYmacVdGf8<#WIFngI=;{U`o%wKL= zrO-$2>ExykS+E;`U$kJ~unhw4o@yI}@zpx}*cC{R->xEd1;HSAkP=V^nX|;5f}9{o zN)XI!_HN(Px;{{L?rUd^ESxv8aEBhktM$d;*%NyL*{m_^UoV?gmbvF6s=ww#tH0(u zX~)6IzFSKrnNh$Xe+nvE)O4DX;BF`Dqz;fQ%S}7!5kooZeH5jTWQn5``bbKlPkraX zsWWiy&(xph+)19t+3doh1bXZ0AkSM@2YKGQI>__Z?5P6Bd#9S?VV!kx$MXlfsL!f4 zqoCZYc)M@|gXIP0uL&fCa(4vTFOnWG^>462`Ml~w8V2E&g8M%Hle1tKg%Xho4=~vU zL3*XY{}MMwWc)D`7$L*WGl-h0&w**4tvSq=kz=gj9UuTf8M_S+WL58ak^_Y1UK1MV=0iBO1<@wReM0# zFpYPHz7XYdjw#-y@Icr~Js-%wX*H>;Y&f98E;xShR`)4{Q}Ymfl(|Z_UGpkowr8lT z3-ubLmaAm03Y}3~*m>OK2zaX`E5JWDS+@Y+WHR~KfZ`WzJ@|YNpDopuB?tI36O995 z><^$$j~4vFE)V)WjjIjBN(y?y8s9P4O`2U3h+RL1{7u%}aH%&GhsO=!a2a+tS`5p9 zWZsWqnbqNsNfB5NHvg%`JlKPAdcAQ?0P9WAILPVM=Ai|wd63_2paoqplSY*T0#N~CJ-czza9nRvF4C2R zfHkflAq??6FbH3XcWSrZk4@Xfz=}{fDTrzBswT_pM7}jnX0nHteQZG$_*}52PZus$%Px?#g0GR z2z#aA*=1w>Q&y@I+^e_M5TB^m={|Ppb%U|7!v@fK-GHufkiOfc*YaZzif1QT0bXOW zZUH{dWb%zX#UD0V{$Ve=(wQAU^sY z+dW#iksCWOdCX2Mw^rJnjlKok!$eKsekN)G4>3_Qk06_{xFai>EF(P{IF`8|IP~nL zsb7CRfB#HBryqs>*&2Lb4NPM4sN-Em?+}bCMOUxoA3>$?r`Lrv=#BCXP@e$75}^!| zg-Vhtojt_nR%5wUw&vzm5B{Co+>I$X;7YE z!V@inM0PGfqLpEg7iTOFYmBgxyKH1I8>mRxVKg3ST`Pa#ng&snKZ=-VDZiBHvkV8p zojM4hlY_lI7wg->p0)m(UuK9E9vJ}MJQx$X)mUzo6$>j$Ap;kPd-)5sb9b{OM2vbFoxqKl06yOr>R^Jh92GQH*GC$Sw z*H^g|;SGBU00>p7=L27%>)D}tEk8P`_{B+9fFFEt+9H4plgY2?Dt?v8@}~!UzE1fi zR^TRTCM5}B9PcB#z7S!q~M+LJb@Xn_@`1qqFWHi}UQ2b6Mx&Q{{axMlqPy8^uhK&51QL8$j-?>kdH=h z7L3N+>VKd#AJR~-)2qZaM5vc+l-0gEs2HgIlKT-Fb;D!Tj=*Gqxar?OWjj@sFIUg) z(O|a9;s}H)yoExBQqWf`^;ql(z4q@!;G>eP06%}5bSDCjnrw0eyys(*p3f1Vrz^kQ ziGX`6l^nSM4^UAxFDifjdr7q_s;@1nx0Kk=9d_ zB9OAg>sMZwHih|=)oKiQv5Mp~MK`UYaZs%Y?H;XHTD981x0z@Rc$SIUzza+?2CS!$ zf8+W)8q_)qPVS;Kwo$fO4f)X=8uLvknlyG*;R71Sj`mI-q1W4{D+Dx1Qg!K1;w+u{ zA^1flx<#+SGbF<*sbrJ&zIBcdv_B^Df_fj-p8{nJ>|^nd0hyJRA}uN?Z$++K)uTn} zWFhj=1Z&fo+NU`GUl0nzKG=aU60g^&qqno}(bpJmvOCD@u-p%x+-jKW1pZ+&*%Z?Cg%kbeeD%X(o&H+P?{b_fE0` zyzsH<<^o=1GWiav;{6_%^n7yoe2rDH1B6l*)(ckAI9xg9;~M9zqOn?qat8xmRM(^N zv!n+kwvuoC!L=wv((im%;hNXGb)l|e0&v+uO&SoQI~qYXn$1wM{2Ljn*L;kDWz-t!K$I^9T*7 zW;G;k;@Df`C^c!&`K9Kd$f!j578?!9QJw+Qm~B3mpFBci#Dua%qCwS4b3&w4r6U?C zMB(%y5)E|GR|UO}oCrRBbij!qx+El>K^nLSh79o&YM`>O7GWBdpSgh`abA6(#_2uO zU-LD2le%KX3Zn5U;W9p|%TLqpLz5%mc9Ip~*O*NHY_H-YO*T0KzQ$zvF&{o(qB?SG z0%Bf0e9(G*QUt;uKc(az+L4EL4-ae1LmOE4kneflqXw6nVYbGc?^I+j8vMivZmw1B z{>B1)eUcU6C(lhA2JixtO^$${ZL+)r@Oh^N-vK^J&17#4gt00$t=*F%5SMYE;Ph^D z+6LAQ^HOiFo_02mEg%JuJNlv?4I-51h;#DKRl@dYV;coRAZ%Y)LjyLMJ!h}+vv5>N zntJVb9=M%k1^7AJrp^P8noN!+6z{oR(i`M+wI$F2K3&aaF#ztPqN-15U7Zwxf1095 zYla3QjKEncsu*c)mK1?IPEn+_OHu^xF-4KqQ@@4tPzQ-eoMCU{F;Ez)fQ|A_-r+o`!DeMDykBv^~WQroKhbKkg?o$+L?U@vTi>4^jdUjF-QkJ+E^TM<#%zLa>W5A27dsa2T z2i1xtcXVyN(u&mvzSl%!z)zZ}4g9u=#(?z<1`j8~miM!P1k+EwX`%g#d1wNOr#v{J z@!6yYtVfc6&FkA*oy+uE?k#9+t!(A(p2m(Ql)VLw1uE420>iIuy8XR{HpozQ8Cb*_ z?k#Y>y%EaZf(Fim_3Rs}e~(^+y#@0ksbqT#-#7hlvHGy1Z?FAa4G0PN`wA!C)#}r}0G_jJx%Hsl|^TzNEX4nSS4fBl7P=hmTQGq|4WCi#RlXVO5 zT_&3x0dM~J!P_rz(|Tp@2csLpM5U7vdRL0y!liS8Rpx=ych>izXY^+X)U zw*;^G8{bO(IMNY%?N0{qQAt*Sw>~5d3GiH#O^$#MG+DO*kD5$&_=-Pfvi!i6*iO_q zWQYN`QZpGjz-?4i4KZ3vk|Ge-l_ITfQUtzr3L~v|Bt;-eRE&d4e5$3<{;9%88rK8? z@1I0@XxS}=5+&{?upU&tvCR#aV)$r_U^$TB`Ux)W(K;Y00tvZNq(vyfXEgITmJtV5 zeXjg(8oX9Zh_?Lf4RAvZ|2moH2@KhF7%~_BMyJIY+JTHQ85}?c*!@4;aLS_bx3GSk zrG@&jUaR@QA~pSB_qI}GZx~EUtiG!r zfaWZvP%(pgXBG1`1lo&D-d!SJP8jib%}wMJAZz+Bu&N$r26ECMetlZM*08ozJ?Sza zu}H_lM!`gD5D^KuKcM)JYBDRK1qxuRhn$ z>Wg2nct?TXF}syBdNc@oq|rTZ_1f9n&#*);*8Y$mzL?RYvANbhsqdi@Vo$I5(C&s% zEyDO$Xpq!hRzM&g zFrslFMU$h-TUYnsBAs9fgo}|TLj*`r>m78-X@7KjrIBEz9j18(&u>W1`#3MuzC^tBw8ZLLV{VrS2O)KzVU0^@TrmU-nJ6 zoM?GYG|V`F=yscJubtbQ)RqXjiZ+qY5v`sR{5p;IB1z%{+hAPr z(uS4BTgm)8WwkG9DfGQV4N~u9@0XAWD&-KN!Jv|H2xLf!zX9Wm$Tog31?8D$vfiP6 z#e|c{&d$~zlV2%QtJt9~2tB)#^}!@z5k ztN{PQWZeS%OOs8GfEQe!esdAL&}5S%;1wpz&%=oAi^?yXA>j2UY60=wU-mjZTJw~@ zKfDy~YN8I1C`8MTZ-O}2Jhp-O=zDCN$D5NP@S*ClQlz!S;%Ebjqf#6c%9qVU6Ic(W zX`$Si6oEMJduaA(;a?tWfb~%Fead;t{5kW`2Hs?%aiaR8iuxb80^?eiuzj@(L`f#KgcRO3QX?Ca(CH^^-1NVr{%pCAURF#bUa5HR+`>x+{HL%oNvsK zpDq>|;69LG%v0^Dxxz~+HzY3@nXKXzSa;G1hR22k{5=~BONo{N5d7vMLDfbqR^&L` z=wv9?-21s35U*b)TZ~|tCMja5C6)Jhwl%`4Hkop(Y?>UT^X!FswclJsz>FUBn~S4* z_iEZ*Og$Sht zU)7_9Z7`kwOFgZ#s1{`h8(v4q?^=~tdD4 zfCt_-MUmDFO+plbTd7F=2;)3$J$Z_h)^n3NaQ~zz$+`2T@K@p_Y_NMAQeTLl9MC$#Ydw zPghBO^n}J}sd}0g1Ll8l><~6XLtFzH7gdb3Qn|9VZ?$&g+iVInfuBfI;Ie!+=7!l% zOL~?5Bh<0Jx+twp-mY2IqeTqC+1=aK02N6&2otT3TYg!XsNhqGhKt~RE`lIPR2VH& z#}1)O2l}$`(uEfH1ig8d&H0HBDoha=A92Kn2J{^2UZ)B54L}>@?@(BDg-C=8y)H|U8ut)h!vX^ zi9mJ=v`Aaln!H%q@-t7z^>g(qT)|!oE%rB+M_SkhtJ^_J%WW&@u6Tdt2U=q%-N)*+ ze}XeZ@$4ikz)MUf->y(RYBKqxlH$XkGFbS*Cs{a+omXmvY;&|6`7sD^KBJy0p=KKnchak!= zu(u2M#aLcr88v}~P;R;*+gb}M`&S^f4L9dkDlepA5MC+R9OFMZ3pVE{5!tXoq7QlC zpZj4e)d|>Dk@T@F1Aa-Vq`v2Kx@>dqRl>yqr5C0cWNOkPGMRTitY9j(l>@5{$p_mb ztvuOchYG<7{YHoSPcGEq62yvKj6@*!DO#j0_kg@u+495vlKqQt1)DIm*!WZ)X<-}O zb!O=_V?+nt^;)d~8-j}4544p^bc9~ZuNx>nD#;4)mrT|zz!#Woas>RS-3D*Y@wwBJ zD;-&|fSARb^SNrUqh2K?*__kDHrO29qXu{FN>uqq-0KK=aKQcS1r-BKq80QjT1TpO zrA6zKB$e?+>o%22Zv!8t;flE^(t3hQMG^S)DT@1R>jhJ!v<^?^z@w6)Btz@OqzF7M zDM~=Ju1t!+>C1D28lV;Q7%y$5<48&nY`K?f&2TH*>iKNB{Ydw^fm1q&a*7JIq*NlJ zJ~$nMNTQdqmqsdO~Bgh}K_s><~6XLq;QzaZ$xcE0rr-EdO1*@jROXP2dky zBwWEBIycO2D_$kMO``OrCWIwA0sKjBS^?l1P3lkN53ej*8eBDJ51c^#K zb_hMV%ka`KEba+<^Ael$6W>;tIyl=yU!w#NNp`Y_hU)?)sHC+1(>%0+IIR@D-%9Ey zj(06L8~j2mBF`1fA<=z;w%aR_D+J<}RkE%YTVGv#^ z*u&yKIScmCC=r?P0FzyC!0nX+|J?RwrTl?As7U%)mI1neSSqRS`J67>Lwl8QaX{&T zDF&IEw1`aRoewLRinEmis}0Eq+wHA9*(!nx!3q6Fhq|Q;b+`nvdQ>V_ZR{j!S9^!LMb!EWW=HTd02&FinN zRoQ!j*H&u%kJfA5ZW#Znb6n(~*CPMC7WwBjz1oHR&$kXd)VrP0IMmb?Tmlj zcDJwBTA>#jmiTzNkmJ857aFCh#-%WYXWdsz(d261#UQ zBJWc~-er(99^n>`@<8J0E2;NTNxhRw>bqpZRqp=G;m3}9eZ6vLt*5ro9;)}$8&x)4 zPkEn`wLA(1brUId!*8YQJy%liyOR29Zofyh0M&X;ZXtnpkp|vH8h96J;9aDHytgz8 ziBYs@eKbkshDGagmC6kZc=r@VTAOO;h$66-r7)7^hgDI$iE8@?P(s`K%7>J-ft!K6UV!j z{XBl56_Mu(jwv3a@eo9L7~t)~69O!Eu#B2OLMV?PAUiba0a;$dV~WSAKBQp~UMV;x zz<+WU98;h~WWobXcEK@)R|@=dTfWYQTN5}Z-D+ii1xscy>vFp6n8K@sivvo((y(Nl z$<(ApWHRb~SiwZNUOBK5uA%e6c9v~0vQ-2Xg1axF{?>&$T!L7!nUVuVL?`LB{3fO1wMkZh-)*vP0e-K^ z@;|c&|Ea1YixUvD`0@S>H8`_I4*p=072vx~)-Aw|r*c*zfhpeNX~^>P6MSB!ToNqs zRui>=_o%3fpVr~(M>cA}BTdu+{^OqYGZ0$ORjJql4>VB+c*PW3T34H53rMPQf$vd+ zhwW8`5^O#<*T7$(*K%SZPZ4>SLDG1HTRh5ho2Rd&-a{qzPAaL- z?3=D~_h$~zT3F2sa@d$&`F5?Rex-Q2p7K5=Yk49I>L${lZX%^_c&-?{?@H>c`Bs;) zXvsY*@GjE8yGR4?A`QHYbddM+HHykRt%vJ85UJdgY0)=wha}81rzp}oPo<&=WM);2 z z*Iy%=TQ$1+YrfxnY#TfW8LDFF{RT@510r?(1}X7{=8YqLniH z-#4gzCco8z*|7Q51a6xqV(@^I8)gp#UL}0ML1`p;lLs7H#1PzcXQ%-x(g#79Xw9|! zvM^D>rw|Pn!9!dGL6E30G^P#|LYKwH_X{sQ#p0e|zMpPu*~FI>UXnzfXlEsWNFtEa z54hHhC^x6xt`rWke4}O51QJ4d zssY&rNe@VE!_$w|st;)xgjWhqAMl@?1*ab<5t;A+lU;E7;gtga+=Jd~!>tKCS4Gmt zGQV)dB3wy**>k$=^uw!!ivvn0rx;{v(jqdMcRs9OD!xrQu-cG(u>F{oCtF2OAvmGm z=uqG5LLDwatjA69ovqV`5gl|_ zyvy?gZLS^$Y-@)C@*xey^OCFpKi*{B0{ldi<)h@`iof^F!KWYie7WjMu)x=ts0Cc5qAGq`A4!V9Yo;jD+T`hW>HvI* zi8{b%sHk#6>jkFR0>02h9pI{GR30=yZJnrB*;xXqN!$}3SA%aQLqCeXp&62!aNnTX zza4CKy;_mgoW|zz(Udhk;(oK5BEL@CP$PewcImcyMed{Y{vOa+wBNkPW$sk$y{Xtc zQ}G~Q54CPN)Tb4E@ML?{rXo^DA4c#%aJkk6)nG9gRpM8wYX4E5o_U1Lh(*2a6*D5D z!xXp}d9rB9VG1ogNSxk*h&+Fg4fGHRy*v+ku1f0ZDyi>_PrBqcIO`&ZGBaI zO|7yg4^dgqFX_nBSCG0$NgW@RuJ=+&eL;?Nd5D(WoB}^04g82S@DtqL@bdxnSNWlJ zPm;<_kJh$2Lgl6h+*d_nE{e1cPKrSKrBWoHKTk2I#i$oQr1*I4qAE;Ud#h9wfvuz{ z0nw`UL{OpNCca#0FbpOGFTEpq3=T)$>H1R+E3V;iges74{WTINgZgW}hwHET@#Ota zKf&-OTHZ-e0Y(db8*|fH_l;XRe&Brb9x7d*Kqd9{AqU2|X#I6ZJjpPi2aau@UoeV) zsDtl%y~@K8@BwM&1t$x+VfIYmRl;W+lx|Mzi99&aB8K3mc!L_CBHa>%iPmgeZ?Z5^ z!KV-n7s2f=f*?p#;;}>MLBH_Qqb%+TdhvJs|a{NLoBF`lvPt?cc5vZU!by$N(^3pF zrDzeE%oiV4FopI|4y-mLA8cDzo^1A`LU2OA(V;%eg*se)@maJaLL5tt*lu@Fynf06+As`ZGSQ zPpMQkOTf>Yr~`cNv+K6B4p6Ds0;x%SKJaoicw;j3g*#dUCpY2#fNFneu+>_%`ifr5 zrI8eG)O2tSyvdUVEn*06^Dk2aRHR#i zFwr`}^2@?R1)oARTm+LYf*?p#;;}>MLBH_Q`z`JX7RACA#fc{?WLO6gtW^StBs)37 zfNM@#@kB~%GxN{};sx2={7gSXGgG!#E#ox3*!F zts9zb~i{iCOR)Fs?S+@Y+WwOZ;aBoSqYo6K2zdwS{E7eYZfC+e~ ziu#8L?H;W^Bt_uN=ddg9E7E$PN`(=)Lo?sq0g-+L+fajN-{vIT9wE5<=)ENF%QjGDhC9?%7qn)$Zu7y%&f9s2U?&$u#%so zKK?)S=c;`I_1ApN0nf^5c1 zVx+Z~P3itUgch}t6&=^7PEn-w5tWJ}@Jmw^zpbq+rbuc1CYb~OFh!A8M>|9O0Bh9^ zY7yLvUZxxv2BVRePEl28YUSGiZ0OcB2hWcy1zv{2~ao~N_W)svR@{B=B zbad)co0jyHSkX-scjLILAx#OOucY2XCG`nZQeO;mV0enw-^gI~`31xB;X2^w*<5G> zpOfZ7u=malv%RWU3HRP8?VP;HhL#pF1Ut9Ks{ty~EkT%Q?QQvGVWNUhAsQ}%-CYDh zkf_9ChtPw5;iZEu?g>_-C)jEsu` zhCz6xV0(%GR#`dH?dUs5Wm@A;fAdocGZ z;o^YOTT=`&HE9u<%sU@eFcsgR99V5gKG=T1%9E`ks1TgcZ*-{da-j~FAXe;-Bm%il z(IRbGYw}`cA6?*n$-YRqg3TRTY^W-aw6G0Ux7~HxFrtI*iZ^tApq-&aAJuFB!5sX# zBrCwTn5noNF4O7RxYOMKu*nrw0eJb%BW z2j0nKlOy1TCd&^FsLA&=FIiB5zcNt^_!|{fA4s6}c#T_jV!$V|G_@OC^w7#7bftOEFq;+Fb1kz8H zYg+V_R3AvERf>a#GJPcn8bCPvhV33LXhjiN_t4IsoFAYie~exSeYwNyJ)rt>hY#4R z1z*BANj=fMvdFLK{Xt7e9;MJ{Pzt@rQ**lIMz@Vl39($>qcK;7QX^o^?ebpWc6nAe z?^e2$93TyPSwuemO*EPmg52fv5Q1AjmWAch1QJ5IKY{E?Ne{@_i1#t74{5xQaZ15H zVq^V(M|<|SdJX-1rRYOKUMCoo=jr&P59L94{*?oMv)Jp(>6q_SmI3Gjl@oRMbCO=m z<736|OR@s|0h4tL@W)J+e>3o$L#n&Rxq9vMgU?U00{m5zbqnwXCd>JG?ZTQ4_|haR zz?Ye_BrqUmabR=RVA~owc&8*Q zz&o3)TY&d4SsobtyQ_`_2E;55Y>^r)u91WHOR@sI(q!ENe1ysJz~FDGjsylg+(a!P zOmVC$)BtVS)BvY9JWdUd*K2=RfZv*A1^6>2>lWZIm@H2c{*zTlk_3L*L@nUwP1FHG z9_M|A8bBa<10fKP!0EY;(Pi(owdD`ICdmr$J5AOtz%0N0GWyjU{(n_F2@Hr?oFrOr zPlle`tITX1J=g18ptZVCul*Ro7bjT(zRP6Y0(`g0^8Dccsp?36z~7sw1%xS18N+MM z-%$-PvB*1_E5NYLY@C!mE_*JC%a`V7>W1KEHIAI$qXG9E*%EiQpP%j7Fuu)_%tE;4 zqH6KIR&p#=@qz!zyn#pVd!dP_&E%-&z zm+W^+3#aV$MtU@0l{${}Xh2%kaim8ZC#AA?10z+CE%)I)8c)$YW;IS)-lMUnCD#Tf z52827!zO0eAu{ZxbWhh;p$Z1kJXP7nh?+o%$_+78&rEti*u#zU4vs(ExO$~vcRaP;^JpLoHHQgo7D`=cMcHpvR`k4)Arz*m}Vas<5Dg%xl3kp|WOv|gpZfLEBP z1%$C0{j}f@M*l}0{p`lk7d3j`!|cY9BK1zH@xP?!-BjAXcyLmPastr!orY0P02=pL zer+I`lzM|aoNsm=Lc?CF_eXsds$c@#penZ*Q4X#e%cs6yDo3Gj2rA5H+T z6ik4P^-qE5P#G6M3KrkZMs?;k_1d2R;1?!Y0e+{+WM`rHM3YU9fG;#zzWn3!)v6=? z1$>8zT0j`9_-Vl(On{dt2b|JjBRv|hmMc09NLl`A<0M@EVWbM>=%?`sjiDUXG|si; z+Q8%?SpM-aX?7hV!(K{vp1ulIF#1nZl@A$F69`c`s-gOP(gVUCj{egfe>nQRQZV{A z);|TJKV?t=DOf!E3!U3r*m6BN0^Tag3h)Y(bqnyJCYu}qzsqF#=*Q=7sw4dcTyCNk z5XLHgTJQ&>|B1>0XSMv(g0@=FX+g{KPa8M!@((A4C?^1o)fz@Q0cgD5@@oTe5ib9D zc$(RD2n~Cw-W&B*sDcUbDplzkQ4wONZqTMzb2Lb73|7b9tzoyXhX7 zZQy4#mJg*jyK&N2*9>DlNKqfZle7D*m<2wFF;h%IR4DA<>^V2k@m}=oX z9#+ruZ)_0v7f+asCl8YIDl*dNX2YL~+yzo7l+W&{<#mInp zk;`QY+!tZ0UWI}Wj%>6j=gtn#f-U97Sp`IaXb5h3`Z^{nen1t7hBeKj$fkL4D<4jj za}RUx3vP#j$a9DDEfnUKEAt}HY6QaEGI*yxR~m|G2&LifV)+E*+1^Ly+nY63KXT6M zkvZEe+&UX{UU!Hdxu5BR{cgN5_Myg`^U1$&?AP1L@>u)#jlCaEWjh%D!-+gwxI%?O zZyBrx;a+%HJ{FS7d->lt_NhD`{U4ea!*3P-zOgTd zL9ovbM1I5sD#Py1?}KR`#ossfQj@=L?ES!)+77lcQxzJGzt+Znoxaz0xnBDld+<+^ ztN?%PlJt2U@W)LyIRf71+ey#oiqAhPzmx}fwo=K12@uBW!Gsq4!4u3aN(-mFW%Z** zj~2AE8>>Z13)*TAv#duOHd`n?^{V{=t&5X2@a8Fs zv~D%UHt!hRzJa>vBtxHXDIq;S#inM-f zif!OsQxs`EM2DB`vw*3qqBlS2sySA!&dZgV*ku@gP(=hDOx&)j{6D>xTNiH^?q{$( zUM*#x4J3qee-7D)lOB+`!hQTPst;)xgjWhS`}j}Jf)g2(h)j5Z$u9WXq*n_3(?!fp znS1L7&D2qwsq|*0P45t9B_*;nRQk+*RzFyW2ow4L?5s{D>(7|HWPK?mW8TVy12So= zWrh~>R+bqcleSW%#k?JQ3ezu-NK=?l@FepUTKYJc!dK`-A(C>Uc)M`+VEMB&HGzas zPEE+Rv}LLZB(87@U#Yy1hCz6xUWOwfj#i7*k0Y6o zBBck2x03n^`MAGN$bLz5gP=o%p)b?NS5ZWRN;p5w9kvzh8f2nuuiOi4cxUe|{6GnQ zr`K|Xdb@DgVtI{)&;$}fIVT|7!GdT4i7T8tS12!}VGv#^m^=7S&Vt(?N<=0+z+@NP z{=8D)pDtq7$uYsg0aI|HO+h-dRHknTvJ?^)i+(BebF~!usagvC7%PQ-lr7LM_{-io zNso=~dbhdMp;Dv}Y=SLK+6)m4aD;|Ku!~l_(LJ@Bout zFe|-M;GZt4&C2-$X65{7R?hD+Y#EI*gXZ@bjC6Y`^n7I;1{Ki^DzZJK%!?x1LY6{*V_K@i zJS!)>z~O~9NLxTQoTcdyQB10Wl+*??#^V<@ntv0_SJcV|nyO<4VhJIgo;tdNejA&+=37w6?WEEC=pAMUmDL zQ)~l|n4(DQ=%fhz!W2bXUrLI=8>T4I`bAO%ZmQj0ZIWnhuTohpf%{BRr1d;gYy(H9 zDAIbVDJ};xA}ZH|y6Pb7mCn~Rd}5brb+3vDJeXBxICv=D~k^j%m>Qu7+(Rp67zLb(NZ~ux@n0|R_n!-fI zVj=U@F9*RCezGneEGFed@pj?t!E!HKewsi+D5oZ5FHd?v#$GsucU65z!yvp;FoibO zKc%(FRvvp>Ys%DH5=}ihB+tiD|LEM0qw46K9w6RI>eueW|2`r6B^h{6^;MKPI;e!l zq`AYkf?b15l-FqopP<)Z?(Cv39iZ28gnGMh*kZZR$eTbyDCY!ZtCJp(xWc*fWYvc> z48kh~a|i#)S#bM9iO7TpnCybvpH~X}(?!fWIU!isqru&-y8A7(DM)9Q%JdCEmO{c} z(JzI5u9iYSRZF2CW2MlKvg7_oCMxN%v90C>E%vtZhAxmgREiXW?QSKd^(7m1Z6Fn^ z6n)7msjrz#L0_?8R#LAwr&;-K^^bFzg5F~=E6-FbLM_L>w+kl(mLIpgn?OP+XB%X{ zO?tq4RTR$359o`KhCz6xU{>HiISXbbN<=0+z+@N9O0N|7r;C_~GXCW}Ta%kQE9XbE za(<6t%V;ba7>sm#DfEM>6#C&*1>k1jNqKz$h-Yy)xSpKsz$lw7ILOC-adu!4IQi*T|jj2AQVGv#^7{T~Y&Vm_)5|IfHFxdq& z$SVc@=^`eL4B%qG3@V}-RAhU|k|CHELhJsWrNiS-HcZBuv)no5sNByx5qb9DKppNc z8g~osO|7f5LvO6^$*odEtvsSu9#O_kB$b!2MXOc?a%?Su!2sesL1Hq0)ees+98$J04WRNr)vO zlxOEy;xRl>$8w6#L4i%7_e!{%Hc*tNjj5$2LMfQibnQ@6+DD4<&$JJxJ5cw!!2*7@ z(hNiAbpyKVl#bK}9!UGN8e`SL_YA%E57fc4ldJ&0+hpAWe1^#;N5C%}AAF#W&*!L} z?0tdnQBnW&yxpVqwWJ9A(-cKo4^*$h2z<1PX3H71fVNoO>c z0x79@0A82k_>DrG1aVMU>N8y&=u&w}9!TZI1Mq29@ukmIh?5|W6{_+Iz4j+6_=qGc zz*m~ATY!ITvdIzff151-<4^c}t?EcVz!Och6bMs1r_j2<46|{D%Gsu}^fL;-Xrd-C z5iRvY@fy{>RlWZYnJoV!TkzkmI#L%PW^oZ36S~^!wOnl#&q=ZZ zyp74a1^6*0%L9XdOVyFUfSARB%~gYKYvkbFldJ&WV6tujzR_fpBj8_|EFWF?e5vZl z?;Zf5lr{E*H8kLo_3p0KzRMwdf|0d>*iE1LA~S3PiDpJ)8L-aP%=YasQjWLjwcK{m zxX2u2f7Tg0yvX7Wyxy$Ffz(5Oy6B8GJz7*;9#2nP)1yVa!GpkI$_%Zj0O7o!JX~Wr zw171a=Y%;(W_b?Tqr3s5;N1p)kuiJE>m-KsC$rq}*N1^*$*3h)-o({=~E zrOEP%3jZdmBV!+knVgxhZUKI)$@0KX)Ynd`>44WJSph!PWZeS%UX$hgXXtBZ)^xxh zOtJ#}5tDTb@JCIS^Pi)yom_=_g%7U2IdStz)*zw2WJaq-J-@0-YUro@cT^GEx>1(Odc{6|A)!C1^9fE zO^$%SW3v1%L~Kt}9a(#U?=eve*i+H0#!<_9Gzh0ZEjm3~pH0@lFPinSD|$2tva+T{ z$iasjpQkL#%s~@4rlL(6D;ujC+wHo|M^pf9u(8}#Rj{4aShc2y-RJeiQs@^+EZ?F^ zat9%Kk`ob-5UTfr=Jsf(OtYW#Yb!AhW;XV+@)BWR=BfHJAFSu91q+pkJd=n#5p^Oc z`SB#OPDEolQT8iLN4xCg$>P5j=wlV;-&CFYYd#=&j#b?`()mX;w#zE;TIX-LbYZQf zOK_>@vfQvbUVX|j(qTOsiK>}XWw&BVaH&%D$M(v@=4{tPKp6eJWzc7NGsCyBSY+Lz z@m>{5F@Q{KSqXr2Fk_cCV_U3&WP~bhq6|h9^>~K`D8Cv)gAn9448(ioB42LdBcTn; z%@4128r9``?Qey^-%qjv{A-hS3-E7Emfu$3zgBgm?7*L!s0F-DMRK26(W3!5S2ICGY4Gw0|%*3KT8J8xv}4%=jVjteyG3u{?}|1-%7 z@a-n+7T~)~HaP-b{UV;v@`V?lSE-$(2)x-uW57F9RMn6c{K3Kt{SS<*4ZOibEg*z_ z`gV`jPXDC$qecse$4b%H9<3#6IIGb*d4$Flbs>#0tx&0Xgf?(e3cZiLm8Pjz*=z6q zRNaSvPi5BxuX&!QIv#ls?ht1#qJPkkI(iMh5t0*)|5HXZo)cw{D*vih@7Jqj_NIlJ z8Rq+G9QD_HX7IdCc?LaU1c75h0c9_W=Tw0#aI8*Lhvnk~jW4NCR>5y7Ozh2^J$s@c z3vYH+w(z6aCFzKQ8O9`Qm#X`N)Ac4?e4R zhlYsvGDL3|#(l3^?yS|3Ltyz}J*@>cY}-IwREpk5CG|<+1P)oNyrGD^)x*>|9?P4h zw+ru}SkATZn?OP+Z{v_1mGppV4GC`Jk5GL`!yvp;a2wxP|Ezl0hdq0o26?<*`?qoM z8gW&>VivdIzf*(U22;E$MWas>RTe@=Y9Yl-ds8i({ga5trrr33g6DynW? zwDwDizz?ZtRzptQXb?|jO>2%uCvJd;sHn82K^CGnD2ex25^dm`S7V!BhsuXD*niPSrouWwVxTFYt=M+U+sRY?$(SK;_S6d0jfRD7kkkyhb zD7Cz8C2s^#W8#!;2oRr@qOUw|@gWQ9;{Vje*1M{|hC|rvudUBV|F_&dcVFf?qu+dA zr{%dquQFdpdo)Nwwg#SGMD!LR2OEgnl=Xfiy3=~I1B6@V#@wt7rO*dj3Vl(3H&m$a z)L}SH&VO=5)qRKh-K%3yM$f0#^k_9~z_)?5@hFPkZ)NUt!1X3JbvsumgjSZbUY0|4 zf4fet2%@};c)Re{g5|9iLK8>`<^2t^vn=x_klL1dKE+=sFQj1*UMaZ0ZLEJvn?_x2 z4WZc8(mU_((TOL?%4IWEbqfyi(wwO#%H=-*q$P zSiI}6`N;qe`w7_z0HNkU*3$-?hF5BJKVZE#24pi;-W_P*LQc#U^>Y5~tr++T@xDbn zd4EK^s|~<0HYwCSICxm2E-65{x1~Wfs##7sc2ozIl-5q>whbhbO3?=sFCD~lf^}F2 zztGBZ@414~nJY28@_gZs@ns&cMg z`wwy8^OCFp|G;G30(_0hCP%=3Hd(g-&wdFHZ26fjaa^c&GQNSBRnJ$xSQviA4BNo( zo2Ui+p^BQtF>PTR~ z=bESmgek5WhP#@-qZ(jhkzcQ00fud+yy@lZ@4147X*YF4aPl3Rxjh~FIaeF5Ad!%PQ~C1WOFc*9I#;jd zGOPIfBrCudn5XBOYLo z$>$>zk&mmFWh4(6-Y$H4!SbUPd=p3r_hnM^*It@sR+$p^C)|I^C`ud?`jg6c}I0#7kf3wWA} zs#TWOuF5YTeFE;IqDqk#fdn6;CXUCM(>CzECK?0cxmsmuCHm~xrL7#x^g6R~R0F)) zWZj8BD}G`s*#yzIYBE3apX>O8$#Jl%;7*3Xik|mZ3cbTp=siMrn9|A;>Q!EL|9U(k zr(13b%+=yZtjl{e=BZGYA|Qn=^@2o~XN#S8E2X7skc!At1s(7}jV6U4tCP127X~c1 zvV59ALMT@!$o5ToKn72#=R4{_st;)xgjWhyC;TU8!2u6SL?%4IWEU)854>FSWc&ujSyQajyzxkOFJ*FYg5&@%iD#60n1x0_$H7L%8>@yvNR%rsbWEA|3Y~o4TJDX!HC#c|NcG_4w{vk z)De2^KNW(HO0oj{Zj;GhOHh1<$>e^i_^T%C7U2IhS^o4$9LKAU^fVB&>OSb_J%+2z zunk;mq89KyDynXJw7!xQfnPUK2Uw3Ie=J$220zeizmVV`C0PN!#$??Be3Qv0N5H=@ zS+@Y+VzRuD#PMs@kwOA7iwo%uW$Z8PdDH6gTK*iK`**8)yR8-(_>Lqiz&pM?ZKuEs zOg1?Jex}LtPlw|3L8>E}0(US`3pigzRr0jp4|Y>IeH(hLt5HO2p*d{>p_h})!(7E0 zGgTc@2_GiRf~dSz*-PF|PB-%|!Vk(-@IETEw$bS1CNko67U^q?O=ofhynm7v;OCo6 zzJsB7smbyo4FA5WBb5O*RU~OI>(PKK9@nrvCz&qn(SSm3TtL_c4R!bkNkW<5qXCJ8 z44lfBf46Cc#&xJ(`wIv76-icrSDLI_fY+ETuO|HetU3}JaJ7ocYSMr!uBK-zv-f=B z!n0M?9GpEA!nd$T0}>GyJsQL}sDFr%8p^p`_2Kq~@wwb_T7=_kH3YvQ$qMiXOx7*H zXPazt1bq7|(h}!q5I#>;J1H3O3=@q3Kd7RrM`)d6iX9*>gQL3KV;heURto~HPZ)h0 zc!h~tz_T>T%9hqQR4VHikkBecUytu8GX%0#8SQz~Qs^xSkJ@OwK;tNdG?EWF zzQf1mbKLCoRt-5u)ik9w8kyPv&4kMCMaFs9e~Yd(RS98do&u28$J^eWG#Kq&ia zm*~sH8y(|4D5J_woVHaJsKYuhP^JC#8h(!prDv(q%*Lwh=J67JEp>x*H5sIe2Pbwf zSIbi@1Ua#zaheKcAqUnx92j}XPwemjgG@^wnTUK3{%e+zJb`$-aPyDl+bsAdkPynH z53*k*Jz%O>@C5Qk)rT|;!Yc(&ARFtS9$=OQ>ylTIag}dfn4QECj?l&{tMztd)5`YMgP(E{G6qDqn0 zFOwqhH&Ya8{Vpj2AE-%GjI>BC*k|UMwaJXYtEHUQLd&-e{F=ov1|*ltme#M6B9L4v zMOrD~>~wOO`aj0v7zchrMdh%0mijtfuch#l+904(NCW5cF*9Gda3B&1ZtI`G_TKBS z5d{9~uX)Gy*Zg|q{r5ku?fv#;-d|tl{Y0PiUZdrFhhC#cgp>6(Y9NI=(1LhrD*b^y z8m~~HEa1Skbv+uVBt2lQD-X1+&aWH$w90UN-H7=#ja?=)Fr{(qVV1@b=0Sush)Ilr zDLm1m=!7SFd2piVgF9B8B{I3mc(QPP$MOU#+$fL;%bN_1oX`(s+v+#Z-s*l=Wf zw=(F+fw>lpLlOCIJwUrPg&?Ca&s>CqEMI5?sR<;6av(wWV7+0x?7Ysx>NjSXqTS-_iFis6zqXL8oSsyYXfUZ9oP$!%AW`D z0E5g3Zx>9GLR}|+G9SEMI6kp_j0N8W5<)rnAv-ha0U2!JBzd^%LmCF*m4Zov|Ku!~ z@hB0Q@Bout@X+Fw0{`FDJlLUygU^roP-(6%GuzrGUw(a2@eWB=fS+ZuZUJ6mvdIzf zOHI}-z^^n}en>|gyQz*0E8t=iwSdo7QMFdkdP!0QzQRNuAW_8Y%t|#lLa*i9L5g3O zWCeJQ$+`vj1e4`?o~W;#RMP>Ul4J$=RFlbHJXCzT$p-VkTXm$4!1t?2X2vl+8gRwc zAX>EhpLhUcIjjF6HNP~S@&DO-_W(JoBJaPGKxiUp16~kVHe7VWWfcS@!iuN}qAO0* z-2&^(1YAX2P=bLO)MO?o0)iqKR^zonP{9izf<|4rhzbg7@EQ~~tjI-C!DSVdm0vyQ z)aRUM>QpC_psVlieffi~Q%_yKRi{p!^F00ZM15UQg9`nz%xgh^^Z0y^3B5A$Nh`cB}uw}6H z8!;89=x3D*=umNoyEGS*y5TM+81dM(Zb81g-3=(89-!Sqt*(%93N!$$cC@ zUh^xMApcHTL5{&1TwbGgS0dwml5`zmW%n1CtF=ev?^QW%NeUx;dcG3 zashou=Cz80cLx zuLa#bF}Dur!xL}334QE%mK)@A-<0JZHt1WUGWOWCGYBwaVB!Z}t0ue70W$;EW@1OswV z2||;EV37eCsRT(0>!IS26QT~v3|JDCpfk-k7ypI~(~MX7+VE4W^p8kc@AYe-z+wHG zbzHwTXcp$Cn(9C@3G!EsmQMB=F$?m?1n!&YGdeoeUk8$iqM(f>a%~imYw<^}MLtUr zQ!^6fr4yPtJL&ancAo3kEXw*dJH_>DgRqfG+5RAb8?$PG#!xN9$hF`i*TV9Xb&w|O z2>q0Wb>qY*b&^2gQeN)vR#W!mW_k-LlO8IfyK zd!OQ{IbZ3uh-)XTZwc?()R1ubdvyXzrW*wIP8JzE!~3Qxb?aB)HsfANEwc7QS$5rWl+TvkKd{msR$Ke_1rQ+b5`=#h6F;WL5y9PzGpOzc2rJqM%}a{Mzz?KD-Rkd%$oYE_jgP^;B*a;-AG z@@ULfi1R>r^K~vv?1yr*9^4wl$JQyZ-f22#SLmlSM@+pit)ij^-=WegnDK_pkkxai zAI*O9*M%z91@S|P_jQ$&fa z>BL8;VlJg+$~lm^p-dtdT*qo&BiC-MJFIgt;ycuxbsd=2vs=(Mef^VKDl42j z8PLgOa#l>(x(ZCD5%+;<>u2vrRzHr9Yl~AbKK9S00^p@->U!3cQz}QQbS`08>Q>L4 zB{W~1{Iwy05J~`JhvZU$%xQG`#L;ROqb>+5ffJX~Px<&!!2;St$1^ARbIQ zE4`%+^U3<@7vVy^dV+pd-y%Stn0YPeRf#v&g1$BJ#+%S{P9FR%0zS`BJt=9(?C)Ow=cq&`nJ|jFh)Al~K(bvye zjiF^t23IDg{7#SoMmLb(N-S#<*M^$i@Iyfc8zp9MS+l7Fz(jppX&+OUc#+=?KIxPJ ze-aGYTU5s>Z$N)Li3~$hEAc@EBm7Ej$}OQqXXn;=_lsF22LcL`bT|!j=})4ov-Gnn zdg!w=uLXT$;*GVSS0Orr$4vKWgxYrTQuU z#MWJd^Mkfi>S!V2{Zb7XBCQ3D+L}?nKvBV5KtRy5G#UP<4*M%57z0Mq@ ziFw&@A#*Z|e+di`Tu29od}{J0uR2<9=m1yi#4Ate*s7BtL%uT+ua^iw)JhHlF&3_YA#fZQns zQ#_5u&|Rt(?oiMJlY85OCJ<&dq*~F$V_-JSe`rqeX=EA*O)+nUrsb}s(SvD5<4|jd zDdJc$@Psi)@y)B_l{LMQiW6j=gV`x+=1l!`+AtzmS(8UA>v+8HXA$`Q`dJ+Xp&!V+ z7WAHXMfvK82R%RW#+%SDzB|iBD*qp!yWSaj0t@mV)s!4{A@@>NwQ=8J7iB;iqG+C*NWDo8ifwd1H2@M>`ndUGvONk(N;i=|_%eI3yaB(*lXu^- zKWG|RN&{CFPVp#$c*s!{zbM&9(XZ7!v9VHR!9)IqJU+63D2}SWtfh))bK@O_NzU$h z@~kPDVr$81_&v=sT_>z~OwmjN)0Sso;(;C!m~LyZ)q~^16~Juy3rGv)pR#5As#Lr~ zz_rYclvyVz!qx8GN?R zv{-`r+I&c=@jzg5i)BsKCgkBFTvUIB43l{+w97dx((uK?c*il`D2;bYYDW zvqw4_sb)Kn8!9W@H#*iy(H5ykbRdZ;s8VBVK=C`xA0bM!e{tWs49q#|EPIfHt@RN0 z3R?j9cu0LoOT)vG6nqc+k4ZuGuzo;hS=$&Q_uqunM$rU9Se6;mA0D>w!*?b+)TVtC=m* zTo>m;M6fcaG1#M(bv(XLJzbJLa;W)!X8m4C)~a)VhoOs-)`->ePI9GM5pgL}93g$A9nRw-2iU99UDkC!u`Lx99K+acIb${CHGkRqfgnZQ$K}N63f{+u+k}v8P z_89;;y0J?K$WKbvx{x4>_s@)aSr8ILQIHY->kvV{TZ(?;I&sUbL=OgLDwPrW{)Z)R=C zTc!vyx;+a*-l;5cb8?>nQA9U`@(w5|2uKjcdS~>7$rYxWu6o@Q5s z8IW43KS;8SzD?H^YKNExhPQUbq6c7`Sk@SrwSS)iyI()U^L?cs$h;Qx7O$HbOjOVJ zq30&vcoX{hi6{S*t=y!Ff^#th8WL^vUZC{P@RZoCE zC-KIc&D7r>{y`hC{Yr62rXg`HF!qPWq`Z)N`6Ppr)V}CK;xfn$ z$_I{Qk|6ODo`f*Kj~KhyaoTm9UOZ`?zFre}s(x)YY23t%z2M@mAbnlRm2b^vm~=~`6L6dh$#m{>9Bavio*xh;mpSFedvc0Z?`_y zpRM6ka@Kssv-$gHl_w41T_*;VMR>E7B4CmOlT;Fye0PNisgj5LTbbyEWfNqREf4#js#;IiPv`kRzR(uKd#E%sYk0O;?L(eFD6@`UX&c^URsMb?bTwO?V?>xw|hNL4tzqHh|mMSruYrMQo0o0po zE<0(i)D7*y?WES)l(tzjcd=)#?2(wui(=8-ez_=w3A$X>!Wr6h#a93QBy5FD=(a~hLzR->yM-6K}i;eMRDxw`=&^LS^KZ3-Wo1H3Esn>Q27bXM}xcqb<#MF~4;(KMc8l zVs#+#EZr4%=VmF$_a@dbWCm5dN8liMsv2y zmbN>k?M`XCgY9>xP&(_8CV6Z*w{IN=rga&Z)@fi`w}ENmQG(V-HhoM(x7KYxESs=eGv#f0lF{|M{2lS{J_vHsPfe_wvKogJd%MWNy@i_?C z6!TVSTJAoe(SynPsc|`bBP2Vot`RbeSEqNBhB~F84u)#AZ6mXWs*S~3s(6?JleYmK zsm}wC($A_#L%%%pTF^gVk{`!I|040mo6w(In&m8hd`_r+>Cuq?^M|xFEqN zV9!rrnI-{y&JqSplqf?oOF@nS^CWVR%utYHz#NGjB(oFb7?3%Uvw3^`>tl87ub*-- zg(NQd@$|JzQb7W|`eFZ)K8WXQl|(M1=cID#Kpr+lkkRQ`&;}AMmXQ<(1R`NtBv?oy zS*IByG-hCJlaXUs@5$KiFEJT^&K&Qm0Dqw!OiDxkk_02tEkE^wY-`t)%r9NS;8bNs zZAPC|uJjW~<}C^`x-Y4pyLzI}h&3kakhM}3LFV)AsY_PsjFzQ#+J*e#6hTHm$%2pv zXgifs6^o3XpZabW@?}#58L^sW$=?YWOYc&JF44NDp|KnGz!{&Lj^q}^_w10@FY8>wIwWT=wB5gxWW<5>bd7OG+&c~ zY(oM;-n(e^F?M;DgQTGbIg9KSDvwbYgcWkmWb5nyC7Rk(Q;Iu~EFoD?E8UhZjh=O~ zG*_T-8J(FbumjnjBFN~QSrBqtO^j5ASY)(IN^b|UR;nUsYb~nVtP?ez=YPBXgIWAq zz+o@8cwh0Cn5Dl~@)v3_>;(UBU#O;=ogj8XMr;Q1eK#aKK@?=fRxo8>U>!zL=9~Q? zav8Bjh$l$)hbYL1EkXn#Dd#9?E802pQvyp;*Xe-{=hDT?MPD@bk7?teYlQY`_1vC{ z=BHEZX+r`bG;EA*mpV@yk`ClH_D`r?jJhDKkki=lpPe~>R}3MLi5;Le`7hJ?0A_+wqC-Z=mDbh2tLcfBDGf zgT0pA%FYN$V&lXyBDW$4xjt!r@c)PoPj+~SqYX_fjpsPh4dfSjd2<;SOcV{_B%Fu1Q<0_9) z7lajZ+8+M1GpFq$1TwJ$nf08uYlR&D+v^k!rK##b*4pmUiS!tqMk|#l&6tU~Fr}{p zd6lxFAR|JlE%S%7E@W-xixXRM(V}gzM6zBDmN+uJ1!VS+bYHOM?=-+X-RCH~KeEjK zlRa|DEL^!R7YN>s213E(j~+^ey~n zXHMTl2xMXhGV3{g(+WBMkJc&5-KGOs>zn7eeN(zA?l(@&r31OGvZTO7kWubJ9Y|^} z3Np%V$a@qa7H!`wBUy*9ABh7@()=I+6i$~6GP>zKQ8?+5rTH(Py`}$0G)eM6U;C?e zIa2nv+~vSWla-cMR!ng^+*wx&6&HGm)pHvRntP??*MS!Ib9ARkcl10tmkw&E9Cg!OS|>+^s}m)^48Wr@!3A(_ctr$e>Z2P{0FpF z%71mkO4%21ay9{9`@iRmJZ4VWaC4KQ^|5-XZP(Pg?Ad+oFMFbM9nT?4S zH1I{tX3;VJF7^8@{S3{*$>I4$(8Ph?S&fOgeFiT~=H$mB4BnWSB5Bj}61{kwemZZ% z;t_k&HqZjTuq=3|xnPJiO8ve<-A*L;#m_v@+Bb#6ViN|O zoQ)3IczHtDh0F=+lnE-{{woa?=Nt+r*Szz)D1`7X)wSGPp=FD)n$w$Dz~E1AXUk}d z7i_Q4bY-ofQmZHje0?$}+fGp_(nC7?n$CQDu0WXLdSQOi&$=(Q(&ETkMZsQM_&S1Y zWUb<#Mp&pY*tcY+2W(=~+OIHoSBh?w*TmTorI}e%PJhGDY01zChIrS}=`?8ltklZx zM@sj_BE{{8vLVQiDr;6_$;s)x%Z<~MixJ3{vVt6gbwjaSU41g47=BR6Y^Zog-FX&- zp$n3s9)>nd$a{c%Qf85=kEAaWi-v+0h{Ej&diikU+-snTzwj#&H1X*EbOg;QKJ79> zXo`6&gu68YMQDwf-k~W%$hiYz9^J)8dAsL8G(V>k*s7N4>>XOOtB={+IDbylYB&$} zKCQ;4Z`5iyMnA7cYcb~E1Jq(HPh-#1vg58r5>X1B^V9gl!E^Pq`VkBCd70OOz9;d< zTF^gFyzwUVZg=D#Btp+mJo&dJls+=?${!?x?XzlMvIBWXVs#+#9Dk?6Xh*d#Uui(@ zo>)CdP>7T*Xh3{2dF(>sBmOZXM)zhx$Su@k6lC=Lgrf@yjwm=0yjH(a_aPC}QeO=eoYVt^#3I7N)`>_r$Qt=Gu4Q;cKke0@rO zO<1JBEfA;X$u`kNtk@-$>k=0hS*+p|vhJkUw@%g#@V8Sf9Eu?d!1YOt^rBhQIOGFQx@8gbtvWb@&bi`|4ro| z0@{7Y9cFFvu>7}GANF^3>K|Rfs$Kt;@&RhE+c~q>nW{tH5~tZ-KU(=rp1pp)rk**o z*X?}R>vm@D(o+4oer_!3&{V+sWvb>8NU~IuhDGA$REbkdHfi;1B$8>anS{k$*VW#y z^Uh?~uMLVZLz}f7|Cl?_vX6YN^pUR(^1*sv^U?=NTrFTA6_Lw`ijw6E3D_tIOiD`x zA*rG$$cQfRS8NCr5{Zz_kSq|Ku!xLFc1~{?a`L`YYBoJ`xiqzvV*h(cs~oM38z(lJ z^LK2{e{!+4Ao?hEFsG600v=|ZzxKnW`3YYKlIA2@(}0Zhs2Y;T-PbPeGs>wQCAHX; zhd8#BghkQNnuKM$k+5t75|-^b!m`U_%~079Me&YPV_*E@o7o(z-*PiLByE{vD;M_} z5mpudlD>^hxFSn%8)|=zTt>TQu2>-IP1ELAS$Lt2SVhqSvEQ0y#R8)rXRcUabZ6#@ zEF+3M+O-K>taHq)O3m$Tdl-4BU$fb$Un3_6Y4r7LEeG4molwZvI8?pll9M3XNpaQ-~Az}eH3 zi_|NXJR!4yeqm+-{r1eVg(kLaG?%<7t~x4dW@GmJ>|H z11*(N@z#b-zOJyvEi8*nSQePDEG}VLSi-WXgtazMvUqQFTaa)qv?y!QMXm)HxfWyO zT9}b*k#44qm8q3r{`%?rqybgUyG2#;NF9B;;@QMiJe#(PXVX*hY;r6PN#TQw3nYoxznvBv@ZYC{>VkKw?XRR=VZpbRT%B3g(Amb2xRZ*uwj$S> zi(G5*{L-RSh+|Q>jzy=MK2};>?P3(JV^O#kBNkVvWqHO4z-v>kde)Zn)yM}`nxuzs z%B-IIb|0FbNdDT8KnSl6V(fca4w7kgUopH$t50-4x>%zDl% zhE~Y&&lFMVe$jo~l!&viX6aI?8FChu?NMvq{8(H^9iH#RDyJExO3H03+98j9d#daxGE^le3^5DcK0DEhlP`@^zi4Mb?R0xK7l< zb)puo6SZ(H(uegXbko#M+K{^_OVV|X>qNL~H&?vzVm*epc?Q|3VUS+v1nP9iM=S1{ z?zHivyK_oMfgh2Y`DsJjriAuLbO+A8O($5No2OL#I+Z6}r*4F6Ek0c>)hu3}E&ee* z&L0ylqleRj>@H+&sf(cFTDWU-Eqfc0U{+Yxma_x?Nbvw7>@!x+-F(ozH$~Kj1VY%^ zFm_M6MQuZJAL#CYKUKRJbwOAmX9rqe|7 z`|;q+?m6{qtQzXSevSQyM;-NRb{DE&vo~4wYjz=9+;XC@aD`=23d@2Mmc=A23q@EK z!JeAAGxbxx=B5N*nyTec46RD5xcJ8tFvJwhYBXO^?Dv6b!wF0RVx9xjh7_1!;X!L) zvdnW&5$}Uy1>(%c`~qRcvj8ie#aHnxyozVhRXhu>;tj&Kzs|$V#%s46Bm;iwiB}Z? z1g4E3Fl`8dX=4aX8$@8*C<1d3M9OKFgpnTMQ&5444@xR92btSPv(glE=WVd@Ra^Dp zJTukp5F{zg!q)5|szf3;Y&3W4FPmYPp0aH+m2K0hY@1MJ6E0P&Y@1YNTfm1Jz*6(O zIWsRz3pPkvsDWvL2Bw7>m=%*Mi^0o#D(UFa=~PJWSQgSyzDv1fnT24%<Ew_rZW(gLwIPG_3ySzrjj_fF$IRY-&N(x->BGEEFV2yR3mfs;AVY*aQ$n@@S3DbT z#k0XyJR54ovw>DT8)n5DgpGKrI6{z1XKZ6-xs{`F#lt2Dc^DSCV5C?12UBZNzFf5C zgk^0xUqK$KZFM@(Y*-_uuAHnSF;=>xZGRK6IC9gE(j~++-l-KJ98ekA_OwA1DW-l zhpkq~@z2-CYp%!#^}FoO8{?M{vXS!rGiB)Pt)*7_c0Fqq-OyGT2*)D6n>B=tRZvbp zJ~R(hzp}X;(`SG=nRYNvSUuSPDTo0Karctg@VqM(Hnxi;p= z9R%p_lan53a3<$x>%lovU!n$p77ngf&ppkexgtSmLjoZjl`%G!x?~$NHwEXkdYRhA zs0+dhIY(OjXJ^il8X=I09muTbfV4u6f2Qczl&4`k$IfASXO%{4`n8JYE0Vun>96?3 z_j3z>k|nF>P63*SCVy>6AcQ)=*bTW3An9xFt<}M57o#o+E9A@r{NhcR>&&eHob{j7e{HbdzRGOq>wmBbrsL9a}_ z@h0>O-VyCqKYbhIa|_jzUITeWVs#*IP*!#9>Gc_X;cV_FJCNT}R``nx3|eoGa#5Sn z`_D<*kQXZ}XfwD!%R#ozonlZ&Pts30g+V@RiXfwI7KA)@iXfxcWI@O?rwB5-APYi% zQCT4t20zGhkhj(47;LFCC!s+8qq1TW8SR+`A)h`)kP)@u98oF1?bEz>A({WGY$q5n z{qYRU=xsX5L6pITwVChs89i4K22ln8j8<*Ab`{%e62{`W^YMBKn9`+Zs3UUdG;XvO zskZ!+vdun&*C%g1NUR4rYdbk z!$ag+XgI-!Gy$vVoI#eGfI^42dT!fC^Fs-K8xja%Pr=v*DL-vU0&@4B52#&?x*)8O z)BEwCojH3CLLd`6kXg^!d#sS-|Cw)%{q5QMDc`a{UY}UQbU~V(Q{6w*glzV=3Or<~~sQl{h zWI!{S^1$c{_4=6<>?l*07e?`z`b8>@Au0D=y@j!B@#RvfIjG=mB^+UV%CBBaq{W|E zSX2F??$xOEj-AsL#h^NTlR+t)^ne9zJz$xfPA@*R&Qiajf*E8}ZDP%n+O_~l!(3az zFwm`H_x`p7HIys3IZ_lrDdhAq+BBA&rnRQ#VnQrb9#_L5QdY3E$#`Z=s553-mdfp*QNMOcFN{-zU)W-#dSqN>Avg zY+A?OqZ`@}l=tg=ZJ%H2we$71?JE5gy+_}#*KX7MueWDHCx_y6=}i-^*a4&a}7l;Sc??5Wo?b_X8^3COUr-mmaJBm4L!r@vQ|q>%T}vNdu>XdFw5i#v&@sT z5jj3qPi$HGSnc^(?fF<;9NICrotl+uZvHce>;R?q1VpELgCz+P$|e` zVngdr^%*uJ2H8}bIGGfum`K6BTAXP!f`M)o_k?rDRyK#lC-=cX7njBbnR}ARvBUxD z^t@ROk+WS@OAO&|0nAz_c}Eb0S4;-3p7~$*{1jOJP}u!m{q3 zry(7jdS~(5AqNp!Oo$j}8fu8FFCIT*`b@n(0M){ck><1hQ`FMC;=kX6WAx zR;8I~a~92|(k>^fxW8Z`?$wFOEnOK@@}T<*?%?v$s-26$63(!;a0Am;ZD87x4NSX= z_y!Qi($mWn3|prnWnBu(I&}62+~tgSN_WNIK|(8o^t4Kl#TSb5HChR>a0j>tQdx8$ zf1k={(aA-Zt9^sHm(IJeAoHUTQJn^gyVTYHBosx{l4i53I>NfJO54Tuh3)&2?H<{i zlaTkYy?bV1`Yd9;Tm)pGa)eM?IkTse!g~!00md`;#Q_NeTX#quOjhGJ8 z6d~lC1esdu+FhXt&CxGqt3O~rF+2PL`w9OK*jo+fmTk5go4!%2;TYXYjqZu@#;k1y zy|s$$wkjLGgJtj(Wr`0-Y`Wjoc2s^r(i@(yH&gqho2p`mMeDFS1O}tYR1XsC0fM#f z;zEOO(4`@Qhwsgu9{Eaj{cin~FM;J>LSyv)1gr~*`6y^TM6RuKoM1yzZ55pvUaHRV z7}mDcb8n8(jI{s&??sU}iGagT#7} zv-Vx+bJfTm$yo7H$P4rmX9K~>&cXef10AhHR6BTQ&`aKWkXR3L*yoL*z+`Zy_Hs`B zi~-}u`I0gStLFqUYP4iexNpMh1*V;EG~bmYwR+By9xwdK&TRGE)r97$$zK~12w|yW z>}~1H(1y(Ua~|F;QM(v*L0BPYN#j2|bIu+JfvoCJiZ|;yAgz$&-xiTG>GmZsM`TDF zVp~6}w+*4Ynb(58GV#V*&{rkic=3<*VgE#xkr%2VKblw_$jg)!9u+aby#Fp34n~r- zHsq%gYZS6>tNg3+N2>y!C0~#zR!g-j-v`=Na;B<&KtJUz|I23%N8q0!^Cr=S%^wum0dF~WJMxW1ukhe||Wc1rC2)U^iLyVeH zOSuv?~7C=&E72s~4Q8vH8n%_ii?2v2~ zXM%n75_K(iy5K%41z6naKBv$cF13oI8d}FEIK5JhcIIrQ2!TxOKxRE>E44z7|Gz&kF8>w!8NPUC zu)5B)T`5S?FSgYs7MQHNd+JPEpTE!q&Ql*!e2|aPwkc<_)f1&#VU})%NlO|@%YB5N z^5)F4-6J>wG3_BR=?X0Rz_elfLBrTu!-)5WjEG3yTZOCzx6%u4r5D`F6kJCmiGCOz zmg4I|l7%Q}6A`&K7qT0Zi9B~>D<>F`9+9)jaW-;NGbhb(k0}DA?6Ve`bD-W&qa&oS z)~uep0MR@s<);k^gs{3X_J%A6N$I#QGm?ggTTETkXJI*RDCxK039hMf3X%9-peM z3rSRRPdUGD;|fe0Szr<-vBg`}`F$H*5Vr9Jrj0N#3758l*+Efmo}--CXFzDOS|Dpt z&hw(2*LR|v*Y~5G=S4ZM??gGT??gGT??*YWxFMh|4y7pNn{o#1L(*Iz^OhuXb}mJZ z7@0I-0h%u6v?_~2Hlvp-pkq=!4MCD=ktz|4ln6#_#fT!H@_HB{j}(ST*_tSEj=o9p zWl*CfsL>L^Xo+C7L{PkuViCxuxN_nwgCQ_2ioh&!6w?#rn5&$g>FhY*Sf1vr2Z~G6 zollRz@!{+^Z&hh-yFy>LdTz5v^S#Mm8xja%C&Aclsh74P!R78a?@+rKbwOAmr{m*4 zJ9Bm%gg_>CAhVvc<5(fbzpW#AXmH@5Z#IxUK&N%4{4{NCDAJpR}F$Oer? zH#Yi|BTF=L?NW$b@=D=HE(?>c8o7*U7;z_ge$iv`fAKoxPu^O&{$YLF(s?a*%m0oVL?fd5pRstdP^2@SmMIy%8ahi5oYn`WbH&86B@&d6W%_`6y^TM6O*QIKhVOz*f=O zln*rlh3U0=?wq5!Ai-}#0wEM0#^$B`v>{2EyD1;8b}{OLutLtn<3Brd3J)QWi5JMoY@Flid}*1%-F&|3r3){K3oF4(MFVOgib zvMz;X9SUoZyQk%+`lY+#nQjTP<7ky2J0-|Y39@hpxS^&} zZbWq&D4wORjz}m*N{1s~R7Y5srdHZ6Zg{Z$&&hTV+c%}f+{5-wDVQF%=cJ`vY-AY9 z1uClzy7$gTEZ17 zeTRO=y^Yb`$yOH<^SXx`5B}DO6Kn|j5?WEpH>q!$DbJit7AQL-~S7hiPSv_mKc!NZPWBnyoZNLGF&_o3hsd?iaDojfG^^;WoXbo= zVLGjzJI84LM}psm1VShvj7_Bcv>{2ETWD9QU5vUQtdKL&>+Aom+C{mka?TXL(H)B? zgwDDC9F6*1{j6SofIcttTF{SsPb|yoRn|`Wazg1Z|;V{(@w_3;Eb&ei#yi@q2DY*?h5BFn?(>--aZLnT?a0(AT6SE^0z! zz4BSU8FPzj+?E`4N?1kIRx3REw|aqT^YvTxL&D`*&#FeB5hmiZp2LeR746xYTJKre zZhCF^Bs1QG-ZS%B(EGkO7a8>ai8tPa{(j<(wV+oe-gpyw?0wmujUH_KDGupDko%}9 z`Imek|4CV~7#V#p3qs;L3NiwS^KS!zf}DA zz$TFp)chPAbR)33J7yoe9jHpMvUve@+71 z!_=Oc1=Lq&mbHx`5)n=s=w(#S`4mkcgj+;34^xk`8YiCIX8;WM$b-2lKn9_m;?oMP zKZXMpH9%)Hj_LEN9JQie@AYWdPY60R6)aVmvEjX6#ZlY1v8b`fj*~6g0`7Jj6yy+v4$Wsg5peagL=kCwIrZln+j|9zI8aWv3q}S^+cX3T^n>IXQQ@0 z<-6!Z_%7PotX~^s=Z6}DclN$buTjq77JvbP#zV*aBA_5_z22o3AJR`j`0OtYc>NyP zKdu2Gb~exnud)dJFxDXz`l@F+rW_BPG!Ax0%$*#*{HFo zHQW1(c2>|cc7PgTIv)AlbkrgfE8%trg^TPf*ATAF@S5ft*{-e%FXHd2uRHX!*;usY zY{}qLiZx;-tExcjsi_YPL(W&0yoNE^XTbWEx?uTUnpGh`Raa#|GjU1^t872ANAKTf zfS(N-=UzV9r?=BGBe(39m8`AC*DEY6%Tu*$COtowWk2uI)QcbCGJ0=nh+W7UAQ5x` z33m{n(^Cq2#D`hgNv$pCncf=}4>Jb&360uGT>;Og!A8W+Ru;caz^PBv7KDMH9KUTmkfD1tx`vU(5>2 z+H%VEKNJrjLQz;fw^Gpja*C)834~CF82f3KgCyf_xn8aE7 zj%=gk+{7A!#J(&;@ZXlCM($Jcfy5euWL-KB?kxh@nbZ4>|Dl#}Qom-G33eXRTvfX^ z`YY9rx09ns1|&_b{&uSHO#KYZK_1cEShnm<9+v;MO8WCuUoJKD60E)Tl9Vwd-fD)d zPtyK@q}}lMn6!l?0YK~Gq_`lD5KxkMH!6L z($nrUI#Rj8DuX3cL>Zl37iB=2BUVOpHATTHgL;z6Z<3hBg()LL%bE=SCo$!ZyfPp$ z8^~#US(6drh9BE8*d+y2i8A`P6p&bDa9m>cmNg0ey2KPo1_T@Z+bDy7TL~G8e z+dyacKF#t>`Io?1Y+$Q+Hk;@XheY+@;uICuB&xd?7xp68THH;M)GS_`^Hj5V`4Z2f za0gi&Q_F%;EHe5~n(dcBfn=@9yUdWRR0%_zQl?a-2txXpDb}dYh+K=h4dX{T zHJEd1j7#)WvF%h7kw3y}A`gP248BtaRBV^vsLgb(b}%2S#CnKa>m+h*;_$=tN^T*U zUVo;oQ&F@Yoq59M)v2)BkZcZu^P7wN*XV@O%p%vKFU=LdleZ$$^3PZ@$j;XlmUvsa zxX5b6vtj7eF#2kN}z~e;n8TXVv}!QC+5O<8%5cCrQX3 z=8p1{#YNvK6^p+ZYenP?vb>l%gua@+$(F2m46)Nx24N0kH80Ynae3~F6URukP}r~2880j)ij zsGXKO)g`Va)*mnKB zb=I%3iE`+wU$X^|j|Om76M2(~lq0wG z5V_V#rZfb^JKRwO{E+_6(w{`H=>TpY61i1i5e-Jt@^*7m`wm zf({^2w}Aubg{eGx_{FR=KWoeBhZ`y$K!mPi_1sp3=H@A)HY5;2pTpRfvK%A}!R?2S zQhAKJAgqwn5AmO!IbU2L1TwJ$nf076F07E_pDChRWY?_SLey$U)`Fepqjh@MbMabp zOUg2?-QU-sICo^+O1@gBWlhZsSss>1TY}`diBpQ~j=Sr|Sv@+0-ZS%B(0_MHek2Gz zH}T}XZKb!pG|SnH;Bz!>)?LU46KfdqqaUq5I%IUk$0Apvg#5a);)6a$KTLvM$R~b0 z=|X-}Sy7kKy;%_Q{wact{_YdWVj?vG(c%mpZKj_B8#L7S@yO~{4%S^YWr-FMt! zR#CNwslbLh0rISVJHD~sR(a&4e(h(PA7Iq4Supruw&Z*X$!tkrkRXYHfq@B(Tt>{{ z!07}g6DER?%vQ9>hzS!xNMa)d=>FHiM1vRFyN z6Db>(uxtRrvSlVLJFV0h6DK0WAC3jR$4BC)^iSF287;Xuab=r4Ko{s(TBu{fWyB0e z3pQBciY)OyCoQhZ8zG-Eh0ExI%oPhC)6or6xHdx(14+6>7j49F4NEx9eTB?sFUr~k zUR18Vo$cBq53;_}HJgq4HF7ed5!J7e8H%BP&Bk26W+Sg(v+>uj*(}trtt}T)OzT$k z1T2a+PGQ;bgk_@=mJLQ&HU?o?=qt=LO6w@07u!v(6V27R5*Eeb3CqSKEE|llY$U?6VF=5{AS@ezuq=9ES?D|I zF84^*1AA6gtH5VjS3HZq;@JQyo{ga5*$^t;+G3DNk~o-#lo8xem&*p4HHY`YPb?JB~uZ9-U_ zYU!xLvW-(%wrdKDTrn}ivXy6X#+7BEMy^F0xfXEbTFjAaVMne-9=R5Lao*2-o6YsJ(MSKV|hmzE4?_#A_D!Z`QR) zkBQv1n=9UaupZs-&=IO(kQV4*a2n&J;;!jV8$Y`5P3b7`BT_RzZD?;Rp*<2^nNKGr z&MbrV$~>jwmuh;EPOVI-aF5f`>!xt+M1Mpr)hu3}Ej~Bv3YXDA%9ZDnkTusL=(rZ{ z+FZ+)MkJUOmbK+bZLkntP^*+K@m98yd!r&vKBY*WLJbQF)BIAgqwH z@!>x^bH49E2xMXhGV3|t_gEpvKYKz)pFxTUBu8eykCckVyEswY;?l1K?%#oA}kw% zuq<+6S-`@wI4{+CnUOZ7L#gMpQY{_|sHN#S=AnZOah{cbwfhC>j+U7XOdE7y;(=NV zOnXoXOdEP&+Ta7zh98(~!#%SxzkprwEb5A9L03GBx#C&K70)8BcouNQ8-(|BI&m`_ zuibKxOrDF4uPTC)zJFB_Rbbk%0@KD7m^QG$w2=j-4J|MS;ied8No?u)2jv);K%^i8 zbC9_!HC0V9cisjYU$s>q&S$9p#taI38)Xv!^{#B2 zWo6quE8AvT**4e8wsG8S;*jOBn^Psiv@rxp8$n=N{DEoF2d2dym=<|p4#NGe)UrC{ z{g+klCro;gppia*!E^$XOisPCKkYn!tXf5m@`zDYD!2Q|u2CVF_-~m?O{0 zsRHs7xpvkgm$b3|BG;C0%6##u_IaGkg0v z=gioq5A$hyagJPE*ofB#86pugC1jh1if5Bh@oWkzo=rf-v*A}f8+^sHp;x>?c!{x! zEd;)F#x_=#`(R>|6SkbzxwGUJD{{H3;%pnapuAb{{UVpgExf4|xfXrot__oXw{8Im z%c2pMg(57ALs%Asuq=Y>i_)*MVmh{gk80t@;KZT})V3 zYrRB@h4kyf(E{t}v3joBM?dAI)Z?D3Z{iP<-Bx91OV2)`v3=12pP<)sd<8O0WRU_H zBHODq*(HzZGst?ypQI!bL@Jb%4$2k!?aHnCDfj&Id2V4Nx3W&t;^m@e?-r zb1;%vo8-9A-Y7&FwnKoRxLVVdmCs zZl^)!tgK^>0^!Y1DU|fmpDh$C>zI2$>kV_$5UCzg7RUU{bY1*ZKb^z$9eRnQk-SCb zyn4$EUp$NwDd%-sjuLER&Kqf^yH4q@gS&6#8#71{#H|q!f6RiAo931)`z<3*anesq zv_*^kgC^%6(wpYhp9o;IPkPgQ2$C$yY~1$-8(3h17$AXZp#-L_n{@`Wui^{V7}O9h zU+f@Uz8Hk0ET}W6!Ct=DfnC<%Tt$K7`qHre>(_vR$NDwvxPHy14gbuV6wY674yQj0 z>!0wKn1qMIb0)rD4FD~iJguI497VH{;%q|#A)IwFwn2Vp1(L?;o{4{_$S~@H zutLt66#vp5p)E9CfRif9PZitWrhr`;1w#SJcCTN-G7JeNl4ulR>* z&Mf>%maLvT1!%rI`D;T0AHr~-O&28c z7r$G!>02qgEiyVR3qrnTiXfwtvLNJ{Qv?}ZlLaBKnNh9RG%8Ict+Aj-2K6i>BqfQotJWg4`GlS!^9OUU!3^JmUoaRR% zJug*F7jmVtr07>qFrav<(7LIVF4npUq71IC6;rp*==&*$VwJ&91TA{OBN`sv)hd|0JfL~_gVF7=I9=Pu+@)mo*Wa;A`f zw~Eni2|*VU^HI=xh+G>GPOu@X-zqxikLyi9p}Si>x8}Xg|4S~5RrO}=tl^KtF}SAAv>h`@+NKwn zEC$+*`v>R#RUKcUpYo6SK>jwlm4BqZbSuo#tuSeqEAnz(IYDduMx9v#6m`(j`vef( zZ73DT0!SK~tlpIqw%Cb{K%|M;Fob1;5S9%=ST+D*0iPZ(EXYk1X=u6(=W&LMc0L7cB3E@O#MYJqde`!FIP#;yEQekQvwA~!m{R_{dAT>1XtL# zte(4-p}9#4vJDA@uuo#_z$^zzpzeOUp~_>_1!0Ap{S5!vnX{iF1TwJ$nf09ec`M}j zr#R=NJ#6vGeFp5SQgV=aixoK<%=`5YME)6ullu&~JrU)y>lF3sobxO+d5*rlqI|M` z%Ibn-b%_+PGJ=s3!ARNnM#^%4^^e8zWm0HDj&3CHS!)P~tbJI)oTX58u>5RxX*@e6>yrmTM}izhAUa-s$SY zKzGo0?qxMd4XSyt!*ZLUnc6!eW=54+LpVK;g` z>_+cd&y5pK54&-~h7-J7i0?5umQG>QCoG#aVPSn;TMQ0AsE*~|M48uT@F``=p$szT zPUI}KplrbfriB-nV9gC?qFJ0UEWphL;OysbGkejV=WWoOyJK_ilea1GZr(VlVP$Nl zzhN>h(=pxqbb%$kz|r!H^6^( z=G>bg1TwJ$ne`lyR><*hpB~G-f}KsqaNkP~c3m03ln@OtVTk70VPo;&AgzAV9SLjoZb9>(s^a*(9VeX90S zmB*+H!U{PPkN@nO>M$nn3SE}+Myg;zWyWi#XrfUu=ABOHkW^A=4C zcms1MwaooTU~&`k8od~pwr1>$2vW}0t+1?9VOf{LvJQnc$lVk5t7_TJN_WM(nlbaHtTyy=EjmjOO(4jli<~Ju2IjPU z4icJT-U>|%C_-z*^e>tsgq+5})J|FT77;>+=v=j`dyUyUv}RWyv$vVQb#c(O8cx%H zff}2>QLEt?eZ3mx%@bMw?AhGMI4$9gs&%D)#=VWv3gyb5gMq|+6to`vtq~{K5cF2j z3Fy5hps)d1J$F|^lUH+O@*#l`wmgj8lGaljl9ahy;{}Qgqb>+5_3oZsS7!zYSkkcC42fQ-=rSdXMp+mLf{|=tCNE^`A>)5 zsW$K|DTPFFcJ)@`4s(kw=wVfzl_HRbJPaP4fb<}VI6mUh>o}9}n??B1bNR0_?`D+O z0rZiodX#=vlMns!%xgg(`nO+wAkJf5a7-i|UC5)8`4LDw$696dKUokG&ry(3#!)oy z)71al5{@Cre@o^U;Bkg#R&M!A+r?9We^;A7O}2+2?@6p7$loQ_Fyt1BV5a;Fx___q zi)*|yl|H-1Tdwpk^;7Eh0VRPf?>9isNu{z|A3A5N*tCd<`j8jwntcW&sajFJ9h!Z{ zsYWW{G*HI~0|@8AvTaJZ|8z>#;RmaocAA;uHmuZYms-V_mZjF=xV<&G@02+!+@tlK ztObc7=~nW3j79)9>E8r(R1OaESY-uO1|&~ZZR&1N@7d+piwl=>XaC~<;c6LU!dx*q z$lS^lR1f@nB(Ob9jbs*3&&e!n8$%=_oFvf8sGMT~nm`EmcxWzFkFy#lp4?{u4EIQb zxhX&fp`GH>3avke;}tbPXEctm#_1_^jjCHfADp^C2a*ONl{49A(8+SvJf>(y(omkN z(t9MWA;<$0t7sl{D>{@Mz94^~TA|h$kbdWohAFS{eLo@S&{VKgWyXegql%-pabr10G_DL=spz{ZO9E3 za1>-j7)}Et!`GxJx{!ZTmQ>I3Nd_Q~Cjmy^PN2^{W0Ju=%8a6no~a0{e=vEH!Lw_y zyM0E$4x%>wUsiNKO2CI8H%{pv1>n|+H3Ydq%HAjm#i4Vs+C~k`%Z5(Z$@@f_#Ny8P zRFz()pUuXi*6c;i*-t6fiz^U4Zy7D=ceESk}#bttUTU8i(c z98nkijf4%3e^oqky97xlB&o~2^e>;Z*$9$0AAxBz5}0-hUj8?dlj9Tz35YGqRzu|4 z6htmL*jY<4av41(E%h!WwHgI&wj$T23z)AWam`l_Z_5;(F(M1|ij&XrCCLQ!G#+0zE zp)aeUAM2;QFnH{V`tsrqsy<&o>(|axUf;QPiSn*=t_|}4b@k7S<@nx3ZNRts=+zQ| zN}k3Ape3hHA~1A|0ts)EGq_usQl(gbssamg44$J*kt#I$?lD?(hIcaH;DXS?{Z6k4J|0K_!4b~AVXR3TyQQa0=Q|GBawg`Ej zeu#Jb2g&lhL|P>z>hXzq`Bm7Z>gIC&tZuxazpgyF-(9U_BQ?w77WgU^`Ko>j;1>=8 zY-OF^4hS9$g=WTp=;SHUF~w6N9{$@bVUe(ET?y9r6??7o!6NdSmUV!YAF7p&r2o!d zB7f}@#!vKu^fRjqI3inzDg2pQWvV6dok595c0Jq-=@GH5pVh-i=x*ksb);7gGco{U!@SKI)4xz8DOnCn{I+ z2)WA?K}Ju@f{+JH5oB~w7KHrgDT0iy%Yu;KnLxNRj7rdYi0T#^PLhpA&nh~1xObU=!hNLGb8jxud;klLHY5+;KjX`ni~ujo60#P@N-vI;UK}gEI98@OUabhDb4Dkm zP`Z!=90hI6k!!46nb?8Mdd^a|LXLl?h_aJi%Pt;a*`*^a77iP> zupn8&agzrj+p7pdvbRP-Myw|hv>O6wKdgl%2lCze3@%O8)`cXhAZOzWOdDBX+Smfq zMi-CxyY+2+LD)u!u#GVY4~p`mIm)?x281T71+o_9+`bd#+`bd#+`bd#+`b>>TrbMG zeLu>%eJ9HDu8)SdIz=ge42J=mi8L3;yswCyjZ)-njKU&93ess+7KJ>5eLw*{nCfW= zl1z(KiD0BeFj68IpphjD|y=4TWC4$is!D#8O_#wJ=CmWe;J;q^V>WQ9P zj=;1|1G98n+^pl_N$N=|nvf1mcMd&k-Pt8}EKo@gwR&!YMsttkuMG)=(ETxXZI*-N z7RcQtc2;?ex*)8O)1~pBojJP%LLd`6kXg^!C9II+-&Tm+-XA#V_8!^q=<=D_SXBIj zU&yRh8L^lCXawazrPr_7s;XbJT@*Xd(DIrdj^Dg$QoqG`o>>6$Ek?Rl;>g!54%<E|kU$8_9b>mh5>Z;RdI z7S)=mBJt*g(d?wyg~WUmv>qbYt`D4GLpC3)=r`0QrLe3+VGVM3z4l+Z zYbxCpH&P`?PpbskDM5BhkcB(ItG$Ic@Nt^$}DU*(;iZ6WEjc?Dyt2>T#L>UL=y<% zX9H;BF)(dep*h9pAfYMdtq|_k2o#|;V)~tC4I!s7Ftt-wy+wr3Z*{KZ_u{MK@5SZA z{k^!=aGL&a)Y$ZmS`EkO_SeM6_ebletbZPb@l42R2|KIwuztq9jnR?GRu>ZUQP6tu zw?>>`L(p4AC!pu5b3BF($m+Sf5}HE^ej5@9VavnV>(hE_Ly|IgYdl!(V$=m;g`5h+ ze|F}qON2lsb|AB!vo%^F$N$Y5#}87TirVmLB&P?JzJ98=tA&`k3$gJm7k`;3N^PMfd+37U)n^0$C+)cB$yM9(**+cJ{c`fM6 z5^t;peR<-QzZb{;3spv%4&=uZs{@Ip_{7<64A?p}DRv=Wk{~SF61r}zTf97jv42X& z+K`tf)-Ytf?WTCsQ2tr ze&KCh$_@I9`xmHXj0tnaq;36}+cE{!!`R{kwuh+?XBJRz%`9shLnI;`2++%@oZTHw zAcR{rG{34I!_U4M0K+|*U~USKL1?G=v_k8TVTGawsPnULItjg^TEWn7N%PZzq-{v$ zO!gTp%W@Vwrf5NOt~p+%7bUGB$kP(5Xc_b<`jVWXAh%0%BelkW^gCxQOnL2Y+f-Q{ zueaIoS}Km3{_MLUKl_HYr;6y$zN<^t%6%$wzkXK7Hs}X3uLb?mujCCJ`pCo^Z$ken z@y1%v_a)wV6Z%ItW_yFM%~n0x=pheHtPbR`vf}>D=x13F^4C)Y8BHn>>0XfMDJxoJ z1Y+m41(NybrX7)Np<)ZY9GZL$yAjpVC(#KccMg>uv^r%5spiG_6670h1&4 zs5NHBxh12DScJ0M?cZlWe&siY^145UPfn9ramy+8ej2d9W)aKskVt+7&Zy=`ez1+7 z*JMA!W%OF*$_wd`H9#Wh0CIi>4xksM>Fwbcv(hK5En(RrI70CNBJ9>y&%LKd^JOWb zHY51TwJ$nf06p3s%VSKUWK%WhPGz zAeplG6DEz9Y7a~X*QMl*fG78Z;$CQ;y2O6`kuA&VGiobx8GSx^=tAN&3R=IBYwHQu zd!^;xBL>V$6lWrkDvwbYgcWiM zV}1RTT4qOx{Y$XWY=X{R0!`)3bx`wTEEGYwhu zAaC4hQi(u3lrPb-Zca{cN8YOBIf*p{xoeu&k^PlCAhCuZK_Sc1VsM`CSp@Z0gEmp) z_^n^Fxx&tI3cGsxg#KK$<2{i=FK3{0uA2CG%0O}VXtip;s6zW)s$KgX7OW2^!)-`> z)ePAP%j2WBu`bg6i{pyqY~XM1kmZ!)<>zd*caDBmCl%;R(_T6J6(#S=EQ|l&_0mW6 zQ;-e(aUHUksH}$!?_X9K`KekX{8Y_4wt}9qo76}xZ3BORhU`z)01gZ@l&J21pf}09 z7W7=bSUu>3o|kyzP3U(d-dGEIS>la1q2Hf)<%3SJZL5TI5J>Lhq`5+3Dc-H1%jXl6 z*df^})(RpRlzCrz^^QTl5AV*TJ`CB=2&z7>sso zP7XVec&UElqz1CX4h~nkejHQG;GMtl@;rN5%!()#%I+mHmlA7{e$GP z19_LSWS^SsGx)D8XS2AQ;(2;4Lg;5?UJH7k#2aft@0WOGcJ|k6&#TEmzbNxs(4E8^ zYe65Lc;ijzMTs}of<7_vN*qh|+9@>|=uCthiPH@&ud zO$Peunb(5eJMqR^(DM_ow7afw>-pv?K<@%*@3(-u{w}{P*#kS(eCO~Ztfsws>>+IXfNf8 zAY^-rAfwSN2uToriXW{I9+#jLbG4mb+9iuX{wT3V$Qh7j=e7u(yD!52dNTC?k@x2D zR#w#?|6x!sruLBYj6<542Iiat=A4Q5a?e##Cd-o43LMVWM8u&SQxJ0214fFb1(}Ls zg=T4k1!Xxas5zTpIGg_VInU?4_QT%$aIReX{(i65&p%wB{dv~jo5 z$3oFf-fj~3vI(^UA2(`ftUWZ=jy@-$xOpbj3VhV4b|5(tf2#gBt%A2~feZ(-Tiu)*-^}%9DeC+?2iXwUbMwAwVnZF~V)nTQy0xuI) z|0y0CRFp^4VyVJVP=+vV$I29tIJVnQ)lA5JV%uvRA0lPRGplxY7k4VcI14YI}r1I?m)`-xg+j# z^w9%Cbg;h6i1Sq?)(nx9(5p1&n8ixeWa7ig~fMCvb3SB{+BMCOpu%_=bg?TT07qV8FMGY6re2N;fQO zp`Umgy^UO+mUVAgUewN7MeK_zuXrq+g;1w=Y31HMB88l77VAD<3{xjQacl`H|2P?m z-B=o{m&TOxe`)v&o1ZkJ_lldYxY_De4l>+pl}?)8n}3nG;1_lWapDRy#wfdqh5@NeH_^hbCY~^;gfDiOs2L42!Ja6qx z0IyHm>IggRP8&}|IMwNjpOUa$aK$7Gq2Q5-2&UZ2%>g9ngCO-^_U`@VU zrRC+LPX|wt>}1*6n=bGpma_e2!DscVz%3rcKW$Y+i|2TGUu99z69W0C$)&#U)40>e z0V%-U?A|?=#%smku&(3{3u$}%;(;uU+EP8ON()tYb2#U;#K1;&si>Y%z)%$rHPHL=^;U*DAc5Mmnsin~& z>vrf;#;bcvf!99rYAKC#yYZ%*^{B#>btLiIfdrGH_#uI15V%Y-bU%GD3cV8Jh>Jh9 zI)GmLw6l9gT@BYmdO+~Xbbh#hxv58$#>RHil!1QcoL|^!#Bf^L0QHyl0NL8@4S0Lc zW#E~{RWk4_<2qZwzcsFsf$uZU-3A5!QOB3$<2HKW&x~pZ{z6o~tJ9j}9f73G9fO=D zlI~}LW#9~>h5|{G@Ab6q^^U+|()f=xu2jJFvb7&V?(@;MRRoEK4~rhBxHBzrw8`(^ z+-0s@=E>G?YlR>3Tn4VLoYzsin1iPn*VzK@@d@u|*tpJ?p2D5_G_$4`_K@0oOW&;p z;MGPA1ClwPVp_j6#}43!Mhyc}O&&{&+7d6pDDA%*BDXyOcQ*NDx#SBT~`>FycHvI zecw$WCDdO`A@*e}q76u0$ro5_NEgv$5usDg5fH)sZP!` zca8uH^$v{c%}+WCCaa5%b4K5NCgotnugGIm^d(k&$I)7e{&b2~WJTVj zug`lJms|`)o@M#kfRs>QX^0(Tr$rl(x{@n$taK4g77;onHn?TY&(N}L+?Cc{wP_Wu zv{O#EeULeDn~h^xJ5-Rf;f8kp@>sDXcFR4?ns~}1*!hx^q7WLT4{XOMIeO%@S4B~}mleX_)Uh7*-J9iWd(>}R1< zB0rbYC)J<&Winhs9AsZjFSOM(gj?89Mi)8`?ID+BwuM?X+|jv5{hi|%0-;y!4PaO| zK8tM~M$dS6>d;bL#;e#fWNXiO;IloKfu|Z*$-vW%>udopFs_n;pD`|ewx^COat7PBlSINLf7#9x=`SiWe z`WFYm`k=PPW#9n{s7(-fXX83sz?_OTKQK=(wLXwHw5yA7?+k#1<%=^6SVP2?7TCI- z;C`MGGBZ->NZDFR;G;d4floB9l7Yt?*VzL8fpL`#e4%l1w@2#O@v?4R0>39JUt6@! z_KraG(~EGV0+4kB3q&&?SX#(BM_@5S{I0J5lld1phsxH*5HcV z{?77oV+15D-SsfAeyI;b^IuLb8&toeHucnULTflD^7r#3t=VkJ7!w&qLQSCq!^F>Ar{lpD&C|{o+68y>%bO1@@ zzNw#8X^@BYNt?WN=Wwxut#XY#Dh5xBjm z+>zEf|1wA5U7~VFS`T?g;DRL_X+7s14L+YI$rXFhl65uq7VO8N`t2aC&w5ATPD?n_ z`igf19=n7it#RHFIC%+2TJL*D;My+~J40(dv92?~FD&6m>tOE){Mr(Zw0`Fufln>r zNb9f{Z3=;Bi^>O_);Zo0c-|6@vOh`~*2P`{IB^L_ zT9dsa@X{q5XXS|FIPF$kF-6ZY;Zo)GPH-_>PD4;zKH0H2l0N>mMWqxQA8U>Z1prn33^Qk2 zEw&fu2t2-UCbm^+{lZS!;lL{k3#F|}>j7I)!-0=1;YiC*X7oxTp3K3i$sC-R%)v}1 z6I1K&;KVcyW}2uYcWl16honjwk|~C8LA?=`>8VEk8Bl;0J1=8r46alVvRUC zAeX${k=Dz0r5pk5^Q>Q2L#nh6)oOE!K$cvtNNbTTz!3%u7ndPbE`SHx#bpGL3skO1 zi^b$p1KFx`M_Npia}4L`Y3(O3+rBc)pw2;eYd>ooz2MxblgDdePm!&YKT(5{>Liu0 z8`sHj+1JT%iPy=n>VK=+b+yH~cg^noF)iC|O0B?O+g>!>pzTGq*sy=OA|0HhKIJT} zE5*9M69F<3xnnpKIm=kwVb|T^!29jGTdRrIS$63f4&;KGE7Ibk=yoI^1D-pEBc8M2 zkmqcpF@M`uN(aM3@7;}R*yY6Y-8c;!V^x3t3geOwWkjB11K$Rug!+>QV$;1J(67qG zli_&zBbqECbV@uKlHVswyadOI%A5|+$0dpkof7$Niu@ToBXtJP7{^*)X8v-e8k%Di5qMkiNv!~iD!*VB%U>{QQ{Um&pYVFy>?OU2&EE>^Llx6{jD#7 zFfO?+i2S+bYXee3eQ_f8xc39HPuKmzE>4#}qRApcr^Mn|*8JOQXxTsA*9Ut&p8vsB zmDyw;D;^7XvEs3C<0>8t`yb|an_QUIQDHVmg-IM0YJVx{TYYhd>U9$R?`lu3lVsrO zC3$XqT{*_u66GziRYMuL)^%tw?v9*g=Pd(XC#mfSU)!v4U8-$(-2dsR9Mi{~ip%t+;!k;*Y6%F)fSvWXBF(|pQ)5Rcr)nVm2ra_9R+0xZn`l+@fz zv2iQR|CDHmF8J65?_XR_VZoCEId|_c{`6=+$XV9TW)jRBZ{dMt&K(=2zS_pB zqo*_wa2x!tqR>k0`K!rg8`=8K8pb8JTO!w1q}y(Rlu+Nx5!>DS0jVpw=V$UqG+9LG zl-Tph?~^5NNN}PurvvnHi5rs8DUqKkDy-oq=RPx8-vXH!Dy);?a+nsZ#OC{CA;+w7 zi5&55203o=OYR}vvVUNA^Btj7V#&>yw=cm>NEnx#Z6aT?d~HBVs4peN`uimZ^uw5# z&1a;GXtIdVDKX{b_sJ4V4ks#eIzS(nC^B?P8|h1>J^ zE}4U*O>BBIwUBO;b!!gD`}i(JwZ>7=-@blcIrflsABheOcg?bnT_x)}Kd{Oh`#);9 z>tq-?R1p`+x_e3YwNzR^66;>!0ZEZNhB9?_LzvLhLk9 z>x{{C^0QK%n>8-cxmngZ)?Gb(7oAsy&dnN^=-jMviO$U$m*`x4mvu-`x7*d-=Pk_2 zIrf#98cXX+`$TXs@LHoffShcuE0^1uH_ARatO?Sph;{oGaBchOy5>lW9jdO$KvuLh z<)zd5o^AAHAbVKu$a-SPb2c3FoJ|b+Sx^;}smiU!}I$m418g^9d=y~gIt5xFZZ zHo&@TIF-3;xS=qYL+mr)jy8<~L*TBx^pIUFaXB8QCvC(e>QbPT5 zjM#4W32z&ax{?o6UzaYT$s$6h#O09uK3U>&j1!eP9iWd(T#iGhM1H2Iuw69S3z4ZH~IXI?RY~N|mah#+3H2q9*q{8TVnA+ulBdQ1=^~meB6LbD zP4fF>iBkh7DswtOAD1{aLZ?LjPwQg9p6~ARw%|^c?|ZPsi^sy<5S=A%_L6sNVdR&V zQw5<;eJc;UP$$C*!Y@81ohAikI;Sb)kbg%TYn|k)mGr(&a>L44*2%DtYvUXOrHg2?h|no9k>vNu5(^0@DswtOAD1XHbV}rZD4zLQwvbL$C*4Ad zA6TAZ6cBKz9+6g${0iA$`7MNvLCQej+j8i@SRmSY=`66$LKvG4db1Ej9x z1^;d7BAP5BbV|$x`F*m)TEL0QoDR^(CDuadl*k|cfkATG-`C*q=LGdlCfoql)7iwr zbx!ds=Bgf5mv}y9LtEkj^B0oiJyks?kJ|H#PklV!t*3jox@Yo9E-X2$#=T1pYjIRq ziKD_g92HjKsIUe{g%$j4`HaUOmd|+H9#=DKTsR_bc$+*S6snmuE*zJ7csMe3G8`MK z`Hg?Q!MOj{K27cj^%J|u4f6JNxpORxOP;_)&aixKKuW0Z4v1y`u>t5;W#Rl-=d`Xx75Q~Eud+KwLzUg@cD?GD$W@v`-a4dartP2|xg-Ug(E`jSIzg7*VbSMtI& zQvQf0iwK<(Q%-)LEV1NpqB5rg^l^zL7dj>KGew0ZH$AoFrl*$NbX#&vuiJs9k7Kqd zyH18v`^fTHhlRwmQi_cKd>@RO$f}6T9F1ap<+{N;>0V$!r z=ny;0`vLvfCgy!R`6HSvB6LbD4)XhCiN%Q%l{p=tk4qF8I;HaKF1K(;1uH@dep8OF_77;onric7KSz>wML}g9~=;IR0BXmmSXNn5T!{1UdY4v*| z=73`AWVj<;5w97)+6rtg!%$OYUFYl*m6jp83n| zdUvln>DEmA_UE^8q+f!C$oMiufjlynhI77;on=7Rh_Sz;~VL}g9~=;IP=A#_UQ|DF2Hxtg5z!*rq?E9;!% z4S<9EWqxwg`LiBfmUt8ocP0+h`*I})FM9K zv9~$V6Zc)I579!YdXGb~MCZs{ZTIe(uPN+nK^Ea**r8HRDmwMpcLmTxeS66y;d zvBeBhX|O?i>6ci0Ye^T;WD%iL;x|6Y?>{$9oFF(^WnC=N{B7n3hl`P45V=t-~&F#a~b$t<0={WLgQln2|9LJ z!3TV$=Q8kB##J(K)wo!HijGY!_<*N*E(5=BTqOgSUM;L);lBTdi+^;8oDWLN%`fl` zquPNVh|1@e7W#=FIzj$n(<%dru4$F4wEC)M_vc_hK#J^u3 zXBeEyFgTH6Fd1%pEuRASj|c$o5>@Ng;3_RToA}oT;yQ+;>KKx!V+eJ8Q^V`_;>*8F zv+hcR@@hp7i8i)XS#UOq(XYI1phG*#)_(64{1xK{RH^MYlNtg1y-`Q} zMeq$z0mrCQ_430$)v_|;3vFtS0QS}iQ;(%V*L#$X2-o28N>4fNn;P5mEe_HUUOd)F zhaT4RBk*dmLt#;M&qi{-tV-$h(xxj9Y}vqi@5}PXLLCMk9ruO28Q+Z*ayE>;GZ-4@ z^>ZKll&!oPON(i6djOC!^YBJV7&o_xF=_}nDjYLMg+jkqJ%6<|(FR1Qert!+N?IuH zat)-?ffv58&o+^vxC=AO&IKR2$DfoB*OU!KvwMLur*012yYi}C#)f#+CY z8Hj+peFqk`;`=?0&MXuPzQc1Fc(HMn4E&C9oh{%VuQ$F&Am?+6a~%i%$EcyeH$~-R zK@0uFNr(KOOsfoBWK=tlG(AgW*8!7ch1&3Mwhm37GyVZKb+@l|yR!wnq31I2M#fb# z@MgxvYbDdM^<-VQftwmt2BMT+KK&IiK(=;^58mE$8TditDjE1M#>KUwf4h8Kt-wDS zH5iCey4JZ0m{-ULe#mnfxP75tcHpvcajodL$;Z_SBy8!0;q9(1z+zy0!jW-9%h(1) zz@5CnqE>t-IZ_%&7J3Li%5xd`KgLxu@M7cQ(Lw(S`MA*mE;6bNL@7OBXx--nfe5&M z1B+Vm7?u|4?pL<9f_n(}_FM+O#JEZZo@89yZ}ca~$MqXXSh|x09%F%JAOfzFz@k>% z$tlv9S|}7e&2t%e;2VDFgZDBn?j-tK$;WjPxQ9`LfheW>-Kv1LLOyWWa~b%b##J)# z!^Xw6qW_S5T&+ODmR=a%?lc7!1LM&r;}px-21LNkB(SIzpQiJrv7pdH@N=Haz?J{_ znFMzl7mp75Bjn>o2Y8}UWgtrF0Yhtl9|%Oi^&42!ipOxgG|rH%ou=TkJ(qzWHm;I^ zA2F`81-#g}`27PpZQ$Fn*2~8f;IVamDaP~5lF_| zF}xd%lO9P@hROZ0^AIp%?w^%7pqW(tsRFV4R9O8NvT6Lqs_g(WdUZb<^p2n1rcE`; zpWU7GqewX_6gpHcBTT3bh*14}Kx&Nl1EQXM8Xpqq zC!fYcr^M6vvgV(mXXKf(we<>~?YRtmk8za@{J3%Pb%ycepE;?Y44%t*r{ICo+Do=JxZtmNE(4D=u9AVjX zWbGf_0QWP_{aahYhZI1m z{wVplxdIZF9`87?oC=JernC@CN?5A(2+W1ZarO_6U2H42l7S}}*VzJI)p{AEW/.. elements in the path. Returns an empty path if the +* specified path has a broken number of directories for its number of ..s */ +std::string Path_Compact( const std::string & sRawPath, char slash ) +{ + if( slash == 0 ) + slash = Path_GetSlash(); + + std::string sPath = Path_FixSlashes( sRawPath, slash ); + std::string sSlashString( 1, slash ); + + // strip out all /./ + for( std::string::size_type i = 0; (i + 3) < sPath.length(); ) + { + if( sPath[ i ] == slash && sPath[ i+1 ] == '.' && sPath[ i+2 ] == slash ) + { + sPath.replace( i, 3, sSlashString ); + } + else + { + ++i; + } + } + + + // get rid of trailing /. but leave the path separator + if( sPath.length() > 2 ) + { + std::string::size_type len = sPath.length(); + if( sPath[ len-1 ] == '.' && sPath[ len-2 ] == slash ) + { + // sPath.pop_back(); + sPath[len-1] = 0; // for now, at least + } + } + + // get rid of leading ./ + if( sPath.length() > 2 ) + { + if( sPath[ 0 ] == '.' && sPath[ 1 ] == slash ) + { + sPath.replace( 0, 2, "" ); + } + } + + // each time we encounter .. back up until we've found the previous directory name + // then get rid of both + std::string::size_type i = 0; + while( i < sPath.length() ) + { + if( i > 0 && sPath.length() - i >= 2 + && sPath[i] == '.' + && sPath[i+1] == '.' + && ( i + 2 == sPath.length() || sPath[ i+2 ] == slash ) + && sPath[ i-1 ] == slash ) + { + // check if we've hit the start of the string and have a bogus path + if( i == 1 ) + return ""; + + // find the separator before i-1 + std::string::size_type iDirStart = i-2; + while( iDirStart > 0 && sPath[ iDirStart - 1 ] != slash ) + --iDirStart; + + // remove everything from iDirStart to i+2 + sPath.replace( iDirStart, (i - iDirStart) + 3, "" ); + + // start over + i = 0; + } + else + { + ++i; + } + } + + return sPath; +} + +#define MAX_UNICODE_PATH 32768 +#define MAX_UNICODE_PATH_IN_UTF8 ( MAX_UNICODE_PATH * 4 ) + +/** Returns the path to the current DLL or exe */ +std::string GetThisModulePath() +{ + // gets the path of vrclient.dll itself +#ifdef WIN32 + HMODULE hmodule = NULL; + + ::GetModuleHandleEx(GET_MODULE_HANDLE_EX_FLAG_FROM_ADDRESS | GET_MODULE_HANDLE_EX_FLAG_UNCHANGED_REFCOUNT, reinterpret_cast(GetThisModulePath), &hmodule); + + wchar_t *pwchPath = new wchar_t[MAX_UNICODE_PATH]; + char *pchPath = new char[ MAX_UNICODE_PATH_IN_UTF8 ]; + ::GetModuleFileNameW( hmodule, pwchPath, MAX_UNICODE_PATH ); + WideCharToMultiByte( CP_UTF8, 0, pwchPath, -1, pchPath, MAX_UNICODE_PATH_IN_UTF8, NULL, NULL ); + delete[] pwchPath; + + std::string sPath = pchPath; + delete [] pchPath; + return sPath; + +#elif defined( OSX ) || defined( LINUX ) + // get the addr of a function in vrclient.so and then ask the dlopen system about it + Dl_info info; + dladdr( (void *)GetThisModulePath, &info ); + return info.dli_fname; +#endif + +} + + +/** returns true if the specified path exists and is a directory */ +bool Path_IsDirectory( const std::string & sPath ) +{ + std::string sFixedPath = Path_FixSlashes( sPath ); + if( sFixedPath.empty() ) + return false; + char cLast = sFixedPath[ sFixedPath.length() - 1 ]; + if( cLast == '/' || cLast == '\\' ) + sFixedPath.erase( sFixedPath.end() - 1, sFixedPath.end() ); + + // see if the specified path actually exists. + struct stat buf; + if ( stat ( sFixedPath.c_str(), &buf ) == -1) + { + return false; + } + +#if defined(LINUX) + return S_ISDIR( buf.st_mode ); +#else + return ( buf.st_mode & _S_IFDIR ) != 0; +#endif +} + + +//----------------------------------------------------------------------------- +// Purpose: returns true if the the path exists +//----------------------------------------------------------------------------- +bool Path_Exists( const std::string & sPath ) +{ + std::string sFixedPath = Path_FixSlashes( sPath ); + if( sFixedPath.empty() ) + return false; + + struct stat buf; + if ( stat ( sFixedPath.c_str(), &buf ) == -1) + { + return false; + } + + return true; +} + + +//----------------------------------------------------------------------------- +// Purpose: helper to find a directory upstream from a given path +//----------------------------------------------------------------------------- +std::string Path_FindParentDirectoryRecursively( const std::string &strStartDirectory, const std::string &strDirectoryName ) +{ + std::string strFoundPath = ""; + std::string strCurrentPath = Path_FixSlashes( strStartDirectory ); + if ( strCurrentPath.length() == 0 ) + return ""; + + bool bExists = Path_Exists( strCurrentPath ); + std::string strCurrentDirectoryName = Path_StripDirectory( strCurrentPath ); + if ( bExists && stricmp( strCurrentDirectoryName.c_str(), strDirectoryName.c_str() ) == 0 ) + return strCurrentPath; + + while( bExists && strCurrentPath.length() != 0 ) + { + strCurrentPath = Path_StripFilename( strCurrentPath ); + strCurrentDirectoryName = Path_StripDirectory( strCurrentPath ); + bExists = Path_Exists( strCurrentPath ); + if ( bExists && stricmp( strCurrentDirectoryName.c_str(), strDirectoryName.c_str() ) == 0 ) + return strCurrentPath; + } + + return ""; +} + + +//----------------------------------------------------------------------------- +// Purpose: helper to find a subdirectory upstream from a given path +//----------------------------------------------------------------------------- +std::string Path_FindParentSubDirectoryRecursively( const std::string &strStartDirectory, const std::string &strDirectoryName ) +{ + std::string strFoundPath = ""; + std::string strCurrentPath = Path_FixSlashes( strStartDirectory ); + if ( strCurrentPath.length() == 0 ) + return ""; + + bool bExists = Path_Exists( strCurrentPath ); + while( bExists && strCurrentPath.length() != 0 ) + { + strCurrentPath = Path_StripFilename( strCurrentPath ); + bExists = Path_Exists( strCurrentPath ); + + if( Path_Exists( Path_Join( strCurrentPath, strDirectoryName ) ) ) + { + strFoundPath = Path_Join( strCurrentPath, strDirectoryName ); + break; + } + } + return strFoundPath; +} + + +//----------------------------------------------------------------------------- +// Purpose: reading and writing files in the vortex directory +//----------------------------------------------------------------------------- +unsigned char * Path_ReadBinaryFile( const std::string &strFilename, int *pSize ) +{ + FILE *f; +#if defined( POSIX ) + f = fopen( strFilename.c_str(), "rb" ); +#else + errno_t err = fopen_s(&f, strFilename.c_str(), "rb"); + if ( err != 0 ) + { + f = NULL; + } +#endif + + unsigned char* buf = NULL; + + if ( f != NULL ) + { + fseek(f, 0, SEEK_END); + int size = ftell(f); + fseek(f, 0, SEEK_SET); + + buf = new unsigned char[size]; + if (buf && fread(buf, size, 1, f) == 1) + { + if (pSize) + *pSize = size; + } + else + { + delete[] buf; + buf = 0; + } + + fclose(f); + } + + return buf; +} + + +std::string Path_ReadTextFile( const std::string &strFilename ) +{ + // doing it this way seems backwards, but I don't + // see an easy way to do this with C/C++ style IO + // that isn't worse... + int size; + unsigned char* buf = Path_ReadBinaryFile( strFilename, &size ); + if (!buf) + return ""; + + // convert CRLF -> LF + int outsize = 1; + for (int i=1; i < size; i++) + { + if (buf[i] == '\n' && buf[i-1] == '\r') // CRLF + buf[outsize-1] = '\n'; // ->LF + else + buf[outsize++] = buf[i]; // just copy + } + + std::string ret((char *)buf, (char *)(buf + outsize)); + delete[] buf; + return ret; +} + + +bool Path_WriteStringToTextFile( const std::string &strFilename, const char *pchData ) +{ + FILE *f; +#if defined( POSIX ) + f = fopen( strFilename.c_str(), "w" ); +#else + errno_t err = fopen_s(&f, strFilename.c_str(), "w"); + if ( err != 0 ) + { + f = NULL; + } +#endif + + bool ok = false; + + if ( f != NULL ) + { + ok = fputs( pchData, f) >= 0; + fclose(f); + } + + return ok; +} \ No newline at end of file diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.h b/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.h new file mode 100644 index 000000000..c38ec5612 --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.h @@ -0,0 +1,98 @@ +//========= Copyright Valve Corporation ============// +#pragma once + +#include + +/** Returns the path (including filename) to the current executable */ +std::string Path_GetExecutablePath(); + +/** Returns the path of the current working directory */ +std::string Path_GetWorkingDirectory(); + +/** Sets the path of the current working directory. Returns true if this was successful. */ +bool Path_SetWorkingDirectory( const std::string & sPath ); + +/** returns the path (including filename) of the current shared lib or DLL */ +std::string Path_GetModulePath(); + +/** Returns the specified path without its filename. +* If slash is unspecified the native path separator of the current platform +* will be used. */ +std::string Path_StripFilename( const std::string & sPath, char slash = 0 ); + +/** returns just the filename from the provided full or relative path. */ +std::string Path_StripDirectory( const std::string & sPath, char slash = 0 ); + +/** returns just the filename with no extension of the provided filename. +* If there is a path the path is left intact. */ +std::string Path_StripExtension( const std::string & sPath ); + +/** Returns true if the path is absolute */ +bool Path_IsAbsolute( const std::string & sPath ); + +/** Makes an absolute path from a relative path and a base path */ +std::string Path_MakeAbsolute( const std::string & sRelativePath, const std::string & sBasePath, char slash = 0 ); + +/** Fixes the directory separators for the current platform. +* If slash is unspecified the native path separator of the current platform +* will be used. */ +std::string Path_FixSlashes( const std::string & sPath, char slash = 0 ); + +/** Returns the path separator for the current platform */ +char Path_GetSlash(); + +/** Jams two paths together with the right kind of slash */ +std::string Path_Join( const std::string & first, const std::string & second, char slash = 0 ); +std::string Path_Join( const std::string & first, const std::string & second, const std::string & third, char slash = 0 ); +std::string Path_Join( const std::string & first, const std::string & second, const std::string & third, const std::string &fourth, char slash = 0 ); +std::string Path_Join( + const std::string & first, + const std::string & second, + const std::string & third, + const std::string & fourth, + const std::string & fifth, + char slash = 0 ); + + +/** Removes redundant /.. elements in the path. Returns an empty path if the +* specified path has a broken number of directories for its number of ..s. +* If slash is unspecified the native path separator of the current platform +* will be used. */ +std::string Path_Compact( const std::string & sRawPath, char slash = 0 ); + +/** returns true if the specified path exists and is a directory */ +bool Path_IsDirectory( const std::string & sPath ); + +/** Returns the path to the current DLL or exe */ +std::string GetThisModulePath(); + +/** returns true if the the path exists */ +bool Path_Exists( const std::string & sPath ); + +/** Helper functions to find parent directories or subdirectories of parent directories */ +std::string Path_FindParentDirectoryRecursively( const std::string &strStartDirectory, const std::string &strDirectoryName ); +std::string Path_FindParentSubDirectoryRecursively( const std::string &strStartDirectory, const std::string &strDirectoryName ); + +/** Path operations to read or write text/binary files */ +unsigned char * Path_ReadBinaryFile( const std::string &strFilename, int *pSize ); +std::string Path_ReadTextFile( const std::string &strFilename ); +bool Path_WriteStringToTextFile( const std::string &strFilename, const char *pchData ); + +//----------------------------------------------------------------------------- +#if defined(_WIN32) +#define DYNAMIC_LIB_EXT ".dll" +#ifdef _WIN64 +#define PLATSUBDIR "win64" +#else +#define PLATSUBDIR "win32" +#endif +#elif defined(OSX) +#define DYNAMIC_LIB_EXT ".dylib" +#define PLATSUBDIR "osx32" +#elif defined(LINUX) +#define DYNAMIC_LIB_EXT ".so" +#define PLATSUBDIR "linux32" +#else +#warning "Unknown platform for PLATSUBDIR" +#define PLATSUBDIR "unknown_platform" +#endif From 471d3652e4241951cf9b4a774a13430019fbcf45 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sat, 2 Jul 2016 10:07:13 -0700 Subject: [PATCH 063/115] (finally) applied patch to fix 'setLocalScaling' of btMultiSphereShape See https://code.google.com/archive/p/bullet/issues/636 http://bulletphysics.org/Bullet/phpBB3/viewtopic.php?f=9&t=8237 and https://github.com/bulletphysics/bullet3/issues/125 --- src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp b/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp index a7362ea01..88f6c4dcb 100644 --- a/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp +++ b/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp @@ -75,7 +75,7 @@ btMultiSphereShape::btMultiSphereShape (const btVector3* positions,const btScala int inner_count = MIN( numSpheres - k, 128 ); for( long i = 0; i < inner_count; i++ ) { - temp[i] = (*pos) +vec*m_localScaling*(*rad) - vec * getMargin(); + temp[i] = (*pos)*m_localScaling +vec*m_localScaling*(*rad) - vec * getMargin(); pos++; rad++; } @@ -113,7 +113,7 @@ btMultiSphereShape::btMultiSphereShape (const btVector3* positions,const btScala int inner_count = MIN( numSpheres - k, 128 ); for( long i = 0; i < inner_count; i++ ) { - temp[i] = (*pos) +vec*m_localScaling*(*rad) - vec * getMargin(); + temp[i] = (*pos)*m_localScaling +vec*m_localScaling*(*rad) - vec * getMargin(); pos++; rad++; } From d0f20eafd161542ebf63c5f8061c5e266e3b8776 Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Sat, 2 Jul 2016 18:53:19 -0700 Subject: [PATCH 064/115] Allow to build PhysicsServer in VR mode, to see the URDF/SDF robots in proper scale in VR. Add option to have Z as up-axis for VR examples. Add OpenVR LICENSE + README file Don't crash VR app when no HMD is detected, just exit. For now, don't request debug lines in client, it slows down physics server in VR mode too much. --- build_visual_studio.bat | 2 +- .../SharedMemory/PhysicsClientExample.cpp | 3 +- .../SharedMemory/PhysicsServerExample.cpp | 2 + examples/SharedMemory/premake4.lua | 62 ++++++++++++++++++- .../StandaloneMain/hellovr_opengl_main.cpp | 40 ++++++++---- examples/ThirdPartyLibs/openvr/LICENSE | 27 ++++++++ examples/ThirdPartyLibs/openvr/README | 9 +++ 7 files changed, 129 insertions(+), 16 deletions(-) create mode 100644 examples/ThirdPartyLibs/openvr/LICENSE create mode 100644 examples/ThirdPartyLibs/openvr/README diff --git a/build_visual_studio.bat b/build_visual_studio.bat index de3b886c9..56ee9f610 100644 --- a/build_visual_studio.bat +++ b/build_visual_studio.bat @@ -2,7 +2,7 @@ rem premake4 --with-pe vs2010 rem premake4 --bullet2demos vs2010 cd build3 -premake4 --targetdir="../bin" vs2010 +premake4 --enable_openvr --targetdir="../bin" vs2010 rem premake4 --targetdir="../server2bin" vs2010 rem cd vs2010 rem rename 0_Bullet3Solution.sln 0_server.sln diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index a4199071a..e8e181992 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -835,7 +835,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime) enqueueCommand(CMD_STEP_FORWARD_SIMULATION); if (m_options != eCLIENTEXAMPLE_SERVER) { - enqueueCommand(CMD_REQUEST_DEBUG_LINES); + //enqueueCommand(CMD_REQUEST_DEBUG_LINES); } } } @@ -855,3 +855,4 @@ class CommonExampleInterface* PhysicsClientCreateFunc(struct CommonExampleOpt } return example; } + diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 05c689e8a..7cb76e9c6 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -306,3 +306,5 @@ class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOpt return example; } + +B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc) \ No newline at end of file diff --git a/examples/SharedMemory/premake4.lua b/examples/SharedMemory/premake4.lua index 34aea2de5..be3c7102c 100644 --- a/examples/SharedMemory/premake4.lua +++ b/examples/SharedMemory/premake4.lua @@ -15,7 +15,8 @@ links { language "C++" -files { +myfiles = +{ "PhysicsClient.cpp", "PhysicsClientSharedMemory.cpp", "PhysicsClientExample.cpp", @@ -24,7 +25,6 @@ files { "PhysicsServerSharedMemory.h", "PhysicsServer.cpp", "PhysicsServer.h", - "main.cpp", "PhysicsClientC_API.cpp", "SharedMemoryCommands.h", "SharedMemoryPublic.h", @@ -84,3 +84,61 @@ files { "../ThirdPartyLibs/stb_image/stb_image.cpp", } +files { + myfiles, + "main.cpp", +} + + + +project "App_SharedMemoryPhysics_VR" + +defines {"B3_USE_STANDALONE_EXAMPLE","BT_ENABLE_VR"} + +if _OPTIONS["ios"] then + kind "WindowedApp" +else + kind "ConsoleApp" +end + +includedirs { + ".","../../src", "../ThirdPartyLibs", + "../ThirdPartyLibs/openvr/headers", + "../ThirdPartyLibs/openvr/samples/shared" + } + +links { + "Bullet3Common", "BulletDynamics","BulletCollision", "LinearMath","OpenGL_Window","openvr_api" +} + +language "C++" + + + initOpenGL() + initGlew() + + +files +{ + myfiles, + "../StandaloneMain/hellovr_opengl_main.cpp", + "../ExampleBrowser/OpenGLGuiHelper.cpp", + "../ExampleBrowser/GL_ShapeDrawer.cpp", + "../ExampleBrowser/CollisionShape2TriangleMesh.cpp", + "../ThirdPartyLibs/openvr/samples/shared/lodepng.cpp", + "../ThirdPartyLibs/openvr/samples/shared/lodepng.h", + "../ThirdPartyLibs/openvr/samples/shared/Matrices.cpp", + "../ThirdPartyLibs/openvr/samples/shared/Matrices.h", + "../ThirdPartyLibs/openvr/samples/shared/pathtools.cpp", + "../ThirdPartyLibs/openvr/samples/shared/pathtools.h", + "../ThirdPartyLibs/openvr/samples/shared/Vectors.h", +} +if os.is("Windows") then + libdirs {"../ThirdPartyLibs/openvr/lib/win32"} +end + +if os.is("Linux") then initX11() end + +if os.is("MacOSX") then + links{"Cocoa.framework"} +end \ No newline at end of file diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index 746f10835..547f813fd 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -11,6 +11,7 @@ #include "BulletCollision/CollisionShapes/btCollisionShape.h" #include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h" +int gSharedMemoryKey = -1; //how can you try typing on a keyboard, without seeing it? //it is pretty funny, to see the desktop in VR! @@ -139,7 +140,7 @@ private: SimpleOpenGL3App* m_app; uint32_t m_nWindowWidth; uint32_t m_nWindowHeight; - + bool m_hasContext; private: // OpenGL bookkeeping int m_iTrackedControllerCount; @@ -234,6 +235,7 @@ private: // OpenGL bookkeeping //----------------------------------------------------------------------------- CMainApplication::CMainApplication( int argc, char *argv[] ) : m_app(NULL) + , m_hasContext(false) , m_nWindowWidth( 1280 ) , m_nWindowHeight( 720 ) , m_unSceneProgramID( 0 ) @@ -556,13 +558,16 @@ void CMainApplication::Shutdown() } m_vecRenderModels.clear(); - if( 1)//m_pContext ) + if( m_hasContext) { - glDebugMessageControl( GL_DONT_CARE, GL_DONT_CARE, GL_DONT_CARE, 0, nullptr, GL_FALSE ); - glDebugMessageCallback(nullptr, nullptr); - glDeleteBuffers(1, &m_glSceneVertBuffer); - glDeleteBuffers(1, &m_glIDVertBuffer); - glDeleteBuffers(1, &m_glIDIndexBuffer); + if (m_glSceneVertBuffer) + { + glDebugMessageControl( GL_DONT_CARE, GL_DONT_CARE, GL_DONT_CARE, 0, nullptr, GL_FALSE ); + glDebugMessageCallback(nullptr, nullptr); + glDeleteBuffers(1, &m_glSceneVertBuffer); + glDeleteBuffers(1, &m_glIDVertBuffer); + glDeleteBuffers(1, &m_glIDIndexBuffer); + } if ( m_unSceneProgramID ) { @@ -1067,6 +1072,7 @@ void CMainApplication::SetupScene() glDisableVertexAttribArray(0); glDisableVertexAttribArray(1); + m_hasContext = true; } @@ -1462,10 +1468,19 @@ void CMainApplication::RenderStereoTargets() m_app->m_instancingRenderer->init(); + Matrix4 rotYtoZ = rotYtoZ.identity(); + + //some Bullet apps (especially robotics related) require Z as up-axis) + if (m_app->getUpAxis()==2) + { + rotYtoZ.rotateX(-90); + } // Left Eye { - Matrix4 viewMatLeft = m_mat4eyePosLeft * m_mat4HMDPose; + + Matrix4 viewMatLeft = m_mat4eyePosLeft * m_mat4HMDPose * rotYtoZ; + m_app->m_instancingRenderer->getActiveCamera()->setVRCamera(viewMatLeft.get(),m_mat4ProjectionLeft.get()); m_app->m_instancingRenderer->updateCamera(); } @@ -1477,8 +1492,9 @@ void CMainApplication::RenderStereoTargets() m_app->m_window->startRendering(); RenderScene( vr::Eye_Left ); - - m_app->drawGrid(); + DrawGridData gridUp; + gridUp.upAxis = m_app->getUpAxis(); + m_app->drawGrid(gridUp); sExample->stepSimulation(1./60.); sExample->renderScene(); @@ -1507,7 +1523,7 @@ void CMainApplication::RenderStereoTargets() // Right Eye { - Matrix4 viewMatRight = m_mat4eyePosRight * m_mat4HMDPose; + Matrix4 viewMatRight = m_mat4eyePosRight * m_mat4HMDPose * rotYtoZ; m_app->m_instancingRenderer->getActiveCamera()->setVRCamera(viewMatRight.get(),m_mat4ProjectionRight.get()); m_app->m_instancingRenderer->updateCamera(); } @@ -1518,7 +1534,7 @@ void CMainApplication::RenderStereoTargets() m_app->m_window->startRendering(); RenderScene( vr::Eye_Right ); - m_app->drawGrid(); + m_app->drawGrid(gridUp); m_app->m_instancingRenderer->setRenderFrameBuffer((unsigned int)rightEyeDesc.m_nRenderFramebufferId); m_app->m_renderer->renderScene(); diff --git a/examples/ThirdPartyLibs/openvr/LICENSE b/examples/ThirdPartyLibs/openvr/LICENSE new file mode 100644 index 000000000..ee83337d7 --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/LICENSE @@ -0,0 +1,27 @@ +Copyright (c) 2015, Valve Corporation +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this +list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, +this list of conditions and the following disclaimer in the documentation and/or +other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its contributors +may be used to endorse or promote products derived from this software without +specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON +ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/examples/ThirdPartyLibs/openvr/README b/examples/ThirdPartyLibs/openvr/README new file mode 100644 index 000000000..9a8923159 --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/README @@ -0,0 +1,9 @@ +OpenVR is an API and runtime that allows access to VR hardware from multiple +vendors without requiring that applications have specific knowledge of the +hardware they are targeting. This repository is an SDK that contains the API +and samples. The runtime is under SteamVR in Tools on Steam. + +Documentation for the API is available in the wiki: https://github.com/ValveSoftware/openvr/wiki/API-Documentation + +More information on OpenVR and SteamVR can be found on http://steamvr.com + From 993bd52fe267fae6d4272c44f69c72ee23e0922d Mon Sep 17 00:00:00 2001 From: Jasmine Hsu Date: Thu, 7 Jul 2016 13:56:32 -0700 Subject: [PATCH 065/115] fix minor issues - arg parse size, spelling, duplicate function definition --- examples/pybullet/pybullet.c | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index e24a2470c..501bcf515 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1038,7 +1038,7 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) } } - if (size==5) // set camera resoluation and view and projection matrix + if (size==7) // set camera resoluation and view and projection matrix { if (PyArg_ParseTuple(args, "iiOOOii", &width, &height, &objCameraPos, &objTargetPos, &objCameraUp, &nearVal, &farVal)) { @@ -1459,7 +1459,7 @@ static PyMethodDef SpamMethods[] = { "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"}, {"renderImage", pybullet_renderImage, METH_VARARGS, - "Render an image (given the pixel resolution width & height and camera view & projection matrices), and return the 8-8-8bit RGB pixel data and floating point depth values"}, + "Render an image (given the pixel resolution width, height, camera view matrix, projection matrix, near, and far values), and return the 8-8-8bit RGB pixel data and floating point depth values"}, {"getQuaternionFromEuler", pybullet_getQuaternionFromEuler, METH_VARARGS, "Convert Euler [roll, pitch, yaw] as in URDF/SDF convention, to quaternion [x,y,z,w]"}, @@ -1478,9 +1478,6 @@ static PyMethodDef SpamMethods[] = { //applyBaseForce //applyLinkForce - {"renderImage", pybullet_renderImage, METH_VARARGS, - "Render an image (given the pixel resolution width, height, view matrix, projection matrix, near and far vlues), and return the 8-8-8bit RGB pixel data and floating point depth values"}, - {NULL, NULL, 0, NULL} /* Sentinel */ }; From 60d2b99151650f441f80928d19f01a1e20ae2dc8 Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Thu, 7 Jul 2016 19:24:44 -0700 Subject: [PATCH 066/115] Physics runs in a separate thread from rendering in PhysicsServerExample (preliminary) Improve rendering performance. OpenVR experience is smooth now. commit needs a bit more testing before pushing in main repo. --- data/sphere2.urdf | 52 +- .../CommonGUIHelperInterface.h | 12 +- .../CommonInterfaces/CommonRenderInterface.h | 2 + examples/ExampleBrowser/OpenGLGuiHelper.cpp | 17 +- examples/ExampleBrowser/OpenGLGuiHelper.h | 7 +- .../ExtendedTutorials/RigidBodyFromObj.cpp | 3 +- .../ImportURDFDemo/BulletUrdfImporter.cpp | 14 +- .../ImportURDFDemo/ImportURDFSetup.cpp | 18 +- .../ImportURDFDemo/MyMultiBodyCreator.cpp | 7 +- .../ImportURDFDemo/MyMultiBodyCreator.h | 5 + .../MultiThreading/b3PosixThreadSupport.cpp | 2 +- .../MultiThreading/b3Win32ThreadSupport.cpp | 4 +- .../OpenGLWindow/GLInstancingRenderer.cpp | 60 +- examples/OpenGLWindow/GLInstancingRenderer.h | 2 + .../OpenGLWindow/SimpleOpenGL2Renderer.cpp | 6 + examples/OpenGLWindow/SimpleOpenGL2Renderer.h | 3 + .../PhysicsClientSharedMemory.cpp | 2 + .../PhysicsServerCommandProcessor.cpp | 22 +- .../SharedMemory/PhysicsServerExample.cpp | 574 +++++++++++++++++- .../PhysicsServerSharedMemory.cpp | 5 + .../SharedMemory/PhysicsServerSharedMemory.h | 1 + examples/SharedMemory/premake4.lua | 214 +++++-- .../StandaloneMain/hellovr_opengl_main.cpp | 44 +- .../main_opengl_single_example.cpp | 21 +- .../main_sw_tinyrenderer_single_example.cpp | 14 +- .../main_tinyrenderer_single_example.cpp | 37 +- examples/pybullet/pybullet.c | 16 +- test/SharedMemory/test.c | 2 +- 28 files changed, 978 insertions(+), 188 deletions(-) diff --git a/data/sphere2.urdf b/data/sphere2.urdf index fb0108b3d..ec939e694 100644 --- a/data/sphere2.urdf +++ b/data/sphere2.urdf @@ -9,7 +9,7 @@ - + @@ -19,55 +19,5 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/examples/CommonInterfaces/CommonGUIHelperInterface.h b/examples/CommonInterfaces/CommonGUIHelperInterface.h index b9a4dfd26..f76414126 100644 --- a/examples/CommonInterfaces/CommonGUIHelperInterface.h +++ b/examples/CommonInterfaces/CommonGUIHelperInterface.h @@ -29,9 +29,10 @@ struct GUIHelperInterface virtual void createPhysicsDebugDrawer( btDiscreteDynamicsWorld* rbWorld)=0; - virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices) =0; - + virtual int registerTexture(const unsigned char* texels, int width, int height)=0; + virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId) = 0; virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) =0; + virtual void removeAllGraphicsInstances()=0; virtual Common2dCanvasInterface* get2dCanvasInterface()=0; @@ -73,9 +74,10 @@ struct DummyGUIHelper : public GUIHelperInterface virtual void createPhysicsDebugDrawer( btDiscreteDynamicsWorld* rbWorld){} - virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices) { return -1; } - - virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) { return -1;} + virtual int registerTexture(const unsigned char* texels, int width, int height){return -1;} + virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId){return -1;} + virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) {return -1;} + virtual void removeAllGraphicsInstances(){} virtual Common2dCanvasInterface* get2dCanvasInterface() { diff --git a/examples/CommonInterfaces/CommonRenderInterface.h b/examples/CommonInterfaces/CommonRenderInterface.h index e1d6170ef..0242a2bbe 100644 --- a/examples/CommonInterfaces/CommonRenderInterface.h +++ b/examples/CommonInterfaces/CommonRenderInterface.h @@ -53,6 +53,8 @@ struct CommonRenderInterface virtual void writeSingleInstanceColorToCPU(float* color, int srcIndex)=0; virtual void writeSingleInstanceColorToCPU(double* color, int srcIndex)=0; + virtual int getTotalNumInstances() const = 0; + virtual void writeTransforms()=0; virtual void enableBlend(bool blend)=0; virtual void clearZBuffer()=0; diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 23c225677..0af5c8577 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -199,9 +199,16 @@ void OpenGLGuiHelper::createCollisionObjectGraphicsObject(btCollisionObject* bod } } -int OpenGLGuiHelper::registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices) +int OpenGLGuiHelper::registerTexture(const unsigned char* texels, int width, int height) { - int shapeId = m_data->m_glApp->m_renderer->registerShape(vertices, numvertices,indices,numIndices); + int textureId = m_data->m_glApp->m_renderer->registerTexture(texels,width,height); + return textureId; +} + + +int OpenGLGuiHelper::registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId) +{ + int shapeId = m_data->m_glApp->m_renderer->registerShape(vertices, numvertices,indices,numIndices,primitiveType, textureId); return shapeId; } @@ -210,6 +217,10 @@ int OpenGLGuiHelper::registerGraphicsInstance(int shapeIndex, const float* posit return m_data->m_glApp->m_renderer->registerGraphicsInstance(shapeIndex,position,quaternion,color,scaling); } +void OpenGLGuiHelper::removeAllGraphicsInstances() +{ + m_data->m_glApp->m_renderer->removeAllInstances(); +} void OpenGLGuiHelper::createCollisionShapeGraphicsObject(btCollisionShape* collisionShape) { @@ -247,7 +258,7 @@ void OpenGLGuiHelper::createCollisionShapeGraphicsObject(btCollisionShape* colli if (gfxVertices.size() && indices.size()) { - int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0],gfxVertices.size(),&indices[0],indices.size()); + int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0],gfxVertices.size(),&indices[0],indices.size(),B3_GL_TRIANGLES,-1); collisionShape->setUserIndex(shapeId); } diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.h b/examples/ExampleBrowser/OpenGLGuiHelper.h index 0184d6ea0..72d784a0c 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.h +++ b/examples/ExampleBrowser/OpenGLGuiHelper.h @@ -20,11 +20,10 @@ struct OpenGLGuiHelper : public GUIHelperInterface virtual void createCollisionObjectGraphicsObject(btCollisionObject* body, const btVector3& color); - virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices); - + virtual int registerTexture(const unsigned char* texels, int width, int height); + virtual int registerGraphicsShape(const float* vertices, int numvertices, const int* indices, int numIndices,int primitiveType, int textureId); virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling); - - + virtual void removeAllGraphicsInstances(); virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape); diff --git a/examples/ExtendedTutorials/RigidBodyFromObj.cpp b/examples/ExtendedTutorials/RigidBodyFromObj.cpp index 64d52793d..9e09f9dd9 100644 --- a/examples/ExtendedTutorials/RigidBodyFromObj.cpp +++ b/examples/ExtendedTutorials/RigidBodyFromObj.cpp @@ -134,7 +134,8 @@ void RigidBodyFromObjExample::initPhysics() int shapeId = m_guiHelper->registerGraphicsShape(&glmesh->m_vertices->at(0).xyzw[0], glmesh->m_numvertices, &glmesh->m_indices->at(0), - glmesh->m_numIndices); + glmesh->m_numIndices, + B3_GL_TRIANGLES, -1); shape->setUserIndex(shapeId); int renderInstance = m_guiHelper->registerGraphicsInstance(shapeId,pos,orn,color,scaling); body->setUserIndex(renderInstance); diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index 9b6eb8ae1..555acf530 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -108,7 +108,8 @@ struct BulletErrorLogger : public ErrorLogger bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase) { - + if (strlen(fileName)==0) + return false; //int argc=0; char relativeFileName[1024]; @@ -132,7 +133,7 @@ bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase) std::fstream xml_file(relativeFileName, std::fstream::in); - while ( xml_file.good() ) + while ( xml_file.good()) { std::string line; std::getline( xml_file, line); @@ -969,16 +970,17 @@ int BulletURDFImporter::convertLinkVisualShapes(int linkIndex, const char* pathP // graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size()); //graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size()); - CommonRenderInterface* renderer = m_data->m_guiHelper->getRenderInterface(); + //CommonRenderInterface* renderer = m_data->m_guiHelper->getRenderInterface(); - if (renderer) + if (1) { int textureIndex = -1; if (textures.size()) { - textureIndex = renderer->registerTexture(textures[0].textureData,textures[0].m_width,textures[0].m_height); + + textureIndex = m_data->m_guiHelper->registerTexture(textures[0].textureData,textures[0].m_width,textures[0].m_height); } - graphicsIndex = renderer->registerShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(),B3_GL_TRIANGLES,textureIndex); + graphicsIndex = m_data->m_guiHelper->registerGraphicsShape(&vertices[0].xyzw[0], vertices.size(), &indices[0], indices.size(),B3_GL_TRIANGLES,textureIndex); } } diff --git a/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp b/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp index 92a917fd7..51b09e079 100644 --- a/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp +++ b/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp @@ -65,7 +65,8 @@ btAlignedObjectArray gFileNameArray; struct ImportUrdfInternalData { ImportUrdfInternalData() - :m_numMotors(0) + :m_numMotors(0), + m_mb(0) { for (int i=0;i

      7;D zZhZyXWa-UK^7DLG88Xm^qvtc0?AKj!W1yT_=8VLi!X6xVk#=5BU1b;A`;cFq@2oyF zzb%g*o1+n^g>MGh57x{toF4nBDdiG4_VX1%JBu>(R$JrEu{Rkj)}*Ako#nFpb9q&* z9jJwEA}?wo(D#FZ$x0sl?RQm8_0$N|(r1Ri$?vSW=1)|9zH<$n4N%ML zRg83ttSFC-H@*FzjlRDAV`mnupTKV|hUD>Sdhov`k^zxz%WyF0G6j=S791tm!6qjp2s2=V>N z65hDq6azgRwYt#0HhmMVgK0%hZ?!E!qIFOfVR`adBT%bnL5c?mXUQ&`>-HBxEk$JY z{358VFUK-a3&#p$tuN=4|2c7;M~R7%tC?k%-p)7*sQV&B}kwzFeVp{ zm6p%%<wNJ^u6l*2xL$K4`Yw72_9kQ7c61iQru{4Hy!VyZw;27v znTWAEm5Pg-Io!qawpS#2IL-_hFQdJh%L=Q5pNp81R#)?OY&k~180+c$E;TM7zeoyd zrxB=yV}&BZ>w3yLf6nIBJ`Ywna!?E7WsLQCGfcXje_>2ZAEgnfg>MGN-p){R*~Q#) z(Sv>pB^Xu1eq!wO{$T6a7VqV~#BK_E3VRSEY>ZWHTE?)inoAX$-%%q_3&%gL+bi`H zWiO}5*io}3_7wIYjxNTEFPtc%qr9v+TKpn$6rq+LjY=wBNG!7}EsDJ_ps>%epYSe23OYz)IuL) zEGBjY|H|1;LM%5YI`>_0}16H7JgqD3+8 z$Jj;J;o?TS7l!{loj@&|yBKTUx|N6W)`~cErk3on7U%Y@QtBd%AUZ4Vfs82WI1s&knI- zKVyVe@AJ8}vWxk}_Va+4h6=qJy}hhYtZZ@BB7e8V!o90*zK}Q@;8-dAVv{_%%T?BTVXjNsz6lns<~`=E+xcqe zQ8>17=Pug0u9jo!PqM7fceJUK})@j1yM$YV>wI zr(kT;@*q*9Ulx(;)>i`w)Y98g>*glDB2@ClJA&1&!ZGsgbQj6ycx&e^SHEtOGrzjX z*F8;JO-(t>^E~J$W^_7W;AzIa+nZ#LRA(8!)QjV}2t~Yx9_H;_`-@r&cN-`{;xnD3 zG$=$dxsm4hs23b<_4+hPH0@w9@SFp+@LYtk8_yDC(dhxA}%AhDB9OdegQHqj{{V;z>etFpsy^K5??QFt)NjCP?7f z3u8l~UdVijj;e@9IfW7=hVF`yRW`fHI$maf?CX3^u4(<7%GP(d#1j+L!m}3|Q4{*| z!FFSn-6{two{S)YCn<~#5<_{!iZNT%eN1y}=94mCf>rp}kG|DM1mMbk# zf@hw1n#owppj=WlpQzZd-dcZPuc4(G3v2gQ8r$ltJQpu%eU2WZ6CW1UQ6>LTa&Q?t z%@fgI(Z?vh`-Lkfe>d)1(^>O&97Q@Ydy1o~w%JkCdhkx-7{n2bql>Zq-=gGiMFxt? z%iBqu8F2ogx6J$1ZwH+__ltmICOK9wP!#ZjuIr?Hf)mJ+qlRfc4ispYqS&P_e|hE z`@U)fYU$SPN@tHA?JVNjzpGPGf`mhMI-winEZft$Aw_Y{Y~s0t2Z>`Tl{pfqrF)5E z%SF7ArIT3u{+>h$5?^M-$YGR`Qev_BHrT#;yByfKwdgSYAB{jQ-P=zsUm)*pdBG!h zw^t}ZB8D<+y6%uV)8H_I^2 z&fq@%MyXj1mRONME%Z0WK78oL4~!bCZYQ*`q67)_V_L&?d||Csb%L7LC5y~)c!Rvw z+f6z>tHzNC9}q3`IJn8@=c`h!MyI`yPH&s3^u9`>1PN>t)v8!6l{`ertf{3G5~wvh zGFs-k?IKT1G0Pb1URTAfXe^8PIw_POfqlbR+EjN{wAfW%v#q^GpqA_vEg!`?%K^8| zG9LK5s>W?{iQ_W2LJ1P+V~q99?kH#VA15|6EFh6Ut*HAOT=T9x{3khhAv%7__e88`0wiF>YbR{Ps70wqY`+(m1jr{%?s zs3PiFg=`vuTIg>yi@wh;qH6mpBj_$i2@<;R)}40D*tuq+`nU8!0}0eZucR~KP>V2g zIj_0|Xr72ZhE`{6VYEf~4Np#T%N?N5R_Mn%5k}doVL^R8ok|8MtQ8XYB*uOpZ4nPy ze{YYf0ScdmwL*WRY>`%7$PavFhJxDI0Mm*CBO@b-@C-o#51<88QdLc7t)Pg6Hh+0{w;7P>4^3u(QKBUhSG zU)-}^omo=L3PS?hNBO&(MvMD(b6a083)QkQG4l*pXLOozwry&Sk9E|=t-mUaz2FWB ztw52~UMG01*HzRk%4I<8(W5>63l?}h0lAR~@P#CAe-6UFpu_sx|^3IpCs1Cn$QmBQrUdFl#Db+@e9T&$ja);46%vGd3fQFCwv}>(Yy)Sz-0<~~Y#n|4g4-J>X zQP%fMCTjVKn3Jdza|>MKSzqU|E*;rh+tDL|wWV|Ck3;#~*q*A){X-ICuNc|HyiUdr zuAIXibM{irWxPh97Vh-u{5-k<_nq37KfOI#+Ye%VS0~=wNayR`9y1C@_EacA0&7dL zjEH|zqK^lv(*7kB#zHYhiW#kpEv+!q+M}w!x_8o|5vYaxPsT#+1{+K7c#GCOswq6d z!1xSWfw4O;UKsYBuJhJidujVxr1diDk4)zm-?vJPwEta;6d{4_W9)PFjWRa&l$_qB zvldUp$Sr37Qs%(HwX&ADE_XKVq!Flv`)E2JoR!KuCAJg4Ogk$vPKi5jv>RhNZ{!k3 zi#Ha#mao$Y)WXw6%KezUo-ayp6z)$vwWu1Fr`Kxjo6r2%$6|cT&dyq{GZGkKWo%c6 zJF=!{ePiX^UJ4`sm`{!I0LIq5sxEc~*Ay%0Tma7pFoJ+~qZ=cg+lUW;7Z8uLY_TGN zT6hA%Sp8x4;{1y8qG2nh#VnE5Yn8aGi102pi}$@>U&{+e0^7&fw6Qgm_i@R~pK#FP z)EJw_Jaoo3P>#ND_N)BKx{?}!S{Mmo>{UR2F*M*fA64*m9gKftmiR;JS z@mF)#O4LGHFXMiJ@*;fbcz*n)ua1jgYRJNx2@Y-8U^cr8ej7}Ll2H^#+jL@mA| z1Fp6bI}#6T1ZrVKht8c7Mu-E=qKsYl!?nzQ%;wjLecxM(!LRceTb35lZYUsuwf)~c zul?pduZ&wl+`P|~amR?8_q;OhF>&+$*Z=N$3G<#;9NqJ35?_;FrF&jT>qJ@C3aVz- z0^-^8Tq@&c5I6604gYb^i_fHcUKuy4xOxBU|GekL&3j%*>qK?BiF7VKI^`DKcFMTn zWFxR0SVP8Y6G8X9Qs|zSMxYj!M;Ssy_%{vmtxdO`P=W+ngibSvINmDAw?-xcwa^N- zTA8=c%vvd|JGM!;F116v|LX^V5+rn6O(5dIvLIi&=cSN9EvzApbMuBa z-j04-{KcfAbB!HUEMigbFnP3MYkn-G2XFQ4$KOlV_2k_Cqa4!dpl2ag_c=8yi|EZ@+5MZ1)m{BYwvvd8mM zvi@Hch&Y!)^vy(|mieTv$+_h*dJ^S85>dH&x1@;~#81h99H-@=Zbz*l5x@N6`XQ#ztz#jo_-@;nWVSl{;yfwu&Py zERR-XM0`|F<3|zkDZjL}qgnwwj>Jd$ceA!t>E9VEA7&8)B7HnB(Jf7sAfeZ)2ode7 zhb7(0M4%S7i6Si2@&?UXC%I9rung3iyEnzw@|szSQmr0RJFdzB9vz67LlW~Qt0_UP zXAUVgFZuVYNmz*pnVcR!ArpaGXc5M$Q?1;mqPor}s~``1aQ-%87upX+J!Zn0uf za%%n(@?uauvQ@Q}77=wYHt814aAVRVC?~YEOdHmm`z?r&?y9&P_N6)h&@9Y0qjsEY zz73j8rFT@le-iAS0~AV-NQk2+wJ$0o4mKyE!wf2;_@2a>FZB~D|tzm7byuJsRvP#q268PSwb563=gA#*0s}X?`By=yS9AOb-iXsKoTO7r)4Ey6R?7|*_Og};P_^E!l}=?HWvB?y-(=vSjP0Ry?w8I} zy%c99yh7_0y0takA_}c6o3yS1#i>DpMBMgOl07Laodz`}V#acdD8C?& zcd4SZS^`P-uiY_ z3$o-sw2wjw5@}0*tRFu#D@24R5vgedJa{GowO&&hU1-hlqYS$R7A4hF4|C^*5+qWo z40E;gql_=qj?`XteEc#IsD)NwY!wkTmU16@*J@>;7FwOLKj%$2Ww;^P^%$5$y`&LPhzYo)oSJv?sJ)Hg%Ye4w#oL6 zQV+6v`5Yzd+T}~JJ!`6Wam`EcNfd!3>zcK?l!-ts^GT-nOra;ysZ0j(ZwB#Gf&{k7 zwx+g~L2GJTt$q@ywQhH!t&ADJmZmbUP|M9)^&|o%Nc5hbU|YB6bTLZrQS$b@55`#v#Is zYBenrfm&7RNv1{S(39x?2N7n==MjMtB(P1kRiBNZRi8$nmi5bzmF0rM6{w8;)PprA zr+e<89z+Qe%{J_|?F}P-aV26-MxUR}M4(nGm0^zBg|;#lP&-z3|LQ@z34szM0;vph z)Go4>A&Icis2!1sKrQSW#wHOl`wu^#t(gea!hWLF>sE`h|NN`hjBEj7<8@m+LAw3X zlV7x7DVxtOCdYZS9msdJ8Z7{e5TP1*Vf*RH4;tVuXueeae`vT3>*lSKN*U7Xv2kDm> z!1W#s*=SLV-+l5LpG)^E^rc3M{A!~HZ?%se1 zmt_`J>gK4Vdc^_+O3=FaBzog4v8drsHYNRGua|)Y_7mOnqA|EBC`&TM`m|c17S2R; zD`gzbS68PbH>|7^sD<+*&7xFBkB0@4CuJ%FweWpKxlv@@CRw*7^~z*j)WY=xWAP1K z)r#1Hsh^J273dl0F*uLW3Yq%jdi+N3VKfF&f*!7q^FN5_j9S(EbE>UYKPCSMk>MpZR#Vhj zM#fjS3sBh4y#jVgHnu1)b=!@vp><))X@$6*tVpxZ`DGSyr9wOJJ+wbZNp|ZF`RFo5 z%ZF6v_$0;}EulQJBaz~xak0R7^B;JMWlB>p);GVnO zGPPs&N{eW6X`0s(io;$Kb6cQZnM=um>Yjc(3o)m|yT?<~RN z{|@A6Y0B%P{dv&3dfr2bz#hcs;yD#%-N#zQsmU_opI-tLN{|>49U-p-7w5OHn6(;2 zwYqhti+45hM3i6+@k#W>tdg#x+=*8ytDe`@%0NPI$1{qsEEt;K>vEX@6)|C@^t)J! zhYp}vsPii6SGEjq*|J%tmhYx0PWbvMiMuF@^KQguX{QSDN6l*SFD=)}GdYU#57D$@ z)qHm;^~cQt&fX);{s0LQaSPT;R;mzBe{8N^KayYlb+2GjL-H#mP^)A2Na1z&mNo{bP&-bROh~v)?LeCh@rjfnzm(-p&J8*GG=1leh}g@2BjakI!5z%Kft8|BRjQQpcA{t$w)TT{wd{DR01uC*Sg6+WM|0>@rbkoHJrq?# ztz&+xNs0Tv|t(Gn09J$lsCRCd>vP7q{JnCbkOrA(PFVVKBU(x|0V!qLL zN+L`0=|yVuW79WFw$y?9)u_dFTb-eHw7t>C`ysUhB}kyv=~Ri@k$+`jFS8x!B{(zS zxS>oyI%!zbwSadXI%z-x+kqZKnH=O-y&~s&m7#Xvh&pj6R;I2h#y|Mi)<+jBL`1@# z?FqGrz)^$*wvWCXNw#YGxLZOiB2a<^+K{mTdaL#87@K&R-Zc%+ib+9Pv4j+=JGlC_%!j;Z9kK-nETlf29#c zJ*b+NOiav6`zXvQIO@7mUTR#N=PuQfW7%}7KiQ%#z8{tl?W)%biGPfh@>pei{@|^- zyK6JoqE5`MkkrvJK%m6fw^EJ^D#lw^ZIP*rhA|Wa82vfvb`HAr1oh3{ZkJ3uP>9dI zTPah^^X;%Gb!&8zdltRrNc?(smvlQ&l)DtJM76p$+oHNVv&3a(^_JJ_x>C9~DZ%@s zwcyw$%Cnq6JK;5cUeOixmTT?Ex{AKsQiQkMX1>*26D*2bPk8P9;4i-2-X%lsl;HI~ zR^&b>Y>{T}x8ae2{X~(jy|nZ4O-@Lq$TkwFrMF}BPV$mbDc;|{`wM(7(!uqq<%=Bn z<}YT;{~<3~o7^X{EqMvcxmAv#)ywSTHM#qcb#nII()`$h`aHZZ&F!5Wd3eKyM6996 zMAz4TN&aSJ0$MoX?kXA4&yL&G49wJn_R}pYJ^Pr%WfcMhYWbB}BjaAu%CbV!Ohlt_ zi%P4tIH@CjZyP-hiS#LvGVw|QKIEji+b%*enMD;xCYd=!NT3#aKJ_`ZeB04QiN6tn z5+v+WDWcPk-V9drUE6|MF7_Wwm_;qe{F^%OSIU;FO7WN0=6p@^N;xX71m9f2^!8p< zhPmE9LS-OMDIfz(rqWQ?%2O~ zBpl2{pq7gt#lC58P<5|4!3Zv#3j7?s$7<)d|$nM^psa z%4z2duOVcs8=p4Iv~~_WYF=$#>d89!vRO&)caT%}>(TqA{J6cWLEOWIh$-RT=s0!P}&Jyw7KQy5q5hy`I^B#7ah&2VK zB?J?J5+pkH-YlmVvFAmnnKup(5m6#ny64DD1Zru1%&t(&>$~^&%1tfD)<&#cB|~31 z@X#HBnOa_)`eT*b!i1X{WALYSk-#xed$sSA)s)%}iL2v6Qf^#0ZOiLRx2tJfJNF~I z&F@wX!}m7s=${f1QlfoQhmR+GFs6r*BBbdn9z@LTQaELa*GgZMAYqpAGh$(jWvDMK zD0xz@q6t_!(mq5S542i~M43^Xi&RDy>%gQZ)rzH{1PQ$iihih*J00U)JIqN$0=3M) z(-Ne$R=622@uf00)gGUemV2!)zR7SzWzZSXD2iXH#g)Q*%KsYSgAydr>WuwGM4xN7 zJZI%8mx2Upng1?ENTb?JvsU|vFlXvo&Fb5TpAi;Q>u2l@X`ca5pi7>)kX;t*gmS&fRDCzRQ0vrk1;E( zA^I3&vx`?wG~01tNvYZ>K|*iG<%w70&32f*h&5Rry4N-y^VIFBS>4q85$Rkr@=83` z7m4;c_Sxvy2Xm#+_bd}E!ZB@+=NVeVVLLJiX_kRyGp6ExWS-f7^A{*V0?VVXy?ywx zW;lAlUuBdo&C<~ddaWkpbyi`y=X&kk{Xc?dCa`^sb)wnRZ2f(jO|d3eo?ffY|6hWe ztwlnw)kf!NTc5uyQ^f24sJpFAXhX&l`c&OVk!RKY(zSS$U>R6jdY_lOVC(Z;V+SRm zC*u1YeVVaHO~dz^UScg@&J!g_;I7a7MFdCR(C2e~y(tE3j?SMmnfdq6xfWx+rd{cl zbdSxx<%vKE5*Ur9yrl-yQ(pf&S>%qKR|g})7zM`J^+y?3-cAR+5SfQ|0JwtJQ@kTj3KYXQ;k=XRoD|zC-bcKa~3tr`0w1nETsbV zx%<-1z9_*mu(ss8msB0c#q&~U-22gvpXURn*3WYTlm2gRH_MpcJa20B*B?FjQ<9nZ zNz*q{itIK0N)3HEe?LZq@qLA~S%UdrsLEeP)ItdoX084!BZIJw!wiY-qygXO8BfYM z&1mFWCBf`H^&;|w9U}hb~!fCZvdRI3OGhZLeKw3Y$%TD{J77LEnnn2M`lptaLZD!W| zxHoZg#0j$?MX5-7pvV&);8O;F6W=-%7$4Je-s3DiO>(1|-m z1#|o|AR(Dn$|ylXx7Co0x4{XDu4(yjaI-_t3X9Gl=4TLQ=DV4Vhqo^9&IbMZQ16R2 zPfWH8^u+8od@kOIpwsZ#m27XEn)w4gP=bVB#$Jm4o1R{hcB@zh(r>i9zN=)bqW8TL zZc~H;B}nKwkl%-%u#Jz1ynzWwpcdMYv6CIXn|&^b@I(m`Xg6v=@c=P&=k55y6uZQ8 za=eeB=fgdx$V%z^{o|LB@1g_=yh%dusI_x#{ZX+%U;<{eA&qw^C^sr{?*F_UB}nLH zRHXhGyZ5$-r2fD%kj9)s%EqO*?!evM;?12TN|3<&EoN_<|NU4eB7s_H!yo!T36vm# zcB7L~b0< izDfa|H38hMqxZ#xRa8su_S}J69evTa0}o`@18&~A*GF>td#u9I~!cM$J<==pFZiMaDe z`P$|kCX^t7H)7~L7@5axhq{w5&=d3ekj5J^)bhw5Bg*U#lpvv(;YO!pZT5EactsHk zECXrGTl_ITM!q?{-y9z(K?3j4m{v0X`!PO{KrOW45B;A6N{~Ri(Rc1@G)!Iae6l#b zDyoha1%y*ljP+9-Zr-4j@!uwk5m~Ihngj?fi-1k|P*B|cR#Uw=d5hyIJI4L=$X!rM zZt={in(F8FMI%rPPv7Z2QA2NWsm^gZs%9a95+pG8PInX=R2AJyB+3dQ6*L01^i%y_ zF3rS_Q^ky9RZ0nzAfcZE4DZP4OKeMx3BOj-2-MQ^85U&o7I$2a^2dIK1xk>>(-Zmz z_PHve@z)F7<9aELKrPH7q1znyiimaXtBJIBe`}d1NN7FFO7zPqYG1D@J|(@;2-MR1 zeEXk6>m=TvteU(#oQjcD>~sB`^WyG-sUIFpR)gcy>YxM(^d9ov!8fIl4aI_v4<(+_ zYkmw-Zpv=TS5}<}ttLJM9@Geop5yr^V})NAQ6+NPiIyFTYbT>f=uysc4H~MI5sAF@ zf@~UrT6pG3zZlZfUFG{agOATvMWF-1+P$)zq84$7K6h2kmSd35-TF_IFaeIZ8A_%XIY~?! zpP&(_h4;!RYqC=vIltE^;qTW>qC_LK9N`0F8_M=Bqr`~d1{#4m!gwo?+@2nYWekiqL|YIi3Dol%_kbQqg_=I z-t%+WUzB}ibdJDr&9%&wN4@l=PeKGO))!dtEMO{dSho`CEs|j5vYYXb?G-Jg_m%ycU~@jSwNr!3A{Z*yCUTwI_Ehn zC&d)f2-L#cxpez%Y;Eza#$xN64K)QykkIe&Ufb6}`1$)9EI7A72@?30pl@uAa1{?$ zFXSsP)YJ$~OS{AS?@(WruWzKxwXC$lEG^6&&`&K_dl+ifjA&_huDC{^mY(C)`E6;H z`(zQ-vPxbpYf>ZNT$Of3vz$~9mr}|<8~yeGo9&D&-KD+S+%QEWP)pC)I+_+D6Bdn8cXl1Lq67)dTcdlBmp`Q5zdb>18tEWW zf&`wc)0^{lc_U)OM3s6lyOzs`T6#X*z#I$s@ns{_*M_GJlpuj8{It8P8^+5y_f)?* zC2=HB3-d4OmXKp1aX;Nx4PB);N|4ZV4cr&z7CYa%t0Fz#YXoXxmL|<`)>`8D-J5bo zkAeavNML>d#Y@JziOA_nUTNs65vYaPdvwzxuC;j8?Xhmo);lFdvrAQU@L7$8P>ERxcDBB}ib_6J;B| zJCJ&}!bDMIkG)2q7G}^=gnq({I`e;>EG8FUX+;SVn7u`{>bzZsh4vA**G`g1pcZC} z(RYfAAJv*W0PwF-{`EIk!Ry5}3nA?Kodfjc_a}cGUhNkw7iX z1g2U&uB9rL+0PH&aL{suk-)4#%Cab5SzTyym=C{PUL#OT%P?kVt6Y#d@3aw}jvtUH zK?1WWX?<1wjl5i>nOJ#7Y6NOw20qOU(+rhrZNiI=rJJB|O8^Ny2Qq$HfZE=s1b;iZ ztVW;~=I@hr7gSU`quqwS9CiJR&x&Z(g@VTH!5ROW(YGoL4@S}?1?8>cxv@w$2{4eZV%lr z*^ADjKJ;7aWfCwzk_2Acg z%#*X}@0nYA^2AR+{(X22vy6nM>ul#AW<(AN)WU3I`uV{NWoOQBK==QSRNdZ2j>^ z=T3ZMp&x(y_YUGn(-$31PqXE){F$~s5hY0I?Uw!wpe)o7Z!mv!SeK4?R!{PtlFO7Gsog8P=W-OO?RsI z`KvkQ4ewpKoVEVITA@WK4|$}&&9e1dJ1dkRVg7B70@DgVzP@Mn$~HOy!kS>4kft3A zMgL8LZpAB$_sr|lxOs8}ePz$_Oi%uVM(Q;ByB&>GXSy+Betqw? zk2wZ^{P!bzj(3#I{1Q{k%+l0}HJ6Usde9`1KrJlK{4UNc+omF)zpcC43YhWGKG^a#Y`PB?(ff6M2THV>}uc{rb<9(mTIhKyKLW|J%OESiJ zr;Ks_(~3x-)%8(}H8KDG*(Rj*nE@r436uUYm%L6|Ri}N&(jwo0rULV?FtZ9Xx#%9t z{NGczPsuNSY2HrD@j}AP>iL;1Mz`n!id!!oc2~`xdD-%>e&#JA+J{6@aY{BNt>JwZX|(C%=6|8$ubYEw<8zTP+w_yBJb;}` zZ1dGnpVzhRTu;fsPDiYMyY3qiZBCmtw5BzFVvMEQDzpifm+|izW&G4P+kz4#GXBmW9?{I>)PQ*(czeYM z`vc3ON3?JnEI?w?2(y8AzkmDJJ9IPc=H<$NSx%r!)e! zbWcp66Kb>d<~M{gdde_+%KPFPxy5U@;qbh%?e78iR@naj@eLu9Fux)6e-Kua(EFUe z1F5Pv8c=)De}omvun|{QM9R>lcxz~^d9P^H8jE^9xlD5Df&n5|(s~(|Cas}Kb@|H; z(K2mxiq(A@&*X{AD0d}vd+CHmbn^vk)pk;(On1sz-JI%0_nkEYTbp5BTW#rHYJ^2)>y{j!P?&CM&fg@xLRJ_> zoBHx*OE=j(agv`e*L`=}3X9se{}*rPA^`#=NNhg4QKl!w8*a1A{+LBx5_tKdciaEG z#AaQzDEb>?d8k%J+O|&VNwvyoxs5u+W;e(4aC3P=1Vb_1=G<^01=* z-XQ(%&NKY}5M0wr+aN=t=UHi|O+;<#!M6Q|de6?(gV<~7Q=+BQg%l$$nG^93eXXbR z%nm-w=^H{QiJP`w249v&TH$(`yu^PgeG|~}mCsH3z7Mto3G`{ojHVpU=&s+huA8l!4=h?&?#veC%wlpukg&sgiJ^i8LrzVUX>0RkmR=;I@n z<|*@yGiSaBh;(#pL3 zG7-ZlFL7RMv!q3oPZm0kW@KNhHSK9V-ZCG(`-&%7o!ZprdOO}x{hNCp@N7nVXOw8f znbk5ab+`3(FY})8`$&s;)MT0O`+NZk>x;F*Cs9P0zUWXaaDY#JGangNdPrbx>5C_u zEJ8-K^ieqj6xs)^fMwH7Tx!Sgi#65oVv8-={_b zwKD$Q<_os3Q_^=>DtTQaB9xwW<@#=8JUuIM8m$06BpYYu2K=;c22qHhPfVsBywp3;_T_pcPz!BHGaM28c9w+Z|Mj`e?nq$I(l_YV z(=Q2J^-GS=quc7kg!OXBJF5|O+u(XThEeAA%r22h`67DUO@F<$c%=f%Gk1>{&zF%@Ne1^v``hE!#sD&OwUj?Qz8m$cW zu%j}6w7#ddA(VNHLZcU%1E4N5&OSq^{hf!>sWWB^>#F(Z*1)y-N(a) zz5<03B=jYhIhtPY_iRO8_ok?Z%XkXu>6_tSmYM~YAy9P~4 z+A^>wx-ay^H$A?iu%8%<_+r~_i&^5K7BxUZA5lYZFSo@2%$XE-jkwRm8N<{w{|i+K zRbT8w2@?8F_|yB6;@+NO;&V`5f!>E}5$q?54%ROt(kHu#ODAq|lpulYAj*^JcAS?P z*h=)ebV(yn3;TxpW5-|o`{r)KVMZ872@<%%p|9yS&B{+b883{b-wY&B3s*Sw&9iZD zjl;z!h&#KpXl0-l_CI5FcfPeAwx1x@CuWf-K?2uAjKwy{Dko5_g7$o~B7s`EUv1d< zmmD0|O;qY0CQ*WfJ_Zxo9+yQ1w-QCKUXmz50(UaBPHa|21&ntSZI0g32-Lz^nLiisZG@+y=dfqPNv^STYiHkWAMafwdaeh_^OcY2haK)*(NGk!zL;FfLzB}m}g zj((SHl)WnGUR*6&m|t5n;La3xth6_1;;2?!s;(Zor%HSmp%%VZh}az~w>}M02lxCX zQG$fNn`reeLMFT%qB_Qx(+JeUcL`%LloxfU!vs~Urh`NY61aPz7{EVwQ+Ldmq!u)} zU?727`a7!T{4l;Db%eTm>AZmwBydMYZ?*VHemAJQdUJd)M*_9ulb(IFTNKui9 zatb{I`(O86mzE9HmglQ{&c!;}h@a6jBybc^{#Ck@xZA6+*z+}qZ5I8x|G*tR#s(-O zWvPQ0Z!IPU1n1HTh(O`$oU+>-Kk~RejYNZ9hqZkTJ{MzI^u48er})B%R^sfKvl@X~ zxay}^M!+&&GkBP2_arYz2@)7Pp&YMS>y6Y#<3+w2H8cXXLSauu*Y0x8ww6CXK_u@g zBvFC{Ms(;4n5DBy{?B-^|JpYz5~vjlJ2Hx@#r`E9()(lk{4o0d+<$vDBy4kK#=ecd zixYHQPN!Kk`?-u+G(&>K6)noSw_zF8nBId6f6k&A1Zv?9iOwcIl~lEN7ZdY>@+y=d zk>Q~kG0STd!|3HcD#iQ-E%YUGPW#sW5QMwJvtcLt+aag_E&YG*(HfPFVw<473~A>-H~<1Hc}UQr%RL|p+^l? zo%%zLaOsxz5fGoDuTu{GZj^p7UUeRtRa+Hf6h~jZUX4oP{fG5X{zbyM zCc)=w(I|VLL>}_Ao5~?#bON++~IEp@5 zimNNrvWsd{7RjkWD~#=NRe8TXkuojI3d19gzLMs;Scb+gHqusBp_P8sVns#x9T!!{ z?z1LAVu++Km~9F-{HSd5-G(3d4r>FoxymVxKrK7pB{I!YF>rSzfth)z9PAiuunp0=1&ntdOD9^7J7VA}Y*UEob)Yul^`I zS)xQEmQfs*tQ%U++^fwTd_r2|f>iTU+chEzwEPOwcSorQ?Y^16ulAt&2f6-O12wM9 zDTxv!T5j1S8F@))Yco!rqeM}){<@25R`Rn(pq7s#{hk;3m{%PqBKq%lRC)ffS2Gr5 zS13VZNQ)SohbH@)JKfpZNYQOtOk(ljBx{)pX`*eIumP>trLOLTz%jz=mw>2_vRH`w}r5cYqPJK|+YJ`lg%UQwIl1-;bdT@0j zHr}_BGjEO;D`%uzQG!HTfeo@&l1Z3eQh!BYosdtHMXoNReUU&dr|tCH0|TWIvd8?D z%6pB|j44kiiiDxN43r>|9!uU%?ej}APq5gUE_}_0k>bX@8XO7Kx-&XL_KQq4&Lz-y z_1KHB+iJE^b)(F(t*)2V`UCqQ?(Y>cgjycj+8l$`o368NK08sI_}iS*FrvZdLBo6NantwRpp*9YjyU$FJJfPC~@~t07nTDddma5Z{T|Z`-`tN2WtdsrPW>{qh2K&FVCB`x>?#$ zeSc^#J~sMARVcqoE;+c{SX0}Hhc=Cop{4g2ZR;8Q<#_syvflAVXftyR)(t79nqP1c zGaWxjlpql*Hp$R2iH2WxI(1^M)!)f8Nex8Hq%%4JS~yl{A2sl#JXWx?*gTWIAPA!f zpNpPPSz%Lm${sa)iCh;JYXoZHNTc0^U7So)J%#6Sn(?6w)IyJ8YDzIaA2QQ_et zu2~fPRkv<%)Au~v>IPy~`e}|5^xdeo^o}CyMy)e{n&Zt$O9ltw&o%BmvW27%_#`k-zlXDkrG|p8BB%=Lp zKe2UDRXOHFd5u7=;YT*eqps0LpRVnQXcb*c%s7xLn>{Hd@VQvt9!HuV@2xhDZD>ox z7W!4)Z@=YJId0|>XU9j&KJF`xZ?)QTKOQC1{Z|<21Da|zWbD~q7ctd0huShCpGIJL zdKoX`3J5vwSLNUPgZ5l3&o1vqdF9A5V`yB54 z`ad^Nf&|u(=H2&9%JvhKU5oqHw@qT@v2BZtxAc9d@h!k|JThjrqvSTT2uO>Ia~JikSwvLiz+{A zt45%fSJ)=$RC~Gca)!C~IaU9fbZ*g3&8fdnzPm(U6;E4cw9MUTT)PY zPpht$MLv|Mh4hs+TV#5<2qV0|InH;}%|sqpNF_hXrM$M#FF2f9Wt50-%qR4Xk?Ay| zwim9el}D$2+a1;69QJC->R&Vh%hSu4JljL%_B<{pZYrv@=R$eca&MLC_Unw6?xrW+ zGq@_XH&_O;@*06!DKbXRqjA1`nz@GSlsn6SG#w0u1%;@jSj`ZW;COwJkE#W4n>wqA_1gwhHaC z-3TLF=|pf5uKG_3=KDO#E0iFCWs~nVtDwSr<`aGT=TZ44Zjot!?=qqsn{cnBO)~Au zZX?2{o>m^+mVI7PecPQy?7xyvBd`ptE#>c?E35|oKd!Djtg75;A3Js|AXZQ>3RbMt zlUx-$_J*Cccd<9rYsZe*6~bZ)eW zt#n8~(89Fsg^QOETbs<_K9%!|j*oVUP3I5k_C4F@=ysT6iXKU}1Y4q8Du+9Z(jn9N z?mLAP1ahe|s)-jFMYCq}xd;3*Ol$C?U6dE(yGz78J)~Pln$@QD0R>n_w-8=4;JW^C z^G@M0jwo~JCV8<%H}(F+Io#@f_LZBpB-dw z<#z~|Df{(~Rk|?bLNryadsm2`aIVKcWxiFo5Z!8el+YR_>KjU!o--oCjTiOO_`$=) zxhNbZyeh})$M1DzZ^)lVl14?4KUWdAN>t_7{7Z0;@O&I8h`=6F1d#2^&o5lcJ~eXY z$c6ImUfwR=oQu|-0?Y_tdc2j7%jn0pIjRWc!uWym^q*LH#GCfI>)GlYDTq*`jNKjF zMfh*?+2A!3xGj{%Hpb>$d)8ugdJ(F7C=mwAVQUK;cib>bjca!iwc{L7-<%aXLU0X_s$p9&$u|tTQhs~QeN@SzvaIo~9!H9`?=GS7)w*`C@WYLPV&~F`;LaSo@}peDhacjub?wG2E`)N5rei&1H{Axj9l0p|NO@d4pm` zf77<_{&G`{sMSNxJRi#tfm|2?Qp`}ejNE*pr|=xqlH>SjwW5WVKyUD72d2o=-Y%~s z%Qa`xZowR8yFpwlX?*%RFZeh>q7AaiuMgfjy-Awinit z!z=5uWAO|hY|BbfrcJEXGphtJj2Y?M*~eYpd%aV{u-aT{3uIt#HSNxZ4s;v4gFHRC znlHAS*?hOq+&1X8TW$X%W7g%?a^$)Sa@wthI!Z@`8d-kIs3&97r;FCs+FX&2y@GMm zv|8Op%fk*SVyfRQ1LNIc=c!lmoAvBtZCHTQ9;%44RlnH4jF1C-N6V(Ilf_T#-YW>? z!iba3BEOt04<{BB-v$g5NIB2;i1VeQ^sh%-GmJ7RzoO_!c{RDCaLtZm*b|$iUcHRa zZIjymr&n(VO_we1ef7(i+F4**C<7x-x;-LzmMpq;iGIp2$w02_^(n^ni`IvAZ1bP! z_5O*eG9!Bo+f=crfo&n8!bAFIm>sKUpESp+*wo2#{-_14PlMG80=d*!bkN4(a$nhV ztoXg%22v1#aVedt4h@nwoX_d$3$q#aB(uUEVV$~Dx4+Vc*-q2A`R~=WVP+)bc+W@H z9#ospI*_ho%<0jP`hIkup1G?nvxbm%EjXZSf0*BDEoZyQiYu+$<6tfYfm|4uQhn;V z-DJt)V_EpyZw&j6J+XZx8CCY_+6hy};+jR}*2W$9#@P0%^s2;F_@J&GYsXX>zZ57f zzaDDCt2?(=DS%L;*WZ6`Begr%Sp1lW44)Qzg3qLB&wno=Jx{mcO;Y<)^!LA>SeHf% zYf!STjcdluPd35p&g@Oo-mMP1-jlWE?o@KA4#!))<3T12BAGvOcC(AqW zp|egfY*#z8OJt6vUghh^R2jKeCyDE?d-9;DlPU!eYE1nTcb12${KXFbU5P8w*N_cf zLNlW@S!x&siu7kM7lR6P;ho-pVM<#d10!;ZuQnGI)tp-L{9h_?TQ2%)d_?cLJNfOe z6!mpDpxe%NW@=2GncYKQ*nso!eePVL00QG{+W&~2m=ROhfd`iB$gy3F6IH~UX%;r( z*V24QtpJV`L}081G=C6G)_9aZ_7}sKag>e_v)6XBn%6l{vch-$o5XglqY?RmM z6T_~@>=N#u1}H0ch`T~#Wx;1-%5{oKa zO6+sN^_%W@#8HkL9iSjELQO5CNbYOBcsYZAoAL2Z=?0A(oAhjwgkZaMLATY0T!G(&%mUQ~@_oU)3^?s0A9 z{^sKtQV@Z$gr?oNRa0)c-cT04Fj$FLFp|N@fL5cH)RjK=;bQjanj9k}?IKyC;Ptvz zvYiqK(cMnP+Q`23?~24>cU1}?R2h##o6CV09*f#XA2Edj2#h!=Lax(a_Hq3v60fe( zG5$a<^xCwtU0{HWD)dVH?$*{o1ae{YLDk+0_m|Tg!o-2!&oOKlBLGCxxuRF?WkkEN zVqn)oG_PQMAZEap=+=b=)8)MewT0i~R|du<7|CE{K>53;hR9vMX~vdqHL=zOFAM*=%9wF+yMjP2RYu`rljXI1uQJXrTE>uq2=w!`P94-%?(R{J54El{(4S+R zfZmSsGFA{P*%LN zgw<|eooh$|->&#wtx5C3BHy^y+|{WZ$DUvh6;Gs9u3SMj?6riAN@1#u6#9aEzMt}1 z=mu@&Ip$8Ym%n}5&qjE0b*?CT=O$~lt{+z@;GJ#Cn#}W;heh4V znapMju1-|eWDtR#TGK+N z2eHNNcIhRaPE`=dh3i3d)8Esz%NA>S6J!G9})s&C^K9^jMQt$9^sFEf7dRCwlRhVmlSp=ACL^pIVvT)~GH9cp!s0f7%a$9Ks zoNB{YaBt`(=>!kvOdtYtjWliHe7c8s=0?xPban|dgcP)rw-idJwv6Wu4%z6`7Utq$ zrUK?5(22t^IvG}Yj^|N2MTa}?xHFDDq;p<$?(TMxUY;+@s0if3aii=V+IMdCxqC`W zI*Ei?VTeF^ns$-S$~66TaB?|1D}xB+QnTAOQ?HiGa>+V92T~BB?$KAG6IJG!kuLN; z5P@8nSx1(7p@lzt6Ylv-W%YevW);30x<@FSPM?jflro;i3Mq)d_e9yabUM?aQiaq@ zbUG6e$c5P#G*+`Le2mjZPtA?q2jpcSLVf4+Y3{}keSPQv&E3oGBgDm>+x7Q(+cWzB zIzKpszV!M8uu0P+gx!Q#{a|`KS_8;KbJrZJCUnBB#wNN$dh=F2+1{6#zn{+8qwlBR zn9oAzooObHne+8vEt-jlKrS^a%y$Z%+Iq4hwO1W~iMeB8kLlZa;95PH`7sr7Z<>WK z@;H)espT(`f(VpNndG4sK5AuP@(ViWh1na+A|iy#nN9krx$Tq;%AC7i`1Y??Qj%yU zVx}Y_G#WSU&}!X<#*O?Sov0f0Y_8|t(kcSEFdvdCQjiYb8XxLiy(~QkW?(|Q7dukc z%hlz&%Pw>M>Iywav19h$o9Q_afn1mmNjq4iAAE4Tw8o?#NI^vA2FgxZxmdT_%sjFq zyDYr9>!{Rebg~!`$Ym|Ejdoub=~jC)yR9C*!I{_U`1GeYhzR7u3`(jtO>?*1wxK@l zY3?Eg5s`1Ui_Ef%bX%60Yw(1gBf92d?=PfLh(IpPprn&}bS7@pheh6x=}a6_5P|uS zbXOy3ZJTe4y-Sk}q#(kYu|wDqT8Cyf5=?44Cy7y~3$%+W%!Z}U#smc1xEqyK} zirzU=6vR8)F>zn1Ygf#y$xX8@{I$b+ufXamq9btO%-6KmG!wt&Dw$f9&i0|E4kL}q zO5LwpNuy97=_X9-)sb$gsginy6hv4_p7u6XkGyR5s^LKk-xW|Gt=s2j3Ie$>3ytn$ z*+*x?FEmVB_zxi>$pqzQtkPwY+J3Nj5Adn05I_VrFy^r;i3Z#Y8`#=gJTu476pB(;I zKf+1R8!ug!R*Xg$5y*vkophQ!(Za(YwMeV-wV6Z;BD9S^i_GQnU#(4}=jdR+%EynM z0};rD*>rTjGo7javTcLULpoEfP@r9xPGo&rr~hkx^3aLg&Gp;(9HtYwh(IpPrla-t zJr*9ixP?!A9(o^;zlR9)K6E~cdR4S@&D4f;LK+dsg%+GLmuc=cPAcRzl>9kT5TRIY z?KGX?jXYk*YbEIiQV@auk#e2sev!sEONjR&^*K_yZ;i;w@o~A)o(;ZA_muCC&=V$` z_qfk$(~hry-CCUPXRjcT3uRLTFt-ZN)90wjm#Y>>u7HtSM0U_x-8Q=&QxOZ-aUQhu zkr-a%vqC`xdLOchbqaFdARu1cy@>$}D)EICYRWO6FEd0S z7y1%9c^`0^bt~0YdenQtkZZ$C@-kwH9+|rhQxQYQyko6qb(a$lE>I|lK<`6)cPyB> zjU6Gy`&|sVv>lNmvRA zC(7mQv`EjM(TrpqX*pXwojgG{Ebl82fm|mKQ8vu_#d=4dCWPoa*IzW+HC7(Gw@yJI z7kVG67vBAEA-i{z14_*m$aS{fF5$9zh2HfDV=5xF?I}^VUOQPR_OU<;BG6w^KHRZ# za%y}f8CXh_NI`_^)viCPDOb!bD@#7TE0F7D?`ZKba-D8}-jAt>^ybxNyBQhcLpOJc z6hx?TV#4ZHvije<#F(K4BytV?7%i4v{aNq!%lFv#M;uJ28ZGtZ`QM_G&)o7<;@$ru zeniVuN$%G+@>r#Zes{l?m&g_VEL!xLxko>AUyZNnoNyB^=T(bmTN;#9{5c|W_o0Y< zdXj$UoLM)jQ|sz7b9x3_+u2<~AQ$>}+M5_rOJ@3);#*^02&5n)@6uhues+p}(%n2U zQrNeMoY|lfkL_aS-7x;FvqK0uPTMn^)%{uW?XC5=;vXRfQeMr?4pS5KwVpFRse1A#}zG=xxg@Oq5yL2As zYd)$sP>v5fT9zXP5jXqNmzU3e{bRWKmAdg@b1ouovwByum2X+(Qon0|3wP(wx*cW{ zqg**s5b+cFbC=<<`hgsOu2*Z!L;onj>|8xKQZNF*mZ*Z+_#RYG?U4R+Pdh~hA~2TF zv@EYFvi{wXVp!{U`d@dWMWpjK-6@hWv=Z6gwA)KNO_>MG?~i4EQ{-p=k)lM*dmXvZ zcBzPUTL#FGxCf%HM@fcUXi-%}g|NPI>*&W~p#M({DTv6bPI*%ADOY)p>2Z3t@|6Wj zSCWt4u4YI^*mJ+}#M3ysxjQ_nv>93sZ9t06DH zru|yr!Z=7pJYn61i+vgCu(c&e3L>)3(pj>HVR~jwb1h?S!J`I0?I1VQXwMZchz(W5 z-5DN6hmTp}R?=XO6pR2d%A{4b_&LU>Nf$)18N(F>a;1!fi3>60*!p1%X^`N^BL2D6>DZ zl$mpPZv0ODdY|9*o~vhaq#(kh3q41!INf8X`5Z&_Fn#;5%lf8Vvp900T~QH3{1Wtc zsmod3e3Lj*5P`OfZsA+i+~9c*u>Rf0DhTAdxR|PXx>NRdg!#_xF3<5ig8tYp|0BJ4^=3tIzP(fMe41Hb9*WtYIb{Mxy2hFlnHsfdA>=vJW8cUk>{ zf9Oa-1V(^#NA5q9WbN`}*|lL#3=znMaVf2lHJBuiEnGkSpjcWwGwvtvg9G zvaIlImSod3-KD}l9Vv)F|EOtSht8H~gE#xh`wJA$i3s$MG73U}i!4wv-TNTb znL6r@<6o0_Wq%`cO4p<6brIqh`%XpdbRh1g%DGw#bmI zvtH+l{|5nn3CE4{OQ>4t*9N(LTuP}36Fi|7xpC=v?{id_6HjWPZ^v_NnkJ}X z@3DE$yrZaM2vQJ%BSIA&sM77{iq*XfR944IL7)%T>eKs}b#-4#6Ow@^!!QoQ-fG(R zB^DVLRK}-tCG|NFfiV%?^-H^!J(~XIeV=wMu`T4n9@5SajaA+)J5y;Ffa57D)JN1C z%9^Bi-lp!0LtW{eBLcb9b6&9vE%KMIU%iIYSRn-wst#t)x5y<$Mtl8MMMWSNjv-a1 zpt<|Bhf8WCRX0WoB5>SjSD(hJV#xKB^40t~o{2*Hh$qHqz1?P!8}46E@gjsm0b7gX zrfD8j@3s7nIjQdE`+!qz$c1A_?_-rkj%ifI%bx1i;wdWh40u+GRyk>2xlYaPRgLBq zQV^j$pVph+M^tdF)Hr${NI?XSf~LiijL0V?4>qoCkTNQL|`mID=Y^ra;JChw2PmcDG20JMp`RIH8V%`s+Ve`-99|y zjx`6i)mkfNhD!a9tlH$&W>7_=J(f8>yJ;^KDTvrl)h|rMgSOQPF?6AYk9@T}Z5{19 zBLxvyM}bb){JXcEMLP|MKrZ#H{;!ATG9!BgzjSi5aHR?qYX_gyi>5YW*h9~O5jp?Q zXQ@lQ%9S#g?IXljLLdbZD4WhStflu+;KbQ!o7<_HK!)Wq_^*c!>=uP z>v_u@DD?-oc=5T|KPKld_2GwauA(@tym{d7`B`$H@3uMM!&Z+ z`Pe_B6@_65d#P#j(S&2I>`1^zl3@M06q`gV)V7Ot+sV&m|&Q}(E zvMEohdQCwfmy20jr0#0NC8xFsW0m-%Y)8J*F&{??B1~N|XXy9ZBA$Oa^U@Vc^Yxzj z6$EnqtAob(+9EUf4z~UB2-!Pk9Lt=(#;l%XX#3q+us79Zd6Q;jovX=mQGK615gA56 zj>lQ{f-+2djFh<>&SUliX?^E)nxWlp#cV&*TRUJFwqIJX9aA?5`^XGqS#l#9t0%KM zvvp4=%Y`@G6$&D(XEq9t`NFWyYCwpf5m|a*qnWa1=qVj3h|s7i7u8!bY&liA@-04| zZv8x4+Ilz1Km>BR)Y&Y;MhhdTMm>_TY2A5a+_RZ-L!F-ug#ztnc8d~OCk?|&^#>@k z-?h7-#U=SubsvEUc>Ko+8`$v{2rl^49jR6DQNC8h>YV z?)G~3MRzzfQ^pT%r{g=QS?EG zlx>D82;|E0STC$JW3+0f^>OxJD%!Y@lqXMy3#1?-c=U#x`4(K#w28}KJM&zXOUtf} z^8fHSIkWm-|B<5;Hcop8FAf@!N6k#9Gb=0c$S00+ko;cfj%w`WAdoAV>fBj}B^!}B zb?#b>|H6hHY9;>Ex(^8237h=7Frr1a71xlsiRwY#|Ke$OAGn)m#dwWaU(QThaTAD0`xrY!h--K_HjYs*S?>@}QCBR+-*Mjm4GZi+5Cg_)uPn z6hxSw+I&yntG#u2?<|W_Rk;=3`4t3m{Tl(~cx_rKa%1w~r7F_)l}<>$*lO69 zYt5EW{gR-}2xDT&COI`ymao`he6OnFw~otR+uN~mbRRDw%rDj-T-ROp2udq4I^H+^ z$Hl3hQtu^MP`abUb`kyj2+4l9*@&ENu0U4mQdJh~SA=gHUPwL&q1rTF8;wM&c;aDx z8#Y^S*vR5wOPaQGe06#5dOp7Abzud8T&j#(Z%fL#skL~<@)rWzMS0Vx;z{J=wMN67 ziYG_;L(#oq2Yx>NsDePQsnf|`Eekh-b1I%R>3&!I^`$dUsFEg5QN@$yY_$*e@dOdbrOF6-vOhiK(`nnUA3+Kth}dhWA^9HDjc~k9^Wn&b&oPO_3Oq|L}=?KeC|UR!+%9}jub>3 zxv*WtUfX3P^)h?4nbk;M{$k-h2NjXCcG>Z# zlj$~~l8Hvg^53hyX}9(nX0vdn2ZjjbQeV!Do%Vf6kOsCTvp>_#CPXr&)_cnAAy6{NFRMDd6>Y&%-B@f0&8 zk`BgD%z!OXe&Ul#@@!)V*-Ou_AdpLy(XyncWVw!uS%VxTwu|ygQ++s_{T{YOmkx5lfGSgy&7PQ~c4hAsWTKc~= z&d`pT*`J?lHJ77$%@+PGsBR`u5TQ8{`Xr&-m~;31-GOpI&?+J3CbOV8st*@S?<2hp zLwVQ|Wm(K0BWsLK5?l6OGH^r@9rKZ@+1d6QK?&wNAF-*wbasdoH!Dbn6hx>pCYBl_ z2Q^I=Z7!!9IJzhgTcSL&71L$RqE2Gvkx?0lK(06S_K1r$qK(A%X0Ham=q^Y3M;Y$n z1vyd>q4w&+u5mJ7ziq7dlamIFce4#k?iolyL@l>H zBFHDwX!WN#6K5q3m%Y}WXXEnP42&jG9=1fg$acZ<@=x#d&yLXy+p5f{e#zn}V}l*_ zqzJ{-bG92UAI)C5?;9*V;~weTci(18TgY{op5tbOp;4t6s<(8tjhwf)9KTUKUe6ps zl!y(6=0+4j7AJVEVVf4f)L7K=xw;H0LMIw8J@!*5fWWwv#%g9yd9&&cHh;=>wO81a zY?`}by`fz)EnI6y7x^}^39l7NJND47W+AR}YYgpZJEqEblvrB6_@g!N?b%+X078vk z@AtEpzua%l&wrZEu-%J+(IR9D#ib|PGZnFP{_o28oikDhX z&O%Nzq#y#LTDouIZWVcW%3thI)$$yBrHzgj+CX~ppbiYtRP(H!A;OAwOVmaqK%jIil$erY;gk z>b7K_$HsAm!s*GwHq%{wRDEwf)rTwpvk^Qhr#@Wid8~K)?HRTaQ#eMfx4ROTW0X;B zZ#Sk!mg3wM@g#JGes91qu0gxnFEpawI}MMS-Tot^tKB@&Fu99mCWcqev7-iB- z%r#jgKkg`Az8%kz%l3|*{IA`Htsb@OMB~;a!LTkfXGz}Oi~Mq}sVlRrK3r=}l#)q? z?L-%5dr!Zk_Zzn2U6>jt#^`fI?qWB@w(9-4(v~aD-N{LYR+nO2Xo_uG;Zx!#uJj!cifpZU&?T{X-ZgRmOb4#C1qjY>{~L%T(B zuvWILr)agc5#1h9M?oN$8oe%CS4~tJ*-QGR|D(jzwi;9&XgkHCXF95Juon15imJ0Z z$&q>QG32sk(dhwBh*ur{gJ?H6UF<&5POd4Rtxyo5Mz0U&+RN324vOd5jAP%m9b`Z1 z95A$#9T}qO+{E9-WJtTVa;pC%W~I}s+9!%@!zp4h>r6Z&#PxPejYV^Pc9+#2d&+T} zY0dx_#y%=yQ{j42``B1!#$MBrf(VRc>8_Neu5v}$t75?Ws$A(6##A7i&X{~_A&=3` z3+*=C*0EiTuT&XZy0wurFO`=MNY{~q2sPf_7SLC2nfg&Y=$T(21>-A>oM_)UWrkdH z`K8~s0$u{+1dKm1E~PJF=McGMV21wpBu52-5eK5F=Gm}`QWW)J`}jD46hvSgL|I{4 zfSeLjmT&H`%)pod;~*va(B_vKC!aL=U0=6#yAm^?3^n$tc4eq^sdtOLEPp)>+r>CY zl`;75p0d!+J#38s1x1Div51P8o3Fc!d3T!iWk;Ao0fZ8-Xwm)X+~AdqtXoHoD-=XP zjG}3EA8jy_$Nj{!m%d^_GihbB=xW2dzmu|Frp63wQya?0OIET1bE+x+T!|l0p0=xA zIr;SXCpJ8@GFPGrj0Thl;Og3yV)e?_e8%!39HnENfW4)gPkLK@AC?H@58D*vxb}uz z>Kd8R_@d}mC@=3>kfKYFj@}v3bmGu?m+1CWK|XU>OO6x;0Wk`l?R$UK$PTH+V_Nwt z2#f~QUX^&rG6r?1!E2T094Uyvm`Kyc9iXq?JJIZ)&{0avfSy{7OQsIrCnVK9`}2Je z$G&4UphO>9c)#wfX5)H{1x;2~)li1w=e2g5mav0gOS4)L6BGn;VZ1`S$OQ(oM_JCs zl8)1qm;vJiHIixdZYw)|uY(wnF`6R<5x8DPH}@`C#V)rPDS}&%QP$xQfw2TxpMV6m zCv%q=yyYhafm|4`&^kl;Myy!q1L0iqCnaXU=mpVKJ*mI9*hVYpZ!FW4NCtbQLyOY?1aRRh zo~HHR)ST&EJYmk;46_uHzW2xa9u$lml|c{|E0Lx5YmJU^0>%#* zanM&$!zOZR#aQ9yYft(?QP{t0NEp>%+(ln^B|6K_zYRBDttp|bMxjT>l^3f1T`fem z{FFx&S@EZ`?t@%vTvBhtC^;q0!LMS-QDv0_qZ&lhdCn=bsJih2P22v2A%1GK$ zO)kji=i9S)Q}um-AH)%%9O0F&@^T>u-!DznZ)c1dRK%jyF7i{^-+dSNYpKeBZv*@a zrm|6Nqpizhkxds>^1ZskU$H)l#lbI2O;RS{)Gmd6!%9;I z8c@*ts21*eZdZAK{gW3+QoKVm_qr967w=Je*!bP=w?!?=#XIP zp3>Eh?UsaJP*^-B3hy~5lmL}Ol-rcI_A zLdOsENXeucLP$Y`D&s}0B`4dkO)h_l8BPCY9_D0qV9pd(h^6`rpRe$g3Xc8~DTu%f z587R#>M*CDl}i~xRc=L7ZIW6Oq}2HeRRJSRT0Q# z{{E30Nux{kOHOyGekhIVm*6|ckyhTOHhiXqdptRnT*qCVSBOyaWOh;=uV%M>Q~WB@ z=t6#)f>5$|wr;fWxW}J7=aul66%yzy`_An~_zNG_%7N-Sf8J+gzVc;vsbb!UkUhql zvc9yI(UWqWUGK6(Rm%CxOKl^}6M4qBg6&!C>(}>rO{gchW4u?7t0V=*05CwZ_N& z0Xe<;AL208pd0PdAms~<6}E*4luhv!Ab?BP1ENm8mlv#45wgUB?p#rQt5pR zaw(V6hh$)`DtRS#}^4rgJJ?2%3^4k%CT$s^H8A4QbsIl?Y%SunK zP@r9xILbo0y4(l~Fwc3l`Zrs>9=$FLM@=@pc+D(rr+@{YNzT4B5>wY4I%1Pw!SUpHuVa1JCroa zmb%~YIPhJg%*?azxwUyI+uo(~;?!qUHwrZs5ttQ7`f@>ZzGIM6)YpN*MVOk!a*;G*u z5egUN*=pKp@;G;W0)0M_$HAOkL`0HCQT;0;^S-H3vp197y*bL~3B@IdKrYO))il>} zWZ^F5_8H%R<}PIRBEm{~uC0)UHo?^M6?9gn`K*3vGw7@gB9II7AvJA0Av$LDOj|<; zq#(lO6Xi1$NHZeOnl;asl4Ur$G|u}BSq4NP7v@7!W(`?}zP4zuqg4M2DTqJ|PW!cF z+jHk`oYLSwwjB}Z6RGAIA;!;%Z&d6*2;@@iympc* zRfe6rXs>wZlXfv?{VO9O-j_L^ju!J>BMcV@(|_zf(m)<^Yr}>(*HsY6g|ewSOdhN3 z|K$d|F(kLrD?}745G^9&R~vZ)&G&I}b`5EF^f4Rn?xY|TF7Q5dH^=WqWR=*O{BrD9 zfu0Nz=u2oH$7+!gEsFW+z%6~=_{ zfLs0ikV|9RMbi0&hILSLrXq6ZZm1XNJ&T_YyJjd9K%n=b)0uV-`hYPr__lX61Ar^o zpu3PiFETR8s;P+kat5otdI}HpTc{%i5$Js=JE8jsHuwHuzHMA4Q@DyyEu2!z46jVO zT}APOOFw;NO=kDvE|M!08z9j8(3u9`OKj|#TDF=KN_yV!TzjS>(vo$) z=iPb3MhK)JqAm3>yWn19JoS+FYuB~oA8Oc%eo3Vj1ahID*R;K*TzUHD4BKrZy{wEuCr8vna{6`ARDjUfdQ=&30?;XS1r z+^8W#M;75oK}2xcR-x@kH!@qBSuZzkonU_r?j^hRPGX2au8#RBKX233=Gy5tHTMz==7t{YNx`2#-e;0dzZJSU;JuXzI**Y*YSe za>tH}3Ie&%x6>(zq(XYzW3%MjQ5gnO5P_bWYK7hFBQo5kN#7pZbfh5SX6_xrqu^m9 zai|$HoV)wCk$3z!xw-6Cx`q3H(FAg#r`ELNzdR7tuKy(UlT`(BMQouR@S7QiTRLYd zqWYRhF=<~XdH;`h0x5_8ZDTq+N zowrZxD*c9)5h9_WL@xB_D&qF-y0Y1pB}PwQZ;2E{s4+u@=vw;7zEgC&_Om%!13!w8 zttBFiu!Qz(lM}_%|3n+11RSjna)Oi=6< z+D8@ffrT3P+8<)gM~&e~L4?Z+`i?3>xmc9HO_>AvmiXAG<|+k|b=GQ)Px)bnu@{KXPas{8q>vEp&i!>Ne3n-7aSmumAiPL(-Q z5MixGXW}j`F|_68>C9Wx4~xjR^|-dO0!J?N)G8vQMJ_qS<==j!r0QIQO}Fb+}?ovyTzUuWdwy6<*| z6huVcqqU6rYmDpw^V=ZpX;&#f7vPQexH9CzcuqysJ1|bJUcZ5fN5vUZ5P@+i`HwN< zL6|pSe1lcljzW6+#F+&O>VrX=& z>krVGYIAg5M~#zR#b&Yka>1N$fFCvrZI_COOztALBo&Y+E^>xkXi-(fjQBP(&#L@# zWY3=&QV?M^=hd@xL(7?0@?sr%?Q;#eZ0UN2T<958#H&0`a9Fqf!0({39mhXEL?x6NVH-pogP-;^NPU;J<3h=r7J35y)j*M3$jAowaOXT86Jh z*N7r@J>{HJRX9=*fxeyA;jWAqmWCB&?PRNhP`HXyl+h;D&~m#W*A1`)rY~KkaP;0=X~_q8+SF0L-6BtQm8r*SQvDJ*0f<%t&-rQEuT&ApJ@R$x?^NXmDTqLAri^&1+_GYGl9wM< zhd~5#siy~msLIWZep|g0smcvf5P{lEcdXB{$Yx8Mr7d>*UV-MvDLS;;cm|KE^-QzK z=NY}z_SN#|NI?YJW6GJBXpvhI1JcfWs0if3F{C`1IkfLwwNctxS9Np|f#XKCiX$!3 z?ablS>xKO}o;X9Fh^O{6?G4ra*uFep+Uqj@T%mwRR?qeYP@SS9hdQR&=nX0qK;S4) z<*#Uqe4lwG^+G;><-8h397=Ds>r_d{E^YUr3&qsuKm^7TnszGOBKMA)n`))!z_t`F z=%J=f+CaTZdgD2>q`z{O47Cfjfc7BQTco+uP=)Gv;b}1B!n12sJ!vcLjAjLSfiU3eED8Aw5d@_gE#CoJ-n$6=qIf6{I^JUJrJOK4ijFpI2wHQi?%Re?f; z!Udy1H$qRP8gzq(c@?j%+7h%McnV6>j!v*hC;M66{`LGhQV@Y&Thq3Zy(+O`hj$3s zD?}g{p2wo>9U9%bQ-*kl(dZ%t5$Lt)t`xGO<<1uLPNOGB1ajefqWe;*hLHEZyN^E0I;a%{T)$UnlK1{sp~*07H=(?LD-aoGtta}fr7BSA z*(2nO|5bs?p&&x-)u$O2DNFvAJfMa@$9fr_19NIc<;cUz8*~<#-p7dktq+wZuZGnR zum*_Qt5ftoLPnnU98d29DTqLMw70#Pv^Mgjw+~epLkc3)Ugf^pQp(|@blKHec^`;Y z-lkUPQ&Tx({th4SN3Ienh`GzO)?!Mm$ffPij z?}KVOGY#|QchI`++9%f0BTabrKE4oeBFC~NBqbTK!mdMt1bMuZd3xzVa(*f zU2DwIpqgj@A~OC({HWrA2;8Bgd*bTm;=B6LY44a@EO_P)F{+_6v+G@r6)C?*6!CUu zPoo>K%&v4V_V|iSd)JWW?uR^f{OC|`Ua-)81%X`Ii=u?f=I8qSN!9rgwUrVz3TipoJrIhal1X!el|z9XsZ%Dak#rYcjYrf3L-xKy;}r*F2=Mw4G1wWJU35m zZI!v!Usn*wCFbrB<9{v2Ds-+!h$gfXSHH_|DMe`3KV2Im>}X~L&!9h;G5BWbbS5F@ z?Aqa(O?!9vK5*QyCHmT?IqTTK_t4V+$Up>+A=N1&Z;*TFH?PvP8;&xtUA0$_Y42{K zW#OT_ln0Ra;BL_|tprQlSdmpMx<|y&?7N(=BJOOYK+9 zU*hQE_@F$B+t*w8V%gn$WhoVbTx%rMRCdcA*qk;s6uR+IN@}<6wCal0dq-?6Pex0G3~GVY}k-^5fD_CT|Hw~ znu;?cvfnGGT%r6#L?9PWj~5S?m0>};i3pr$kwF7eQW{wNdDxOzaWT0x3w+j)t*Rd@ zb~8t&&1$5`qkT^L@><@)k}{sYybyuCLfM*jiK3+h@3kpiC|W`;l(D{PtZ3ELiMb6l zwKkZZ!&1a6B`-ymdDg^>MDD;E&#uR?UG+Koj9T8b0cNccCkAaP#au#F z1hzz4JF&I+{bYZ6z3cA+5y%zj7B2#ymS(ZPdC-&B6b0qX#5QsPt(zbP5o)j2m2j1< zmMsvQUwBGHAlKTF@nYi0GVJ~+Q^p6`R%U#uBO24`U!)*H9o_T))R7-r{>rl2l~EAL zg>#I)Qkj$7JS>~-Dpp-VAlJk+W0x5{V*+b`@i>x!Y z`j6*bUA8F*SWu(>ysY0f z9TCVC<`FAANC#bNn*O{)uRmCP<;r|;rOF&Bh`#X2I8 z3-yM^isHlhPnvj9Mx*lNPW$(Y4Ue2y;y(?QG1N4tMO1D2=5g<$RCyRj7ZDwKtgwwM z$E+pIC(ji^YXHBV@(!eL14JMf&IQ`%q^}9b5f{A=69OrS$SM#gayKl`E*>^#qCHu- zm3KCJcOwgj2;@R7pjCs_7TKrMX73b7e~uJHoO~NcH(ZrtS&dAM3MUJ9>E1@~yJX=I zfm}Wt;)V5~6MI(Kvfq%7uNYdtLJA@-ddG`M$I>h))07cLYnIcy zmhy6?D&~kluE05Q!v9N2mi^8gtBthIP`cTW6bJg+Mg(%HGqDPN4~8$Qk=lX22a$q^ zfRV9O^|Tb*aMFwuThfykPpa$v8_iurAQx%@-AqcWYQ-X!c?Z(yA_Wm18~2K@`yE&# zchhs$p;@wYQO2QXG)oYHT&Vw)RlL|D%M9dRK~#+$DTqK_p;d!{4aMCHGx%xWaymY3 za8#VIJSxfTOEqBFLrtsRaG!Ca^JM;_@qB?4L=jm;iQaF_v3hy3xvcyy-B@|WML{4}wL-DN zrD$2wS`)GVcdHD38e^3FQcXc1mpWE%FDuCFezm3Tv_4mNisXU*va>8I zk%EZqTybJ*q4G?tVvf}y=L|9I+$h=J@q~d0Qbh5rJH2 ziRj6XC$LF9`tVEBGMPewc2Uzv#)&hm%x^>Z>b|v@LIDJ77wur}uPXl@zBuE}ajL)% zTBL9V#);tD^j$mMv{xINR+VL|F3fPWH0KJ}hj^hiv}f978c_w&IG?LrSZG`N+k>>e z3q8>Qp|qqW=5muC2DxYKs@jArBYGr(DpQnT+Aykai!Et;Ke@~Mc?S9ZI*O|@5CQV& ztLQ~F`MhaBMtl3Fij3g-i6T4Nkp zD*x)x&+l1bdV?TCX?H4pEtR6L`2cg4oN=roho9KsQ=?i7j+PVKMR}SwH`yY$_VDvt z_m*TpTPOo9k*0;brrRU74bG@134t?i&|ab0(=55rnBknJoQdOAC0o?hZ*sanSK69P zh*~tFv9x9dvgvCgtFm-xpW-{RQwy&27sgFPwDxyT7wN3G$rvBnQhD;=j#Nu+k|VP& z^I|v(6kp}5EDIm1=jZ!P9V^>hdIw>pnby>cA(~D#4y!7!eO!_Lu^8zfXsrfMj-yVi zYJXLh-|Ci1Z{Jjvfe4gG>kKWb%D|X>elG6K)hCCiRmM=e_N2JX^&(Js?+)PDuJUev zqmj;AoN1d(&zXMlrFfN`Tl`cih^iF)?`aX8^M6}OS{L;sM6K-0qJH5NeWlAVj-!}q zZ=%aG+ZLLy_-?e&CHF*S;mMp5XpbH#=I@XSOj|+i!ZT4uysv{?u%#huP`E8eimf@t zZNW6dKa+n|X369pb!5#7BiJ6t`pVqZy2cCJZbFPA4`5oKP+Id@W_ld)qK;fYwILff zfbP4)wvY=njp~s(SmlaUOW1=U`w%-_9(XgwD!hQr-KJOz>JlSlVO8KTxGEWeqhXc!U ztj&~B(2g&(%Fw7~A~~q6`W)ahlu^)D=gKWt#yk^W)2KodJfW?5oUj{Elv$(eGus!^ zkDEoAEuH3==A4mBj-2^G+#9K@2;_oMpghZ2nPPsHP0R`yq>L4gkE&6n3#}3{DMdxt z>+#=p@Lyd^JW3Vpj+A0qYrUv~nWCOWk5+7n!gYzpZFPBOYi`Q8 zUTLKWcJgPwzXmG^4Y|+~X$Ov_h~P)NStXbLiuK8{UH{rE>u#Fuy~&n5F!xwa`5hG< zzNE5$w)RvI$fejW?Pa@SvUIs;Y-9>$PJ;DOxaj|Z$6T0J*NpV1Iy%ZPv`RFxer*L| zqW_-@t(~^Ow}-s3B8ZKe@DJ0_;!I8ynQO~4YoFSRZqj+R0fXh18cr;_!F81a2-IN8 ztvxzKo{vvX583sbqP56{8cgenw?@bQjv||@h|6>0 zSzP0Pwf0{Ga-pth+Ljq{;?&JYENyQWjyi!{wg9r!Z=5OWHzS$eLlZ^Yr@48lrL7f& z!evkK!xYk}S*C4IzpKg51q<+l_3A1J4Y{@u!nZPcH8ZB(I3kzqkdU7bvi}bPxlkXq z=Y5&{IQ|uzwBs*^u}F|LK}1e-W-jUE&oScA{_y8Aw)PA5TR}nqMM0o8YYDsi$msi- z?7;pwMbEQtB?zlWC1zViGaNLSvZ;!9m%Bzpi4y%ED*Aysp?Xf&z=m?fQ%xon(zv1% z5M@L*ryY}7MVYqTjIT;`s3Onh$tzjB--JBS&7K_pB9V zK_wdg$2&LKw_L0}VJFK@qj(o|5Pdl6BdxGBerkja`z%Ti>B~{?kW1CU9(lX?9iC8F z{Iz~2N6oQ(h!H7=O0(`sUJN}P&8yN)^%gIN>MreObEKTT8Y5zgI3u{IQuO7 z6GhOTa?E2*O+vUB)1`l|`pk3YB^?pSwe(%0XtA#hd$rp{GGBQocVNyx2q6Y$9!c{9912H+3vA3R%Ev?!dx6_2NPyK zjn&ZhVrqUjdAE`e#~F@XIFB{0W2*$+&0(&%7dcs(yXXyY9@BnQW_eb-r<*bPT!=Dv zkqhUsrsZyUO5fS*EKBH5-T*wnbC2CZ>qB36XFM6&d0H3kHq4mbtTG?brUggqtl0M2 z6klzl@3ucp+wPw2C!+HB@+zI&6hvmLy~1W%=TcYZ&=6<|z>f^#P3y_`H&h{BE<3hJEE&hm(I)Pe*GoNlV&l61gkst!}`8v)xoQcN+ z6UD@pl;QEloV&wghRHI;&x!I4UnvOWLOV~lK?S#x-k~Mry^eDjQjC!a;z3d|W(laR z%xTh(rOoBQ&!uJ7uz3mv5jgY7<5bNhXWKFP=ehe7m;di;3w6Sc$BAU$A}r{H=|AS4 zdMq-m{<2-wX9@zjP*-Tx`Epm$$f37vvHXpqImq=iW3O1_QiOS|FyDDVdYq9JrOPtw zYjD&Y)Tq;k_lT1vin5!-&6wer-RJf3mCMRK^V@Rt6NvVhMiH4P&Jq*NZ-egp2eYA@ z-ipI1Jr%_KH*|AB*%B<<*OQ?>(q3w@>Fl}dcF`?r1V_rm6)~b!WGSYV^J1uv6j>f# z!LD|nz)m$7!_l*#rdHn`L-`uzncW>TB6EJ$iDkEmVr_pPr63e8&}Mq_D*A_;HcYZ4Qz^@J72h$@nN1fFWcNh(R1VqirFJFvs{>U zmH9r#L8l8% zJFqJ%;&|~pV$X?|Ja7s5b3h;$+7;S&?$|^2axTP+|6a*J|9UDeL1b>J#3GB-VrV6( z`o+EB((Cgn7C!5=ft0{ziNd;$JaVm?OtmGo5~s=@;cl#6uDSv#?SH24!7;SUKCK2r zpQvd*e@>P6YSw0lKU)M+5V3~VXPi1ZvCOhH=zZK8JyROjFBqejpE3}Ua)!KqK}VM8 zP=lfEqLUUSr_1zU2QkUhMIZ$c$MzJX60hn-&K*QL+9?CZqba^ldgioHTEv|XCkX!Iub zXT(X7GOwRvuaFCE7x{DdN9=~PgSdA0Cytg3xgxw`L|`vR=F-^wuKkde#@a6&YUFu5 zT0tNeT07cN3{Pj7!-7~H+fa^_@vUM+>5^sHG_s;-yU3r{o6hn%P(JF`4jgS1TDAY< z>b=9NJf8RA$F2y7ARPqZfY=cm?d%=}6crQ|6+70Tv0%r3G}gpIte~PGh{lQ?fwPOf z#*!Gj5o7OIWA~ls`+Kh|_kRB4V&*ufPMnXyr%8SG0OKP_4whOZ3+UpP-D>7@Fodz+4G8& zljD%084!V5g6;^XPm-&W(!=lP4^ZSBWgF#@WVZ)dh=rfxYG@TA697+SKp-djcDBl3{b=rp1DyFI%%x0DW_$e$<8R49l@ zrZaVM4>v4$Eq#rO^{TjC1o-$c)9(%c$3xDkwng~lQx)+10V)L$ zDaW^qlex86-p~4)PdI5UtBmQ&Tds_@pdXD~sdPWFG@%yD3~NA$Q(Iq)nZ5h-+VOFWHjb=OQVWKfh~Aj|>B)B$E@6}6!a3>>)Hp|d z=%vL_cQ)?5Zlf-`SXhVW;k?6gJC0f=?Jk`^%=86gUo)oY7_IK&0@n6-SaQMuzP>@;x5l`sd@>xlKWD{v3_)p4%Q>7mA3qCe7buWk19T@=quD}Dq>T$ zSH=$Gl6chB-xUOMq3)tPkcE-LDK&*}scx@mIMiy29@DAM6xQ_IR+0FY7SWM3f8ZRjj<)>>`UPx+#!?2vuLze%Vuw=|(k+8ov=p z37?WDti4=V<#z!Ly#ac6*S(Ycpcwpli5gue!;8&8~|D zL$@giN8a>L3fIiq5nqOVY^q3$9%Kl4O*jCPS_ZkLaDo0c%#= zMzZn*|1+jh7{C^s8Kb|$#jziW<|(t)!#GJaHtbecTra0 z;l4aLrh*h+)j8@YKik~K8L1?zCte4T@>*WE%-3&zLux^8gtZS$c3Jh zrcK%$Oqp(nvO}Y4bJS|crE0kF%ql$Q^e47!Pa{PqA{S~t(z}r!yw=Cc{M1j5icUm? zqV2TOw?D8-mnZUwdN+)yWl;MlT0*O|cd=;vb_{=;<0Q~~LH&VRg1*G1)RA^uYVr}M zt|)Sj+5jb(?$D14k#SEm*)S(hiBgMPD8cld(>PF0-nKftXxUSN@{C;Qqi9;`?kMSV z`>Lg+x3@$JB2eb(=9vrC5gP6#T|T}OD9&-1+np ziAKJsZnx0f{*iKi-cE6{jT?IwU6Jfhy z&O98YtRSu$?qhm0I?=%YwQ>peZWyT`kPCaOY4`8>@LF4I6pfe^C2?2d9>bZ|v??!s zxbL4~MW08i2;@S0rD>V>4E*W(CWSTsh>)nyaW(N(E7jZHU5gJ%|5$iwd~1ong>9g8 zQBJ3Nln;6GfWm|kkrFA0!2L$?l9vXa^87_X&r=Z+U*V$tPaw+YbN7Q`C(E^xxVAVB>@9uiclYD{UHTW=XLDKzQV@Z86zDuiS^n2mP75ueyatK(8R7}u zZYiGEmR+5*Mx@U1W_Gn=SRiHfywKH~c~8`954@pF2oDO~LQc6vN~9n{>q|M^Zqkj5 zo;o6c+8C1(5Ym?NGav;K@i)@Ng;Aa?|5*n@j3K>S|Jq*%mXh8rdAL@*cx}x}&$VR* zuIb|H!Wt~2F;yUbl`aCu+p!BLbi~u`lz*j6Qo%?~MPPe~raQu24LrWt!-MbJMapWs zGKKABCl)`B@>W9M&0E%s3qE$Nw7#BA_ZRBb%oD>}Or>5S<-^EK5jV$yh2M=}$}ed? zlMOsNU|H~sdXX}6MyA+Y!;QT?5y7S&raT?nJXuBfm%2EKm zLIn1Zbi17kyZ`TGxwuRPrSFK)j;s^ORp{pW0evSncdRPD=1rA}jdoa+-vX{;PCMo| z8&=Xn&qC|nv$mM=E=AhEsv{7gaKTJ#S}waL!l%c}-Z2O1ebRrjh6voD^kuZoQ{k20 zQTja37f3BK`udFE4lG11i^k%9Ml6DZ7+ zzeakmj*T=)ucC&mos+MEKrY+l4I*`%8|(dxjtKaUhBkBOQc?ZoDBkR+_5vx0Fb`cXg5T5K zkM*(C#_r)xqFc~pe#6T{K_C~}6^a4$KNkLB#|*yDJ;;a@L=@l25P8SFSxKO-ed<2C zWvu&Q8ecYZmV!Vov?ZDr`zeRnh795pt7a>f3=z>(SIV@#CM&t#ncC>w?G2m$a~vPs zVvB-6F4T|YEj@SP_bWMY`?l3MQV{XB6=}XJ^d@p;Jhf4&Wec85nL>ga*(eC)Qnly@ zhcI4Hw+`#NxDH1OA~OG7EgH6RVwY=lr8Y)Kx93N<4lbOQ?yew^OVQxkxwnmYlLy;G z?@R+n3L;Pk(~I?8LHtGC*W&wzDhdL*RNd}K8JhmgYLnlXq8})C$?GY1*F85Dytp;P zoljrfDPB@-&58q*mrNoB5!(3;!n-`}_Gh}6VMTS~^n8~4$uB_!a-pnf+74=?`5yO! zdfh&S0>6tpU(-I2t*!m>Jp+0hVs@lUdrUtLDRT0RA z`jKw$&^UbSRSXFvp8+X|5SiH`F3f>>EYvfM>$wfb4mo-tm*xr)$b~CQ-#-YkY|qgH zn+SmvL`=MtEqa!5W^J44ZJZ%*Fz_`twL>j*=2R$v!1brE85Duc{bNu_ zObvA>D!cC*)lDh!W#)Ujm$8TPk==h>7*c_12`PIQxKIaE^`T(~-gi$)@IS%i@1oWR zgl12(Th_p|+xqNYpn6`lXD1XiasD3!aG?&?wD;R7igSw>3?aW=p#VbLL7Ms|-GFGO zYwEkSud=gxhxDd>r67O{bugWANc%WS>yQ&9gQ(TEpGp_r&7Ih?YTa34*lLk^wmM6V z>qc#Kr&^7>uQUj5Mm56_fn2EV=(_YEcvT$4Jy+)Dx-o^ z$YMHqAp*H@PgBiF(j`-UR)hr6IFNz}-1(FphI-X~l7C2F8VAl|-taZTyvLg*#>F#r zt`^fSX?QB-KyBJ3NI^t#&}xwv>%jv1>2vkt0_xT4;(QOPGKL7`LVHE=E0WqVuWz-e zOj3&!MBuDbc4Jz>#m3(c{PRC6hzMLws?hEGmGv#xM(%Yv!Ek;|beb%#ZOc;X^kC{- zRk?VX^%>MjUSDuZp&;VI8mehgiL`dCKJsDT=CFjNW8{UqVG07d6fL3c`q`G{{544) z{#sAbONc05pDAK)S7C`y_1!+Z$)fQ4=Vr+FuWT&%TM8Fw2|BB}b{5f_Q)DOK_ZCIt z!0(!#Zx9zclYX?(rPjU4AhF@qSZSBpSs((rRPA%T%XiV*FG_BuocBmUg!lX$p`D>` zA-#3&(|p=@!EbVT^Vr`C0=dxo(5-vXK;9bmUW_eoE0KbT8Ur^9@0<3l5wiM|`^Lf!J`yR2Xppi|B+hnYQ%~t_oK7{#pFM0?{9A*9KrYn|?yb^P zHd}OwSqle=6hs7G%@HQ&nk?@x{cI5Ov94S&^$DBT*hxVsT;SEvZQRbTvV9qUUc9nY zC_WYZuJ;3~O7exGM#FVG=)}H=kx0=X1>r43(uS*#4`$@6<=3Zx*yw2mqU zRqNx&&B;Cvbgu(?Dj^zCBYs^=6aOYm*Gtxyf>!JMnGrk20hnBGZ#< zZS|$wjlU;QuT04``MpyveB!~f91+NM)qbt;-si#W7WX8?9j{uv`6efR`AHcCfn2Dy z>Dxp(Bfk*Sg@q>?I8qR?eZ?BFiL%l7B=({o(O?5XhxkgMO>RdGhKc zam3b_BLxwUzO4}@HulWCQy<5cGmJ+E%@WZkJrx9Up=~Ebe}CTneR&yD#g-!l5ok*^ zZNnme-hXaIIlia0f>rIS zY7hb`h{zj~EAq2lSYU`AXDB9w-bOarT0|fh>J^HxP_ObX)D0d_Z6E~^(T7P>^O`Im zR@ZQB5`A&66qCQBzKTFDMH6XPDUzB!|6NFDilib15vV1ouBBet`sU$~nROy1QVx;_3V3#&xLfL>e+}uF4PkA{)3{mje_h#A}Lyn6hve?PzB$^GeL6F=yA)@j zk-v-m^WbzEIZ_Z|4xy9xlq!_>MUPqTCqFT>;LX81#SxxA0jTn)2kCGT|m@f-Px zhR4AncKT@oyb0t&OHDg5ooaedcprS7s(>Q}5m#?*6vZ>`SYAzimjn@FWxegexBdr# zTqp%(4e0#Qc%Mf|Je@y~f(YFC6iFqY`t0=X2mT>19JN8qzgCN7^_*Gt?B49U`x=q# zYtL5K?@hgGPjQB_w+}U+NpS{5AQ#F!or(xC?R|sbYJ@-vB2eb3#^F2z|7FVZ5GSf% zixfoIRa`5~*D30pt?R34v+0!D>QjEWzJlQ6B3H@q3=!DHiY2$zb$bqFX)f?NnSYAT z28ci|^h^I=WoxVZjY1nz)Bq`nFxRG&a8hMv8lXp`hR&sW!l$A_*U~r;fn2z!NsH3R zZ(ZvYy2xAI?TEmAOt(cyUyXZp=-{8EuTXMOqO{qWVtyTe%G}e1dUZ3+z%7NJ4*Jm7 z3`8JT$rC!)&i7;HllnNG(Jq;Owr@x-?Gi*F7g|x;iPT28LuyESY6B^VD4vlaijR>8 zP*-1%skBR)&FK}|k#-3pkPGcDeW~7M;7vEp4o&?UA(4WJu0F0{Lpk(5Th@WHC!9yGg1K}2%ZH6k(0ow-Eo^3j)~I30F(J&;9F90dVf zC^wq6jaKmZsdD+dsSTvy@1i_vTCL7j{4oobDZ#fH?(k=+Yel9z-LxOlo8hh`tG2y7 zZ}vV!K5%-dP!zdlmB3WuV(T z3AaU2WN+E@=3IdkL=i9!{^5iOe`Afg*5)sISmVv&w@8L4&;4#tsZWW0XL_|Ky z6&ENj%eFX-WhwzQZLI*A_Wm9hfQMd7-#nNh;9dM zD7#qVxki?SP7M?Ua-pw9a=tEB?!VB0{o24@A_WmW59NxuXb+YWtB<3}GGDp2)30nr zr4|YTxzKZ>>UI0Vr1i`SyxkAC1yT?Zw``-xY*~v1M(h67ygP5iwF7?KC*DOO0=dw0 z(zHi2t);bW!`+so3#1^zY)|Lf?sQf=r=JJiLS~BT$A|DWRre|g1^^-1wibhKS-t8-(esAKhor&x76fPPgp;YdUZLaG3=W$d&muQ>JdNuG=6hCbI zhcz7fm>~kW(3Vh?wyZDT`d~U6{zoWB3L<_RzeZeM?95uX>Pv0Z+7!b-9InFd-*r?F z$feq-I}wrGrE+yqwv#tU3L?;-qwE(4Id{L}CKBrUaik!^?hwV0=i9TBNA!^=g!}Q6 z`8P$Up|unQa-oHzS3-4~^MJ!2M7Nh^6a;diMb)%%XAH7uqHRdl!w7z{Rjvpc=g1O$ zVi@YHuLtKXkqO&pm_usdGp{vp*s@QV@X}m8wp^HptL^P6huQR}l)A)kb00 z!zWK9;A7AwWR{S~z;+PC4S|E=Vfa>Zl@+D{<-udK+#|*AzoOt7{+6pAE9n(_ca-QO0-k!Yr}P z!@x{d@eDNs>MnX^I*_vbAFvO5$W#P!mF%KB6Km=0?4^%m&NhSm7;FgZQznul1rexG z>CNa7gPeabDa7GLgn~e>{7N|@wSo_eE78|uO1eQ_>b5u}vw9>)3L?-lP*z~d*n4`R zjnU;!D+PgEj|%8qyN)7WQr}l!3Tw;ZN4kgpKBy%}3L<{mxKXs4=gEGnqg%D-a|}|C zmst5ka-<*vZ6bY-x<)l8H%trjyb+-wkgIjeTv6if%KYo-5_Q?yU#8645<2!uD~=RI zplzo!XIDSj*wD9d_?QRTCAKy zrr1Psq#y$IJiRh4PvZydJC2=xvlspt^kxGec%YM{=Yf0_`q+X&6BE!+B@O zpIk*CSLyDxA~4>AB{kIB*xQThm|W@!_F^bqCQ$!tqi|8E5sk$oASODw=Fq(-=C3gIA-rap6fVxwn_CjHzrT$5BO$gie&_s%l4u zz80d%Tk;K&yQAld_ltdH$pMP?m#x9Iz5^9ow~;TV@)=RFHMx~z^2ypk)N22)kE ziLnf=52EQ+W7S47sM9v~T=+@T=vTo@ZV`rr*>$iKeq(bjl|a))S&Gpt-@To*Nid+pjAj$9x5WQnzv z$)6kCjiLOL4`*D;`mRsrH%D-lG9pt1PVr@#JrWpdCAzWIcrmkz9myMcjHL|n>xDU= z?%a&(p>hFQ)3T<0WxsI~f3^QMi!-egfmOVj`F<~k8a3_gI-&W{s{)h$?anz!<6hUI zc>MAc3@M0EdsVMpT|S{~B_0=7iMPw3uaieTS+q?bhI$^+nzkaG^Sj~8*qG6-+}%1u z$VqN2y0i~N>w{>z2QVp$-#6S28}Pt~hrFWinGc=V#qNC>+C)TCCN^VZ{-=AEcpvJ| zy?KU6qXq&pV%v2G7U!s+AbU9n^YPD?iq!Hx94Uyv_9$!JuzLLV+VV1~ zRb|Bk!1h$V+iGMTK4VS=+3ji-rB@CYXx=<1F4na-QxVmBEfmcnK3cXlAIF!hChK*< zk(H0>$4vg~Me2BGmeRN%Gt+AYt*;Z)_Uhx<^ZmMIq^+Nbs5^ysZBJ|al``Vn^<#)G zq1$5S&-Sc%la6?LZm#fX@Ux|;_XLg* zWgLx`JYvD^pNZu)B9z(vEj2^z{Z^eBDADlhfOX=5jU7uGr}t`CK_<&dJ1c&j(wid% z5!hQzTYS0``*!oZ*!6v&f&`G0>l* zbw;j1K4huwY+2>?x_|XG{)92Rbbx%E^^l=OMzqcROfiP;6g{%^AjGY-`Ns8w+erT$ zFOC#MXfrcKW^ekUSXtK$n<^F=qn?`NtSo=3UGpCW5o)h~OV1Pa5AGHJK z*)XkqZ&rMgqFlqPvEm`L22<$&W9?|o_4W9rBwXC65h3#))KuE=K9eQ9XH;dyO?xox zEyWWn))F2GiL$%LV}*hU^f;(0`}}mv^Z9*bhh1M4j|CC)UuB6)IacH+>YhyeCOg^9 zzr1Lk5yzGO;tu~KOPKv^nO0SwtChPhi7cPL#3}2J%E&d~GQS|iU2CRA>;CSCfU2@W zQ+Ls(J7r48-yO6;P_j$PUrbzprcGkKSM*=rR%Wd(!?C|O4s8S7#o1Ps^3?18ZXKgV zG)!wRgDSmeh(NC5#}r8|Lx>Z)_iERBjabqoNtPeKLO~!GdTN^1=l9C;_`yb!&H2KR z3)@J1lr1X9(#S{XZLDl!EqQ*ZjCpiXK_FM)0{Z@8O>v*b`q#dTc~3=|vHhjS?iazw+)Ras&S{fpwE4^?FJ+5+L4MAe6I7GZYP^|*7vPHsAJSgdUy#uW-6w1wHi zG?n(Wi$1%b``XC2jbDovg7Ti@+9H>-9u7;KUcw%D>;J!!PRXAA8Ht)Pc4ADj0$$W~62p{zUONKp_?bANG%inDKRSW!eLhOoFhw1l&Y-;N%+>V@x}O*JQXcM}P@;autaVe0z_lEE12JM@s=m;|(tCx+e? zeQd3`(qG`hnWonRl&R-@MOPX0vX3(F$aU!-ilkn(rPpWrdi2X|El<7ilFPR4HsZ*U z3ul48#6?8OIUn8Rp~f)+Dd%Ey#Rqq?eI4SMG7H*>j8J*Za#b|WufmlP!pO0Q^ljpX zQD$BKQ%tE}i7OO9B%Yyhq?4X6(Pgk8Bwm*ISCf64eJR9V;W)5|l$&Z;oIE`1n{eBa zF0jAIRk>%b2wYH|l{C@MA59-bNWZUhMNWbfS6YW&X$2dFR!SCUvmSdbYSl+(ExaVI z4EdE|PY|6vB3Be2wPT4z`m4r9v3+IU>y09+VX;tJ-%MP#_AIVWM}}uOiYJ~PDU;^s zi{7=f!?5r8y9MuZh4)Mc7EfzK(ZMw%<^Cc0V)!v{3nCOQXpd?^%o!vFUcibQWmmbs<_!*e24!AR>YtvB4V{BqY;IddYHdV+MHH$d*5yIiD9D2#MZzDyohwm7!l=m3ALD#JYGmYz_ zv`sp3bzAA)zP7mR?V_wXBCtLBjuSRYhL9f& z7Th3?A)0QO`V5hmmpNEmf4Z&o3deyxr2D(S50X7f?^&7-`rdG@XY#9Y1nv? zg^aLP;tUumz}Nt3xSI*m_2PXNk^8Gat^pajB6Xn$E4kQ_B{!x$){I^QKG(lAWc##~ z^A6ba^B1xe1ae`_fhslCoFs3IuEW;QNgn&2`kLYwHC$Qou};kHTCO-5x@Ks7WT3oV@Q4jO($Ink4Y;s}^j3eFo4kB9 zgde-VSzweSIhmp@bSudFQ5?g#21UG%^pj&ZR$)cuUoz~wIhod3xH4@j>DmtQ!-O#qu?T0BbUKal~n%$UN zhH5*(2yYW&od;!+i)V<|v_!vDvGnXXzWMbA3&wpit7nV6)pSFBM?6!bI4zrWkZ-?T zXFpZ^L-{RpS?WnuZ>BZu`aiw$=@Tw(PS)TDKJ8K{i12<+U$7=pe%adkIPSFkC^lX1 z!(;49jM%G^Z`tC*d>^Jgq%VKaL#i2eFIqNgyO8zkYRi=o!pN~bdXd|S%UMnBd4t>A z8McmG=27I;#89ru)w)kzbzcKnEu{`m{=Pv)02lU`Z4hPQOd1RC6;r-L0a(cj%|>vb%0riaPh_^)1hsfRc_JT~3bq)t2Yk*X9ZZ5ikoB(+_xG6m&9y2fnGqaTalYDnFrD9^Xkm zj_D`iIn9HD=l8qK}OHdog?0 zFqmu5cV+MDC%tR5kN@v{K6HPku&P^|PaR8D7hu(J&5N&6EMqav?l*lLZt)i_w^o?= zo^}2T0=aNZ6e+6rL|9+_%07P$S9^6OOK8};TkBGbyGER0&#dYxQD=-Nt1;xelWb&{lRm6*GD#Gyt$7Lc zeLvZcJ`{n%F=>rzTgg*FjoE^yojFnzgfjAP{T+OqwS z^(g17fN-|$+&NZl*kBa_TqnO}keBJsyc2cA-I2RkRLcj9TRJNU=0ExQAW6z z)?B(%79HYxK_f3ie_z)T-EW*1Lq2z6Ex!)rxPO${MYJ~d;~#9?>aj+4IEiEHA4)RB zqZ3Xnph-W5Uk9iSV~S`#|Fdybp9x%P9ex)h=~O{-(!Z8nBkmYiE}p6&kZat4b)tB) zD@*g~N8@lhbeUzEK3P7u9-@4kz+U0^1d^yR6T(hCJRJV@*$j@qg>4|3ve33(6uz%k znz3%n85}8yz-T>XBpq*IDWNsRqo0N;2#lVqy_#Ommfz^RT})jFMziiOg*Bx(|Slw7=^|RtgL4^AK!!}?cvu`(4u9=>pM7HsZ zGDe`uFWI}t;yv9}HrYsZks(fvJ;Z1+%jjlojminlM<~(gc7sX4AJk3u8bTi z7iC>kdWErRHR@dc#9&Lv^6B!|*!@O~nBo_36>)n1CGmCl7V+n%1U2dm@k@0aPE*&4 z*$3U^-h^;v97;42W`y3Dgs&9~eyJ&sHx5ze3K2>?S+kxUEv`9^k;h)lR-)$^PsZ`l z%NKK^*j;6kyknPc!DuahuU8Q}*@*Kt1U>u*rGa)S9RTFY{Pc)_8%`SNI`@ed!6_qKstV?E~?%jPX;39N>mkM%T%Y~ zQkWcdif%u&8m2^RF;a*zK>9Xe7bG{tmzTq*epljfcuzt_>^|8|I+|PR z7BQrZ68AwaHBxjVWtz-cRBA~*uvUq9Ap+Z@8>XwK$}cT7;n(+)5h)nUQrqYgI83JA zvu8=24hf7?Vq{8e;>pu_AV!pf(X1nLthlz zPmtp>Hir(*{e@wFF{*~K8uEA3r^rTQyBS6MW(oqiFiJ)FuTG{&AG+&t`N2gC_5``q zC{Ek@V`bH4scc2dDgqJ6r9`Q;k`sNTn{zSU3*4+AkV_qTChsN7=AC3K%54)!K?Fwh z=(|B=2Pu0L6nJJjbBt4B{0irdzHQg;D<_!}jVZUkFr**?=Z#Ln_qp`>;K{$&8?W43 z!pM{wjjFQ5UCvq^%sUR*q9Py;hw(YOb$_|5%&FtWoXSv~0b_3vlTo5nnq#j)@{FHg zc29p&B6Lbb2jXR#7WJl`{IbZMe|r*P#26XI#nf@M{um{5(`)hWlSdnof(VQUQQoMZ zy{JZ28{VUMy#*1-rA8nJwsn!C%f|A|28%67K?KING_CD{YVzao&fIzEQ6q9;JV{0T zTz-yNKVt$9ytl%Fu`s-grAF@7USDKM@}0rc*ETU?6bJ8OA)3Bgc8L^rBPMXqvXM$m z2GJ_wYS>tDV%HeHmU1s(6bHGAGbnS*K+5TKSdVz^UounFe=wR4S{Bccf(RTR>Gu0A z<$+3Owlc|$JTi)&{r{0PCBlY#Ov`rhkQ1)f<9{E$!f-}0UZ%uqwDfIvM7PdedAI9Z zR0PDu)Lu>fSXS0v9?Kt%S*ye*@po~2bi3`^Nn^ys$=qdhs1jAfh>m(6F6ZT0ae2Cl zXS-D7_*>Y98vRJzyj~=9jpa86mQ@iDBf)i|FAXi@*uPaf^S_Q(<`_f5I1EOO=;pu< zYaSQt#;dv4Q0^gP>_k0nd;e6KS<-`fLz{+5ECYWR+oL-Z%WGQ-AJyZ{e=sTtkC~pdyqA8$@2{1<#`&**jL7*T@X!I6oL2!kMO5jZc3SGbf*B-RJgG z#(@z8jJ9YRFW-=tO#WyLuN|VC&+)#X8vRHtTTkq1lE#j2PF7+W%I`u1fimOGTp_yh zG}eA!64!vDAe2Z^r$bMT9S6^$d!gf%HZV$o(H5#d*z=g{* zpf)qJls!CHke^nSWH=iwzQ|{b*m|tuVMXhc`Cq#d_JL;_ShBqUYHkm7AFwAkxU*$rp5|!%OhDqAeVZh@zb?;?3bmQ+~XFk+_S_Rlo;KidwoUu;Z`T!i^ide%3V%u z1EVbzJ%3P_Ay`Yq_KAdm~&qc2#$=dewsp7QLq7Rt>`M5w(wx`|#+mewy=TY=tY zz#Up#1I4$~yy*>A({0TPgXj$wQWQ@Xeu<(VhYhmX$(sc>FX>Jy++o1G4cIoFIr|vo zyPt;@j->ag3I*=4DCcM`!rD*n_VN!qoJYOF*72qbpvgntW00Lz9}12C9Kkj4CUE2! zBd2#>iwrV#Txh{=cY2)(2!#v$6_RsmBg@Yzw20bJeizU!rZ*5uk>+EpjmX^vm zl+i*ofpYI`^py>6|D8Yc7WE1#AS=p@XfJ#GYOM2My1agGtTBJga$!}zrszH{n7O?A ze}AWDh0ra;6(ZSGQzUA^!6t_t)lx_?XyC+&7Mw zZL0ntkb;Pk_ABYdil@+eHY0?6un;v{4wKW1y#-Pbah0zU-X}eT_hB7T`rxFfax+Gj z1U^y_$Q9$eN+jNN7x|@42r*=5fSjM}BNx{_Cy;`OVOD9v9OEVeM>ZwI`B~0#$H4c3 z|Li9bfn0lwR?({hS9-4;M2H5J;$-leaiXVlWr-9-Ea{deyz4rPQ7`mfO_C;saV*~yD#Oms zVY8msQV_^BYso6H?v8_~AEx)pL^)F0AIv#W;1MZtm*8ruhz;44Z^_mi;#MV6A_Wn+ zvQ#&ma_^L$t{;4ga_=Alxo~_GxtnC*6?XoS{{v;^LJA^qo#?wWwb6gsuLnL*8;C$I zTqlaEQGTD@AIlu9L5TS_Y2v~`d!Y?&%JQDA6eR(6!W`S2C0AZ9N^)rL287XEJ)*og z1@q+oFO<^>DToLRTSnCc-G$j4PKXm5DIfCtsR!Fvij>xl%S38pH!-F-oc&w0R0Own z74h*#rXrrwIPwk_<_A%)5P@7{nywV1?d-(USuLoI>XdKEbKIkYD=FVnK&9m(Z?v5# ztrNyF?=KU{G1W!ffH0OHwnA84swPZ^5JFs{99usQU3T!){~(YndfW=pEwY-3JEm)f zXY&m_!ozTIt`}ui1qve6UOk{)QuBUZ!MVyR0=aPB==`zHz!TgCgfzCH+D@nq5R7*TO%SiW)PV#lVI-;x*+}`(AHEz9-2bQV@aCMc?RYPOu$i}R4aZNWn#Ovt3`LGNQo3gT$`IF9!zu+12S~o9!kCXb>x@>gQ-`D zKrWO5`nFB=SagZHPW4!jf(Vo@P5Z&UIluOzg7IZR6PdVZnb4lt3-dE0GlkIK;~j)K zm9coIWg;ouNqFyP)T`|d&3OBIOO4YhQ!FC1zRQJ{WGA$rX)kRg^x5h{yRNUf|8!4& zI>E`twek|?{h^e%eTB$8 zSW}o?=x^=hum;@geq;9ROLM7hSRqUU=(mOwWz-6xeX!GoIZGj`b1Rz)CJ%auZlrMCO)y8T>JS3dmc zN=wbq7@6n2N~CtIDN5eZ2zRX#TJxGhb8W#)lhQ;1AqegoObCi*pBWaiXNf!AW=__0(tsT{tZBoZnG$k}h z;*KkQvy|+&i-@bhS!wJtVXEXNE_Bg%V%6?w0E zFD<95CrF%kQyh)Fx~DKZl9%zE{yyX;GBtfY7Pe`^?<6K#>NIUGmHtj4nMiXNnj2#{ zBa}O#r3-(*AR~OAC01hV*ejG9dPl#@m6y9PGyGOwjIthxz_lUYXMsJha3t8WZ&fE{ z9N2f95kh3tcV!AL_wim_O9ogFu$||2) zT@=Uax4aK_s>3fm;NfMyaH&uLapLE6v8}bExHne6v;A(aAOGq3VB_IKt>lFSdgBH#@E%@6<%RzjI3KTQ>2<4#r0v4%ruHdzJ@&6a*<4#5iNhYJ5Nf|3P;DZSLO;4 z%Dibe?*{PSrUe((>SK}(vS^3@%A) zpEHD3o_6?!Xr}I6pTFFBY{9Yc2IbnTdzWsWnq3`5>Z}N5ACuI^dGdWPGKxArXe;vz z*Neaz?xM6B$@3$U?GdC)u0*op352$C7nzSEXymTfYVmIOYgvAB`k(c%q4hZIEwq2t zwIR>)7hk^6#@TWpKT;)FY=BIpyNDiwdw7qSava;GAo|L=I>|=Rr6{W5@ zAT(@GYnkrDmpa-QZ<6Iy<^<+SSsN{(fa>Es%?gjbPhL1`09Zj~WwqM(Jot~Z?uXj6 zqk44pNHc`Gh_v`fc2s1F;_5EKJ2`@(#-PZ=RCk_s{b%N)fKPDp9`_dGTeB zcNe|+&_*g0*d@yD(JYh$JLq~ti##5ouK6*lN^**J$#IeuTutrSk=lG+YB@{8#x12{ zmk^=YsKE>U`L`xFiZa`ie}xo4DEm#jcOsCVtx?1H;(4${c|J*+K^y2K^!(k5{A*=+ zeeRy3g`FN?R5Sx36uqKxhkE?Lh9?C_M>7S1T#C-u%Di>q2@?l|xkty!nG>=^B1vk% zj0iTS5>=TBau7xSk?cIxlDbgnC@NBANlo*8-+*r^YHiFN5+>8`r;Eg;)x>71m-*mM zx+qSz6DRA$vGQwH3ztQ_>>>i!hT>PZ{dt>u^NfRrv{YsnXVkkn<=Fa}Y)Lz^ z+S<^c{W<&SW*pJ5m4Z;XR;?A@x2g*BHj*yQb*~@4yje5;`hnyFD2VW0o*~lOT8rY3 zy6-c4zc2T?n{8ZUiBJ*1W#_t1xRh2E#ReVmHOZHMt-ahhEHF~yZ)NtR{2Y6!?;E3; ziijo+H>%DFtZV zP<65!UsW#AxOsDXiCoFIC}+tvTaoG0nyHA?h0eTB@dTq3u@WhW2slj{E6&)7)J*by zwS?g{_=%J2jE6ULq)Oxe{qB5v3y}FYalMXY|AV;hz&m^}8pCtrBvKH8GEZmc&@U|L z;6861OTh%M$ok zf5ziK7iZ9JQsZynmnEcV1zge1Qx#|_G zAdt)al6Hx$m$+c9`-!85)#59nXBIWz+*&~(SN_k41mfo~4i*4LUK4=;w zk!!Z?I&pe#Es^w!BuYU%T+*2DEBME=GYe`_yhhjULD`hkIWouM?$Jsj1rg?ZWDPozKX+EwSNjju;R&NATbw>K zi4;2<$|N7}P0^bU41b9-T4yxi4GIrf5)Ou{Z2+Ql*lJ-S|559#p9gIwHQ*ryyDUYo zLnZ!h+RW9$+}TScyLDtLV&0x0es97O%drs@1AyN`gxzC0g&pt|S3Pu3f7yVh+#zR; zrOleA3Ie%GD0g*n2*n%@>4Yw?=#t5qKJZo!X zh6v;;DWS?hYiaNPt?%}L7FSs0^1gD)z1a*Yh``-L_Y+_4Vb!%>vb^Q6fOi6irg(TRdk7r<%mG8K&NzJdgm+_EYaVF&mAy;H%b3) z3GVTLAq5fW+mRL>Q=2!la$=T`Mve&NLcfdR?K_(BUi4!9hE-z)fm{>1kks~c5H$ky zULDG9!L{D+Sn=3094UxUeYkpwuDo%@GQ2~Cmx4g9so@km=~zu9Z_rmTyKFh0SSyyF z-Lj4$1rg{u)7Pb1$JvZao%o)ps|o_Sy!TKgn$6^e*Vp~_kqf4<=!fI^lCc#SQV@Z@ z9pz6PTbIq36Zw((EfoZEnV+u}+FwpG=Qe*{gb3s^wV+tdld2-|jqWEFoZlm^r;Ol}Ldy!IAi^$}Y;C*^)hE;~XPqdc zXmVm8->~g3%CPw#1rg|}(YNh(KJv)6egd|Jj7ZLsIDN8OZCWVMYoYfS|O{jtE_@RE|0=2@nw>uXjN7B zWU8$Sk`v~JTh>=;A(4Uz^r9%fo6=Vny*y%ZUGPC50=d4-&k|P;yNQtl^fvyj}H)+ms?_wL+HpLTdYSL}>Jl3H~ zGX;^lV4X;cs3yECv}cH>j3*O<#I=jknY~$tMnPT{1XYtCd4MVi1wYt_{PP|>s(spnu!@Y|L{3WV5RoFv5sUa*g z=auJ(xVo55cfYs^(}p$-(Uj@-V^?W@-%?C_RF0z@AOe3$(|TX)BzOJNUX1yvih_uK zM|nAqd5Fq6(G1aayUjL2{y27}_+2`1^p+5TZIg!_#AVaO^_Kbl%M^lvz?S)Ap+Z@8!10g9ij4rL}8P`inpW% zleTN@E-tK!Q+zw}kY}G4cXuZVwsU~eD?}*mX~lgvizoAMTRIz(72n6|kJaKru8Y`4 zS?kbKqx&UO^F@?vMbR>OxY8>`V0)TY@;qC#+}++dJ#dWT`)oZ=-|K{;7{)g7XL9y=@lZB_OyeK^F`#Hn?`fZ5lS1$errUWw}beyFODIaZXqq$D>gh~ z%;C^5j{X%Q(6^&^^aC%6SF3xow;cy42(%f9*0j_{zS6bPjnG;=ivJZ#vi+B%7*r=( zk?o|GR9Wtdv)JIJpK(?-_my=kOe+`=62*~%+Q7q#&R54=#r(-SVqP;J`N&~uScr9N zjub?wa-L=Ok*BXb4D0rLl!8F6q&1}HN4kr+rn-MMd7_V8kpDhx=_TqFP!OTYd5e|4 z@`uup@Z5Wp>mCruW!5Om>J|@?7^+7N#xC)deSH57>;62FBLxwvoL6Y)D;Ji&4}0!U z)){^axk?-{QZnIBDIC9*z6p~ zP=6HnS|jE%XYosS{p59Jg1sq_*FD2PyX$?|4?GBkE);j4ua3Ie&_&Rin` zkJJ#!?s^+-Y0cj}Sr^*VH+>iDfn3Ge^bL9#-LeSPPmtPOUm3NgR=9g^ zBu5G&RDU=19^IkuX&25|O9g>kD4TS;bEXyR(ZTLZ1u0I3?c%hi)tcm^pkzp+2mJl6rpMc&~~U}2ywHn>|FFR{LNIR zY9BzL=A%qgnxEWXwRWMUKy3r}F=|&jc?~kivOD@46N*&5iwNAIbhCfBpS-fQVpvK) z(hMLus0Y!`)7hX8Rln#n<=~Lv5sKwhEFAn2`6U(ndLFWpsODrCYdPCe+~{Tz_ZI-X2nkZh1rY<8~RU+DaZ0 z#20B=u6tYVU5D!K6e%V#G7lrch8CwgmeZ8e@LIQUPS5(%O~Xi0|Is#qQB#IUitD@J zD00Fg)W}1v<>8LJ=-eG5&Tv6s+c7>Z%9?Iynp4!Qm2Tl~O`O6u7TjiiPIi+@EFVM| zHts|>4gJaqEm*&a8&`4&U-rB)3%W=>g($7`W=lndZ8oA#zX*mA9(4M#bUynlp}ee6 zsfAQxhdfh+r=y$Lv6-F=F=ccDd43A3-sr5D?AKFbYz%URQr*G)b}nLQuzsG%j2a*9 z>A-_LU8M$*M{XCFi(-9fKBkj53Gqb~r@yf@Z|Pl~2aYVG%%Fn6+0^2bzU6n)Ds%S@ zH)xN5SU%)xPq!JJ%TheGt|i}54t?IZN@C(`JAqLsT_~c>>9?xF(?E9xN<7?^ZR7dh zxt^lL_Qz(VAYzl}Qn6v2gV=FN_m&*4kLK)oU*UJAw4x=*g&ITooY%|qq^quS!?{w5 zw)^&5E{?9KCaU%!-BlulDmboTPn&VMwL=wk27wFjJn7pU^J}wdhT<~&U`I953Fcg# z!K*v{_e89zA!cr!C^3R6^ku48PVvp_s1A%8O_jI8&789?H|SwzoJ2~2>ngFcnVq;k zkz($Y7_Z}Xf=yw+++_E6#YiPm5@Kspol|LT&^t~8U9XG-dhy!jpE93g)@Iapj446Q zC(CeZ41c|>3)_FrT3H9kg%L2C)+8^MXXRuEoeA7!!ssSkMe2>>0-rekzVo$!z>ljG z1ahIi>ECybTIcdVNBDKwfNvA-{( z7QPHZ1ahg?Cwp`dfAvFcxw6<1GukWU!uw&`&y7ajIj62n8+ArOAQ#?8Yub|L{`}gw zx-zBb8U=w|s%<}#@ri}sZzH36(i(@|0J-p9ouYTvSK`8|xy(zPt{{+0SzVe#&K8#N zsDtb~Cr{v7LoU4Gr?b8`i&@mgcCy;g*9ro;)HV2L-B+fTA6iJ`Q72{9BA32Xe~p=F z`u9sy^r=w!`yNLHp>V+p*0kC-PQoSSoVeoJTd~x*wlNNbzF27QB+@pV6CIsZ1ajf} zCogC;DB5SCx_;hoGfci@`~>i1ahgK%*dS%%(Ty+Pq|oI@qH97B_6K*+9Rgtjs1C*^WQ26 zjC51t#kF15^GyE9ZTXxV71c;`c&-wEr{#?t!e$-nz)jVQD4q;H7vudXS9DxFyYj9* zZ`nmt5Xhx?HCq1PO?dLyntaglL1x910q+IlAt}GMoiE>7%!eO5K^Z9E`zTzHtw7%f zT;t2_#{2M6dy5G4aS?$Lt(5=KBZv=ksLhAkUo#^Dxl|9i@IO_qh-JqOrAd7|5dBomA7(yFHm1m!%-_K zI=adc_Dxa@-`BL8(7=yIeZ{C*%A45rfTiv3$>ZDGs|bwQ1wAH@Z2nP}me`+fJMub6 z0}4JDwUYAH90U059$vg-U>%0KgqnyNLtoF%bm5JTHx*T{(%Uw8_c+fOAx3vBbKCF= z%Z3Y4+*&~(7y9tD;}q$~n;+jPe(c?iAq5erJv3I1FPLFsl$<`Oz6re-^nK7rq4&Y> zss@E+jF)5gwr1#yAQyTZvoV$9`{Q~ZOi`%DI#%~QMh1dpjt>) zv8E{<6d$Shv)J&x9`GFONEosR*akO%Mh(;*4u)mcgIX{R{WlVG7@^99b z{bgHSkx_(l3^E-mi!J%S4AJz)!W+rz@AtCHW$Yw!VGGra!#TIS<>g5a*&q9D6a;cT zennZdP3fj#pgy{btnKA)s%JUtla-Qpw`D11zC5TPQoS276_MBNwb(SR1z%G7h(Ios z5%q!cpx2cbC+g^#-X%>R#F>sEJf-tVffPijxqZWTtQ4Q7_Tvo#W-18e$`7Rc^8@8X z<9>REbn|a}iDEIM_}K~m0<*S|3(-^q!p9(NeaG`hJ}-)8`!hXqip4o#XCw5}kI53!pTgcL-mxn%KeUYkz8oX9^s z%QhiG;fh!!PHZ9>D*{Qz;0ue{5&wbQ&^wmCHVgTjnMtBT7)3fw4q^>G#g{OZ6JW zZL`Oy6hLT-jC+rBS-sia`27xPii|B@Nn%623Svo|iBY=iKl12}-cjS52Q}em2VP*v zg)LNbM!j>3^T_rAe8>HK1%X@vVxf5LQ&G(GVAS)WFPwSD)%Ki4SaGBvBK!x+;T~us z_GIaZ-^$eH0}sDtk9w5nNI}GjI+Xh!TS+YO=7gxVp)PM;Est%VP=zA}5o%`Gp+SMX z^UalPk-wvYK(5n|7l_F2RYc@$UB=`KP5G4ANOQ???i@3~E)^^gd)iUH`)dBL?6YXA zU>;U0%-kl*o#S&6G5Fd7@z%pm$Ru5c?W_=9CL_Ug+o6VnKrXdaYkC>^j$d|&EqALb zt@_S~YD?^M5J$>#c8RKyY#eVdJiF^MZhpi0MDuu&Ji$dlAQ!ff_KzYoy6Lxs@As8B zJ{Lzp&39h4q87jRM-ge|T~qmHFGb9i)*qNrO9&z$TlRy)4g|uHR{?2d}-uL{Oibz^>$Q)We zR=N}dN;=a!6>1*evnk%9;{>$hErAH|KJk#hUqP=N^K z+ORlTRJEe~j{<$i`CxrewAmji)2-JDB`>wc5|QfeA}Ty+^smg~?uT>4wS*qBL(*FM zN;hPa145Ot_q2noy39#Fo@ph~V+l>8{k4>{h^Wzsp^u_z^Np3{%P=q5>FhIs6htVk z)fWHwUKpY%=kCT?r5}jUpoN;2($$7faHz@O&Cxj4dclf7O5GRj`p6*e8N7w1c~{}c zg=nnqK{ac}H{@gbXRsOd4h_Z>y{Cp(Cu zbLw%VAVR6tp`A6FxZS{qqJq;~rP>#Asnx99Hrex$ugXi0g%vqc5TVxnc-o^9KeZ@O z%G@laiWqWXohpq!9Cm^^bZ;X+8ZRid%@CnhRoUjhoMkN>E*}oxYr1RKezIBiGM3S* znu0(swK~kHQT64k*i>fkUQp9$!p66^Sw`Fc*Whl6$El&H9I=lmPZ3`cZlPx z(?XL%!RM}qT2I=$aSK`W?cqFgZZW1HkV~loHMrAUHZXDoKj~zxB7h6)_-Weyh$*bA z<7j^8%~6v=0fcHrQ%W27k0A|t*7anjAfUz;T37l$PV4#R(A%;6Ox_4{#q>p%`hwd! zHey(P53BuAp4ZwUqS@|A{HL`B1%X`g{)A{aFq|#y*pH`rWiq570&COJ?Na?R{LRaj{M>^X3Ie%u@)n5D6dTdO zLH9D^FTG&VKRNN@C8}|xAOdUCk%jxcBY)HAcQz$1k0AoNZiO!pQ`2lkdsa{o$fZ`TbN6h@V_QUuTJg>b0=dGLE)aP> z4&v$@z2}#xmR`orjmG*^OAlLxBaQu|(+{ejsMm+x`$tVl7SRNsQoxz&z6sfb>n3MigK)4ht(Ic?kMHNeX7cn4Q_m9 zFO4Gw5m*hCqN5`mWt&(x`M~s6;E3Y-P+N8AV^wMI?k4Z|(j-z4f&HTsuhRqg%AaSN z<^<&kd=tV7X6SLyZQrXNJnve(d7JeIs$})GY8j$cMCBS|I92Fl?W@f(D{okUR%)SX zc9X{NoVh`lm9qmE1T#>cU~wR?Jl&Id}@1J{Tjg~|!bzEWlQw!J&p zwboRV1D}Pvn$nNmQS(@{*POrhwU>Arr9q`a_53R7!vEOj$FBT_jZq>ORzp+~_rmPi zsof3vu5ar}g#wiv@kEc_?n17bZ0?oeZy&ao3Iz~&YDhB}c-GX`rX0T&+FoKyuyUk| zXkGEfp62~DezI#1i4;VrXO=zYeKMB_NMrja4UtH}ihFp%N^wi|D~ODwynu(pCrLb& z#d>|}`EHi=&n&d{esllrqa<>npNQwzlwIS|o&AXqwCRi_GuO_HymJ-9n*2l}+_5!~UnrJiDw(_I|!uC=@^_Cofu~N{nAmb(Uo- z{w$D!H8a&yoY=HLZg{p!Jh@{dvC=8NtKpL<{>s*iH=K1wT(NhRNI?Y3qnaEoTJoxc z%1YmRKMRzOTkEi4;U=UUc^A zx^BP3{bg@fjk7QxSvq|K_y`9bz*X6T*k#%@vBRj>4DmGZL)Y)6zdFQTM z*i2iB%K+<)=ll4EMAP&-AsJ#QQ;cWUpZAn3x{@$GTg>(HZS)oCLbHRDG20J&dan~YkxB@-RdTfxHgwa zL4^-aYpsI}d zP)#cK3M?F24E<}H9e7Z$X`C7)@j}s}Mo(rTXh!FAy3+w$- z4eUCt`02=tBFFBUfoRVcWE2|dj z2;F&klX7s|*LsnO|m{SY+*_a%kP%RCei;#$3~OgbxaDD%Ul+l za-9quDTtWg_cQuXl#a-8Ig>$e>72(u%a~g7INMLpJyGb=!kP9L+?j?VnY-5Df_bw)_AIp2r;{7 z>iy6WNI?YlPt!cUJD;xi>pFdlr?4eV zZ#&Av7JfzC`ic<$MyRd2zttceJ|4?({1D7>K2RQxA>G&hYOu7beo@LS2F*Z(+A4iy zzX{+OXShQa&Kk-?efvBY>u#LzTXSNe5h;j3*_sx;*dWUc3f*&>z6F6Aj`DD&QRS~x zgIs!dZ+e%~ArdKwK-m=Uv(g~@UT*GZAQ^~2t{WW_S-f)uSy_G6#w8o1^E|hpdi2!= zq#&ZOwc_(SAL$z`%k{`HcRo^sBc*Vq3f-3AlQivr%j?PBIc4`$ZsX69f{0@eELKTe zSsO#GTD{f4(@vb;J)6GNgj~3SRYc2l`fkReg&Bk11aqVyLS2Kkq=660m6@-f{0jj# z3T>rcwa&o1hvx<@E(lhvC_Y!US05?vBWPlZG0^FUEL?YpP*)V$Dt`I3V`lfA_x+KA z2<#JO(M{OotD~Hp6a7%bQ4?`JQWcM&le+ccRzpf=AO#WFS~`LJt3d;Ojp%xh(s6E3 zV>E4F$UF<8bN$)rNI?W@4`pH3Xs_E{S-t#QKhzSO&6TY!dz84-pf_pB(3t&xI^xW; z#zsUSm(%nFi?&By*Y&ECT?gG#OWSsBG7*7XX9^PZeNg;5L|-2Rt}gJ`XOUM*F|K=( zz^2m<=`$*t-H1+Li|BV!S`6Fy)`DQeeDqemIbYkKWbp8r(-j1A;o77x-hRJQ-=i%1 z2T~BBYT_RcPO)`$O<5yD`YGCuTsR7pcNaC7Wj8$NpZIDlM+zcPo~9iw7EWL9SdnF$ zH(o&?7mgd{xX(H*#;5i1KjhYrBLxvSZgl6h`;2LPViV(p6|oY>T^VV`UUjeLYdTS3 zcIMLTIK^He0>_Y|6Z#&sXuGbv)?0sOu{3Kr-Mg~26+izD?%Rzank@B*ETcYyr#$ax zA_Wm@Kl1y?ow}FtgSTHsA(zmfTPRQH@^C~bigng!-PK!#6hz>NP%glqbfZsyiyj#` zwgly=t=d>RSZ27`Wz9S8&XIx$luciWxkR-FN{*9Q|H0yEhvYk!!Z5->X0B>)aq0SbWjl4R2*2!sG5NQHr?2tHda1itLZxV?pSB z!RI34%kL38b;~f=rC38nspf=wP%|8w>n|@zi(I~ zd6u&u)$!30nRkZoKnk`HpG4;j>#JCFSNnUoFH#Vp_Pp}68y0`J^0~~6YHh=q-V$@a zL{q);t(ZP;`7F_N>{uAn$11(MqPB<&SS%;WgrFnfls2`rEVQ8h|4{b(~*J* zY%SHAeAr*N?cDQFmfwi*R+d(ED~M+2mV_~V+)nz%u;o^*SPA+)aH&4Jss45rMA46p z8X^MwfoO_7?|a44bA1Mpf(UFaAxh|;HPu8S-J-eGTP5_lE&R>&-=`0@)LSJMlaA5b z-C4QIt=^5yM}$BMBGi89z1C&ue_v$i+V=$kzb&$LzWb0j)(VxBr5&kc*;LVi5IKG0Gw1C+unSv-^MUf{bg+7JKJno}|D}%AC32xW)KK!4T&nXD&ktt# zxiyzaK}67?FkSOS!P^<6?NzGQ%-X#3rjfh=*|bltxeQT~E6r3^t%`_yQQ&vqF;4da zBvMe@Q8w9+CqA-A){3n2HhvPhP+p$D#WINea|zTctMoAGVV>bXcD1vDKrXZxns$fU zKhYF#Jka9qF4LbDnSG--Q%Js4|QfdhgP;?OV5t+8ac1w3Co-hB`fnEcD`^8j#<(_K$k>4*DZrZy8hh%KoqXQ)Tcgt zR@#cJ;EH}6xlrDVUb$x7mK-2!M`uer!}yf#GyJ31I4cO`Qf>QfYE2x?c|yqDfF-9a zJC4{xwjFIPqAhdI@4s4~S$0)=08$X4%9uKNd*+jw@s?fZQ0LDp$C`FEw45lLZpl2h z8=nn~*FABL6hxpril!p%SWsevu{gD=+`KTRufdJ9Z==;l*_87`h|#9_%!ICY1CW9U zl&5JMcZA8EYiDG6uXX0gh4RpXQzeAQK5{|k3jbM^{1gOo{oA%%w9#VU3$3U{w1>6hx>p2IutBeIJXDg)0hY6LpN{JbkwA$yg9ybXQ*=i2m~b z&#kI4xRC`h;MjM1tNzh;M5r>NYn;{lVUdAzj&=pD9i1s<_R@7qdaoa`1D}fs>=TXb z!G!HPV(t28zDPj?%BDE7R$&$yn=fSgp_ZW4#+`v;KZ4tC*GKo1SCLF?FCtVKy|d3- zTJ`R1dLyJD0%eo#PF<^eGIIJNqY?K()GO3VI`?_s%+ilNowc3VUPP-hY{epr3|$|Q pf(TWHY2X}7KSJ-fP+C=}l@>dXEhJxIUyXm}94UzS^82%1{T~9>BCG%a literal 0 HcmV?d00001 diff --git a/data/husky/meshes/user_rail.stl b/data/husky/meshes/user_rail.stl new file mode 100644 index 0000000000000000000000000000000000000000..7542c59bcd8944e07550bdf9c4325ca899d14e4a GIT binary patch literal 115184 zcmb5X1$Y(L^Z0#m2@--6B+wG9f&|Ew+zr9qN{|A@p?I-SpvlFdr9exu;_eQ~mA!ic z#fw|h776awLUH)d>@vyhy?lS~^X7S4&U0rzXO5pavb%Lh4jwdQSkE3|y@m`L5Ej$F z=fEC4hkRP~vzj%-$`2jhEv#|{@&D`ZZFV6Vt$w5an3|vzt}@h9)g2_~y^3`>&(Bsv zAzVbXbqHr8%beOlGAd_VhdOMQD#YyFTUG5*f`X>FMH)pm8aYh^hPKbK<5+o8u zGsilvu3DgCc*&&G0qCw66ylp!Z-yuMT!Q2hPP|PDl97?M9Vbd5 z(YxAB_1g6WNvY~MBSudz5*WsmH1q_?y$fR;uj6I|;jH{lt(ux3EuYS_a0w@>K`8_+ zj&X={^DRRB-Ts80k0W;y6iUf}knvUwW1cWhY8&{;d|7yM0vgTTlECXdCmQJ;VUJsJ4NDR+bOT+Ki8iS40 zpCMJRfjGJ&(Y;~MBMX;sVk;2At!q1+b1>(ScfIzgtf&qsRa7_Wb?#44Zv9JvN?Hi{ zEb3uFCR$Nz?ZR(3^8-`w38MR zrEbRR`NNparArbXFNVpU5HBEAGi`AmN);za3yIrDV)b$p;w=!}hX0$EbCU3QFzv|3E#6oDH$f7ABE3iX+u#IgQL2oQ`W@s0OBVmQ z1jC%but9vt21)ai^E3I9T#Gjy2F#6zseFk{Y8ftNZv?x_ZEAh`crWYls#R<$G z&I}MSr0UIvooQoYr6n^FfqCy75n_Jp_!HcD1|mX;4rkQUN7 z2D_c*!Nz|;^zT1cx5gzH<^+{=V5%@5G$!(K9`j_3qFCo;A4R66iX>=*6X~!~4u_>BAL0U*qdlRDQsfB7- zL{E9~+|>Yrw7734#O_}C)R(p6S5G^K5RM)u05HpK)ly^txv|RRNG!b0O1w^0P;Pv^C zINmWt%A%o`@3Xg(T*3+NISbJ$Hm9t&a*XH8-fc|;*Wztjh}gPQ)q8K_73bq^KE5`< z+~Vv*y^H)HA;x|)$D6rcoYDkJ*PkFQq{)jC;^4D_YKDw`l;Dmj0R(9wK|YZX2kg() z&huI-XAXu)e;cHQ1bH|@jPH6|U30dTaxzQ40D`mz!`fgecs1f1^hMoqUDc3`)s;N& zA|#jacrl#rE#+~KQ(vD6QTncL89J+aC2ML*UAbw2&b0 z9A?1+4dk7tFSLti_iG!^1j#FxV;s&(vsK>mc?%U{*;m=*i3`y(f7n4&ALKOe|3duL zH&i|vUP3-PEKFkwC(JfNpS;$xFU~4IiLPQIxR$xKPr31*Ha+O1<4V7Jrn2Hainj$J z60U^G8I39`GovnOT*3+7LWS60KeudBucC5lpD?vVPWV!SPS07sEKiq0cD9Pje5ei}r`e%Bx!j z5Tu0!d7MJDeg06boIi)GSD;-0L0WvJFGSvy8tRU2Dcb9|y#w|Dh(H_UaSE|9p`*8F z`~3W*<J$39e-x85X%CRC~hq zsD&956uu*bwZ>PFw6YYUlQPg|nKZ#s0p?qOg0zsPRk09}|4gyWg!!XT);<9QX(2&t zb?_`lY*bsF4N;aZZy7+4780}{AjI!QPN>iRD5Q*4n*|W0RTKQgrN2YzcKHbU;Gi2N z)Z}*&%AZ-PD_p|k#W2p)#){>a;2^c*hL%e1iy;97X(2&77D8nIbgx?EX>TQ=eu~52 z25BKdy9q)R@3BuUo~w^CYzA41BnCddJKt@?R z|0@R{6S)@eX+kvHm{ThE*Jv|J*E5Yi+y;*cN_SXJnPZks?u$Qdnhm&?*~Z(N4dvTn zlN}jLU=c=_KCGnZzG(*g=h@jin!*639$Hf33G|9MAaI|0*uxj@$#b5%MQCYTDcHLg-KJQAr-s?q z!_NQA-LqBa=F+w^4Z%jT15))8h>o?s_KYal#l@8M1yeN8aN$Dn?ht8m06kgUm?$oJYSj#uEoj_cGW)3Z~r}qMc%nq zS@O|`*Cub3aFTdavk!@`Cc`(@FcBs#ZcjA3-a^U!daYyR%YQVUkK_pjZC@>ob)?>$ zt(r{O0xd}QDRuO}EwqQjK^dtW&U{!`3UgC>HPp%{N7i*o4PX~(eL z4imvs$lIF`ch=NZa@Jm}{i+1X{)K&Te&zG4r?d|HBTSCm~K;SZ)t5(M3s7o;d^?EqNal-(0socSCD;*)Kek-Y!((5>D`O1@;r$)Q#%e=z-&BrJIT1T6}aB!ZYV<<+u2g4*RQrJbX;# z^=zseF>p+KrCQEx$|q;PwwegmN}S7rZ7Y)?A7TQGyVvg)Q2w*DP#*03-NPlOcul?b z)T>-d`^{~XbqBMX2;Rnc8Nzz-KxZYl?X`BNYNBZd;4^~=&S%?=E3c)UAXR=fU|PI3g?Rclmr`V78`)-8KCel_2<{CCaduI#QZ}l!ym0rH$3!p>z}!j> zl^Yn<1ZEVxrc1{>ZXGeCM}jiA@VnGr5s*x(~*?8&B1HXnYoZ{HuxnXCDhawgs7H1v(omj z>yBkdt)}^$6TD4>XF08)@^DQ-rA?V&Q`_YPw=KlLeXktbezPeB>OX=#$@HFM(qcVL zhT82IZUmA`46IOh%F5FkQ-Eh(ydt{lTzfZT~_p^I!txT>YSG$thQ?v zR3iQeld~>lGS!F4p2k)!phl_N=v*JoTyir)P`r1cW!2daGXlae@AOi#|(Xu6?^# zR!0KQqi*kArE7h$H@}Z-aaxG}(fOgbJLM0*T#e)e*D8H;z3(L0D?2TRPl(!||EQ;G zVxgigu63ftR^M^Z3T~6hXC~&Bdg?-tY44|nT{EpNJ+95`CvYE7|_QL}PyO&nXX$JXW3OBTtf13SG)~@ZFoe zQZJEP|8#_W6e@VZg+x$yUrnC&BdObbhrveqky(8O-fZ@rh48d-d4TZzHLoTTGaihq zIkj%09#`L$!M-`E+x2|x>6Xv;PnlhMDQwx84Tu-caXL|aiMuAx;oknLUJAl?U*-9O zn*;d^C1F|R>N_!sOE__^nNPRzbGbKAR(%_GPQ+B*dr-ktx?Jmg7nh#G^SLuXsy-h6 zv7V~)5h0OW!ihSms-C}oUuObh!`TCh@jZx&L;(*4jt5f#tGO#9>aKc<4 zqbC2P=e+1&Q6?Le7j4w*<4mcXKHe5!ys~|)+i1MJNF;Bsye0BH2~qLe>^iY4>YRz- zTAc=Idb$0&XD`&?l8++vvdY)<$3!mS1TRCl-L|`uULP^%3qc7uW~K-2O-(8I)V)YmRwxMNidTyTForYd_c_Nc@a2ba@bzVokE~yg#XPIx znS3jn_;fnD(reY(&!vZd3B_J}@yZgcbES~CaE){BEjlst#4DA@%k2qK(oxC-w*i&7 zJAb)3!L<(lu-;b`QnmISj_u>rve*Ze&6~!!IKj1?maRH5Q{c#OI^RgF59N8-z@+5n z+k8bJuF54JspGdU)YC35Eik1J_OBM@#rjZ6>^)nP=aA?8iCxuW3OjKZ%BtY?o;p$E z+*K1{(prE~359;|q;@SHa*Qaa;-{-DX zy4J|N9sF8i(;8EEU|EfN)2upgOPt_s8qOe37uH)z-5Z}o@>as@pT`6{UX4<5OjNd2 zYHHzaiI*;~Cn0(SAJbd=j7@o5JRe6_F4Xh!0OoL>LLr{a9IuydnJS5qT*8T48&>-A zL0O4QIQoqAmXE|bUm0G?#oH^-NB$B!jlMbO9<-~FlJoWY*qoz^i?_aO!`yny5V^s7 zF}1|ieY5K$!`!Z$YjO!Eu3g^c3xiY*ZukIf{PROCHAt{sd9TlgwFg*C#o*ZpU5SgSe@CR2j5r% z`B)uaF3kp)L@zY#wc5GB&qgohegvh8+u(#b=c8W3Zu9xW);|lBw{sgjReUA_pW#J< zEHuL9t?X;8atSB+YzOP}<8wVuM^W2Bn05G^x^(tY-;z1awN(rDs>zQJ`|dq#rmcgp z5ZkA`_N+_VWj*0XaIHpD5BcgnX{yt33#s%x_t9J{+;GcH^4YTT^wU0Py=K}Hi1)ypBkzsAUjk5N)tnwqc7B6*ZR~@f; zP8^tIy#NGnCAIpU@fBOrL{AA%E$l$9y5$~|CzBiRxpN68c%Fpl{>OUHlxzpBm;4Bx zTVCo=gKgefek`)yRvZW};RLT6@I^=G@t(~-&T|q7o($+&t%tUy}-#x`M9<%-d1lOAP)oEXm znvM0AVJ0f~6W+YX73+B*xP%kDHifV+sV={avD@~29U-|F&g+JcL_*xRR+H0CxAnvw zt|7UE6XvpN{482_I=04>YALVqwHhDo_?Qp7ICW~vF4cQ`+fOTNBDfY`w+Zp*p*VS9 z^)TDWB~AyIaDw|mLTtJBtz2;Vp~t(slZoJ3eBCC5>+|pAhNTa!C%PBbxP%kj7kI6N`Vs#O{(xfb{5%tX!OV;vs_eeBt~JWg^6C-_+Q?o-d$=2)?#q#9Rru!-PW ze1!}xG55#HpeE~V_a@enT*3+NYr!qOO`j?aT?M>%L+mDkYw^{j5IcHA$ljZV+A^-J zF1ZiKR}!@THEtB`zeZdfR z!Z_&sBht_7`v-_m$5`C&PObHDuaEEhU`%%yyZe?A8Nc-K9O^dSmozUCA#mPEjC^AKwZaZJm+<<)aD#svY9k+2g`7VI zLYwugb=#OsrqbnFyhQY;YhA?{sl344)VWbw2-7pP9h=SZTfQ3Lcv+pgxE| zn(9V~W00!ZO{1-{Vqq^zs17jaBfa6Iu2k<8lS#F)MUMisKrAt~!Zw3!3dd25{ z#4;f6|J=cL{Pij~uUk%_J*rta`2nK%tpV0Hj$2`9{}BJ_^u)QPk_7_-d6S8+?@7x=b9pKx}l;KOjLtC7~F zaj=e zhY5dpmO#A0(ATELDL%d@!`F$%Qz<2emaydeWUh(eS{PGp=)q4^2jt@x*vRuNv**ao z<0b-AG6hN%T-|fSb3fMZ;ko4mhN~@Xu66mhI^+Y|l@he+nzhqMPu!T2LXR41 zGsjiaYmHK9PSp({$`|%{E^bQ*sKFvbAyq{y>vZ(qW?FJ6);aWZW%X~BJq4=Fv7&X7 zV3=x^+`##r*9J!zG}4QKJF_5C5_L% znpcop_qDZtQ@gnhRz(Weiq?MjxuC^d4j|^fnPyEMJjVJE2(A@8_>eCe+H0VV{`o%l zj5-=_#U~G!oH^~wHmR|81>zMKPWo;QZ=~IWFi$N^YGwX)XRs}?!VGH42Pb%Hh1j}p ziM4QrGL|Pm@Er0~sUe5-(G^n&w{f?0x3>D_g!P&q!L|6_GCcXxX1it5u@f$Q7K=+b z@%`CDdVjp2+sK(X*RsCBVmIziaDr<+diuNXd86ion509F5v_}p#d9TRhQ$>4fkeSA7LW6 z7C+?>;@{M&vVFyT-d1I5nh36C-cKBzIzs+D`L1>4h{+Bv;RHX;6k?%uwCuENy0?eB zj)~w}eD@RfuVDRg{@>lUqV+~=T*3+SDOttrUFD3MRn&GlpO^@)#djlx7(C`Pxw&+d zy=qgNC;0i75VmIn z9Y+sU^wxU-D=@ZW%C*e9gVPR{RJPXJ=WTtof#ecS@cmLDR^_Ox?0y?<|LE(FB$sf4 zpO^~qQIk>1!zOLj0pnsdPH-*0{)7|WvG87o!Dp;ddE&`~~ds7{bC$_eh53bCm1Lbb}649c;C9VM4=0>d;1!_%2_ z7ufUkbtuhpRtg|Ui~FT;6X{|R)!}HZbebEir;2=B9xsN|=fUsi{bAiYGF}<^%_V*H z!wJ$tg63V=tv!3jR^U>+(rmd5AV`b*zCz3$wa#1rO@GBbf4756c)S?i`rdOAqQ%HmB|0tnK=n3CVGmf%UGr>)eFN>x)zUaX;T36B@U%Y+9P8_NeB;oO*S3_Pcoa*=JZr9ET?fRqdOa#}$aJu)J+^W0U z;(T4-XPaP`o>}KwSm){M+U42i*?-yeK-)I3o5CfW&`ad~+7O-|$goFkp0$!Z-NRwz z{Jn$|m?!cwVJunG%3ioY3%Rs#K@-8X&^E2^h4|rGLv`H7IQgdISO=GI0_~AkD@5|g z|Jq6&9W8VJ5NRT~7RHpmO8xq7KK0`jedWHLM>HC^p~NI{U(BI zVNA6C6yivm4fbj`%Szw17`;c4#GgoCrH1TZuat;{R zScX44Sb-;GVl1GE2Gk0N?OE|%O zMj^IcvnipMK9#>6>1pEx*D`xczvr)}47pQ7uJ2XLWP@w*-C-ei-W;TacHFML{d2vY zOE_WPL;g>RS31?Z?h6@|&BrC2F#A4-=f^3N8;*6<+;+{*39e;6Y1n6JqwF7@Tj}!M zZIw$n!F??u4!y0YOzY)PF8zJR&Izu?PaWWy>Ya-nnVJq&HWxo*IW|y)JT9(fKF#>E@=$HgvXM%qb#qiM;e^>2JvZWt)_Ph`C4Al-J14jnKbsOF z&%c%B_m3i#TzBS}&bBzgeR#O>TfBvAmaCxht+lnC$Hley*_061w4rj%(1nhKpMq2_ z;RIhJrwCuh%(xCvI^ZLm0z0PVU z?_aZXf@|?pAh-w6%OM|Ut|Yf8yHzgX1Yak@j&Oy7a!9rovcQPec200Deue})EIr0* z-))GK0~Rz?xr7s@J}-{WX{Xt$kCK&YP4aMpYw?{3`}-iN=$n|7T!!S}C)DDri6*-K=% z_goYq`ME4VujS`dLi}dWC`GLkUbTBi6T!9k*`yFBBb&+$5mT%sauk((Pmk}an)l(N z-_?`tCtUX23@U9RxE9~V6QbplBC`DVlda7gG&Qa6_==UEV8e40Ps8NuSywz$^VK&I zT#KJz!_(vw8Y*KaX0SK7SVH0ZC47H|?+pl%>u?EW`X!-``lX?X;97i*3uj)FZA$qq zg}rL+&rG|VeE*W~?g-JiOnqhBgpX`JQ^O>eaKgM(q#j6+VX@e@UUR>)8O z;F+Hl@p4Pb54KlxPepNpYw>eKAsTMFmv$d+c}}l}w`2Ezm%~?nsYeexKhNo_Si-Fx zf!|Xa;eDU0*NvNic;-;=lSEzXwYFD1GfUI(_V3oi3)C4o-1_gupW%%ZDgm|FboDdb93! z>#6Dzl*z~Q2RDQ^Rjr1^?#sU>@l+lBYLlLlg_HNHBeQPO@D_7)rev^D&liR_YxJAT zb!R5(61)#LU`(QJ!`bLR_0w%hdbmhoybpJzO#?kulSg!~$xHO$GoyUOl{|i>d)L!Q zC;I-<+LRAYEPLhBZHya%H@33gXoWYO^i=VjbFISTU3zN!=r^|h4t-S}cA|8GOE|Hn zrePymzp=Hxdm+4wBc~UglEmw|#T+9a&hP&5tMff`^WkkOxuMI?k>hS@8s5!z#w=4g z!D9mNwcu}&c<&?j{!UAm2Z`DStlNb*)pn1Qv~w7i|ERpAp;f&$Zn1t|VVsLgI5BN! zl5Sfhzl0i`(&43Ey2-Dqnh36CuEE5;S1g#S;pIPa^HimFG3r@_rJ7O*Ck+dW={GaK zIX^j)r^G~<+U~n8we?ixE+Lb68|7{Hm$UCnx)0`K^w(#SsLnaTwbr&%^;R-?XMSiU z-sN#sk$7=qW+Inxg4YwABFARbM~2j)H)?PRCwOhbxk1T}dY#{UC0x9B@|^SD3^f>C z4{y-vE%C|?P49PIe(&J>ug<;gecU!Yk27|dURFs5s#oI@PVoG}`v7t{^|t$B zR)(6qpYy(*A-B=zldIy5t@SVa=&731x{B-eEY%p7w2r1!75Tv!?ShMRg3{gc^GV%C z%KDWqF5#)-`FlSkLe4iXsN&+*`}a3eQfSixm8TY-f++QHCzjRp7M>bh!U=Pa`nLL2 z%!h*3+>tH~?}c`OX8}Hoc58Uc_mkTBd|k)7G`wxNQGXU7b=nqeSIP>fJ88^Vw}y95 zqZ1#g36nIP=(1~pnwaF$!#hT>v0b;pC7j6qS)xu>;J0CO8XV5uoj zaO=XPY)0d;L3({) zyW$c~LCkE@!X50&UsNZOOo6%M?IChhUch6t%TcBR;wn^72J8iFDecU+K8+()@ z)t!mFEpdXk7+B-%+o6|k<+}g6c+23W%gYd+CHwm)e2zs~=qPGR)uBwA^!Dm}u+)@7 zXeD=M>vi7bWv3*b5>7nMzDaMp(O;s^kgv%Ky(JD9y|*TBi3k30>!siff2HzP3I5g4 zB)vW!T#m5t_LF(1$4HgT;p6QMZgL1sxAB>+kc&$=VLxp2X6GyPOBNT&trJzMmv(W< zoibhxZ^w&kIea{Y_+07?z1J?fyTi>ToXFf>)pH)aA7`8+qoUEvP!{C)DUlOg%bfF< zk$dz$c%)TH3r{<@!BdO(+Xw5!&??8O^LS%As(QO}hIjC-Ua9IOeNTU)Dnl1V&$(9k zl8NA2{Z|{K#G{LN1N%(-^5}~ytF|wx$tBZozaJCxbntQ8u-BKZa7`q}znHX(OE_W9 z`4{z;c)xk`lWo>pc*>ty=c(fJ3fzbLZ^f;`b?dYQ= z9zH`Bfw^|dgyxzkUBy=z!l|(99OlOJbGRp}-0HX5I`zLyUQTc=q||~UeOE`gH+FOLD zet}p!@Gr~X5kGi%%fNhu!u{Q<8x_;suHW}j78iZ(dXaF=ln+jz4cbZ9-?pGU`tpVQ z&UA|#C6vRW5T>WCwQp~F&T&{;UjG?2Cj5-2`BVay{}Cn zP62V~i@6?4gKPn1MdgD;`X2IDAQmUsynmNj=J79G(!x?G`2N0z5Ql;I<;R@f&D&KI z!L@j)>o>L(`@Vmy{hnm@a4k#;-rse??G!VCr{FWHbhS3y+R4MUFkBh#?}p8e`T$X@ z#sf?F{pLF71g}k)2XjE;2tmcWVrWYUJs6%G+OIYcBJR?@*^deaDwj*z`IyS#4AN}Otr>jO!aXIC%ESX zdouMB6y@uw-d$(rn+UGO*Sqk%bD_S<@Rh@C^P-PCxP%kj1B4aJ7rm5y(=U7G4!>j~ zxE5dUf=`_c?*XW>)_Sby=L(l_g8N!}c|nrSRR#CW346wV@E3p43qGzr5`6 zTeYy(jo;g-+Wbq~XE!5VctexN%k7!-@pNe+Yu2aJJTSY-rJiltI2iTu8Jy*x zZqu&89F9+L@I1jAnyPlUhJI7lgQ?odeH-EW=6Fg6F zjx*k7)xsn3j+ZItJh!Q>wrR<5-^+Mn0A(43i@Ys>X^ zRsJ)lbzyvn?YJMowH|%3U8@ZDERE9rt=l2%%)2YB7ySsX#cLMczq_NjWl`Cep36XR z2`6}agZUiZ5!U{i%lpHf#&*7!!FO2r3JIQSe4U__$amO!A!B)!OE_U(M^%i^>p69( zqX%!d@m-F-lXhrJg>fH_uM=Tu`om^->OT&By~ZV+I5K#Lc4Dt_S5b)1_8+#6pZA@9 z6Y$!ut=gkPM!bB7g|A*={n0JA?e@iX7PyJ6aKfauZ>uJ*Hr7(%#-0%MXP&a0`XY;d z6Oa?rU^Kud-0(gmwj zsagsn(b9Fsy-q0IzNf9*f1F`W1;Qj@<-=owwez1PJr(yf!tu&f=S!idhQWnrn^iW3a&`oZ#gK=TTSAyMHh7x927hygqmx@ch9y zcuLN64~Q!3MQ@x-IKj&eN*DU~(%GAA)`KOjd}TW9j;58*1b4*m)bN>CsmoyWoL26% ztzVO@RxaTLh9|%%inp<0cL;3sth~*->7z*j1ZfQgq6N&H&JLA;cmc#u`Tnzvj%wiX zPZiw?LV}*UfqRxfOzix^a_8L~lMNm(rm6_c+GF?QlP@?o%~ZQti#ZFJZ18w_o`irq z&T`#xcmlNiWRndZFW-$ezHqc+km9zS`Pj-OoIrc@%!dAMLs{Bg*c1A7kcr@0NNVFVF27A9=Ap@aztE&yk?pTf7X7=ZY@Qot-qV@T7p86M;6Uq@f1i zz!N-6GpdL8#aK~-PlkvgM#~_3=2R7iR26h=^v>Lo?B)`lLS7=!c7b@8x2gBL(4!u% z#qH^JlXf2tbKZOWG0*hjZL~t#>`w18O!?P>e>}>XN2ir+5;e`2gDLh+G zrQ@s--sGbu#QxOip%gJ9dRYnP(9gcJN! z4xUjw9j`RJI>I*lx8FuR{ z%{F(pbAOl5uYBHxx9P6^R=HlJo8#d09x5le7WaK&q%Pk``Q>$SrR@2+b}r!r_kH1h z$?+1(q0tSMX%%;?T*3+SJb1mrF-N`zeU%aw=Gr;IwYcvK?{15{6xDBFys~WZ9Fgo)K4&(6g|dwHoS!?Y(e_wOds(+b zHib(#q5D2*_uI?<*jlyRt0A`pS2Gb@i|=y7yY7bv*}qA8pj8^tO($r_oD*m--RpZ5 z+Do;z->&`eXpo8ETISvJ0jFH{6{qU@PA`YAtirB5ovU!d?2*;pa!uU?H01^+E@FbgIkM@(*rFLl00G%KSC(vH{nlpA`J$31`*V@`?olOMS zLK}4c1$S$6F0x z_O`(ZvQL*)`nfDgIDugrSKv*B^F}GXn-B2BHE!wP`|5nZo$so{`!a@(QHuGlSXW%B zU?R8{-&KdzM8W#X*2Qkys0U$^pD*)sXY<)z?=L$l3mfp4%JUw%_ zC)#q?`tz$;EgHVio!UCpS|(FlO*orbyj}Wj7?ruLmb?|e?2vuQO?48i>R+Arm7P}My=5(9gWt#E_k@GHHMIW~@|88~ zE4XvOBqrjc`_|DBKu>=Eg>Gfj%{!LmYcg1)3zoLktq;$q!WX)`!1p*VH;mO<{PT;N z4BzS4*%)ltXF;m)YaXHFURchpcw*raPK3c*x<6}OTPs3e=$2XXH~E;qkJ*3C~9rDX6U9cicU^SPL`3w0If9`z)ttvJV~7SbDw+m3;K!waHs0 zoRYmgrQSatEAtf%G7%=Nhj*-DiO_FqV0~muiis-MHj5lorGpeqVj@@y;m%#Z2FkDM z3&#y@pXMx*&$i)mjFwzswrVOjULvAFd?sba7Q0gWN~*?diqpJi;f)TR3o0I%J!>Xp zGPM#DVX{#-?6G6W`tX=WCF_&(em93Ont)6L(8qC+k&V067NwHe;UHI-J zt3gwX5k3EU?O6TpmKMDw$~5kBf|nuecqs*yh1EWj&l+6SOcG{;*DRcdM+GV0Jo!W> zo_T9Zl}U@y@cc)q>gu;c8Y^=;hAMnS=KY+HL{Nj3qoc0ps-{f&xrT`_X|eHGh(1p{ zD>df7a(q)F(alFuUgxH|5uHA5rEDx0qRiWq*~SU3<=mUs*7+`s4B0QhNd5WVT*|3a zZIoG;^V_(@M6j6%oCScCM3}UA>k$)kXHjzP>L3rDUFhNMiW8>V6i13(b1bji zQ#LA8%E~32;Qj;5YOZJYYTxYFE}ieE2sT6V`2!w_vX0q~`KSkTt@BPE-~HO5vUIz~ z3YTz#&qUy5l)<8I z>s%BlX#2Gtl$E_Wl+}>CAxfW#VRCy)R#RDV+Dsgu_{#C^l@hDGpwWCL5+29Bl2ZC`Zq@5-PoQ@U)vsl$A7i8DDi#W__<&T21=TMDWrz zrBJjy@Z8}DYwC@VUnwRDkJmIZ6j)GP$=2(pb;Yaj zDU79V)Oj*^`p5T0*oc5{i)t-?oU7Y_FOzC};A`&~6MP9(Q@rT=e8>i+1isv>Wt(KA z(44B)d8_JWfN_xo!<>LG1#5lFVJpGgF6WmPfpRvtT_i{g!|<(V?Pe-|bsF#Jqc;Ab z1isLmmJib6w0=85X{^L~K16UE@a1N`6pU2m8uxEnK1jmj#V~v$S-Uq4)}Qcat`8*e zi?FB#Uu)Lzo6Z=<)EZx%_9sZ%6qGA_;170_%TMfw5o%Zi^^`1`p7!@whNd zS{TOGW3*lWRBMuRj z?mh%2zA(BgYycni72A6T)%~1Ee?Je`xPtp7d z(n5k-DBM+Rw?l0f+fQDJI21sT7WeJo4Fc1`)weNmGI;U?jZ1jE7^W5~M7bl4)D0OE zhk|$vQ%Gme$&e2g8JKWb=CqAQz z;93XI!rUGUrK{qO*Qn6!vS0O|JV#HqlU%|H?m5Hlgfd0szWU782w|3DJCBvRca>t9WCA0tnKoy$ik~ zdpkzUJPv))^EdZHrQT6PH_NQ>7EAF=mUL(OL)8(CNC52MwKb=tv+RfBdlIr06|(vkhcsw zEUwShMkBUI-GdhIZ-caupfwzv6YGZJ6TH0%(QRB-SvRJHqULAweDveDCg^OC7W)R+g(76hM$xS(u~r{r0d( z@R5ETP+9ef>hf@=>I#?ecrlD~BKoC5Bt4m~ZcGW0XI8ZgAV>=doOg|NRLreY>Y-6t zWVZGl0tnLLdjoJ=Jy$jLM(Y%9amGFYy9Pv{4f1Ls=fBVPHk>d)s{ms!kBe(zn7mqe zLi)F1s&(XcUwate{Rz@SBHiCD`CDgMsqt&A+Tx;azR$q>Iq#3~rrTm)$&3YGX-#4V zmU5 z#Fy(W=Vd?d=&|o#)2<5NZJGUNki7K{dUKa$kg9_Ny2)ObA2^hfJ~!{rT#NTEIMr`e zL4KYgS{d^5B`cS3g725X+pL=9kVo>iQxY!c^>Tu1nS1TTCb6mZLuw7(6~LV{NJa4)0A3QuB6 zh;naR%K(D3kf2=(*!@_Y+h@BSq2Pc1Hb@Hz+T(!M{;HqaJEpvH>qc|{L0S``pEv#; z_b*FAuN@iwvAPUWH0pGS!X-Rj4AUM5*f_7L%OCevN_?5(@Fz$M3EHs`BIdV0)NUuf zR@UY|5kQa@uTA)#SI`8tPpvqme!mG0F5&TFnD#i}t*2MksAXQnEA}qiqx=cdLV|V^ z;I4D_#&Tx;tWuf0*une9)^kB}ZBOWT(WR`sH$z!XdaUi)c31mmVzg;w-~=Blg?RLP zusl(;ihOhWx`RtNVeW%3Z{(8=D^!uur>~e&#kDvM-}8E1OV&EM!|~6dTng_+yw^_q z9o8T1!Kbd=7V7+mez|1chZZHQ*cnsla+=pHoDWtmB(s*useC@Sn5mU;!ffNG=-;(3 zpJq^ICD&HCgtud}jgygI$`fsV@w}~;S>b8tbzshUoxRQE^1WrOl^+)}5nPMghJ%Km zib<LEyQu~kc(uguH<<1UDfrE zTWNo%Ui4si$IRwh&OcUou_e;)2JsGv8}J{O_!C4M1ntX^jea5HbsH2f#e~0`2`(WT zQ%JvKmFJd-Ar%^*&qT_7?>)ufjj0DCIW5X?}iQ9?;{)ki!f|_ z+&H`CU4dHa5V*aA@rL8O;^Dpz*`OWz^!YqJC-9vd$RSDmiS$&hJup7IWj+aZSo28G;12Ybn@OUvy-ZFe!wqkzQ z8(7(OA3q_0AT1=wBZqeaHtv)7S+)e(sPXnFe;cHQ1bY4V^|L!{CHU;!u!%iw*fLN8 zPmO#1Y5E=R(Az5D^VAYaitB$7={8WC`rwl{U+6ZtJ&cKdH*}5vJM|MqlK2zpsX}e) zQK)4Qb-d}}z4~}XzmpB)3?$w9|04E!iNJr2v7~K1%m*jx=r-tgGl4cplAbDqFsBN} zT?yl^M6E8@TWG8MAJg+eG{!`~8#Z9vl`!t=WknLCIYD7cl~IFaBYcOVQW))#4gB3q zaLI=Vqz&S&kt)4^p!FGhhNs!Uc&SA2cY`=;+!5Fn**^>wQh>`5>BXKwC&JE1lpHqR9r)=2W4U(W>jD*}!-)Ci>k> za0%HUf>H}_>uKVNyadnjUdfYLk5_#it998vM-NlH6ce2;p&fHSM+r|M5k}7EJkJmr zl089Ad9lrhT4aN?Xn!9^BIBfCc%M&PePN$r!JG-2KS5eZ<7j8>C$`Go-_;;TA9=d+DV7K z*Ajn47QI|q7R_e~AV@1Glt@_DSgmq9JgNRK*Zms4KSN}lZ7n62@OUwdGn{e$5#PIs z>vhKz?R4fo0R(9wL8lHvfIH-V@6{`Tm1`1;W4>G~NCwk?c{B>sfi2JeGN%&Gl@-V%wX znDBS%AL(QJ|3zSGiNJr2u>`$4ZUe(;gMK#?TtcNl1lcAceJsJawoIC+=Y!&CLW*jad8$?iQDOLEdF%RCz-YCrm z#fve~?`DEacnZ1g_XMPf^6_X*y|l8Tc#)vr%>5d-~Y^e-TE`i5irYim1AU!8WKPL&LiU_g|_pZ)%PkcFYdlZg7+y;*q z!*osoPZrNzn{;8^1V?cFxB!B*kf5^=xa-_&Ma@0^Qyj4V2p~uc2|A$xukyvI$WJHd zR?4?(6F`s_<|%qrjJ8$cj8i*&NhGXT6j-t7eUKzPUJTQ@kq~=RKXJi~qri$KfFLa- z=rjwS1sH$Ebre=aFOM0s8n;1ONYIHH>~fC!!xfvQk8-esF>`W)w2+`vIe3>vD+kWb z%EI@vGbcz32|D=`qV@Edk+A+yVEv(c0GuE#B$)Zz7_`8v+ zDn`!rc@We4A%bYi2mWi!gIJ105REqIcQe5yJcWU&f_1IF+D0uSuDyCbDBkp#(pRbJ zWBdP2P|l6C8Tl|;HMe1`o$2?$e2|2v(449o!?IhxfxWApt!mkEZ11xI_U_ewTT8A2 z&k~BaDd9;M;da6+IJM*w9xsOJ+z7tZlrKN-4mxmm(4QbJB*iI6E!fXTkI5K1dcV#I| zd#@N%`i?O5T1+oVK13jmG1H&X2hr2xHZY7a(eI><{~G=kNyr8fWSfZed>}!4`b3ir zzI&cNmi%8tdd>y-?RW}+DM4==&k8V1G}@rwja0qgztZPglK2xuQ$Fxt!>6Vb1#S;* z(C=n~OZ*A44gS@eI_~p-!JF$ZihKKuiS%5`Ct*hkVpfY1yfyK1Xqaw6Hf9`Mas+ zTyYCVxHdEMT5d*uq)ez;S8@rD7sEnps)-{=jF{Rrvc-^Yj#2Br4IoHsHV`-0HPO~T zPX%JuzYE<9c8`q8HrepP$vW4`VmL$^|x_9B!nEp;@4;ERBX*Mnv_LQ8%w@T*3(qCoXBE zg-yu|#27?4aA))K#c#Q ztoz!rsoHlxj?jA)NqD^2LanQsX!WjD2cmtRZ!PVwjEuTD$rwdR!U@b%acoy}s{(QN z$7!xxzczC8eKblRcZuLyXrsW>rrOdqn5yaOmdJ9lsnYq2B0515PGFc?z7PrJ9!9DS znkWSu77HLqi}y66e^cMZGNHX53ggNYiS%7H91)P1mGrhEmv92Zw0DwzW`Gn*3}3`p zf4ujvOly%qg4Q@la{|NU={uEoTS7OG4VrO~pwSsqn?Bc4K05Dzy`D=rfngf8F=iv@ z+y<5p5wstGgt4MW!qxa*g(uG*SERW72^?c+r5|X6;^JBq6YYK&sq(DIy8*SxTS6`J zkTLwe++bv&d}#R>t@kHL3kmWW(+Lc536D2DY6{{+IFmL1Cn(|V3QHPGl$Ufm(Yc1b5|7uvbqvDM13m=;>h?N1ybZ_q^L` zJ=q|MKS3whfi^fnT4ckhK{^$^-EWCrx<(5(R(D3rH=p(zHllx8splL^k{aCWW z*FCKUIYC-Ta6i$htnzhF8>vac90yg0#p6SA`glck{^2%8H5ieaToGBcPVEQ7yj{`QW!N~=wOytA_AL4+N)k?RZ_t>}_Xii- z&>`%w-an{xG413BVVFD|!$zit+tS(<+2HY_J^Ver1{-wmwee!N5*xXM6Wo7H_cBiI z$h3i{1ZhekhOtD9c7-)~rbF9LX0*5HVAyu#9@6)UaC3uQFdt?cIkVb7K|3hn^-NmyJEjozjI}w2(A%c7Mhepz3-!%Ff+YR~KYcaZ zpmIloQix${J%KjJ$3-pjeKCwRn>G*XyDO9rlK2yRPsW@o@&}PH{KWJo#l1rj7dEl#B8 z1M8ze$;D~)!3okrnohF8VP)E#f~iV85f$0K+&_BSELK7_+%ukp#6kf#sIw0hrn@CrArv zI*B!GoL~DleB08W&ouBcMXyRwK!q&GEAxB1Zg2nBOfFl@^MVv zsn3Wgq0<)(^HUi*J;D5%TM0@03AFv;If|dFaGFj}0&S24ZE)g$+u#IgAx)!#gHGiF z36l5|RR4hl`8Y`M8IF9SK!POx1odX4NBveTs~cI=;sj~Y?`dl_dCYe;ZA`>6AuofM zRk~;C-*!oY@p1xt7oDG*TRSI63u)?)|7&D0d@5r!Fv2*-U|R?*E0SQmoWO8;D`{1_ zds@!@3G&Xc4Ab@iWTRuPO{Gg^Me(9N93PD*S^Y;idP)Gb_|pS8<{NL=z|vhH!_#b# z#Gf#y3iFSDsKp7=!ryUbNPAO=jBJAUSPX(BsKtr&eE8Qn?I$5Y`%Dd zKY{i>Ji>8;w2;QWV!TxaOLwrgGHo^>32JeI@?^BDU-KSK%eg;6wTWJh@pc&h8YBtX zAcAT$uhNN=+`|XGIuJKl8%+D7rkS>&2Mzk(4T2 zjiMHvBI56Kx`?TF%JS0&qi~bJ6HFsjzFnTQvf}a52_K~@Z8yr~Uy%(SFNUcM)5{7&T;fkqxdjru_3>1ZZG%Xj zG`Z%VKW^6FNJtX2K?IfposzdMfkPw+N|ba<20?-#L2^=(WbQT( z;HiKJNah74DIg$OLx@K=-_+7Rl{grBW^=ZjToIia6 z%|wZK1@^+T+QH7H&3!|Xz553>)odWWy5>?(2ePrIB7fui52Sf_NV4NcBGD_&Rzc8 zR^KAoRGV{NXfOOcY(w;U+(HQwXq)w;Z63AJz#mPgOFENTEo$Sx2rhZ_&uy*xt9rN` zNHp+=pGRy66Cso&>Q#ge6MxYA&CG3j-|5$lZ5#9{Gqe|e9*%c;L|}s7ca&&^?QO)X z=oyRH;L%dj97jt|kx^9HU^^(ujIg6{@X8cVc&|?gWiRZNy*qd#T#i5KU#Z0mgk2+% zlLq#O|Jp~k8E!k&Yme>*NEI|+Dc}B0I zJv>S<9qsM54YA-hQ6e_L9=ADp#h<0Fuxn=8pQY;tj9N=Qo#{PqnLIau_Kb2HJv?6R zP&fPeraD_m+|(+75+u;JVeFw%=iT)NAjmvMYcr@4( zYSYfrBOnKb^pYVrJO4o!ldXg09T zWpw6UKuL4Hl2gXrL6l@h*j`Ed(aaN>&(Q{_WkwYnHUos(n-m*BXR>E0vn5C2l13ZR z^|^Q^*8hvJy@DvilE{MA0TCNaOO(OS={o_#kqo`>La0+c@e1rkPI$#9w>992*8)68 zab9RI{5*U1er`~A-z2Vp?2sq zBbcUN+9+2y@J^3{4jQ+tp>vi5c+6OzBWi>5U43p*fX1=VK{b|K8J(==X#RvhO2h_u zsBF_OXVI@;{609@+l0m|w1M=oxD|mn$i}NQR?;{8k>RWi}n8^>^VyE=W-lN`$Uxk2~LNfhtCZ% zA(TYC0y<1w505_g>Fur8C0W_vSOo2bpNFFi7~zCa5+q{1ipHX1gQFrzvpunqanBMZ znGtqG23}d>3Dsi62InhY@pH9uR6UVNl!y)RFtU>>_3O5zMmaCECoOB+5PfPvA-G>@ z1lnf(484TXb(psUEWQVQ&gYJ5q%GILidWtsn0qU zbWABx*Li}*jJIe6FlbGN_Wq!efu4ux=XYr3#Ssi!+Au3Q2_;CNZTj^(8h!E)P4@ml zaTeM@dJv73v=$B3p|vR8te_FD$)IG%a#|N6fm-Wn6y?$NIkifiHzP8NM&=J*nW9#B zL=CS}Z_+q*`<;SbjxbSz1lm)3mMXI3(#z<~t7=KJJ;}*lZDTJ%NoEAooU{D7Wp;L< z4Nl8kD>gC^YCl1203F?Dh?GNSWZvbFG}@5ek7(Z&>;FaAUO|*$N@PL3!Y?+MmMDXt z(>It!;}Rj%{tgmoTT0FUx=o3YI4`s((UNT=%0vid0}0(LYfXw(t-%EE=0dH5Z@99m zad*wevVjdbvZ!~W+dIVr^M+&#w56WtIhB*<+VVq(Srd9zbG)>zO$a4O^nWKupeyzE z@;kE#3pDynX3+2$4XoSBDf*z5U?$YgAY3PSvnZeeQ6yuNG&a1c{!mqJh`R zM()b|8IwQPO$?P-=I}N=Iani5tMr13{0_PvA9#+4!|(hWv_2c*SkY~ig%Tvj6|BZJ z5}LR7JQ2Tszu5KOGoN@Hbs3-$sP*lt1U1HZCSE7v(;m6ZP0xJdFzR=(P=dtjJGBE{ z$VSiNe-U9U?qJRwHPc)ENKTDFt>$MNsd8jVDnPaC-rCcAeBxgTgWfwDLJ1N*S1Te^ zLVYUbw|j%l_;Z`nJ~=$Wg#>Eto@sJ>gwCc^CL7mNJ~IFQyNaWKlVpuRt)-Lds@`*U z_%lQtEnL-1$@7V~+5ne{5+qiid`Xq#)lX{>QSrtj*XzxeI=W}=Y@!5-LQAWtQS`M5 z{27yDa~?TMrp)xdaW+LGQ0v->V#-Fm`sB;zq2q(Mdftd%KQP5a2@*p$lu(gnvyS{( znKI88u=aXuIJRDBs}ZQx-IpiOjp}OGTUCe{VL7ZXC!F&BUb(tPpccMqhOuUAPiy0? z<&Hqlqb`&nfo~W6LU*4faWeMGI+NpQNvl{L*U{mDAw0@~1PNK`*^$1DxXrINE{LPi zMYS!(3|eG~u`lh7eLI3qmTVg+ftVpea|9@(l}&&aL>Z9?Kt&%qAu|B1Yg}9lGNRh$ znELplRPhQWLNkG@3|bScC`cz6wpU1?mOQstcLhEjLnktBb76(%9&LvOY8v;l=zDQ) zm#4ERx7mExBoF3`^`_g9_SoNGcRa=nnM8e5R~%o}UesIll03=tQ<1=$j z<(0WBcN*r4G{z6n_Sj5bVac(yvioJXdA&tfReKapE~ycyg?m|18=OK35|ZW~8YSqg zGZp7PjH#t|B?4fIK8+OYmWC1}utuUbIE4gi$#Xkqc(TuuNKcgB2Qih3gEFt(Av0IT zqeN(kWE4%`-=2I**=SbxSR4}Q33?bU$E8ve5=6o+B?R|y=`nT-9-lrfj(5A5MF|qv zkE1p?B_j^|E@`d>8GY=!8uNG=)prXe&rd@M5_pnAzqPeux+2&H5~wB5^)_F!v2^g#~x*mc!i!si3V~$sLl=9d;YUWAM_UqdAscQ zT!@`?vX2C6Vf<+8vkgD>c9b9?Cjzn(j(VjLa26uZxpziwa0(@uucYm@v(4~3cp)`2 zg0-Z4xU1$icLuvfO3o6@SIU%e#=*Q$OP<^FM{4pZ)!SRuJ(h|RBygA8Flsbkre=eo zlfR6|HqX4ra4-3K@8@df+}>$s8je>Omty=#->u#>XJoF$F$&{3d2ZKk(svWo$Z&Al z-gvZu`3hmTd7Ce4M0z_)kU)Ee(d4?jru1Emudp>Sw$pnFN{|q5^?v2fQ$g#yxK0ql zUKI^!I7!vj+NtXkP=W;3GzH_&@i6-VyWthM^;R8U|y&tHDcH9zF@^jn_~-NT#9XD7(L3J z_wp|(rH^wa;Ob7axDAlj+Z-iGNZR(wI@wOeC0R;3JR;$I(H^#D#D?0*3C|g7mt4{u z^@ZQ&$nJUc))q>TFk;T5*baU3#l{7x;W$d|Q-$Y5mBu|F!zlUP1D*|(S13Uun&y$g z{9ki%7_Y&)$ zPMcGO;PEwD3k?GLUij$_dD5u2TXXxgNJ9d(#6x>*zqfk|_g$-Pi<1ecg{J^Ifpvvv zo8gh#_C3=UWD?ipQoG#8q}DlY7%$Vxi_5_T_f6g%;Jzejo-@!x*5g07#W5U8kdSiN zGfvjsCHOs8HjqFqNo(_<)%eG6;5+wAURJOvz7uni*#5%ug;uWXy{WpvpWnas5WIzIK+vQ*zonJp8afv;W zK@ZpZLb&L5zrqm?wdA?puNW2U96O^|(z5pZVHmwI zs+{{(3y$lvKR#-sfgiP`cJ1{?vn)^WtY)=3GsA;gc#ljcq;~mVnU}b~N}5ZHw5`uJ zM$cTCh7u&iMzpTv{Xhb>B(1HZtPs8DIC6%gaCK^xIYDu|tnSntg@p7sj|8{Dgf;PFGe@M;1jNQj48)Msr!?Uz_o&B&;w_uYCYven|ASaVW= z1l)DRT~3|o{#Q-aOMb2XxCi&9#Y2AYaPBgU*I&;OnLp4IN%MQB?X_2=l+A9;9jp`O!xLtb=Ch|vRBH%1Zv?9bhPhIa+Go) zfm&ET`W3!s$0aG1Q&i6U$B zpW8x-*Z?|0M7cb$zweAoGn zcbl4(+a)_fAC%Sz)G9qA?5!~!?m8E%lAN?|nl0g*1E>{#uGUocUFXlI74$yLR@aFV zB+wq$sr=Cmh{AT?WgBQO{5)(!^tsJZf&|)T{b-vCb0R%5 z58Ad?noA_w6{mkSd=XjCE^v>Q?~89&Lu(x9J4Cd4SYpo2H(c3L-+U4UO5^Wc)W6N z{*1~oH+;&_Y~{Otlpuk&>DzQaXli<^Cws4SFKwX>q&L!7$u>6S;G4@+yOuUjFG_aY zqhC@&0=4LOuGHvyR^4bERl^=d`KFMJoV*8sS~7z3bK3uYvaYl7;DTQIjD`?u*8mB$ zr?;Tk;N1a9bG~B3-Zj9n1SOdfwpVP${&Pp>bF{%}nQO&H212bl#RkxkUA5?#D6=I; z;gUuhvgXV{sGGf+5w=$lmsk>6a6~Tz=POZ$9qHE&M>1>a&K*jS2&Xf->uemzrg{VC zh4#YFGr8-G5+u;JVf+{#eTtHIt}nAI8>&vgUif*~D;VK~uq8mCZEn5jC@MC%7A4L0 z#D-nFnGmXNGb5x0qrGJLdAqLA2B*W%BfTU8q1gaBLPX0UHn>+y8f{2#&p@bmFf)Q_ zI?cG5EpTZ3qJ(n~Q><^t=dk$h&{;>+2IrePGKU&V?7PklCr57SStt=3;Gwcj5pvto zR;Mocy%$F|)odW$b+v87t?oK+E$Fb8|M8S##`)?Rfm(m8wY@do;@>~NK);K_^?RhU zfh7HxBsWJWM8x!bnhdtkqVXoJ(?=h{xHMktBc06I+62#-FS z>3y$O(YC>{2-*uj5AW&22q%P+AQ9_TbQBdE92H5L?THOLTEh7QC7BU+Lwwd-rH$;Lm0lhL2WWzl2AIr%#8HP=ZAC9psY#UBY3Fuk^I{epA4^xCt5+u-`T5U(xA7X=7)skj=V#8i-V=qBTW(3pHdUl)3Y>75FEpx5d5Xv2y z&tnO+t@4hPLu~LahosSl?0!W1u2}ys!uATH3{zqs-s=$?DqlO|2=C%#LMRCmXj@8c zmq#Kbwt@B}T2jveahsYX9Qyzr_NwPoDOUOPGu}_WSRMRgZdTs2a2cD*2D;8rYuwPy z?nMLRmfGuG<8(Hf4IcOOwH|iZJ>_}lSQI$f@PG3jsbp*QH} zGUSC?C3+P!Z91Gj^w@`w_{eju6c3ckMO(K3>(%Kxis;GC( zn8F%?T0>T5v-g%h;olxeo6ydz^ldNi@%a22fm&79W>fF^4s~-m`>7POd;9T@$3M$c z8zo3AU#1AE-LhokSieE$gY2ihUrn3oLISnQPReHS=je@Fd>gk>!)E5h%ju3UnwK(B zq7hVAYL85PtNf2AFS~xalpRyxNB;N`CQ6XF zmfLPYo7j?CFm$NjN8UGwjMNC!T6rei6OZz@= zEz7n0U5b4Vx%X2)#ACilq=pNleWVved53&P>^F6iSf58qsYafm-t1p3e*Qj^0C--UsoHx=EaQ?SA>` z%6OCr4N-=o=@Yr{o>H~T{vm;$poe-nM8Yj41ov?1F?I{~ZTFb!yU$*39gh+u{($%2 zwjnJjBM$p6X|4qseeAlj8M{4Df&`wu=;c5Hwd8rmHjnnJ$XS6JaqwhAw}Fyq??YPF zA5wDkBuX@pvpaRBr`te(k&w3wS6+HuaS2gNi|xWjYyu@ng!kKBvPxwrBY|3ylXj}F z#zd4LA!&PEYrEw(`QB1y1Zzo+;EtDGa+YAeQl{vPBjv!nP)nZc^B{YN5+rb(w@V>5 zu+1~?G2BaDJn$=@>YI0J_we9&g;6HPkA~5p%ZrL&Ygktp2VuNIxi_7_C+?~}a8$#1 zPM+KCaix+?yt9P9jSZrE^h5}|m)!2=Q#KYSC&r@$3ACrz75a{465D#e>bJK|8be0E*sYV%wq0ze58IJz1}uD3sp zL>VYS0!LK(71v1*RPAm}e!+thB%~a6T@AbRuOc1}{vgtVEI|Tmoqkof_1`QhB%R<%tf({S%4Jj1EI9^7p)j7wWbaa}2| zP=Z7>Ewh0T;g(XT7U9yWbh!6~cOcm(A;N90ZgNPPXUlN!ArHld)D>9Q_LJqgJtp2< zqCT%??Ht=F4kgiAXb=cTfFXM?eCHc^;>0T?P)j_tN9vk`ACC~Ih5PL~AtiUc_^t<6 zzfxBj_ZjB*DHpL3j*#%ALG=u@XIqeRphRe%0mLhNHkk6=yoe1XP)pKw$tRYrn<_T2 z$KlCncrMX)w%t~PzmBA#1c`7o5GKC;;X%X(N-`s~2-)%sekD!_mLQ>@@Jf5Af5W>@ z{B~l0)k}^9N|2DgtIf{pjY0you)oX#1i_RC6+_1^SdTq zaT?!$!zeU#Kd-#3+ROH&q67)utD|qViL@Y&SJ-2)FW5dwzd{1Fq1s7&Iiemj_Y!7MkXy1+8DN-YK^f`}-^S$=1;ubd! zVQ-gPNQ%(!Exj4ORm}B_d7+lnuDzOwA6%Q~L2Kf7(kuC0vC9$L zcVWe%W-_ex%n9z*k}r=R;%zi$5F02#LOis4qHV>V&yheaz3+aJp4-bdrZ<`Az&Q%{ zcO|EcZxrS$X?~0Jy}oS&x~EAwaAy;DQgyEy-+5N`#HZ&h^`IxXv#om-_fIa4$gFye zN_tR&1bS!~pPb1;=U8s*;(H6?ao-qg0Y?n_9+oHPD;p)xzmb6XVrg|7+ZH!fnC-`g` zZ)h()KiDK!kai$1)~qGOtJPAK)?-$B;K;0y(%Q6lL120wuX_IEpVw$t?f32jRSWhU zP|tw`YIW+GrfB!v<3ud~%%O;`+gc=`L?eUf)Ybxt87{w?;RdOv11X_kPkmN3T~`j$%T9&tOS1=o~+Rh6UD z+n=V5x@@=ej(W=iNMKHe@z%8tss*op`*Hk?BdMWpxJH-$7I@=Unkubf-40CNmZoaj zZT(Fxcp~kN>Q_&{d>{=8)WWtgj5n8VPf; z92uM**q!Yw)%)tSwgT8g4ddauS5!GJ)n2QWqt}Oaf88&5M!SmP((_G`a|RGqkwcL>gY)3($@mE{9daf)Kyz-TuUe&#D@YZNg zXaYTdZV`_@7iy(*$xZfe#At75B1zn-Hv`K*4~523y87`2f$eEFv2`%d1|4qJ*iLhl z=}Gx44kbwBc_CHVuDK(fh|4F>C+;QU$7A<=NTAl`?rEWMWY0Lo^T)2oa&wenHhed` z7YWpIKj{e#Wun?mA_lJO!adO(^J!8VmJmyRzo1<{PcJU{OD$J%FEOWoJ|hh!NYr`H ztIF}(As%-fSK2ABI^SL3K|<52>I*I6I^2?Lqadgr?MQ|@c0=0gnxt9Ce+59}$R@zimeKWA_C6%Ak5TOw{ZjRk-HAmKn$hUP{_aR!rsa!o0o`ZFxl*-9pVgBRu=io@Vmlc| z)>ZbmKyh7RISys9%jEuinN}wHo{9UP@knjH_0)Iq=sOZd{;xulxpoWer1ltdwIt65 z8Q$7&k9$>J8I}GCVEO1f&-Qfo@>@IQ`%Vt*eP@^ZR2!Tvmp7>Q#D!HiD;w={--t&^ z+d_UtRGgY8i1rL4{(oClZ~r!Bvj-(eWbY7AwO;;Pp4AG>FA+JlL;|(+a%8EZVmPzL zgyJ6b3d@1^=(9_^yQV_rnbdC5_BG!QX*y9ijvYob9-V+@@K&i{txC?|N`fEl#uZt9Kf^hTeQR zSc1|A$24)d=RZ#+XCiU_u7o2mJk$u(;&g*Ao4Ph_uS^8@!U;R)c+EYly)3yuqp8c? z-KFw<^1UXm@-q{)dDk$`5OHnzLf?TJhkWQ2=8JV`81!w^X75ec9rrGF^`is{PUkJ& z-1Y1~&yiPmiRe3HqT_ho&wVVZbGNx`>Bp{MNlNbwG;=+gYX-5$&^KTb@%yopj&dg^ z_)vlbMgxYy-`X;I;y<1tr|x-Cf&|-^8nKCfWs3Ozcc8RJu$I&nwvAo8`zQAI_Q)|` zBTx(LkbWzLyt-Y!wy#35QhuxxCWba@;o9V`64Q705m7qNAHMgypYov=(;ND>bd_K6 zVhmA+h{AK%_zQn`&l}qwLU2xt=d^U~_#lqj<0KK|eMf!tWt~1GPz!6_Fs>1iC$uf` zYOxoz_CSKuJ8raaxxGnb;}0UHJo8fG3oQm`AViDHBz?g!y1ZS}-0<^<{uXO$Ss1rt zgshJ~fyFh=&S%H_pYK)6LJ1OBKDv3fp}N(#?lVbu>o_c2rQ!&OBRG8q>vko}tl8Y( ztyW!)KrLLc(l@?;dnJ_r#L=YAqq=Q_ zU2x`-?~^{>J<37}5*TaI=jgXIcZCk+3;4bnrV*%xQ7zrM`=^kr?yYgY^xh*i0=4wD z^W92A&D8vZ6LWt&+=W^gGwMXriXmpzE2Vvvz8~#E2@<$&H;g3*Mu!?bD4n=+`49_Z zAB=bOb?y0&hll2#80`D4(ohQ}NZ=laVZ5Dngjw%@?!=uXYlcvQ1jbtQ8TX;1%$%t{ zf9o1&f=HkiuEOcl11}CY>#skW)N^J-7fO)8n33YE$NQTF7M2L)+q_vLPz(14sIJ;H zGtakhIJeg*WugQLjJ4={QI47Bl`Mn3MaEXv2-L#$C*5KlQNtWip_wly zr811!Lti!zy;widH7VXg2@<#>qe!Oo4~eg}pX)nIvopqUxJ&WaH=9Dng{H2R3wTvD zYGsMUQvVM3@OJ{BaWnc2FBmyN!=q3O8ry5CH z3#2=C5P=dT_VwQyI+)&6**1)ezKMzDA7=F*Ct{OtbEwc0O_XHm^P59U*EDf$Ca&>AP66BDV)h zx?S8HdTC)x*Xj)Ik>i&oiM^j_?O#L$wmA}5hxCcCE@cw;B+zdb6M+&WmM+^8DnCHH zYFhV~#FLu}`$I7VYGKRLnls@-Vqfcv#8X6Idte)M&9XIA=rg<4i8$;|{I^e$r2R1j zYF%%;CDh|#<8WOK^k+@#8@THDDTY8Ty*;M?G1al|a?o8Z7#No}GLg^Gu{zCUw za2E&HiH6Z;M~}qk$By>04J0PfyIsCbQ`b*1G{q&=hx*FDY$o0z0)2mt+S#4GrRyva zx>s*!e=_m-M^F0xAp-L~OYg*vK}}T2(L)+{>+EsVygtN7JA@`mkmyP8%DdD{ekFT! z4|UGJiQ8KYNa{lbmT)P(^OMH4R5n)9JAauXvNMVZrahl@`@o-xUlM^5_u)+{3gi1e zm=pb8-?cZAEN4>Uk{BCEU>zDpuXSa7-HNwT<-ivFlHR*X&o*(LCmWL-TSGl_G<985 zUQO^heU}F=@^W1vfm+!9hB0e&8()$9w-bLR0^8swy+ze&EaCRo+v7&v(FqTR)N=kq zy&fe<=q2A%sA}T2?)jXH=`&a;K>}-j-Qe`r#PaSRy#ud=Lid}rbk*7H2y(i`Vv6o_*9zhq*D$E9t;RXp zCq0v6SOQ9r&{x7&h?uwKaN?gWx;jvT1gA^TDC#a*og#f6(=Qdc=g8t+pMel9ChDZO zaP25vjflU97~~)8_;bYDK9&@v8F}gu`dJ}LPonwNxLrG@9BgA;kI9Z#a_`7sL-J)h z|3}STyNmEjnD^RqSAHS!NP)`AhUCjyQg2uz^l3mM3SY|Qo6sa@Vrm2Tnw_gJWv}?R;%o0d=j~XoSRzU|otx&29i^X-*`a5zR^965_~39y z-!g(D_VJ3-`_syX}E8u4@-yy+ml+SJ!B$Ul|Ajto3_?5 zfF#9kHg?SzQzMA>uzd78kVMQnG1IrK%^8hAEi98=SA&NZ_O*WVIWOjm_LwL?s)?&k z9$rDxUWRq}x5?gYPlq%DwXjTvk@sSX^}!$Ky+_Ai4B*-TqkcU9qP_6ZDb~Wa_55=W zjSM1zTDT``7_Dl*Yb~w3D{0V|r$Q(}0#CN6Ct5A6+2(2gXLpNPNT8O!%enq;5o_oN zzNC_iT3IMT0#AhK6K)4nLp>VY@aHMpPa{wZ_xcT^onoQ{34QH+?8{oUXIJ~#G1k%v)WVfF?O)9qX|DS%uj~GWxlUYj;Eas1FO4NV z`37p#vquM(y%%75ro0DhGaUy|Q7%dw{_xFmM6FRpr|NV7N03}H1 zGiP$4{jN~+US|K)IZh-{3!`PjSo`sr+I9PmGN+uG6F>8_$x<^)iJgdQi>w?JkHHTS!KYSyUt5m)KN|3;~l)l|KeSo#J^}^7sarvA`pcbxJ zX>2e4n)TS@Pgq-5wF#gE35=X6BKtMYDpkCO6~Cd46A9G9^)7wir|){`?Ll3wd>iux zP=bUWS-#b0XXr}yzSiTD@;Q+}EnMT$XII873|>s6Z#}8rCV&zoFp{Mm7RQ;|@4Y|D zy88JXClaWIt760Wpvr#Ntyg+k!RO}&P=W+T=k(SdC}ReOH?~r$>~tc5TKa0cX5}Vk zqX$n~?N84QpacnAkW|E;CAx+VOzZAM0<~}?qPTs;K=Y?Hb3-YcyJn-NN`%>QabmkH#acB zoovhzC+*q zcs}RB4;O}VSOZLyV7{D=Mwa^q)7XotRS8)xx0yKC3oG0H>< z=Br12^-W1uGy=8Q+vv$p-d2sB6)F`qtL%79c_k7g*j_Xit>6ESKP|3; z`5>;LMxYkkkaHutrMJ7Vv()54=F}f&xKM%w#=eFz_GaP0k>f+n+4cKt1Zr{1%2^@p zEq$27`EW>I^YdC(2qj3cJy}`Mr)#Rbn{+crAG2$tZ#4q7*xTqCWYdMk1M9CpV~+p5 zo`sTFB6p8qK!_H58$E-3n0;Qr*Kc8{YU%(*hy?THI+Rm68cLcjbe0&A#rkP?CkrJ= za9Y-%v;#SLL7>9BE^9{qsu>8;Vy|Sxpvba#NoQkM8|&4%g_Kt!!F)L_>uAH+mo(9L zYxzj)?L&D(m=|hsT1F!JzP{}P&5q?iPdfD0oDiOd;VGGZYI$hxD6?|>H@=6-$AY-q zkEZ~**KZh8T8=cg{3^)twmZ*?+H zeb&c6`qiu&fm(R-OC_(G)ja(5!KBCE@1*UE;(oHeXPG>`mRa{suE4K@Yia~)X*-_A zuDI8&&cEmPf3YmDh3i^edE@;6!)RZ(xz%aZvq{|_me6hvAc1!f3?udLc&l-)T7GBN zm$f}I+{?n1w_%)a*1!rieJ*Ka>xw2ykZ4A`335lrFt$&7#cc4yjigSmmp5@o825T{ zC(JOW+6A{Wwr(PQ+mgoYk@~u76pHx z^i?nKqz+v1n7ZTDu)=3?ZHI({2S}2W?rftL(sU;LnLqI&?brMlhLyxdR+YMni|J$Rb5x-`BX(23xyesx3WrGE@>&efZPhe+$O?m2^} zkFE_Kr1aEPd4jzruUBPSNO#f=qv=*XC$}7HOgAycuZk(!W+Nth^$M*>-8*@ILk$^qp z$dm;t-x7jiD&}W06oUcmWGtWy2Nc=j`tJ=9x{xh0A z@@hdbb-Ru03Ozvr`>|n68qk+NJz!p_P%RC6BKAJ41;a4&B&oNSZ6JYK`@dPG+PwcZ zzTNh!IY7O&A5WQ@iV`HSZD@V|=U7z^*M=-!^c~+jy&V0{6;pNf$LGH7uZ&%w>Ss6I zXsferm1^guT{;GJ8*7#oQZ4vtUr#NRAc5YJR~>GucX0Bq&D-%E#P{xt>=*2ktNYYf z+;x?WiYdjs6;oC!ub%v?ljhYAD;FvcZ>T$W&+N;m%2DqAj0BXRS6Dt86CdqUcL!^o zEayS%zbrhbdV5#8PmSKvt(TwQS9k7u)%R(mC=&P<7{>nePq`dcv+G&YCO1qC7TxfQ zs~6p;o_%&pun47hb}byd{q%PAeA9ZqRa|}Y%WOk^4zhZmEy2f0>y3%O2Ug8msI+F^ zSrBO6Kct@9x1$G7$<6)BT5&Un0}0f+`L0*lJDBw(y|r0}?Nna*$29dIfm*+pN(~kx z+q<0CiFhiDx&vu>cE6m4{$e@ypWPfRK*X~{b5c2O99p7&3u1EZ(jJr`QS{-4U@0P| zjwwLI&}Sd1a`5|s1ZwSjZIh}6qaEM)b-$d0+uYjhc+7+T-k|PyFJwHX!eG8=^rmqJ`E*E9BUC&#HZ@6GZWH+NTAl~ zF1C%+>aKJC|8?dW$7*uBMjA?xXmB=5JCYE%c>siuYKNFuim>6R-T~VcMJZ!F;WhcoLIOvSe!h$dm&Fyw^2SRi;vF; zpR7F5ff6J-q_0wMZB2DM`ql@%)mZY=+|N>xKrO9&#>N)u>aFcnqMieNM;quZ-LmMS z?w+ghYQ$FC`u!m^XS}ykwMT>8Zw1jFePX17{nqB(xFHTDNKErDRJB`z#(cVm{MJa- zuPWS`nTC=+;}@vfz22!~jE(+ni>7f;Y;f(9T4)0az2sYWjYwM8@h`_{s$sN&Ug5k# zCvo?7C$^rxIFWB`p#%w>yJ&xxG`G*c=d1VZE?=R*s-UcR3sX8kH>=!hs|59#^Afjr z#|4SA*DUhkOvbeAUvYXV-9mCtPo%oyTU053RQ3J5_C-JDg*KR&J*=6l@nOEX%;)EE zHQx7DFY>xZpcdAlVH_f&$&B9Knco%jW1BOPD|}wd>Bs2I`(rxuwoAUH+Fj2pDNkk~ zL<`GD-*ihhwlB(`nCs-33?&zWZAdLpOhtsR-=B$F+BQ+OD|NzJHR#Snmpiqz_`xuK zBBIV?g?%SGKFVN22&_Z8mqEm?F1`JWx9s<#1Z{9yTGlT4;(sS6UR{&dkG05J(gvJ9 z>uKWZ(u!{mY$h946-Ux5MVI?x3DGJ@#1r8YY&y*#;+^VGB{r*nS0hjh+sQDN5^?Eh zJO9h)hx<^AJ&_$jo#5I%US^5!%<-RnC_#eL(*E>oB)w`{Gj1mNuPm-*VZ4j=hU1E1 zJhwN_+A{O?#M((UER-ODHDVZB+gCN8-sMZISj%PM$_vLX9FOT_wB8Hm^W9(cy+1ig zBTx%hVHAs0IN<8}-n^tvPxi7HZcACs0dY-F;Jas8wRX5Z}$_!(FI_@tjT+`)Y`_ zvVV@m^C_cUC_w^OmJ~A_8134hyP|J9-CV{<2BQ~Tw;4w17QVxI2BH3GHt737=OKC;f=x#8RX-CHh{ zAb}AeeI{=25UYYYFe!DBTO&{l*P@0|r(u1oRI7LWrKUV%qC_JglBM(7dvz?w(_i`) zBtEAR7$M=Rk9zz3TGoPBok_R))wD3C!blI-hKAv)Tf@roP6J+rM#aBLaQT-G5K84tZ)6XZQ|+s1)19sDJV)=J=;%SfP>Uh++cD*8Hn?oMQ{(D(AK4hC;dZK>{1@7QrD z=%!m?wvD4N4fKspD457~g%T_W=0q!&Z5@5z&AaO5yIxpAtZA$f`gNvl-*~TV`NhXG zC`zzB0yFmqEBqn1abN5g^!0h^2Hg_MS8tC?z5Kqo zFAw?Xvp*JU9qh3$xQ#wn#JAOTVtcTg_x*0&{0oRc2@=?vhH-D{9$)(S);^BRkU%ZH z1rtbf*2v<%ltYV?aGwEpKX5H#$5)??Kj`zFzMO~>B=i-_`IFx#_T299(JeO&$(O_mkCr39LowlaqOS`T8yG>!7=k8c}`P;UIs;fbStAO{34bEs5<1-@YgIJLBW!b#qHA%;LL?4gE1Bec1^e0%@M{!jXrj#?0O(=6jYo)F}; zoE+my&oEvg;;~=n`_F#-u@@ys=<7lLtY!B`i@ek0OE^%11g8%kBHO=JrMR8ny%Sy!n^rOr%YpggF0TDa)>p2~bo9SFH4!C9u)XLh z@-6aeX8M>!-_G|m0=3wyE#c30(iuGw8%k~TmLGN6hr6;&6rfrE^4n$*>(DOwuA^H$ zJF5Meq2xla4XJ7RCLOY2&3G z*mdO(OiCP5CWlrIw5Qr8@|jVZ$IZ&+^Cmv}dsEvyBaYw7OeQ~i!4rsp3O#F!eR zW!z_^IjZR}v)t>i2Ud-5A3_Ndc*;RHGjlgI=iRU4%+jlZg#>Ehekt9W++EgOUHKb- zxgTD&P=bVh(y;%=`>yK?tN1IJJ}&6WNfuO(@OrUg5N zbPI{RDZBlzq~;xlhj9NB3EZEf?`QZs#Tu5sNWgWXWB?^d;7JqR@;)=zD%seVv}52z z7ZRwY@7!gX-qQN#@W1|v$DS}zf&`vTQbg9dmNjVh`lPLEYH9>(;m$n~35lVa)~tl; z{^2G{kigX>jfl-(4vnic#rI>e5hhBI(AS*XFOIZk?K50e_IsQdLE_wp@uOk1_+hA3 z@}>Tv76(^rYXBs07A3EC4zRwVTVc67jQ3$)sD%+H&71|QT2nu8S+3JBI8lNGMwxU* z`>43J^?Gxw_LyY>lpuj~B7HhDI4am}V2ZWm{bf!hPz&Qyx|eZhRPD+{EE}~ffD$Bd zrlvcP@8vabwR+t;-fp-P3Dm-sjA7KuR@JQ3-(?-YxiEkdBrxuxPs<+fWLD^w#cFh5 zffEVT!W9zTLYhCsbTu9wD!2KU07{V1cAj@P=z!jbY}P+4-E97i!^3 zk7A!LyMsmPHe)e&n*d6Xz?hM|>N`C&aN8jB_oH*1NT3$34e8tkwzUw~OWfjO-)htwfrxOX(!V!a_*SS5djO6mS=O&HT8?6DCS9Ull(@ zBFj22ec|l>R8ceC`!;loaZ|zLL^9VTE3ryzF)LM8|RW|YFL5eaTy5FVz1;pfo_Fms~mV~e6p1z^}Guu zm@n6YM4W~(v)0!ERD^~bAPC_#d2 zA-XoWx4LMOtHbEfz0E^30<~~uL7)G)P}n&wu77CZiJ=;STI{Wyp3t|89V;A2U%$`w z>&jlL93nx2J(M*S?W%Pu;{5yE1=s(Qk~IRg*oK_9(5}I$!hzn-WOL7%3n7#s!D)Ht z=^L}o6?WcT-pgFNeP0Gbv~a|rlCKzLb+|Sqss6%4wQ(O8_jhp@mx%9DEPvHG{@>a> z7eoTJa2J>EmwaB++V%Dx-<$nvS$H~$r;7m9n~E)HtxXLrBm zDrp@$Hqn>rXs+#x@_vBaPSE$SzAf;S^~vh8nfaxiC)zd8c35y(gXmmaoT>iqGq-?uWw39eIW5W|O!>GCFQ0<4Or}(c^kHoV()WY*N-pinqGWwO+ z5;TTW7R%@wZs#xjFJ>d2SO1{l4r)`c++cY>2|Cs1l-S^J zE0;8X6S(ALe~Y=z*aS*4Bk)_ynR8pLm2{@1`h_eZIA6|5p4%404oYGPE_u`|zF)$W z*x>JPmo(bo=VBvT4z~VZgl%KRzG-x`hX35EJxXS8uMte=rE)y|PJ5TpZ$#L}=6^#; z^c%A#O2jKBqo!H*>SB`E(JoH?RD|oPonb*@w5h95t z=C5z>>TvK?B62(bmvHWKb#rYVhayCR1gCuusIJ~PK)0M(}C9%Z& zf46tlXtkBR`t5pEPp<|;%ms7CDMBQ%M7^A^yON)XBVzn3SreYmm0~t+x}`ST5J@ai zJMZhR-ya^?X!j`YQ=DRgC3Lpsmo#f}FOlb@)zg=7hQ4EBYQgMIlpulj#0LLszk~F> z{F)86$2rM!oj{4$5F+Z8%|yo%JFf<+9FlJ|C;9CGd23O^HZl_FkzXr_mgDtCTn@C+ zK$SzDXDo+EqBd+oytN7b^uc(l*ElUSdn?bwHfWTlao0jgEFrXb6>W3Q zi@)n0?MY7BFCwU3f|AUL=TLQfTn;)%H6PyT z?nepR5JLBA!j4|4O=#{YuxLwAwAe;0&7;z#v$M%Yhsuw89yA(ab{{*AewE1{uUHaG z@W_{?-W($O)vuJ+jpmNcy-z4YB(VgKyRUsRmxvvA0txkpG&O(gR9d}JB0(ZImHfFe z?OmI4@JU?hP(DYwjjhb@PZ!Y$)M9UW%-`ji$6i^1xbXa;2$94RJg=Dk`9w6EGsP1; zS;TCxxs@VB5=-!GcWvtDL{!SX*7Km#3D@E5JryC6Sb}HNUX|2|V)rthY?H>h-flER z5h95tc-GD}fr)e9j!k$tbW828a;7LkB(VfXANHwbv@b^EE0%Emh!*z}j&N+^OtajM ze5L9-Km3Qj^9&?Npgpk=eFr%&{uM4JBwxu%`>jUx)}kacB11V$*5c?6ZE%`%lIP+T z|7*X4A`u%xh_^yS%fSTyb`9DS8ySD82_=~kP;#0(ex=!fwK&?Q5h!AV^W~i6x$V_K z(k@OEO2mc`;;oc}|FzrvV(ump8QB+qpMCFmjA4ihx1NjYwQ*(g$1k}nhTTqjV% zHjt3CcoiKJIWK8*$yaiM+6|AQC}A711hydCvgfGIzQ&pj=_T@9ys`Z&xJ1Df|guUG+P{KB13A^NPzQgl}@=Eoq(Vx}VY;e9jqCVE5zU$x+9!vNy?&D>yIFkmbUB$halR6jf> zK9&4z+Rxojg#O8DkD?-pCHfVqA0Bsqyc9@y{_WD%EsplTy>Ip#>sUs zpMzE`7Ohw^5TeDkVEkS$JR2m}3C5kvUCYXz#eQo=g84GBd0)Noj8l5#6wke_t*i@2 z?Kw&$vBdB#^}_RD_1kMa?Q`_B_H?voPLaeCRhQHY&$TnMl;QPR60spf)GM2bzJp9iEGo3*gi&Ag9sK_Ywx@f= zp44yCP_x1LvJH8z6DVO?>}B+-I?V*B;kezg?bXQIK=Nfmp4&Da(flF%J|aO6(YAOM zZF44g)xd<%Vk5emkY0k4%!ufUh1MVJm3jx+cPeqj2InhY@pId&m+X?OdGNmo@m9*g z|Jw5)*QnSKnr+B)oj{4y71J5L;(p64YuS0(>vPFBnv<+j`3@NqD2dXx4WU_2{_Jwt zy&7$#E3f3aX!E~rRaYX3+OP@nmLkhP%G3Ttw9T2|y#*$O=C`)as(LP?OCH)U;lJf{ zZ=$%jl@ldMaQTF$9hNCGc=yAS-4C%5OY^8?@0WNxxzq@^FucPel30RAK6_6lW!!Pz z#j#`;M|M171r8_N9h={3*0!A@M1lnG;?(O{-(`5+)E@H=uZTZu&zu^8 zT5OwVRC}-QXrt9>v^&VNvm!(iOYp31?^)1npYZ>q z@fAzh6Vc*c!cmP)+;~1mLc4WNzn|U_lpuljYzy*6u@>jWyRwqzd?lyojW}4vIu<2qE4I5gkjI;9YXGCpK{RJUU1He?+w8yzj%a0q4un zHlG!U4cXI|=V7nx{VUZTB8er$wv>bawcA`y6wn@*L!RpdN@5AIP2Y9@+Zyk43x-+W zlxP+DjLK2vK7Ge)*T+*^`*XAo?p= ziKy`QXh-K+@0cGJyR8wZrP`?v)zynH60tZq*_+by1=E|Hq3@Z-R^3`F8$zHK+qlMk_sFwE{C0AUx02P|>fE-3B1D1&r={o9%I>E%j`Q?> z1oF0`^=vdR)WWwwy{#(B=M)pNb0cY9XL4G0jWQA%_>c1yiP#W= zZF8FSbV4Ld$T}KxQolZAJ#%C(#c>&JAR%jN+lF)QLHe|JMnbg2hU}NPt#h{)MQq3_ zm9=F3sS|vL(|mU=FWTU|VhLG`+FtSh`H!_E>f^M;?VOhQk@fVt5=kr(?lCkb{(ppM zi48u@%AAmsI3(sk^O5%8 zd}WN1wFnck%CK#;J^xFlglI7#s|@&TUD|vP8~5IE}3-XD=DcA(B`^TK4}Z zM2l%T5z0u2gtd_P@17{}AQQ6g=QP)$M9BL4A(B`^#ufY9XYQ1m5b0M)h?dxhwjh^= z|4_ndBxD?8y^LN-n~N6H(t9!zJlD!PN^W&95gubQ8Lwom##%VT$*M1-4UxnW(nJ4$ zLbRBc)vHZ-^E8Uou1Hu5iD=)Att+lk*|}pv<`N!vGmij7A~uAG&Nw_W_}*9$nFo;& zEv9*1$$Z@9Xh~X-)6zB^`()lrM8f$ZAuVgyRoAyKN8WQJM2l&Do_TM#=L~zN$nF_- znxEVEOSt50iT^k+k#HJ`|L#{Ai3VylDR)~qXT7(JBx=JZc#N_4Wa#scR;}YTBjXhk zqQx|i81}vo+h}}uny2aXNgkHS$_v*{{9Hzij9y`lN@vbg()9KzSt+BzX5LdTv1Np-MjV zmHCRW_hj_*A>K8Lp8QbEU>5sd#>hAEjJ9=hRmW-uRh#cqAE&a37&nT?ZF)XF(H!72x?s_2lp%1Hv2A7?ZE^~VhKB{ zwNKpjUV?9wyhT!1dJBqIQYWm1gp97Nr`te6w3y}|s+WAt_RgvW<;@XKcs-E$JGk+D z{&kWU<)@uBb1g_tQLpCp8MhWCOv_t@_UzjIw@-_zlRD;6@41X**#1mJ+g#d1>PiUI z;xs>x*6#jbH`Noxy1eJ;l{Oog>A`O6#D++iMuOW$?i%RrfrMx=Ev*^tS7O8NSM~^J z_a!?W?r-+|VQ!l7`MTbX%Bs2&3Fj*Wx1fCXz;2Ig_Gt zR#}T$oR&|CWF%IvD;cRPSv9g2r=?#B9W8kQ&m(0+BuI#j$STzwwzs9Sk(no~C4^m$ z*j^%W0&B@?LMLM1D5;ZJf_oyr1$OQ7|M?H|;GV<6h2CcBJr@aU$r%*adi2bT%Tc9z-?gnr_EzJr z)GojCaz4oE=ousvPd3V3wd9-mGZ3Q1gq&d7C0|y)aaHHx92p4FVh^P?ZG!(Fc=2u} z_E*jt(JLn8-HZ~aYrB;Vk;D>Gz9_Nbvx;i26;GIub1vO0?upB4?TECX_?sDFuMMQ{ zx<;AnI4@}rYy+mF=bX}aCtp0E#$EA*wd90Pyo#(p%qBA{t3K_lPkghr2f# zHef{m0b_i8Yt^ssUhS80eckJL!~fTRd&&az6GOSF*cSF%csFLdSeikpMmn_CEa{so zFx!}L9X=#kc4bv$>1X=u>3L!-07dRaaE}Xru;#bRDF~|NTCp@spB$vyCZ!@`LVpWS z-BOj`eN^6{5{kIt<<8b^8LUs(y%rJiRZ8(QydfX*bCF@2_Q3+j@@Tf=dD!eZk5CG+ zCl}>scmI@sJ9%!+%+COhXytj-XU^T%{Hh?RR>pTkM7OA4$Grd|x^(s9nK%5n<->0} zwL!I93q3{~Gxn#qkO-3&z)L>%<(;>i_0UQviDm&4J{4dTts;ipZO&7wmEcV_HehQ` zNPo?-gU%OJ5Pi=*vUFSbIA%(EL9|i(RWp8StQ-IPcy&f4)CRQ;FxJ|Rk9+x;wK}_p zovbTujPWWq&zV7+j~2-E&}@qw6?*{IlWqBkXIaekN1}qDHhvF#WSLer!0TKeED1WE zXv;@tX0b^wNsLM;g4Pcp;$2lfCs#M^u}?z|@W2ALiU+~HFazTrdgyZiw&UN#Lx9Sy ztvvd8I4e20jEW#y>Fy5^UBGM6z(VMiqABHN{_BMqUORG!53ivjlI#zhm}jwry|FyDxE_ zc*f$p?DWS31wplFyW!aFZsv#LYjWeu6lEk*1oU)bu=JP)0ngCJ*@eCMk;Dt^N#!Ms zdSY`f!eCYr9ZFoY1fOtawyw@PJ@9ks3&w@q2E7x^<)6AcuKH56^AJZs-@V2h?hRx>ybY{n_x1i zgd$Y0N~|r;CqrZLrq2vUXB?Paj)gZHsKbS1i#q$1Uu5M?@8=RjJ7p*cIww*zz@ne3LK4+l5Yayax{NZS}|N2nj_il)SP_(ueW7emGb@0tVMEH%xEdKLIadkjP z21G&;>xVkAgmOdlH@D=>ac^`28|*qlH2+dtK`8A*+70ItxWn3>?kNiDQx$~LK9$^9 zbgu{e5mZ7DO5ebj z1}|BYQ=P=?9V?W!qOG9VhH0^N`JYKHVtDQ+DuQ}QdKQ4^G4XaCK{yO~rS!Q{F7+06 z4YBECj+lhe*oV_T06CY0bpdA_8ZF^!7TWytYs@&Z4az zvM!Tu8sn-q<8&+mK`6GNR^FM+B_YZ30yl0!GUDxVfvj(^`D0$oh7nlb5O0%K$ zwqrlM^jO^<{~bK{pJ$&II~p&e269D05KwCeB47{PuZW0OsT~;P-)U^yG=zuWPQ=xq zdHoB?Sk`GdB3f&ZRZ6i3uzX_xi+f@i)^dYY1hJub3#*)~8uzbN5_29m89FboPZf6x)uKN@O)p~SSMtfng zEv86B=*~B+SMVOA`{p*BjwN{Z*#Zs9>u}8hzyD7b&?@PWI}aj$S$v5d&40;o?Hi^d zs1_Od0F5i`(DpB`C7$}2xH76K;{JOJ?5cvZc5bwB^;lV>^KFYb!m6qWqNRROI~ty4 zcWhgY0x8|N;`@e79PMW{o0|)^$Q=tL{-r?;{2TuIdV@`kUuz6+@*f1%q8`GC)L=d0 zVO6o@UNBeMgd&`7S>W1T4Zg{^q*9eW`ohZI;#wS65mbxR31D{d1FWWPg)#E?ejKRp zS+t7X7;5UL9R;UAL0BIX+ZH zP%T;~sGqkFA5|nu`~2>2M(1!EGbnRDtn1L3=Z}gp@918DQ;C95W@>$N7v7=xouEqt zoj6^cDT2l;xMK-u&3oSXkUC?Jn~EUul`^}6U+Wh9=7Nu=1#9-RKP_F|)QZ+7$$eeQ|3Q z=gq^7Mrq+GI1*`DREv%`*gVUdzu!PuIw~Z+~<~Nk-?vZ4dWaYMrhV>sLk23`3el>t|m~;~`fJwf5KOIzh`#DwSxdyR&8N)qQfsNjUOL>ZhNPy#Ka}LDUmD zQ_ua}CRWbpbe_i;Zr&4nJ=Xe-PN4{@MePA>%^H?A5pCQp@gS8-C_-JM_6F|PUY>~L zG0$BsR6-GQjf$?*Cf2^%fo;(920zip@m$ppQ5&*9Vs?AQ+Ix-mKh!&&-9Yxol(w}4 zDT4Mnzj(>A;%*8E8gAUT{8=hrZ2kb;e}Wd%ByBo+ zl`^)1iApGf+5=b?tC<_TisUOBT`^IwXm198O2Pt|f(*C8M(?X-#A8aho#Q zk7*ABB*JIFb$^PWaU1m(=c}))_en&5xap@zNV!UH!iMJo=B{5Od6A9tOmvj=zK~!k zdbm|=AjVWmNsxH%?N({y$27mKR6-F-+yy%8W^dgq7gs5*OSRN5s+CWCTDu>Se9y=P z6KzpCV$?5qMO2F|(yNP|8*ZTpsztLR03jm_*OZ832R7B95{i&{hIUOHV(qya=+>fK z4T-2&xI%S`kXe<%&bjSbBbpDwnPF24%=g*&;vbPo6hXD9x0spOQ6@e*hilAC*Hfl(;i?fRxvhjl41j>meVy0JpHCYEg6gUN_7_b=UBzsIJ7|} z3W7#`&UFikYW1w*{M!E@XoS=)1v3Y~XmCcxi5YDRiAnve;&`(y45)-6XsiV*3l|bE z)?3AB&;KBZ7F{I(O1~*AqCbX+BSx%ZgKE+B5#ZYn7rr|+gpc7dhRr=6gZ{5ISa-&v z4D<9wW zKM0Z+S6Ujnk8|Oz?}c#JwlRtgs-^T36rVAWfB&AqfXTGe`~Ql&y2@Dw+wvGl8>7C<^As!1l3AEED_QB;oAg6_@B#SeVSQ#%H~fBf@--R zm52`hwmcINF*R3dzGRUvcN~7&h_2*~60ZOVnQWmRs))sZH0F!SmEi8z#~CpZ5-}ro z(r?ogMESnntU%2Uu|M13ze86CD|g!H#@(ja3`Ig(L9q=b@Ac)I5+Ac-J8$W8XGj}8 zJR{HBEMX&ku-!a0%r7bS01m$C%{$-7VrS-mR}i!wVv0AL?EKc_%v2kCHT_j@?)@Z- zeV_7OS0uzMrG5aXf8{N1?6&Y&8-wQ3tMGd8c9tbNME-qwA9&1GJ%r&G$8)Q-E<5>W zpn{l7?RBH>xP+1DB}AxZ?=2!#+cEsrX!;Ixlz1PpJZ0a zFw9g!5wr~fg1rWFkLG9Di~~1xs@0`;U1nRYX||Y>mT*xAGa!33xK<2p{F&B|dzZb- zqM5Tn5sDURH-Nl@D)ZuZ99Ud^AVT@?}|h2kG!_Gxo=rsP?>pXJO$N zt6QjqA`bPe%ZA}8KxW7nL=>Hw%yKUsC5k1R6$I6CSX`S;^BAH}h>!@;WI0<~Z=7g9 z_Pb)8YMI~FWf^bq++aoxM7;WZl+~CpOk{b?(5OUdAJT3Bz76y6qjkEAGKasWQUqv>HQOnzOSNdvVkY(WAb#lepT?mn zE=r$MgzDA2VvE><>s+j>SccPHgH?Fu@}{c}VMQ#oZvdLEe8>DxdkM$ur8(77&~I_} z>Cy>TZC9LqexKNeS5G`|bRTw&Q7zkfoIf)0++d}%1r$WCRZaNm-8YT;i=Ht$`Y3{y zgy+ry^?2ae#m2NA)%f}aWmxl3D?R&v5*Bc%#Na{;4Tf#8*q-CxHj@TD640xsDONt& zhZ!A?l~WK@%f`#%-2ONK{0&6R=$eNoeS2g~nIFWp?-tXe4^W7!|#nBS0n_XcnfWk{McJdH8DTR#A_7B2r_zZ<+M6@?$lZ4z46@O zX@Vua7ydis-M=e8{yTKZyM+B}loPYNTDT%12 zQj4$nWUH?rsFrQKL`3X=^HcUFWnZN1x5J7K1u?(r~%81xjI5v&KV* z4Q&w-?A?~X`a9W(oAp{jC|b&Be>^XX_54~%tp8M=E8hVvmwb+}gcGN=wa22v{?K6i z-2c>kQqwwoP4T~sm3c~WT3d>+&8UhI;59t|nulKH4{yv;X9S2zb89LHMeBKGJdeb) ziA=Ny+mk1=y|?R#o`q{E2%uV|P5@V;8*nx^*0|N9JXbuSvjG|Tc*gRn1~;Cj8$TO+ zDhT=&DIP+B@F;fpk4j=j@A_Pk&~nMh2hiWwVOPG^5e?VYQxQ~))(IA4R^q&)O)H=0 zl}1+?8p)`0`_&bZTx)dAJm_(lg-R$wT|YLRkL2NwaY1iG%PZ>#MbIb;?;4Dm#_M%1 zndVUWo`RrSbOs0TzA}~PUjNb5cT*l^Zl?$uKLS+PJB2TKI6LUjLr(=kwdl8rCvnJxcIW25O#_7Fx#J4MjQ8Q_oDG5mPGrfC_bSOr0~=y=1t z=;krJ>&xJ@Ce33Rl~4rTivW~3F@|TnY@9Y?WQ>BKT89eC{RhnV8#M>NkJRIX`Iw^L z4|ykFP!Lp$u5bXEH;3@a+vjO+OU^JVp@@XBp3(;FG)JS2Z!^Prn{QRkHQwT!NWLPf zrLLSm$Ng>3p4W~YACMU(b4PxD>4#G+bgq@B81rg3kCmBLfSdlMtIO=5+rb%$bcLLl zT87CS@~tRgdET}Zb1vr<`}aPXVQ~m4xJBlvPpp`mKoL|+wefjmvi)pg$g#pHrCQ4M z6?}tjeU)Ce;9ecG`CTNRwP&$L5mZZwC1B6!PI~Zfk^G(hTBGel`#|=MJlV+U!H0`& zanh^&+wOQ#1l6ML2C%fs(Rhit{G(D8DxnBEVgLdxpX*CRkw-}lC_>R9yKsQEM+*jh z#U5NRtyC(F8E8~PTLB=*uc|iwQzY+qprx5gC_-(kQ*8&N)kPcEP7E;7(MMwjS`wa^ zRF4n*frx$q`wmeFMNn@62H%?%_zV&423!fE5{i(Kj69FBM^WIBxZZwZV(C;dg|-zP zOUf97opp2DPa1x<|E(HDP%R}Z0%Z%Ax99Ym?kZc2N+?3+8RRK|%+&yts}P!&7wggU zmsM#rzhj@f{+F|&wgKLiYiM#uM4n~~OjJS<>K9e@qOhN_G%+43UdhajJZX@bDJACw zp+~3Nzo<5!9wyRyP%Ua3z&Y(#dt3c^@3PWX6yaV)&Y~qfVJzm(U|X*1=99^hyjPK0 z%4|TjXp7+7UVXC>zSb%N&lcuDsHQoQSkDAdv+BiAIDt7s}a3%60h}GFu z?0H|0;+Js;*>`e`(W$;wtoR#kkl4Vsv;xLd-!+IHVo_{E|1mK}eSfPc_*wNzK@fYm z$C(vlT*p&@lOGU~7w4;#-!({GVo?ypHo&7rn~lepLWEanuTbL^nicsSA)f?lCD$Z6>Yq^S`-#lH3 zFw)OXWOL?*@Rqp?D;ePqPB=1JV-JS4POBDyxz}F#boe+H`{QJC0=wM}5ieDQqNQY` z1`plBPR_UTc|{8eS}x5LDR~Wuyb;5;bhq+l3568|)moRY8f#o)h<@$CY7L-Xn>aSg z)5@La7Zw*L;OM(HK!g4jEi?nAcnEzPC$eU1tlU+17F0_?E7`%UlG|A9ju776yO5w6 zT8f}6DnOqFTbL=Z5kKYUsvxMAIy1Pi%KTcDE$rRVI>I&@M|d4P1!%lohiAC^9gA6& z6FT0=EXji9TYy~0bbv*lD)8`w2budoUll>Mx|YZ9+=6EaSQ4}!GMv?|>&^G31PGuK zg1EJ@D0_%+0j|xpHH-Oi?oNQ z0P`y1{o{XI1R$xfFAvK5h85^nP(e^FzbC$I=$NfBORhe}daUbTmoKosWqtP)6pDnF zOT7i(paJ~XyW`oBw!(l5=#_29et_%RC_G&PxV8_TUsXMXhr37ewx`_L{L9e_g4W~3 zREfSC`z|&Uy=rJ{&s)t&X6r^hHmHOmTte%yvVIFFb5F6SA%Mp`-KyG>hWTEGg*l{E($`? zqU{E*C6BU@k6ye-nzu5pDB{=7)!ECe9a>-CzG$OKxRn13vx-v_^ zl01QY@~d28THQA)g3fRR4e-86W8VL#lknfN-LNHAW|?)cUq3F@!}3;VfH(VXr6%cc z&x>UaM0*>SV1Jaj7{bf{Sx6jcm}pQ5MI2$?>{ra`@96m}B1(VR#`4u0Atqlgp&+Q1 zZMHib_5?HZ+t(vv*QZ2g+#Vrj*oqodLJ?apRApUojhdG^1`(^>quKB$!^N>u%@l;v zK1$7fVlT4_9m7R^r%4Kewk{-BWWfs}FrOTUHVW-9^N`UX%-5e7iiDOs81F=7;#$%n z9ua*zF+QxcKR(jEDtDpiF;UuSNbjQ1JB z=T@$pna`|vbrAm@mhOY*dCZvSpX02a>uZ~0|JH5jdFbHFu8hV9T?T7sDhv+;TrjVpCvXfM2uMI$*Ct4 zJ<&y$w9B(*!(v#El+DE~JL9e5O}vVrT5Ye$SRyP|8!HiCocr-DAy151rB7JsSaMIo z2kpgHK`1pn2-B9RG*z#vs07-z8(*i5UulYN=y4_na?yu3{03cfVj%LJ{is zF{LDM-uiR#?26%Pj!S_~a%^x`mx*t&1b2@`VgSq|q?h}dTIm4eT zb2~+-^X{(bzWi~`HKrfsUMusif}oKB92-4^|GD``(8HK>DuQUyxe{RX@uB?I{DS5t zBTgDrqC^}dp2OLv^GH7X)7`+I+x9C68f($-1|xv=WBIg`yV64PMj48PluJh_<}$jB zX#f@;yxgIR<3len?nlD5X&+@KPQpb(D-=g2A{r+uA zu$GeaN~aQv*!#O&4FHx*4MiJ%uOoTg)}E#bXLOAssFu1$4d=%y%e-inJ4@m>ov+3! z&n#-6`{+FQ*~OdPoMMR`5q;7VV8;fZgEF)2J!x-!>dDogRavg_Zm~;7L}}8V%ADN+WPhCXf;U%i zb@u-~-Ja`PylQ+BMNlnub%ttj_Opqo1DjLmdPmn?r6jPp71C1hR`J2XP0Un65sHVf zJ;cwv0`t^6>T-?tGhI1pNqAN5STVgPw$=Q-)h$#)5y4C4TD!#y#uPE*S39bIpd2NI z-pxEj5mbxT4__#R6fw8P8}X)e2QzJVnl+&P1hDzf)!I)S@vx)2MkN%Xj;o~HHPRZR zS3yf{X>{z;oi{BBSA!lNLD`7NJ(8>AitN?t4jCYA_Kmc1c!$2K+X#~)Aqcq(m!~y3 z`}1GjjRSJDpK&_2pN<9@Wy;ef8Gou@?Kt-YKZ*Dp>aQTE7HxHW`7?8HJ&C9gIlLZ~ zPz3$b@Z9;AS@yAe{6X1jv>tNbFSGJ8ccSDtplo)1J7VPK77BuDsjXY1en8yqJ$S$Bn0v2r}C^O?jXaTkH+|_N`vmH`-)ga_qATUjs<79 zu9%g*m8}6mD7N9_(0itD^FlxkN_-o_tpf9jB+Fr|RD{7Xvkv=` zb@0MGY$9fKhONN5n)yz6Wg zp=c2g0ls!}Ga2tf_-9>3&{j}u-gstzbF#mcuk7z7Xt~rYn!m(b_p!^&LAx9BXYJMe zE=8!bs9enhupVXSc?l|^2)fP#EROBQD!fTxX@`dj$)E%7m_5H#+JKMv8tj*F-L|=c z0gf@2Xw04`W>qwBlo%D*&b{YY9_N87f@;~2L1#)3=H0O*i1aOPoGn;|_ioMwPzgbV z)m&%U)nl;!S9NzpSREG|uY(%$F*QmFD4GXjHOz(EKIoD`N5&}lYC+Fo&}k5hTshe1 zelveHET1^vdbqrTpjvhYox~RPkA0U2|9&g=f&TtHG_#(9pjx(;l0nCPe{`Y8i0E6e zzV4dh%Rjsh5RyR$fCV(Fgc9PRikOdu^}0Bd>UP>gm1Lat2||r*tX;>cHmN5p-2cqsUK7t)qpSd?r!-d zS6yLe(1}JSoy_~XZJT_-h)g>AJ=H_V>r{nroL7}?YsC}QSq~?-A=SO!v7T>TTVjgnt^lp~Sa;<136bV5nZ3r#CXlz{fQ*7(<&VqUZ z>)zpOd%Qz`GOq!9@I_1_-l6{;|Au95TUg1FciD}EPAY-cJDagw8AU`-k2B zBUtx$21|K6Kt)h3Y7bhPOa|Qd=Py6{2&IM;p?KAFx`nMeK1f*Z8HO^;WF}kEJ7E5M zRyhN{?Y3C6F;D$K&R0EN&1A)DT1EJ_l0upL2tp|ds@BV3H3W#jj-e`o&Y}bju(uWP zY1<2lmaVD_Fk?>@#8Z)I>^0=v3C0Y4X0?LGR%FnL#(aB+kNMFn=cH$>Zu3f_@pX3v zp=gcz%W`2F-qUX>`+R72I4jj_q&PEmu>nLv5z{jtS-QFp(W{S=<7)ND_Uvqt2vOGU zgaL03TY~#yS&K@l?W5GgvHLN$`fVlgIk=`!5LBz_QHw1dPasm=Wb2N+$RgTh8@KOb zTTux`&~}6PTlXxUHz$e4wW}M7zqHp#{qT*BUs2X@^RJ?H$3aTXm42r6gK6QH*}h7i z;!Wc!g0_`XC)!U?IoDsz_peG~LuXu_sf3nG>j$;A)#UMG%_3L)01NE{aLTg4nJ#+z zy1Z)rz~Mp*{$OG*5m0igLA4b0*4Gy3&{4;Ca@e|)-9mZ9^GxHL!z*Ph0nt*>(Bk<} zzOdse<6DE7hGfvW>s81L-&X73jkh|oxdtPS={XEK3q9~pk$4BsjUX=HC2>Vh?l7hX-?Q zRhr>bxxRv+UMb$fNuBf9v7TaSh(EJ4=s;Y6EjwPfJ;!_KyYNPQOuA|hj=F?$*Si&j z^-C!QLA{a;It#Uyp7=5w>k+=P8=uP^MawDQOjJS;_Gnd?mnW;wHfS@WYB>r zamX>CctyPh@MvCwJC6$#F?BUIK{DvTAU|X%P!O~vj72xyVP4%E3Dd_%rilACK3_4-4_<|M@rP_w^Tyu6C8CPE$bS&AfJ1_{q zeEYM{x=k|Zh)TL`>nB8fbPnTD?%Bq<*mxB|waCZ^D3hD>;sdLT6SaTE7nA>f6SUlP zd@T*vymWZ_9&Na}dGdOHagq480lr@T7eTd@83P(ud%zB~Ya+h;KVVcs5s>bT`_C5| zEW3j?8XoJ$ujWfOZazC@D7F2HkxU1?-+n1m50;!eamc+hMk0o_>&C0~T4!8tbwfc= zEm|kMWpO^3M}DX(f;(6(R6-G|SJSVBa@$}JH=;A@8H$8_=XB%)Y&vD;)0=yXg}*y9ilAC_ykRD_J?EBERmHX{ zKP(iXXes?s>Gpfptn@Cez!8jO=sH283}xP}8C8HEb(n1)Tn}S7DxnBEgTsi!PCVkz zg@@V??xN1^6hR{#XmYhAZTy5U?$3|1b!9hZi z5QGv3L#z9oC$6-n)g9-pB1lZFj5m1mhVv%9>ZI-Kj|e&vDT3}3VE%$uJn?u$>bte2 z6a?K(^t`qMQ!ojK)AV9C9Mx7E?BGqJh#z}bLBxeV6-=_`H5W87Q3*v* zdzd45`Io6Fa_@}ktZB3!v^R4&cRak1T?cJ=?AVqd`(r?j{aYx4YN@f$peq*pNZeMt zeSIpC(V5Is+v7H6>~=#29of3?wTA~Ng2rvsHm+*Opd%5jzOMFDB&1y0H}Q^Gx^-vh!xsFg!OHT`}53wdjaZzF;^!`Lf-s2?LH- zqX?>{OQ zS@=4vg>AM*B^067eAgQ%`|BF-l0xxH=6Yo2U*@uuEEPnr%bO@$w_KSsTWCF~7PXDc z6srf=Z}yAx0b8krBJ8|Aw&wB3;Dg`CyNMkwl_y1VhgNPDilADwMUazYP$J8kXcgYK zow?-Pv2*X(-q|^KB=-(-@cd`zWuCEx6<%T$5qSzJ2pTieSPP)puL;ZpPXPi`RfM8d zJ2$g)?>Jw>dc;moU`bW2V(VQ*Pzi~5Y^U)Rlw{KBmV$`O8HvpEPKbE4rVv*o6hU?X zc&ErCkv%zU6^*AkD+n52(K#PSyB5n%d;KJ)iN_tAat`awQ&f~T#mQAse~eEMhE_O+H9P}JM@0@ z{)14oR#;$Z7d^OHDYP-PY>ctAa40|i2=AT)kr0HM#ku1ikL*EK{*b4`k4>GwCF}(G@L%#!-Tt zJ1y#3xhLMnr3jjJR$3a|dc_z;ABFHa!~TPytxNj}MrSWHVjZ`zOE%2ue_CM*uF**6 z&HN0=JdhTQeEN8I0<#Iopo6CXOC9iUD1UW}v8cs0cCI}}$P_`f7R)xSX%(bja+iov zJ#&fW$Exx8-wF$$5`qYZZd$cdgY~$4brDf|_F3c8ko)++0uGt3HHY9_N zWYWQR07edj4s1rQ9NAA#KN#^d%sl_MzYU6@S~fd_&W8QrM8&CLFB`8OS!>ugl8)F{ih}~myA(Dkr0H^hVX1>WBpCOt?XKr(L!m_P&Z@(*0rTQ zafCN5j&tQ+E&OgBv@vMSU7h=0U@m@xR0P!`?S`-7*OfMo{q~T(yV6I{v80qs#x(A> zE1uV{Pgu`V=Zz6SJ?Wfiwyh|lXT;){O6|e<>iv!8u{T+(GPv8O5{ftxYli9tbobT1 zSdZ2nRKr0#d2SMG>0RT4$Q#z*|6Ch92KDlXUev!dHxT}^xq4K z^j+<7<@{Gd5$VXFBl+~x<%of6CqpgP=e>l_{4a(gsW8SId~L9v@(Q&`NtnMH6=ZQ< zGfGqqPd0#PQS_dEU(DT*d*|n(+Gr!%xsg`>ml5Ksf2x8|+DEDR-98gjE4J<_Y&$_v z8$h*&FMS8+$d&r+iz77RLjnX^Ed!sm?I)|uZ8O_xkSZM z4-7bY1ZU*C0k$NJ)u@dQhw$Ado*n%_OmvOYEg6!yG;Qv^2em>x`F(a%~;CW9B_$dKr_TV+p+4SRhvgJ=3k00dJAr=AnlkepALi z`EKXst6n`d9-OPMBB+)!cJFqt!n1q>#iXZm4&;6`DV;MG<1Dc&{E#;#^wyyL!x z;z%w~5L8S3qS9hY@K3>i8ntft3dQ$rbMaRf{?LLCW2E@P#L>_IC}8Wmr{+i^R-k2)gm6^ox5EDyzC+mF*hbX0VuO*Om>)MRoFH2 zi4};T5{jVnF?8-&-tu#NT+r(Ch@cXRps@sOD}B#0|4WIqBV(qi2%@FTu5hkk9v1QL zm8ta2sp`B-5K7zy%ddH`h}FJ9pY$mzf<|X_o`<{(~S|Ib1a`AGtvA`_PVDVC{ul>eKYWiVa1Jj(k|T_zWAgW`VZ&<`8^M z{_pBV5jjjJ7`=`4L>uAARpWJ{k~v@&#=8WeXeq1OGh{lE8Ltghj#idhGB+*DqBbP+ zjAWoez6rF^BW6N?%=I0b@OO%2w~;J27orLobgq@`Hj?EAbDD@)66tJb&At(uR*gz* z$Pk0^nn(Jx(uTSY{;?%HL3&kU>1aE{_&;S)E!C?cjUU@HcWqYB*-9l8A=z|fJ{h@S z(5t(cL6!A*g&9?fpjxy=0M4hr)*2xLP0EN)7Am2L91gvIVur!Uxg%{n9huxfa_->n z&9_v`iUzeu^8v`?)ntQtT2>^Vm)g)w+lRKB5=+3&zDDXJw6USt{8TET2+7|k&sdP} z4r@MS@&HpkS#zfWCfaLst)*x@85*<6<=}2|JM^em1^pk^Cg->tm6L#Gw0r+HT0Wn5TgK+@QDX_WDZJ zfS^^x*JX|DuOJHl^2b4npjygKA6gA+Waq3|uy%0({U+${o}%&B5m)84GXmv_oN$0j zC_>q{!=^+Rd%k^e?tWVo1ljkiUM*_5(~fZ2>%EQc=;bb6=GbK>L`5`tyv&Yx5kFQz zP%X*vB+vAa^9e_Z^^Al4tKGTk{&p&%2(=!b`^HR3G?lvHZvvuh(SIam^bU;!uKGe%cE!}`EcyKIC*i-APB`ajGykpqw%(3pA;3LXpzVXcl2{z zxTs(iBcG@U8pGT9aF7?rmIq(w!==lGxoH>P(%*mx$&~Ytgp^C?F`Q(V6z1+OR&i`y zoPwZQbnOCo@v)HTI5mWCZIxsw`Q84l(}G(uJt-f46EBeur$;`0S3j9a?Z3Q`h*}cD zTQ}RPBB+*<#p(9NS!j!`d~W;}18BJ<@1tZXU}jQbvAvg-Z$6By@&rM(8r)y4?Jhn< z-;_^!)!WxaOc)r#ou}iyCCP_#d4RTSf|rs{2F0rlQH8|W-$M9{R#*>;pjxy}I5iX& zQ}bH6+ex%Rb72HcS3B&%h{B@m&k){ujEbOI>KC=AW?eBdd^4M4#v6@RytkJUtV0Ce z=Krqgz4;7wz7>WxsZG5Q-!fPo*0K=y15ap_Bw&wff>G z{zh*1#$ya1S`;n$a55z?&c>o>qffCa;*Tbcc*`pTb-0hefDzqMgTp?CWVgY!Jr-Xr z7&+`V(Xq&5gNTZUtB4!RgL%hdXA}h0va{PD%S~7XnIjt;RYhz)>&HhOUX1&}e{E2$ z^n-t+y+r@u<`NNKrK0Fsx-8GE`NM!x@(p6Jf95lkbaB_g318Z*K~G3Y_b9`DvKh4wRx!^%)?O$L8xA3{asqPi=w>SBxGo^zp;Wi zd`+czASaR6=Yh-h$(NVdM+@g`J)<08iqsBmWpO z>0H3FkU*Pjma?sC-itO0zpubLA04S8h*r)Ey$iAUVh<5s0ndyR z*SE80neBusA>|Se@r88dC&q$~N$hLY4l06ZNzNU&4^3k6l^xnRQT>TAvP%-nQ>BAY zBm|+fAvC-K;;%FD>}{!5SP$X}a_-oDv`WRQ6?7$?Po@2}K-6^jK%z=2RK$(Qbr~IO0*A_wKh@EsJU?UWIS2DUKWU zxitYt0F_V#nPc!(%7$tpyTB=Sznzx=>It3gC>jS!;+Zg&P=sP5tBh`} z@@OJ@SIe!=iHRwC`edBL8k9EF8E*EXi$-=-ZP7Ac85LnYq%U394}VJr_f7;2(5SSF zaICY&*y)Y^LA2;BN@s1ne+Ao(axe3Xizo38efCm4-5)u960zM&Ptv3Dqyaes@DyN) zeqjK5n2Bo_oE?&AT)tLFlsy)LnQbB=h(zS|k?##sn2cWgFgN4Ev*DsJ$N7pN6fNZS z8HM~l$YXy zDs6Ri!LP5f#u8w%N2w#R#2`!hjI<{4V zdxkE)8M6uns|c#qC0I1iQLv zPoLllK+&-D=wN!<6AN^GT@JD_)A&kb>tf{V6~?X2L69q zo>~T6n`UWo>!K0!5l`YMf@&!v(N%lF&c|8Avf*FUF-j2XXy2aaBfGwhi`LG5FceP!2Wqjr0@5JjgyQs3db zJBpxM)I<0()KRRi(m>n!E1uWV`IWBc$_zJi>~mwQ&lz*SX*jN^gd&t#bdB2^qhtT{ zpy;xF)wPx)X!HRam*Kqos7Tt(aoAS0EUHCkKG?AFm~pb;D^tmy!_+yEB50%rA2#kc zE@oT_tlSMFWLg&0qF(_Fb%-+D8}Ck=wSKJneNY4)q0r%%<;MP)iFzoNNjD6@8EsJWk z!VIYUT0dkG!O@<(<{ACcso_C8G(5+l2&zR#B^*nBrS~g%MBCzv2r40ne;9O-n*(hO zKBjBKW>hlOe~qV01fggtD^7Xj^^qC+9{gCmockod53(y5>O9!8vgG$cUJ$gwOe0KX zG1u2*%MFv<(JZjbC?!`yf~pT^)%W(bj6`{!kbR(ye;v+NAl>4Me)qw-`Xk&J0DJh7c$?Vji6Fd zX&KnM$Ir}2qlg^Vod0Pl>)=k(y8q-akX^x`t? zfSsQx-3ytBq*rYt?7x0`=gn?Bo%y#OIV?swT58NNdO5fA;!K(3kxD(GJ8yNwd|TEl z=p%Y{^_W>fC|Y!<5B>5VLoQq!A5p*vpw?xqCC`WKQJ6B?|8D4SM;t4cu#Y0tD2&t( zE+HR|w9#$W;Jr%CNx90Xgur99%$6^a{ABK2W+nDfA|z_#-K7@VN4!IyT=Iw7=LDgS z#G*Gwq}9Q;n&jLwjb=Y&#zWqSm-!hb^8&Nqf`_~mOFl$ou; z;$&@Q0A_xvJq3}J;l&?33K4n(cTGW1EgGZ1fKgsNtQKB?T^VY_r~8rR}fT-c!(L{eO}@YA_C`~O;r$7OR4$P7hYoW*$`f!Zr(J-I`K;V zKAuKl&5K&?Ypo*re<0*4flO>-s4x}V!hQ?yX4o#`8BrUjq+*8t?xXUIN+<$< z9oSfh8Ttvk*CHamN-1%MH{?TpE@JqbzBn@SXtv^cb+8^s zwDKbAGw1GWepL`u3x5|IbNwyq<69#{bm{6RGH>{C%ZJ}A)CSdZwR7&w*q`1)B1~F< zDEZizciwKc;4gGzSu6nG_!tzeBKCc3CQA2oydS=t(f#Oi?wu2GN^1@Zp ziH87{TU$l+@o-jha2XXrv~n19&U@l3RP@SmVJp#aXfku~`f4Z=f{+Y4DJA~C@ z9*7t_IGI^Jz8Z>zAe1(QpkJCj2{Qk7nEU2J7}E zu9L`Ee3za6n4lo27Hu~iiQUcOP<%~pe3_z*D~ho5WGuxUcfd2Wadu%ZaU}5qds2Cc zK|QfE=*+@jqb+ew4?f{)*t$C73U>t&wzA>k{MQuLeqfw}pjwJO= zN+?40%E6XvK|P_f1pS)Pt0x0Q#Z!XisW?nQP%XtCM7;D7UXT3w*#r}# z5{gj0DzUb>m<)}@n?5rPI)A|Iaz=PF%rsv}*44SB{35GpdOw#K+9^Xp&>4=R@ps}p zYlxZm3JKHG?*^pmhBk$1fT8L;Ee>mFMe|@O%dpATuC|cW#8P=zm!}QHSMEH%xM*QcI;_85o zn05YFLJ{kSIvEM&hUjl@$+_m<=mcZ1>j=^O3+AQ>LTMk;Za9~~9i#2(o}!>WRY552 zQ_0PU?uD7{rbp05#N9?Bq6Ub7e1951CA8f0ZbtewTua=KBI2iCsF>F?+o<>e5mZ7D zO5ebj1}}{!r#gw(J60%dMeC&4hH0^N#h*zoVtDQ+DuQ}QdKQ4^F^P5^K{yP-TsW0b z1oakn4Y66q95D%_v5%mA0CFw~L*{zFEM4u7%=I6*oInpXBsXEQO4QjLxp6}89%w47rw1FpyYABFSBtL_1u5n__Wy3co{WNC=!CmVbDR&f&20_<5g-01M=@Qwrv_BB!dpv zn%BROjAfmcBciniSs1rbG%Vj3V8lH!3~RZ;DuQS!-oh&9s_g!?N@C9Ah9W&X9?Ojn z!1vpDPd{D9XMFezn|P<4+Jl3SOR<6zD~dWRttx_ONd}#`noB+LWj5C1!>4bil^q<# zoVneEA|VK+evpwkgC$Jx5zfo%h#ZE1#&M5&s9q`FLXpxM>o_t{eC|?0NCq7|@2_Xe zry`V+;BM<|HaW17*s8P#Qy;viPbCy_9~pFZRl$*&8*N-YR+e?XZ4pNpvRP3C(Ne#t9SzSKcWhgY z0x6h#rM_>-#4^unHaEPvItux45|J0D2L26yeZ65!jbCdFZ}J}m)uJB4h}2+9#KWp$ z$vr${p%RL4x`l0q%=O=7TvDk@AIrkZ-r`yuo{~`n)gpDm`x(U#7&UDxjFG=%Mwt3e zz7Mq?6{02?H`gCC=Da`z^@JkGI7ZG)OJ3IPNmVhS4O0jd@l_7S6sL}{Pj{cX@WoW=~woDb_dbQbxeV$3_b7Z6mUAn1Gy`sOa8L-9L7 zmj*iFTjYONXNsWl3hqAwT8o}HKBUgrCKjg!?x!|K|`I55Ayi3cq z$r1X$m=SMJ2R9b4*L4WW{#Z#xP%ScRBa>$tv-rAkNm_CovIr81QZ60SFsplzxEsB} zBxcrDM!SL_u`h0v;=Dz;(I_oE1xF$+i)zvF2AgMji}xGKq+Pr$Pk6~!L=iOVhe=OM zh#vj-1WuoYa|uOIEjlXU@VrvuaNV_9;otB^3Y8E<4ucNfMJXrWE)6W}C@RmzU#8!R zUoAl>T6UJVf7Ymrw|Cg@2(PIT(7=X#IFc79I-{gP=Rv%As!Lv+ocrzHpPx#UdFtu$ zp<8k|P)2(p+lfKfB^A*%R?`BJRi#6tD`^x#wbb?F&GWpLVaTKt*4p1pB@`hUbY#{U z8AGt1_Lb>M3n&%Uj<6){tmP<{8OAgUl6Z zV^C}p({!wP!*LbT6bV5{<{8OAgM2fHNLt@quRS%AZ@=Jfp$Jur>=U71V0(K`zw%v6 z1KOf8;*i-|dn}^#;4x%{k-1l&0oV6a1dT5Sd6hXBV+psljm}w%~xLe{u5S37b8Z+z- z+;4t)B9g~Ech#wcB4o@UZ{6FY4=9Mgjcb3QfWMV1d1Pdc1lb%6+BY3lkMJQ1ed@It>es0ij_KZY|pjzr^ zpW$%w&^K(WrvsdWsP8lzk;A`I&jXoOa3m%iakF%o7|Cx{?4(l!)lxGot$gB5?eL6c z&&ULIw3EDsl1)I)vuMla7t?s^qY(T}2%3TTcZAD~g**$($z=?Qb}^@7PT!+hs79^R z+!FN`IkqBaYwwU3C!^(4GnG(;+JimsUAFTSZFo0&8}&+NJml*EnKh!>9pv&(@vy%h z=yW4v3q?>ZY8&9dR9|}!HvQJqn@T7`^6$t~2jt_y{`le^#un5X!`}u^S4JPzqP>YM zY44nQ?r~P(6o@yrkPpYsi*w?IoexLeoA-He`9J%py%(JMo4$BY|GSD%VnZdq%Dcyz z|3J?Ev3Zje8$h+3kPqkSHw|jZShQEFGtWQAD%QrK4JuI(H0pD%TZmV~U!y(0_CE+3 zAxQ=u$)s~e#)%ni3-L+)tm1exyh%xP;tJt7gbbSPv_|Qd!Z4BXu3dArwgH8`*(pii5o+Y>I|8iD#1|4M5LEapkYo`C^ zD!R1{;hP)dn+D0P^N)lel#C9Xn&~QYW1#r{J%I&(UdS3t2A!IXFn7EnEgTtiGDl+`=HUU;JY>+xJdL;R zv&-Ras~@9!h$|sySrfdgPZ3lLfA<&nQpl%on~mp`^ZzU?Ubn5ryT#<7C<^As!1l7V{>qd0+e)u*45&q}0j6TgQJZ1AI1wpmk?F>2{{E_Vj5mR%O7E2cS za>wDP8U9K(mgN-yA(M6Lp^8|ypuZ?r{vMk-@|4BShhv-Th5RuJB8Lyh<_q)i-(d;< zp2cs!x$%b0ZA_7nR#0q%)4jf8Nz!9>Gv<~hO!DF2z=1z(dYI(Hag}`f_+1b*z8Lx0 zTh!d0#ms5n6a>{$yoJ*lzl!mDc3VE|v>9(CyA6cZ!`E%Po!tgmZjkLpwFfINju+W= z>arL20~G}ID(BVNTu*#!hBY5~W|X)wB$?gU4UI}DLbBTo+Wddmy6(6tj;=k}J4Eai z0Tl%s0>Zs_cTup%-aGaZ3-%I~Ye$VGR*V`^P_Zkb0{89?c8%Q_d%+T8ud!?LJ+qhB zobmVh$NS!J&a>xC*_k%-O-y@DSb=2cDa#66`EW)0CrzB@aPW%oksIzhF zfQSto#CO-x)kDdZBm~ux>@oN2jrsU~d9=gzSF2P)5%@+n@#^mh-TBikzpL3x%~h!< z^qr?~Gh@^D_vcm4q^PGH!zBdOlI*cfer5U8L6x+9js8@rgd$|G8nh|TM=oi|=e(J( z(D8$T4`(oVaafeiDvu>E_jTphD!K9PPMd_FBOFDemrQQWzu)JMI|p3P1RqXK@Zzw^ z@y=}E!x6kV_Q!9X@zVp1=eY*x?DJZ*$B5-^c&JYy9+aT#R6-GH;KLb=J^jpxk3bZj zw#~@4Fq(UAvq=c5m3@8g4dw@OPqk5rR6nHNaEq>P4t}s^7hY=rCksW;`e_0_oYmmPVI%UwhTFj&e1P)a zh(7YcCP~P1rJ81q4-Vix&VYetv>_p=)&%h31b`O@ObM`Yzgcd6qFEy=ca_XUE zn;lx#nqPY7!S4sOmTH%3(U!%&=#2q9?b+`}+C+D$%_&0mD%NwJG53nbe<@#z(^g|k zkwJOU31}T+%W+Dr)1X(@_;kL9P|83Vbqt3jC2JL+mL7#*ya!73+Hfp{xxvL)+3_7JgUiQHq zdYxqlYtC6P=?vZoE_eI}lMd^;0bV^wjpRR8Q;oKV%18*R$yvd%h)U2J3l9&FGvx{FgHx%TYLi@&puxfU2>j52&iCxuHAf}pj) z*oUM&#@l-y{F+^r5yUI0d@LjKzFuf@bzZqd7hpC zf9fBHROi+zVO)|BucY#^XV$B>n}fr6#U3^JD#5wKS_Z{^FWZo8vwu8WsM$N#P-U^evJ+Wci|&8~aaJ;8T0l;gW+OZ-yo9o{xl}TGE@wE;+|@d+c1tF^`_oJ18OO8_cFu9nZ@fzglm; zA7s$pP7!qF%-HFK5&UrOMvi0F1PMX4Xn(`Wv$Z35rzhc#hD{O-DxnA(i{R_PVCgyb zq=94TuyqoGYPnc?*le(T;QdHHJdlql{3Wf*wzCp~YS9^vu}rY^{J1sNS$x3>gGwmE z#nOX}nk^nSK2M9{Ek0Ma`M<=NNZulVS~^T`}pEn)P`W`5o|qR zu7HhyN53}r^lK!H-J1!P9>LZF<^!FM&LWE;7+u6pD+o)6w^zc!a`Q@mW~0`rJ;9(O z_TIsK1H`>7PV&54ZYEL*MaW*I^o}rDv-3RN;71WuOP{IvJx3dzJP=s8L znbEHAjDBi&ILQu%A=Fz1X4|h*w2bI`yQb5IbI8+^=i4ZPYDudP_5r*;qCEy3DikVs zeGqL2g3~~!UeR3&##$ZBpZ*Eum^-Mt_`Ye8;jcmz4v}E82G=o6h+8h z9dFgwS_?KVAL;9$?M&x$`Xrn@tGeFg_vsyy5=JEyLA}L|k=xVL1iw$~z8BM}gd)T$ zLu4Av6%O;)0?a&4sj748(E6eK8YbTlD_9BqKj>Fm+^#r}Zi~^ne^*_qQK}{HetcJQ zrP&_af6Wy}V|{9a+D7dLtaScy3}5aoP*kS~swLQT#J)J#b>LOo-DON(oajQ!s!$0< z(ESH6Q)K+LPxO+=535t@n@aaiC>p1CMlLk#YUB;iP%5Da*~ZkoE7F9GeIsA(r4ot| z`zRvQ;M!p+Q?9->7h15}$fZ_Vi{^-$wJ%0(gSoy;U56JCIU3J(PzgoIy}ftUwQAG~ zu*#nVYc^d?G{UWJ@ZzuluWzEFsa@jLqZ4uVyqY_g)=>l@_;AFYEckH{5BBBkT<2MMplF42akzPF~Sa8r2 zBP+zKIWi*o!rLeZl@J7d|G{V-pQ!H07s+=mmJw8o&JyVD?~{y~vm&(bvlWtdYuo0* zzF%{+V9VxKzkb+B?Vej_Z%3g$j&9pv+yK}8_fKSmq$TYw{_0_?enteEWIKDE?8f;bAL&UP9ut#!42X}ihL-68cxE)d$ zn+HDGsD1lXul|8Df@*aV_g56`@8d}<`_LiAqMB8-52+y)OY5stKFYcS;KdO@kZrvvKL;8>!uk?z#Rme zi$P~e0=RO}f(!Sa)c@YEX`!2B1l7V9+A*#)t%G|&KqRbQZseaDq&0r&E7_o0;f;V` z3xnC7*FfZ-i1ncnsFi5otKnPmkOYOWHZN_|Lm4r(Pd?tULUFBNbV-c~b{lqf56gHW zA*3fUx8?Z$?!)_Pi!OOJldFcE^#<>XEkhCZutOgU)+SOTI5SZwkXv%SQ1kW9FCnNF zzHDxEUOdu!!KDW%$1i)kcUljn%Zi(qfhzTg|L@|JyPRPW@jUFaL2(dXI;f=O@Gm3jLOyLSbx z&BxGPk$nb@IL?M;lUfX zs)9!*Q?UQMU8tBmGB|Z_FEK%3w|$Mw{;;kN_kw(H-6WMtDB=KkWX52J zetWkuK$QHr#mHTIDF5+7Q3*k{1dq&M@X3G$1&E#Rk__X~Fy~^gXhoiM5Ci2jwrCgup$kexQ%afvBDJd!Tn_9&&$u6 z$eXjA#+f;%bSj|;-A%B<*mttk3xOCk#l{=E=jOfdT{g@c>EZn<;$E;L^98bq8J(SA zL9tRa_LeHQ;Fi#bhIckYLQt*v2I7YIs5&g_DQs*F=)wK7?Kk?=jyI@;B53*WZKsT! zd|su>JbSMK++>CEnp+XvE>6j-eK>=_7N)Q!SRJr#v#Rl8Grr?3(w`YoL_!g?e2gtW z@z_|m8K|EM^YEhLS>Y*o2P7NRHe$7G>x^D~!+5o;W%xqDBg3BWjc!p`LeM8+j{G}C zPe_d5Lx1w&)Dwz!@yMk3fH4N;NL}lx?^qwnU#yoARLjL9(=q{fV1f8ppf}$b@s}~Z z-r6q40KO{ayfOO7R0%<~R6`BOh~eijcIVa>T3|$XDLnXWZ~_WKiE}Z>JvOJ#TI0BW4%m z(@LB)sDvVD?*YH)KSlVx>y>$g`c^_vEy+XH*S9kdzrEDiqwGq=8#9y*iI4hxVtmH7xJia)_=-8lg3>ML01Os(C|V0_qG36?yWl|BZw9qD;XPp z_y>M{c79vKp+{9JkyadJJ%`b!!!SPM-L0^Hx9pJ+bgf0-8>|4pBQyEvPDezp<*Fnh z&!s&SyUra)^Q7!Utg%%Vsgi^sq!lM?_izI5Sa+nOXt|~mf@;y;18&2=Cvan{;)t^~ zQK^I?=!zV1?WWOuPW<1F)t?tg2&!fB$YjO^vE~=i+h>ADCVc!4md&9j6l#NN(OwBQ z67a|*9^daw-SkwU5{hu~ui(Ver24QC1Rj}M&3&xnPUtp@pjz@AH3U2|V*jer%>@+& zkBqqYFUCGP4hkL_!6)PS!kUPi_p7Sa5j(23MaVX=pNoHXZ5t4-Tko#Olp<)viu~Z+LF$S2BeeaO`>Qk_qzJ*XA+XF+3>J&k>c2b20Y9x7X5av}e${mOcqQ6NfyNZm6r-yQ}I{ zLJ=+ooejR=%5ma7kM3iBPq^T#X<-yWwP^WpFE8RdXLFp0w`OE_(t4-+478oV9Qpe) z+rQv1VcWadsDvWqepR(=5Ay`}xzU~dXhcu@5`7X%-oCMU0z2S!*G&{bwM6VJcDBX- z15Tb@EWJ^*`JPRI8>xgMXcUf}iERGX2I#w%g?1}_2k8z1MPpX$>Ye@`h-||&xwi{O z-K;$a*@k1rRcjfXy02V(s6&zvgxF0GJKL^(hB017h$zR2Jcoj59~G-*k+l-*XnFJ* z?X>~xLc8{%ez1g~TC^|VPQx_8>tol-#SGa^B@{u&7<_$baZ^XCtv>e(^x@K~C@1#C z1OrXYdf&t!ZN9TR^W*G!(W1VbuCEwD{0`=s07Q^ckA`D?RVlQKCFQ$F-erX^uPK;k zI$>A#`gqi+uwdkq_b5yG^XYp#0JY<9~A6XPT&0wGbON@oulM&_1XLt7e zHjc8R^$gaa=fU(QEpp|^dtj8fPUwjajMRsA2h*L!@RJ2e!is2-fq&_ z$SB>uww%gxuG8bOd!F>Xyoz38lrwhhKBeX;&|gMSEjzesCgOa%7oNmo0*k08^HIFn(&iU#yOI>Y*e+doW#l_wWqFwtNMR3)ihzYn+pt!hd zeo6o<4ca_t+89-Nr)it_mz5Ay%jBv_YFg*e7l8=wy+r9B9IVyPtSup^mi>FdRpYfM zzTkZzdgZU9c%%kuZ=Qu{f~y7$ej)WLKteo}5z&?aqj9z3+UG(|G0!aRu_Ga* zC$S`O)z}W+SCd<`)=aJ%Hr5xnkQ6pQr@_3$Y4x`fnz0w3lZ*$)o~y^swvrLVE5TKB zH7wE>ca2bv-ZwTHUk<-e^B!oWNfLsPyk!-lL;3tFU6he-wKS8fCLWwMnRgWX7IA|S zoHhDw*+Z5qPbL0qY-M#zGgU&+a=7ky!;FHl`+omQgYNkmNQgXpnbIU86 zFK%1`5es&k9*wuDZi|~~l7t|nI%G{hI*rj?j;os&b*;sUg#{cKXdlAas%5d6!B(3*K*<5l~G zM)65!)Fo@XYmz5LE@O}KI~_NrRhAE2H63x9^{@vJi>4_qb-b$)Fe+RLh|ZUa${pq(LdDVT5pX}Pv|H?-)6Qec&O3km7%7->?t)|~sw|6a8D z5AUOl65WU4yUX)cMkEx0ui5LJyawr2qeZ`3Hmr?t^1FV#bnzo9d$C^+?}ca0D<;>E zRF0fo4jIc{R^T7P12hRiwHh7N?HN6FmR?-c?yz%4zt-=K8@EtbR6-H7-q`xJDkJLQZjNeIHlRRcbN>f3>s z`KlKmHv6H`K4^{Nx>?`0BJLh5U6Jz$-`3pe)#QM}b|YgFKBSJ<&?F!>HSN!RHk~mF zUM;9niG-l`*ln=e1V7tvTxwTELeO$Z%mT( zZ(o-od&vCr)#tnJmg6hEz_2IyaIz58E5U9P>2_cp?pdQ8r%txvd$YOo$5)2wR6-H7 zM!@g3ttOw)z8be4m}>kf*lpO-MBF!*yrQ-l^KMd<7Z@GJ*VS?w;{>}68xVxs>JoxJ z32V_cHx1t|^|O$ zDAB4VcbmD(ICkloN_(IEN_K;VV88w02gNSfZFmLUzWE&xZws{K%e~$krxMo72&zTi z6~;)vY&6lM%_c5`K8?3jB5{%t5Rt{VeQivr`6AAD&c|; zClS0jBLre_>(1P-`!B|YW>+Ny)uLs>DT_1VJmyVh9^N)mrxJ>gy_#~lKDQ6_22atC zPKuyfQkmEfLwfUm+9G31j#Sl7e5Y@eWRG2{(vvqEa>s~2R$G-MBxM(Tj& z`S`)?Gi(EEW7S6`6d}z9L-*(5{eJ%`tUMj}x=9uJIe6hKVpju=# zfN%ZIFU=$KeXzc2-W0L(f9nKktwq zu@yA5MtCBZw`=yfZ8zRfJ>mLCdB2uX|d zW5zaa>CD^B?PqONCZ|T<2?=3xw*7A&yk8^4JX?F=_V(1X;KLETI2jM(6gqN>v%`WH z2PetlmDl3@RmC3JqU?^%bpD`Pf-OX_hJXtMh`cR|=y8W)w1K_%Iq5t>$96Frh*QO4 zUSTYy+x7Ha*iUR4=;xrGh_PMpu!tFeq8aP7uu_=F8*IC?CXFJf7WEK&46JIHD94a~ zk3y+L)Ro9Ch&G^YgE^{m4f8bamP_v?1l1A@I)X_D>=-D=ik{^hf=TE8oQ4i6p$NgC zBbao+l>@}p89yjR|C+4n-Igd6A!!Mw)vV~1v4h}v5#@Nf`DUWvcoBOG;2V(8bk6}S z9%ZguroyY|llnMl$!T5DcET>sZ?hZ&uou4UOt6h2sFvL3gOaaVA0RhTX5wNe?Im>O zM4yBef=7zOiF5i@V}F%wP=w%L!k()y*p*OMabtJ;h&Jz5!po07i)zX1t52+;ftV_i{ zwYg%I-oegbG!iZNxAR^IMbH&1EgxoQFd7L&vro%XBnf#g?Z>#aHM72RFS0V5j=DRk zzjUXFmXEQQ%^%pFgMp^0eTI!nC_?U6A3Cgc491@R@bd9eZ>PI0(jEspk&sOZ!?$HC z-fX8!64JxPK8nZ!xOQ0bTGyH^H%X}l0w_Z4k%*j!*k_XVgV^|yqs*LFM3-NaD1vIy z@-a3i-|{M=Ul|`qRG|`z5bQQ0+Xo&S^pfp6w(7ShPu2$JnJe`YNsI2CvBLwBjOXJc zd6gRlI0L(l$#P?Vr3iK#aSA@6WA<+%FWc0OMxh0fyk8D{CypTK3Xrax7;8LcgW-)m z{jhWyA!*gfW|%BD1uml;2~##0n=0dLw6}nu60&-+|AzZUg0rS`Di9ZrB^f?9Blw?j z1-T@l2(q5X2_f$!YoYt=~&BDBm!II~S96hU`%*y}uN z)uT8O9~AoyLeg5SvxOb?@Wv%z7g)P;rWYlr{DNpeOc1R?L@-1J(nCa96xgGz-o z!Br!A2DoeRtpCt5Lc6~~om94-_Gq?;CcT|xe~-=*jD@vWqs{|o&HVW&2e@iX&YBG` z6iJJq(M!N?)3jEk=7Y1f6hZfprJ82NyRTCVgR^Gl;BOGLc4<4Y;qQM^6LM};&)cy> z|8B7(+`pc#H4ai)=3Z+!c<6Bw0=o&|s==QA!tD6X%3j*2&TD#EJ=F&5U5cPub7wf> znpyPoUIG!_%}rZ$$WL28r;vuP1OF!>2z-;*=68Ico|wB95G7}vRNvjNp>60|TEjPT zb>_RsX&+ca6iY`GTLNmb#04GMn0$g*8m`D zls&2b=vPZC?omp^*Rx^WHzcD1b}5LKY@?FL7s9eBK0Z-+)h-5nINe^WBY==31R<4=@!58x zZ{{wg?x`^v10N1Xm)fieo&`P}jDIP(Z7O@n3jH2tl=-oin(fS389~b7x~-MR8@IRM z)y(;Z^UB0+s`Xg3CP@fF@Zt1cQ_%J2OXUrMTn=G;?X zUF@mRz9c=D^l8M-<V7H+fJ!E)n~8#@-#=riw_P5G;u z8$Y(YtBjyyB0+-V!SgGEH{^TMlIBRlL0Qc4g+_JGcGalkM%g89hXDwHa&U+$d1l2ORYVL>N z4m=R`cPm_XcjM(t+*R4p0~pV5h1fS?twwFM-H*R#>|r-VCT@H80Pgo@m2udH>=Km_ zgyb#TG*ICd+}7JLdAe$H)nqKF2yPdwWZ-+}ZqBIoIFUeYvkKD`UhGmC-p@HtmQVz- zhx<`pVLacc>bzg?`-P@=swKZsj&()(yYSzQ>Q@6b$@eX@@O^{R&hY(M={=0ax1BFK ztPzBzSDP5>bs|Ndh_Au(+$U&>N0|A5fAZo zm7O8H^gM4qD`vS|CloKu`%q(6t2HQu4Mw`(shZff18s z1ksX4S9U6Y4x`_zr`D3!CduP2K}hQ^w&=3A(QjFx<()oJM$pw69p~BdjNV4M5!)QG zOUKJ^6h+V;$_o5E#8~%fsC7biAgF{Q$VwL9L@JPAtQb7pF>edji4;M#Xn$jS`y?3g zLmN0AuL6QfD1xrxS+}9zsdW5blQmH+xZpi$?~lw^2T@5d|I@-y;=lA=9zmB?w7Nn$^0l8@E^N zU!{$E9V%F11Ut;x_A@YTi)dI{@=5xmf)%poHbyTfQ@1gR+tPMW2e^krxJ<~%rjz-6znlT35#fGb#lb^?E zvFUZ4w6wGqq`gjcH?&$dtrMF`$I!PyUd{OeJ*xRQFszqyov4`Le678|7(!upqLJ_o&;XK2io6M8_Mbr;Vb z>T1xBeI2!hS9$t6XkVi9Ijsfcl18MMU)5dNbG`Ysg8%grijY4JeKrtOR{ zDxnCm$`H9CbA`ivQpW04v4_0$P)Qp_h}Fy4xy=*IwU)HLy1jL~qcQfWmlTh8Py}6t z$>pd!Rn(lVrZB_eg%|mqZCcwdice*yFbawRV#tw9U;nsnY&#pXS!^W~#m^H+ses zu-kOat?%qDc2fH+DyS`A5TP}1yjez2Eom30^Tz_3bAF^YYyC!*(dUwVA8D6@C2lID ztpyK#pZ(x(CkU#Qd3Twu0q%dq625p_{3vYDy)c5Nb1+)4Um>mZzY$u85i){m$>WvQ zYWYsgQTYBR{w+IUP4YaOo@4TFwmR3h**4;Lr*~&jds-c-wrIPss=+qvS8xDi{TyCZ z^eHX!wY<>SFM-rL^@>&6WLpdy?DQxg#6QgEW;v)9Ez^#MJx#CX#EeS-1OJ+r;!ESa z^vVK36hXBXqb!NAQP(paHdYTfYnG#KZ%3f;S(H$eL6k-O7G)Fui`w;AeIAHn+dKpR z=M}9VT5q&Qux4oS_wN4>LAB(%DlqI>ErIyqB&#j8GiiT&)j?)WN8j2Cub$j~oGeN% z>Wm_&*0@W1%=X{8FBOP_d0LruHF-x;3YAcV+#bD}dWifvkNs(*grHiq*0BbD-s5ZE zMGJYmYP6>^=h0r<2Gr=Xv_EZaCzLVEG2>b{^sB;to@U?O+@;=bDxnCut}1z+Hf^{C zdnZ!_)uO!;Z0vW|nRPYe`q5gnH_%=pyb<1tC*t%@+Y}S=rb3BiilADw_b}G^xVKr3 zqiO9^D1vIq{i^4i6J}2oEl4G_C(7^O)LPTc7VLYlYzjqCE!sozb>L+?Yl#-D)uLT8 ztx?)G@>nwF@cJDBu`Jmwh$5&K?QdYtYIpi;IpDkgzqbe_H-C$^$n5sQDMq4eIZmT? zUH|O-;c%V|ZKptpzxg}wI=A8X)!ivJw2g_L6Z761r=z>o+x5RU3ePhUqGs_%nZHGy z6}#%=$Y;mBj-wtHneuppG*&3y*;r(-LK`K2&zTPhp*jqD`NJm zfb{mYDS~RrC9ipQzS$o6?>9-t7-iO?=pj^#)*Eiu9NKRp`i}ESrY%KV5dND_a=jmM zW7nBp{q0dYh$5&Kt!c2sTt95SQDZ_6)S?oKklVal?e%7F-@dM()E=}AFczA%E5Y(QyijcG<8|Qlk1qmDdJ!b};y?5Wa z9sMdEBPVS^+OjyUUcR7dBjC#AK#HJR=mTa8ig^qCyD_eEbPViWOY(%QENDMwtg`B9 z*6!_Je%ehDREzdd#(w?zSF;?0Ry%gn+Qn@DwMOZaaH`lNpE=|FoZl;jmV^3E`x`QG ziO0T(nb+ChSueu4a~FQ^k3;Nzc&F?zm}=T^>6h zJE@15)fR=CG%X)v*7~K)Uh*x1YRM(X3ZSN_E35zl zsf5-Q8Bwt#R>;rQcayr*t4$G93$vZsHdv#ec8%vfOdG;0Dxrv^9+m_#cZqR}G0dDb zgjbk3Q!qoCErqqZlcF(;TC>*eup$2aZ&stNM*EmNCYC)?-0ZsoNfA_w=e}e1Y3KM9 z*ucutoN=(S+>L0$A^b%&;iNsEdW&y*w_5(SUFth6x#TVL zuof}P@uptuAX-eIM$hL};&^CQ`JQyWwZZ?K6FZG?kRJ6t0};)p>s=F~A3nz4as zJsA-=b-39cw?cB)rV@&vw#8c^{@Ho*ZGG3}4bM#LQPZ!8zNCoKiZKQLo4>_q;nEif z@vH6hD>ku8UEsF^p8OYQ0%<-;#MI`RAw{$~)(pEvEGC{S`jm)av(^bt%y#DAvC4pr z9Lsi^b5zFqs)2L_pd$lq8*_Fxdx_~EdDo~GW*yU8@n+!^(s`RXI|~GrPz3Eg=9BS1 zu9DOGq4kEb-K;AydV}BRP5-Z6i5&@1axp^CTA+1^?Caw~=6Ln0CD|wf+E4vftJu%C1y=sP&YW@GcWc8FX zffPZt@FtlaiW%ZR8;9^NS%IqQ*Un>)5C2Y0D5kjCu@jhM zXq_7U2ioRz6eqR73sbtFf_;XM$1G*v#PCO_mpJWT#7U;JASHVNiAF(x|)CPU7mnY6m*yDoP$Y!vS-|8j4Z@~3J*(?-6waRAm0>WCyD@PX~ zVqWh|e*(n5-r*MNNyb#+6{4A6XMN*U(L(#u9{>^1cd~{0OA%ft1iElAE4;vl8$9(N zS=ZnTE8X^H>J;J83AJEkxBP zY%9lRcy*J{F1Lh3;%s#*9aAh%39Vi{zSkm~RWyjKwcdx42-+x$p z(5H(+`x5PA*cV-O#5(g!46l3Pgq0$wmTY6qoFvD}e`0vt+-VLfp@`J2)l|Q0PkiE% zTEeR{1-m=O!Yl6^g(L*kqUFP`bK7|$AH`Q)+nz)v6wzWJPA}tM(=DxGBdzR6XWxf0 ze8#k0&d+F%{{bKqC5T$ZuNIVZD-SB_^E5P6)K@+3U4K9+J7HA z)d7g|Tl?sz&Q0dq`5K){D1x>PxQhE;Ny|X(USFEqnd_D(G682oy!M?@;{L>MFTFBT z&xw0wrnjyeZpV7hHuskPEPFQ8?)wo|R|aQH&#rnEe~#aHEAanq&*m`^tw*^2CjOqa zE+G<%kZq*CULrWpc&uvQoUrqq`P}lYa;QDJy;bb#&V>yGHTF-nzkGpb zEDU1Da;Vf3>LJcEl&Fx7@1OI6jv1j8LAAnfyu_0(C$)VjyiVjJ#7Pdm`e4L1+G?fF zd8!eohE(huaQ>SXtT=yk9Wmp)>u9mil2b&>wW1b^1hd1x!`3H{;PezAZiLkp_q@K= z)$fb*schorI;VHx6LoMx?hP(DB^DD8zm)i&bq_L1){cn zz2zlrwB7$DjrLvImna&UpU?*8dw%1$@kvxd5wut0#>mu9rdMC0Z&s!VswI1s`$E;K zqVGB*%lK0XMU1@t#w_`?6j6?y$1OOI5yOvtd7MsL>Z8ACHPp1I8LckpI4kbGh5`No9jhee0 zzjsxRpXaOI>D0rlD{Zl0{xTl53=rkG&_mlswWhyVrrbK+qT=jF-y$|2($d5`SShTg zg+7ZS?B~SSFLDHjPpb$U@wJ9HTYJXv*iKs%ia5#Pp?%KYB1L@E_*DGPn4i?qOPuja z-M=+GKjx_L6(6h=LA7Z4kpBqIZ?@pi(-x)aQNCsgD^9DaPM=mmxi#-~Le!9&YRfU% z6c$w@;3_H^w>^N0l`tO{+nYtu%f=35vg8L#olaZ4^PZUM2$(ek^2q zXKx@nx!)4!WcZnlGt($SYBl#ouoqs7?GWcOn*Y2#Jq_i!SlQ3Ph=d|)d|qspuSpGo zn0>0SwbTdfSw0#hm4kXh+aIg?hn^0H=vPahTG)rGc-F6bSihPotx;OjSUGI0EjUbh zQ^nq76RHuv4S;SKrt)iVQ z{`#I#BmGoFb>`n)EB;ZtR@j>U9m5+HC~iem=R|BA5{@VjQ5}8*jVOzE zs@)_T(sM^PgN+rz9wN$PZbh=0s|<^uS330yvENs%&>UUFO^Z6^MU=-@PybPGJw1jm z*s zcqaHC2PcJ51l5vkv;C8HnIm<|-#Nl033;y6nryN?o3i_649{M@kJKJg8_-%{^Zu%5 z6|vg)eWp4Pqv_5?YNCi-5TlvBPs9a?(a`2SL!w2@#;&Cuv)lzD6)_uPG+nHnMFb}G z4ANr|32Z&#h{f#eJ^hH4B51#oZCpPz&AI~fV8g>n4oO0uix^EWdg_^vh^;Ut-YsMm zv6^p*?h=A((ehz;6P0iBClqJucU?VJA-GP3CSlS zF!dbn?Z#CWYk5RmrdR)48~vAKp%O${rj}TZVZ~|wcC9>(h98uaYm@lj`D^N|RSp9; zp!cxt@06W~@!OtjU-+;$3f9v2JHDV`uC0r8+G>4>_GtdRw1Xn3R>n@SS+Vdyw&jC@ z9OUTNw$e9Z_=FW*om4^*gWd>xM?zSDhy*%Z2sZb9hEB$LCGsq)C6{Alnd0fs(dLgr zw@C;|YmD&9V-IU3V$!nB>Y1}ag9sMPh=d|&z2OUz6Mr%$v>wIlR(h!*zBE4cPDvCi za9UT0LCv~y#iVZ@Cm4IPMf1aL^Q%-s5ws3*n#$u>^F7x}|6Yf-;Em=7^t*o@Ot{-6 zpZdvq5~oeq1;xJ*>-U63S1n?Xtj3#tX%s=VGByFhJW?`hiFNkM65;9R-o@}m?WQ>2 zUl#SAeV@ILpSd(v9KSUjO{MKSLFix`?pC<3uGY#^>PW9!UOWvdB9bQr$> zO8P5eP2K*BR#8Nf)LYC3H*D!5=A3_hoK$j(K&%NH#e!Y&Nwy}Nl`q9(_|cfAPWmjn zaSB>%>x3@#R1ueByjqbIyGxXO_lRuH+jyh8-Cb#+2&yH$X>8+@NtSXzM7=CwqrDH2 zHQKp}pNLjzjo_A0gZ9?4w-7u4<}{!9x$^@to5>BNkR~EZ~yMZ;Pel|#?;U-+J6wE zp+=`{5D}R4BsM>ynqCgOgATXcHY%YA+BRs9A0y&ngNlBwfW+qK%f@ycdfhS~W_-5nMxS=SakkX}aU0K^D4|EgfHt-FIR_r{8! z?cdkMnHRA^zg$PtDS~PtCNNmkv5@B?Mqu^7U#?70WB8nmEjC0drgagycwMXk?nm!B zY)mNyk%}=eLR%|Vg6Q-7qEmYi!#_Pc=Agc_{U`_6BJI|1%Tap4IGYpi;PXnqSgBVO zkukXMO}r?T4?KYKZg6S++{1F=LH<&v5D)*nF9GSKdyNEqme#;!wtCh2Z_fZ7ZLab@j$Wy^rM40gEpxs<2`fXV# zl^oHDX-~u?;lqUOUxMux5jAZoQOq3M-}EbxMoUh$s6D~1w#{-6C6Dg1)P zbhG&O0H3PyI@AVj1L`4S&R)4}4vZx|lT)R>OM4%!Y2-xCx77Qrnan5b!gsuTq4%-u z`xv4l#82i(E#fKaEl%vHeUt*Sp&Ar-eNu#ZX z_{pqY5l_jzz1^g?=IXWgUw2a}f@)EF$V#36=s1i>IPDW^ zPr6Daq*`)0kR=Pv%94qElb&rq|2ig?BrDXy${?I<<%Ouh}+Yb&J(lXw+sgQrBtLaPxE3 z)n7Nechs?4Z#-@gEcWqr&m{rIring2{~l@Z|0;|zL9o(t2hSZkV|m}}3g0)2lk z+uBaDhc!cLVRJ8h?YND86hXbh%Gh`{YOTm-zy>mLmaI%%IxQ_CF4!Tv&a~5t%q3kcqQq zW#S|R)uQc$or!A$&8+2xZAqcDZM}S|!$$lb=J@`bx~g)!vUL~Qqw3+SB9{s+GncAU zM1{Xywccx1bJW#}f0((y%St9CQ3TbJYZv)JYgT?RjMfR_K+~Rx3z5geZ!gu#AxPku^J;QOV~*1^@l#O#uz^Q_7nrz1-%9vE)MS#8F2wKcjC!{6$!Y>Y@GM8IpT z0FQ*2>tS|g!CA{+sNMHhg3~Dik=$1;xg5cDS6DB*!pv8Vq@ z$!VbyTD!Ck&HP|`R({Y)TM+pO)V-M>)RFnaTkw;}4~kl@vno9+KPVxn7VSM?^4wC} z+=qKLBxh*&%NKY?l*kVnh|$d577>BbTELg(&g3y;wWf&KsDvUAqnRal#cZp#);Cw- z`39D+M*AybG~>+Fx*|XLP2WX+a9>t_FrAj1A`qjY7R>x0Y#~2r$;uB}DFXRHBP&0s zBO?TanI8nA*}o;6Wib!lDm2+b`%=`6mykC1>xc-9mXERaH9m$3ujZt-NTm{rpmk_w z$*fsfG7I$=5f?l$vt&9VF8nsLWUz}YS*n=NktGYG2&zTPXJ*OFY&f!HL6U?#SMIxi z_)ksC%95qiIzhw*PmXL5@s#u=hAf$ql_gWDgd%9KG_z!mtSp%gStOLq%#s<%f8n=N zWXTLfT=}8l)86ZCF=(bgiiHQZ9R->LEucqH|_7a)6Z@fY#&U|Z;iA$$8C;}N8*fuk9uz^gR zEh`hJQv@iOI9Y%K@n7o)}fh+GkXa#abbvt%#w>(2U!Qb zcehO<6K5bhpl4;`U;~*r@r^@~iIWgi3(=6??Olk-!~yZ{*g|t`cfV=hN4-KcWZDz4 z2cjYD6#f$IiekRZVCK3#^IB#dilAE59%C&M)~18kfFItz#X=<#Lh@?0wV*kc>>K}O zGc7Hm2-7PORUl^8pFZfiR;>ORLslkLv^laeVH82NsBP^36ym8Ou00Z&6h+xB9f#vg0q2XN3CG&<>%^kbVzklvLw(QMfU9*#Ey%1 z%!q#N-NSXHXAuOo%@}fCX5U55Yo9pDC`K8vmP2O4mX-4|5TluYcdcTP^Kxe8yd2^r zV^+?~5GNT;G-5W2HgjI44dlEe8`5*llZFRI1ae-stels~E`4nSNsH9Fne$4^ z%6VC-b#eAlw1*k%>=$Pr&72o(Am^1P-gD%<(kKEsudiB?ZISab$3*13L?-S(uLweF zO_B4`vvOWidq{0SYeD3^%=3xJd0EA|#H^f`AA2a7A*Uy;__`8|&f>+3S=~+21 z1v#&;5?Ur&(_ke!UE4fU^!!ETJy^q;Z6MZi$O5S%Nqc=p$DA*h7B1qLQ%DXLj;NilADL zj*4?vINAO}tkMrv*|tf%wd2RBepEsc;=H0jxT1~TA7|)qqGR~X?w&S^pjvIO1CjA| zZ`4S!25y`4k~0$LMZ2aHv{DI0gqtTBukK~)TOe8#xTF+cG?~Zl@OM%K)%xB%Gnne* zS~cHV`b;UPOy(2+jc`&4MYv9!F@_Upurbdz&5Y0I{ra;XMNlnq)~;i*{1tGP4TzU> zN}D6Y@I@hY!rzEG>7JaK^R-UVGGg;T%*=mOt(Yy9BB++@1fZF(`1v>*zFS7zo=>WQ?6ni)m2Um>F?;?}PS zs)eZDwDG?c|9|;fDxnD3E9AWNtels~v3&Ixc@_LNb6$q)Eb3N~^D@kwmn|#jl}-^< zOR5pJKCR|9(RVMG=u(x|58^28;N1~Qm9v1R5tfk2+q%n2jU8AfeTE##?yHuIc7Ag`95l~=P;>*m=< zw6huInP(r(yc!V5tC=|#)kL22YnxL9ZGXn^j_QYNF8+$tS*J>U{oV#{S-ZTF_NrO_F%@RoK}dZT1&c)r{N46;^3Mov0=PQS8}y z<70n|R>M|6LP%QVR3J_pelErb6p2+E)QQmO2`Y-9r^Rq1x9})q{fZCj%G@0!8?KXw zU3|sKLs~xU@9y?6&VDMQWoB=tvCw3Nl?hPnZumN^$4-TnsG+b1W%2FIpA|L$-*A8C zi*nSvep0WI_ED|w=!S1j5(z0e+dderIlyMWAN+?3A-OkCk z^mB(YRPU+yel3w8Li&1^({;x4jgL6viF0wU+N*=gEmi-0HdJFzkTHC4$7Vl>Q=U^& z6!u$Xg%v}YX!+O_x2?v&JEgSmPlif1Xid|4LtgFlExp9a4Ao+ny`sH@dWhMe;vvKP zfvSC;lV78~kJhgJ$w?(6e}5&aVG)#L@}Tbet~+j;e^oGAQ-5hq)AF$!Q`hQCB44YY zJAn<6N+^QXI!ljUYFjvcf!ci6Xt_N|P1CcHh`f5tQWjQQs_tn%N|Pi6A-9LM)=%l{ zAL2VE2l4$ha+Z^7(G#>_bSQmIPbyeeJNJDfO{x>x6KRdGGH++-dA*Bkaj%-m2%@#~ z2h4UW`YKWDMeTaF@>icu_+6b9&{vZr1QEXEtdj9VPle?atXyA`CaYBv#t6aGVjtTnsVhDz({sI31|09G47hV& z>DJgy9nqwV5>&a%C8Mi$sQh=%-&eVD zDxrvch2AL{!M&7nSMLMy`g02{wnv)!+lPk+MNqAkub5imRd3|#g$FmW%KtME`xDxzXX^~pGRH5G+JjBJqlB&-sIa^FznO7X?aov; zA3$hD$6sGl3m}eo}9QhB86Pno;t8*s~)ZW}%s!G<0RslbzmTcHxX<1Xm z2G8cNH{pc;VX4PQrYMDav`$4>tyaoGr5iP8i zhqmlcF-@`|J@=Kurs0j6o*Oo7Z``y>ak;cXj_UFoMQqS_1-BN8m)4pj=g>T-mD222 znHpOqN(sOGuOiuF)JEX22Wq}Ofm&z=zAHmLp(Q8w7`xN6fEMBDq3vj2PDV&t)W+Z+ za%s6&b<%c@sH)I@McYR9F!|4hT9=&Vw9nZOO9-mZ}xXgwTB>r-70!Xq4$%u z<)a5F9ox>+={rbm(D$FQp^j*6;=y0kyQj(TT6YKxK^b$XgOp=@-=*o%{Xbhkvqjn5mZYq$M{}Nv~w@s zsg)jal|GlEY1?2-Tr*Z%Rn2a!uTw=DEvXG!CY<3q(oK6Y=`SOsUnhfFr&@G829xKh zvfAg&dOXIzxk2wr)axrw98E~!VD^umbX3XcoNRlsN6b+rxSw`3AkFyWn4iX8VeP{* zgV;!{eUh<;i~HUdUb4JO?`h!nz)Mf9e1%TNG~QT~Bn08Q&Cw^pb(`Z;ug7WyuOrR} zb$e@)gdpTw5R?81)7BKv!+YJosjjTJ9C7B46<43~Ri#@y6wPY7RntzrI$@MPR8FG^ zS`K>02xk|90<=Awj~O|(cxjS^K9|-AoA4z>yIO(q%kCdlwtAPsR)yJEh*;zPS67mU zOtXe+&puS<`KJz0rTZ!bEh9SGD{4C?hVzEab4V>HwHiU=Y}Cd8ZR#}}-~8^aleRha zaHTk%mpLoMqqn%h6BiYr<@rwGd;8|sB?)=197{b@m zir3fL*Y`Fa)Ga5CyX^5_3Onts*b5Yp-e!Ec_urOU&I5aladjTb5{g*)Kw&B6l#I2w z8_8B?wA4mr=Ha)C_m&WLqD9{owE1$ENWj#ya^ zjcKHL*iRUX&;G4S2%<$jWUTcHoAwapID+_Ak`M%KC*&>)hH0zs)#TY{MLQ^hYSA)* zn<}@W&HnXwqszcNn&dm_?Q%JeKT)-Ws?Uuh0k7o}QUvK^;7+)pXs0Gs=DYmCX-<5n zeV2NOT?6--YPVHatll1DrD(!+yJ}&gdGAV!SjzvoTWx+X*s5(CCPgd~g4{~O4rI(8 z_4>x&tm)llgfvFcXo+R4x~r;P z4jy(5!rghNn-SWUk_po7JZb|uJ#uGs*T#Z;&mR$5q>-dD-#!WpU2n5j#64PKL-LmS zs0F!u@ks607vCUgnP{xemi<$JM^uc|ew(^U-iKMZP+=4ED(nxuX%eD)L_z+?2OP-m z2LzQ+1of8v_HO~cAxES(yeRmPeKGf?)>l|F50y~_jl5ZAd_i6)AwnC@VS^%wmK<~5 zJyMW+CDqrqE?XlZs21Iy11I2C56$-yjuda+Y0#)q8l8_lRhV}@g>`%(R>;NNwSko) z`GZ#L3`QgrA&-flm$++5nGxLo-dbrMWQ{Ij$E%RS&Sg_&gl)0Aw)AcUuYG;3AxQ{= z+6J%3`$AgNI}tp^Em52b!Csi_t}ea9E02k-6?ZKvcO$0{4ihf`%ppkOToTq_zI=@ zK5zBG?SV>099C@X)2`Ca(Whgy(gREB^ya5#iZh-mW~)$r@>Du>vR6HU}}n#fli;Zeh0U5|@SRKG8WJS8m6> zcW!*up^Tcx*-k=GEo80;`$ebjxwTe7Wz^n=jG$T`n{it!W3aFLE|I(V$*rhXy698o zNPc|zop?pHC_@6uv#64utx|yYLrq1K>V%Zse)FX$-yRP$%M@ELr{*3zTmAXR7LpBn z%e*S9+1tj{X9{bZ2jAWrX=DG#)m4X8*);uCFp&}zOpr!e0TIryRg5x^?kp0)<3*1E@yr_Gh1hO?%m&BhQG;`O`&{D zN+`Qvy#Xr!I<`@66G2z=1I&eT)wsdn- zc+cy9)+I!DYnUk@BfK5Zq;t$%o^w5%C0W@qscn&0n9&2+Nb*-I9ZX!=-2D-Z;Ia?` z+lDj3wae1zS(R8|adXKl+^?isC#i$YS@xG>wElPGfZwwi?ga1J#4!`2$BT)d(rPoJozF>{wA+ zs9aa54RkseTBPf#I38OH?a`{XH9I!t2HjsikVz7RkXnu#qvZ+S=vtY!G& zLiJ@J8x^hD*fi>#@>O(ZHhsQQ90&Hj_ZVlI2HDyoa}Dt+^I!VloEKZ`;V#92J(LmC zvI>+Hr+TwXt`{hl;JFsthOBePuk=@q)jVfYw8*dKOE+$Br=&IZSL$WD(2mPvm5HzH zl{d|OX|d8-F(|&^l^ZXn59THq?;YqWummHHXSq;aaCha=Nqa!F9`=(KZEQ|Qd&f!$ ztmR+Vm%g!1fPD`1WzuZv5$fK$78^6hTVM%B9CG%h@vnO+@Mtd}23{|u71mc~i?izp zEWwC6qg`lxX&5(g)d5ke=LG6@zBB8Xe3N4Y)>_cZhkC6}QXHoR1EPAsXxegCS2j5P z3da(RsO{lGw-+ZV)%Vo`#G3qlw92DCY$m)ph}(lic+e0AxzO*afBgujYg#vrq2pXz`Y@bRN9Yni|_xF*w&( zq?jbcrIRM`PD%{Bc&D+{cX7SpQ2-qAt0S3>M|t+}-X3XuU_@$!AGOy*>)oykb=7%e zeRil(F^z8cRYG7bJemo)uISlTlV$YRxXRKv$B5X{e)P<1n0<= zA5VcjaXjoxH&1A<=(pBU@azgV!&(HeYY*r1SA9LDc^CVROM$)?Z)SM43eT6S~ zfOpSLW0kxSK?=4pZk``4Q!7rn7paYpPQjzt)r%jMeY!dv`-|g{5pfZNS*!isbdK#d zNC>PYdlfLS2aE4NnooIlkYfo(U=M*6IB6F>*)B@FjVdoNH&y&g?R-Rf;P!fOKI0p( z4LJ%O$yp9@+`QM54RJiox76(hza!drOcG>Rd_f_W)hU_QTt`B4l|MJtf8T-tM8U@% ztiMkzZ~N>7l_Uu9hoS4M^Pf{HpT4(eG0UGAZNthjNrDiVp$mQo^J7`CTUlXqxRY+p zHSnrvwrk#0K){A3T@=FN6gzk!AEUY>6AnTj}YeR&PJR~NsLz!D$Pw^lufRjwEc4r3{xt@{G zG9vtJF+FS>E7{PaUhl%iyrl0E0&B_aVl&oOWk)K8igxWcaV)_I z>@A%ANZv{Nwu}Or-v^Vi=ifVtJ}+2c|HVr={K5&~<yIE zujt5@l}gcmXG-GE>hglLF*s{^GW(o$n(KPa(_sYG!XCo+!DB(}XD3(Danf9lB^ZI* z34U>EIKGLsNL$YzUD7w1k%E*TG(x8^<}P?opM)OAC}g;xX0i=4K{xEVcqj98tZmG zDj~3zv^paT?S`_<`sRFxZaT#?1OBa*SC*YBj9}IyuNuEinJgi&7Pbesw)PETXV}KD zPD?jaNrF~-vR5P8uIICwMX?6a7EH>EpzH^n?uPOGhocqVU7EX&U;Y%yl7Cn*obe!S zwM?3Wj=XuP$cX1N*YWX{qFD2bfH(uWx9SBt(&8NCdj5xyN+N9>*KqqDQLLrCrHnvc zNx2$gcQu2%ghsO42d!iT&R^iX23gQ%1Fumdie)$a%PXw4#gdZKuHflzi0xPX4V)~G zVh2{kNe(PQ2zl?^=;a1}dS4U^iIfpo3uiy!HsIY18qz*Oba-to^j5IOc>pXL7h6cX zZF#0P_1R3FAcvfiZ!RIQmOLkRE!aYP)r%Cx{uUBK(vs$@b<5ULUE?S*_JWMS^Dem! zuU6)q(-HewP*>ed*3p}lqC~-03n59Qav^gU?W7}CI{{JMY%v|uB3z8UUrETn!bnR( zf3_T?OGqEiwk1xdOL}?Gt(TLOvONbG%VgA{iP?!tUY%s)&f|6H#)ptYZa>-xJFjvj zY0E1Ld$7)fVV-3It75o~pd)$Jl@U4cdrsn=j+BP`MP$~)r*y##d*)o(lfj+y|7U#8 zJ?Kp@)GQM=;YLg44?}dd^%_GoWDQm~VDYK8;&R!^)bJ1N6bewO7gqwh-rC6uLeK{8Zz6C+D*5b_I~WlrKfcGn!nluY2lV7B>7n-_Hb`GHX#hY zG~hNz2q`|&u~8Ye%pT40U(n7L&a8L&ni4|NlDs-orM*(aD}p6A zb7RuTL0Xsz9!|uY3}qM3#L$S+@f3S9!z`FOy1Of6U_|J}42Y?`7qrENP+-R>3TCgr zm1OmkKS&5kONygis3Qw=t;F<3Q-*!V2-{+aJjDlWPt&zEdp02<#!8o!aKb zUJtLtqFX(a5Lj#4fceTJ4BaZpJiFfkWt^oAJ}sak^c=;EE*}@wBQBjqebzY>v_pZK`g` zO%Cs2JW>p-q)37hIs0o-E68knSZauOTYYqnbq>&TL;FhztW|swekJzxPz(zq0Z}jV zOz!A1cC5$lmI6yKBIQRdYJfa--mGvy^t^vItX^z=wk6$PLSU`bUEb6Yz8mPDGC&MC zmzlf7wkyka`^K>ZBV6K~XzU%xY){kyqW_myVM8MNvkywHguq(Eu6fh=3rR}+$uK~a zZ;(shl{ympln_`8+aqL0n;rCHoeMN}Laa2RusuBf;r752FSeu!VHvq*k_}u}`f2bzsw}k4 zb#2s^+Wv%E9NbF1hyEiWu$FA2UfmzGZQUx=+^>@~mtX{*$AEiiUny40sxE6{{37)$ z9ETivs#>4z8}^zW4J#qA@3{T3J?JGP(rD>_5Ac}U3DPW@xYdX1r?gk%&qt_uK8CZL zhg-2h)r?B?UK@eSl5AMQid+Zh#W!m6)jRIQ7Svm$w%8XXA@oQ~jy!3MGke~@oVxsM zl;jmg_)qYqc?lg9eHX1ghMXwD;=E>a#k#eGz*;ya`0~^8jV^t6q{zJOBJevup{-$M zNkRe>QwHc_RTz&%2WzXDu#!1HHj%xx+r_&M7{t?#1cGF9AW58~JJ}xAJ7pt)oxnWI zjs(LFxs8s5w1#!b{C0_~{Hk4iLik__fwl0jX+e7j2xV=dR3iS-K#Ieq~Ozs`hXf=p`nZp^IPF`kq* zLqcFJTqAJzH>?c1y4h3Axm!lymyB?YVl<4ww6d(5v#0Q^BO|aD_K=W?6C2SM&%?#8 zi4IZ=VjJhzYOR^JwrdaIJs@_&y3oo&;iCD-ngUBO0>9b>A0qDUr0+h5iqQk?q&Tn^ zM#G)`V~2EQHb#oY-(3Wj;C=-xaR2|}7@UBp+luvmo5^cldC#RD9tFMc2;`}~-y3m1 z2LASLt=Nc>nf&zp_Z&<75yB7%k*7jt+wcw6iJQw+Waa-g7gyR<6BvQD>%Z*@NU-ndH`%RK|!gx;(94}gLU;l^Aqe0*ZcBNrP*dfSe;H&}G!h2E3 zw@)9#)+-eb96IYR?NTv9o=cKXjbRf{91eTcrlKs-R zV6i)jExhK;r0f978sJyv2w6K)gmph3$v)k4VUh$PNEX~PDxL{hyfO;h)caXlSJ(}5 z$iZ+c9!oGn${MsBrPp0s63JfGa%Ff=9^D4!T8|P6={r$}vkAaY?b%HC>TV?Kc@k`( zvLpnyO-48V8rIn|iq&1}!kj9=X_{i~+|Z2r7=dj=9R44|c6^RxGxy2}tcCZ~@Lla? zQEorS2CQ=%XUPWE!ue9*X{Z)$TzfEFY-{W;9FyS-Uq$fBsfM(7mgimL(<@w69+nYUD}SFmC7-^)_xjy1?|OYHty}LDCHMpvfh8D$XFhlV zY{KiXg0JD?q?xm8`t^dOSS1LY%eeHgij=BZ6ZIKPE<=7PX4DwP#$uKXl@qTqObN`%A zE3Yn6utY-qWF?E`8=unr3tYu8PDFI`Xr(irWU)A$-la z(w`k~wvT2e+AA1=wel`ONf|wLq+&m?;gR2!{aEyoS_Q0B$Qu~vv5@)Ao2Ozl$%k3= z9WYkBTnLE8wtZOB?32`U_^|_6f)TQfHr~zH!|HbISRvd?>jLMS6CuZXeW!};MVA5w zjDuc^Vc~AD@$+gYwzhvs*6&=LB1w>k*fyLH(hXn@zRso-C-mTwL}S)C;jX~#BvmSj zgx+vu-4^+>+G_-4%l{WSZgU(Hut(+9VhbI-+2(;qr1roF+%_;%7dK#4x0tgB16E1B z1h+pP!Eg)0-hr+53t=DBRTR$#xZZezEscNKONn2m%?xXj8nDCt9oV35WvC=UH7!T( zaQYvnZnk7QLQd*10&7(SMvB6PkV77N7HkC9?#UkZxIi1c_TpHA5gH>!1~5~=eJ?(suNo^fiL1IJJAp)pfTE&W+Fn0-~!61pf)B1>@ihBwVbJh)?Rytks0z!Hq82>cRhz%x<7;xp7$ zn)^%s9?lLPyaIV2R2J6C*bR42D)&%|9ucrn(d-D1D|BN&+qnxY!H8x9zbS@Fy_JDo zHN-*ZL%bejq{@AD5?F!}A;2$@2RswNBmrKv9?+k=rFUVGmF{qiz*^BE-<4@uNs2!0 zCm=Qj&Znv42Cx$!+j3mH#)$$cVq;zA=NtR>*&jJkCbAUmzxMY z2C)sfx33y)#|-Ia>~jfw5kLHw;@G6SQp5?DVv^$Uo$1Wt>?$y`0p*1hA@T~_BjjY? zx~xZ48=85ej${L)iyHk>iq>>i2HI#NDrv?8eK!0my(!aWrBQK@lC!X*pV zjkJ||J4WDf1E)W?IVx9g*|Bn0TSy}cBO1T`uIP)qDaUo1S6u*zsKm7fiq&U^dzljcP1iHx{exQw10 zf0w@M9V@jtjtSQ^e0@EdNFQe1RbzIK5V$Ptm0`;dML(j0lIN-0n^J@gyoT+ z9htIAHR$1nt{(Ec?Xm#TuvH)%5WI>%T;?nxu-2bb&ang|{=BS80{(C$FKD%h{_5!PUy0)MlZ+nPt{pt&Nod>M{emO~Q17r`F#@Dx|H^z8~Z6p6eAT4-B3ECsn z6<$#S8_l<8)0D)@;{2=nLXsea>{Y4m*Nm+zE8^imZ>g8yo>AOg3Bb;@*01AxThQlHwy*QfKkw)uP16)3ySai+duxqDBAn))v^fyXzc1=9$W!NW8#f zq6p8m(F9H>#lqGHSY@~!BNDGe@`0iZcF&(rghu?Z1EwC0buRuv5 zWSw8Y?|DXfI28stSK+#MG-p=RcY(g2J+^ds2}Qcy!5e+^*h?PMF{_3^~ohjav|7O{Mtn(j^^_uNRu(qT2g`FyyDj~3zyyr{; zE{?hx-9r~V{Fh@1M#wYV_mBZBz0KjU`wg=tgrp_ygqQDyUD3Xo2YgH1llPpz-=zLC zb4qPP>}vwE-=+y+Kf6DW5R#U(D=KBvf!)77DRAvohJGbOW3`rYK%o*OrzXA3Rjm3kE4E-zblWVq-_KJ>TH%^!{oVmdW?FDU((OTp2hZpjy zuA}9F#bbxwl3@u(z`JWOU;TcC4-i(DH_`9+B3YyB<}6QR?*JALVDnHh0(%SDD7Kl- zNseL{e^!tXk`~Hw5K{Z+7WyqSlGPal=S5MbfLsCg4vocQewvh@A!Mw_R+{-XlJ&3! z1TG69u(!ZszGO4CE)m794hMwB-eGJ2Ib>MlAcSO_w7a;O_Ny1g)>ioofjq>!d-!$k zl|d&xZNN_Y%LuH6GpvMUZph?McQH}k$6DY$x%3Or{>>j2kCQK8v z`|V75RRa$ft>aD2qJ+ymI8Uu{acl-o4yU~;K{h1YWU=>JUb23a*i;7MKnO_-&DxM3 z{l13JvWpUSkun0WI3y2A^{NK?W5qBw$)OZYi=U%}>;>M+PF1*R1J{bvdXjqlXvk^;2OL znlS~}XrAMKg(N^$HL)sx^Jb~iPVKD>{iW5eU9>9;@{eE(GIlExt32Xzmu!>6L&MqX zE$%FPJfV4#kP>U#S$FTbqz5@XNWEfh*J9^*-Hm! z7Bcymj6hoY^%oTbuy`2atN}5hS5ww@emSOuFXEB}AxNW(3Q2jOgBwYJ=ocKty4?iM z%tgy(1k%Fw2H)J^e#s*5%IwhXR4z#nf~4mFdjOn6u2datG@1~`I;oBrzFZ-BYou?E*G}ib9$7q+Duuz(z>cu~()D}@4xV8zBaoJCV@b3xdvNM7E&b3z1n@fGS_4kHsFCgS75z}gHy#pnJ#=_1Air>Nvz^A&=+j%_|!&Rd7H-1hkTPH7@_fG zYy-ZGyyhC>(f+RD!j1&v=7Yr?OEBUE@MP%WRPo6yt(V*$-$5+?7)bl|`zax?mcECd z5^oI|y*SNA%yufyR0X!%>^mGwFd{KFK*>P7_I6Ox z`z0yYnrmL=mb4MG;M(Z8Ra+$l*0Rs6tHgUHDpuSF5I1^l;0x0FvQf^hIhJ5VA%}0# zMZgYKT0?lPa-dJF6Is^n<5CL})6oh^hBLxTJvr$+RA~&nQRJcrAa(^^Q1YG(XO(`Y z$Oxo``xx9^dOV)KuGD}{h^Z{3F@bF0-UI6rr^U+M&BNGgGLuXGA{%c;)KiKsCMszU zwK!7pOzD*pJ=l1sJ6w_=gcK8bP~b)Xjc>vVs@n?*fxH^nubyHk-Al2$sI}mIn`qkT ztS_6lzOIlY2tj%zC|Oe>Pd(ln5GQ?CQLC>u%(_Fk9C_)U=jIk8irUv#^l##o=A-?%dvmMU*Lf-oB-f z{KcLid(a-IJMtlo`?9@v*GcVx>kaoeVA6@q;hs4bEGCr++}p8NdKRd}r*>03n)pFo zwfcTc-`u3p`0&B@$b(p)1 z|GZY2yE+b%>Ix&Uhj1P)s)VThc_qKpxut}_S~xy9>s&X9wp%B-i9;_zmRwMXHav~f<@uBq?M1B6I4p=^xGOMJaOu4oj3%WYHKW7KPII4to)QAb zA-zgN?9R2NWriQ;g(G_kNrKD8H9~AAjZ)4R5s|bmPLRH^DoO(`iwV`Fx{^F3+tNF7 z^Y^}D@%}nOdZ`7WWrQJd4gUq%;5}Wc3;asVz|N-?$F^m1D%e8XAT-=@r-C~aDkAw` z3kiX>B->=*{0!r%M%jFk_W*(W5}{)ia@0x57+jl^6~HgSfvdPI{7pvBuA}BF2l?KD zzA^%7;XVc@uxUO|-{2)4uW}NS1R*rG2#qxYZUTdiptS9L&TJPks+zxqz*=}s1n1m4 zq$vYEviY)k{e|Q^utktK$fTOWI-%Zj;H3iAi2d4%tYGGB-R+{&Jab;MjKEsRLpWJ8 zDV5vwsU<$Q2@_JCV8r$%z@G`{cVB9|qP3e2@R!H^#D0@nG6HGgn1CtdWs$Nd;}p*f zND>;;#sB+`dm^?+>YcGta_C#WV^udHMTiknFF8*~@*PjyM2AcDWCYei9ugAy@*&@A z)QfT*K5>F22qE=KlHM(lU3$GR?8HXM)}nW?{%}g9t^fV@6<(2(bYP2UqN{Wudv^mt zkVHbD7nR^uE7w}=<*;XAZJt2(93iCnLt5$Ie`d}$Z7&;o(=tX#yEt4ft~U}j!kooS za|;_9_ZI?doyNPO`M?(OZ_I?;m*=28ummG;%aVO}U(i0!w}p}S-DL#Q!n-9nx0HOC zvioNaEM3)CUi%<~Gzv(I-A8HM4-;dzmwjXe9_P|Z=FyXxH0P^0uqu4GG|us_nzSY& z-Pg^ceP%T>+BnGwNekN}We%;Q{6z^}+nIyqF^E@Tl2;#Hma00l@yz$KzlvYs!x;qp z0wCN(8eqxHo=39XL2Id$HF)(BPNLP+0T+ad(ZJo-&yoc^j$|RxYpEnb2-(K84wkG2 zFc0_BgAI*eLgSe@Ysv{iNVdtdL`$~ZJBn4XS|cM+UPH=15W5kUOm&K4OUz{i){?Rb zggv%oeTpO5ho%{l4M}VIcHngmP{<4|`!U+Wis{cpvI?^Rfg~6q?}QU?RA39=MX`u_ z8zltR!udH^E&Z?-)%!(=w1^B&Znl6os%k5wVl8Q3E6?pU_L>WSizsno`X&j1wd7fJ z<|T7c?q;MIS9-IAkhJhTMs~k67n`l3L|wj7LP)cn#xDUp6NWogpsw=jS%@KrfDbtU zyuuPxt~@7-2NvQmFjLfQy-q?%S`~K!Z>p2dK(zK)InYAvhp(?2j<1(q!ox4*5eX4q z(n>7;&_?thFYY%F{+z<7L3k`kNb!H?S|8|OkM_2%L_ z{3>u*tOqWO&ByD2S3Y_-c0VwJjr!b9#c!GZ;jIW+2exfmsF=(AT%Z#2>DT9?rjCIYkJmB$9gk8LeBR20d*X zFYp_wzgZ{@^<98(f=l*@&(UY}dBqy^RwWsMwIti*SE)ieVB1TjLg_?-Ux&pA$sU#CsT~0apJ9Z3YG=cm@URR0eUt~^>vA%;uQ6{+Z>4BC{7rfkIG$Q9!dkY=fqVId&M{iEQ7)!5YuVn8)i0}3SjlH%Cf_yt`*(TE@kpY10Xzg5YSe7H&=Qvh5q{JC?9DU*HT2 zMqn)*6G^a{OP{|zL~Ct?UV?{ud|H6TG&H!`%`Z^v(zSf{w=J+u~*2Gye<=rMgHBCCv~A8lXkgeUjzZM|6 z`wtfD4sM`lPj@t81lCFf?uUP~;l%Gn&4zBNB8t9xvC;+YbXbBBS7%VQ;(#RObg;I^ zX=m*%+-E7QRg8BoMqsTj>3TJ#UvI@DT#I~N4iV<8Gi$VZk`YTV;_3#S+T|ep;$&-H zh1z5z6%>L_q&XE@yVFiqPOB$5Be)Y zLssqDcJ;i6jwR?|)S`AK2qD=f9jlI2$AqS^$5Dg1?|l1+5kR@DQegT7FksRQpkQ0H#2ffsLD$&r(*Mm;b(=+DELz-ajVdt1Gn^pmztj1%(c zLS7&9jt+p59a$GL9CwsMTb{P@6#F@pOw~*=zqh$nXV05=5! zzedA+)p&ZSp_)#&}-I)&jss$K(sg}@^Re^Zo1_d@6ifYG8loiaE%a`wWUSCOb>D8S~)>F4u^85Ws^Qo zF0N6GCZndC2%E}o;@NIEk%AFe3wub+&QuXa>l9&mWvSGH*hYN4L124AaMoFEwG_~{ zikRA75vkrQxg^0}VcVp`3}+Ewj1==e?o@HPxR+EJruCRTfkf*u#LCoGSY)N~#OgpjoGikx^9y3-E>-t7N0eT*PTA|a$vdt-Vn z+BM@)SlCG!A&u>SVJ`Xa{*(0iFjes$KjA>)fbl}wnc{MBO_Qvkk;>KPbHhGO{tJP% z&_02XKK*K{)eptwE32r46eH-|qBq35DE7AT%Bs)L4o>7uu1h!4sVi%TN5wf)r8*)j= ztolVCgOy%pa3TRAB-oIptaO#yl6XvT~F-nQF|%2uVwt6AKQyhz~C#MOf8~ z5<;5K>24z_{-VpvafcS{Fv&$E)QS@Ii%g9KOK`b(<|D^yyNIHGQQ`~h6o!Aj@>;_> zDC6edp+lerZMKJ!f?%CxWvF#hg1U+msga__$CtSnA!$josAZ0enEoMBoDHrhdxbrb z5M`FRh>MVQKIZi{IXKB^#6pc;c<&(HIz?;DT@FX~`2Yv%?Sf}0Ucgc?b zuKhYse0y6-Yn4xjo=6s{lWM66owuxu@8{1+qQ;Yu8mez9qag=S^<~ddvLTjtUaaj=D%aF>I>=8e&6ZD`bV{H=330$KjB~v9H zehT?ioi90ZTFv{_OVLN#LS32ppQC-s`>^IFHH1FN9wIMOFK+;xNWnGQyoXAx;Do7` zvnG{SOogZ&*u4Wf`2Cotl7TOEBptpSV=cZwC5caUhJo6Ab+K6r-DBp)47);P1lB?x z!f%vAC)zZ|i9MBckDiYjbaSYeYL|`J`(D`j4FltF;|gWEg?8#5{rXzg)n;Q-p>(-I zUYp-}bAi6KhqE8pI`T@tpingcgTNcpO5jy(*97%Y+ibe&6r3Eu5#n;47pWxWu1+ts zHunk5Q7_&*PT#hNoFztJEo6_7muq79n(pb;+F=0n64bUBF=CHOvVcLNN=>k_<&J@e z9@#|SI>1^KBaoIH$EC^-buHJ|VbAKt7xUQ$B!#T%9>qWSjoDd zq>+QQq>)CfS8r6xckRV)cD=!|7M|5)glUsz;@7py+^g1I3a^p!%3ouYoTXn?c-K_b zcnuQoJyPLCcs{skCq+N=D~!=bXX1ok6J}gJp#;McjK~Ts!Q*PgD~4bVF(EHbQ&4zPDFVU>J z6DxRfjA98!oK7G-`fD#`bKEyTxZH9Q`(Jx8+vGzOOE5xXK*$Fsguu2>0nw#@5zp}K z!mgzckPujF;rO5G%6&;nRj==W$XL~tw|4HwX8Wv^+JlU_r-rPBbEx;t{`$rFcD9Ir zG7V%d9+m>PAiQj>5(cL+Z7euO!`;`C3;4`2N$lf;gVm&v1Ut zB;IR$f97SF#3czrkn}ey83jG@WNGM$7uw(A7p+3rwpM2Hs6}2$-jbbNY(@P5E4C=V zvXE>@<-SwNB;YtmEdw@oW|S1|PMNaB%l(8ja*z!?R^a@uT{Y2kw<)ukR8<(R6F$u| zUeRCurAqb)wozxm6JCCA9Tt*j4kzMKggA0!57xWg;FV(=xINIWri_rZu#LWbN{ccp zI1&aNEcp?ta)vbShPoeK$EGA+VNpgA#n2MR#T3Ev;Y8f6`J|W>#jON6#{1 z8(0gE0>~l%8zUNzEy3UTl@lwXOK_{AIE9n~t~gY0hR=i>f;%W=yVgrAipPn?!;+QQ zwzCyH2C)r1{(%WPcc2(^cp1H4;6Sk!M$2BMKOQLF4_V3GdRlR8-2?9B_a4$-No)RH z#oj_z>Oz09t!)5(xqc1DHgFs=V)u>lVi7;ByH#e74kNIZ9LLD+O~tu4pQ+n3_?m(0 z2cvP@z?`^xgjnHY;2Y|BO0y-lfnx&x_M@G}o3W31aIX#&TgO^>J|?7ZK@IV}C_;?) zYDwQ}x5f3xgMoX1NA!fh$*4WzX)W!gXf?0nZrz)`+ApWQ@DRtm_w!4~J;ZOW0a6r5 zhQKf6Zn%55q`6LC#ex4}4loS@z5qZZzO@k!wL0)gq6sjiFNAXcBSDBi%mLfi0$%_i zzIA`jYdIb@J_%0{k^~|CFbC)Z;07%q#{R4?R@;>o-5=fN%UyvXplFKg$^sYe7^%f^ zG+2KZPXA#v@h{;c3f`UK)$(f!jKEr{Zx*TdjNM(Q!)+BfI~eFK_HI4SO}9A;NrKDO z*cbj=BV^Q%U~#<`5mzn0aRyrBG%w4GRNpeqn4&p3rekq(6CqA|Kk0CrV;jr0zECtZ*eXH$+P5U$ zTa>j{M0QUzMUtR$C2z^7cDAD1w@A_6Z7#*0;C=jtRKi$|z#`stdeR66BIK4uk*t zj(WQs$B7qItgHQ+AN77OM~D%qj{$%CMMV^hbr-w5>}3Sf!XCmMti;K@{+<-&%T~yw zqWv=7fBxYCNLvs0_n~$NnWpk>>&?GD4cw@IHa`EdPL4D({qQ2<#~cmf&)6y^&i#9`a^=FNfyt zgLC>Afwj=i0=`WQE+b||Zp=L#+5x@>pq&Xu;FcxVE|n8cE98dt$!RYmke0OWBHquc ziQ^lt?5}LrOkR;8gw&^rsaZ9#v)jDfyLo$xg zaYNn3TaR+O%d5lXF^Cb;>a1=_3uZ8jVl&d<>>%20lax^SN)xJ!pXbDJ{(+E=_e|KJ z7Y*46ul=$FA+%fl+UnNB(k-JvOL@e?I*2Ka`z)3)~uhj2M`!du4NzL zt$t)t)7KpZDF!WaE88&(v`&A4zZZs*jwUji7&?^~Lrt2|zW=lqHXDmo_tz#)z&*f8 z8!b0N_QDMh2@Scvqc^#q$82i)s*{XBHYD4m|AfQFb5Fe4)}1EALDRCF1QD#1|I^BIAF6v5{xit3<$G;3E{*( zu#sVEBMPFf(e)v9Wdzc~bqF`siyef?+QT%msjrBKJ!Kv+A;29U6>G^hhBq=1h23_rFTheO@$L2OYq!|Z4+WW`8)45BAt7E zYR%wnQN9u0S4(T`uhs(wgpP2wcH%30b;)60{-Azm$RYcIS4C#u_{zEo#-EkCGAzM} zVF^a0 z+xYULWxbRd05&2?2-!ZZe`(r(5Xyt-owE7@&?D*1~%*_q?R zQ?-+_-Rpr@BQnd1=MUR5x0vc&k|4zQy}tbWl6g2*YtN zZdlR_R%8i)@M+mt+}T-%9f{v0#X-V6xgi|##-@{191~>0Y-5D)*Ai^p`UH+`NafD< z=5HndIz_WFvv*UmY>^48)pje#;~d+-bqI6GgEr#hgi>tg^aS1#*a@tFr68kyeK{t{ zMvvM=G;Py?RTvGYM{%^M%_R>>>B49+XU8vEamGT9B~rAKjgQ66#Lmv;Sm|bSI6)E# zf$9xj5}0Z~7q0d_|_YK1+*1|O{BWl#EBkuQfWwmt~ z6l)b#_2Vz#4q?XLKvhQUT3J_Q+7tHlRtaegVgw$|u&$e?6J64-QP;fE(m2P6ivfOo zPkHz{FhLvVrS}Ah46{kprlg02z*=}#f_FgeyNS{4J)N6k25e({%+G{e0SzI@=M_DcLxxYvzlS7^ZoqeR0N_Z6RS z!4#K;Z4?5ZL0Z!|B_}8ZBH!OTS;SRTc>nX+5&~< z>4DqpomSyJX-*u4j^r!{8#nLu6hj;j^DT9|@uH2ent&_mhQ+WJ)ff<_HHTM1a@FWH z+W*@I0q+4I3O@D_{e5D2+h-@ZBteKj3<&3(f%gCqpMU`&X89ANZCE)WNf3f8);x5q z12>uh;g%mOg5Amro5P)q8Uq3_R=WZtf?E0x{2hNb*m2)k$wPP#(!Zw|T>dm~{IeOy z2pmV%b2j|!#Bf*OJpdc;QhSQazmD;y1ueiOwKjKJPP+b8ejeOpF}bCG5Y zdxHBFyeAH8(XI8){Cf~=R0AyJ{+A>Igtg zE$%12lr-|i`%D!HfwXYXhf!>+%EJQgH=c5)RRC(Wf;f)Ti#;04K=4kGfFzj$Mz zN(iilV**wc;5#p#a*B7Fd{@Q3^H%6pptaT~9sWq^#I&A?3($mcl`~ z4Wkv7-xsy7`q#oY&^L}zta(FV3&pt%U|E3ti;lc`smcf&{RW!iAH{kG0OAbflr-*y z7Uxurm*Kw%sU))Q$QqiyCW?`Te<6@PDT72>B(I^PvLe~lVoS+}q=mC05&adOPYPwEnCZVjibca3o-)FqU1JkCIEK=FeN};bu(GVZvqoS!B-0=Nu+Xt0U_E+ zN33=NqPp2)KBPss7<<1GlYdi@mW0k|+QhhL#c=jsH=VZ!K7(VxYXIk`b?_D)Pt1m! zzIBpy@bWv~2)qV)?MK6%8MlGeL~*HaG{xFc*ra>&En}RWf91DR2b|Zw1sc~KJ0Anz zSF{^?-$RL^1$Z@oWC?ySm@;<;uP&5@bCiaj!H!2dsvYjZ`$c7IhOPY6QvJ<_0M91@ zzX2d@>)+$&GaZ>=Lah#TAD2&XKt z^|f$XHUs>Qx0LL``%%S*c>fokEb+99guq_OHueTBS)K%aJF#_IK<#7`3CYR|5f{3?qs_a)JJnc%Jd|vc zPTuW>ee_&9#qg3#5>yM0&e~VLjJ+hcImFRLA0ymL&!(NXe&mt_A;@*D-X3L>?a(X9 zh2xc#$m8RgK6r^vLLjZ2?LPe7&^6A$TmgvHgP(AHXmwVx4&10h<>Fq6+XiZP;3Yl| z&JKA(JvcQI|Id+NKC{?8G)#szVa-?ING?-k(J_v=dl@5xAxa*3KTg%L@LfP7sfU)5C_RV{{mi1I!wRt{(8EVbTHMNeu_i zgn@aqxBFg>B^V*~9`f=+jHr3=F8vs=nPcl1fo($u@_9+I=vXs$IDdl_2S(T2R+sCx z!ff|$6vQ#H;~w6uT32SbeW!%LTDT73H4nR$JbFcMcDMOrjwKi&&!Uk%W*X0(Oy`@Q z4rQt5ym<~}YhTQYR7L>f7>x=&Nb>2`e>&#(j| z;5~XC-yvSv9Hk-JRNWGm9NxotqcK+g^BFCnm2 zvBrR~uZLn-5DAEX!rJRvfAeBzmM9EMFya(2AXottLg5Swh#Fti&~0_AU@`9=2a&RV#XVG3T^{E zFd(c4CInL9`Cq?k!E3(px-Gh}Pfw@Hh>$wGs3l~C3qR>F8hFp`s)`q>&6t_zG6nY~ zJwjmHgw$Dggy&sIW+`otE7)ILZdQg5&uW^ekOvCHG2=lIuhXgryEWmKf+ZM%?LjW1 zlC{{fp%v?AW=kam@@n8{U!MQ5r$QEJHcI{q5%Vp**ixq;iY2&Qcw3m~0TTk8hzCU9 z*p_1LFI#r4+D$2Pcte;IU_v0@ujnwE5S#fiqTAB)%uZZV@aV({T!*mdjEWVkQmA#=lP$Qur!3ieR;%FV2U82+dPtC?AYVhQ#H+k>-FCVJj0y*G3FewgC+!1adv z8|)_L_u#Y7hOmSk?#z(y!}Dz5*2bf71^0XzkzZ{QPyZIll9yMM5LgS_gKtG`cJPmN zF3{KsvC{a!_V8$ibNWxb#F8e2W#pPkHgH|(r}^^uvd}iy!=VLBZGXZo4sNC1L;sNw zSWC81ukH`twr&+_?$=40888CRN^tLPUnx<`sxE6{{37)$9ETivs#;&{8}^zW4J*O0 z@3{T3J-AbSHJu;aoy(*3-K9Cv^aQj`MtjAuJwm~=E6hHY(PFCYTqWMtmf^CnjaV~3 zuFvYE7*=Vs&o&2V(dgxJ^`Dq134yib$U7Fhh{(?EjN=YON?u`vzLzi85A2}m4{GhP zaU2m%7ER&$w{0W@*1|Cn(&AGkW$1$labv$L%V`6vJ92x^n~?*Ip{=#QLjn_11{mSR zWB6MKzi2bzxAy$lMDf;c7wy&d-TA@6#-ld=DF~CI_xar?X!^9 zxv*|;mnh1w+Qlb?50(&E>kk7$#US84fK}fpU_j^zOb8jZuPIo95q}sEPOJmo13*Lo z148?gFN~}HkFKi#uj**pi#wz^6bTR@K+quJ9@!wJ6b~*b4enN4b8#uIfkJUB?&RKk z&IZ@wT0S5JN`V3eitGRG$!VGG^ZY!|_xJvpdC#oOnKQGqJA0+FMJW`4d*jjC;B8DS z10w%8O*B}ML9Ci{#&jwmu-f6MZxHax3JB~>WmH5^`h?1=?c0eA?T*;pW=>HMwC8k0 z@E!a*ji@xKgvj_Y4Ug$7pS!s-yE;f2QHn-Qz_A%cYTZ`P?k^O-*YifuE??X7{ zqFRD`xKT5_ca^eTx$s1e=qS})RTJ&54aJA#TkUQ+{x&HW?x05< zWUSVP{jGZ|q95b1TI+qMR#t4gSd3E&Mc~$P zXYFz)=?5R{9y5P9e7-NYaNTVk(x z@`FjAOWzNwW3Y)o6%!Lmd?8lq$v8z&E-H_)j8)T#;Uz-Er|B6vrBDRb9_;8EHdqYV zds&NqIYx=Rk}50AT!o4VmJ-7;ftm@8cZO?mr;97m9Yv_``Lc~8#O&zfTGh@W3W9Q} zu|Z?hOgKDmsBiPfi58_$1RXbgYf&>{MvfU;|ItGg1m&V}31c-;Ghyae(f;et3K*0^ z5p>iU6aH9{E2f^-et<_oP%i2dVb{yGk>btdjQ+1nq%{+6gQn4G`ti)eO8XQjp- zkg=+z8tI$%RTE2U7w5ss3U4P}W|KJ}rMDAlD3W9Q}Hj$;h=x^|_ zhOiE(2+DPE52`G@e1jbHcG%rgZ&C+V6-HUS(IK2tD1ur(+^949FaIxZtBKb^3wm_=aHN?dosto#E6%kqTlmC3inj+s~6+yYEJjS*cPiLRK zJD8V`YhkZL&4i4ooltJ@eq-p!Z1#%3x*E&6pETOP%4+Ys-_5A>=@;ljr7j~y&n_9v zUW1DnvN}Q8w1q-Yt-x@q6L_12pn8Duq_(Umu)veB3G3wS(bl>m#qU{o)iPadS!JPH z4Za*z7Ytct0hxwXIEVfp#Qr-A?d0jY@dbfdwzs{kzmQ@NYm(atzJ%YAg{$DwJtMV8 z{ykxN)&033#?E@nD`}$&F_w@W;qv7_lHdy)XJ6LBA zQK68?Q2X%}vX*yJUw70MZEt4b;YJq)LAmINU=8_F zby03v0sed6ns(oh`E74lnBg_I8!2&SZS#gQ#(YfsF8}9YmK= zsE^yfxlR$3YuN$Vt7lkAeK-$@=B2ud1K(dZj~Cn+pcDl`Mg->vLwktht&W=q8|Kg` zf{q(*;k4P@PCCop3o@o2?=2qh*kk5tm&u|OilAeNdKn!?il^B!nvE+LQM4gg*34j$ zJ6X#RMc*JJ*+@|--6NxV^Aie!YNAuyf-S0qvqor@^;>UoY2NeY68jK1diKrCf zJ$MrHaX&p5_nwFFVW~>lltK~ed~_dMSCqVzhYt?_*`f%_|e@Y6?p9F|5(xN$I^&isao-%lp8&?AGC$^NwA_hGKsy@n(?@*D+2Vn zl#8Nq=61?sGkf75?25BnaDDt+>vckN zlTz?IH@^tnTHFRFt3FdGA}cC6%tS?pjG13ytY#K}Wd1#1g}LuC)_n+qaxL5b)?ztP z>Gm#zjI0?BnbBv8@sG`mb4sCzx_#eS-W*+wzTZj2z9Re0D)&n9bZ-lDN}-4dRB}i_ zMF-SuK&ztq^frslZOd!qxM@-Z($~Fzb(k=e9%@=4aMz_JF%UwNY_qW07GR^;n;#!+3is?^4OrnouH{OZ#83W9Rcw;AgUlj>L{#A`Q9Ax$XM=*Vb*`zPFjds7ptP|Ya>F%hN1sK z5Uy+|@ubN5MKd&)GU{#IZ4c?1Q=EHTl`9m2P+OI%{Z&0Gry+jt8>Wmd9nshAWhIA6 zmAx2s#-7hTq96EE7q?c0afL$WKrCNaM64gYiG0@$`zuQf|*li~~jN+6FH?iC74Ax#B;;Xg{du#V%?KSQm zWTdxF+iBAtwTn({q9O>FD&xeNrpDEatp-13}}meBV@c?;Nz(P>1j zs^{%8#|;Ica1nXP+T^Qij~-n_1T`_a(nF%VRC}=N{?C1$22U%Bk-00W2%?EwZP?c3W92k;uEpxFY1a( zXI{l8yY;2&Ez#%FH<q{#FhC^{<&kf~@3# ziVmpkU{C~YE%q$VUuzehU4utO<331&P`F5}j?*wJSJ}NoYx48muqTyLE~Apeh;-QR zHPfI^LjCrwtLzKuYx1kpfsl0>0@!a;7++z6P@cqMqSxAMN7dxRie*v}L>`SMvEH6% zxt&>j#S2wc5tNIr8sh7`YKwVs8yB&qzu+`#RIGE0CrR}gjz7Zaj<3JMtiPg$@SM!T z8KF>wYJJvDTWKyyQB$;ji25J&J8>>KDh_8hP!YkPPr@5ztTJP^)DSVHvvB%_T!AVJ zEZC0ddTRQAd>`-Bm1dm`HAToR?39&N7S^HKLg8HoBQg}(Y(dxxGkMjTVr?4qgCGi8)>&yGyEdS!7*~6-)^N}zI~4U7)}cPbDKn4R_s9b4#xc}q zxL(*~ccxosWPJuLkBNw-e6;;##1OtE^IsN4;GQ^Z8*Uj3{ZL3nvxduaiQNsW@jQt$ zY+08w@K4MXXQ)L0w7Legp(2VWko9#@w`tr3Ie=xQlk}^{7iR|;j zaH=eL<5uCUyP=?2onKpt)m8SH&yxAgKNqI7-*niy>bq}W8nVg)JZ=w5c%z_^gZ$V^ z_=ec#j^dWdq9B9y-NiOzm4hIZC$Y9>W3k|BBlA$#v|K^Rx(qC67mIqUps`-ksWPeh=inO-Km*7;D|7HGTD7&m?roG-%E12lY?F&}o_e7=w}eX> z1va{K9no}lI&M^(uZ|Bv;5JcIh`pnGcV>eO?~bp;n9wYIN~=XGf^sRNTXwKVl%Mz| zA69XNsq~z1CCpuDCF4CnwZ_By``F{%oFpzY%KoBnVL^|9IYS} zF4`w{zKJe2zCL8W{tniMv_$FcNodc6P=kG$AFa9-87}NKznX;xXH^k|OYO&lLuJLQ zdMC`v_uw-uK?Q_NsLcCEh^cT9G%|rF8j32HCYoWDQgKGxOWqIM2TL?D>U}M-2KSQf zd7V*3P%b(*Y{;$y_D?I@@LhYhDDy#ErC2*wujfU(!J{tx%&-ND?oux0Enw$YG~#nA zEw!Vf-OfvW)3PJ%ecMl&!QS#Kb-2)&}ESBcWayjPBj|@A&ym9Rln2 zy;dj`@euV4BC+rF_*SVUH)31y1urU^y?T9A5R?n|ty?i)V3jIb%4oLHw@(Gs!$d>%W^)b6}V zC0qTnJRfJpXxR74LroSlz*_vE8?pfS&Bn}WVK4Z;4G;S1iK=}BL1z=Tgl(`hPEO9( zJguYXE-N?Qig^`du&O20C$SuB*V{igPRT2LQHN7qq6kLhq5Ajr*VfGQoq6sN7fhvx zwC(?EXEoY@-T1dlp&ylUrM7SHZN_M z9MRxaQ3I;MsxOp2!1ium&$xldGsw{?5|ci%ypGp^8r(tf}mWAF0g_n z!p-f;-e|x%^`#9$B)yRrK#@qg?8;id|9raer5K{&Rd| zbL)@aC%BUMC!pjX=X|GKYt{`S!tzaeAY+;<)Uq-Q&$Va6t$G`q*o_(lfNv>E? zVmWDRk*Urz)<~BFw^a7*ujnqFf3;PIHkUGYKIv@4y&TRdg(CXqh_Dh@wlSVfk#pWX zY`$6GeRj*7IY2>BF11x3b}ux4OuO2u8P#9uIYk5~uVk@)t&A&?QpUy0kIl)c=i9~B zHd7Fki;f$1e};Fno39jhih`Xvi#v~77hY6kYvHj(_)#mYp6<<(&rGUkkh2o17(m9n z`^W6cyruo;^Nw7h5JXZvgLJD<#Q=y7sAn)C%e}yZ_bs?WA&8`U2HpxdVGP9T`_X}f z(rHBt(UQx01}vd-QB*51BV|1UcDi!bXytCSx@*lGf~%IG(2H~P+G_~%x!IE z`n!x+5MP0N?O)LLZC zW>?XS)i#A$@Qfk4@5rnms0>9mi;O;N7muhf_SL#+Qq7=xrE1C5@^O0F2fOX}nfq|c z#mtcwJ6zaU_I*i{Egoz!8`X5v;y2r|B$Ju1%0t`VDn>;RE>*_MX8X;Z!^6a#28Fpo zAqZJ(K-L_<$y2FUU9OtxYln-V-?J(R%0=IQ><@1>)9M?#+g>!QH&@z@S_3Q^Yp*Hc zi&Xj1Vl7c~AifA>{PM%Jz>UO{_Lf=QRRrZCEyV7fvE$5aJqn3ejWw=}2}Nv-LzIf0 zvX5kpvtq5!d~~#|h)+>SMG!99C!DH#lxWRgcEa9Lz8jZy68>#F(L}W$RZaz2d(Efz zrk~nzg+dWTE3t>(9BOX5S4_0JSVcupF496&ntJrRxhoJU(zSYN;+FK!JtPQ4kJ;RI z6~)EB=4r>)V11WFrm{K#BGOf;Jz%PS`&?8f_(sp++r9lOPALk)sg3fFE!k1Dka#rk zf!6pQ*4wFfPq`FN|Mr7SV(rGXp8sWO#+A5+BIvlWnu9ZmW|N9(1ET+fpj;#hq-s$A6f}Kh~8Mt?C zkb+RSs66)LSL^J_tyXFC4);^vLF$Dmty+3Fv)C42gMXQPwX#w~*8`HO6JVF0al^p* z5ML%yq;5?;j@ko;iumqqCehqelecUQgse^=s}!70X;OspB=)=$ z)zlO-f^w-g@rR36`a4mM<%QL8G^%)BCU0o8{7!i!{$Ih~nw~OfL{& z8*b!o|1vD6kw0g5Z=(6F{8Zl!DP!(c4@FQedRGokFGpBf9mv?(b-Jcd$bBsH zlpA&OwJmDpm>0`yepl40SS*Vzd%NMz4om(|{+54JWV1F6GU$EZ$MVU$4rvrYxz?0U z={$*_J%=ydBGKRa<=rU0Gj5_qDHNf!mL)rI(DUX)EKir^gLZ}7j81P%r?V;RvB-a3 zF8}Y0-V1cu_RF7&+s)F{D=L4#$x=d@O`I$0mCSPmqg#GoMy+IMh`I4~HzVJkLIxX{ z+lar48X14DF=E${Q`a zNgu9Tt786RkkR#Fb{}?go9=FI3;WYdcXyjru||4xz$H9s&VG#5)-9<6lV4)aclQra z9i<~p`-Gdbehc?!g^Y97JdNt;7ZVp4VUM~Qt7aCqSW|C`3VoZph+#M7PP`cD+SP#-s(vUzTmL$9QyI?!asaKm~MrZ01&2o z#yt?%In?|aT9UStJU^IobZTFAAnw%Nq|x_)z8_S3u%~Eia;w735&R=VW#fl^0LAj__$~RB`^YS%IzpF$k6!G`Y*^Z0{QOK{l z|Gd1*i`Ba*f^tzyBy%hu;@_j^P5!gPzQR~ycIT)XRs#WCDl zDoxm3!@Zf(ghe&n`@>9F(ehJ0uHE%f1m%+ZUEQ0^AOm*S@7i6zLLtwE-8I~s%z%L1 zHC($ZZLI0qU1@s_*Y28%Y-x7`uHE%h1m%Ktb)E#f3mLGxhHG~XN}&j)wbJhTT)XRs z-8I_ogI(GkW2NvN9q%V(mW9p!@~98*uHeIcJ1trE7OhH@TV*m2Jg`JQ(lpiut*GiZ`WP|aXw+Yk0R)*Jhd_K-Y5N} zEd`=m!Zg1^Aij z<&xfoe3H~{tTQZ}XdQ=_u@G8MDHNf!mW4deqhErItt)gttr|hAkx;Acs;=v0Nbf>Q zms&5q3;A1eNMBL@mRgS;jrac69>J5DIkSpJs{+%C*0hGPW7|EhZTHi6jlP3aLmk_0 zxVByKKPUn=*s&|H?HDWAcE4-e{q$Lsi)#Mop2N0FOYK-0X{#s#R@;#Q+YT8?{~X&c zzXtyzC>OPMsEPG-uzwshF+<@9AN7#vTdR6YfiGtp%}$Quxt@(z{3wc$w$RlQ8#@aw zPOADRWc=9j7-|oG_Pi(;(Mrsq{Pzin?qfDrq!fxE{eX-+F$a8;@P5=yc}ZGoM;oLL zQ!dqBt&W@Jc@7!(`!%f^5?$DAc@zG}7~P^C05sHe>*AnQbFj!9pj8< z=in99t7j>G!s))oNqh$*KTHAQiharXa^~CdYgPJ%q+iZu>$e(%Ae;Sq1ZOS#twzSk*2>>zk# zPj@CaD1{=VCniT%zGbkxR~9=SS(#G9{1idCq@GEHeB(ar?%t(0D^dzYNKZ^6k02Q zM&325CCvKL=ynfU(q@f?I>Hgm^A5x{!o=7 z6fR{x=G}Yk>xh1g$#-3&(kViIG2M3%Gx#k2YP|d!G}{zal_Dq??cZl@kC{<-H>FU7 z{9?NAAY>T3(tGYfM*8NbJgk0hYcJ+J;U4to#lpZ${9YD=aUqceIaB0Aga1N`5+niY888uDh+md_*2eA20PP z!2{pW%BtJDAmLAj`n`K*cZ7mdkiTthSzV`bcay7wbwOfY80 zQ-s1rN19El@|*7>-l&QZem~U=ilA#XGLO^N(W{?w+=!Kz6P}-E5$QH zQ4nMm54Wql|2;yk^>y`U(pc_?Rd+}oorsJTnP+AG*$>O}diuRV&zE;Wg^14x%B8+h zUk0V|9D;>wS0s&!pl>R9gBdG+zJ~LDjI7kFs<-0;YcpEK#x=C)8?4IMI5C;?{aE|B zoQEP5E}}8GC(f70Bj4K2ua>Ja2$#3`&(;wsdv-c#`;EzWeKH=58@xbMC1|FQwGLN6BD9?;pG4rrC#+p=4oUp)>)=ugjJQ>Ki{!9sE z6zsaj9ed8ca0~mzk!N*IQ~|MXPa8em+gQ;#^$`z6P%fOV!wxs+bR7_vwrBI7L91r` zYAP~lt8hy*T9vX=(%sA@GJh2hZ5P{Hh3us=a2gC;&S^J`_K&eajo-z;1ftO4Sf%F_ zfpct5&vC*Ht%{g9GtlvFtSI&4wm{Lbq#L-YT$HB6P#d2-**v;Bn;1yIFB!2)~{B3_xtiom2V@ z;zj3-RVjjUQF)B*`MAk<2R-lGX1R}2C_-&jxy0gr9}pFaZuZb|$Gz81tDM`ew>ZDc zC*1`*>&XOZcLnQyb1y~U-fM|)xM*t`YccKqc8Mq*o?@p$AqYAOSkrHxI^h2hE81<} zt7r+;B|4kfk#eq)(Q)Z0F>Kpj12t065~oIrg)=RtTjk_GGq}#|WHs+MN`zM1Z&8FY zZnNc+B164-@?bvh{XO3!^(wf@hN@IEP&L9CD^zZ=P`||dA?5r+sOSPjvyn}mvFh;0 z?FfpXTvQ(7!L2`P6VdaP-#peRg(6rwDQ`|?_VG)|NR#Qb-^5!xJAG(?A}Cj+(vKZ2 zhV#y&u4?b2s+;p)7n44YRX95;u+@fTh%_x6l$5zO=kIc5kFn@11Np?K@mhwAb4~Be z0$6SQ5Max?8*(-!+KGe+8vCVQ59BEpe-}vUn`YAIQiLj_-HRUFYP8<>ZvJ7DrG~}X zyClGTGmM09ux>H8rNutZHmGdIYNhGUub%!|@8A2h(khDh^{>263v1M$h<<$drZ?ZR zu$8}9LBE2aT(pI-)W65@0VQI!9t)qF^trT!Y(bF8;!0Yqz!u18wxmklP8g^*kM(fp z1{WYwiKhHS>)HMj?KAVl1(~1?6)Ps}gXR;2BAXTcCYpz5HMA4hjY|=fOKsKr8*RCF zUpnhZ)I0N^wWFkH6dB{Biui`|B$nG~$~$czr@zaQMU^3Q%q~LhN9}4&`IT%9{Id(F z2+F1OiFGmC^RJd9YN6BrGEuW1TH;jm$C!MUp|*B-&7OSswS9hHu0slfa^ExO)JZB1tAn`%cJpN&`3YneN?yKrE^^lyBcWz%x0a zt4S#oQDJz98Iu}!fJWy7Vt&w29?~s?-h56^lTs*xt{P$8r%rEvezaffn9Hy9oQ||Q zR!!>n;qP`%)3V;&r64GmGH$HV^4|Pp`=6|Bd3TwVLJ?<%z!F{Q6kr_-q90#%8^lBA z&(|BrPEin)OZG{6GD-I8*ApZ7%M1Uj+ILhTGZZ;G))tlNUJlSvY0PwMaq1L}eflRy z@D4vruKKV`A(K)lLX~moW-PCF=Bht5+dI8~juIwIku|_tUhpkF9cmUGn{{PiKsKGq zMtFW9mfuJb;XlwTyFn3@t7%$1sR3+oqXwuDJ8D`iPd;S7GdEi&7|JQJPS*R*vr0mD}@yc=2KYpE^9k+W2_3eg0K`GYpiN z2mLIT3Vz$2Y8ES3-EuX?lFvRE@$AY-wLDqzt;gOPnEH_@d$qX z*jIsCv0(~=a;Y*dbRELeu1%>|X**a!C|sn4xF30TEYCLnj&Ik&o(7#YI=Xaja6(~9 zEMHT3tbSpNilAJm4`;gd=sc)?dpDNvn!n25warbPQYb>MUrJ3(TIDPr7t0HtU##6( z*U6#?$|cuGB|_#bV8<3CdK^|qtGch9f}mWev1hu~_khTDX$a3=JdJg6!swD0fQltK}-Pq@Kl55DKC7yBFcd#@lUm-je) ziMaj&)_N~w95@uibJhMzfAIFXtx(8Vc?;pYdr-I7&P_mcDbS2J7`e&c^?W8l5tOTN z_O#~4tlh2L+l~V9yRSaK(&`uOWsBSjLg6Z#++_FO2Ux}{K&+1{#oLW*66jvR6s2!p zkXa;aWy=&cJNzf&^r|>P@XQL%^_TN^{1=F*lXdvq3%PuUw0y$NxLfeAEJmKI$Ybr3 z8~pP9a)J6Q!vy70&_o_)E79ap{xo{Exg`Z{2}P)_is&4}o193k4es&M#tCU?pL3>K znRBWOnDe8Jcr{w+na3yPpz#D7H3A0=2dEk0qe70h5&kjbV`LIwWV%kxQ^mqt`*27 zAcjLc1;ps@Pn+QrzScXX?k<=@`HYb9lYG+)o;C{!#$7e0mGE`QKRW@Xw*kbizvq}QAIEFyvJF&ZD9rki1HqOv;UBt+LSubMA8pBZfeh~ z-`-`WK0iT=tJghAGTQ_LAr^YwP! z1}O;2CHo{TT#_cn|5C{8|M#Q#Ek{QP_HcmCqSIJgJA~Q^QGIo`?0>rk^v51i84dj_ z<7lnIX6dMes+SG`K`0cV$_VNHQ4hbI=)ZC!R>(*t0TD}{oF!}-smO>0UaU=JBmXfd zr}2B<>i&`ERfNLTv4KCbzGY-sJaTb(;|iMaVsVQWIs?AN8*gsrbH}t7&m6f^sEAD!4fV zyRC3eI7@pg&rj8~^FOKxh0EL?V6Wfk340}C#xH&Cn6NDVWaoy6MuU=DET(Mb2eQi0 z5RWAzmKa&#C8B!(#$c#RRrZyWH3Z3yGq>lM|&{mghE@D6sfS4 zh%g{y^p7R&WGijolOC9Jf}mVVYgxsvCGAt4I#?Uij8Ixd5$q@;6+|qNYl}dJfk>ss zXwCSvevpEoT=-sDaz2v2oO$w`up>XM_V@mXuX6|@m2rmxkzeAw-F1%TL@Y&e+kH<> z2f~h6CoA}{4nNv_uuzYZIqAQUd8ALGguwS#Z;Lu+bi>3REF1yR2uDCb`(|SSk4J|?UtXSeWT}f6qG^{v`?r&)A+sp{ifyq(1f-M zLgA8;ii}uJz&m55?B{mZEMMytFTq=)6f#z9HzE~8EQm>fXoo6R#{NzI19_UM2*MSF zNM#)&mSWk{0+DQBZn3iY8LjE+`U*nfN{dKEMl5BL12G7Z%A1Kz0!yMw2^pzKyM)Na ziBz13fT#Iop-Gas^5N%K+YH&YBm#Dd60 zMl4Qyo&ORa3YmxL@WzW0Ff+3eG%@tF0%lF zQs_Oi%9Gfb!%aou=(+y+EiwxksmO>0k%Wa+dB}4z0v3G|Zhfm0ExMknqGj%uT(A^5 zP}R-JK`03NB*qSH>>!$@=p88h_P$LKl*=n4l>{eSgMMVZ79+m&c(sXm7b%4zSRMG- z^IKZ%(`+DOUiT0wxBu)*m~>b{P%bA@Ny<6_aV2ASac^ENeQ~qXwn8D#m63{k(-4yY zfy|F^Gd~J~a!GqD5lL1LSu){f$!r;^ND3mC0J2%Ajp}5{oG3#6U4G-8ESZ>?lqFMS zD9V=Ficn=B$0FPuO91%~SRg0I;*pVxn_~%3*-nl{xH%S? zG5HrkxsVI7-5d*cE+fYx+#HL{%KVFUt#xuN!p*TLt)d9zCgh#>GRFcfL5@YZITi&$xsoCkXCE05$gv1F$6_MK zg6fn`j>SNx0hL3Y9E*WG#phb1GRGp^9E*aWT&fJ@ScIEnQ4o}iw$RD3*lv!+l#z<` z$l!-6EkPy)e|K^$=m&Bv!p*UmltNoY`{d+Ugqveg5R?mf5!=nNKn8Lw!p*Um3Wbc7 z6R9NSSb%6>mLXzEyX`0t4}JB;p(ej*4_o9`5DHgW_}ED~ z79fyg5pIr!%Sc7qB}6VJG8;*8g7=w0Vgn$iBT{KMAeV2DmQU_saXc1y;0CfM|2|id zCvz;q&9QLGrJ#vCC&wb(91Eu{p$N5A$gv1F$AT;N)0@n`2Sx)>1Cw zg`?-lu?RQE!f8ERDo;fq$0FPui-MqBNs)?^V}T6hScIEn;mEOAQg@viB8XJn9E&p_ z^6wY{AY`QC=2*BBsr*AB2ofQgPL4&mITo%^2m<*JtkpO<79fyg5pIqJHH1D>Xw?Yi zNixSG+#Cy+k&2sRF|m@4J~=rS)O7m%Bqzrr+#Cx>j>VD@3vw(ff;`E|vDj{oML|$` z$fTgc1|k-@Crjp7Y&XZk6^im)thOZOSb#u|#ddQnDuNNN72Pd2#{vX$EVi3t;mENN z%4dX(ROFi`ccVEu7Te9SCKT;JYQyB9eL{%KXb5i*R!+ zT%iyI)iEc>BHSE{f>5{=y+V$~c5^ITsj5O`D6N$_7Te9SCcC$J;7VNjAGLU1j-5d+26pBz~AjcAL zb1WP=7LS`_F|po`o#jrB#iX*G9E;`VSQLc9)vU3wEDA#5%C^zx=2$RR$gu?691BN|g$q#O$n$g!AijzvXKE=2}%ET)@dL6x-6(rK%bA{8gc0vX7$m~M_m zK~OHGwKB(Ix;Yl5RTP2jiQ(p0AOkrT)6KCc2+D=;6}%)T#{vX$ET)@d!B?%X;pSLO zWEu=N$6{iY8we-I0t9j_rki6?5R^-mfgFqJ=2#Sj!lm>BITq8+v6wPak?n;as(vi-J(NT4M)HQjP^OkYh3391AM&6ABqCL@pQija2U_Ovz;ckwFJCO=V&hD@^PYgH5;>?F^RnmMQ$HLtl zi;P&D_B#J1h@|#AnH11@R3tC8VYk2d%TVRq1a_SLD?>d!(7Ih&k*maxK$k8a<#rWX zOOf8w0#AQ$H8FcvIcxZbVqA&INK~XmWGvYq)kNOTX+3?47FQ4o7r8eDl_~zGiR-BX z+T^>Xm3UA=keZOFvpvHQHP4On4bBv%Ae1_gGk7l?5n2SU4uE7F^5y%h2A-e%3sw(#f>>Rj9$AUIi*m9TI*#q@`JB`DeCWm zosE=>)`Wx}JMyIE!*{T5abe}k=IeG?Z55qC{Ty|70_#A+pXs0f8ik#Ta|AQ79N2Oj-7*`zla4GR>q zLvicE^M^GJx>CqkpG*V9v}JAd#eEhj2+BoQBXMVO!~UY<{`kGe!aUqlsOpjTMD*rXJSpp`ISeQNd>OW$?z)yB;TR0i!6MWcSn zww~fem2;lBEC)e}JQDuQy!ypik^qA~PiRmo<;D40EP(aOZ> zZBVr8kX+G`h$K5%BSVbn+@`$VX3Z;;A}E(CBjizxD0C#q-)-b`1)*@!+o#yk7bC=k z26wg4u>5wT#>gmy;`Z#GV*>D>ot8L}gp$EZJ7TEl9C5B{p6Q*Gd=$-KDQMQB-3SqF z#rYddD5X@`pz`E;vg~=%PMFC3v7+N|Y5j|5mRBmC$klVnB`tK}j98(6T^YZp;5_3W zSZ~jrr9_qa>pNMLLJ_KrZ`Z|&#gFc5TlYpO2+BoUh_jaMJ!06mI|FAsl@;tLR=Elz z?r4ep{Hc_-Q}q^a@3_>joSU1w;s$5z)BjLR98D-^je*5h^8F;^u4Mb!yrRX0-m-uv z@ve$cxab}PW?wBWYPYtuo%b|luYrPSidM3MI(vdvvj!={#KppWeLN2PGU&4?7wsP_ z7|q3jHKVnr8L^X`QYeCq0+@A!Ray?PbptOhSGrzJDDz!HX;J#{{ z{@xWSsvgc^{0WOqDHNgB{v3rJ98azE{vEK`l#8v$N;>NLvZmYrQ~hH4k!s@k#FD;S z->9vkGpIa?y>AgEv{yN`MJ=tG zd4th&wj)M-A2dx%7490#I(Cr2J$IJ8@6L-`>>fU>Y2|~Z9tw-C z?p0gXZ;@SbZA-m2EH*_bTy&=!3k_dt*O?c+w;L=reJ(7t^X-#%5*FIZ4NJWX78_@N z7B99B`sVAAu-KGB5wwaVYPStsYI`U4_Kk(brZQ*?DVj0gHwWy(h0l5ht?nrl3K<19 zbEf6o$ahihJ^%ah0XtKxl3FM%wt^sBa=lDyrL>cB*Fq+-phQq$Ei5(**@{(Je1~v< zAF3f*ZcRvMf0;zcIl_(UYhKww8!GChVX-NKd~0o0Mttk%_V6*q{jo1qgu+Eyh`NL2 z^PAtl`CXd}i_N|tqqAbka4%WtKReW&TrJ)Aj6D-eJDI`PPF2k`T;1zTx!hHXBs6P2 zp_Dngf1JN1EVe=+@?;z>d!Cd5w5OG~rgYBjuL_GzYk$%jjVxkn)x;N-jm{ZhvDxSi zos3hb>&E{s_i_>nMW`|&@#>%`L|AOcr{=CtEs~-I_bdrH&EdofcwLh$D|~A1`qTOPvuG+wrNn>r)F#p$J-64`+CTv-9IO8U`91Y$PZbo4gTgK;;cKn zIr5U;DEQRe^{JIs(HT^p#I9Ay%9m#g)kYR=tjeIhCGxP&fb;XGavaiw&%_8?Wlw2| zf`Et2T@TrYZ-^UDR?B-vEqIxx>mmQ=R3kiO?s~`y0v__eXCLXANXJ9wu7_;X=fd8a zaz3ODgCA_V9x~?R^y2<}x#*=QE4jp`6p9#vTO_?Wg`F_98W2a8_2oO#v%&D3(JIHMM%^U%)ZF!{4N9R1RR(-&?)uaUf^yLo zIzBabeQFNRGRac6gvCCERWEsy1m0fwkB+5=Pi;6pHFte#uB`8n6&6@%aJs8I(x>LG zPpu#nF1qFa zLpEIxnZrV(_NL<@oA5FX*F*kKrU4$Z>3YZtLdi$aJcaa-P1i%_^trIm&X-JDJ-LSA zddQ~ZA)Bs;%qfK;Xf0mHLpEIxS&>2eMA43iY`PvYS14o@;2|5Xhm2OiLpEIxSw#>o z*juMh(&{-LGIu>>jMY}026Q}Rr4BjyiUI)-*>pW*1wpw~8Ss!z*F#ni3KwainEHQTQs5=c$gF8&46G zOYO(61@ha0a(A@`FI9xXrDXL>R-b0S|1F!oG!r7o#q)Gl`IsIgRvB!=E`4UR`tUAS z7%cdv&MF<#y+fAbJ@={uriT zeD|G-pj;!ujY$uV>fQn~fVf>Nl}I+bpr_dE)`C$AMWi-Shqb=pefk3szt74p>JG`K zXC9369~42k>NPeZ`yAB0!Q+6a_cV_4&|FYKg zjn}vF`%HJwo+W4XS`YD?)vMFr+VCNr{%Z1n5R~g~F03RR)4SeU3q+^lcdf@6&-o6< zj8bJ#t~KB42@C2O-ZN`}h&WQpUOtrRHNJ%=QVK=*=j%b!kLl%ht^(rvj#l=9GIM?V ziw;u}l&jV*J!WKmBj()-AYP80ZXchQO|N=$AZL_95x$#xaLHpj>yG_dY|ofg_T#Gg zeYbmluOcYd_BVRay?Vy7(zr*Ch5qk=okmZgCm)YH!zhI!Hf1&XVysxDI3QXTxNM)w z268+v5(jUfT;|hf!BA-q-BB$XUyc`b1q?S#^ z#Cub;h3_&e2!*TiETd~;LxcTQ8VJ4LcOt%YA-(bWHzp$#itsjyGlEMU*IC=FK+I~@ zUc?@$rX3AKbuogVTnW<_8i{8iqjhE=zT4PS^jv*kyI1glNhuVuY`{_@I25|u^JV~A z653n5$&+7Oe+)Gg$g>o#ddrN+@zAU4SAe*Ef1qf8Z=Y7+tLY{q6pH98zbDTjqxyUx za&;XfJ~ZyFMO>PqASl#Z^(Yk1mZ)?2+`r@b?xTxQYNKPM6o~D8pl6DM)_Po zoL)6TjF|DGwy;7`1wpyeo9m32-yq{rHXy#o`C!k$z1pi4?F>qxh?URR89C*9o-72l zFVoJ66-%n0)w-_jt{^B^>-y`B)Ee|^-TFPKHjSPAm7bl~{z~}Hq7;hAiGE=Jn9j^x zI(Ga*Mw;+lTG=_>6$IrBILO3e1d*_Ezf_9 zTscBau6jqiWE52plq)EDwGs0WGJco|#Lg!Jg}tq-R^!X*HlLE?;tX#|jMev9F=h<9 zd-(Q8E&Tz%ilAH*7aAKcpdZ6B1JN*VjCi**vsNhfmCXpnOArZpXBa{0Awz@%(Qa-# zarF7`T4IK03W9QZU(YlmtD+yx%K(vcRU?t-bvIv$7TE=*Py`Euy&8(K@-_zI`G=-r zOpWUL;18%%M4v^t67Ehgf(+=@V%SA?Ccc`8Ni3-iZB<+-6oOzw2O2XApj8LD0?{{v zDMHg_*4vFPB@_xpC|*X}LFL4+&%V&s4yvjmC>QlnSV)%$BizoTZ}7p(pq>TwOYY0`f;uO2fM?|pcIPO+&oaOOFiS>6X|8#eq7e%SI%kq%fZW_2+H;M zyg&jhoY$6K#^47H%-=@N*;8OIybMaA2>*`2)|43CN-KdladEo2J*tX+^(?#$ilAHr zZU!Rz9MvPcNH1e<_Z0k9mGz#(+wgVXQW3W`AJ@HCkolQcz)HB;(1@IjuYP00N=Vhn zNN6Fy&gI^&HfMAg@3|TVzl1)E%9!yku z_|`^@L$z$YITP^}t~bz%EDP;>+tu=poM0uUmAYFW{dhYoFV9y(*UMytmqDLJ$7fy} zE3qyRx1^WR^h9<(ZSFMRH&KmL1mzmh1ld?Q>e7>$KA=2*bE>{ReFVG=N}&kSLd-{o z()`lb8MIpKbQM9ln)bG0+QXB{(g!lGGXuA)7SuDZ3FC}XD1wd%OIfZrAG)rG_WKII znOI|))uz- zXIbngJSn6M5Xrxe;u$WKteUc4HU+^5mp30g$}+G%KT1y~>`XfzTQG&*wd7M%p%8@H zs-H8(@Zb3t+O3VR6a?i;C>3Y*oeUZ0r6&`!zbB8(no^&)eZNU56hTJ;6_oR}w|gwU z9?^31P{D#)>M?IHCST%9Nn=hLy|UqBO4(QYR?xq0i!2#MP_9`ybuTPK#2wp-ScA!<6ztj#-LOzO8D8hTc>QHInK1#%sgOhxP zsyveS52y&r^<<8JCj9mR_a&mk^M=N*?V0q{>w%yYil~q~Fcvc6-pYPVd4I ztFPXWVJd=hE!q`GJkroumTn~wg9c7F%e5+@_e(_mD@vh=h?{|!i%0d~@8vo}!2_$! zOWCq|>Q=@&14U4-pWg-|M?l*P$#sStSr3^l59QNW*T6ahrBKAetXA-JShyl`o#Ehw zOJ>^L@t)KDx~d4u^*X<$cdu_mE|lvG3HM)^)vn~x*GxdZmQpBUTtzFPCoJC$xhr?q z@5%YxHK(iQO%|;pC|4@eN<4=+DrhPYQAe`#=a;hSj~Zc}fl?@9TVpE${*^c9I3TnE zdHMBwxwYSmW1WE_C|9>O77K4=c%ONJ2x(M``*)SspH(siqZEqR*V{_?9+v2aTxTfK zp*(+hP1EwsjZhJktL;GRB-TsVldeFFVJ1KOG_&4k8oUfjp$N}7%PV7?e$w~(t5S77 z<=_p^tYgJg1mW`To?rz_fA_KUeZo>l@r2{4^)$z_357xs3F%?sLSTI^OCQb{--OTY z(N6m%JV-%ME^pph)-o9n_Ln}~sSn@rVt?k+`L$OzrBFmd4aENEA!Cg6MOTk+&+~qY z()y2otRe_kq<^8+@-OsbV?2ms*LVF(0R{!$bDP_U7Lv zAElkl;8PHca0NG5W#T>1Q5!q2jB$z;8ObN) zTNmGNS8fGCxkA5KXU&QF#$ZRY0&yH`u6guG&(8-sS(HK%Z?den5+MWGESzmPv=lxl z{w=@tt%9Ij^7mNCNJ1Qx>$>=N{B$SW1pJvo5mMd**^jI;=G+SzDbm;S+<5q{f}mUx z=*MK)kG)xeSR6WnM~uwpON=jPQVK;hvQ}9!MKB*}WbAw?$4K6|RVuytwLB_;`js`0b@}(0aaVQt?f##4NJP5q$HTMD33IqsoeDB2 zS3;Uw`f4DSHM4cyJq_Hb*J3+GP%ildDMQj3`*>`OBSW?ge|4lU8{esLt5;|A zwcx7qzfF3|@ZX%jAH1^zGLrr!^@AcP*Osr_IWpFLC+~@)2-y@apV0c=-01xFmh7(67Q*)_RzFv8 zv1${4HGI{yhYr{ON+u}tOy}PnDzs|J=zQBLf^v<&_N_CzO^4+pG7jE3QJx|w*Z)5s z6hXP@Y$E4nuXRTE#{2CR=!hy~MaB^K%3SMFL5}Y0O1mqvKBY9NOGUSy)}!}s*4N;7 z_991gtyyMgM6`*B57?{>UpO+Zlz6q1QYb>5kH17OX9kb7jtr+11);QR__x)||D#uQ zrsxdHcT&!#)JVq4oS9x;_9N}xI@>9Na;b0BUt#qtO2n{9FLqD_<)ZK7=Q-~c`(p*# z5~^czu4Sv_tR^A;=?A4y#FW?}DS)I~-T!|Bod6MorV`S#-d4#?k9 zzov$62}q4;;@HH+waPj(IH^glO0Wq3A`~v7Z}_ThNann?7naNkk88W#c~(SMOL;Dp z_jx{kELo#GM$eKhLAzIuS#>=it;Bwe6aMD3Fp2wgnsmv zMNlp}>Zq9+R?yMJiF4EKqzKBT&d2aVXC1`CxRi=sDY~Te{L=g-4r1P>QVN0*E@j-< z=#5FEJ1@Rfcw)(fzy{36&-jked8YG^bJ7LpIdi^j^x_H>LAfwS&gdrDl3D{dZH&~~Bal&~AC4$Z^eFs$; zLsx|Ek}^^hi`YdGl#8|y{%*EED*V%`b>Df4NLwQH7WOf)3BO@$0}&w`3(LRDw+y_c z7CNIF7nkz?*gEgHD3a#kw~7%&SQNzwiWw9UB|&Ov{fKOPWS$>ST{!he8TV$+G1t88trH%Y zz)ymoP_>Zy-+$JH*~R=+s+CdAC1f{vDp+fG|8I>#y-z}IAi?@*o>9SD0>bU$Y;)hW zeA3AswHl{|X?PQM>AFvSDp+eb#?yLmvA40+0)!k>U{QJ`>D1%(=OE=OE7`Py!4wG z39~3BuoiAvvxjW1xyoV!YvHzmH?P??<`Fe*OvRSiCV0icHvIimd;XGkW4q(thh}Z4 z`Ko{v^N50Z*Ml25XhdObNq#H$bNxUW9MUXYTODPPA@oCQ?z^knboa>Cy)yfp*;@`94e&0j z`a8Mf_Zgu)Gx2}lAYld&)ZbOx8~T;`Z`A@Y8=3!B?FTvZ(MQeW{8i5FJ-7_eH2<#J zBk>c$J7>*9=6c*|mAVfTSPR$hcMGb2;nJa&<}%b70zWMw9pZPmsblcjtFn9XxPw(x zC|=u*FuKh3P}|77o||WCSkL!h2_~==AWpsQg}EorJ=A9}mS6%uEu6}Ae}nmLd-CCP zyK&8N8^F_;>!gl-$RyvMXSVL?q+0Hnz*^YSkX>V^H500>@G1j-g1N_lcW=ZNfe3y5 z+WXY?V}AAK9$112TqpRBWv;im1^?RDlk17N_u;l7B&qZmv#rKhYFgs9#ag_r)aO^9 zD*WonJ+La9TS^_*uqvDXR%hw#0eR-X-*(wwJO=-_4$eAr!5kf!IeNPh`mk9`jkaJ* z!yP=A=C}O+5m*b474v)4FYBst5_NpQdz2ABA+{T=AJ4v+`_-C*E%#vwZX5hda5ips zb@NQ!z;5Mk@F;|JP=@Y5593!oaQz5rKD)fxx-ky4B_=p6WH*Q-Zg$!GKQ9AY6cfC4 zz28qa6NcNSz1e}g%+_@yM~%2n*b0!7I;-?ATVVog@nv)`^NH z=gXMDTE#0)o?16T#yUo_niZN#7i!#=u>=$NT?9PjtzK;FIVbUJ1$PA#oYsG3N%*+o)Nxo8DTFo9zOaOS|&I6ATU5>ft=$Pt{@sHO&3ee%>O6(PfnbHr5Vx6<tYEebX=4ZT2NVb)=3-)Erl4>vbp9B-?)2MB({vzCd>KLIsFgS_-hToSlfwj~bL#+q+!!SN( zB}FUs^PHrXUoOg6f(ab=g;nO_Bt`RgdGT235*&fG;P=gCcssj5oVv_-*b9dL#tyu% zj@n<6{|^D=SYFC0U4mi>Ch%NING8-gLUIz_ zzFg!8tW|6Ub(|aFeXvf1@(gU%Waxd0C74jH4rTg63j(2z*5Yx_Fu`d-Tbo-JMzVRF zE5+lSslDKr1pRJt?@`A&5HQZ=;&ILqSgW{K=D|1zqPVxK|^{KoBZO_zR0CqP^I0C(^!|p4z^`b*gVn$LlN8oouwXM}(`p>!_!tc{Y zMklF^V+7+Q_;>%CUCj}MUo*9+&hZ?9wVEs|W(2k$#`!mx=iMAwcv@&w)$^%KGQH+u9G`nZ1ztAoC4JayllNMsnLv*F>0>W5>FeuX0$<# zitu;#x{MHa_>QG?_33i;{%f@_S|oA=r&X$gMC8GO<3yEcbg`lQan##Gf2Tvv9g=Xw z;T*7$X_xms4NxcjROA!OEBRZ zWFSu6g&L$45W76bO9frBw0}?kgTPvWGxDJY-wZ)o8dKs4G1A!%&s5wv| zkyiy{nEF(=zP1t<_%zV=lm8%)mML_qQ0O*DeAZGWE*6!i{n}(2+HIM{I0+)i@{a=P z<|I10wglqKk`lCi9y2Ds{Da`M3Iv`1AW?T&C8jk_q?NpH819W22WM;vu(uo{>I0fn z@|20Ee!{y=W%#>tWl@(lSkzr?0mR^>czW|vsBz1*KM1VFm3P#}pXT14tzBGdBAlj+ zo);4YKUL*R^%SQ=eyp%sM&8kS{Ur6C`_rLKD7jM;&Z_MuI8JF!@mZR1BlJsW#o|m` z*57nN%SjM{zuo2UwviBq_(Ve zVgo_Hy0zg-jH~$Q8%Xf?SRBz@c2?qFwPo4&S_uS8FoDY^XBRmu|JeGmZyncZ@wZ*L z46baFm+Y*V>iV(W8#ZwS);d*nn2@zUO1!g39fNl!)l+JI_hZwFb{lXRSPOs025&_| zLst1rYbAPQv=M*Fh`(1f?rS4j-s&apD0G1`ZqIRMEA0K0Gbu(bCOEB|Bjw7(vE|;ZZ z<)m!kVtfs-%-gHq4P}A2@csEAEWt#ze&fZ64OxPzLPr61GlcgBParDw8o&`)E57Oy zu?IY@PKdc^XbOaP3Qu4y z+YDdPAX;ti%@Ldy>Yp?b&KH$tW_;5UUG+; z$F8Ij_=%$rXuCnpvl=eYVhJYjc!cxxhwjqa0&#NPUXH+8+-Qa~muG9c0CDD)(U1+L zc7f7$S@1n%)py2^Te5^rAHzibb}uOe>Jj#|Iaqh9pW9n2JA&`Wee zD7O7ChB8bUNkDXHyG;k=1W7P~dklOfb4MwDkJJ>f2h5E#|HzJU;_6s_=+w(Ryzg=vZRy|6IcuP zP{=)hKAAb!{aa`6J9@)w z)Zp?Qfwk}x!p$dxMzXu(2N+K5Qe^zQ_z87Boh8$0c-n9^6Y$ZCNLI4XGr_rY0Y_jh zb@xxLle)hK8OxtTS^lXa!>1WvWh}vj$wrj)9#HdTpMYqzE{Juwc0xFNMx$T?YoQ%} zX!E^sU71$Hv>)@TDOiFD{k^6VdF3ML-`D~%s+1>dF|4!@Udodru$Hrl0c$L1}I#zi87kvK_y~60$2g+F3gUdW4A1@m9qKlwA z)d8NWch3SU)!QS;pCT13QFmR{+Nyhl_zA%;SzD4>9854&YXskapx@%OQ2ijv*>EoX zdeuRw*gIaqzl)!cM0GZrMtBL15BkAV6~?E~=<+XwdoGDQfwWL=0}x%EYSY^_A`JiEyVkCqV?c zd*9a-KZt4;=Haklh&eCfZCE$Y3uaY-Whs=4M)LLB5O@Uj5|O50?8bvw^Rj z5W#72Wkhx3at*^rl79uz;^t7;YCO1{Owh7nvwxa4d|NSKB3H3!z zqHevnK)Tn0r`qzuLs3G@iYws%n7~?SpBsp>bNrOg^D_*=#95tv%w?z~CiEE|@NGEE zR~BV~2v{4WysmXl@PIjyBaoKbCaT@ky1@+BvA2?0{<5!?t(7{9{*vI|)d%^BrVB9d z9#yl7ACf5L=}9L+4lPh;>fZ#?Qu~%#hT5v|{h)TJGC#~x9N_m*T@8Lo@bBi-4ia;3 z_y}ah79hliiOTR+LjI#)E=+?uG%Bm!J zUlKV*34HTHTmM~#ge923PYXE{^%9j4rOJ!{#-`B134KMf6#8h?5F@gc5kDckJKvnB zByJsHNLb;;5m*b?54>>L!D_5;A}rGtQvD)7v05AO4W8WLGImVbAki@zTGnZ^5iTuw zAE|id9}`9g6;LceeT;iT@ZoO6DgLMC`gXHi!x6Y1xPH(RC-hbZoH*v&^Oz;Wzl)!c z9QP0d{a{4pm63p06QsyTE(&{2Yd8XHp^*ken~#3Vl!2oRA?fuPC&9m)R9Do)%%C?w zl$f-5>7lfIUs`m2>A@373(XinI6i8sjOo-{`+c9tI0+)iO)Jqf4XoSS4T$IGHHy{L zO~Ud`K|F!9&};|9wlF(oSs9}cAqFu{f(Wweg)rIAThPtX0pSX(LF|tQ!k3qkj9fYZ zZza&?P61qw7xzmf-?B))z1&y3Z|4w>;Iz0hY~xep{?_k>j!j`7XTBcJT7en{g-B?P z;>v@#X{&wm_~q$_c`HV71X^(<{In2(^gAu>DtAcuv>WyZpS|}r)pQlc4FLZgW&e`z zHiG^jcuQ%aQ1cE+d!+Zn1fetRWMK&=@DswG*X{vwh1_J{jjzUY1gC}S2N|aQe+YxM zGYq%yPht3X@e`8ITMao!T!qi^YIN`xcruB@i-h|xCi4W+g7VD%9E@ZjItn$Z=cBHM zA!HKcB#0mrI~qR+cnPL*{ek$LkV3CIKM>9~OXLZp1(r6K0pk*gkb~Lu&Ppet@633{ zNf1FomKo)IFCnK$B{mNzpige;giSvqc>-xck1>}4qZ){{OE1z}!ygNWwnwXd_qPNQ zq~L;42VS_Yc1IxggBQLms=Rn)K@i;LL8QVo7@grh5{xdX*vo)-IP^=Thpr^^3F>UP zFt|TQa9Ug$niwx;@8BRrWWnz1oTieF!uaT|kzkfEm!XzLqN+;z{;*0|HiV~g{OZAe z{<}%21pmhpOyDOZr2G^o_V1SnL&ECz9KmU!`oZkex+{yArPWUSUQL~Sem@C%LQ*J5 zVZGt0eE)`-dhpsHwtDGVq1_n`ParL|9g4jSAog7fWi8u1H$1TUMmY&0^!A-4qP{`? zt!54om_zoQek!!m zUSyW=dU6U!U@diA6nh-%Q;kVvmE%SV(WR0pmSDoW;{eI61=M4jD-f3;jxp+8YM%2B zD+7M3#_<6Ec7r6xwXg=4gm?$Zd^DL2?`9!>h}a`y2_|sa@P%~7BsQ`{Y2PDR6)7gL z7XMTmzNE?T*C#N~+>Qd?Kg0WK1;G=Ab&sRPO{dhII9FW*<)KF#HsPP%BHrgbUIxCl zC*ErlbNM|_IE^H^k<#LCk>y=4LEVn`h1(VfwTdm*l-n8QXfiClv2s4rjnPdDdE#{l z+_1XdOJ5fD>+qf@$vSMU=yusN%WGAb=}S+^IG3(F{{^&gPQZm=ctY2MBnbYUSPZjL zDz!LI-`v%*&RgNc77|{sTeK@jaKA)SP8G>5Yt^FXDu=Pfn*yaO=U>;$-R4RMrv^Zs ze4L#=@-&onqDX$BsYUNr;R*ayT-oGj>5KBHt*=C@GH}Wb%3;6+S02eq-XxE&zKiyE z8pMd(UwOpOMcmaF_Tq6C0p9H=J4RJkdS0h&rt=(%+Zpe^lB^MeX>+7lxJ=z248Q28 zto~7zy)_WHLGt&0Ho@&t6S6F_#|XM3>dt6XN*(2d;>>L4Kjd2qYvJ8xQodIiB_Oye z^EqFWaZiG^aQ(=YzkkZDvK?9YBe+Q!?`>l(t{z)DzLeKZtI8~zH)dQ7F;Qu}U}`&5 zB)ip2j{bjDQf~IE#M)e~!MNJuzJ&W2neAbxZ2jvceQtzvaj<=`7PbO;(&&f0X~#R- zX{s;dcHFTRZcXy4=UchiB*Iqz>%$XR3)hJZvCEQQygNdjHb5`IHN;w6FUc?cmwcjZ z8tt*UAKVU%+7{OXWy3%$Jot=!=*%+O>%jn?z*_hT$-TcL<;>C>>E(CB_@_co!ex<= zIj@(4kHB1x#SAsCjM0 zy$8a@!mDZ-!V-}cerd|eobPSK5=`)?H21c3VGU=BtXnS^Ehey5=zN_xZe*m`sI^-2 zwYh{73YBZRKAs)iaUKqvIIYca(1_QA&ff{Ejo5@!M7|K zn3yUas1V9VWqsp`mwyYUu92dn7p!E6h7)LRZWAvz64(#{MlEV*f(Wi`(zp5~G0Arv zd+HZQx#z{dn z%s~|O%Ogaa{*d)X5=(f}7A{R$_7iW$Nf5#3MtR(SBxbF*V{4mq<7M)l`&yfA@nNEW;fq0G{j{kYYcg_UBW$#sZ$>P9olJt3D_HFX8tZc9tDaW_I> zhC{hr+>_w^D}PfmtsD?an^}+M%HU|6Ax56NU!Wy*Ls*Z(Funy*+u$BbNW;yiY1Nut z*sLZ+TnplQ@PuQ^V0OIzPD($nrg(hl#r#4kaS}&hEj*gx3!Y29tm{=f_HKlM;@`#P@lSPdR$1n|xE>3+Y|YsU(>y`CTeGdC z4zn6wkt47cwgQ~F?C;F$~XyXHEacVSDP}L zg;ylEl6W6v_i!a0Bm=jx`)K>X^zAP<#5^E&-)2+&#bf;G1 z)O@cN9$z5ei_h5FQ6ZLQ_ueJ1JOqAXl==>nois=smYiY9Jmo%P^XI0XFqCJ&( z0&C$XB$oLOtZ=QURJyT*Ye8H_nAd11dupp)7u5Ht7CjwUYOtuJxU8U@1V0siTGA(@ z9&2H2tIYYd1MZAY|CPUodkL5CM{F!AGwWU1^00Sp8SZ^}400K?L|j>pk;FT4VlVJT zac(Wjf#rUQ3~XY@N{OYFnQNT*G7!P#Ly{pm4VaD6SeemD;>IA>!s8KkWpc~0+{6k> zw~z*WHZIO8#<_|l>$W9JJY7-I-E`y$tc7zfiGy1v&3w3AZkG;u`uKNo-^J|@X_F;c z*fm=vVMu+Rz*@LGvIL&$tzTVbO(QEtumlsRW#Q|y@uL-a{|vf5uA8h28!ToY=qZq& z&$Kv>&+jyN-x{dgtB^szCg;m|p9Al)=$^J0brSs26E#1v&$$3a`#zO^%q^o}2`2C^ z5PX+M2-)e;4m&!8mzZ zB=0NCq;um!xScq>SEw({6&!c>6vB1{LKzWnR?D<;2FrEn6wU&rkzhJPL=*KL$R zOGLsRB$lAPP5r;Nf^J_=AuvGQudTG)C^^(kqt=_^6;6T(ZYP%beUK!%RyuvD|ARm~ zyrjxYU;X}`LdQC4uG)cG6~yi#skDZipl}jQ;2mW$HtLH|Ny?;^8~s6Gt*bi>Gfu2}nrMDODs9mnc1BU=0N&vzKQ9}}iJpQftP_+` z#4Om-71QaNqk#%1K{)|9&jI#WqV3tkmKk)Be_Jk}0q05Rqa7r22>R~#Mo>oh))uT{ z=T!Q0bW??spsWWjt7gyG0TG4j_EU~i{(3+APFXL1`MnpGkUX{ z`!eaOPdtIOa^S>ay#dN-astZOF({l>iOrxNdK{9m1QR%uhmgw2;jH<|bXwb$C$N^| zVu;D@g)-hjP8?bGIEIx9OQjR(c$t%+944Hd1lgaHW7yiI=`=5S0!Lu2kkVn23C0IG z4tt&CNK8Ci*E*G2kG>&c2_|ra6~6r;@vOOZ2CXvi78gmyvCvq{Fv$_dIibyrgpAl9 z!{TqH(r1+?QY^s)j`c#DFN|TMe4t-FAI}k3D{M`Oq|PNISM{^z%n4_cN2Jn&Ie8RI zFo9#%gw*H~&gxvqr11xGIRb0xwse(D>iGC{9Lk9Q(3>5ZkwMqjen+tc6MRg6t3@y? z9h64v)O*hnoK|-xU%$hd%UFV9`goTE=JqY^Sa`<_`b_r+ zfp!{9S78iph572GodlVHjxCs5UK%}=+mvwik&AJbo3@TnH%q=;N70KSB!-wC?lv7 zl#$`0&_m5;&~+DJpA$NyhP3|N8*Zr^#Wt&cKPN~I%u*Mp}* zyZ2~UUtictG{HKkpIHvd=&0+aOv#!-4-G5>?SUkiK$#JQ&>jKGySo|m+g_gFvJ-B! z7xgQlUo|R(F<7HRm@;d68a=W7JS9ki37ks-Z`*#Om1TxBy72F=TqXz3-e}T)uvn(LQmgDNs%tTcBe2$EF1 zGx3T;Q6|l*9w%W5Ca~`d-+8$uD7((3(duU>as<}Go-^z_-;Yqf?Z~H1_SNEjYLqP$ zJAa^Dc)^hkZ>5#d!566IE5;K@OMmK(KsH1Px&?6G9!UzjAZM_>O%Y9tGz1V?lB=MxxB>o1(6PHW(7bu7UI_O;3U*D3Ub z>m~Z6#2*CKid$vWuZR*%FG8Rm^;?{xtCP;rn;m+>?b%3z3C?fNaePiUK$~Zc>%{x* zC}&siY$1_V(65$?P)2+`d$we9KJ9y{rNT)t!TIf@G9p=-jrp`*a77vWaM*7PSREmS z&4+$9J4OpR^! zNf5#L62w1nI^Fy-pSBzS2Z3^N^i=|kxeatMUsw8rz*?nj zM3MvJ!{h;FSk&%)(3bM~OcOq-A*}< zpHDsd&81j^2|mxV&!z#2A>k4YiJQj}SnKVKfg)J~Wjs>PnYex@LfJnzA8tUcO|b+M z*!zHQWjc3N#)NCwW1AMT{&AGJsnGsEULt8=xIZc6V#8dlEbv5X~{z;P|uuRYdWxmClCy|H}66F4r`UJ&2fK^dK_ zL^wmJd@ZHPP7Ui^&r%^sf`1pU+K_Yi^|ZVW^3{Z!Ufeo}qhI>LvY@LwK`30?8_Jkc zDP68JS;KmcZm(boCb-p(^m^G@ezQiyoMw0C)HVn#Osn>)JOEm1&5yaKM1U4xz|9T9(qGGlrd|OJ=KoVu=Vo;6oMs~z^gX#TDh7^7ItiC zXls70#p~<60weK&9_pvYEXQUS(!IGFHq4`iLa+o8+=@z0AN@g>E!41pa}Bt)7DvBy zhFTJ70cE^&g)+LHwP&BlYuI9Yje;eZz;P`?lE>Mz_jfgHL0O)_TDl$XlD-buDySNi zp}00;`?qRXV9^(ulc0DRj%&f$Z6_MCN)7DT;QN0NDEg(_?I)>i4%xj>#=Lp0SnanO z=3F{o<|K%~aV>~b8(Oi&Fg_~(JkJqW%QU`+u!JcqD3)LX$F*QRk8i`SUD2@HrFjBtnO63YvTH-X8gUlNc=iB#3Ctzh z2j?l4V1kQlkpVwiv9Ey|)}UKHM{rt&eo{_rsK@o6P)6S3Mr>vk4NGbKl@csL@iH#1 zMFLV9vAv-hc6a|5j=);FNA6O&R#1=1)g-v1>X|+3+(5&wcGfT~!2}oAB5TgsvkNCQ ztkfx6j=)-`ueBscweRkQcpQWle$w2*8g}Aj1BNA-;JjM0a6zNBG)S7^ceyU54Y zC*L%NL7VIC)tF4ZX=~`lxzHZdTQg3A3C`d3ji^drZP2i7LjpKo6i2`G2lgA(H7am# zG?dZ)PJxiUK*Qb~3u0J;2`;Wh4m7OHjNFd$ojkXu2wz_24btX~FrT*#B&BD@rV++h4IK+pQ`@BZR5=>z49KMOGS6-Qr>&udE-juOVjs0kyS2Ho>QL13-)KDbE?)6J~ z$1WdMC$Xf0C79siTJSabOZo6gU-rIs368*8`tYiv9_pcMAwU`FvrfyEPWmwWv2Y_B zmY_%)7uO1V0!FlJT?)xqD!V6zkaYZ%GZ^yp6E~LB^ z24$Fbwudqz(jL+NF+R*P1#%{kgd;e=z4dVyw%~*>Yc~1;=fh#Yt@`I!Nda4#-X}wh z%)!}>m4-2R_wdR?Sb_=c+ksDAxj9<{?a{bAHDCg3?Qj?^sqH}mB4LKxAJL3m3xILH z1jWlZ z&wzY*xtMNS@5`dr*W!Ez9R1QC-eml&_T9k2P{xjV9cjG{KFsG^BZeg$!9~3MYIUL( zXMNehr44xkYklc!>;h#3vf)rhi){zQ8{K`F(XlxrNP^>K*!zGJ9Y$El?IE9Y!@Z{5 zdXCp{eG>e>TE=zN11R4xMIIXhefLN`h9w-qt>>1F7s;tGx6gSAw!#t|{o49j$ax0s zVb=}HC^!GKJVo|lSCVWP!4gd1xE5*u@q|3{FJD&vbtRs_T4$?><<#*pPK}Fx4}2*v zf8xWkMwes+OAx`uwaB$$Me?JazAVU0RMUdA)KhRUidKCEi5P)d*l6F9B~nVXO6 zD|?||DH8{B1lC$SFj|}pW#~(dhcb#fHdC^LeOP|hLlH|bfxQnX<7OqrrgadT^=}C| zm&S>n%`*fdeA42z9k1H(*-# z5LT-B0vSuV6&b~~VDApTV>!^upKT}k9D!GAyaq#z>|VC~&KSg6_x>q!s~V1S<(&|s zpnf@45LYB=jkWUp=0WV^M~JE+310iSwTm2{Z7+wO3S#nwiu|gERx*8)+Cohzqu@g< zl(GBq5b40=Aoe^~1Ltfb2_m>C6=~zzN~*rNGrWCO=Lr1E1U!oT$GA@E}t*PNBFbmFKX}vie+&tDv8VLOIzIxVivaL_;nCPru4T9 zji;J{brp4Y>0!ehY7-p9Vurv?u~>o#yxPIu-Ln&P>#+{3$`gqDpmh*OrV1OoNsplB zy3LKDjQq{V=nMA{Hq}azu>=!b%!$0H@QvPn@6TF=8F>Q5thfjgskiti?LECCyS`K6 z2^4|KiR~q=ae$|~{~CNz*GsSI2cHm@l`=!d68yV3f&_7Dy)E0|+KD~wFoGkn7LEtO z_s&c0Slq&ntb6s59D%jgDI=tHFb4HA;M7neEw^Bunuaj@W0o?OU;@X3U_HN4lO=}w zvjhECNSMG{*fW4LGb`0$Ll<^nE=!1x&t2BZd-P^PA68X-f)h^SX*5nM_{cm+Fx4W3bwifd5YwK zBVpbXgV-2DHpLQ5aIqS4rO1L^uhfOvUW1%%{97oZS|l%Uq!eDnM2l-sm2{ff1`3Px0|Zw@?xw6LcJr)IbJlCz)%@A_NvJ{b&bXbs#)dVD)VI zWS1azY6)Rj!ufO9QzJ7QeUSC1I1` zfD$CZ@fj|TLaJ`GR!WEYvt13+ID*qcJ`v0e9cn2x=XGG)zklXD8SK4OsXbQog!UlM zM#1~Xnmgr`?u|p(;ZD{fmS6%$MPN7Mb4_LRSAW)eavcd1SPT0>P)4dosd^=dE%|W5 zhzYEPy(rktn3g6dWhAh`yc!Zd2^eef{#EI)Wpe!`aqLUnS&qP3IK~0z!ESa|!M|!A zAva2lXLlF2kg){+F7LxtJ>)AdPD)^`WEYOWT3l3woE^|z{!niedoW@FM{rsw#sMcZ zP3$b&ZH;9u&d=fq&S&J#d#xVuNP6%jfi>zDFXIziF@gO@LY}_9BYC`xXK(G2c>;Nv zyl2_c?}>B}T5!|Jl^lV!@M)NE?#DAGRezVjGzBR#mSBSOI7vjX(b!?<7*==8a*n`S zoc~D5dG0hmcsQDQwcp4S$p6HrVZy#z+!5i7|2WpU%{UoL@bB`T=|HxX23`vHQ75twyj_{Un}1ksEyCCPY$aJrK7>k7F%M^p~*&|1RgFlIa5;iY{=A zK$DgIcmjE{*heL#^R9{1bHWJLByu4~U@h#U!gr7po6{O_Cw;qegE<0g;qzr7r>Mpt zy3#v=4YF(~V+kg($4SVc?4k6^-FSAidt;8kTKIff@Tsd!qb0o(*eRP!5|&^BdxLOK z!;BQV_f9->YJbkgx<3yk~iJU?t=Z3Z=Wxq4E>5=?OZBT4x-hsLFjVS7B^as<}mPE#g_9eUEa6UVX3Grove zf(g#!BrU&Z(6WbP*_yN%3qq#5!lPb=d441$>*oyyTRkwS(|>8li=S)9w(fR-|vZN zh#1FSdH+EmE#4QMRpyHL5LO)Pk2|()3S$r}(Av2s$ z3(tm(V-e{IaGL`5h{<5k70Gj zg1?JPM_Tyi0yym`k;$9R#=#?*M^AjyyfzT{bShv2mQI5L9iC~ zui<+G!&-Ul^f)%#e>z8CE$p4cy_R#w%QL};^VFA<@!bPCN2iGvFBS;8>t3SG+j*kt z`2x7N<2^)J?2|2&PWyt{E$?bFC#khe%&}Vw->(!1jXZM1xAyS&gE>HGlRGK@^m1U+ z7X6TN1J{T>3s(wcYb8$0J#B-iKet~XkE;OjLF}r$npcf|UgO0PSnKKhjbe~WIL?Ld zCY*XED6N;J(eEuoMVA>HM91?W8Dww7S`A)o6wmxTEsz#fA^H&?G)B=|rO}U#>r+f% ztypE9NInA5W+4!P4^!o`|HiYB(6ti23j$jqXWepfc2ls`_+e0w+aW=Ua!125n^LiI zo3&!O%3za6cE;9S*NF+Ltw@JlTsDl4I{``x{atD`)H~(XkQKW5j(R_Jj;ky1|!|okzg;=ZL^s`oP7a zW79JN3Dv-xaAVDI`P!Os?8MTk62AEYTY<0np~x5Vz3M~Q<}S_>mf-g9v0|0z@p*wj zIyOE8F_{?}#qj~e0G3ZMVhJX&-QWzN`x<4)v>+BVzO;x5tc7g|IbIn7%Ij)&?8P-J zYSTDJbkjf^ES+n_TG(!c%#H9@CKN#n7DjOd*1|S~Gg96UQI?NSqc)F?RR4LQm~#!< zW16jmwRr0q3;HPb*Jse`Tc7a+Y6IQ7*`jXNF@fA@3GMM&EUA34>BH_XtVT)1JaKFh zSkdnvW2^WT;uRRFMCoTNv|1+avV!{QZ$g`w?PIHCKlNwYiK97!)A~M7tY!nmNoy#h zSM5=9y8u|7tIZVgT|&4FTsGWkaqNe@EwCq?d@+qH117Rxzw7uZRjfc4Lq?+ulu_rg zz2dUVmnFa4O*si7OzUTgIghsr7NV}{cdd)^ySoj zPTjbs$_uYcbjHEj3`;OU9>j<_r;Z9_WegCvPS;RwxL>3>vCTMw(|X%obnJCZ(BDf2 z!uCg^{P|%#o8HNaayI~>_UCL!F8uRMF6q&o?Tgt(iR*ar0E{*L><$vAh3W_Q0#v#$ z4}c`Tb$cX^z*Zn928&x5wBYb?c&e>&KjcRHeA(2aZz(51zl$vbSr$j%%I}-{vS>(R z#st>VKk6zbec2%B2Tz4E+F8Dqub=#TeR!W=}SMwU{)8zf#(y7zu5gb9V zmSLe_GyAmQwr?HSs`Rw>a@)LkR%U89uI5~8&S)>z{|GZtNw|rMbUv|6?)9WM8<6>g zl5hu62cAW&FjLYaEo>3EJJV;eJWKXx-G9Is#00k6aBI=A!dfB6dOnoVH91FqvQfj< z+;7cPAH)&XT79i$k{)Xzi$LyRT9oXfhwlyY{5b;Kjg(p-n9e|d8?qM4usrB2pR$`t z?;nk0`bSj+(^=?!X&WR?>q%9}PdqI|J=h3D!?Zfmnd2GM9byd}fwk6T`|O%^NhsyB z83>Dab>+!>$FX;xTT*;48Sa(XZV&@FJ7zT+Z1vY1!35sj+m<4#bvm^7E3VksH(C5ic5mcH6 zLfEl|l4)t6@EO+K&%0Luak$kdW6auMR_{o8#z}^1%)K(ZgW8um2VDU8Fi+L5HRL56`5|d%}4F zYi+WX0)k=v=&jC)6Q?hg-h=o0Xe#VY;5*LH&3oL_l8>Xl81DuJv-+$8GnMr>M1fzs zPgwOwZE-zjdh8OmU+%_i2E!?|h~R3wP-8UhStf+ptcIsLr0*xLsO8CCM|i;Pz*vHQ zw_O#Z?(SA0yV`mnuGkicJBvKn$!aZm0&C5kYt&bPnV|{vP%^cAb=ta;9jpGOD$=IsW%BTMrZ zIi8X%R-H49bsc$zauRHXgL{p+sy`RL1nSXr=mT+fN-uVOKm|sy1QYma$-61dX#L~< z%q5~KPhhPi@DDB53SpMZpp3*;l~|OLLbqf>%`Jl@6ZAy=w`mdygRfoGH;V_b)+Y6k zNd6f?U!eLWoi{kK{$XkK+DJGt3lmtYXN(j!7<`{fqky>bHADEPU;=Bhtuw_p{b9Rt z79pGGbrmlvW7x(4OF4qm!WJQ#-TmmU2YuOS!#m2^3e{GBy^>UDwNcPNP}h%2O)k?n zei}CBwI|bmZzh>k53(|>&R7dufy`L&fi5VeVfUk(as+29Y!Q;`oh2@~F^(BBhEjZw zB4-7z9$qD$iNfkJY?t#~oYYWue9mu0>Sa! zR0(V0`oWia)(2?GYMofsYOt4z32X)MrS)JDU4$OW2(94H>W@jM%`aLrJ$PTbP0%yi zyGtg^WJxc>-%kQ1eNA|pX5e2fQ{PyQJ_=^uUKw=kvsV-oSj*IOu@svQggJ8{0`66{ zdzQ$mzV6S}oT~?VTDZZ*^B|3y)|2&me~Yg$^JzUb?gZGb@>NgFy$`CfQi!WOp2>vc22-Zpl8`XmMsJt#fxKFIj+Q!;3 zaR=l9UPO5c5@xl>8ho>0q_gPi-%8TG%4w=zzCW?ij=_p5DR}NK4l=Q*yKg>uzfX*46a$ zVs4%7n6Bj+s@K3chFM=f#9G2y*dmZK;iF?g&UP#&a|1_UE&YwLw)*yIAZyYtpHA7A&JkEE3_MEJvjndR$~Zq~B(s>GN%vb!qgaB8 zKxv&6Ru9HUSv4B9L5yQxOU$G@QCZMDVH9d$&FRC9_3XVzo04UoS(dIH4~ zOkf)lQjpq^#lRbV%JLpOf!YA#iBfSq5z5dH?8H|7qhX#S`cf>xzl&`M@%9D*?DI7Z zJAK%JBe2$;8tbJr@G{7N%20+^pP_7H{Q{bOs3OG@Oz_ryc`=gp+kc&&E}J4^0&77u zQYwyFdco{-Y#gh(DTdm3I*3?;i8Am`uoK=5$m(o}k=Z(rXVu3<(SwhxNSMG{UBJ)1 zI1k#qUR43U`8hI)EzrIe_jjKnVF@Mz$tLOLawwy^N>tOhPu!31t6LY6G_V715G{F#Q$c~?rr5=`KBf;%l11~Hc-8kW1djD!iS)dl?AYHCmP zs{-xOaA+hums&uxb|gz!!Vz4Xhj$&yVgd^2xAzrgOyKs1_@z`FLxwVr42WYtdu7sB zK5jCWU?Lmd{T*S)j;vV-gzeIi%q1<8{&RIIM{rtGS4o9aVg1NgZ%fMlZ5RVt3Eilz$SWvEYeL%kRI!Gw;i z%)pt{;*m9+a`T(uw0u(}y&Bmb-5rRscb#c;P7?F0mm=Waj-N#Ji!2Zf?y|mj|&{hbqgMz*?~f z7D+$Unfl^&AjGN-ncZ~w+G%@F8A~uxcz(I0djvgk?`A|E|%nwSR4pAqxCUf(hK3giJW%#dg3~zc-@Kas<}GEemH^bn<7r1JkI+ z2yOmznp7Oe6*(=g%^kAg8Xz)`fjv!d;aExS%gT8w&2I_HI(9_e864?IQ+a-KE zFt#+dA?(-oEzRC&y0fRbv5>u!CFQAYYi}uXTF4^s{a^xNBMd?8gzapOz;+|HnbP7? z;Nkq+44&$!e^d6nzlQa2_#mr(xg+@J#Hy=^wXj9tl(g%$*`SUZ_H}A`1rwasvtd%l z+tB9ahC>;FQd3s%7acgpIL)_}mr_Y1Ou-7l2a0J%EEeq$vk+<}XT`=3eEmJ1%r%Ha$ zVE?q9ugGa}EtuSnu!jHoGyAFsI0CmIZYTKKsYWFh@?{3?q=TCKyGyz2U`~87OXTdv z)x1H~zv=CE$<%8{Z=S$fOEi+>Y={)qTMV|^>C~NufTzFpIg{}%;J8le`%`)w*aa97 z4#bSW{q)Mhp6rz89hqG7lGIpO?2&0Ar=@g}1PAE5$$B6*4>>^39D|XYL==udS`ZPI zieuzJBy~xn^KWL-tFYgx`pm^qSrMYO#^NZqNR}@&x-~p4z$yfUsZk3$u5>0H6$)qk zVghR=fM*OIvOZ-a5N=m=^s+}Hd)U`Y#y41VR^V#hu=QXXTzxdVw{I#(a5cvkA=VE^ z({e}qGS_P_Ia}e{>g!dK0?Ta_!mJm-Q+>X$n4UTaU*3noslW#cjKz^{k<-FfP$S#4 zII_(VoUO1$Nbu4(;=A_a*q0xD`Ffyd*IT_esx2D^`2cWFb;D}3>;c%3nQ8(1=tzQ| z5F*9K;z%(N4-XBH&WbbXo=fox3AY#2_^u=D)x$2Umk$0egdKe{#~x17IW2fURokO- zhx+o^>lw7$3ur-1V6Ejav$i@d*r+0hxXUsNFi*H(Y8lJTPIi&kF^PxVia>tZ1I zqOXhG6;6VG7v4Mc;Pq{)u^xz0x)AZhTMxEjkq1w3S{=NLW5_^swY3o6fiGHOQjh}i z*54A2K$a#pM3fw1$7J%9KM33&*y`j&llt=4#TnH96SPMUu={@zQ;};Mu03=vY4U0( zSe-pb@&wj$ybt?!Ft?9e1@)+#e^xkkDw^HbUX-zQvEB6BmujCuPjt>yiK&$X1iKl% z*wE$`6)eF7XAv^%uC;W2n?IX4vKB{hS|9BM)w(v2w*l6@WF?pUSHo(ohO?07&NWN) zO>!VR1ZiQ55P!R9xyxk@OB)L_H72mu%)3HytRKoqi8jiuW`XxQ5>6POYAfnhe-|-aWa37;NRxEOL!cRz=T+flu`fAuU$2L5HwQ&82Xbn{o`rf01rOf@QRfG+s$ngz9w9$0mFH<`v})7NJb|^kbQg7_U{!NeeTFyvL*#ro zyQI=)__oi%QY?;`iuwb4g%7rfx^@_Dfs)HBxRh{8JyU&)h;hWKbmL+%sX+b1a zERGZd;gR5=jBRp(YR|eU5D^rMEdJ zd>TQ(zd{7og1Dbp990Fv#o1T!pOQ|aWG97_;NNvg5%uHYtw^uF-yfs%MEd6~J3k)c2^vgXc*tyN_ovgZs--X%$4jn5JMD;ewUUeF$xKw6xo ziK&yn(!?i~PW}$>21T>P;yAU4?Z($U$t^^A-z}An*TXv}CXjvfT^7Sl<6x^e4cJPX z+(hZM(~b?O{9cBrqgWi96d`ge7Ds{Mp7P&iL!L}WFJ*9o9drBlG)G`9h%Ji6QCuiv zY0ePkM|37V(9tM|xvdln55vqL!mNO_^ix-fdhn1*!993a8*^fWlJp~!{%n)V6G%(V zZrk@3hz{x-{p0fAC7*BOS;kopS=S^;)K1D49M6V}xc#x!;fR9O{1S}>vIIwvWNUcxOE6l;8){ti3hvL(!~U}<(fN} znTgwmvmu#i|5|pk@55-zXJFsPJ06vhH;zos%$Bjimk}uolkige(iUShiAhqM05mnaSU2i{z8 zrX<$F8JlqH!k8M0c8fn-^6CngTZ^^0TtyO@UqP|E(wiA_n{foz!g-_+xyzm-{|Jp| zhcovXahqc;oDU1WsAr^{F?c-tG$_}AvnH_?rs1vV`bOE}*l4zU*d+lISPMTPL~*uS zC=V6{Ggo6ZiY2(_*lutV^p)01g~b|n?(ZCmvoWz2ZX57LLw%G!6Jd{~;c`cZV4lEQI3JQ2GGgSW%i~zk$bo!bAI@UrvOizmKPoR7 z*_HVv7EvzS3~6DDK!j!KK6y=>uFUo8-~W%R^8kw?SpsmIb3#wWh>BShjIg`iz2*ce zM$DKI6+s0QQP(pN%sDG&%sH?-J;SMIRxo46cxEx3SzpaEPpj{~@4m;os())jcXf4l zO_xMqEjbe~xzA~}Z|{yH{hhOkgdX<43;j$*s2C*GgMj55Bxl4K^Ku z46_z55`~njCJ_ThS7cqvKc{Z_#&d#m(%!-97p#%kRLC8}Ic#KYf3tWFUk@yTeJLqx z4(G;6S!j-8`PD=i&vWmGlOu7S9oEA6e&q3hifXdWpU(>_AZJZtEtDGv(b7GbK|*Ff zotjf7u$GjcxOLYpF|^G%IQPR(%DKb&kT@$8YS(o5EGn)a%?tR=l?X`-+aoy|7F2s3 z?aFr^$|+~*VJ&=5#Ov8b@qATl-Y%}ROkgei+(^R)CNcTC3*X(xpG!G#SPQ=!vVCYy z>Iu>7v8DeZuvT-N54U>x6#8m(8v8tS2q##A38|Hg%~lXjtxsd={%{UGCa@OHbRz-Z z>#(?QGuWT4MsX=85fivok`3)+*@DP;HuyU9DEwPk3+F15jjg6B)5ebD!#xK{`H46u zQOfrsQD=hKcvzVz=x7b+>7y(*oZTj6={0+{j74>K;rm85l?kLJ<$IAcSsW~(_#M{w zR!1&L5J99o%Z`Jtuu{+A)RW?VGJ&&=|*0hoWtr?@Z--dxg-KV z1v!tb%7S<7R3R7c9|-wyD1%DUlJenROwPk|d@sU7N|%=iDUT54Nx|v()64Nc{6T^noC?pd|3un4Pr2i!cTX8LdA1yLm%BI3ufiRE$mA&U&XW+&<1B1Ej z?;I$U8wD!}zjE=M>kQmjXOIZ21#{eA*Y39N-PlHfdmnvK{vpGcmOV3o3va88+&Ax8Gy3uF(Huoli?f*EA?@x0Bb z=QJ&QB^75q;G79Lv!;LT%WUYaAYL#b!-BH~aCQpL4}kec_JaJ@$Id+DQ4b52U;<~6 z!0AbldHwT3d;YxfZUqxq3uh6)=p0<1N4YlO?^g5_Sb_=!1?}QKwoB-7rzSNsKvZq8~Eu2LFS*-K=@{SoP?Ac#& zDwbe^NEs=8%l6={p_)hBm~9e)wP5!0E7t_7M?ltOwp+2R^}-{nBtgHM+;piRmtg+! zr@lJaxM=_%aW;ni`QfERU@a*-g}AP3%SK+0;*HwQQ1I?F&O*U&7WRs2&0q`NBl!8d zm8I+itc5cb;I!$(jrcqGCT@zJWr263QAUE4KSBHk*W|0cU3h)BcM^fMq?`caG3y=c zvKn%up45={=<%*K+UZ+8EFB){H`$eA1{ zCqT+UAQ$rvXVuaoc*lQpNIUM57NVhlTzkVxUo6T`M%B>p&N0Dvj-ND{vMQDNIEr$` ztAR`)Eony?5`Hc-&wRI8%j|xz-i~&p5kaKPfe|enY1O}yJrd%SFH`P$)xS?8Jt~_gEBX z6hH>H+f<7gvOibdbC+@r2qxSTm4sDuEy?X+C!XBAJzMb!isBvJI;(g$6cdtdVr$w- z%&Iqr+j}mN2&{$g3C_~9by7e4gfDnDepe+4epYA?8uljO4HkzLuc-A<2Mh0pVlDJG zVOQqy3$?)+7w#zLArW}@UEWJ&;d!;Jy>GK~`@A(tf`3=qaqoD}RddAMWbY2uk_oJZ zcdbc|%I@mUHKTY_?^*ILGTJ$ob{EOuX36T;R_%GE2an}lWW3{!cNfW~@)>H=8z#PF z)ejZ#J4*M2cjEPLel+8oABm9m>(PFs^P3;d_~u8$`@opMd(h5rel+8o9~Bc=3-1rZ zJ8ux6B|V+aK5mAcYP=7O_L}9L>Yx7%(Do$9u#d}yOrZU2c^5gdcZBx6UM#D=VSvE9 zlXzbZ@5;fxbIZ|MWyr=|(Xg_L39N;8{$NjdZfmVNw8XQwhDbZrk`~%sgwsMrV{P*n z*d_b8Mj{B(l6Ejj$;dbAj!oV8hp1`Njyu-EyQGl6TdjvWs7p9+biIl6&aoEWiG^?C zmPPUC{?F)?&K}IWNTP`IZ%xTz7sc9pqbSTeP-2~@q|Zwf$`yY~Y%U6%bN6uqFYfu8 zUf94WCa~7i$BCkBclf1ai{Sf@a>Xa|h<;CL&R2CsHL$Tjw{g(Yv+qTgbLLS-t?vUe!B$!BkJe?M% za33pufe=lYw)RmRt9ZJMCP~JH)4Aoq#?c^3c0|(LK5!qg!9dhHSw&kH63fD_HP9pp zCVKRsfvek7TWiSVAx{pM(B`RetW6Kdbi$IHjFO&y)b?fuwMBC}(gOEU9`cz;YQQHo zAuJxg;OVSM5=4+2WogFO_B1(J&;Fc$<+9pxRvcRs)<=^hX`d`<=Y6SLlT}bX@|z{d z3O0tX2Eq}$QvG&uDyu#%Sd%1}*ml4&w+lRljCDXPja#LTD-+Mmi-*bt*4lp166)QJ zhIY{NEHfszP~V5lV6U5pX#`6!Q8>U7_!-`LX+5u@?y%S5e&;y$>dY98V9DHB=G2G2 z^vJ_RYHhpFoDT0}Zkw$@{3zemynfL%mQ*29lO%{B84Db9$NSMSPxTn?z@3&!gD%Zr zYO@HLz*?0TI1<3d*tWWj+NtO0)3x!;s|4hvVhJX01So;=zBK3`Jy&(p;45@=*=g+W z1}iWe z-XNB2{i0Z-;jLAGcOLjnv6{Nk^ichs|Ize3v+sy!SyTIJk^~c<$_h)cAGI#i+tsEg z=UKmRv25y#{}4#acA&gShCZ0QSC4(_p2)&K9h<>Y+xcsf1Q8?$6X_SBe-xexMEmbm z`1Iy+tmZ`MQA2wQQm+HGy@kA}KH=gl^be8&eQ;5vNN50kFhTEw8=p`9Njf5|%a)126nG+43JQ2umY#gU2k<@*(wQX5KTnX=V8gw(0PiXczY7Gp z+nT@HI+J;)<>!(F6BDM3^xV4N^#kJP9m;oYj%RgBLUk1^@eLQ&I$+~V5S-Q%2_ufv z?*cJ6Z&iLZDu#KVY``T6CKmM+>21NreH#!hvs__KL_B-fs1GNL%8BH=?Wr|xksx!v zDhXTtXkY<2hhy0{#qfzh)OTCLE>xM#O6Lvck^~cueai0aV57l$AZpF*&)QyD%xe7@ z!3mb^?5cPU@ug2PHVHDmk1`kDdG54CApWd&nvUV~n8RZXmn4|DyvUKz!;gM?pcAi@ zWZD$+UR~OS%LLK_&*w0FA`mT0rI_4~&S0NfL~u!h2y$?~+1ApJ=6|Z&SYD!)&vO4b z_V4Qd5Lm170<+;0f#`Jbk~nuAqQ0hZRakx_{855Otd&)37i0L^Xobwo&|SO+hoAk98*GN0&Dd< zXt6eecGVSj#tEypQe8o2usb`3a)Kq8*!$U1_=zt~@X$|gX?Jjy`t|#C);b%s5=>yN zz;71A?*dWb*m*TiR4lueI}mo_kOUK{<)~HhrO6$jg_4d1Qq;fH7}meoe+Z-n-jy1D z7l;#ei1r97ns4aViAxehkmr;pz&Hq*xIh%E`9lqce!jT)e+aDAlT&L8@a-P6fM|NN zgk~=h&sNoG!U>jOqHs?-W;6Kq?|L6x^{|R&ei6$KZEU~^me|9o4aRd479_xfQ^U6d zaep7v-jNuVdan%hS|mY)?ecW$Ru}r<-@ZUR+d4oyIz65ZR~42#YZ*(Z;00WpLq6nLKKrEh)C$Ykp|t-e`zidTK^$h&*A4-_G%^7 zjL%zXey?7XG%IGwX-TBs`Y1EJm<7kdP#e&Dh}HutpFZqVLL#u%;ZK{XQV)J<6MWfB z+H?ujHtkPgqw`Huu>=!1aweq7w;r14n8NDz+$hD=I9d)Yy^@C31{=PGDU9d!{j{Wa zXIajE4^&BlB5xcyLoQC1W?J>@DeTnvpDLE%XxaKUmU`9#8~Na!kiAXIYy)5L06bBBZF6RBTa){VaZ)UEbec zjuTM?Xe)PE@m|q~rpD;8=&=v0+2oNoAP>2_CP@$>MT5j)f55IayUp5PY9+^TC~mVY zY%B_|>H|^c9I){yFhBQ5yUASl!`c#-AVP}mpx|#I{$Wch%U2y%iZFp9K-+ouoQdr|FrKC6!$A-4Mv0|>?KU(T-cjec{ zykEH#wzgO{4ND}V)I5=(d!Ny@f#@{4G0(_IWzXIJLm(};E(?TP!(P-D<^_cN#&+B_ zODgNZZ>m^gLj;ad;prZ3$LA_3>_!8bz*^}ASBgO0D^1b+dHAHB{N>NH>`UxM6-zLI zqgu#GEgH!8C#SN2O4Fox7st46Z#RqBx^N#Q7J|Rp{(dkYHYk;~=;Wee2_|qH4BuLQ z9mo?Pr>NWL;u3+i7XG_cEYBXaQI!tm_^>b@59;|q_RV`EA_ zU|50)DLN-7S2yJire0uceSb16!4WxlaAEj%u(7zHCm*}-EF0}snqvtjr0ATyKU9f3 zj-|5bYgOd99mncNpqhE6ZwDJkCKccTQ!cVf^L#k?_TLgrbfh9VM+chRO^;*-Z7#q^ zzP!WApMod@6G+R}q=^^~J~8>hY#`!&UoqlylaY2%-x*5~AkA6K#2mG3h1r~rBXfo2xA14&BI(mvF4 zm>yGiz3Rc{w7kJ4jDa&uu>=v)EQ9O}$g2hSJ;x>nP&tM}(HVGGYWQ8Sv8si;w%+|5 zOAW5dB?%&=NR4Fkt)neXy}(|zC?&;kIBo;)N)5jYHgW|u)l~k!&m6Ui
      l9YG&on6(#qlS2S8DiO z@FjC2hiLCi=U8x~5)4Z)k(VXXzIgKf^UjDKVTYk_yAhTjFE-jSi& z-#mrgEZdS|2_|~@ZJ{~MFb*befwR@e_8qGAeUi%JGulc7)(ZQwjZW2lyY&kY?}iQ4 zqEDr=9g)oimS6(M*U%ET4b?8LOks!nwU!91g`;z*!BeuWwky$vhoyIvVrm>mCm-2B zdn^y6ww3w`G+q}QYvJ&X$=$7MRV=}T6giU?&rF*61e^)jL6u@^94(XY3+c(ZU?Zpg z<>a8}HMP}IF1&26H*kK*ZwV%F|4*B*ClMIC3UU$7j*9zzLXr{&JUMYAKFx)|4Ju7)VKq9`$|Pby3ZF z$%W_Y0xNe&A`v)pCW{*#RJ|eB;9ZJEj;T=`oqUr}+mb-KJ9I7B=tDjVCn+tz-!C%7?Oh{|XB-fjFN$c;p z@XI@7Lel!Q&|w7|Y4dd(|CT>Mqqe&6gG=G6umrDJ3P!VTJ0;1vCx zAA7rtWj*J@+x2IfB*BEV>Rjs1F4pC?3yH**I-ak~2V+kgtHCgg#?={u4b5Xt_R3@;N?Nt*>;8`WS)V~Idjmn}m z`w1snr?_)Tg4TMa8G!B+HNz*$a|5(;3!aY}J`rqyPt**b$R!CP@C?A|6E(vpN-;H# zqrvl0!zY5j0-vZEK9OMwCUE2oXEa`{tKGa(pRaHGOti|ni;Ct0soUM+7936DHCf13 zx7F2Z)@i^yZhs;XSnK$kZS)rWQs8#|?1W=SJhVUls?T59+o@QB2^?_}642aTTYJyM zOWg~VVo@A_h7?&#OOnBK)4rk<*7UErYC}f(@ID{5t5|{w9C1QE^{k>=ld~r7+gFid zQ5=7k7%_|X{W*x{o7e?xbUvO6 z%V2uu`yg6&({!-0_R4v6BKP6tn-uWr+v?8{d>hV53r0X+G+a50Cl2LB$eG;I&Lb z)aIr5h9@RoHA5z_*4x<$!UXT5@S{J#M(+`od6y|Z{Aj6g6-zLIqbSIY>gK^uR%pQI zxU`qzD;!fbxw}m~ZUG)6ADo*>7Kyt2FnswE@cx;=5=`K=Ojv;&TbEa?)`0gP|6C%l z){{>=MHR4NTki@sJ}#@zhkdQjpEUOqSb_<8U36m>6K}Sp4mY=Rmk6wNF~@F^7i^HZ zdm%evW_}az8C-{VcQm6|f(g7{3VV<@Yx4-mn#_ISx&;$hOKG@Uyn;S>a+H38a<)?* zJn6g-Pdfa7VhJX|Kcbb?{rT$hga!?G?W^A;0&9VH6^7ph8{l`j;ddF9U;;1Oh{3! z?su8tcbOzXF)nylVfbCJG5;8x$;o{9;x>i2Bte9dS zf(RTrLuTC-<(!jUc*1}OO?Bk3fTD1v1dA&u?1dc^< z{CRRBM6YxRCEwu-W-@1d0j-9&AFtSZsEQ?+z!4{8s}Ikn<-Oz2=RcV&#iBU=w7D;% zM=OJk@p=T{e)F~Zx~o4wYTl+w60}B&BThmNg+5Xf=lJvH?+!_^s1#*hnoO&^4WZU7 z;b7x&f#WL6?$4`@y{Qr;!GsiXl0xLLngI8a(d?lrNzjU?^+hYHx(}i0a~6P&>=)*# zt>8ZT6(pJ@L4*`>k}&@mbz?|No^w_aDHg@?r*+4DOV(0DXxd~wbKtFe9X0FN0RAjI zi-skbkk&GZ-=Uo9O^?>R|8B_3z`uo7Jf#?wlsmab9K7w%TUv@p(JPKv=ej1CuT~mD zFPrwlRn3XonACl$KR@eQRKpTXNGp@Xbb(pid$r}o$CZ`{tYv*)R$1segce@62W-T3 z7)DJ|0et+;T$&`oE1q~|l2o7akuI+6%URbFGJ&+@HOpe(Gw8bRe*Ea|KO{oZatNgu zv|Ufv?Qm5wbKA1+ZhpK)L}85}2_~eqOftS;N9NVKEzdUAMJCW%sN0R=;#kQcv{kNk zU?XhGAXa8%0AJ$uNyQTUyLc@V_KI4qU}`yEp12@~CJ|^Y6wfjsSMAPHwxEq4?=&vE zOrW`l^>j<|sUq~+H+pOTm@Sz-`{v8PR(Y*r3I1I?FM)5c8XRNC!u9hc!0|j}O};L`ujlN@9r+7MktL2MbGOaUVF@O1{OI(e-0-4OWQn6m@Rh>wqQdD#nc+p5BtfgHIDT|`QD%5i zDYBGe#!Hih;YGm)cu{6}Q3hW0mjn}1{742QB(sF(etgN!mkdjAGzq>^7+w@?yv@6W zUC-*rCymI#u>=!R{HS|TW_VF4vc%COcs|AOqF|#><0dTIpf0@3h3p(lFd?tjev8V( z=Kb58YwOBM1lE!wPTh-A!;4C>D2_kDS2_$Y3ReYQ)W`6m97`}Et;yw zi{VA#s=g4j+GYdv+Sd6XpZd216VeK+?nPC@i^>FAp#{%J4KE5dz>BJe7iCz2e;2Q? z!pSWo*QwQZw&rUq=i(B9R%r2@0f_MVYWJ7^eEqravJEt|0AEQBFA7(6?cpJ{QZIj= z+xs!Y68yV(mf`fGs^LYY`3Ig^fUl&67X=&OMODL#GAzLao@F?_sAhOkDQ?HHI`~Rz zcv0|h;6*jVi!v<11dh((pRwQ!6|NU4#VSZ^B2-NIfA?Ax(FPbj-vOh_C`iA96aAba^MtXZibK5)lO zfhCy0D=!2-d3(g}Rv5@F*<&OEYaMyAU*vorL~Y@lpytcVho{&{&tW`hz+MGQFoD-m zV06y^mHm9xho6~Ph++b3;dK;3KDRx~9tH>VE_s?s>m_(4#4X!iF+3LTeAyy+gMmS3 znKdqm->UwTVhJYj*adrc`_onLRRj3OciE+Pj^A^JV;}XN4mP}pfsH-KlGTR^!+Dcw z6DgKp0?)4q8P@5(x^~7OzUku$3ns7@o-ILkwC8=b!NNg&e85SGz*@My!Bz1i>a}yj z`3C=u3YK63w@Ro@{>-M9T@cCZRV*&GMBMrkw(O=6cj3-&oPc(9W%yLp%`1Z6tzs8g zf(dyZ^{m4VHRJ0DzQpYh6%$y?x_%|?a{>CzRx5?9;^AG?x`AVP@04!>OE4kLugLTQ zomH3Mv2f1T4~f89^33bzyE$r>>m&Ht0ud^%BO8^*U!nko@^7Dl=c zqwe~B_|1a*cw4W%dVX{`@8s#LN)q(D(u|CBb}grN+!Vnd7YdXJtR>CJNa{8(HEYpP zywu~F5`nekxmt?FN4?oSl&|}=NFpSy@RBs?`cRtuPS3#h*mOqRC>F`1E=Q^aNiZSJ z$VmLMJED1qQ0^YNSt2B@kmZ&|(5@1q_kj&_-C1JJmIyv%&{UNm2`1#(-LZb(l!Ld! zc)eU;0})sY&*2E^RXD4t*=RIB{&uxQNLsBvCyl*0lztj>2(D`WpRwlVlg9EJ1tU~~ zB$$xqaO7Q%igfjhkvw|%9*K~&;?^p|!G`sNKIa^euO)5VWGsL8WQ&}F!bVkD_xN!BdC_ncOE4kN zyqcyrVHFQX@Wd@#BCr;oU%?Er-dL8i{wO{pqo+h*EqUhETdZJ(N)O|Y7fhB2td$(K zTC~vn`E(Q9M~~OT*(o)gH@{dx#S%=w$|Tw=YWZ_CJ3lUhr%%f&5m*cF?+_BwVK=*Z zegqG*Y-jNiymgHN5`ndFWB?JsmA35tl_)+ge4f%TBuTs&8cb~` zr!>SP^?yd^m)+UDa#6fxq=!UET4j=;dY%5=YcmJb0PVDrwP-V%&-)6iSxABjJZi(& zfOQgB!$zYxH*b~3b3BIIs%{l0pzV_Rc?67V|4wFw=S1*j7Y|Y_!Gt_Z%{5~I>vl4X ze^x3mOkgc(E=oG)oyi*X9L@Xi;u3+iYy+2wo%&TxZ4Xyqc- zBocwoQb7_SX$@RT zyFl9|zWP_D?)DMtrS0K7y;ns>kOUKW_YBUOY%@>2(Qgzl6kJ*&uom76gL&=8CF-5} zVf<~0@)99wo!&~P=vS2`CtMXBGD$6VD}rzHKS&9ZU;@v=33>lyrF!eZD6V9O(;*On zweb83GPaJLr)t7Po^kA;g2y{Ns(tNwSd=XuOur6xgE`LbNOx9qM>MazBd;AxFoDNM zLRuf4<>>iyl6L%`X?9X>l*O7hR2+WkrS2W@#nPi}f#s-FnxAC77sKEH~Tk5-dvYISDr6A}iUy0Wqub0v}9ZE%`q3I4W9> zf1RZ5+`r#}C78Ii+J!ybJXEB`>NeU}o04=KY&JMDu&i_7f#N+@QCu+DkFoCu3GlX87 zwA20?2(K@(Ns^+U#(=H=llj(f{Alc#hp*&=0$h7s?2|E+Q5CSB?4 z3av*q`Um}eANpT#=fdb8Oz#)^-+DiRcI>nP{R0T-A10%J*fD{%;Hg`T{=s06rT<>j zHF$%6ZoFs55=>MnmRn7L{*imnNw87Cy^=}qAB&sMPr?M&lJ8^g&Wg(4&_D9;-EYPc zOr)=NQPVT~2iVxMW{QvAKPr@{DG^u;KSO8#a2Wl=0&mdye4u|Y=pVx99}HT)F!~4F zIrI;^(Lc>m<=wWKHVi-7*o2um;l{ljSk`UlwP-n}zq zXV|nC5j75{KUi#O0bYM;u4-&K{Hy<+_F%DsdKVByzEm~q{bT2joJlZl&`=mZbRP)g z2JHyM1{g<@pN7#b#e&6M7)O5JhyE9g8_sb8o&ZJT2i5z9-dA*g4_Pnm7TceJjfc~g z*fD{%juiA_b}>|>hjoWu+wk!V`$Zs*mp)?05=<0^evt_M1KKm#i1V-~eF38Q6RSjE zE%`pGwcBq#0sX@b#t|&R1dJQh**{<$fm!N|>dt4iwZO6@Oh{Vj8A8roQYFhYu+iQ9 zgjw$w`ZIwyNpHBjvE|V3#_m~0@e_gbOSa}S{|)zXq~v+&Sz&@~FUp!dff1*!?iptK zW;JU-*aCk@1lC$HEH~R!CRk+LdIUtC?0Sh8PC>A z1lE%8BeR{@v~gKmH^351=>0-}B6^Gb-L7WtJGCDZSPMVH-^7pt4I5$!CiH%x+t9}m z*l7@TO`qY;AH*r-rvs0kBT zt4dZ_1HK4XHL?dpeRtPiHQfSYX044TEWre{V`20Uu<@;RxQ{-5jC)Z)BCwWxACr&o zcj)oeB}YXCOE96wRYv~+8-KN`>CnfI_Nf;V}A#^sF!eEnhYIhj8`}htWSI0&7A4P>ucpgt=j|{T|#$wSN<(XN4mU zIm+0xG_S?;`y_34fk-ocA6N^&+25@M`o{q*!34Bp=M&NW{ci&LM}16SE&L3B6VN{n zVhJYnxXS1sU}MMWF#CJB^Y%NNn#j_U;;*|f8hqbG@tBDF4Ix$X*D`$v;@Q#dNmzmj z9DTq!MHvsxsqm~=j~Qm{eXvKx;}ujZNL%Zzk7_@xoxQOH6Y{9GXwE;5vtVQEs~9-~ zK=*{lN2oEPEHpiY`xx8jfL)Rx!dMRyuu?<`$#LY7`3l(ZdNEy&!k3n$#&Z+i_ZKUB zVB}nrs~Yr=&b=4fAAyZsmi;D4f(Wo-fz>G82D}gOS9Zf+nc(SC!(T}=I`CK2@K->z zINrqh2Fo6pXtxcoL#JPWH@F7ASXCy_H~QaGr&8(u$RqN%&r7(f>gQBD%&GEpp@?qXCU=2WIt^uqKK7Lrgk7dONnv6Xb z0lP2q^O5cxTB6BliFRm-zn&{6w5B(QdRvA1uKHv_v!$o|vMUYkr)h?ddVz z;@NZ$?Hmi&>$Bbh>jBQ_MPDhv?G0v-DVrSY;hpoaI}S`pTA3>r`kg~7S%2`1{Vv@3 zz|O1TeJrKBu7iznzW-m>aB4|32`O>euKV`+ep@60Ysqgg>mzSR0uYBn|CIe@%r8{2w)73LJoYp0+a!J%yE*RRa6?WoQuB~U% zW1mr-J+0W~LLxb2(Ixzy#Ln?INsI!A7g4VB_hL3#?f8UiSDHIJFK-Fma=-fb*$E z=K0ib?|fvFf7DX0e1&s_F@d$B>xtNBCly;c{cMp3EpqTI^UK?-%&Rn@&21_WzHeOlsRE50%i`fI3oOAzj~)Wf z@)ntAc~_oYgYOzxT^aq5$pqGNgowcE#}sm1KZj-3(;4wt`5`j zc0n?MwNlFoIEz(ep2d3q+((x5`lll_YarBQMG{Q>Q%^uWVI{Mw?xgr^{9)Y4@AwB0*XfOyiQ6u)+_p(Dct zCm~=0YZdM(;4D^{W!Qj-EmxD@epOR>)}QHTvHq4|;(mxoIC)edt3!ZTmDh`(-crR; z;;FYxU@d#NfRkK>^CVXiaG&yRu7#9~JE8I-mSDnts`FW8)?R+Qr7`c4zoz5bu&OeF zwBQsl0q4Dn%=2D{we#m;Un(ds0^y58EI|a+dKT7M&Gmm)^?^yN~zU@PV zq}6bqfYZf9=ILUVu)aLWqk_`$(q{%Iiv5yc!q#D_aI1M*A$?rH#=P$R`J@w#9VctO zmI$l`r+^7KomMzcrzL&259h--K6N}Pe^fuW_Ll?`P%&M&RfD!W9DF=kTP=itb}j4J za>^kQl9n%=Xg&?v6`XntUi4`=@Bid4N4e&+8JvgvOM(fg&@P~kyF!{Q2BJhz1pnSK z#NmB4ULvp-oHQojY+Sex{cPOtfzf=x-P?}4<7+Z3!9uaM z(B@!?z*=z9n1B<^MCJ)*$5u|_4c=aIyiV>bumlrOtpwgRymMB!W#`&qK#mT3I5n z7Mu_)paO@`D{w%bWkxtx_XIhbmY%KG=J+MS1XOSlHaD=5rk^1+A|!%u@;K|rx;|ba zuol$m5K!4e=#@R-G!n;f-m%qFd-5Hqafl=m;k#7WYQVD^R$gw%JmBnWncnpjk#;Fjy$PYhv-qp z!r*M$$3|Q1$M?YKysJKiiph$zV)CML6lw$rXN`c4l*0L(!sz)-ld%sr$iAibp2I3Md!34fPvTb=|?dR1Tj&&1Yto4QnI1YM_UYpoAoI=$F zL7?gaoa9QOP6M=E`2Xa~yi!`3>K3JTeuy&gZ{g>&s3(Q03nH`XLgzEZv{?&hnOgh9 zX;zrPTG5>-Ij=u;J(8I{#!LHr-cOkw4N(S`U;Ka0?u8|(Hh9(?^ z$l~!G1y0tbP&Y$l*3I}H-C4VLp{(*PxuEoPr6-zy9)%hjkk45gt}1Iwe=XnT8cEs1 zib@1QT2K+1lG@;XR_KvTt<-+nr1II6pc-$OBte9HRa*-LYL9pk$NlXeB?4$=qf7vtcW59}d_#POsXdKs_JftmlL0oOt$1 z#{XH9T@S6RwCoct6Ig3ram5Cn!TX=h6e@-sI7!``R!*97Y@$qHt+}%tP$fv{Re}ha znme2}P)kT;))E@iMk~%P)$^ERud)h-yVvH<^ksY1K~a}fwgV~SfG}W$gCwaah#`GE&8V8 zZFP87Sb~X_i!GioKZhFAaObyocT&xxTui=WqhtbWEk9s^T0$bTmQY0aY}K=SbtNo4 zT(2ecTY?GiyB4Uhs$^DJEq`>QdbOyFy=_BSXTSv3+WN%;m57A15)t{s0nmiml-<{cDqgGm{Qv9CnX(^s=_)0Ca~7fo)jt{31{Ua;@+XA<~ZP`yluer znn=GTnD{G%CXWJ7bVpxjs5HP!dvVk3a9!vv6IiQHIE9KzuxbNH>iX~9YP6zVRC%(_dpa{6n@r*kT~P8HQ8 z2_m4fHPjRW?{iI$;pntZ+QMP|9Ovp4mI$l`C*@N(fnQ{vz<>UGU#-gX5(>ZhQND9HCK09Vz$*a&UQ#@tHn3V-SK zqkc&+K_;)E>677ooY&70woif@BUvXp&gQdA1lEFDQWUCB3BCFhtQ3iG&39dzqs5px zsw6?btM_j={aLNk=LTKML})%&*E$M4ohcDm3r^#Q>UHp}oOSye)r!_Oto`D!nmtu4 z!35N!r!Q7sP)I3#j#H)51Z{emM4zw&B_#rDLCru4RR)D#We{dZODAcr7OQ>h(Ls9s z!Cw+gd@i(wrh|6AefOE96^d#2xq zi$3Q(3^uamZDGIjqPIj~EvTB0RZnbF5dqNpgdXlGJtMQiv6CK0`8dwS5 zM=pKteD#kBTF34=l&&{jWddngp{@*6dK7x4M>r$?T(}mWW1VAq-Z^?buU``UyYg7; zs1~8!wBB{N&YCF^SPRE1P`B^EEpxXYleDa@iksh0oh^bV%vA!D-YMxRgGAola}?r# zLkS)-LHKNdzk^@F%64LdB?4=Omsln`!PUCmX$(Y*S?|ryV1Mw`EN=&v zV50Eafg%UoQ?mIk5PjQjFh2(y?biC3i7iU8<%RW%7mJ1U*bs$)R+=MHkYkUPaIg`3 zYmR`}XLnI^M<5m}cg$EK5vN}&OW;1{UJL}{RK_SX0b+X4J&7PltHV@Ju@!7&T$u>O zw7E0Pen9+4RLznE5xX1vh(_=}l1J46BB#ee^Ch_R_1%w31l9@|A1bO&nX4pxZ3e`4 zQ>wWZ*zlTRGh+!R@cW1FKSEN?HG%M+Dic@>w;ovi7&+h39f(I_zd8MDGul|U4p%`^ z8_*xS;MzZV3G1iFmg;aHho=sJtD5UM!;uE}k-P1EiNIRWGA()w)osC|LDw7(Pp}c% z@tGM*Fp=!P!)yW@D^2>-^*9;m7zpv3qfJeTkhDUlS(58QTR6WMh{k@)?G1srb!ml} zAPFYEu8yv>rRZE``wr*Kt8N9;SRh`#`O}Ogn2=fwX@2s`;mtra+|pGdBrViJ;dJ~~ zkIWXh^FeuvI7(<=8%NC<@CJSBZj%VC1r=|F8Em+n83@F+zO&7h z!A6ZSryN*<37h&v34tD!P_aJ{TguEf=LDj{nu`*FwSr>vie}K>cDv62qK&_+`41qx zLSH$s1QW>>dMjU{RhH~F7KkHtY>u+Acp}yPM_}~Mq`6Sb z8)|wh1ZsOjC7SyAl$CJj73TFfVF@Nu*N4+Va35~RrU2pS^xbg~h%W&h%$UGh)BL-+-XwzBwE~{3zom5m*b}6E)tTfD;5x9CY}?o$m@-WX2Lq;Qk1$-E_!N6o})g z+av;ONxhjgEHv9`44N~r-1 z4|&ueb73HguAC~hcBzGTn5GyW4xaAzk0nekfjC)UnFH$4|B_%LaO(}T1^W4>ofCjq zRbsv=1_(#@5fXv5z7I`YXZS=Qa>fTa0^wP?O+4Yi5==l(vgkc38G05}qa9w}@dH{( z#?E&REWreBW021_-!errP5t zja}chK|lJ*+DIXJ2b-te?Ct#ToukUY8|;=8sr3)qtn@r!Q%Tvbbax34g^ZbH*}SKd zQ!CkZxh1hjZ<@TZmO}c~1R}O^q_%lk7p2JLsVbIWLbfqs*96Ue^xC13{qsl!*1}f^ z=a=*wq1_(W+kAYtrsChlS7`NVOOsE*)ebxgSM~7u5G`x>CyIO9G>O1km0X)T?`c=d zdqAxH)JHpi@|pR=^sg$GU?RCNrMCKT=PNz{QEh|2*7C}6<;-ap4HH~K8yn8+ zb;F+v_4gjLg%JT;#8jiCL(1rMHs&!kg;PMgLv> z-taHM`BzseXh#$u^Wz>ZBtp`XYz!QKS$(r@jPmpztYr*cW%29|HWqiH&h`X0^tVdh zr&?^ZmSR2G60WLi=QLGR+N-D^hGDh0ZRYxsBZ6_TK~mgM1$6u0}Z4nfkxr>aBqJXh}2ij)bYrS~NLx#{g0&NZk| zPQ6)rh&keAv?fUqK_>4s+m3oD){sCTmJHu3a@>2W{Cqx9CXg2N;)=Qry;s9---Rr~ z@8k^g_&bmxjU|X6x9{4MgK86`E>qMDAT5z?>@B2`%X!NbEy|Va* z^QwMJ5JBD+gnHW^O8N$T7T!V4X;K$ zS>yXF?JEky${ivkEy>0Z-!yh($vvgnOK2tRpmO*EwCcv~^tS7?p|@RZ5Au)v_p!wn z=bIx>j+6*V3)zNQQAiO!ZO>UH|Dui>$(CObi#M!ndFg#Z=+DR5?-HLXp7X$?mTU}n z{_wmDKljIK<--=}QAmObe1(MMi+IWkHuiTEygEQ4BrSA*Fmg_*$^DuPbac(n^nU*P zO3)SBo>dUmjou3BSQf5o>+||t>yt~YdR|{5uom2l^Oy9V40XxoHRGQa#+$nlcisE^ zl3>CXUmx}(!Cz(11w^~`{`^(hvr2vNi4uXd;GH;sN$;27;aYX&GxA)t=P#09_oBZf z_;+po%|vnv_}!!W+R_6O#Q!-_K~ejp>7M#GfwZ7)Isd!ft6?qNJP2x&=M%k~JOk1+^Gh zC-E05=`JLgc$DHDBk+ye0%$R>m&ke;roM@7}b^c zK7P#J`B*-Ve-~dN`MbX8&NfjBCWFm(>Q|>;W zC=*Ca_oPOY0YocH8MVPfKl1=GflCrZknyc7pV~E2l5_V0;#0&_^|JeY)GPL#% zBec#(2AW;7Br`0*M8cykG&vmZBW5-baWqnEL}n?kCQg+ItOX;S(}vzJ;i^VQYQ;v4 zP=;ok!mtDr-mQ95PcOKSKjB|;0oE}_zKJop@67MOvuYTfoxiKE2efY9kGidgF*qx% zcaRwmCu+mmXBY1V@1dD20Yb{UrCBpQ{w+apy<{5uAwM=p|fI(%1xmb#C30;Rhh0{IbBJ^68yV3 zT86mfpJ!};`V4jcr~oO_$Fmn(`eDUwPiG}?X9ut``1M-Gs>iEyE(K|l1kVSg8Oy*= z!K`Ancs0uqnB!mxnmgG(7g4PHJ1ZU9>GQ!tD;4TmF;*>@7_LbYM94G9X72=5%f_iM zZ2uwfeDIGKcH4o@N~`kvTKK`Tc}2&77`3z-p%E;>1fH>yF+pFHLSlwm40in_0&88~ zX(or@eRvH38%i(6Gmw_diz%y@>zjLyBJ}pM|>IgG0v@(HL5XjGq7IM6^ zk{s9uY&_%HwdJd(si%)Z1_YL%H3z(o0x{gs;@X3H@#>P+O{Mh`ybfa<>PkrxwB7I3 zz{bFBURr^+G3w8-nwlg*t18lp4%t-HOZ($loZ3E4CM2!DJSfq7+V`ShquJ%=TB%1d zYL+EXGYm;Efmfzr_2Wo$ZAraY)qAB(NLp4-ZKuFS+0W1iLsoRtc21kF*2?!rB}jq^ zyut>f!St?Lnf)`=H6LUGYbC7oqc#WFsBs)@?CdvC`y(`7eb*^T#S%>5l|uM7e9Azr z&WSj+oQF(cEw`lslyL{qi`~J|#*b zuvS2hK$;BwgZy0^Y#a#**ETecQ45A$6Ig-??7?A2k%Vh?3dXB{^t~Z@YV2!6^952j z=;wsNe2ol05Tb?Oh*6&u8_%!=6L>6vcfL488|ee>>ghO%z*>Rp0;ujw$YI!@AoJ!8 z)Fuv(Q4b~98J1uIkBNko_8q8|Pnn^HA3Q7(Sj)QAk0$H=V=u*8dPFl1aV{eQ+E2s~1HD>@>J}X`c32HR*6oE=dr9<1UyLRr1nuxW}oH z3I8Eb+-95TN_{oBj~CUzMz!k2wS|Ra)F!!_LA6aJK?IICA!cZuO*=>8)v!d!V#To< zjwYL4vZN=24gWS^BfgfVCPA&y4Jj~>!V*m2*q3Z*<)NlsoT1uBjN(#6k0O0r`Ytnp z{t;Sx0NBX4pNQQN@oL}B5nPfWLYj+^;)j1IAHT(^?t}kBpg9$(^2Dy&u(}Nd8|6kP z(})o;MjZ&}k^~cIeg#<;|0+}@#;Mao|3hG{=pu^K?{?}3Hab5V!S?yZsQK2yd=N`8 zApP8ZNi4KxxkkYJi^I_JRPVM-c z+wtnReKH}feq3uIY^$MNRZE9HSh{5(pEWI3J-*`{BS?Y?yjBCJAvO!+D;%-v;(z_5 zl_I=4RHIjak*@ozLeC)HT{IldjUFGP_MR0&u>=!%T?@YdSRBsF=9;Biy(UNm)_Oz- zir4yBdw9|zLWZ0U=dRCYsB=n<5?F!>9QzV-22M}jeKuAtb!NOoU@aUu!@TzHVE%3A zd9}v=vT{s~)-OXB_7w>Wg5b`BEl|&^U?1Kt*Ln5CjYTS!;K&=t+Jw~X-kWEudr6&e zWxhmUEnAbW!fiF!XtD!rRA1JCw;PzEUiZJOVhJX2bPlJ5LM_N0i5JuYK}F@58m(q0 z|4~KEo)M(j4!TkB4Ef4(%Z3y+B+5g>5-IXV>*9p$Enb$pcDkT8cvVXx@cKUSC@fMJ z!F{Z$4>q=)$-&28KdUyiTQy07e;2Lw!`Zmsa`3QjDQdo#Tqcl~?c{5PYzk7Wi<*Ot z=)e>@Ew`+@JU75m|G_Cr^1L7=Ax7ViIvQYRvmcyM z*OeZu5iCK3Gy@<_`x3Q8`&6~n2H0c4F*S~(+xS_?;vmJ%xx4fjdeg>~vucHPkcW&V zn82|%S@>$IdfelJ`Z&vf2&^?~jm5SqNJ)MUkr}D%by8g$eOA5Rva?381QR$qCkbv( z)lKlu=ZtM5$L(lO(B___Za>EWsUuvp9>BH(kMPabGOx;?BaNUp>BeetT>G;2h4mbzfz= zXR2>kS9j}nXDgFHkRf#YfXO{6^_o+Rp4Gq^u~Hf+8_dd(vp-sY6vn!S;w5J3hi1C`S6 zh(6l?jIKMSh13k76I|DqIuobz_i-(heGD}x=vI4A=`qn^mOy|Zw1f(3HbMXP^pvhU z;y(0ZM_*Ab5j50+s+aQFvO^>E`B{_hMYUA&$Qs|Adcsln;!ha?c%ml z8|t!;?2}Skt@EGM*9!+)3K3*rCS7&EnaV0$^t67S`9BP_O2HYzc>X>TtFVuZKk_Y5 zFHh)$RU5mJ_R&QjLF?~fRYe~9Ox=Q;QCL+j?>o{%K zcC->A&g#&?GX(>!UQX<6tNHBXULW>x>3R=q$Ba{YMzf~_Il9CSZR zMeVxZ%U)X|ig$WG55Q3$M{VwpzmbtGHK?dfvc!%`C^46buedtAody;{9v3gGXr4RdPn9<;~iqqw@N^N#fqrw?T z0fN7aqc-RCKOHkyaz5O7wYnGwG5h7}qTPXoqTER5W&E_mU_``x$*X- zg9g}=A#z!b{@$BdJj#7$Lm&2GMPGEUp6{S%`?+!e5&T^ogH^*?=iJv$IVgI`e;8<$ zVOxOW=Wr$TW*<}M=FkBH9JFdy6H{sB{I)Ai%)97U!uGs?j|D zKC*o~DHv##IHHB&TZ!8$;~)H;cZ#k>>!vbe>tc-vGDKcW{obw?T|3~QBL^e{t(qO{ zWCU_7QH^G?kKCymQAhT%zj`Z;2r^I;@y@U#4XNlg2eqFn8E6$Yu!j*>jC}-FVITkK zX4G(qgJ#v)VIzVJ)I?k_x~LiD-RPj=v$q+jeNgW-8`H!1P>Oxrt>oqzOY%l^WQl{0 zuWV@|f(*=SDYf=(L;AMUL2G(S23jTE>tw`vd@P;GK0=n%q6woM6!FVq6A@%!UW>=` zVYTSuc?VrfB^hXyxTJ*B8ej60sStsDnaFFYCgV%cwoVSZvE!p)pjF_#N=Djh z{2bYG*}R|gVGe3k%t03#IV?nwA@W*k`5!sx^kE03IGR;3&?@m$KEv1Z?rtl~J}%e$ zrgwL7(BUJ+EJTnYRIQqSE=l)3>!82+lo)}4#&wOm>I~yPcjfTpWD1X6uGh@q{+LkH z5(qMc-u3U1Q$JhnpbcG{2rY`)FW1f;0iH3c*|y&7qu%u^?zq_wdT}tsLIfEiucdaD zzV0r`&(V2-WC*K1Pri>)Nt^qykK9+|jckh@6nBragNR@z4f9&6+KZ*eU;OS~N&F83 zt!iiIGo83U&h}&B0CL+kdycTDKPnWlTh;Y!?>5?I=#_;J(CE3UR2mB2lGA+xM+d+#bZ!#4k zkS{}3t5g+7u;p0AYUz4Kp+!-D7W=c8oz~-H#w(sdb{G<3^_c0PhL_tIh#&*=T3lyY zFT_gD@71IcZ3P3ZDxc(Yqj?-u*~;;mHBb75SPS^QnpL*7jR-PO`|_@>;1J7?wa<|y zEd>LuP&xCCk^5z=x`+J9(fzuO2^eFul zDbtz->-*8^c4bK*m@k7F04soZo9%Z8{b|zHvQkrnj&^-(?%eHpj_rNf$BT&#bcF+c zlb_|uB##U%r>U#`b1ofRHLyOUCRR>SMM=jk8&`B7cp0wfS% z2z9OsyjZ^<4+kb&BcHFdV~w4D2+WI8he z8ECaB_aMX5AF4@Dj&M7Al%tDH_&c9}%RmGfs0O*Bas6FglE1+&Ia3MEAk;vr48~Y) zD>cTGleu+%qweDLqll}yErkf=%Y-seZ=TN68&>&KuT}YkX29&1Yu{Su2hY3PtPA_t zG_!#&yxNcaK9{f%5e$*>s*|swPIe z_p>B)}bgl(XX6_|d6p zcMU|4f$D>OT+M7{sTo33|4F8In}hADz)UC*N-4_E)`*A^8S+}ZcGvQyxwBdjZB(ZO14n8cgE>cb zGtPYF4xyT@ziBb5VU}y}VRtWnzW9uu`zB&a2AH$ThtS)%oK*t^$38K3seQlZFgqO$ zA$|G>IjX@(<|>un{UiIh@@63W*m}RKv2%0?JsRjBfdE5fsZ_19)r>sz8u9Eak7PhD z%T+gRK!seB-52@|Wgnd;PjZKs2&K(A(vd)bA+l8JL%LJ;upU8F{z+cRfLxXsQPtpS z?R2%PA(S#}S~(6vX3BLf$$7LKw=Q{Bm+lsi*IC+xQ2(xcstO{&z|oG^?j9c2>krna z><>QjNg@A^keHcDDp|p}$4?&kTS@kD>bHaXNu^L4laVwc$PhUv^(6ggeeHD+RSR=V z2IQ8Ow9?Uv=v_Ytgc2pX)b%p)_s$M2!gkE@qH8 zPwmP|tIIZ|zv_nz23lc0i0i2r_|V`v4XAmZeu9BkD=FMq$={%B;xPWJ>_sW5Vd+rH zaWI2M1R0nQ;_>|Qk2Jhf5bf-+*hU6gp)%kzIWiZZ?sMu>8NYa;0C3cQ*)!Z&$UT^N zm}f2O{_2!;vRo+DKbPJ_1R0p!VMVqzEA1=LkWv)xD;Q{nxf-s_ER>F_oerVefz1R1 zt-{O>#_Y1(R@cw*U$xU$QH_xyG$bL;LRu?7YhbjRaj8li10l5 z_fyiAjlZVL_X?$|P+^bmIQMd7 zNUG*pgB(AjlXf)>p&8@TS_%+kpzh+mO9$@Se;f&+pjyJrP3gpd68s!*zYJy{ z@1`zrKm0j_He}*DGC+i;!pw`>K67_MtvQWodZoOAf%%!hpnVBNxCbMD8p1xVZ z7Y(J_Q`1@k!QaKqi<)#klev_?sC=JuO9oh>QsX=I>Qy(VaSz@I${;lys595ngKkgU z^&P{jWvW@8IP*y35IQ`{ z54Eduf2fB8c>b~cdRnV_$xzzYFq44@GB7K`s~I1Dv<7_&qMD-%*vLRD)Isbc+F|89 zA42or9CjlEtx!erYR1?YbJXMrYPL78jVBGEmDE?M!WNoE=MScjgHH$sT49cZ_n)VU zH&3r0MC0FFmJG;|;F&C};r{7kF3&ccS{zgw5&T_LYD!J>S!{+5?nhG>wv!A{dUz%a z>#OoT%o4+g(TzD3H6r-CQp4rk<8RIz6+u?=#)5%XA}gX!bZl!lF^B{ssG##e#L>OeCepKqO=huxYPlwSK}WNkwGlxEszE;Ecj9=x z?fNkCt$bcE&OU3!!Vr#X#_aMsms-1xhv_g%_XKXc^s#o6{Mo|lM2?ko>X-zyj zUmdH<@spRiaKu0a8K^i}Eq$J@2S*Q~->be9473ubHK~2MTk07jBkA14j|L*h5QS zgeegGT~M`r&rf8H1YdU~jjJ+PGQdh`RP{N{-+Y2%fBNI_Uco>sak`w^S1!Q#VQB>2 zX%cNBf()r%e~ox;w0|{-#{9idFwhD$DzD09zhM-bH-xVCpD7urap9ap&QrgZ!p~5Q;Tww0oJebNl&KQCLR+wkxJVVXj&8lPjQ|_1xf`L|e zswb~UT^MTS927}sJ0v#{K?Z7V&Ir$3WWL!kgm&ENAWj}dE7aGX`zBVHLnjQTUxOwH z23nyySE~Gs5#|)ua8+GtHJ)u4e_*Vg^2uy>;HBzDmX|Z_#7DFFT+r8?VaYKrrPXkI z8~U?GE-jFJ3+;HH6}*4tinBzOc>84z{{Nln%m^6Q(0bo0H;tY9)!yA~x!p2piCeAD zEUYTUthQZ$>~O35*_rXi2)3Th%tarTR~HPl`fJu2JH*5Aox%Gi3i4i`nhRs}m&%=t zG80$Zz9$*^DTf=a@D>!V*$x?ExiZG+wqEA0qRTdDfH(Kmk|*PB@5 zxsI$$&x|HA&?>O=3OjK>KVOU4{0qHTghW9jt zcD0)F&dEmMwqT$Y-mb%yPL96j#pRK7c)=JOPu9d%kWap+=M(d0p04y;<03X9*#9jS zFSVe)w z=woihI`7@phApV#eoNA{&1%K{6+{6e2MLC-`ZCkbm4z8c zGI92!RsI2H-6lLb=bB>RS;goBee?ab2fvydnzf`cdBzGK9LWCnyT0$D?eyk6u4pX7 zJ__8=VU^k9Pvf3$H3b5U#8p%5`1|YK>P-b^tbLl*%EA{4US5AdFoabPm;Ga!6>e9? zU}jV(U($Nf*FnD@{lI_KzX&p1-^SWuSGk`ug)pP=h5T05Ag+`hm(D^4TDczdvFrS~ z-t9{3S?3IlENwlhepXN1mES@H84BNwY!R-qV9VE~{i!z>F(U)5T=#k zU0ueokGdJ2o0pEo>ZS|YSgwv)?YN^m+)3Z~OyW9~?7#%>wZ~I!g}2P9^^tC~YW7&Y zdPP^sK&!pC;7+{?ZM&Ik`IL=6=A<$4Bxr1D(Qc~Y(qGK-1&31CvSkEASV61v>EA1! zn2U@0Q2uIVE!XC9wr^&BM@z->y>Rff_)MyQ>~S;2UtEnlv$|m5lZzHn`@6W!+09~g zzNNgswmOdj=XbahD=x8xm3Z>Jt76O@O(*GsAHoGgp%vams8WrsXV%_3j8czjDxO^Q z=EQn-(YG9ll1Fh5Hafh}Z1tcub&P#rs&2XMKvot5ol|TVSYeAO)y{98IaLQy^RN63 zA_Lp4ZzkI}{R(${rdjMGcwD^sV2y*8->S*CJ6>`7@>uI)P2xf;Xc4X*jOk^Taq)hG zy+MM3?WR)9b|)U^_pR#+_K{&%5%Z|e6n*Q!V9RwcyF2j&zkRG+gcaTmsfx!GFpeLZ ztSeRLoyEvNtL1TfwoEh^SZBCETXmE&z}Y0(O* zUEPf4jx!v04>XYsXi?E3YIwU&#*pU&bik-cOSxuNPh@p>g;k!g5^a_DQg(a9&%N|7 zh52kMU?{XIl+zhFE72Y5TEnf|<&evM-r$k_2T_^BErP8 z?p6F*cjNc7-C+mk*oh08xj*o@`(f*1_OY+pJ7@nDZK&}6be2H6JHEe_arHg#QvDi% ztN<&p66AWHKY4}_Baz=k*XOae3gg`_o|(lR9&7RTG1X{w zLFy0|qc8UJmkhMRyTsJ_Pm|s6uS8L)4UJ5^NdVhTw21m`X0UyRhR~Xh3j{-0VT&lo z*7kbKopv-R;gu=c3ZB+=DYKE3agEz`$1{FpE_F`7sN9&!YfQ6eUyh`N$=yx7r$MxWc#i7H9@@@jLugBp8Il23 zuG|@nM9(~G{WN}#Jvd_rv1UAouUmelI?pYqA^ zZ|~R5hzp#@a~w|%WRBr4bvdrUE*iq)ARs(*`1ffu^)*~KdH(U#v!~(D)QYAw_NQgd zSnmQuq18B-q4M!OYHwp^R2rF|Y7g`wV-wc_AOZ|*H?9}mSc(eO@S*DZwTTS0!ZzeQ z+`BfEE7>Idx$|?=rRExmN4O8V@SGF-M%-R^YfBf(eKK07Xm&s_un+LA9Io*i(p&Fp zH<0%Jz-O_-Jtp|Zh!#;jO5WD%*Mx9IwcAwRMi_xSTDr#6vxOD5h&s^mrPd8X=*+Qo zk^xqMrDF}>tlYXA%5m#D+E=FvjrjbB%EwKYW0s*f>btsTve61#gli`J0x6`35A}~- zEf{F!y1dAUzruaq@EXsZ7vyb6{cE1mDgD=*h#*6@)#rDesZ`xl`j_pK1Ou(Yx~?!h z%F?5nxQ1nVKT0_(R_{nT)j(T=R_Uo^P<9rwXY{Y+?E}fh&FoMVW{o16y6GE78TNKj#3(FKQtf&}*E5 zG`tx|_TlQ>ke0l6P}T5uCL;K|*y^02FV=)UTy)T}eYph#t*+-?WyG*9Q600fkLqo^ z)0(1JbljdFOhk|&`{U`Ep45KFC4DT-cmo+|#raFao8_#|@#O1R2;* ze9GpW5Gu3ZLA#fwwvmBWjdQIsa(UjwI-cx#@$Nn8kLW9U+NNfhvw z{`~p}jSTF6&UhN$tTX%A-*GT~YZa@X`Bl(}AOmm9<2P|ZKPnRwtKVN3BN)O8?(pM0 zb$z!En-Wep23-k?1ywG%7X4}3?_|L0*1yzfw{ zJ5dcNb>}HM<-JUNF3!IUVFkA^awhdg5#2j}6xAs_-idEJ{w1vZ4IiEXxS~c^&qUFSLa5rFY#JG8HE`!# zgBWH2)nZWy_Hn!A=AS3DIA|vn~zlqzfF~j9wgjRg>qZ%nk35KxxGSl#8 zoej>gOb(=f__T!;w^wV<8~+bM2KJ^>QTwaYCf+A}x%UadKr8H7KK-I$5N&N1qaAMU z^KWAfZ|2t!R-(^y$MLS0@QJ$3Uj+q2p%vZ-s*X8b`q;e)+L3>wjrSE{OJf`I3U9kq z^up1c{@Oi|>wTsfdp&)dBZDEVphbAcVT7Xagb+HM^;f~bc2iknjd>|p6a7<;TlYXv zX?oPbK`nB>(X8YRUsm*rwJus=i}1N>m-5q34IK1oOgch_uzJ|XXmE}DJgsNHS~I&e z6*_lHAF5h_6d-~j+Uj-I0yN>oDIJwmS}+t^J!ob;JiWsmm~kBYD8IfS)k`}?pGxo} zo@@MzAOr7!RZl8qqKE;px@Dmt$v`W-nO2$gCh36f!zkI5bvE9Eg}o{IMpY;}OFwEe zgq}ZrAQ)(cJs;JCVqivJTtIdbk44D3Pd zC*B{GH#3EPoTwWH@{A=*tmd9j>->uYt#>FS$WO9oouO~Gn&!R9*j z@i1Ed$kKQ(89o!wxQt1)c-ayb=iY8Pv3UR^pLsLxdyPIuc?*LbIvXa(`)#cOua zZSoAFo7=|-hIn#p5tZrgAf5I=J1Tqesc0*FT36xBMzgeQ++mq!^I!Gh^gMlZ7w^>% z<8y?0J>HuOH-r_of+rWQy}59~5N(AmqS`EYVZW*uNguzqlg|NvyDQ^sr>AGbUe4sd zYFY7II?c{D>b>ASSir!ib=}PDJmb-#tVxx6-{O+pjJ4=< z)}#W#-|d*q>0;Hlmggb77dbH0e)F;lt)5#&GK5wA-QKJ-GlH|Gv|q6nO~#tkQ;G0D zL@=PGRTgC!zP!dV`j`JOus^WX)!|Y_%}?_t>!5esAD()J|IcO{qHjch1eS?0mlfpE zxoSVjKr7!{ZdH}<4Ub&P&r#^q3HQ;Xz3EoK8I7%r?dICJAmJguiA7>Pj4|1oxP2zJ zqVDB?AViQMT0~8~k;yo@A&5ry%O@DZ>aCC4(}r1Ut?;z&*^FlLe;kx|8K0gsW5##H zRVtouF9R!V5f$Xq+iZN!K`}!)QX>PcrrdCQR|nX~_}*@_+EiAr{rF7sF`V!5Xk6C1 zyoT_vRY!*%$amhm8q8zH=~~atcS|PgY6)#51Fc3?wqqV2b-VKOjpLjH*ki0)+lH=u zOe3Ehp9B9|HU4rhb7CZ)q_dZwV-!~({C{@Y5YL2vp(=GL-aO&&po_k>Bm=GR`IPPV z-0anGvTksKpQC#v+m*<9>N`BDp_O=!(61S+M=>!vXX!?gfmV&1+kpcPx?R5G`N>~& z2sKYF2%*fs@ovD}8EkKk)o|_H=H9~ZQrd3w4Ht2(L>^XApF9!nL#1EMINoL2q;fLJ z04vVD+TPqUGpa=7wuY8EtpiR}AkHD$-b|z68q>rMOTNaPSa^(~68hU=CHcnmtNoeb z_pG#4{PHQ?L$SUB23m2Z(DvqGnNg;QzZLY$B;89FB!S@XmKkrmM(_>YuI9|BSvAPo zn0vAw(KnN1fK_6iX?B+M$GO&|GBfsdnQ2sRK7#sp>7em$S-eLR+l|jQ^tos3%rumy zt(hhmXoao*J+p0kGuxW8jX_}d z<~*hC&1M>$>$SakV*`JQD{C55x4K05P=$Yv2?knmHq!Ryec8u?_^#I1-m!XT1D-=y zSYjvb^wxp+ehsK&j z&LRJ61?|SQIO~-)|JNY;>-0{^04vezs{h>T)(mpct7pfxuMe*Uab1QQn8`pZY&Smb z?QKnK7N1}?_~&@RKr3u@u4v5F&$_Z8MsJFU(apG)AkdTfO+MR+RqwbGprqM=O&3Wl(PN>FBu4zkWZ;*$#J_0*h6`?oF>tguD6ba z;A}?Ci{BGflW2wYki5F&7h+Z7lZ}?{=;_H0{;#SOt?>Cc%lS))b%M_dtDN5OWFY^? zKr5^^bgWhu$57t(q71nt2Jq<(hS^?{VX#TVFq8b;iM0KO; zc`Ci-bG|ht>@Fu5XoZ!hoVkmeZhq}FjP}KDcVnNU6;{x)7OmRToZMvuz58i*0@hig z6|#9&bZL#5^57ua+UKkj8EA!nA!l*cr?l?OZbN0=xlBax$+6w|?CA3~t@QI8^vB=v zCf0AF74{8l(N2C=+mXD+Qv8r$pcU3!^7*1^8d(El?Gwh4A+9+`(<4>=tv7sM5uZvf7{W@_ za?YPW);xMOg4!OPVPL%=_KmER9lJ26HS_Ha{p>bZ0z&m4)<7yz{b}_`Z{-ZXu9Kzl z6AWP`Y6nXd%4mIgHc6+u)X>6uLBaT|^7kiCOzEi{xLxFhnetwY?s}k&WS|vRP^yH< z{ms&RgHlMp&ax5^>mEhD=+j#V%=!I-sm}1nrl?N?D{K+Yuq@baF0U0#Wk3Bb7-%JH z2NOFTH#?{Gq0QsDY7#2i&`Q)ps`_=}&BA=X=0-+9ax zTTsy^Y6nHt&x9a2cQD)7Yi%`nnZSjF~+vtK264yd`>46EMMvMvF}6W(ty`{xi@pNQ3TqHZlA zTSjv&kLPK(H<1jq!U{q4plcyB(G^0|d;K8mEYS+8=~yk@<{2dK1u({^mJGBK6^-jQ zUpIO;9Kk1r1dA#?tf0g?Qoik`**`|16+`HU;5fk$R_ITqs+P&@aG*79+LcUS2EBF+f7xg>Tis>>Yy#1LM%}=hgR4(YD4eTb_G_i2j~5VfmU^~ zf^NxzarW~eSM)!d3Ql-H9!$Lg^S_|_go zkb!TdTG=#4&m2Bk_qfVm6f)2Xs~gp-1{0hUB1ceoh3=xF5vv$Qg_w#u(Myly%tWRH zu5N=$Fj3iX(Dp0A_YI%wN~+L8fQqC!laNS2`EbKKOOuQ#^@0t_W8Gn;q6sPjDG zb5e2yO9onr%CjfW-|8G?Cg}9LTU(;q3>llN7%K6&+jZqvj_r@TW~O}3NqYRc29kkR zSh1&6>!0|hreHcA$~9hCVTP4wSR1FF9-XEu6%3{)&NPC7tspDUip_kZk7agHNElbp zLCux05*2h$c^xX%m#ox3Zvnv&wTe(##pmfy%um^~pVhZE^NDhZ;O~n1#MakJ)0UB^ zweQXRk^xp&i^VIvt^MiX?TLC^)Bg6VKb!^xJUGjcwTK9CJs6xWJCD9_PZqf8qDn5v^ z2G0`=w8Dxco)4xRNeu@-v9F{otg(gxDb=xsCuJVH?B2f^41@|aTOKLc%itii2 zKr6ArugXq+qgyTEN~edV9M>$XP8S#7aO9om&MFF48y^q(=%lgyO z&wLspBFGS{ulxFc)pvLLQz?2W8DJ&X&zC>?QxD;);(69CSu+6)vCggb`FGTJ?hL1^ zZIrCbfE9jGQJ~JH57#BGL{Rg;Q;GF+VFhgdJ}$q~dC&RK(Wp{{>%a=199vqATYN_Q zCHRoLVpYiiE3rPzKb7mvDq2Yc4;{)~&!y|TsXRC{<;AAbw2aJ^nV%`nL>TQkWn zbmwPMm2x@9@jPnYM_xIOkMrBam69pBVp54!{W+P6=*O+D+nFnjlnk^IJ|@?jtnV#p zLHQ1T)?ytPSHrOl)udp)?=?dM+Vqjn%!GAv(bBjw?%9K-y?d|-SB`OoUsNrq(ZA)^ zVNV=XJ{PY+;>t0uKkM@kjF`nfly>T*of0bt+Y>N1~fq)cPyB?p-uc{LnYLvbx# ztcJ%A&uEs3caXZr{ecX$!qr}7Ch%KgOF8Kl)Hif4=7jR$PS@uKcRwQ_7jX$Af5b zr<`(a8?12UPpPr5_ZpiYhtj=gsRRS9aP6MY7cKoNA?weP)H;6zp8^Hz{gI=0diP@) zvIlecj&}!eE$8CfMMUL*LWb{JXZ+$gcVbgsS6A0={Oa`U6-CW`TWVa}M27IKT(w&m zQ!5Xpz3t};23p}W@mYGV7UsKeyn|=e7cCHMD_BwHl?Lv?9Gt(3T2Y;F1yuA0^d_&d zJa}qWJ>j5)Y-I%l*V5(6s5vaXmAvB(eR5k3uHb>yY5ZNWe%}0KZYyEZHT`B+8OcB^ zT!U7riWV_9Egej?YfP1E!npbl>$tp2s7|8!sX34AIrPvM=-?dJFG5#-}7U6_xup9>LLSIl)vx!vAlbJG&0Z%S9`h7 ztA<*89!=Em*YLVCuIj=Xv|M-o_E%SHYhtv1zrdCZSe=$@!oxd8SYIl~=#neD+PKz; zt7N#w#;eHnhge0qwsv8)q8b@!h3j~{!W$Q4mEPI+00gf)7?qa*Bb7Ne8z;!;pTJh-v3NFD!j1I zt~3o~pw*)XYmIzu`IipP=G`3mbBv~lpB~w%pI5R=u#cG@A4eTdwAwIrtx;q-`zVx^ z*MtY$j-qw$tF~d3(a1onz|d7jT0i~^9EQUd)m}iv2jjU zhj`m}MzF2MU3SLDFS7%ywXxMI-aD$^jqYk?XfZ|CG~F5zWT@!*_J#}mOHr9PioW~3 zy_HJE=o|NvG$O7Kadw~|`)FOxa21=`Ps*TUWVE@+)nGq&k@sy8D)+ZvzGUd(St5m zC4nHLT{}B$NmJVu#C199;qIK)bUjHo8KDe)(YHa(~T5PEK zpWVFz*+=*iW+cQcGC!XiuS-toLjpm@`W^1LR@@3NmosDDq{ZflA1CX8IlUzVtv2j* z53JF~9@uOpGhU9VXTI$pt6$U|L<$jPWC?YL{lk5p*HbB5sqYKpPRmL9`H7*V5Q&?b zaOPfPd;h()Mqr~^2}#@^aShio<7WdzdV(vt9x9u zhvb`}4<-JGfmXdbI9=>xV6f+}x}3ACzQk2E=^G9tg$Obh>~JO>X==x(^VANuDl=C% z`!!bo5Y9b_$hwctz){?51-Z||K05>b+t^71J$;_N_9?x0<7A!uOlJ}ZGCt%poPC1r z!1M>Fu=;Sqkxgf-(ceJ9_>@fPQ@m3d$AYp&+*G|c#ezYq12zroqVjrgkk4aR%E!Br0p z8dEA(&wlYE2?Q9fof8e;Kl#0S?)lCaz3WO2D@HH<>ehh?^Nr9KjBNP9@NE)r1Qui; zH!nL~3zivMJm2|!PrSN$u|N6tjntzwkbdQj z)$qn$H{X@=rYjX25v~84Wt)g30V8n!d?V~Mw@9%}Hn)|tJBPz4)}A;XLAekGst1k-j)xii*}Xj#jkRR?>{ib>+ zOU=%2B;IOj2Tq!8t7)H{@#})^upjswj`^RR-k8XYD!y~|* zP)i`lxG*~)zFn~W;jV}A+?{CG<|w6$pf2bE>2?Q8w z=Zpkb{a`!eBae>-IUDR*5Hd;sz2rX(v?@9?!5b5q(PHO$JnqxNZ1|G*W{evs8EEy>PIq8+ey>{dI=3<_FESUZSbcM2Z%ZM9jNkupXL;Dz zjxXyuxuwa@#pb6k6LnAueoK&nR$-sr-nh$*f(K8T>7ruv<+NeEt_BD)&g8cP-Hq+U zX8eY#=0BV^_vvWeCEI@(V8zkZ_QqXi94W7?`+TGM$~G-5fdE52G3ZFpV-sbR)hFEpFQ06#&%}h*=AaARJ1;G`$zt20Re{V!bID*5`Tk- z_!rdUbzQ9k6DR9%?KTsq&bO1!awKcVk*smN9XNrXw$>FlM{wI4+c_pKY~0`K_}658 zC_c&*2r%M1uCjaG^!!pBGpI{Xt9|%Mow7tO{qmo6cE*Yw_++tc&eYDeb`8%c6Q0e9 zI+*VUtkKhI*YuRW*CMB2pw;dVYixIA{-xD3dBkbhD$H8F{j?sEVS+{k8K|6+&l`~h?B&%bUyn0$6 z8~IHmf@(SNb&Or14ExB?jD4(~R^D3ab5@t|&qIhHLnvoe?oweZW%V;U$Ae;0Q=?km z-^q?E-@y*#(?gW1%6Wzg)(IVS$smOYFobee&+2?IZx%eOXMLzEH8tvJ|AO|>3LR|U zCv(|H>Gy84!iGO|sS~`z4H0ArO6hV;@ah zuQlE${-GOgWlfC;FoddAh3b{p-*Vj07q)kiIuR70EB|h1jfI`;GtnL`dhp#6J!Zh4 zTvgnb1Og19235k|yZUmS8@lQF22#U;Zgb75X=GX4iB+a&|Hu8Xj8yi@HJy8VbrJ|L zgtp@ge>2m&-_Ga^B{@@szXb}=HLH`6#P4ok9#5Y)xKo%Ws?&O-e{p620t}%BRqX}k zsYKz^y5_|^LMNg&blr+E;ym9+eb2kQ=u=JlDgSA`EL#dfL@@G9H{w0fXNYIFY>Oc^ z>E+8a`bm-hFu=;U)l9>;S_j)Ts3J3ptZG8JlbzA+tZNz(7cfwxa_jDHLUHcX`p>G8 zfmTVG78zlls5H*=oe%q^Jw5yOhyEC|N+W^{RJB}T>JvuW6VK?-!V`qvMUCtGdW{iN ziJv3qERI(j-u9rr-OuQHEgTvVWS|aKD)Cb{isuTUHbZg<23pPfdz~@Q^Bm4^mU(_Rur?(M71}bNz{iDyIS>taeBB;nYf*ao0 z&OYX3sz8z3{?J2w^IC`?L#T80c2{9aICw^nx?D`^cGT+o`8MAvO%8u09@}~GU7@c>Q@6fUR!^({r~Y|pS5|$107J|&)TYq% zR-eu%_2^JTYB*4599?a1++`n&>lLw96gjES^eJu$1Q3Tglq9>YKRA zLOR$Tnus7Hy}8y7yUlI& z%!e6&Rqko+YileLTjl0aKyuY_~$U3dB<*RQXf{b>-zuBn+cpO~&8=tKn z*}1pX`QaHo`DG))K&wF?*W2Sgu|4o3Gv4&=ZH+p1MsFNm*G2>xsIU1=T;JO|x9GIq z{Zo)&pcSffK6NNpBWv?o2MtPUE;Kdj=*0ai?RE>oY}cY2PTnPSuBJ7NcZ}Rxw@f2~ z456G=y~qAmz!5$Zu$dN`8r8D;GRr<1$39Y5HaK2ADQzu@a!|fBulO{Qe-UJ$a^{m; zDipFR{pO&%`BMo^jXFAU+$j6z;zYA^qJ#F?^++JV5L#OWRG(<@3Gzfg?%iJ_zwfE3Whm-xj#xwUC%!DcBrk#jp6f<%W%yEBES%{3_fmZ zlrG7Y13|pURv?g@c8yksFTYn|<2-$S@bzY${G@}LbTLUF$PiiQJU2J%RyQ0ps-0wD z2HLf*kdegC5g0$8eRR5gQ@`Nn=>Mo9AtD$!FHtjl{y=;AbYti5d>bv!KOi?9XpAy^ zWBB{Q9b*hBqeiXuvU%yfM*41R1C}l_w^WHzo=# ziYk*MpW%&(_V<`b-k8Wc!~R8(fr|5cOeAki6j~JZCr3WR8xz?F$3*hRL`xu;X-56% ziC5YiucU?p-NsSL@Ww0lvHA4R`VjAlvobcY1Og19)YMNmF4~iMZM$}=W+K0fnOlw+ z0p3``J~)=_@x~Gh5oCy*tS6T2@x~It5LO>%C3s^A``}n&cw>phvE*L_bG?|8^~4gx z8%rbutqO*@y|ILSbj?!5{FO)N7cU!I983O1kbxOi6;i&6xnjP9{`%)X46t&o*yFCi z-+9>BHSD8gxrt`?ZVt+syuKw6V2GTo>K!@3{4u!?HQT^*1N<$>+;UX1z43~DaJ(|T z@yZeiGDNnP$;}fk<7qJ8axn3~?@We#R8x!T+05Z26`D|}YWFH(8 zEpJS;1Og140ep{%mNzB}O^rI5BcJV!i5#yuCR*N@Xd;3PRL*?j;<-xJwTo3~MWe@d zgXEiSyKXnz_f`%ks!7bra<#gvl2y8VRcgNBp-T0zBZ3T6oJxh(En+RZ?N51b4-{Gy^=JRA%j{gLhrN26kHI+a`)GMMg>|dFADzwoL?eO>p*U5Y zRqxFa00R{#-@LfZZQkbR z=sCzoXi?1ErpjF0?)$a7U9t8e_R*!m6w{}zA4O#lJRy?$17w%9B8VfohOX^33^%zMd+8o<8Rq7SJE4I2w%U zX80uQVGkJ;%|0e}`=GbY@}tt7K59geA=HPOKPWj}+2&9FhaYJ~P>YoNeTs33->bF# z+pv$W@3Kfwh?Mltr`T9KQ5yq{l%`hKcH59>k*`;@1)33Uuakb(J9UW2?=jv}~fGVR%`PGq2!yV@4xIe&vk z2Yb##PI0U(?K$N~dv@P75J3jVN64gZ&rpftt5&6Qmp%&yT5)tWym6O(aNH$t+%*wF z2CCZcahJStSLj{TxEx&#Z``%N$6fNqT@w*xpsM{IcgY)fh2BMt%hA>F#$EQoahJSt z*F*#vLe+ZWuJ*=VQy`#mIl3C&xXV6f9OM%=O+T8`Fta5PV2FIF>O0e|f8)5DYm|@7 zi$cbeqpRVKyX=GGuJ*=VOCZ1y%31CHR!v8TS0(>FRBL*Yd_) z6A{!q99?a1++`mecP($+H4#CE$YpxsuH}upf`L{XU2SjNWgi@OEpOa45kUs#GQY=N z%NutE1Fbl^+TOU!J~-}L-neTbf(%q@-{Y?3jk`j_p>E^oYJ1}@f9D)`EpOa45J3j! zGQY=N%NutE1Fbl^+TOU!KK{O6#kzg73iZyF-#`Qzn9Ee^`pPQSg8WtKrx^tV1Fbk# z+TOU!rw%oGR>k_|Y86^@C9jPLGEkRtE$7B6)^B;LQmy;B1p}>6)$%&dP-T_)xjj{$ z{n$n=iu&{DXjZRAPg{LC?&Le~NB&@ysu4_uI`-CxAOjUASF4Aou+rZQp&1Xy2rY{G z(^X`?eV{1&80k>}MXtRtU$hRP0|D!`Kp;noic_gw1Miz_r-e}6H@k!u6)N-m7`voz zPdhN#F!u4_hr_0sGK5M*^6C#D$PkKCWmdb*cz%wTb?#|_K*lrhX#-mq>1iiTo5?;> zo}F$s;OF=$lOlltLnux)C?wik)xSQao|;u?QPiJ-8}GQ2=jmx*8RMxOcwMBtnLIL- z9uG@Kh#*7cGF9-d)aJFaLDXdn*Ja>uLB>;PRF(heQe)?h5UTIYD%2|~*0|j936~1@ zv@iJo&VSXks8xP#$A{1#xqS!`WQfe9@;__3i*#s2IY#6a473V-o6k8bcTYRZ@~!M+ zQnS9ce^e-qyq1Opf*DWDOsbOO-rIAEHYT%mPRRf(k(pH4zPz-Tw+*HPH?j+cuu8C< z+4$Y9kb49FRnc*cbX(tGsuz)k6d=eDxlA=OQ*&K0s1c>$vnB)sa-qI|<}eQC>S;Gf zJ{01w_Lb*tf1e^zKmOd9J{5bR5y9WZc?s{qs(Mf#927z?Mqd*%7MzRt zhK(^c6zgdxri)-7M=CwgGaojiVt?<^h#&*!B}$#0lbQs}ZqS_lp zg|b97$&t_LjiT(MQ_WgBMfX0+Rstx^z^^$5-ra!7-%IFrzeWq-Y6=x zDC$p+l>y!;%6}C{(LLTMY9WFQk(2dAQKvVG3IEL)wLuxUp88(| z86v~#iK3=Aib@7#XgTuP-YCjGIEtFyC~6{tzl#}GK8Iz%aa6y*rVQPlEAQ4wXx@tt zr&<$68;BqSXG==;ZE?q37TcXxzdzzc23q0Vht~}j-!{|l?oQht9TN<+!na4MQxEr< zn{S2FkhH7Zh#&*sF}~I6q01aKb2#ljlU=-5_%6l&w#AOP#ZUg{5q?W9hL1OWD@M?* zVtZ{wkRfM9&MOms}HCHAo;(BQn!rIu!+K9OWJ`D`PC3^7|$ zgBP|i(+r8E_YJ-Z23pB^R8;shGt0+*WHcP6(TA{t*^*LoPs}x!j_gZC#*7mToKv|5 z_O+GgIa*HT=U8GlG3SmMMt?79qy+-ME9O_~_k;P&Y?~t}>(ZW1{1Ub1Q~L!HuTUp=eqTS z=xHJL0SvUl85y5$d^UyAy~q&S-Fc~C2&)GF_(k$x^P@Ob_L8RqXjJ%C!4OuHmN~=ON8mfp46Xvo z)eJlv0~T6uF*t| z{>~W|{Z8KJmp|T@$8$b++L<#mXUZxBYN_j58r9sMQBB7*6fIc2%2Cbj8Pya5*SIux zIX$Bqm4ik#w`Ww-6$yM7*SqwKh5L)UJ)@dJpcbxo>7DIgYq&k5nnIwKx)P>Q&FvZ0 z6hhHjTG;6s)u{w3`02+cTs`7H*yD`z zEd8c;-n$Bwdg6bVrX)WX#(?Xk2E(`|2tSo{M4im>a9M#@-+T|=> zu)phVpHj3c+BQ1CU3qi3Rc>?6B$Ob5<0IX7HoIGmT5NOvTkDzo;@ZdB`g|vYyHEaI zYjymIwl3evq&zE5YlY2Q+D7_2s^|ksW7+K{R@Kf9SNR`GT1cQ)O7@#t41Fo89TPLl z9(0d+HOtJFd7y<7Byv$Y8;A&{bm_f};Zxl+zoFl6YBb712@>DbIwEt(Ii;74I((&f z^&RGVz_mv8F))i7&qCOy0^E55+r{7BT-vRC11RoNV`^sinj;~*zB%*!nc;o7f zWv-d-+b$$ftMjfcoU7pcWqBpMsorp-+52tIPGP_5C_!S(g#@nMq-{HQ5#e6j*2q>U z%5}1YkAVbgh3Lt$J!&+JCn9a+5&g@#OPsww?{A<4iCKqF$TWT$wwZ{t`{wE!M%^_J z47kh8QS8B1_;6*@F9T#}U!-k6Z3azAK#m-}W|8 zg2V!{*)>%1dij!wxG>jYP1q6cikw(gAy8}0tcNm>NT3$>8#;?)^|EZoFFTJlyygC>!d8>p_ABaxRFfvR8keU@ zz9f_T;4iWd?x~?$AI`c${8*feKVDi2DKpq?hv zOYegt7Or=-FEP#4hRTBkYLTZf*<)~dXhs%zOK)2!%31lx-WE!bIC=Z7xrNFRC3{q} zp(TyYE84r(oNuBKsFl|4fw`N~5MDPajXO^U7*%?H=KRU)pc^GfP)(a`SM0keW*Iif z@M{+A?0wkfMhOyWU7pI4U(Rxzh$lW_M#%C3uHV1;N=E{<$cM<1v*(}_DY<$Z3kvUX z7Mg!cM+p*@&0FSXD*2^2?okW+2O7s#%yBi^Z8wlWt%+-{a;}2+l1~xhrT<{P%Dg4c zm-WXOC_&<6om5$l{6)7AvHXiW&R%2gnirc*Pzcl_A0q9I{QyM=Pv)}@=qnsnrq%{Z zkXYJvha~FsbrI3BsJC_Sc|li)xb_B0kPs~sxUQ0hcHus_@Z1n<_R}fOL3g+6NT3#4 zKHYFj3%9f*mtD>L?>Uh`E$ju-Ct4n#=%$j%{Bn87)39YEk$*ACcgeaUpJ>us#onRT zlJomrn@Z=ikU%XevHTL}L5QIj4!cv2Tz2Lf*3Uu-64Y~L8k|!aYYX3VU8Qnxd5}P@ zw$!7z&F7FGAkVO4r{2hak+Wa$U<)NkSlMsN+BL_<6R|0&!>_2L!FPF1Wg2ddAM<$JGNpm;uA!2`?2;))jc+>vJdKVI?MIJ$>!G1u9 z{zoE=0=dbHO@42p1c_Mh$6UKf+p1kAqMUD20d! zX%=UJmemZDAaQc*HR(n3Z2OalLB0p|cjt1ru0I%{5UAzxT|6%#;(VL0^kd$`oYiuK z87M)5<`2@w*mKBviQ6+TQ3%u`A0q3D{eYa8xIOa{10_h%{6W?g%}a=AcHC~Qpn1u( zh(LuvEt*TP_u+X75$E3avx?BXq-*)3I!chhz9Q!()+3si(0N}c5~zj!Mz*Vrt27LU-}Yt#FA zmS(M;y(2a|Bis`#lpqlz_Q^D+hi;?xn0RNa{!`#oR|WEoNTAkS@}4}_K5dae#M$PB zjPe1MoqHYhLIp^WAdf0*n*1&iMIEh-GgT_PwtP`YAy8{>=r&o78e$(2`OXb7z6qS_ ze0OK7Tamzbsl>7z?2+g<4&4)s6A_zT`C7MjA%R-tsiiH@42Otb!Gnz~MHV^z$kU+& z3G!^R9PE)OzB^twT9AiJCQpY1YSDZ}^UQsSxN*6hF`@R4+Fvj08z@17ERZcRi9Hf| zhI{LsiCyB&qvYw3KrOOg*&ghjD2g-ny|&cngvOo@B}kCqeVv+6ey|21<~?zCyeD1F{;6%hxftj{3$B|C&x=baRQC{<>&L zC#QCWxI~{4x}f((Q_{M-MBh?6t+q$}p>M2uMC(PbhAI*y{+{bhvG;IAt}jQ#(n3%5 zcD+-Aql)&V+h-s_!cMoAfAVvs6e>@|%6Z51ExJA(SAI)XgcDx=b;t3K4&;OwdoIp08W(n;|NJT4(z?#r>~bVqRq; z24r5MmukE{dGaqK41p3Pj#qGs_r+bMHq;=Z?f3Kbgsn{+lUmZdYA8WMlyr)Y<;|29 zHHj!ut+{?^K~%E;UtubNT3*LA(f7Dn%Fjkb#LXu9P2HZHC*L?jC=&SY9~U$lo8pIF z3nXII<~jPwfiIF%<0)52pjONCnkco*HvJJ3nW`Ldp8jo6@D_7|N}$$4A5G+HVm3{( z6S05uBWEw~z2>@FM4$wSIpZ5qt|%I_f{A|nUE08jr5&{&M<|4%wR|qc*(0}^p9K+7 z{Mwvy^uLVG#{P2VhHXqRkSq@xj~@$zM*WF&;5 zg}DkmIcE2JA_^8Px?7}NjOc+a zr~8-ulJVojp#!ytzwhWin{HXvj!)4_$8I8v#04;-0D zCn!D<0=4pc({EHSPApZAZFeiwZnv8+*&3pw8Q!w=k}G9T*i7)d2BHuY_= zk_Oho)ALj#DFNbVE_rb4J{7q=u07peK_Nh^kTW@XeT9I4Cuf-$Hs474o6-mmD-(=4 zLCa7r=H0xmNw0{wuwPRMMeF=MDqkskq~N;hm1Do1b2T`pI}uZ#R5mVoPIA-e=sT1X z#oAxgvrA%sv9&fNR4u4=aXMm99H;TkF<-Rf@X%tC`L>5yqiRpP2$%s+6F1 z7PZAaZZ%Bf`ROmTSARzsn+v{I+Z+hh67yaf?5II?6_%@uLqMIJ-2G7Nmn&2BpHph- znSCB<|~W8U(^mQQB$!>dUtSNC+#iyD%Z`$CZ>*rYP(TG%37s(jSJp!y}&W2Xb@83E^ktv#(z1dtCR6$qLQ-}?z0oJWM z4J=n3ia{fRS}FG(V%s<7{d?R$z8xB1g;r~5ZEL4%qT|`%l+1Ze|AOShkyeNo!^&D+ zvNp0>{+3N8Knpz|z5F#Nz&haHkbaSb{)047i~r6TSLh`9x&UKk)`rHTR6mDEqO<;W zf?Q$`)qCP*r`WH#B1`+}qA#7iUZ2M$$`+<_WUd!rM0ILtEP4JgSkVId;`CH!+PZ$O zi!1XI5#Khzc+tF}v0`cMWF$~4&-PU3`n>&J<@0+Hv1M(5;mFp|SlpzRLj(+UipdAe zkfJniOReM-p=HdFb!ByNvo8H!PCHZVA$t?W5(11YZyFdCS2s}!)Pfw+z3un_;~Eil zrymVg(m*YxA-3p?V_R&UExu!s7^MPvTA2UP;K6fau6O*zA_Zgrz@@MayoD1KMX)sq+gMk#v# z`4lJLzp1fJlb+?K>{_a2{`V5c4 zL(4?-D2xP*L_!Qdn$u|9^QHcoS4{&)93+(7imWp%J$vZ)`r&Z;g;ktE;+z`i@S@6% zDBbsE3BAKUT7Mt`T0BRk-yD#0RJuJ7^guuOd#wH-t&O2dV5W~{60zm(=`-7H(BFRE zRwY17nWKnzST^x}1Go559$y=5vH-FmIk6#})CTy)uZ8Tg<{SGBafRCa3YRfAaf9L#7zu6|h5SSD6QAmrQa@H{X-agU$J@YXHN{~>} zcv8frFDlc->Q*6>>J!)Ra;A)f78TCu-4hu))eeN#C4 zabt8|efjmlR<&^>95ZBu?Q`Sw8Lz&!)>MC_)GpSWl3U@uWUua8>}~aHWT-8OWx{xn z7`A{SMS1>p7w-8VD?tKtE2@OjzTop!RwXb71T=Z|nbMoQXZ?%WaXViOj+Eq#!otnMIo!fQj? zR ztrlO9l^}s>;L2OP3yXB8?)t^uvHk!Pq|q2<1yc8(-G)-qyf6 z*D`^Ah5OUW1nDaEIL@@K?AYAAVwv=7Su6LZhSsfR`4j@RaAiR;%Ww9(TK#d?eW)Tu zQqh($QnWp~@+f~vNwXYm^&)Mf|WsjowkTEAnfb~$+VCPHsqD|$kq~`@y0<|!Q zV)f18c8Wk+{k)0=iUw;PO>$*2OTA7@7E7K6H>bbPZu2s`Kk{-kqrdYfO(ct~u{pCO zcv;&ZSC44cTHJu*ZvFpB`hx!6HTl29hem<5C{kplw3``-gz{ZTPlyebeS(;15?ncm zbHll!+$D1kLh0|JkGzt*o6*UfcFO2m92Y_kfz^C@vAQhE(a2*mD(qp{8CCTe@f%sTE|BMbA?(+Q}3-*<|EPln2*fwn3BI} zA>)4C%{5vpQ;a6cG;(mg#Xqq-Y30@AbUc?se?KNJDoZX0mt#$b<%*UlK5M7PL0<-TUsHx1^sc~=1<^q z#58_xLqgH=irB^FYxH6SrBS5vHc1?c46+N5D8%BYNu1urZC*sQDm49L?IIySYr601 z3=1V9HhhvKCL1N=kx;at4u$AGuI>L$1GKOX$x0pu%N9J{XKkQTi_p$W%ZhcOXA`&& zmONqE$*vp?sDvTZ7b9wJ(71jYjA*a4Ce18AM9DVq-T!>cBy-YTE1R65HTd@-X3B|QwU(4aZei+0`^$f(bKko_lpsMKRcl0Pli#JJ}|WoQj`+o`3{usdiN>SGY`L*UH6-VsLfoks~gI{8~-^er}t+c$`WSa-vyF_Ue={Qv8YF&-Pb}V^hoifhaT-wkW zbHuABGFKfdrxH?jsus>C5RIRJnpV~{iVqbzaiaAtsWsC9R{aP!uaN!`OgwW>2Y)M*MDpRq<`&5o& z2lvWcjcmNYj^DzP4?TQGmg)8vJBcV)FTDj%-G69D2@+TfLWJdep1`@PR=q?5))lrO z+5(+ODX>JgdGMlX2}*vU99W06{s{7sZT@oe7fS77o1=vaQ9Wl}Sy#oK!d~i3pp$2M z;>xXLEJvvdRnvPx&K^{9cdqp^S3PSluu*Syvft(2yRBd?=a>9B^KDgl>jc1lm*Cc2mvBjN}nD9%~$Ofccae3(e`N1jlCSs&@vh(`d_}#Qdm7F}k z61yiVG~Mn$RA1KaU)Sc;#_y&K&+RNlL}aBK|4F0L)IVqsHPRZ|d#;V_RJQFqvfFD7 zT{0&vH~y)K)-hURPOokmnkP2Clwa2F*DW8$BazX9?AyuuW%)v=Hwck?WI`gRakJ#| z+F0^CR7&>qKQG(-pK{bn+$(GMmG3z_=KX%k1KC&7cHR6>ITrN}m$f_epC)!p9dnh3 ztexi!Y+phQezsd$yVbQ?0!om;9MT#m#~zuh>zmfw$QR1G;{J!Z!rapNgMZ}Swwz@= z^>~A)9iC`N;FsvvJZ7wuewX_>5~!uLjd--{tR$YF>upmckVCZv=NHQo&z4xBM72bm zkttfIHCetIRccV1Ck6k^JMPx0+XGZ0WN9+DV45GTAjWHE2>*SBc7Vm=uWrg*6}2TN zk_Rw({9tRrwFvcplV>vAUKCYZ=`XG1mjai9$orW5UGlG5$g*6nGW2(3?)zF~qtY%p z61CVsMB(X2ZJeuT3*XxDTbKs5wdomGxXnNNQRXVgT{B^xZHvrRiyOabsD(7m`cAlI zt|o2xEeLZ$K3LM-JKfNzSDD^iU#7kl?u+&*5l1B;x6{6OtGcb}s=5)FR&{(;y#AM2oZUrQgj`Vs;|=D_KJF zaNJu>?zL>gSPOL6reFbC^3`3wwIP98N*#){+oxqepHOJLQdd|%L;suQo^a z^8x#(2cZNB^6koqh+5-vv61~j5DZO^T zE}xXB)FQNjQg32;_(Itphi#@(yGW}_z$iDiW|=L319qU77>A zSdagUw6Zk4Pz%=|3at>+Ds->IeK3FSCUuo)9YoU9_|=<{+ogxw^kp`C)RpQk_C9ii z0c+<~k{k^NS5KzjY77gJ?J;&rP&}=+W!rMR3VW*B9?l+lq=&orM@c(M6keU1KU&y;*y{Cz7mf_2xzIfit3RbxjQknLSo4~vrV2S_TE|{IlSaA>Gn#oIsB3k zjec7#dsMO8sX<7fmReVB{O`$ZIC%ZIB#L~wG=X9=vPL;-fLd4!6a$!()6Ol}xLUa&Oalr0 z620kkcC{>dNTWJ-)WTe0nWzOHr_X)jnq0CWfm%4O(A>v0Pui7l=2;0SK|+Z}iV5{* z$rVcpU;iK^Pzz(Ebe_6(V;S+vVc%&Jh127o+w?W2(rYm`Ah!Q@ToPj+=ddGz5rh6NyvJbX@|8$>+!UEc zi*ZF0QGx{4A;t8U{v^wBK6q1n6vSI`7f5MMVGABBXJi-Wl&~RzS{ds$PM6MrRi7`3 zOV00YC_w`4ScrX(bIGwb)6sQ-83eCodDX)0&#Pi(g(M!%Stm=bJ!t()Qci+$M;uegezj=1UIpdpw^cAw*uCvp4eQxy0 z@-{y0(#BvWD1K~~qJ6bR^mhvFJLdLIa4=E3NC*+_CwjBB8%1u^RtVIJq@6^*M}Lxb z7U^90ot<0`iz|NGsu7A%R-YdU(rP=ly8f^ZGYFFrx*FBu$iU5J~&l*n;189?ACylXx~rUbIJP zna1N1&Ev3y8TG>@FLh_Od?STtwbW}zmXv9Db?Xy|5+pD^iXm68DoZ}=Rc9L#sHNmq zjBYF>aWtZhP026VD_ObB6Q>%;!@?}ybB=v zV9NR*lh`xFeiN7N)U@ba}p^-01_V_CY z@1b&;{-!-uA%5MnM3&>Tm;dfizJ;ZQwCNSveA8^)9&y{s#R=4cy5hZb?t^qDgwog= z94Tw})znf7p=d#F>3)>hEImW{OxqJrMEO21sLT(g}z`HDwy*qB`wB0=1M{ z7tv2zNl%^j=7Ehz7j88!1CK6Tqu0OmG2^FZmw$)UCyybb?0-sY=O#x95^L_{kZ%s8 z#a$-v^FGfYX;)L`jY%j)Cu-zqKqqXFz_jU=w3BTlak=NTKpZW_kX7bF$`!9^*#mJ7 zsb`t=mYywKmb_*wD}iHuEa4~!YH^f}Jsd~fC<0l+i)S*%FP&+b37)6;(eSpM_p(~@#huN5`S>y ziAMspI9kYkkRxC8tJ5V4)Z#R*oLgo?2@+U7+PgcjNw&wKUj8x`o>4+9IY+rU4c=p= z*WT*>EbB^}^L;!@kl@)Mw-d$4iKyxHk$v!Gi3Iyyik|VeI7-N|!=CgvM+rkHvdty0 zA$NFxb1jqoBXw{YJ4XUD>IZ9KDMixxOQE!*EJUAqYb4RO-miB27N(&ReotmeVrcnQ zc9bB2X$x_?ZMwgjF{7|uXEFYZ;YqD0RvAAkmrQ~Rdm>%~Ex#pCf8e0lm5Nn!# zF}-uC>THRb3M`CA2@)KCTf#Lh_aMu!8^Wh|j0eWdS}0jP#qQ!(6Ak7k3nG@L6B?Z_ zSuW!x#+TlM0#SkljT5%5YSb{W)0<@AjGe(p36xUx$-t zq+K0&9K$<`vVZW}32BvR-#S{>?trj+@oZ0Q4OIUc+Y{Rr)hzFr$uxN9kM2A7N+&uV zkBt*_DuGMu*@^q41vIU3Dr}LyWYU>@O0KxSF)jBw^Cy}KoF47S(wzEOuq^qrxHEwq zZ|4#|qy5@Q@;b6_4_U=~ke_lZ8h@wBa>NAglhN~xav*_a5+Ze2eVMD6+u?y63+L~8 z_6I+e1IkCfudvVS0fT3G9J1N6oNX;)d=7f%qF z--2Osl-U+q*~u2qt+{pzpJ=?XW3FtECMWv^;n>If=82>w8q+<(youU;`a8YNvouPT zY54xVBaZD!_9EIxO?y|~$wcI<`5Ida|2x$sl|0+Tz#uNiZTBzn03(r`h zscCc>GFrAEdkF3^Y**ADlsOgmDz07f)Re~0lk75A7Y^D`a~FzUvl`B}6OX7y#EUM~~>2 z9gftNeel;E4dPLPB}ZEz(-!9g5*GrV!!HZpymqk~bobEzsk`e7+otSmv|mpCT(&0fB65pzu6WF)U9#HK zC2`ir&c5VhIWRpnjq}4c$&w#ybi>ByOFW+1L|QF*gMX*W^~aj7o#K%|Ej3r&`gD-F z%JRb#n<9Z4#q!a~vuvr7Shr%99ZQQ^G*{I6Qpx2msc12Glq6Em$z5bwCuCo|i!5!4 zX98?b8Er$qqIC6$Y{9g;1MD;!NG;Fq>!kYacCfSGOE;O=k0>6O9o4!Wj(|_pn6kNCAV;)#Udww$7z^ccagC%$QY&QM{4vUjgrc=?L@0fUd?jI9(DMKF13(AEso1^uJX#8FFnWRk+$1?L-|0ICd|n_P zEd#x%Y9+^p`ful%iS3YAI=4 zTbEmwJacc~c#KS7?P8RI#`BJJ@`2iX{Z;QclpulaPwS6YTVxuW4vnkMJJLLF;~NUN zZo?HBy~^aD9LgY#GmbSb7(fUB{F>-CWZ-ne` zOml3BEs*~vyQ7&*wn5vaU43zLpN%bzC1iQYSXaD9@7Y73IQ5iX2W5L?TWpWVTwzYQ z-*ei$15BfH^C_~Qw-hgHp#%wRSz3SihRIy9B_e@ZSU%R{|00bsjiv=+Ik2=y(;my4 zfznFuKhLcYsD-saE%=^xl_-rHi@NMU2@rFQFNzUUjHKdfl78Rd)otlT9~LcU zM+p)k6kp_?M!lN)$DYO$C6VQMb%j7JY=8Rg<+?p(?KWziKMvDSw3G_l1birE24aqLBBk37KfT^U`Lk$+qjD=Xo>Yvesh zIYuc2YAI3Y&{8$xISpySuxq8Pqm{LD{io?`oF8uotGgMXrLOLJ51J`subhS=0YX_v zi3^2U>V)4r6`ldAJ`V2O3d#&19d~``oxEjN>4s2e$_ zS~)o|F8Yx+=1B`@tNH&SP)ljSYB$U4`z|DzKTQlblvYE6#z8*YkbcU0!OC!5T&(9@ zcX+f)pcckX#HOan`VJ$=74~kBp+r@Xz|#=o$d5Pl@1~E|`W&YBWbj+41??}y!3thR z`H60GUVKLbSMkbO3_R;D3V8b%2gfd~+jLDkl>jYV-P4-$XrS>#ucB=U3NjQ45E$2> z-6hg&U{o=)6RAj$fLj-IH)Cx(BemQ7-TAZoCK$p|4P|ND*6``^mWQRTBJ z1Zv?rfg(ljZ;ie$4wx^d+|W^?5O8~h-tC(<(nyW>a!!0aM#nTt`3t&aZ8$MNgnqOQftPrS$cW7u2G9bbjez$}3gIA;z(?BgX`Y}|G zFjDt5cWwG%s0$@X;0X^}d6f(|nm)g-Woc2}jRa~bvs&@|#u($tv*l*cf1qDsd*fcqF<*KmtyxFI_DD+_ z@2EW{mjiD|68kyM+>kP;LXRJ)O&F@jg^5 zzOS7^a4i4hok3hji-=$^WA?N#vvop8_PZL-`Z(gD5OC*<_KKRi^tRrS+JLiz6aw#g zDeDBWXjOu~<<9x!&pQsW6bXJ8P96%OHLk4BuW%vx>t5k1fm(QLQ?#63TDRr9=Q#P> ze+blqh=mY7TW%+>i1l(l_&vhHScY;N6k;dzVy`vSwP^B1bN^@}P=aYFcSgHK2fIVB zEZ4j?j#CNLf)h!!f_ydDJ#qVTQ@c6FQg&aFP)>RKEsAp&xP3+|7DKg*-$E^zGt&M? zu$PtN_E@btw>e7S?76zHHu_X9Yk98L<}J1>*muN{nk@9w-2>6RO`z3dO>=E@Y>+~r zmbyPUmNW;gX>N8U5+z9BjR?9uK)DJ2H&k19I+sGA7VhIw)F82=b?aT2*}SforAXi| zfI2TZPV&Tf?8JP3FG=!K1daBKIRRC7rC z>TZ-Ep`LH=wl~5$@*uM_<>(^~3Di<|6bq8gc6>Y0{7@^>i4r8p=fkP{gwkWJ3;Vv* zVvGSg5{eeguc_C5JH}erY|hS}$)j}v5+v|sHvN)7=RsEGW^;m~4_gX>TI#%AqxN|7 z`b%?0`~e*$3PJu$dTR1#6y=QXX#F*Ktd?2xGLVQwEoIk|tvn)UYjfG}XjH&mL?mcV1UKBo-(J?(_m1Er zjcG;(-%_-cS@?>Vxh&rgr%k_QG$R87&!nnroYvQ`xWiVZYU8ibOFFo&!SCX%UsUty z;~p}(u(Lqpv4%hit`l&sEnch)cHb>u-#oaTUKmFS5;!9ln_t_EZ#uLxujjN|QSj;r zt{`#!N$&<;Xlc~FnAv&eO(6@lkj7K~bjspzUt`O_TjqtI&bpC6EoJ>FwpJfw^y`0B z+c|x#8zo5KJ2Uhs?4AhYb;<^_)t2H;Bv1=a^$0O;%>*O!hKr8wHBUQHf&{)sBg8k4 z`x+yQ-c0_f`&k_c)JlP~Ml>(U(#KdoD9*7YIZa0i5~XNG&nM;StT;uA3cRx!70ta?Jf(*S3Lk-(Rf zgfI&paEGjJXr2ris1or0Q7JfKOeLRs*6r-L$KiLkuc1hQpmzB5a+CPrW4G2*d)%ek zRS3|E!V~|Z;5(c3LEl*C1hpU%iWZ#f6rxg=KGxDnamhW+G+lrM2|U*+#E(G(t?;t( zS}orLI!chh_c`bt;n@?c&EH)$w-rC_L;|(&Bq*KPt`K3hzk5Y1J9D`UB}m|_A#_7J zc#O6CC)p>^+u)l>eDj`9{34;=B|B?{8s&Ob)QVNgZ=eJTjN($R zjz<{(6pJ$V=g8?q0=1OLq*y#L%qVQXt*!ev)Qtpc(Y}Ygo5g3->0Py_4U8QfK67=O z9blmZ3FQp5cv#QdXxFf)v+k1i3V~XDV}Wag;?niTT6eBk)n6g-#IO1)*QUxXtPW0Z*UlP6ER-Ojocx(YN_v$4PMa3%JT0) zZToOP10_h{33J-VDQ>yF+vj%u`PCqWP_)4EsXYo?u8~diYNM`CPzlgddYX7l7T9Cy zEbYz72m@cO!n+52Ry*S*EgA<8tkknFon^jm|Gj|{B-9%UMFa91GriVnu{%Q*0=3jv zppu>KjN_*cn0+Ss7$`vk?;!}$ckD>x*^vWU$f3D95~zhQP|+Q%ViCrooa;=pZ;T5i zNT_!jat|G3jG?-6*eo{^sD*ED(W$UW&5ZlYW|`&A6t_@<1m2Di;&KIVSd@t{ofoepV46!N|3;tJwjA{8R{PQZw_ak{}8CfK7`k5>3gYjD|lO{ zuJ1Pu$`wkGz#B?*lXZQ2YecDg+TfPn3V~YeL)e$_&aV(Z-5YL&Z+>MKdKl$K$$tsY zUh!_)A0%Sz=2u$5hfz8b{C9>H)1O|(J4U%0Sn8fhxiV0K1ecGaZR|7Ycl$>ASxw1y z$1H855U7RyhTdzVpBdK1P=n56#bOx3dID zkigS0^xJ1`^Xk59(zJ<<$EyUKLgAhEjN94tE0sfHT#nb{%_pTJER-nUg_A1u($q{J zYt=vXv`5V-)`#B$t?tSTv9~W4w}xHboBY>|W|krWB1Ad$@^Zmw>-XdL9Er6ix{*LF zFfvjM8o3~EtDWZzDu4vA)iPm2goNH9-pWXsD-adNS~;C ze4>RCB=F3P5MSoZ>FP>j?c0+P3V~Yq<^;uL4y<&yS~APb-r;)-B}m|D82a5l@(3y9 z8KQ$*Cd9}6W&;At58MNjew@9FnFy0p#fMgq0?Z}tq__v!Uk z@(5$dGmIS^<3tG(>dBhF$Rlhg&ro-!kAVbg;d=*kyM{bM%vJIX7mFJxK?2X^(0S@3 zE8TUj?{!q__Ps)&7WNz36VB1vU2D(JrkES1^e7~-uh6Z=9x=|R|73D~;}v1>X=R=p z@Qn&QBd(qckEvwoIdfmr7WEvY5U9l`r9E#U(Y!sbXCb5Ul325Pw^jy9kWlX%eA%^? z@jNzGyVk3aLZB9(_~!AEzd~z+=KYO`m9b`XpW`}8kWfx|h;Iu-7)O3MswMP`aUy|Q zd`g#R2J+cbStvn5xqBdH23UGxfw$&D+CM-7wUm1ZVoFF}z0=KF&X=XeD+Frs z$!snk-vy!@3Qc;tk8L_*4qr6ZLJ1P;4TU2UeXRDK_GlH1b_#)7e14nX3QNCHm1Hk# zRchsJ`qge^p#%xM7a~OO=_9S(0iSCtPR?~Bfm(c0o@i)Q87&2=PD3vXc1%}K|1R_EaD_lE?9FtZ`r)totDCi4)rlZ2liQXplC(@d z9nF27(w29=_>LJxgvWele78AK%XP4`LZBAD<41P^9G#3mbA50OsGP+>2@?2LAk9U) zeP={p%jv2<@RE)aB&gP94%yb|*6)vDhU-?cmM2SVHxj5tttrdLx02}h?xv44HU@ld zE+H#H2@+&IvgGNOSfqAYqfB#e?XkU)g#>DKSKd#&JkiJacF-QPFj+fFkf44e$Mf_a z)uDb*y?*o=?Ev*CBv1=q7Zl=`ki71i)PgUl*P;Xo>i=@ak?u?C23YQL1>b6G$TJ{; zTFNVl;%4twRzStx=ApiYER-NYp6Js{jKX>yY8CGpYnCAohY}=|bA%#azX{fuJ8|0V zUe{enpqBCm40~!Tb>dNzJvB;@AP+8EFnu)G*u1}$dqu1kNTUG~s6``#d_^$*hT9ii zTUqa7W6irX;-CZx8oT7olE)Mw%J(W{ty>tYU7@iG3Dm+jL1}cZWVxT`y=E?;krO3I zV1J}N;qEc6BmZP_cBau83Dm;gEIqaE@ze%ehR27S)O%zvVyh>QDlIYnhBSFZe{}aYe+X)1pacoL2Q59d@vz|M+RBr2btF)WbN1=w$eiOw7}IM_ z)Q&|jVK4eof&}^Ck9Xf`&G~zn(U&}R?b*%Qw|^v1i~5DE1-4GQtMB;EI6|JfQu9j+ zfm-Z|Jf50}z0vuMJmjgr-5+Y91PN{rj%BcQN>8nOJheig7PqEn-bKW5YV$+sGcpS$ zNT@Fe3?;kToA;U))pL+SpcdPhXGTV8)Fs<(u`t#=PF9Z+B-o~TWJtfO|DsDPYt)8V zt#j`}3V~YOS2A7^r8nZK4<@dPHJkVxccTOe4Qes@33$bRiSNFh)Q`y-t;B;Vd8eMY7bsD-_m`XJ5W0%^7-%@JBS{mDcMH;J zP@HNPB}h=M!~Ma6G^eHu{#w_b*PTe97SFG_f26;_@0quoiDV@xL4vGD-od2NfO55o z)&>Jt#%eaQL?lp)tWwrty0z12V0cCY3nfTUztKGJ4^SF38W^6@Kp{|zdY9&TZJLO+ zw2pd_J{njkL4x}K$J?j$sw1t{4%28rYc+*HE%FkYXKqJnY^QnRQ?ioJpA5H9f&}?7 zSywdcBjW2ZpIK>J6SWTqIx7Tf;XC`(2enRC&%5s(=PG5fP=W-_)MN{$|5^df`Yg|^ zkLPe7B}kAhOWWlhAZLA+XV%B_#E%4O@f@B@PP0BDXx3+~rCHws8gWp91dT*84ZZ

      + + + + + + + + + + + + + + + + + + + + + + + + + From c28cd03fbda3c1d340e6164d7100813859dba234 Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Sun, 17 Jul 2016 23:50:11 -0700 Subject: [PATCH 094/115] OpenVR controller can pick/drag objects. Instructions, Windows only: Compile using premake+visual studio, and compile App_SharedMemoryPhysics_VR Compile pybullet using cmake using cmake -DBUILD_PYBULLET=OFF -DCMAKE_BUILD_TYPE=Release .. Create a symbolic link from c:\python\dlls\pybullet.pyd to C:\develop\bullet3\cmp\lib\Release\pybullet.dll App_SharedMemoryPhysics_VR Run Python. Here are some Python lines to get going: import pybullet as p p.connect(p.SHARED_MEMORY) p.loadURDF("cube.urdf") p.setGravity(0,0,-10) p.setRealTimeSimulation(1) Allow real-time simulation in physics server, add pybullet command setRealTimeSimulation to control it Mesh decimation (reduce number of triangles/vertices) using a Blender modifier for Kuka IIWA and Husky Disabled the 'glFlush' commands in GLInstancingRenderer. Add VR controller methods to examples\CommonInterfaces\CommonExampleInterface.h Use the ANSI version in Windows file/string operations instead of unicode, hope this doesn't break builds. --- build_visual_studio.bat | 2 +- data/kuka_iiwa/meshes/coarse/link_0.stl | Bin 474784 -> 0 bytes data/kuka_iiwa/meshes/coarse/link_1.stl | Bin 180884 -> 0 bytes data/kuka_iiwa/meshes/coarse/link_2.stl | Bin 219884 -> 0 bytes data/kuka_iiwa/meshes/coarse/link_3.stl | Bin 230884 -> 0 bytes data/kuka_iiwa/meshes/coarse/link_4.stl | Bin 210984 -> 0 bytes data/kuka_iiwa/meshes/coarse/link_5.stl | Bin 253284 -> 0 bytes data/kuka_iiwa/meshes/coarse/link_6.stl | Bin 164284 -> 0 bytes data/kuka_iiwa/meshes/coarse/link_7.stl | Bin 569184 -> 0 bytes data/kuka_iiwa/meshes/link_0.stl | Bin 474784 -> 151984 bytes data/kuka_iiwa/meshes/link_1.stl | Bin 500384 -> 138034 bytes data/kuka_iiwa/meshes/link_2.stl | Bin 529884 -> 72534 bytes data/kuka_iiwa/meshes/link_3.stl | Bin 523584 -> 96984 bytes data/kuka_iiwa/meshes/link_4.stl | Bin 525084 -> 77434 bytes data/kuka_iiwa/meshes/link_5.stl | Bin 645184 -> 67984 bytes data/kuka_iiwa/meshes/link_6.stl | Bin 392884 -> 57934 bytes data/kuka_iiwa/meshes/link_7.stl | Bin 1906984 -> 75684 bytes data/kuka_iiwa/model.urdf | 16 +-- .../CommonInterfaces/CommonExampleInterface.h | 2 + .../OpenGLWindow/GLInstancingRenderer.cpp | 16 +-- examples/SharedMemory/PhysicsClientC_API.cpp | 9 ++ examples/SharedMemory/PhysicsClientC_API.h | 1 + .../PhysicsServerCommandProcessor.cpp | 37 +++++- .../PhysicsServerCommandProcessor.h | 3 +- .../SharedMemory/PhysicsServerExample.cpp | 106 ++++++++++++++++-- .../PhysicsServerSharedMemory.cpp | 6 +- .../SharedMemory/PhysicsServerSharedMemory.h | 2 + examples/SharedMemory/SharedMemoryCommands.h | 2 + .../StandaloneMain/hellovr_opengl_main.cpp | 93 +++++++++++++-- examples/Utils/b3ResourcePath.cpp | 4 +- examples/pybullet/pybullet.c | 38 +++++++ .../Initialize/b3OpenCLUtils.cpp | 8 +- 32 files changed, 295 insertions(+), 50 deletions(-) delete mode 100644 data/kuka_iiwa/meshes/coarse/link_0.stl delete mode 100644 data/kuka_iiwa/meshes/coarse/link_1.stl delete mode 100644 data/kuka_iiwa/meshes/coarse/link_2.stl delete mode 100644 data/kuka_iiwa/meshes/coarse/link_3.stl delete mode 100644 data/kuka_iiwa/meshes/coarse/link_4.stl delete mode 100644 data/kuka_iiwa/meshes/coarse/link_5.stl delete mode 100644 data/kuka_iiwa/meshes/coarse/link_6.stl delete mode 100644 data/kuka_iiwa/meshes/coarse/link_7.stl diff --git a/build_visual_studio.bat b/build_visual_studio.bat index 56ee9f610..0da0089b1 100644 --- a/build_visual_studio.bat +++ b/build_visual_studio.bat @@ -14,6 +14,6 @@ rem cd vs2010 rem rename 0_Bullet3Solution.sln 0_client.sln rem cd .. rem rename vs2010 vs2010_client -start vs2010/0_Bullet3Solution.sln +rem start vs2010/0_Bullet3Solution.sln pause diff --git a/data/kuka_iiwa/meshes/coarse/link_0.stl b/data/kuka_iiwa/meshes/coarse/link_0.stl deleted file mode 100644 index 84b8ea5d21299e7851c23d8665c1d2724e88dfcd..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 474784 zcmb@vb$As=`~N=>oE9tY?(XDdchTa60!4}wg0;8>hvFK6La;~)!68T~kjzdg?zFfU z2=4Cio0&6v^4@a}pXd9>@42q$x>D}9U-}OCxogFO|3CaM zdocq4n`o3C8cyFokJVm&YU9`K`a-(<-Aeg)v*ruwjxw9%-vE$_23nA~SSgs+%e>AD z@utfxI=|}zX(_dK2K}wqGWqv-M<{LD&-u6A2VQskwgogODn=4t_kk89I_(Rijh;n& zDHRf^5~W?(-|5d@DzqT+pi~%Lk;|J8Bv6H|VE2I*B*qmFrRQFHYbzvB_4U?8OZtC9 zX{njvvVE|h?4?2r5+zTEQUB`;y|gY8s1mJyJASSgBE#zyG}X7xQSx1v_4NGF5UEP_ zFq-~xI?M}!79@_;kEI#>XL}*GjfkLU_sx)&h#t%6JUvwY{dEE@NW3o}MTZ@B()PAO z0##UAJAwBg-d!*IE~DT6w#rLA(1L`hU+dIy|ARnPNGfdrk8r41&Lyji)fcB-h3c|DjW;;{y+;7MfWVF%Sw3b zb0koOBgXCn+a3F(PKs#yV!d-dwi9SULX5XO<2QI|D~`60Kua(Mubbdhvk-s*)9nbFFZ8A80|M^x9Sb4+N@&?{t%*zEUd7f`qXzmIfdF zUj(YKH|_O63lc9<#L^(IYb_F}`uZplb7F;yq14)!^f?tK|5kUi{M%kCw21wKMW{K( z3!zqLX;G`F{9CM#SNZB7eA|8Cb;T}YbJ+z_^>rU;K|<^wZd_XE#Rn3oQY)$#0xd|0 z{lm1ai~a|JDr^ON&C!B{*m1NzztoElBvAGB)o7XmFvs2SA@q2_aG5o^Y>d8_2#UnkIl zgxGOxPwu4cZG{A?u(Wmp??Jq~#O@IuwZ$7Zs#4h7; zDret(y$8{PgxEivOB?H@R7jvo)QLY8c_Gk(gxEhES?tXR5~#wlU~gTtAR%@fb60xn zb0koOBgXCn+a3Eu>?Nufbk4zc0xd|0@y2)IUfK!?REfPrhXdYxpaltWck$;0FFue! zl~{4c{_dQ$?e)O>TVXy{#Qvd0{^kFJ zK$Y5kcp=b&gxWv+4+2$cPvnI_3ld`gu#|-V4+2%#o1Xn)jRqvdj$^aewHB|1D*Gs@ z5$9v3e0|ABD^wiVXtb&fcitVTG^{*%}uKT85apxr*$Z@J{RmBz3N1+By+TNv2^G!KDeLRP2NJ0IZDcIX_GXsy(It8s-CN^8LU3YAUDN|DNZ?vRNOag`zul!K zOCLy}>TbD(^mOf+%Ezp}#kI-li1dLLB*dK0BNJ*QZolE9#}DW!eIS9V>yPHqK7-~e zA8X2N)28G)DBB7xNZ?M5km`Xy>O<1ykv@<>RjK5&Xx-`yl#fmyUTOYmJ4zpDu@TM) zo2tisGD&aNxuYCcNZ{^letj8}Q$D&xr_w{uwJ0h211(74E{YK4gNkv51geDZI}2m% z^`OEBT9Cjs*wt31@PP!XL>unzw9eii(g#|Qz%`f<)#uU&5~vbm;m0|fln*toOi>TC zAR)#vkIAV1P-9p6Kmt`_O#k#tobsXW59tFfNQnE9#{iTMbq`7(NT5pIn`bvDAL>4r zZG{#j#Js{|0Lq7&OQa7ZP$lM=G=8g<4>ey&A80{B%#Zx(RryeJq8wL9pi0b@r4~jh zA8OuB5dDD`Bya{7eLmR~tB5u4TGv7q&c}qr)cTPLBKP`ljUV!E7EkW&CaLJB7Go%s)*0)X_fXN%Ezuhd|A6C zAM~DozR=Nv#P(DhX{rkRS&G+>kPk66S%nGPb>DP34J1${S|O?Ct-Afles4ENZyEVY zM+*`oR>#pMIm4BYd9giN?A|xpl6_Zf1gfyr3AuQnjrL@EbE6h7)%%PK>7R+t)?Gbt z8Lg0dhP*DeIwAQ-kD|YacQXQb&C!Cyo{$Kdcx<{Vl`rXSCT{CuyypFZ1gfxa2r0Ma zkUnXBd87NPd`9LC^XPz*b7i~7Gzg=kFFE@hOUsE#zinlgWvGY`n#Eola(&lE2EY*d$>8^3Se=&XRPwp19%-7V zF}4jTZ)D>Afds0sZwL{k+7yy#iu*$l2{G$r4TXtDI}JBQe;|P>>>EPLI!7WCBTI#A@o1d# zp=Jgq`U5RUh&$@TKFf!ieV7=DNT3Q^osbgzu6=#2BNKBXT96QT@R^*J4>dE${y+j% z*f)d(^I0@z?;9GYwkX*?xLy&WW@=OPAX<Jgjjv9gsrxE@N*INPv=5Rtb<6P3j3dsGN;lQBkTTQ9to;%o8fTJ zh+~?NBMbNH<3Gfil`D3%jdmn(H%N%1ew<`I zK|(%8?AGqJDlB~wy*|a5qTE)2k=Vid8?!{y+j%*t3LO58i8*^Vuxh3N1+BZjg|{x3jP%9mAv# zBv6GTl#sI_AI!{Ci%1`6K?3)Wggkg%g!wnRnIQTc2~>%HPulyGnCZhNr0uMU{y+;7 z_MPRN4LRA?F0#%}) zlJ=rmCM-3de>@|7palupH?F9`!?-|mrJ2hR^*{nuV!T=VU_zEFR`?FI>{aQBjyqN~#fT96R;N>bEd$(lv_s5zOX4K}kHc96s?==`S6ItDFRh$)>b~;<8V9zAuUL# zxQ6oK9*46CRH@ZR`EZZJ@kolaAfe(j%7=R#&LU8yR#D}{Jr2hsLeheSiZdx6?r}Ja zK$RMa%7=R#jz_kn#YRA;n=3}s?t|Atm70l^57i&8I2@n*qy-7l|4I2i?r}JaK$V(N zl@Iqg9G}Cb1qm^Zt=unH4A~Wjvj|kFl|lJ%kHhh`NLr8(_hVA#nR^`0B2cAPIOW45 z4)+ko6)QK+71K|O!zlt)YNb{_+~aV3Zy+s5i1{%oPsTkCXA!7UI}YW;Jr2iD zMx+G^oWVWga2A0o``qp&4yRdhIKFeztT-Hx$;rPx<8b`BPg>LygrwCTRT1uSIQ}&1 zL8xaDNqffOECN+(kE(pQ$Km*su(Tkdo{*Fe_c)wIpi1pgl@IqgoYf{ss3$$;!#xgX z5vWp6mWptX!|^zS^sb(3rAj?zs8YGd;jI2ZLOppaAMSBDi$E3jre_?EM<%3q^}H;v ztDdh^sodjmRy~kVPu{9j?r}JaKo!=>GY-dNVbZ&b+{o*yU6d-7mpGgUp<+O)R9@n6 zl0cQ(cPSt4aX20w^dM9eNBMA%!&wBX)DyDu;U0&x`U43SHBvs@<8T&%D(oB2I2_-f zOYg!5k0HwIs(r93m3th{>JKDDyYVQeDwTU2&LU8Sz3CZ;<4-2iyC^%42+QlLCjeC{ z_c)wY4Lla$Km*sq6Z=FM;<*_ zrE-tMSp=%oGo13_9*5)4gVKV8xTAP{U-@v4!&wBX)H9s&;U0&x`U44Z2lIHl^5Gtb zvj|jS-*}C~$!m#Ol%ILXzg28NmC8L1XRTyNh*_JT%BWJQ)xZ^pvj|kFCw=9^Jq~B} zITB*^;ipT=$3nL_oJF7tM~r72&bmKv&uAa*?r}J4>>^>`S-QvJECN;bK6j79Sv`n^ zeP`(&hqDM&*~hMX9L^evNZ5Cl?r}JaK$ZO-bdSSXcN7x#ouzvm&LU7{A0_T_IIGW* zuSR6X6XG6+vj|k#_oD7`IBRE#gzOvjq|eXp+~RN+fhzls%smcg?XQp!W6XNe zC&WDtXA!8f@2}kBaMo@K330DjPx^$o$KfmjRrXzmdmPT%Gaw=EdFx4^5cfEoMWD*Q zTXK)XS$iKO#N1^)>GNk!w>X?dpvu1M^Ad-Xb2t+AsDYO_oFq_X-}|`7;jEb&37muZ z`JfSQCOh#HtA751S^I}gwCIJ=+QD)ux4zOh&@MGcX*U}Nt|0sgvhEL~w7(BF@g=0z z^^NBK(v4Z6&pr$-NYsnlK)22rsjY6@j1wIK9?_4(elypkAIg5YvXOqyGgJ#&dDnMe zkxeux%Mfi>#;3l2=iE#W_zu-JlzYgD=ydUP>hQJZ;kttuT2fw$qZtE+X*9!4U%V0_ zg^FCD{sH^UzAO9Ld?2xSLmd598?GI0f0_HJ_FEM*`pPBq+ao<}1ggI4ypawd!?pYs zcW@$W?!4yR&4k@P-GQM6iA{lV^j_Z)+JP*)IB_`ZX!8@v%1$>AR8I zz4Vhgk#SZB^W@+X?8=2&3@u0;yuFDY9~-3U6~}O*?wrMD{!vxfipXL%0#)|@Xb~~i z3>d4iOoa?$WeiPkYd6afF{s-fx>m!j?KAjgiU1|B`H7kq0M^NGGDeI z!?2$lyxK%}d>Eh&%;Mv~o+TvYo|X`?dJjE$V!W--k%&7NM-$f#l=RmLR82a#nYMgl z5rj;X`931&XJNhcX5xT8+IMU6YU1x_6@R4#Ix>g&dx>KJz5eqj`NoKyxDhy>d!H;- z{BLUg&1p^0;>vcyvWV*<@%xf-TK-dQz58%ocXOYKbVmB=(%+FKlW6MIzj^WT@TYv# zNX)JaADO0aOlT6ETmJo99!<*;bYJr<71rD;3ATbKf$f8YRj2=(uvEfFxmv%{u*K`V z)Wfp4x7F8c&IwIiOAuV8iS|+T_jOc|eq+$_jV^iV56dD{R7?@B2+M-k6@Qm0-AKz` zZMzpA4VJgnsuuoL-XEz3cck$Jdda`PPFNOkT_oNnZ$=X`t@7dn2}|{V*TcFyg{s8t z?)25H`m$8knD*=s%i>O0CH%h$OC{)QVcoT^v+H}Qhh-5eB&;^{^ik__NqTo^HaSZ0 z4jx#&GK~$%qI(jSMfgC%8ZrMjVW|XtU`RE3Y-mO=J}iq+Az_VaPanJ8LQRxi zl~5D2k|)8-E-gZZ1oy3ZFBKA&O3-|^^Aoe3rw_{_R7hBL`o9TFC1}c$7k^zcuNNPd zMW~Rl=3wE&`rkx@pDt+DsYRY^%d}sMIp05i(|4IxwdPmeMRpOW;%6aR(iw~8fv-FU zs=5sg*YaI-Uia$+T9DxHM`}Nx`pR3_F7K$~r$AcL=@OO-Ym2RLF-5dCzMwZBXhDLX zo@hy@GUx*dRJC{-tu;H~%?DbL;HM{A(y0vkKmt`8gJZO(zdPTlPtuG2!1lSnZGkqW ztn1DDue24mA`)%)g=yC=Ip43g`#=I!{6tZ+&I;`WT9C+GI!tqH_4XDv5~$)Qn40w) zAa)<9np8YgD|O!a=JnSJv>-9V5vpD3@s;1paCt|SD6RM3{XkXDe?zr=^_}lgf1N-J z68zmo?c#&4{8EU^JE}xKdH+?FZm(BpXPEO1doix8_w!RcjMj#~b^eNry>-!ogc!%( ze?dUpMb__0Ea$Dce4g`{BEC+b1&MwYqO{q`z5UJv5~#w`+UtSsGa>H+?PDruD}24J z(1OIFiwm_gX}$dt0urbaGv8N#7sq8mqEzG}jlTh^at)GdB7aH8MW6~>JxMQS2DBjI zzh|j7Z>6`^MFLgWH+CO5uCAqz)n>nNj#nHpb^jicn zXhEWD%qneDzU5w87YS7H6J^)^Z}))~B>4M^{|^MJgzu#D^CT}54YVMUcVDblk9_5q zDO}e=m1slnD-K$aNXdWmW2M*C00~rmeU19kAxg7;pW!f{(fX+0XSg!qcd^b>&)-f! z3ljcI*N9ck3sGgjMlmN!i|QNs_xjLPn)lyl!0Qgn8KYUh&+v60XhGsw>R8SD?=v8Q zDp6X#a(<;AmIVoYMXcui_Zje7sKQoA8dYLuKnoHZVpnP2f1d#fRDHd5(USi|tY-Z_ z1NM`>RA@mWIscV0@4wH01gb=&>gR&2b@V%(_-)BGz5?yD6 ziFMFR4-Rj;M683-GKc?Snf3b&UnkIlM8$}3&HL{&Ab~0@t-W>e9>lw=TEH^R`|mTL z1qo3<{*>XR=18Dw_T#0R_ups0UW<>5(X8KR_<9eb1&Qv@qc!ip&wvD~M4i0bAB(^Zxq`c%Rqa9i~~o&wzKZ-3MBb2=xoo zy#GD}5~vEzIaBOQyo?gGAaSl_sMf;k?=v8QD)l7e#RpoD_)<7j>`VR!fhysf?@PQ8 zXhGtB>M+gw?=v8QD(p?q{;);^64eieY2JUI0k4HB`zT3njx#Q7No@*mSa$1g@$cx5 zkkS{28V}Adl>}OlXuUE_JG^%x6*M8g?(1Q!p8v>$KoypdkbmB^GP3z(mS+cOLBd{- zYBQ@F{l-<11X_^bCDQnRt5W&)%4+mk+|q+U72autu=P*%3@^J&0xd}3{ZB~oc9HtD z#zQ5679_;eJa0Qys)Bd&>UrLe^&n7%^B5uPb}lf>y&fisu4#UE)eu)WqzTEH^EsVV zb-X0df&{KzgiQUnuV0&Y6Fdl1*-N$cd1Y2La}7zHEfMP)4Y*Il(h?H)b0!wnwY5h* zkib1EAD4yin2-DS^dL}$bs}WV>j~^)(^&~(RN{^d_i*aTLiLCL-mxsNqp%#iXh8z^ zjQk8T(@>T?F3N*I6}AW=yQ8|Zd5O;?ffgii?@I_R+mcQGoYkXsQHAZs-{EaMo(-M< zP;;+2)(Ll+glsK6oZap`Ul#;gkPxNiy{Ou%Y(h^q|KTkU0#&%f;U~O%TC=DN84ckB zElA+5hL9OyHCUUvSkU=TXz~R2{C_IHN^cc()>Pe zb4Od$X}l!Rf`omyw0?O+!k;fDco3+vm+HdfO2+YTYf3`QwY%Y#4_#u@qB z%YU~vid@Xdgb%bJfw4tGvV_$zCJd-73A7-g#+53SBRHFJWv{;nfhvqG5|S$83;oxY z&h;EENMNLpkY?|q^@10NNFQiHLfvVqRH02v=t05G^&AOQVQi6S2;~Yhn{*s5eW>|E zUJK*9NE5PW;2m1IQ_^}aW@ypUNZ4bRWky8!(HBYUxkaGLUaB9TRbqY8*OaAFbFK7& z5l<{FA){MnWFHH(@u&w9_Bi#0!-?kKDFQtRRAHS6Y4L0V`!#5TT+h|Iq>207TLeTYrmx$M_{7%`XgP9j-2w1X_>~r4?gY(7fh* zd$4ukk30xeVZ@V=KJQzxAHHNV1dSFX>~YaqbE>mcqpL^)El7xQCGLB1RYIQk&C32> z*wTYQ6`mXNcbEQnYVLaGT+h*h1fFK{_k_Denok-Il|Imdgt!OA9O*1o)wKD{gKwSd zITEPCQ&~bfZ(pEqcs)$|5N&SN5YL2>=1&vpo@;+pOA#EFu>_R;I#4KlL+9zfB8#Jrmi90_r6v<6!y z^8CbxMx6fdy@AHG%YAGFs`h9P91#oOXqN|`=RN|SpVa@V-Pb5tzaK>l5;dwnbmZ9d zM*Fl;__+T5rM{zOH{<)Mb^=xQn!lte46V;kM*WX{DO!*y6a3r}Kktn;c7X8l;-3P> zqLB@a8{6=u( zj}&_iiLyJA`Na%=t(9v2D=$^}f9;Kd15z84M>Vz)sOq34_sf=>`}=Tb8y|^7`xu4l zoYC(F)ud=aVoGRozo%(lYioy#yw~^r`WrsAOnpJ|N;U#jj@ilmDn5LrJ=wUQ`-p5d z&?pwZP1ll@r>F{EmfSDG=e4$T%4AEDwBv8eDIFfuM zZ#>jkekj6>oPIU|El8|S^VX3zt5uJ#Te=x1p1(BD_PA^#Q1w21i(_WpE2FA?YH7<5Io?xWM`jghU} zvOBy~NTBLsr(}+u{V%9e{nq%NKJh>R3;1*~0ae+1c5y5XyeO}0Cmu{%sy911l+ilp z63~LgwBDb6rPBksOd{@@wE*roO3 zohm{)jx8Sl^Vo;lg#Q@dBW>z9$VlTGCkeD5F}8l``1-S*@jyaO?`~)0I+T_PA4s6; z=fCpAZ>#x8>vC^9_Yu1}Qjha>Mz&*@?%nn7@MC_j5z;R9#?D4_pJ->UEb-gXuG6lq zU7l#8(=X>lyEv#r)3elyoKjG|}t5zPV{vNuULZ6-D;! zO0nm$Rt&UH<=H^21y?U{vP35zr_=+^~vRaQzHuaz8d>PD<8d7)ZEunBC zJ$A+b(1Jvk-s85;TKYuut0H_f`dmT(x1uwafds0sp9nExG`&@rt5mL0f<)hrA9f60 z_Cy<2QutW4Y=HjwMUYhw7lA4qV}x8-+MabBoJJD7KOEMm9(}xoqv(W(+V8uV-(!}? zaXQB%?YnV1xQ{GVTd-GuFzASsBjW4^!53j^W_0?LeYg*SRarr>vyAdaS zM{j(rO=`Z9`}j1iI4e1@u1Bd*W$*LYrO8?Da-FQ2yZRi7z>j-;@9ul71y&WKeOR;W zrq2y$yaca>DjaWw6m1c}@=bprX9jE^tZj`9)g4<7KhUZ+KFECxs5y*fpSD;MXhDL{ zD-LTW;%7w<#<6c2B=;atHGQAqXfyntw#w%g_fe|kSk`%OMP1AvXhA~w>(%SF8oOsd zjbh8^cJd%l^~pQ|&=Gp~mNsEy8cr=F21^`T+Jit9mXOcX zgFCR`JgFst79>93E$(PP3B#W!%lP3_~{ z9BxFqW0TGHT}Mg+uZ6_*+`D`mXH3-Aj?BvaZ2P>{%+!3a2Z1VVb^iWf*AM32lwBo( z79=kGxW{)wxkT;c_V2ilwzqP!$*r4v5U9ejK**yk3lqpI&$hxkZRz`^(rDg>E%W8# zK4O}8)n-OG3A7;buSRyI?0Zv-S(%d)8yhduo;UL(P?c(a^_`L2N3XoXM^Lx=Mh{0( zSr6Xl@z#AXXJ)DRbA4`WrKYA7V|Q25*o~`N&u9=?%&NJ|g2c2kCF4^!xvf?EJ{9*7 ze!imNo6C8B;I&XyC?G}r$480U@!J_V@wsni<4IgA=>shvmLJ zy7Z>@xJwT1BhSJ7db>N$$Q=@>!oJ}V$R6X3`(d}Jm?dyWw&$<9@jY7J*S_m{(Y8C| zXGQT7jMKHxiG04gRdK8_`C|onpCf@P91DabUK(Z4XI-qB!8J;d zn9u6Q`$XT>nmC?tAKzE~#c1;LJ`Vy_IAZuO0>w{YIj3dSo({d05LP`!!siOFv{a!x zxAL8Ag7v(N&(VYoJusH#s+?b+UM(F(0#)&)k|%`Sex-HXR*T0OM$QXj=Xlhh5sw<6 zYTmNs309oJPJ}ie$V$xLrZ4$Yj-myLKSGlyoafPxhcfyx<#um2Bl?`4qDCznfvR6y zk%Wn}UTZl+r}0vK)2s(8TlTSjFmr8+79@DIB_Sz_Gq&Up>~h-gj6pm6Z3L?Bt#}`w zc>A?>`_@?QgGY*(6)8d$j}*mQu_Zfkw6rhN%T+MiX6j7Qf<&PQ@8jq2sNpOgHRNXk z{-xNwafVT*O@NI+Rk^26UDQ6p_{iWVg7J}$pHX}&Z18U~L*B7rI%DU45wK&C!< z+iaJvr;%n+KZ+J4uueRO0kWz1xe68Wdvz)!{}wX_e)Z3uO@$VV76d;Fq2lC0{B6&s zLIPFzoj`jw6b|?b%fPoWoT^{LU=W9@$hb??~V`XFam1Tm-7@rNV3~e$wC?4fwTY zEUi783N1+R^A^`PtL@oTNT3SqWY4C;?;_)ul=<0<_BZnkGrA%QAv z5qmZjT9CjmP}{SqkU$l-n?0KfYmOzvZ#~ajoDOa zK?1)mY|o}b3ld^1@c&k&!fYxeP=((Xwr5kJ1qu98usxd!El7xakhh&G6=qW*fhzG0 zzoah^V>XqTKdc(!SErHo$fk06M?!oX(E2Vm&oH!SQ@IFK*-M4lRAR2>HI_BR@BU(G z?b%dlLBjs^Y|N%Y0##Tidp4D|E{Rpm+jn@K^DbsnS%k14A->3$^aWzfra}T$*dq39 zDzqShUp%&FQz3yWY&Wm#xy=7oC8VNG__aLG_1wz;Mnd_PwC8$m5vaoN>v^u{R{l2< z_OI}{ujkfV0!XN_pi1Swo?8T}@H>&7>$&x|0}}Z4O3(G&dItjubq}gixv%FIfhzn8 zr{{VuW;W4l_tW;<1L%#KD25@Myc z-X-*0&#juH3R}T*J-6Ny#4ix5^-7h>%X%&?NZ=Qby{_kyK$R$|)gqqjxn)5DzufG( zo?8T}u-!b@bF1c9Tl_|{=X!3v&xeGlhZxJEXZdfKLUuG>3sqv(PI|Y`eLc4bl zJ=b&V{V^m&Yl!>aSt|GS+#*ng-{kdN&#kx2kiakOdamczJ7Y+Qdr-`g&QiIr=N5q~ zv2rH88Rov8TQ$V5H6!i0o?G6L5G%FyzM|)PZV{-mm&$!Tw?+egFIW7VRa(#W+_E5H z|LU~+dTtS@!a8|f&*iG-?fbRP{_wJ%%br3)th-5XhIv`fC4nkYQmaKg*K^B)1b!*l zb3L~RRAIXj;`3(*wsT!7868}^yrAQS&m-Ep&rZLb?r8IRV_t?#(8{2tBn>4x8~ll2^PM%|;;b|;EhpE&^UnRa%Tc zKJS`yIFa5xm{C)aJ4K{B)7&^xJ*Onlg2bEhCE~}7yiLQ)ic^5V9zBdj-#jse4s?PVl=bK@ABCQgXnfrKAuNfV-(bb8FC2rjtMm5?Dh124IKJbXf{#pCf^)NBMnyS53T0 z^>2lbrO*4DxjzTVdY}afY(t*QS$Qm*f4YJkyLji|9mU7AIPFtymAlDs)?!YWBv7^d zZB2(6aEB&t{Vea=BqIB*o@_#6=Nk%mEhPRbTf&iI_-(q-Pux+%`qgJcDioFVKmt|R zH+<|4tjSK#tYnQuSKlI0a&{I+y>7RtBjY#RN9iW{+0@F7JqT3U`#d8bQ!hSjvLf{2 z+*!5>&R5umJicoVV%_s?lmuFkXw;*OW6_w0RJ$g!MXHdotVq+U9t5gz=HuTbo3qaR zw~F)Zu5{zHzO$!3p}l>V`d#@n#&>U%C$#qacNwpZkX94op11nR^*uu(t?Ek z-Cp07`ybO`WyINb=ITY+gP!#bajzhOD$!3?i|`D(2F2Nh*t(KH3lc-}obbJ{nfop# z&gi#4ugz*2B|QjK;VQxN0Op_36W8>S#FKi%ch&ZPLTB%lwH28PvQGKZuiKR?*%KPn zKbrf9PxeZ0b*P&p(8BBFBEBoJXV&tDsdLZvqe-74y)eX z?}W-EM+*|2n*6@C>Cz{(Vs+u8Oy|icT9Dx5Ek0=^=6l=RXq7sr^nnDb4yP|2-+JCd%0H&ZeU#Wg&{)=etDNC* z-S+vbZhYS8yEKFE6EVYyGd zAAbDQa>62q=DY`!EJ(EGB^=xGKE2fABCp5Kyj0EZI?o{STByQS;J?3H>lY)SP0|^p z)rv@Tu2?!gIiL9o7ZvkW^peg-bQvOB7q5jXd+YKXdd73;naZJ$=Q;FL<^rgG?A79`X;6?Ns%n>>e}sT_J2fhwLU z4>jjG^o-}wGnGT{vLK<(yr?UOp79)drgG?A1gdxry{pw_4n5;J^i1W@yDaL|lByhf zSKqi!Mw!Z?cUh27C#KYuL(g~)JySXKE&^3NQ$B&`&{J0qJ>xm_rplprS&-m)?+HAI zp1N}A8PB0NRSvz2K$T;5@&ukkPhC0mjOWmsDu>>6EuIlC&bFz_p$CHJ&@-MxZ>k)6 zmjwxRN={ul^o-}wQv>KpB~?>6bLd4*YB4K|Rm=e5TAUCWt@3Y?t14#( zD~H}ipv9fwIRSJ`iyO`ydXe9*sT_KFE#U)cm4~kC!E@+Ee!H%6=tbtcM@du`JD;yq z4!y|Jmp()dWqIG05IOYnZ{bhn?y~q)k79>=@u=2rk z=o!zU*HsR^i$ImiXjVRW4n5;J^oGiz7a7X(S}Jo{{%t2zKDD88=tXw4ycQBFw_25o z=g>2rLvN@YdKZBzl}WBj#dGLQoVhZ`H$fC7DAn-UYDg;j$pX>m=SJP(FALz0Py!4V6RhB2dM9&|&oxkIBr*Y499+ zL*>xBuEqO9y!jxnYbVru6IP$Qu7w2efAQ9ZDizP6H+T-cp>pV51gh+J6wjeIcn-a; za_Ak_Xh(vNWAVm_@}b@_vF;BSfhzlbuHN8@wcg;dW*oe0#l2~puf#h)l0b_)Vcq{S zZ^__!OH}18`SH9Zs`8fntT_tjE}6Gv@Vq5cWnJBI*WJW zZ;86{mUN!C#8lprc)wEa4b^*>^u->T zx8&e?OVpLOr1QKbrt+3t79{LGc;1rE^Ol&(TXGSo;=42P=A_#7@w_FS=Pfanx8$-Q zfpy~FaevX)_-$UInY(9%F22I{`QI2Sz6YtkEGPfoTzVGudlO4%&NlciJe4CYo!4Y2 z+Zhm{pW;#SjO{i{i~3fdB*YiTzW)*@|0ZNXviIi9hb`Iu+7bHAovY}))EntPsdT@! zS7Ygy;Ei-uSKUv2e^3!m0xz3=Q+Hs2Q4u;?kcfG|f`)X8Q>8j~VYxZvMIigTbCiuh zmAzD*GW9SIZu*5S_KDQdg2c}~qUp#|&iWDZ?#3m0_1IvR?Pi3HKozzKKZ7ivft489 zfJNtswACEzv?gdBJ-1~YZTzbrZ{1J5im|KZE3-zOqI9$%p}ujc+R8kqvwmrFuo?#= zYy_%~oZCQO`>dvqQs~^r&}~gwJ^z%f+)oiYT9Bx?U?c5$EtcLMD~RuZZoz70NXE|b zK1T}@>Z_Pmsd}|%hwfZ8=ghSes4A<)(Vk6XR1cn>(4A#Cz1`fCFH%Pf5(~0!rW3YD zE8??XFShu>GBbH}q>dIO)R#9^sgeZ^V)OQ7HRE`HAc3k|KW(NRx-U~c8t)szX1`l_-~HUd@ck8Y&R{ti_>W@PNb#s%)z{Z2&cXhA}>8~;L{^08>w53Fj- zH#(~oVIxpwMr@=9>RUc8HgC?-ok?yK>lmS<1qm@?_!sh&kCoeMvM*Wl8}qwH*$7m9 zI=`BReLGv#K+2)tN#_17JI$Dqra}58wqbk)mzn!9+ z9uGEFpNOy#s4CNQ8TAXYd{ms5mIgH8@A2|`5G_ckuP`bfGrRZH^1mHoB;RQ#P*pEF zoJRGqe7yNSzkV*wAYT|S62{Tf6^u`1qHF}J-fWpg`-})teLi?r9pmRtJj;7Vq>dIO)K^25kIS$9johU^ z={=f8*a%czDm;s>{>QqbYQAi1B%7P4XXC3gT98oRPE|hsec9dEU3i=RXi=n%K-H2V z(`i2bdzQ}iJZrWAMtrIUI{7h5M+*|_o2<%5kE=tBMe9aupZVBD0##E+O{Z4^tyy%< zxn9P^YYWXkUPRk=8Mw1Rn!g3Xem2r+{mlMLqII+&ad+Z$8hs#2)g#BDA;zVZQ|ZB5 z5jFx<_ELquI;5SxHJCL%7OCUz1=nyfD$nG!b~4wF<<<+8AH<3VM(Sum!f`j89v)%s z87>Wo)HfXnWIGPn2~>$ux#`&k)w&I)Fn#&xuB<@QC>*qZ+HF}x+y-6Cc9J1ugvIZ+H1~c`8OfO+GnLk=RNfKn(;>Z zVKKDzvd#2GwQ7D*>tg7x@>^)TT2=i{oQl=7N$NeYP33r*ib(;?`1FrtShCNSdpaltg%}ey)U*~xf$ST}8qa%ST9LM}U zuXkYyZCA8oj$3IBv>@@@xo}$QlGVCB`6*oCUq6}Me9!6FQ`m#4XUw9NkFHkz@n(KW zqjg+fHn#GAI$Dsx5kpAY*QtyN`-`$CDKi*Ipz6rp5c+ceM&%={`E&iz+y-p$%nLeN zkid~o$ie=b^-q`UvU@*%V<3Sld(BtHOx1H6o!N|vmvyutfp;(=ch~RHRuAgU1~fTi zBT$8{&fkj9)yjC;ZjX6l_XS()Vk_Wm$IqRYG&XJxm}!c(LJJbD^G&A{FGs1i>anqx zQSReQT0fBgrVPxlsIt$Zh5v46Od8Q4{`rBl23nBVonbl+t{JX;WO~`lC=qc>tJwIA zjs&W3T_NP{&z+3cJ?80-BhNb&UA`cIamYr8m%m#Ii24=oBqPm1@MI zdd9X)@AaJL&e>K@RN*?$bBYcZG`91d#$(>PXh9R>H#V?Tm;2rZsj}j;47lPM6oh9bnVoa60DmH07gvu2WiCt+$cEIHRKl z3EbQ9%*^&<^w+;OHN+@E0##T-Li!es*Yi$lZKR!iNk3JP3NZ?ZjA%E}iG1vI_GS)_%u@R`k{^#el9ZIt!;Xj*G4_7m` zy^5p%EQpb-+8;~fX!5}^vPBDw+|0ib8m(IQS)hX*8amk=#n)Q2Adzlb9PQC3My|o) z*FxK{!GCPgAMd|n>p^U3eBR}m97c0Ce|dl|Mj~2}xOaCm-CcgMD%H^yz1g0uo3&Ph z&e)!WQH9U#eC$qa$My|4oiHX}wZ8_k4-2!JQBBXD0w$KfVJ%0#z6lA>>}Ezv<>Fx#dn~+M6wOUgh8AjwR@u zEtLAKq)qwm>;Wh8|A)&>+b@R_~T7QYPTT1JQ^SgR7h4g_IB&IzL zrY*9^sU6v@)(P6ayCcks+y@eWtC zs^Ys&qmC5O%E!9BK03R7IYHC|El4z&Ih8hkxJdbUUSNto;>^`u!UqzlTGetIZS!5Y z^6_8(6#Dm{kNXK9Xh9+*+f2HoYp~THS%&Gw797?@e;|RX@%H53+WM8lr4J-fm92j`J!wo+K3-Ng{gzEmp^JK;1&Ic;qAA&6`FORH#+S)C zMHl^n1geI0j;3XXT0X8Uc$5&>(ntD03li%-tf7N~W~zE*UUQzVOFdZnKmt{cscY!u ze6v(N3cX!Mv+uts+X^i9DAyYY%3%jpt`bT6OCURqI_t3Z_&yD zbEFTnAklyDR+{={xbktkOOSbd)HXS;kU-V=)mvzeEQ^(o_r+40MY=@Fv5OWYaIWNW zh8L5~auYiwh;fAks?5q;Xmawq@=<8QF)q<<0kg{x%;-;OaxjpEr}U3el0Y zOzw_00#(=|JUhBcQT8hT+4u)P)VH-261a-;{KPhdEoz@!FUx)4wNQmU%lFjpbFlk6 zM(M%_T9Clq0N?4SI%Rf!6RC@OAb~0zp@i&gf5-IcbWi#~3lg|f<5@`ArkHbny(N7h zfhxSyI5C9(ZrkLXhNuTxkifkiZ>zGC=*7N1hG;7!P=zxF?~kJ2`?YLPRQf;*61bn| zznWb!vmU(qv+NHfP=zxeA@!rD>IZXWmp;&f1U>=qU#&|St5<1yT(%VwsKObXzg_X} ziT-KSf3iQ&f&@NO@jNo)o_;NUwDf@ls&FOZZB;Y3F>gf==>siD;IkniD^K|t|5k6H ziE)Jls&GZ+KJped-Y)!*aG&=%T9Ck}V*cjj;E($Dy9G?)0|`{&&Vc_WN3N_!y~guQ zd4ItE0||V(=cj!EhxC0<*O_8m;k8hOI~@N0N52dDqJY=Z2U?K8s0fcnW$&;5a_FJ- zfdr~>r^dg!u%e~@_-Gy`>VXy{Fpk3CQM{j8OI9ca6K#bAs_eVhP0t(Cu_ud2A80`W zV_Afh=~v9GI6e~-vnUd%!Wba`m9)Lx%*S=hF!3CP79=nlDKcvLyDY~7&2B-X4E0^@ z1o2&M@wfG*@u#a&x&C$$x*&wb`rfuuxxVjheYx97(0EO+5jsZtuq?`-{EjzX$w}1y ztZUs+VLZVk#IfuSM!;L88X+b=0waoz_HV4s1WAGm;^PQTT9#jX;&X9)mCU zH=fpStiNj=Wu2JFQmMF~CeDXcPKf+>LT=9QZagcnU7s*I(mKcSAXMB}(ysgx9r8;g zfhu)6pnQl^fM*{*>u?I-L8$1k@=-9cwo$2OR%8E!NbB4{5~xzA9Lh(QKE;h4O)42z zN<>+w86Jd+4l5t`j-@l|-)m?LIqo_!kp!yLX^ryHq|H11Xu%(hbh_(Q#)DANVdZ1& zf;0M0>whvr_{k_<3svgWN%=UkG*a)&0*xVuU8hUZf`p1ED<4%-<<>h^8)UrdYbQ{p z&cc+BI$K(64blxYy2M6Ur)1KCgo;xuA1Xu05E(*vEmWzD8|CA@Gqc8k%o=GyLY-MC zAHMfyngHKz8DvT|`GfhxQ=`TGX@Hk)zddKizZN80XMB-Gi9^3kK$WwTl84o2^! zEF|dzRd~V@HjYGFXY?L~I(=8Adb>Zp@yf3u zJG$SM2OtSlsR*?4k+DP?WAnDgtQS8^MGF$*-W+{tmh$m#!fri%)~@V&(I^{%Dis%3 zK8EoV(HDaQ*#Vwkf)*rHHiYu=^j&_vLh?Z@UvE2sDiz;VJ{tY8-7H+bJG=2sw7frf z=83$P%1Duat9Y^^-XA%n{cw9QTgp$v@wzJaLlSl$DkFtKMvA-^5-K}I)k9^yFp>3w z*Fu$wS*ud*%s9im-=i<rt+9OID)KM}1kt2p!kEyYn~F;@4ueG2?VU zT;~b7!gJMH-MOmI%rcRiPNk1i?k7_QW;{Z=9QlHW#fiT)5k50 z(9wc~iu)=bHHQykEx*gApUW0$BT%I>#FUTfBZjaGkE690zL7dwkWdkCbPhdfhxSa_%|)a7i7)aS7(hEMavb3=cGyRNT_oo z!25O=Li*2$Uwy2h_QN zCe961EK74{K&WVxE;1lgJV_H75GpdIi3|u8jgo&8A|hUyIy}`N;w3Fepl^OY=sf?> z#rX%`6Idr4$F4IL9nM%}D^v*lJK(e*oE1qQNT|q^ zYF%+Y*lu(k)`p)CVozZYsu++Wnzbvy_Gc+BGa%4{1dbR&jwcpp`F>0xGa!&am5OC4 zAL1;v?8`@{I7>wf5;*b+dEB)gYfxu{+2qkT1`?>U*W9tZGfQ(|qWN*j6&)=|;2lhe zI=iFd><$T3+52Nl`~maNdOxtdpU&G_7hA!;evCUFY+f1LNVXMPkWle5)mG{(m5H-d zBv6HGm+Oq4i8Fe%Afe)A%7;3mXX1<=2~^?EfWJq*Vy0g8RwtIX$R*pJ0SVl%5R&2C zHh%58EaG;011(6X2%9REI-_Uej2;P8*>_|o^QSc;KNOa&ixwnQgiZO_8CBZQhUJ!{ z9SKy~_lYXM#3AxaRFq3z3-`M!!lrzv{1PhiOVEM@?yvcm9mX{=F6EhGicAh9P=zHV z@`<;ONPi>!Y4X>=2Y=ARrBiu`Ij)$ zRxm_16eGA_D>~NT~cfxd!uh``Z7hU(eRY*cWu!)`Qs6_#92hn8kzi zfL6_9f1m{k6~9!aQh8*C$Rk4nRrnn3%Ih;AuTQRONMQZ=uM{|Q2Mv)sh}S|DK1cIk z3UTHq8e(-u3ljFWTIew=0)Z?qpO(g50sFTux2oa;iK_P2_m;w*j4J zcbYi6!~F;DckDZvg@MV>QFQ%kfUp-vaoZb_Xe`iT=oBv7T!!qjd_om$FMeY7B< zPDzyybuvof)KXpxRq8BE`B0~?RGd_!1qpT9t9+;vUYP-b1gg|onDU`ck);o`AfZmJ zl@E1NEwe?CK$SWRQ$EybxXczo3li$|UHMQa?$QSms8VNP%7;4Dmp;&fgvugNK2+v_ zY%3&CrOv{X50#xD+X^j6sB8%3LuEinA4s4|orNhMD$7FpKnoHot3&yi<;>)e;|d8> zsk1QULuHG|v5OWYRCbE;p)yi@MFs>Cs8VNP%7@B&k*E4-K|*EOC?6`bMuV&uc`a0_ zvoPi3wKIE1llO=7T+M?}*+R;P$`Fzn5O^(Ask1Q4hcgRF`ala3D(lJW4`-&6^nnDb z)LEGFp|YuDwg_5~z`2qTm9ZtWMUX(1Itx=iR34cwW>K^tVV`$JM*OL@8}+A28S(O3 zs8ZSS%7@Cjm(QGNQDjDgI{oiOU*t(O5~#wSvA4s4IXK>zDD=+JZCccn9(1HX$ zQ}L5g|DpO1RUgO`cO+1SD-j|3nfCh3T+S1Bv><`chWxqq?;={iWX=<^`#r(H%6HA!Yi+zywKmt{`GazL0>o9Zoi!Aa~A1z4W(>)>G^KLR* zuh=j90|`{&4u^kP?$|ps|JXCKKhS~%Mn!l`=J&_uzPW+Y2NI~ly&WOJOY^ev3ExW} zXh8y_B81d3Qm{)0k0wAimAs=+g*#3{l7$yxxke7v#QlL5Brulc%p?0ax4aH{WYPz! zFb3$#B-bI6T+Yr&U^J4DDQPmZPmNo!2_q_+lb#-@$2Nq}%8qW1zu0lQx_1a|+gW$a zEpVJh)efcqj_TqdBk)>6D>&iuRKaWy$+?4@;!oY+;ymu=izmhG-d z%$lta(Fz?G(2;Xy_~y8BkUlQ(8*MUZgYR_h5Y2me0sYsw%fG=hy}~dSF)lb^-I&E@ z;+caqX8L?OqIcyNPnsqM(aN9%D>QExnfUNyxkQhNlN8D-cRI{#B0q=zFm|>lISS*kdHv2vlv|bASfb45d2*R&gIUhIVD2 zCk-|W?6_#_j|`a))787fXn5-=-@~JMKNX!%!#*|Q{jsk~Yc_LOUB6i?GBLCu(Q4fx z`t5A~MsC1#PE@Peg4KLnNza=yvyDJiV4g$NaXpka_`5JC#`G`4eyIPCo|)xmXhGu9 z%7Zk2LI}+g_7f-WG|J1CyPE8`iBI+a&L?ANLBif2|Nc;t zT^yFnc(nbVi3F-}924?Ou6E{`xA$q@;2`$#*fIJ~`e0fk**A_6V~^443+K^%0jV9U zqmR&mvB7k8zGuA8*Hs8HgO~L*Pu&_|BbL87LYEg0q19%;^?h*a810xfnAUIi4WF;h zwcBT&k85EboY0G*1&MKvqqGUn*-m@PhZENatv7!t5pA|E7hoe$btCO@`nh{BO$f}$ ziQjIdWQX6^p#HZyFud-zwufml{yl|1-~Zu@G$Flx^E1C;Y3a+1jTu^y2w!}dF54DL zKhN9EYu+St9+tLpH}mDGdNu-8Lx&!vpG$_)Z*z)LHOy9#)hXS{{Ap|@h884B?LABv zHx8q*DNb`A7si%jW6oSQCydN#BT$7a10l`(`mxZG@66Hfo|77ND*K9)y-azwp=}NJv|j-eEl9*nI81xrpHEj^$;*Az=(FAI zT5O%(qH9;CcRWmEcLmeP+oybMBtJ|GE)AibI&b#vneqtj+9{ak+I)@Iyi3dub8gWf z{dHI`h8863Be6`S$>#O*Kk47M8Ehj^)vetT`n-HF9o6*~_tBtJJ9Ao-VC`x2D25g! zaOCssoyn)EZ<{PysbS-71gaWVJVqasoJR*{5o7mQk>lo#MMv~ynOoax{%G4F8k#qR zruc8Ytrd7I{QW(%+4e_zgIaYN))tA?pAXXO{GHC+d4A>f*j^wrJMqs!J;ShCHUd>R z&+|T?mVxa}e4+ncqdY?k5|v*Zq*3#D-<%oGef0e;GwbO8LGSdgq>Vrot_*~<^vT3} z{!xQ%s{XHuJEV>DI9=Z}gx-4S=fLsC_ta^=Wv#ncVJ-9AwT(n19;`o3gPVoWevK;e z*8Q+5D~qm~gKhaaBg1Q<3hy+29yRWxnLc|)c4u{I+Z}~OT*u>d^SNL;pjSce<7H#Q zay>d~PUFAOjn_gI&KSJUC;n&V+3~=95Z=HxGa%86`)J60WN9aSOzwZwH1{7jGi`5W zBT!|Z;YNo2Zr(T_M_ZeNZSyXUU7Y#&4xr09b4(SY7fIdAHYXy1=g>x2vp(x$V(O6n$2$$YF7U6)uxPRd9*Jf_c zcC@%)8U@eW2vp(x$j=Qv)Mcky=V5=n>|>$@3H!di;mV4v=ew%xO6meO0#){T_sjWt z^kuI&&GE~4hV#<5aog$c|3=C=3THk-t`5m<4%(&bk7fqhW;i77*7$?&o-~FAtrSla zYkNhRrL*qW15$NiI7i_;Zzoo+m}Y*i7pprK^kHa00_S}G3z*~knaK`^=mm!kuo0-T z*Q57|FJ|r+`HW$!@-W=*;2c%s_*RRe_>wEg*%>Fh4RoLo; z{IM@JtGu>^p&d_at2x%mzU%8+Bm-MJt%9*I)iV<F<5rADvA&8?C|cM#5^4VSdbVoW%{IM8GPGR2H;hJ& zijyk55|7E8AFRI&*hgPYA8GS}#KWq;&~3+8Dj$9G6Mf=e9}?V4g{su+d(-bb$EqDb z^Hjg;f2`V@Abg+&i9Koi(OPYnC?6@9kACslWry&AgiX~gkUp!vMES^=dZK=FN()W+ zAYega-=YEZTsj_WmUnHlI&ZZ~yDMwL2NI}CU!@=IR@>UiRIS=eZ-4c*^nn&6ejYQ5 zcD*@8`B-%7l=iyia_IvJRK>>+r^zQwR`oczwWcoqFY197B*gW_e>>|Tt}pzEdLV%+ zaeZNP?#M(PL|udrv>+kcNz}{fL$s4bnG^4rDgN9@6RwQrv&`GVIA7sx$8!y`>&BZkAI(ghzfJNZf`s;P2%Y;OM$&{dtI^PCv3!Q?iNBu>qI0M4k-|&JztuRbm9g~Wy9D6_2~@3~I)FAGwnX{po3*>Kd~F6j zl>0yn64P@Hr(3FrC?B2Un;QPTe$<5zBv94(pCNSGv0&vRN9pE9>0bMFQ4h2rVWyct zOY+~mbk^hA@+!vA`>>6x|N(hYy_ypxD{j0>EqPTOU&zi+RC;<3tkuRO&%RA^@rKDptG%zK$X}>h`Y_{ zW60~|5&7vnd+V%{%FTvdae|x!MYNK)f?dGy}4H#OG z!26$P6=%G!kF3L4xSrbc;XW$VdjsK@boGNh$(gRd4U!n-Aq5$E$kt zrsMQfzuFeefe7@%)qvv^%3VOlwaVo(2U-w;qnYAx%Wk_h*T3g72O`i5R|E7#zdp14 z*k?{~PpcC9oVh(Iq~4LFX7JLled?>EDN7DV7^CXQQ^-E~XO7!E|B z7p?{zC-KKvcUYYqlIsdBh``b8IFDLqcH69aY&Z~sUbq^d-)`&lv-m1SA;W1ra#@9cSdvQ`Mw{XWU{m&JlrLxPEY)cKMZ>ADvqAI7bU2{By~Z?J;h- zlik(OO?~vZT2sB4-*Va4< z@06WhzLJx^!4=1+Yht`gS(3c_J95)kYSFZ%Sma~X zux=qA0=@Foj`9BLp5zsIIhr`OrpO_SpSq#0)+(pbf{1_e$9QLBle{nF=Y$yeXs;Vt zda3&QfPWUnk|Ua;QKN6VgEuRczC{C#7DRMfH_bbAG09t1dKGa@E1p5#E_hDO8&J)M zKrjDOy-{F3?krnlwr;?DPJz+ocD4c*X=@hfb^5aw~P><;VBE z<=;*x#Q9FQ=sitmgTFnJGLmv9CSAI3*!h}IrQntK#c#4DHX=mHmmU+M@Mj;YrxT)= z?9Vk!qXiNF%+6-eI~zPD#A`LSs0=GdENK$i*M~r_)+w_kc6)l?>$T-CLR78%NF6&7 zwe*X!?KN5u;V=1sgf#lloK#D1)otlRpx2G*SrUIr{lL3@*a&npPP(hHEclxn(8xzp1cxu|_xjmd2F)li$7}j=irB*1z;@y6j=Y=?X1~_`OZq z#NqT*TVpm5V$!*`I)A&u%c|aZ>_eazJ|XSVKWeSB9jv=7ZBz=47DSAnmp1Wfng`z1 zy<3Q*^XevgY`+^zH&U;go-L5A$CXgOGG5%Ts5Q-Xu$R35K{xm3r_Tbbst?m> z*`YM^5_btU)_Y&NnxT5}Cgc|Np7b zEA#nFk@2n1+A(>|Kno%|4C@!Uzw{}~QKU&NaVX_+!+{9&T5xDshPPde6n9G3(zgP7l#f}_L=I}xsj)Ruu`x0M* zuN+>e9Ed6ij_MkRbp*BYgBB=cnLp{cE z+8?~+y>;$cfa?ko=tcc1G1NmzVfsNg73zs-K?Kf3bjtDao8H{cB|^PDd@uCE`O$H{ z?%PPaM^npwZ9nA^l^7aPvsUj-i2LH48Bus9mg97+J6!+N#1okoPMXrv8CBnhPPK}DyM4m1Q9ql%(_ZSYTh#3?AIfZT*%Vq3 zLFZK^B%f;aY)u+n^GZY6pK2Eo=!G>+ipD_&wA8ia-5EI)S`dLJj?sC-KUCANeDu0Z z8k)_AK(FUY?uJTEPZb#|A(bN{RC25lI;VQ=N-=EOaQXMMZ2!Nm08t3e3?qd1ZwUIr z3VUI_(SB`Ge)(qZ>as=6aa@kbQ18Rjx$tS}>}8!o{5uHA4s5JB}8J{iok zpbIS+Mxd9!7M_S<^30*iZpL7555HOPL@w%M;Wv@#yE4>w(Sis(+lw-COSP9dm;U7b zyndYTt%hD$Bc!Z3-&96D&M0SGHoYWVSBSt9$4oDg&`ZJy^ul_hUCTOkWVO%7iD~s; z;kUCXIj`>UU3(-xb)e0@D_(Hbck5Y8dDF@7rjLE1(1Hl85z-;wsVeUt{>puAU;&K? z^hz`QP-N-4=PbwE-vaV9#jqZxaWq;G;jgQdH`2;1d2`F+#DNI(>bSaV}G{oKPBq~vlS!tXU<(Ua;YEyth#WN>pmX=yk}hZeT@5y`U> zeb+wS@AdBaj^RKAj#T1KNG`|i9{tt!M(>Bp0hZ+Z5+BTPh146^qB=}S zZV&ZJcAaNX3B!RFL{Pnj-zBt$Yh6OuJ9FB!IU>-D`a)uIzbeqJjy_T6JJaT9K?Jpb z_}xXnP8spG{!zW;a^FP+df^(C6pin;(Kp}NAh_?M1rhkZq7hZ=wmbTXBXSSu=vyb^ zSiu#bfsmYP28%M}gxMczD{adA6MU-Mx-J1bX2LkR$YtEb{s1?q8J} zX|x~$M}gzCyt~LaESAd`PSmCBk`@sE^IM9L!90l|x{C8eAecKC$0}+0& zRsYdxTf1=!Gjl zdZX4zOYwzh)8=SF1dall+c#cUDHm-Qd8qFq0=;m}NNc!OxpkJ7<3u&;yJ$fKjvM+- zr)H((fltd6o&J*4g?eNPJfuiLl^x@iM5>6>$Y ze*O~fK47Ta716WkJTX?G1rhkZa-57iKa^7nbu0RC)sH>|dKLa8Z6H3~1Mkl{-x5cc z3$5kB6Z?x!>XkyH1rh#|&y8#@Z;UHfwDX*dJ_LG|IFdF{G1CJtYAI_u^PGK4cKD-g z(I+R0YP28%Yua(t@^WtR-7AYssW{wMyI7;tvZmI9U&6!c#<}@ctSEAK*kIobhlmVG z*#Zy#zV97N!7-Ujr+;_<8a1}))YASr5xwvU>9=0qe(3()vwYDp{o4Ch8HngpI9s69 zll$JbAO9qd3dgd`Y+cJ0ZJM{K4}o6T-zdY4e);}x_E_)TE)?;aH(7)tTND=)AzjA0 zsHx(s-*$O*)38D)!zWT5%bH)!`S>G^7DP~lO>mSoxQl!yQ=E#w-cwEM*vF3muMQKZ zil4k)-m!w0iDP-|1!~Xf(dv4go*FH9-_w_;iZao=yeq5E5Tfbqqw0^>R;%G%T4=N& zf+CY5q)wq3F8@8X`RsO8YDHZi0==#*nI@iHqqu1P6~u9L$Q!!k=4`r8U$cuWg6fuj z3(EvzMRAJt)`(ua5z(~&@uZ~Q_;m*TQHnGiuLL9v& zWY#t2Tvn$mR`Max%U^QR`nat5u{&`hv`0s^Dd=g;ejU|@;J7uNxUhh9MVXfg*wq&y zg#h&_!7*2!yQqfQIh2`LBMka7Sm6yFyiMFQyq!gnGqXQv$^q-Q`2B4`If_%suN zkY)lA=tVjQk*t{@T}B|J%RmbvXeUMZv>yo}?FS;zi}V^IS^Giy5-+4LK?@>iM@aZI zEM7>%f(Y~?-HAxnu#is13+ZIgf(Y8#5CFiHbzEeP$AtCS`b0?BzOlc$U*hwg|tzKKrgB%!8#r8mGmW? zE?R~3S7<>5wYQ-5u^iOiDx~p3gwLye7r{E6AP4m+71EJWPY7EOLH$vV$Upb@J=Dm}Cy z0_R|(1oS`&7`_*J;k$%R3|U!Kv*w5OKBT`9LB&q>g*4lQ=V1SwNLnA4H9xHP!Fh?0 zBB&OszL0kQ!t)r#mNt4WYkpW?f)+%Owm}3n6V(@za^R~8E^B^RUxEnqq8&_;teGIK zk6_IYbD#wgq|p#T?FVy^)+fN4ALj5Oz>9WbMY8sTv_6V8Kddi73*MKsCL*X|VGh#z zD5Loy4n&|A?I??64GU>~6l;FC9B4rVX=X%Fi^CkG^--+(;c_4Xy=Z4#@D6-X`$1YC z&6*$PKno)1{(`kR6!|6&()wuD{4fV1(2MRbcn3bnL0TWpnjhvs3nHkV1Z#7G9HjNp ztodOMM4%Vdlb|wM4$}H)*8FgLpal`s-h#C`K@QUTXx98N2O`jm+FS4re6Sp(_0g>P zu^O+i1rgM51#5GH9HjNptodOMycc>=zZJX#ALJmdk7mse*A-e2fn$?)+zYvyH9yRO z2=tUGyj#hM@HKm>Z>YQS+w>!Von!yITq1de9sVOtgL4e!8+6DeS@XksAJX~=*8H&E2Ui@V^%0+v<|nB4A+3*O%@6B+(1Hk@i5!Qt zJ}zs1Snq=f^dhZ~U}aBG??YN2mo-1E_dyFHNb4h5T@%#%kk-d#%@6B+u!LB0L^}>? zeO%W3u-*qPh#;+xU^P!r??YN2mo-1E_dx`D`JalkJ}zs1Snq@Fflo+UAHm9=px%eH zJ}zs1Snq=tMBw+Q;XD%mh|4rWWmtW3KJji*TY( z772e9nJftV9cB8G{SpdZ2jgY7m)I{alWAdRIAgK%qq)XAnfxgJ9yB>WXhDRX!7YdV z<_z%nAR^GqekYnIq>T08cWr=kOwfV|`zEp+_S-oDzB$dkd|tsXWXoZ{&rP0}{Stl- zVc)2h!^Qy2cP%2&%YL_84jX4M9B4s=T^U#o8_O^ph(IqJf3O@jUZS|J(1HlN!m%6_ zE8&=o;Xnj>**J>juyG&5ffhvAm73+CSP93L3nz4O80RsQAEh~F zV)LUos$%9P`{iZOcI9N>1{5pN95dnXL9`&kej6IJ$&b<;GvV(+M4*>l0a^}W|MmtDzP4vLj%j+wx>^K%IMt!_CeR-!p(0^iOCfnIh+ zZaFAcqB&;5&>zSc&48iOrAVJvuX!;kpD@113L8 zbIio%M{%t9IRuVolOLrxX2RctcrWzA)qu&5(i}5^Z%)I32>;ALu@cQO6Zqyd2=wx; zA2>fsbIb(3ou5PaX9kLuXpWh{x3fW@7p?|Oew5~z33H$Y5jdJnew5;v33DIK;P z@}o4zOqc^Lh``Zo@}m^TOqc@^=!L5RlOLrxX2Kk3K?IIwlOLrxX2KkZKrdVknEWWk zF%#xM3nFkdoBSxnF%#xM1bX3Wz~o1HUs242InaU#9L**_D!?%l=0F5`;cCF-M+uIZ zFb7%?fuq^vN4Xp`VGcx~7p?|Oew52G6Xrk*BK$K0#Y$X`nb`a&-aj>c7rk)(VDh6} zj+xl}DBhQS4&k3mC|064W@7WB1b?I3{3yY30Gl5bo?}dYl;)U;&5sfsGqL$m;T6ZH zYhnb)Il}o-nqww5KPqg&Zzr6)On#K+n2F7g3M0^qVkLqjBjNlg%`p?39~HJBf?_3t zqZ8r$D8(@on;#V}Aw`M8B}cT$k5U{nvH4M~128i+A}CfOI2sbpkJ217vH4M91bX?O ziee>-V9UZAh^a!Eugoew5;viOr7+TM&WYpC&)bw6gme~BL0Odysn;#XR{3v1bqgYuZ!ue6MPq&Yj*!(DC;d~WVAyIym;A_gw z2~d8N2m~4`tY`PRd+U7F2-pqeM7A%5B_X)nc0;6}BM4>U~5wKgvz> z@`}YaKPrqsFUo=nP=1sM=SR8IBE~MU`B7mDBCOuWmYnjVWZq%rme~BLFao_O3o1bQ zQ6iilB^MnkyTs;4g)NAn{HSnEoBSxbxbz=OY<^U@cCkjS7E6Tlqh!-1-Iv(>D1%@N zA}Eh3K>1N3oF64S$OB7kepDENUigG2KT2NcSbmAkk1`1E4Tzx3rvT+giEw_Dyx5@J z5}O|tMxYnvM}_-aSmmub7r?5yO<%GqZ*y%`%(mn<+bNN=ovbF+^agA}>@g;rLsB+} z;%pA9x;FQ+`gX(NuU*O*kq4W29&6~)f(Wa>GiZ~QA}K3HbKV3#FO~zjP5y_Z{13(X zA80{@RmWQn$}y3nrc76yV}c0u!Y4Gj8Ip1{H0Neu?cx*KOajY6`5%(J*ytKQ!lm zpal`sP6@3(I%^S>W1=a?M01V_S`a~P!)kT=R5rUNG@`=yLNDrL3HR2YvmBJ0p(!^* zb8ZG&5J7z`A;Sw-EQ0bsH06IN&i_CQBB+P5zTG|*=SPM5E+Wv2`fftgM!8wuhyh5WE5$Hvu)*!;UmR{cWC5qXsM$SG9y`zj5?;+5ey}Nl}b50=XRYBWDd^GG#rRPFRPSKE(d34hRVT;cw<3?&2~(#E6&agl_QKmFRPTd9Mm41of&Em zR>T_%B5Z!7<*?bArp@tQ=tX^jvokG+&9w}@2g4Rb`1>y9M`_BB@@#&T>D4wr%3Sj( zvg&xd_M!YJP5DvE=0|aci?QH{!trSGqcr75DVrY^Mxd8f`CAUkkJ6MMrEGo_XX+RW zB5+=D9LkTM;Q*ZAcE?R^YJVPXq`NB;`kWHa{v5`j$Zi zuI)^Il%o77&*n#kXMMVFc&zxxAmvAC%8&AFepGl2BEmnSC_hS3ew4ELQDFpn;rKWC zQJV6jl+BL{&n1ZPk0{EIQj{NMIPhNR<)0HNKT1)4l(P9z;TaAQ{t-p_QHt`T3BQHBHOb{s4I_X_1lxs)GeIQ*96`}#)|xUQ~yXp&8udN4b=`@}peJj|#O%_+IFR?|CX~jkJ>TqfDEl z1ra!IOn#J0`B9$Dj|zm|6X=CsNG3l@QhtW zUNLJ}TGxXq6WTM&U`-f<{DO7GZuqnOQ)3M0^qvY-+vKT3r2qx9}dsfyYBsIUbQlphtY zX_FtN&gO|OYV)JQwTm_CUja~ll=^za$f7ns${@JS5kYxOiIg8D!ue6^k*rnB=0}AQ z=!H*c@}pE_qtwN0ew0D*DgzOe`IJccQ6iilr6*5GRm|o`g%RjQ`BCBiX7Zy1Ykq8g z6#w#%=}Vl$!n>~A$4Kkru}&wPALX*<$L2?cEr_59n-|)9p{)2!aV~3qY<^TS0=!7; zH9s~#$}_vjj>Gv;9xHfkeiU$!)(D()xI;<_YIVN!I+>{HQPjz5FGw6qi?(zQ0h# zUF@rO6j|qelyiXiKHHs$56`akp5`BDBI$j8U*V11+Q(cw&j0jG_1ZrL^{#iT>0E8r zdVQS1qCokr5lw$uJ1yuQ$`m_`dC-dexL+c;&Y zSYD?d<$2Yt9^p;Z>%7W)M(WtamENZJdz$`Q>%ls2>*GG=8lRSSGY)?1eYvNpn%RAr zuN?U7cqhjROl#w1{c4n|IcBJj0}-ox%=dDY>}gBhyV|RXOC|-iA9yeHYWn$nuhi%+ z<_T#Z=iczZk_lrB2U-x(f8`9X&X8V~qhrd0f!b|S80`ll(5rGKI=ALhSIhC$@>Sws zwxNatEr>Wca*|hf`~b`G^%s4`&OA4bE&~zh)u-=7uX5X9P1AdDU~c#F;%0^eEr>X^ ze6&~n*htHf_U1Pt#jS0I0}<#oHCME^qU$HN99e#^Syua6B^k!1#S`bm=b`P(xJJ)igyOqk#-6-Anti?eDdY!G=#q%QP zT8`24M!VToWE5Nuv>@Wrt`EIDH`k{7ruiwP4EyutL{oHwf z9WWedK}3!QgS}q+gZt{V&$;iS_&R!m;Xnj> zm;({$wc=zyZ*7gamZSgq#`57u(>*Q+S`d-??f%}+Z^m1Wx1!q1O%;nM=0F5`75{Re zmv%zD<=BwDmdu)FreY4XAfoEvVcxxK6D-H5^Yvu>`6R=E2=q$(*(ctHNfRx{__&g? zR`$OQ2U-vjUv{jQF~?}j@m{4;vh)1Bn#+L*^va)NoEQ0EwB`7^PYQVIDUxb_-M-mHz7rJ!+{9&O2|IN+qC{8%kj&*^W6!V-ZC6$LB#9%XL^0k_O%={ zH;i-3ztGZfAOgK|w3z8Nb_ZCFe7&@Izj0&3ffhvU6!X3Ei~Cp(XVTn&{H2rOKm>Ya zFFxOEnzg^>NYgN_y75m#!+{n=;L3p1B3nAC+26G`9Ed=#d3w3mp~_&(ak<`7m3#5q z`me-{8ZC(MuQGnyw_Tm<-&k*a__IO;dOdL0cx|f=6PMrVve0bFI+!3&Yt++z0X$^ z)D=(H(r7^h)-;`?xOY^-poEl~IS_$fxPEY)^^3ZQ%?DrAm52i^h`=60zfL(bgS)Wi zKc*arKrdWB(5kO#SGVxhyoLiUh`^ptr`HYo%-vl5g5f{}dg1zke&;U3HaGRkl%}rG zf(RVJ^czAiDtFfSjfMje=!NSCI(Mn2BMWp$QrsSBK?Kf3w0e!Z<~Bbyz;GY}y>R{D zIKBJlk#7|lY&g(@2%J&r)VHK(?&X}PJZ^JDpck$m=w!JbugZcW;yrG2v>*cC431M~ zNJ<$wB%NRmM4%V09~|e!4+_c8tNbLG11*TaHykNa<~?+qt1>QgAOgK`{XmhT_jAde zrzW`E9%w-XzNu*iaOkxA{jeCf(cV@*1bX3$gHB#7nOd$WsogV;Ox9NT8yOL}mLRQj zqg;B`%}RQ1je}|po!l8+HBL-9(tcz0#_PPIr#=?D%B0zt@bND1jYF{_p>tmPDta23 zS?_zjj9!-EAB7e~IGgBq=o=3cKklkah%H+kUHL%)?fj8XBLcmS{JG0ZKPgtczkU=U z9)0$YD)U=@J;5oceHOTH-Gp`Cwl{}~a|w+JvHRI%)&J6JwSZ2@`(n*{FN+u~_Ov(? zQ7z+MZ)fuuv24o4h;PR3@lGs_5xH0IBSiNG%T%g%`_(URwbE#5^UZFrNx@jrrrhcX zyc1=5H&?1^mYeG0v<5y7L_Djw+soNKR;>JfHgWtuVXIny@v@qHy0H&|UhBH7_pbLC zB9d}`Pl#D}PNmVZ4 z)oSwX6y<$Sg$TY5aR(6-k2aAlE9ZC)5%S_Pg|35$9k&O_+9MX4=M7o#zKrmf!|ORp zb}lwapoI}3FaGvVqTdLVrbwK*!&le0{h47*Vj5rr${6e;CetT%ehv}x;-?B-2NB2aej?q;m3&Xd zUgzUGh<1~sd`}oe9OyM%zPF&1=}Y+RAq1mqebr1fU%TpNy)@TU99HmRu7I`Xdu^i=_jFg8<-!RXMh>#Z}{OvLR%t%@F&JU*E%Tya9 z;=foG$zGxQdA@ef-c0XCZycf7vY~sln2>3FBwt_ZGLq(~u?8Kw4%XG#n-koZ)(p{n z-;jl`5gob?B64rfAk*(??&ClNU+Z^UzmkQYB;=sL*p^~QFx z)E|E;wBUXDI#eS;M2$B6Wrf8npF@Pa_)ekgAY#;xQF3MaG9Fs+zWn!4O$QN<^LJ6l ziT2eMdttrNwZ}F6uLxs7guMm?wV>h_QL>5EQsK1YC$i#&8Y=-s09%b^5Q29T?aX`Un{Lc zy(DD8`|@?DMuG_Hi8|C15fSoYj?i@wLA_mZZ$}H>m;WBB=^!G*!(sZ`OKr^T6RJh_ z3SBdLPGleNVy`E5PJHRNk9D6rbqyk9K?GmZtmN^G8std7{}WwcbJgb%Aur~5ZE^?i z!K4tP{>_p4&!-7yW|;g)dLwI}4$UhbzX2E#-=vDy^=LXb$nmJ^C|z#ke4mA%gk~ax z;A?vOc>LZCB7USZCw~5A&~u287juNJgNQ>DN9wqVKl`4Fy*`^0<&7?zcP{xfAgFERVqwyxSv8lgMS$r74(!=(**Jzu-2E)Cb)8WuDNtkDpHInwrT z>SLQiH$cqvF_MnxF=9LUvXa(T$N`|jP_49n~(rQWZYKbkhV)1yj z#MiW1@_4nx=+Jeru6EuYpm~*n_u^~h3ta~hw35-Gl}yNj2)+(+2NASd(xKH7B0^sL zRH5r2;;m0pXkL+_1@G%G$DlOD^r(6_+>J>uYaPGWYop>s^cPPfRt?(coq8=!+^>=? za_6#r-tq@=qI=4+G>cZeUPfPvt0MbfEXJcw^?oihHpeBJhg^zkM91$^6vn!&;XD zht!DB8M*YfOci-`|9)>nrWohm^7JTc9%75vqTJ=XQ9|FCw-YDlMS38|FH%1kE;eh(A z*DmjyKjTFGO^r9b)pEC2V`RKoKdXF1*DbreMW^D$(K!P*InLR=U39+hwtBfPoKa{& zMAXN-z0yUei{U$KQ(b+wueUBZmG=MIeCI=;mwRNFSG)Xl@#MW|;@FiZLKpn`b$PLo zqb9fB?OobFLuB87FCy0&Iwif(Ofl}#>WJe_c6-HI%@EVNOdyVz3JKjOeMy<6eny2B zMC3WP%ez!;rpTC%f624sd7;-PMhg_A5!=@WV4j%NsG(=r@zCqErTNZ71bVIgA<4UQ zZKg=mXVyCUT6vUHue(xD-aA`fjlOfh+rK7OycyX(@?q>g@2yVpV*IRkBUkAI-lT4^ z;#dQhM(wb9`E=Y$I_Yn~OobLi_-BSnkFx1>-&B#aIvw^Q(9511FZiT+$Cpm491j_s;b`8pk%G{p0+|??=?u zyW`wmq6Bh{_h-#!F-oqB1v*XClJ==fD(D#wTCU(#BpYB*{6ndQQm>RJ$wlC!rtRJ^RCQPKb9}5 zYBlcf>m`W57?9&Ecsfz#zLin6$}z}?KreiE(XZS@G}W886-X>HH@n8!x%Zqs-mZ;t z;@%J2B5)?6y@}82>TTW5i;lTo(r7_MW_mj>s~s;oS3FAX@xRR<=rdhDb651at`LD< zI1^C}Ib(g@r}QZ|O}mr6nHmxP6~L8WYUVWsoi5QWyd7=L|m)!jRhFbYuN;#%tgvODI zh^d4gN$6MG6{7iS;wxG7tIadZ1F2v2A=FaHcTO$j|cXM(%FRCeFW5)s&AXl@Ub)KMQ6 zaZ9X=^dZp8Kh7WAEu}Ay7%vhJ2;Znh1onJVCk&?ZGHwm^KCNEIhd?i!l^o|u>qs5l zXN$M?kJo*(4!nXvSw%MYzULSkKt(Ngc+1{HZKAg5poPMuiVC{;DqP|)p3cl7P zkYmj>k+@`)xu%)=o84;k>aw!K*RROGv&|9%e_dxROKQc7b$8bov>%baetNyJPg$8` zx+Bqoh;);uiAj4_88rQ7=HSsjdZd)eOG+S%#n`-$o@v!7tTaNfP%iZb)n#qTsUU1QZi2udT6K_9TZ=Y&b_9%B% z$%cjl5$H8w@;tG2-+IeY;NxLp(d_oJ^SAe0v>;-6-?`%Pju6MsN$+{TkFPJeJrIFj zSnKrrKC7#!hv!?#MpRd5K|~E_mN@oeh@;GrrD{%%`ldY)fnL})j`Mg)RatJ-7B_;P zYU7agqTb2{ri5G4t`$Y*1$zwEI{nuD<_Oth&SRHLjuu4hd~J<58^1hMyHAVALv3D_ zkElHmfnL})+!O1VQ!uzE@>88HJlj0gkmc*e%&v3Ieer4Omm@2;qO+YI3hs$$K?Gl4 z*tEbtRg?Db%SFwnxZD%}KO*FXWuo;}wI%Mh?onD(PvjOH?o2RG#m`=B=p=Jr?mZP2 zPqMwFX!C6H>xUIImmDpK;99635o@2S@70&&$#gjl2O`jm>##zLSj+J}wMX+gk5#BW zLKZ}DIntJkw;Z<36}LIw3%#(`>H9obSBiTgS`fjtTldA;mczD(7ite|!H^fWjpNwy zp?Q38-~IMVuy(n(mrFOn+!t$|&JqfaLEXuY!BBf3g2&^P{p0OZML6BuE1TMCo*D37 z=!I=VyZXU7QFBk^`KnKesixj}6n%U;*yi}Ogb0p7%_T<*B6vK$zbRNI$0zo*;wm~rD>U3>f> z#TFBK4o=w`yLD-&$tHsHEu?9`6*GK)_g7L?_A+3i>M4(sA^{YkUxLC_k z`1mO?G-{s5PlXml?2TF`vNoJ-Io=yp-Yu0TN-+l_&}-(ZNtUDS!q3F^a@P$9 zS`e{m$UJd;#{|ofBF$nk;>^c}0}<%eWb{07u>AzfvAbl4K+Kgiipzl(MAWN4OY~nj z(Q+(|Ka;qvzY!y@CQP*)TP~$i34J;n z4n&~W#aq)v_kL3?$BNRMym9$Xh8(m+gmwS`RmGM4n&|A*WtF-tNiU@ zIM9L!ZvU;N*ZJGra3BJ`xG%gvWu4`){mSKXpal`!kDI1jZ#it=H5`aQFYePVKU{A) z?D#MoXh8&z$NVGLSPnY|4F@97%Z$zAYb=Ky=ccaEf(V{hnmEfXhn-6d2O`jm=a}?? z<(9+FSB3*Eh~W7#bT)R1bX4DM42xuK3Bu0lJ#BOr7EA{Kno&ptxczykNVR6+p!Veew>er6!PlYhM8`Q1``FF#X%RQX5xN(8;Yf3w z{#SF#Ij!Pd=0FP~xJ;ohebR-;YkfnGRcIL@7OKe^>AJ~13M<1bX3{h}4Er>s6Hj84U+o5W!RA5&WFwF0_(@uFr7q6HB+2b*=fqLsdRf7tbo z$LpxL7bo&c-&|MRJb_pGUU;P+MxX@|dHPP_mA*lnmA;~tzIm%50==%iJcU>KmV@4$ z9a6^mbOX(l>8sM4;D<_v3k`Z#ifM;L%FoaG(VdgXt7LTIpL3 zT4i{&(l;E4K(7<;&f%55<)D>JBCYhzN(L>6I6G<)uk6^Mj3nD7?S<5SZ z%RwuBmsa|Q0}(#2y=%GeS`J$23tH(L4hJlVuxk{{L91|=R{Ex2Ap*T-O)y`tmV;LM zZrq6mC3v-j7DO-~t@QmI9#?NH+6*;MDV;qD}Bph=Muw#2=wAPhF1EP z!_HTR11*T)`H@!omV;LMJSUodg$VTGxsui^mV;LMJnx#A3|bI@Gq_plD^_7~zd{6h z;e6~kORBw3zg$M@m(^LMjf;7_D>J0o1YT2l97*GAikF&e6LnS;b(S0>`?kg$jyfC5 zx0&KO>TJ-(i^X%)*&-bIqGcCjzdvrO;KmVfe7@Pd|)z1oh=7N zoi#`XA#@-TFFso^HiUXU&c{qb6~T*VUSu7w)yz{het82&hs=EkTo1kt!VzIf5n&T` zMhhYyG+xIMVf$1R5tbAYc9{ba=*8R=5w<;%BEm8h3r7ngc4u455n;C&ItEJ z+7mYS#iym;bfS{ep0L^fKns^Pgy34BJz@J)v?nZSPuRrU5rJM2A`>QZhZaQOYS2VK6h%J_2O`i5#|>q&7HzJ&FAtUjEr`I?po!ur zisG2|Km>YW%bG}$qDYacE3_a2SA!-Rr70R^I1qte*h3xXc<}ZlpHlU_xKk@QBK2w2=wB1N?wanBvnx))o`E%5vFazQ3HzBDvH*cXcQvQi~Cz> z9c&`P9z}#rR1GbN;69cdHK3@ops2IqKm>a6xCyNWO=Mf7ZWrW03nF-|Bu5SAtoYoe z=(*uQ1bXrK53TL!YhuWkE=A}~U7-aLJm!<52DA$xX&1n>2O`jm=dt9~674j&w9{ZX z(1Hm3(l-$=Nf9r@fe7@%m70mFNs6kOzU#9<%mKgjP2`R;WlwqBcM*YJzWJD=gDyn} z7581VAOdG?{^kn(i`IL#&k{|S#(Vr1dkz*|S6^t)t1{OiZ~m_zfnKaedR92j+{ur? z`ywBnQ|?Eg1rhY5g8u(sI1qtecuu*W11*T4GMF_ydh>O(Mg)4{Ipv6o)@VTlo;vPF zpal{9gzeHV`j?U;0=@9maX-gjy*G%#8`jXhrYwIlYKEx$bf{)9D?dR|zf@ioHum653wBUX1S!@5ofe7@%8u33Bw(YkC;zXfpNnW;0KWxOl z;76bZ5q!EX{osA|^J-)d zY{FjY=RgZ0x_^`;&P|K+9u4bHnJ>xzqBSDW>%xR2aY)2_)32TTe|3eUmRmD4QgQqz zGw_H)3nIAZ)BjUl`TzM5=tXmipqav(G+@_S#6)YfAOg$x-w5<7(l<#I?K9nbF=E%7 zegs+&@!xfY2=wayWs=yEa=KS}Ql<)ij(@(RJd#C8-aA9HZ^Rj{z<}xE=-4E$bgC2^ z{0Oul0!P7rBhc&8(COl@=p^rhkDsphBhZ2foV6+ECsiw%R5XRIzx}qis?09&eWmGM zsq7acCj62lYK)uiZJn|zqG{P(Vv&ybvSymh`B67IyTg`j5-mo3Jwk> z67P~+c#`fi5%Wab<0(rf*E2=u~} z)M;1$NE#W)bJIO|zKZWWdOYnNpOzx2KRj_;JU->N*cGY%F>+3iS-MSr z8F%A=LJJ~r9&?<6&GO0PyUNSBxPv|fdf^+@aWZu2E4|kWy2Dd0R`Xt?J-n51-sJu7 zMfgUPZ-zU&Xt2EV*NjM~e5^t*MEl2Js;GgoeXk7arRy;YEr{^<-I)0UWv%H$==`X+ zd7Dm*}dxa`Me4(h`_NzzhG9XjcixusaiE-jfV*I!kN!;TIR|pox)k< z>_1-6*dBbcAD!^$@#%ipvXpmMyoih$df0vYY;lbiMEHB+l)5$Lgj2=q!{ zdbdc?C)Rr_-)S1Py=Rt?BZp2FInPRs7DV{R;Oe@~Wu|s%bi%~k>W@mhDJ~l4HCdED z66clk&3B7)@5Olw52vAV{(w$b%kuuuDrs{wg%(6$O*_t?FL#nHUx-$LNjrTA^unj5 z+Rfcfj#+%gTebVBLJK0W$Iz&K{DC~NFonC~t(3l!qZigXMWc$emlIlyabJ{&ePa+2 z_@;K8E?b((jQMxFjS6h@Ah4q#EXx--nV*doL_t1-Xn@eOz{TJ$q?yp!JkS$ zbF0-(r@DX8$~Pw>;$rVT;&VOC%d;&9anx>JMizOr!7G*{(uY7VtaZoH8|uoR8+@Wt zyphdUyNJN@InIg=AIJ=?XQ^CM&ih&ry|DMtFJQ*BkdJ=4t@5-O=j$bi@YmH>KR1`x zhosi0hvfDl&62 z#D$2dUY*6<9vRa&l<6jB*FWAWq0oW|Y)!{`SJsh{tupI(^TzuS=oL$RohwfDj>QV% zXi}$vy!AtB{itiaLJK0W798jP$JJ#0oHta9OsO>@(Cfj`Cy-TRB@^}t3{{{1h+wn$w!4VKiXW=&rG;GMMe6Z zyfUpuYP%LOzp&Bp*FJPPxb!JdhWcECq(*=!!%kDQRd7A zv3qu1gQhrK)De;JfonJrfnIlSo)^u2sADMLm;>!%Xj0l=vMjb0M`{F z&}&ufT_GYi1cG&yX+amawR=9mb%hp0w0-@d=rZVbWRT-&-D_fS#tV_mfe7?!Q|y6Q zJor{*kYjwKZbnti9B4s=y-x6PBrwOnAdHv&dxEbViNIkjcwbwlL|#Krh=)UXa7~E5m^nMA$xNIc(oG9EdUwl70 zPX7Ki-R>J7d(+ws^SwC{;pZ6kTAbUuVs$l6_wymp%RgVeetCzxX~;O$d_hNz7DQl~ zD8ub=LpionHhnF9N#7d>-zB|&-Y4eVn&R=B$Z@uptS{%SOQ)w@nX1r&2sSctZ;3DOo#+XH>g7(|ic@@;}w-Ypvyqp7&M%JtY-d5V6NQDwcTBmLp^9 z_vPpm>2$_?egt}9jX2H+wfe{<5BjNE4Pw--miI-}+Zz-4opC3{9Z_ullSHmjtPxrv zryC#_r;1UF_m%e56(YKJyd_TMdci)`>~DL^okdovLsd%p5a@;V<~Sc;9W0x^@pa;A zYLCi)KN8z2+==9;s$J<%@%M*!68Nd?-xGqXj8_kQBC{`=K@`w{4c^%i`pN%fBjek#iz;1XJn0F>O+h~wCj3n;m^G?mJxmG6H>VAiXH%>VvnxAOsi?P4w15p3&fUybJS>EE|p9v^5ygn!j% zX9meL10vAN&J32r&Y}`#QDZ@bol$Lj*qK`LOpW(KFZ<14Iof{y*gcwKsrzQZhPvb* zdqhHDinw?$L!@0_3toAryLCh~l+oteaV|I9?YfP}xJS!&^dZp8zSZnH(TOc42cZRSUy*Vt1RMaB{D zT8^8IkGgFW8mLmmI%%{Z0@n|Y^AqJ|eDJ>y3-Z_M%Ytok8xBOE*Q-nKiOWBHlNkIe+WX5@_p?+xJuU}Y5P|DC+6fw*OD4pA z<#Amh0=>4@cqB59{yibcajWc2xB9!K3lHiLw@@45w$FLN*@Bf>^$!U*FJk{Rgi9{4QlGHf*LJ|z!}4F z&L65LS5#kYI1qte{#9Snihvw)e4Ls>9B4rV&KQ)*TKavtrgjIzfe7^Sudm*z_m;f6 z;dN6Ev>*a!4EimL?k#1N$#*@jD@34|f1Nn|g?D7dj&nRN2U-w;GX|aFI;ge$>2|k7 z=0F5`;VQ~;YTSQE>M>sixINH<2%KZ+ccW^zlD8j!D}ckS;n2&!E@}L0EmaDA{`HPQ!r+^ujfY<4pgdteijlN5g>@MBp4lD!qEu zWXb58?wc#Zqt>i(&)o4Kku4){o^X|80=Ij5snd^q<62pP$ z5_|TDjUUE{tyRm>ckTG4E#<|e6moW@+uoyWN#b_j8A4YrTdnDhBwATa7o}cZ8L^#q zEld9pFY49hUCTlhy2(bBZ;E`!j;J`==h)OgR-Ea2IwEDsU1Bl)zGSIS-~WGzFX9Kv z*P3@1IWEspcrQedmPPRXtxI|qiYJ~JDjU7MQM9bv&xb%S+9wvgUtEj!is_W&ORZ%& zin-6OyvDP8LgFClZ?H_XyDNAvH@L$)W=J<#qRM`ER+qdAEr`IUrKod;{&MF0cz5MD zm3#>FqFrjid(y$3>TY)i$p&w=a8G_+PoV`7{&Ji?+EmUzdsyx6^*=?L9>MyLjil?T z{%w*dHZNA>Yxa5sX+Q)kJF<`tgd!6)tI3YjQ|e~vZY#7Pg3n5&GgIw(sYy;L8U1}B zeeCo>9|FDjY*tow1l1y+Ke_DoDzsJIxY1bi`LT44tT{uL&v~U&Pt94c!x!ul8OFtk z8f;osy$(~X^EopK>I`Le3jxp1bSha9B0CSymDXN zjQX`I`7~M(!RNoysjh<0fOVYrTD&X^^~r}x^E zdov7P?K=Ist3kJWXtZEWe<3I$~I_+S6R#I+hGS=H%Q2G$) zh2?Xcm$SbmV_uhP@(%@kB}W9-y5r2~*HTu#_Luj!V(WIja zEr`HTKxa-K=`DxssH8@SWj+LY;VeOQ^-4oozh`#Y<7Rkw$$Tl|7vurj1sruWMtt<< zyEG@BJK8|rEuBWjCrnjnL4)Tu=rSr)gD z&wjh@USBp=p#>2IX@@s8{f_v(bG*ab^HOt}Vn}LP;ou8C1bP*%xLZuV5huK;{Dde{ zzqy>#HI1Bm|9bcE?62Jx z^;3BVw)GE1Yt4EW5&phgw#O#-tv?@&PSN4LRD(b-{BEaTo2Ij!-x-+E-5=M|_kE5C z9FLBZ_O0}?(tv4hr*-vw2=wy5Ik*1PQhr(~h5RDdZ4cjlSU)&xQ|?lg4zkdtWc>$+A-3p3D$+=c}}ZlwVdW&Ry)eq zi&?$J+C@JDD6pSHSe>;&BPy)fHVE|M`!f%E^L4bgDo?VETV&Or=Dt=H`Y#ByAi}Cm z4H|i(H6qXpYs8O03nHv)_Fp)Bh;efSE3)aHi?OEt9Hc=OtZ;fvI%Lvu3f5z=meZ=~ z{-xwrVQMT^vu&=eGTZR^Ik5j=zhXV)zqbe8%j!_geUaPGffhtqMXPY4PZs%a1bY2< z$a-eTWmvwFlfLnDAOgLx*8K>qE2|eZwQIGibUkIcAAuG`aDU_fM{mCNk8||0 zs!0+5oQf4Kh~WOlPy9RwBGBu(!L z=akDhq5jF$Ep#4vU2=v17=trOh5jJPzUpNqfUN|=W95{>OZ0G-C zNybELv>@WYX9h%|7k*zQGjMN53nKh$(PWGtfnKL7YVk6)U7!9gP-5VDF(^uUt`z z71FGZMg)41GFq^bHK>jzWwgf%X;w$01ra!I=&av%X(TJ8SshKvXu)byR!8H!Lds}y zp1z-h>S$6%yR49Abu?NKfi+ER!Flt8WHG)PwP0Oj25hrW_2`L5P?00_Hh=b zP^^$~UM zAT70EO*QMOaYiOBwO|Do>#6;1PFiZ0HPx)AMhhZHOD$N{8q`yhmRhi;n)TF(KrgIy zQmZ%k#AQu2>#5O#2rM7XiLGb3tf^)_H6qXpdk-nkhTe3yuV^77W=!<;D@6F~YRJ8m zGOBh9S#Lxk9|FB_6gUoPsU>TwSx-$`YQg#lR@RV~TChTz_0*)L797tC?)H(ETC%2^ z_0(uV1oj2`orzYNC2Oi#PmKulA}zJxJ;|V+nzYoCHPx)AMhhaa795AP)GlkPSx=1! z^dc>_;8;U&H=MN8E^De;Pwlfnuk^L1Lt1K=HPx)AMg)41mRhiWFsP>{Ew#&w!4&AVXx6A$bBZPam3R|M82(fyjpUZ8?tq zFQ@y39ws03DW$I8doS=}ibtjeZ$>N$T#*mV^|4$_0-vRMU|TRlBjKh>74JU%v7bhE z99?yO9w0KUIBwTIT|PV?NZ3!x;&#JybeY_Nq)YeBnrh1a+=0>89~durX;GlOxMvaH zW%wdcb>bDlN?AmpS471{fyUMTFn6L|fEo2go!AcUtPaC8S`Z;yWDvX0{bo6S%a}s6 zoqEo2_z>VVW=DGQ-Nl=hqk@WI6sywNJdXq@m$J3nKir`|j(VMZf3f+0$1KN&BM(Hj(ov>8 z(1Q2H)^r?F;tE#ea(f^Gy>RVIG0V6+?gyV%kr~dW(l}~ybp3L3ptv&Ugzbr~vz~G* zk18(Lwt7{g1ra!INO@LTyUXX~lD#uU_z>uY(o^anxYAp}F9iz~Kh?aY+i(!wh*zqy(oqg`d zNnPcayG#2J==IKD)kT`JzgUhx7O!!06zVD$KAo!2f`}U*WE5q-ylpu)ZlCY2AJbRP zeY2zwfnMi7&L~nJy=^&${`R)J<3c~Vh&XUO<2XmO<5Zg3-#uM)uuRjVq(TcKGE~SQ z+WZyb7*~3VJ2+;5Y*osSKrjDO^}4oJO#S2&*`QM?H8Eq}z`47@*#~E$&#&eQoZj-t zmVEv{m&KkcgXE;RX$mcf!1B?rf6q!1hkNyuRpuo55a>1bVxGWfYafZP3-Ae&+wUnc z{L_}QQ^iyoEr|GsX4GZR9*V|MoL%!%nT2l8BLBFfw>I?6)Hpw4pLU$MiGy4>(|-5N z(2l;oiwGQ#GzP_Iu1-oVPc&`hL!j4<$m*g{{VR4v^dH05fe7@%zCiktAHHy_E^i=5 z69-xlfpZsWSnhxA7MxVclmijy3O{Nk>y8<4-IOz9gR z=!I`0$LTbSzH2{fB4^#0>RVYN0^bt!>y&vi$Y$x@liOb`=|i9wu7gSMvqifTzUwLP zkIka0RQ@e8@483g$=c|MX_s$CCa!-ZYJC$OF*uVGxO)7NC?)dIT(bI99=CsVFIhh0 z_rCcGXCgl$@8{dxk4oPWY4Y^a7r)6CX!Q8LDEZRkh}J2y1-d=GFM4hHE8?ehSp)0x zJfsr`_+;xxPkPH89f!Ja_nM|2ZcZJ@TJWJrJ3b-e_cmz*!&5&HTVpmvjEhSdxRd^& zSUGqsMRD#g7$&ooc_ao8a1~k*vE^3kz-8iI{_S)^d{4@nxdR5fYbVU`5P@DXb5jQ9 zrFtm78^;`nXOEC+{<%F*9nm(TF7g&Zi@G2megoL#JLse0{=(Zdq7!HZ13Am&XPfbfJjD> z;D9jG-3UlhF_8o$DIk&sB#gk2laezi2uRKu=Ikm(5F{y*lpsnFkStL^{dU!<)AJS_ z{`dFYwOIE!d%wNAD|L1EuBT!%-g5VRyoVL(d%Wp4>w3lQP$Y|`K(FCnq>lTSXW@VB zR=d%rs-D6tdhWbCr{X8p3>oX+9E0p(tHE0*%!b<5T&6Z>FS zin#MR@4ADAzZQ!#1AevCc&t0&SiHaVR0(U&fU^NSlH+8aozwfIP)|SWr~L(5P+|9| zZtrIGW~7MsKfIsbQlOXk<3jA8Pu+E0p?YoQ21C3zxApJ~R?j5Rf(q>Od_T`#!Rxss z-oKirC7}YnXveYGiW%>^msfnrb$(`BIWNoRc)vo8mV_2m%q)E@_I9efZpmf?S+VNP z%wE1-W&I}?#z?%&U>zKLGE>~UdG5G{I^^c-i0?Vbo7gj#pPyShT2O(t$!n^AJm8I7 zoYT*-q`aj-ui{Np#dR)n$1Ucn6}buTr}f($yzU+Qrh-HZDzM-1I{Ht_`M>PE?zL!| z!BU_Xj$@8iOH)jia3k2NNu7mjw0Q><%S-}`u< z7qg&*H6}j0DOue7Znxc%uMMh#v6&z+><$0&!j%4;grQapRBYzEL9)Vk+^=8V#Wk4! z*>Zl|=A3?)=|5Wv^ujXaS;hv(fA^c0{R=a{6KFvNwn|=WSzx>8ZGPDw-yoS)y6A;% zfnyBq>>Xa%#4nuvia-l0@P5Us$yep}o_e*G|7+p=Rx3d-Y@z&tv2G3js8`5;Z9`Up z<&(MO{n(HHx$U-XJ+KO16TeT~6ytwAs;s~E+iU_Ys3`yEz1Ug&j-yLc)jzW2%;7&* zzqY^ZUF=zt7)t zQ;*-g7S*5BD3w@a^d)_^w&J1d2+n=M%xzm%7dsP0ffl^ld(+k=j;wYQQJxg^Cw_Ohg5GJ$|G{3o5WJB()Kh`+*Ad!n=g6Knp4!->y)BUe6A>6&qXk zj=Q(tL2ilN$9*jtr@ZEV`f3N+Y5fzSA^iM0=e?A%oeO6UmHOwV`_0z7RnqOq9J+Py zrh6#aeZJRTZZVSPb~@)S+tE)w6@}nSLn!j4p?CXiq4U>ox*75%=ecNZF_YG|?c&WW z(p#d1pO6AYrXx8+`T0vqjhpFMk$r_HYWKh6{xYkNr9dzHta?;E*jS~+fz+WFGVpP~`ld>bO({bTKZU=%My+YMmZ`qn`1@7&TR)>j3o3G@ zP9JKR{+8P; z-f;F>XNBskbyJ5X^E2n{d}}yH!xWw6jC(!3(x=A=w4lO{F}QTRyzk$V8AP8PPUvTTFH-#7Jh4BVxRrRGpA83{D-%1&&IpJDK3PsCa*m6Wa9T zUAOmSm31F;Zxp@uOT0fSnXN!C`>dW!o=&{+Y;M0Wy&|zK@sn35^6johp-iDF{H*rO zN9tLvOYY1f*S50$ft4{5EvUH3>KXi=x?nZ+o_bl2+~UZ~wftUX@>>e@!ZPGtd;ZQW z+rEC)o&4FGvQYaBq1*gkq|(u0N`zwdwd30iAw*B1eG4f>LI74q#mn*90 z@=IkJZYj_UTfXBo9ooxhUwu=gTq(1#lNm()1MR(pt*HWMt_B5uXof<6q4eRCo z*T0LzI}45y*jM;{``S-Lo0yy4-W!dqJ0~h|#NbT8)(6C)IXV4n`^#Gj^uiKh%I4Rf zi&JxI`JW83%L*0tSTd>9Oz~aerhc(*hpqZRFT0ie{Z1~CZ)p#I(da=|ouk4YMfax8 zE>8W`*S}l9zJH(>-b);3VV1e#$M*ktr%SvpnczWcMUbL+@K6isUfxS2;?`fY@GVwV3=tNB?uq zPCyGPI1hl5vJ?JXJwxp3+g@iUpaQ-4>mns(K#a~XROIN<-QO{{w8~BhEU36t^g`&5 zx2~HEh_2h4i;nMg@xQD%)>5Dse$1#E4(KDR!EV&6W($0x8KF_{!R3iqXiZASaPyzGTHBNV?W1>rBn_} za4hty(rpASU-*N$@@EUDlux#J-GBPyF#;{9z_E*Y0Ka6CH}=2bPb^x>QlOV&r$+Mq zm{?95m@lJINCW*#o`H~SIyM^&z#AD$3idrj&oyKGqG^*k2(fgP=TX1e>Yg)Q{4Q0 zuXmJ7*HXYe1Mha6lRCl^oz7113XJb+-3Rfwc=vIf=4F2ouT3lFzg6*RmC+d7E%Ba+ zu^p#mpEF`t_gMe<`V`h#p#oc_<2(`CB$9O~r!xoeSm=di$obTzLSlFOT9NF8pgvH6 zy^FtKy*@@1xmG2Toe(I{%WhW(W_>Dtx&MZaffiKYsN^`aFI5){uDqmUpaQ+HP4oQf z&59y*Vj~>`EvUdziL;|$_>;bw*u=lUb8A$f7v5Kx5BFqhF>P6Qe==u4pam872sfwr z5gM5>-rvp{5U4;ee5U5-!3z(BriCym1ji4obEbrlS_K>?g)k*VDq4slg)k*V(?S#} zgef6<#k3-YFeQZ4D(NsOgef7UXd#Le!juqFYnv4*gef7UR{JYbh^=5s2q{{KB88v@ z6-)^swU)`(q!6ZrkfMbsQV1&0izy+b)=t&bq!6Zr2t^A~q!3;op=lwC6oS{pln_$u zn!=k z65=UZh$e-+J)YFMv2{!eVM+)oeu5%}FeQZ4%CsjmDTFB@zM_RFQV3d5!IThE1dQSZ z3-D7aQ$l=23sIyHRG=4ALP)Kb3zI^a65=UZh$4kBC4>}_;>@z+RhSY&iv2M?-{LAv z2_Z$12$MpX65=UZh$4lc1r>5Jd_>1$tpA@SBN(n@G_@6e$E-J5xePt&&%y5T=BXq85Zn zAxsJJ6fH!NLeRpL5K{bvx~a}rVM+)oCdi?Jr}@g665=UZh$4lc1xp%_#90=(-}V$O zM3F+!f(k4{-Y4#@!LFi(C{hS2&`UQ7ug#RLhHLYNXF6)i-OLePQ=ri74UTZBm=ObLlov=BuK z!RK0RyY{?Q=^d#T#FD8X_ zO(3;Cod5gF5|!hrSBjNd&EBL|em|-}3o5E~?@qb?{YtA*l^{`pUVL_>hyv)XekVvA zWpMPtJ1VLYvmleL`T1f5(CRBOR?GX_7mOo zx$_wXli>Otlo>8tG73jq!`<~_a!(SnMqZ?2>wzw~u?K9}mD z>;zPx7qbC^wqTzXT2O(#;PDFdVoJzk`XE|R@%SEv3iMKE%h$;DVgD~dq6HOM-cO|X zvvb|OpPqauhXobrrOJ?PQDUG46?=bMOc!&mXT`(h7F3{@>dn!qD(HnzNRL;b1r_-0 zgQb-qQGs6g>|-mu13Rg9*@^By^%K^K`8%oK^hxfXS~u6W-LRA9{xZQmIHUVR`EY1K zMYTRV>7`#Lxliri{!rV+v36L8owVlec=xq+Z~i~VU94wRU~Kz3P=Q`6zTQFC&P{ex zb)K@)R-gqHkG~GQ52{fj(q8RnwWKHs5-q4uqigh*hzj(2{9O$#sKB<6bWZBdi3;?> zJF2Zf3o0Jpu26wq_S1G!6wUD>Rl<(bqcBssh)GcV`)*;?(^T0d`G$XKDpz1Z1@pFu zNjF-JDqDeG>YCKO1-;ep1ZnO#+G6eu`ZsfUh{;@0V&HL^_C?I!(O!>_ffiJ#FNVizwx0TIBz&C8EO2YUq=F` z;jukpL4}!jap^v04yVfApJLS$Y z?SClHOPy`>c7+yHENZ%ghP*t5{#upkq1~EMfnH`7MNiHw^^l_ek)8C#n2D5PRn@iF zuBMIJNp*gnMCI?i@DOnkEvUfQcIl!5y?z+HlRo@?66N!re<%i8P+?z(+Hsn>YI@gc zrWvW7r}eJWYR75js_9*)nLtF$Ril8b<}z1J7_J&ISB(r;P35zY;i?gH)y%HbYR75j zstLnY3oPcnpH`Una};pZJm#ti!&M{Zs_9*)nJ7lgRU^Yy3y!3@Y94ddgyE_M7E~}X zjhL%O0awjqu9`4hwLpPh%vB4nPjl5g=Bi1P=WVE{szfAPBT|c8m?NPKrg)SYOb2cTs3L9YQ$VMz3Vj2GH{N<+0ne? zG;`IY;i?5Q7G_fgY8;O>S4}WiO&YFRFk?Z5-FDTE)67+qhN~7R&8c&4BW;Y?TS3iguA0YOHEFnN zfdv)JKMPuq=BjzjRg;FR7AVk*2~@;fHM8rq+Hsn>YSM7k0t+gbixu=6%~g}kRnxmp zs~xAAtEP9I#&LydR>WL23b<;5xoXmI)dCADu%tCtO)ytY8m?NPKrj0`)Q;24Rg;FR z7F-7^u*GPun#Wu)sE9lNfU;WMx0@&$5*D25L43h zuG4l6svW19lBRc^MhhyKQ$dH19ku)vnW)1wz{okj(EVVl;JG|7}Sz3a63 z+DC?xModZ5yH1<$cob05BvaD#uG45ydsIghSeu%XCYh3^cb!HBdNE0fn3868omM+e zGbK&$I*k@oV7X~ZnqW$rG?cWYV?kM&Z!8p0(gah|q@kp#456?E6jp62N}6CwnlzNO zK!ILr$7!adnO&#Vj?+v@lZKKOSWtnjl3U3eu3&r2uCa26OOok~Lf?1$IFOwCjkE97^DvMPZf|<%a)fQBkoH7%G31%u&R>#0& zp_j>SH8D&!u8x5gRG6GH6N3q6D&tqjKm~f4EL{`BWEJZeXhDTtx+Zg3$FLOPTs3_r zCfnG=Fxk<%KG1^4#oE*aGh%|7j)4mF!da#!mB3Z1DD4K*be$9Aga)f2mq#R+bKrfU1 zYhp0-Ofd6I8s?eGBz{C;GTlrJW}XRVo=L+z3l!*OvVTnslOrrujxbtKVRCtm!sG}` zl_QK6RG8d2b5AY+T(EnXnLIY8feN8OGDhGh*hMRLnE9pn_QqA*Q5Jn3Bd^H9FAY zLs^lzYN$XjJVQ-M6HG}HhLRSH)HpiZJ&Gx5f+=ajP|||_feP&Nnvy1%k|qr$El{AB z$rm-fmMLk1DQUt`(p2`Rwx9yXE=@@jOi9x*@L1?&ay(58rlbj`r0E!FK?RP%nvy1% zlBQ#z0=-O*r-{LoG-67cj)4|b;Jt+3r8ONvOi2@llBP1S^|8>4`92}0h?1g+YDyY0 zB~2JgT3|s1-V-&El$b~=4UsfZm>h8(56{+dHib^mbI;V2Z8vJ>S#VaU!1ksoX@V(f za#@&?7AVjQ%TQC&1XI$ap`@uSZ+#}Hz&@`jX@V(f(ooU@1$tpy(3CX6lr(85X+gU} z1&)uJk|vmvrmq8!g92NVR$Z73hWYU`uQNTQt%sdl@c@|>k85!nTh?!?(m}enoo>9O&lgvCL!#oQt zOaTfM%q9yl^Na%KnPldfFwC<+fnH2DQ>(BkV4g{4o{?dm1r}78719(i&jd5i$S}`> zt7U>&h?!?(m}hY1%si9KJR`$A3oNK$Hd%<7XB05cBs0&1VV(sF^kR}yh?!>;FwZ12 z&&V*(0t+gbW)@=R83oKU$;>k{%(Fm&Ud&z!G4qT9=9ysT85!nTFsEjMSy2D>=)=r2 z!OSyZm}hE5zn)E^f~ix%^=amrVCI=H%(Fm&UiO&C%rn8vGhvu#!3c*69J_dJM#2=@ zf3&~6R<%2w-|d8k<-SX~vR98~=2?iDXJnXXYF)aypZ7{XlTvq$msLuZjjUML7QDaW zksPPhq$zZ?P7k@}y-5NssK7flfBmVDPb^5)Lmt04)KZ`q6OW(|p59hYFpo@@XC9eZ z4@`S%rmK&XJ|nMv(OTmt40A=O)ytY7Gka%D$vV5 zD`vL|X17VjZbJ(ym;#r`q&ZTgIo_-BzuaQepuWP+|94 z=Bi2NstLnY3l!+Z1hZhQ)Lb>mTs2|1YJmk6cCTfwnq;mT8LnEOKrb9oHCIhCS4|kM zS}=;5RqnX4uZS1nMWmtDHdRg=tBlZLAn zlocwly=ktRV6K`pT(v-fUUn;Cu9{%3nlxOspw3Z&{ZVt(1asA-;i?4+^ujs3=Bi2N zs!79DQ#1lyqJ~mHhN}i;#auPXTs8jks<~=`1r^LcOJuGZ1za`BTs3L9YJmd1@R~GN zO)^(a8m?L}%Amrq0Vv?A3FfLv!&M6u=w(<0dM;sqC1V0jVuo|K$uQ4C%seB*JPR@N zj2>m4DfSLCuPDCWsltY&qrW?G{32F7Ocz57DpWjX zAw`LS3iL7@rYJGcf(pZ4iV_1A=w*0PQDUG46^e_+G`lD7{`p%)XV9@7WWf(lh`Oi7Cp0~P3n z{r~YJ11gwPmB^GddX$oe$3icrStT;fio!Ijq$mlJnTc`COeDihjAgRm71&OF;|TYS1pdYYGk-- zam-aC!&Qr8t{MegHJ7<+WVmW^@ckn$@=V3_v^eIfQNUGmnX4uYS1qvc^I4$amHu(e zRil8b<}p`|3|B2spcm6`;H;Rd<}+7~3|B3VxoTv%YH`d}Bg0jTW3C#%K`>l3pSfye zxN3ogxoUxeIXrR9Ril8b<}+7K7_M5NU@B7_bJfUj)#8$#=$WhLGgplaS1mXzCISU& zrl-X*SB(O$n$KJ{VYq661rtghN~7R(94k0&07QJs(H*+lZLAn$6Pfs zT(wx{s*&NU#WGio!dx|`q`6EU(xlr#z`X&zJ3grTGb7N(>H3T8S5eN$7?e5RxcLrDu1 z=*5JlIHsggKuPnNk|qr$O)-h}+?knYu}n!LLrIHcN*V=}G@mJH(ooU@3o3ZlulURQ zIYCp>e5RyHLrDu1=!NZAQ__5nlzNOz=8_qpF#g%N}9)%G-)Vlfdah@ zja|PLVbWCR!yZ%8L8)s>n$MIpX((xd z0=?{3!jv?hDQVJB(t`Gb3cCiGlIAldO&CgApg=FXwKFBnXG)qdl(eAjqQV|`nUdx+ zC5;RvEl{8rQ__N-rYUJ2Q__T?qy_g0ynkR{(UdfgDQUt`(t^H*3VSSJN}9)%G-)Vl zfdakk(q&4T$CNZ_C}}}ip~4lIAfbO&Cg=%ak-Slr%Sz)xlpN+{ia?F5Qfd&y+N2C}}QJ z(#TNK+{m|d{)V9T-7@zNrlh${NfU;W7L4sUXW%bQaZE`w*$HMRGo1&(U+>j!y*fjH zzv{b@947vbr}m;V3bR`psk{tSpcm%{sNK?%@)^{QY&xF-EvVq{cxu--6T|HKrejzN z@ZvlNwdJT8C7bD5H6Vwm0QbPPNedU3vn+P%)iFgxT$az6qKD(uoV zyYT54cr5hdyc4wxpNV01`qTA+7F1wuYD!uhQ_^${RG^pH0no%?N}9`*G-)Vlagq54 zws!ua7#I1P$$O0Kn&&blO&UsCU_k}m+chQ4WlEYfl(ayBUO0bXLTq>+MXB~tbJ@OH^lxq(mbZ5=@@81 z1&-R9lIAfbO&kqV(t^7edNHdbxZ7z;n#YthVJK;V1r>Pr(UdfgDQVJB(t^7slPQ9G zBA%_LqnvQ`MRN%OxDQO;4(sT?|pcl4jO-b{ZlBQ#z1r<0xYD${Rlr(85 zX+e)dFMJl|vkLDyDPhk^J@%o(9^1{nmQw9&iN``Ov#XUE8JLphF(plA3{%pAQ3mUr z=_f8z(kP&$`AkWZhLYyq$-ILMCCz>N&mCkaX)aUJD4?XdOi7c5lIAicjSMBtWl9qH|YJ`&JG9^tKN?M>mFJABLG9`^_MJQ<=Q_`fN zq`7tf{f_p9DQUqq@w$DNDQOf?(mbZ5Nkd5sEKErY6wI;-Vrxp8$CNZ_C~1KLy?8~o z%ak+Uz$&@r{C~1KLy|5HCCCz0@nlzNOptUm{$Yn|z8A_VVlr#z`X@V(f!cfuz z3v;7frlgUfq`6EA(v&p8lr&)|X@Lb5Ofw70P*c)~ zDQVJB(gFo~F;ywJK21pzOi7c5k``D{Vb=#!(ugT((ooU@1$tqh*OWBDlr(85X~AfK z3MLQ*y+Bja1XI$ap`-;0^ukfXahMh6Gb>Df&a5ydSh>suBgF(`ZkWqNF;YY^rcSxc zBcm{nY*NkS{?YixvhHt11X@s0snU4&3fFnN56bfU#EH57^m>2WSdOnV+ESpGJ?=8Q z&1ZI-H0-uuc89Y*=B>HRZlm7iU*QlRf zb{mD+ZC|8H>vuc%wshycs7P#q1r>Nrj>BBF5OdXp;i?7C&e+=RnGAE)h`DOQaMgk* zY*g5-ow;f*bJc|5ss#%4vgcRKRr8puCJk3Dm|vj+d$8uJdCXOlhN~7R(2MiwgL#+c zs`<=SlZLAn+%2(<;W)3kY94ddq~WRscNSD&d(&JskGX2naMc0@dfB~}xoRGB)uiF7 z1$__|Seu%w<}p`I8m?NPKrbu>%~kW5t0oOsEf@z;fin)xRr8puCJk3DP@tDxy8RZN z7h`TT@t^y*zxRb0P0OyWqwM|a#T`8{mNwVgsDEePJeIzkvXS!kZWhOxvai&p@3tLw zf2`Ht-_U6cwS2%F^vW;9oj*06&i=JV|E^qgJS`i!j%ux~$cmvaU!YMvUh~f9?&G6n zLATFHbXlXl@JNm`;c8(~s9JHa?Mr>E7^s-??Jzodd8vs}cj(tNtMsTx&I-LMmmNXR zo?oKRkk=K>dP|&J{JpDUpam66LxX72ka;FXY?CuI>-B%))Rm(Gy`Jkdgyv?PXJTyZ z`GI(=;i@=3G0X}pP1F!K>Qn4uP_7^pz6kAE6U>u-!VG5+r5i%JVq2^9k^sQ6<1NK*g8 zbzXnmLQ?-!3{;@kKl?_J`lnitOtHyH)L1#Xt)xRNqi-*~H+!q56o5feQ3eeM7bDa17P|R6kTP(1HrpdsUwd z$9Oy2Hn(Zcp*jXC&`XULs;`G*s8KqdD44mLB-Bn)A_q}KNI7x!Bxdu8N17u_9R#e^g8iiIwh>=XJV{)F|XUIZ$J43 z$3P1zj(s?v<~`_dVjS+C*Be4TbPQCW*VMP?Q|I{uOpLo{W_bCgcGFjm7F6^ZzmNtv z;ZjgsgFRldm96BKr3oG?&}+o%8)0Risd`kP~l7?O^kF;zUp^hlS^MY z9t*v&#W+r1kxAxm_Lh!;tpw};^|HfB{R_9N{sr^Om;QT6Uk6%HakA5JQvbqjH?G7> z^3X>`bXlPSy;SQ|@xw97=c^~59hFYk2U<{}+O3Kij-gt*YVoSIqXNBDt5xmjy(9}*2XfH>@ zR8qx21$q@tKA+CsNiZ>Hp%-CaL(vBqdvVRGHhI@W1s@P z)HSI1;TRL<{2yRvdG!(pVKi=VR>;~sB#R)*nRY(m?CD=``oTn zEk!J-z&X6*EG?Bw*65wtRrP@i^ipj~wTEzw{UtAo7O$*yRog`iD)3pvaR&XGPF|E< zJrx5L=%xCGYS-ZyP3G+tBRcf(R1CDB0-vcIXIg__M6V})^i=;q1$wDIu6lGhM)5zU zh()tD>lkQ31wI?{lkiW|MX#@t`)Vvf1$wFRMU6Az7^^lk6Y-@Edul8}3o7vG)p6>s ztKol@`=I!1$KTdG(Hgs8#>uNWT0iG!KX5>NDDwF@XFvsxV?6FYDCTdOoLx@7b>Eto zpcl??m=QNEwf|YM+_K5m{61PxfujyJSV$O{6VNXM++)&RN|GzgX+sR-Y}u+0~P3nGbhJ+=2T7D zId?7{11+e)QOR*mebHQ=%w5D)Z5I{jg);-k>BzZPxRbWX<*o6A!A_5T#GnuCFSuK}LGySi>yxpxK zp#>G8xp!z?>A}=z)nr!W9Q7qF`K7acS#9o8`>G|Vs7&i_PyonR}_ ztL^?vwCLv{^j1w3BlClLqIc82a(vr{@?50j`G-=sn8~rjTU??a z@(!gNI>xu1>WC}z`pQ#Wx@bX#9b^8D>Y~|&zH;J23iN7l;u1A|Fodq@7?+P#5Jwls z%PBn?5?WA!*W@@W`fLylf8-s_yEmkvm5jM=hvR$Mp1%^^Nt{cZW zo$75dxM*LQ=^+JrVcjqjuz8}Wd7_gn#4Qo8qfns}w7bhls>tPoWytI3Yit)6k9LsN zTHB?IiaM_yqe9I`X|?0D-gZRf-`-C48)GZbYg5ld6ua+J%JcdpzK*-~E{NLk@5$w# zHzc&6;&7#dbcxx6FX$S~-Km&No4K0&gs*)5fL+w?&xy3~ME=;}?)Q}c_$2ztKVPNt zz8zF)`xLr1Ya+*3-yp3N)f&qs)R4aVeh-amJ%LvKHZk^Y&Vw|PX>2pyNwIc}oX_4D zIhHqO{tylP`&0Vn6?Glo&b%XTENvkVaJxbUdg1jkPkZtcvP8N1a?4^{ zG4R?x+Pi!lmFKI)vvr&Sn{vuVFTO6T@|B|n6`vK{M{}x!S_sfN4WoY+{a#j0=gcelHvUtdoJG>zC7G(M!_d!&kSM@Kyr6uEM(9G5< z#@u!<%6~JLlj(;vB($Ic`O8ewndfpQM`@XxM^RLuSITb^sdmMAboKWM9OL(t1I5(> zj{G29eSh$K^XdDpt10`yn7G0(&8N6rt111uN^#XHETST(S5SqQD)IAqQ(iAI_rixF z>zt4MIZNl$mNILo5r5&y&|^NmJ!>`Hh>3~I(smJ*^jFgGpVXJ1%$dIs_gBpk-yLh? zrzpRSp6|AdO06#+_iys0)L`Rsx;?afT*cJOs86+Jv^%R({CIAbI68i=*t@xnj}}y1 zKD3xxk6uCR4wqMFRcgMt+;@|x^ioSpfnN4m&1;z;j&__ZHq`CtqXiX%2Q8wH`mUr< zxeDs6YL*gv`n@J974Ky!&)f?#ZT5{CH-`D5oM@cA?{}Dm2@`Q zV(R=tg}8GWS5m(9i|EsX>dL3q9xs~RNf2)y>*%8e75P73K}QZRrdc`FS^d&@tvDE( zFPfEYWhu}L%aC`kD7`@Ry7rYg9sizHR;V~$V;TL?Y#HU|rqMg-M zyE@gXh}b=TKP9{w@AuBQhA72X^a{5tEVsLTSJThm&!=nL#vJFP4@6K3Y(*?$#>W zKWV=1D~>bp?kX`YN386=DwqFFf%&vDah1N>zPaYp?_aIbr7$AXBI-9|1-;&>3dbmz zONh1UUX>lr-tf?Ziuw2E(YR)-Xyj=1j;!~#DdLrsPs#G1$NJb)F`nIPlTX?v1{NtT zuVj42M++)2HqRNxUlAYP$}69(SkzLWSB~$OQrDErs7eQw2QVyII$7Xs0r~N&Y`nu` zk_8o)r!A#P2bNN)dX-u6;(;vkUXE09=kaGO1$x=7WMbo|<&*i7%hP@?A1$aT@Zkzd z)npO9)kT$Vo|rQ7&#QaIzq|8W3iQGj%5PX^yet zu-v#^$@^kdqdM}b#?opfs5rfOA&p71g7&9YXO*dKI{EyxO0w9D)0P6gu-qIc*Hd}r z+_f*riUp;I7E~ zjfWOg>^{PGg%peEa!Pd_ZPV12{~Z5MTzg+y3iQH~cAP5vs)!!LR*S_WI{0{B!aE#} z`TXp>cbsrmoe_V%`i?!e!#xrE4X@g25fXE={wdzA^SY%#FMHgblk9h~vWg?qo${#5p7F6IkZ>^)Z#`a-%*3g*pbM=?}zs78$5r2MezUn7w z5`46vqEolEl;-BN|DixHJ97YIpam7NwO7&Js^g->70|0 zU43aJbzHGH%9W!96_{m}6hWO8D$wiqX+!Cc=e~>*11+e)EGs((D$wiYkwdA@rKwS3 zpciIVJzjwpRAA1OeO9PIuW>m?(u@{kqns65P=Ps9b_`UYSKAe1ss8Vg451`Vf{zwd zV9r#Mzp6o0pjU-D)97%oNXAx@Cc#GwDllg%$zR1l1$w>AZ}*(#(PE$l6__(+$3O*o zExo^(y7nF!r9RMt3e1_ZW1s@P9zXh^1r?YxWye4Tdf~|DI2UfT@t^8>Slq9a*25gA zbctK&sgI}VZ~vGx#b2twf6u?&<)HX@dNu1S87lf8-9iPfPodKB4fuZEvCz-%)8pz; zOtt>j*p6p%deCOdadjpY&hsKGrhnAPOMPW0O-k0sM++)2C%|#$&z$dNACgDhd8dn| zK(F01Hd7;-Nsare80A0v#%nm}1+inv2R>R*u_@~oy0Lu*9eY>JEVDOg>ARKoi&cvU zd3c2he6_PPPNg>Q)Q_{v>fVRV{3YY|im!g2ZIu-&hO*k7K9&9%t8&$fEw1YqOGcvl z%l0=&^un);j+0oUwx8^~E#kMAl37_6s2IU9njM%*i%Y-CF@A37`RxX;7De96=A-4? z&$rNqjnk;@&YE#{jCAv#_5VorrT9B_X)6XQ-gvzjr^Vj=guKSLqKrg!n z#l3d^KaGDDP413~!}f|Te_O-N)bjoWE~_s%1}e~kimi7x(zelKX?Ur9toS-(jDO*) za$;1E=lyF7Q;SPYo+AHDE>C?ux%5MRI{bbvZw3F}d+P7d=mt-ET!V#T{3;!CilS;xm69Xb~`dGC{+iS4S`oTZl~#;=>N zkTj+K}8~~Ur2K+u1|Y)R<|<6`0*>tdcO<`u0t!(%UqLtgs+KreohtR_dm4T z?Ov&ZuPhb5oFDh>i+S~xPm=TFc2&x&&nj}ZVMVd&Ke(leRnTV@u_$#!@iYIfa%Op4 zlho?U%Vvo2dvE>IT{6AAr9dydCVq!phRFKC7194~siM1HSO(bVGeec9p? z-_7^XSzXB);}>2v)J;|AeYK)-8LH;vvpU52UHj%Paf`3BuLHfXM0o9M z<{1Ci_%x#U&T>B1^D4gDUfFJi_I3@|AjdX!-ua0b|7h836yGPfa&19{Duvd+Ef3vJ zp~@;h*T>0Ef1uV$rK=U_rOv9_-1(u`xSqm_nY>HLVpD?=i}HHo%lV-<*voE-g}JrA zGkG03lY%SPF;J12%WCNIfxiF;|SA;X)pY zTVvNCDxTyRWvUkqef)xo(U?oOVC^qMQ_kB8^eWGaS-+)D{BW*P^y0EgwWvwrr4%tf zTApXGJazW0pEfz%N|Mg%X37|UThVzN)c@o8qC)+i@ZNV?&HbEf@TG&D;@Vxe&kDV; zjXBO3Udh2LIy}gAc2$m`xy$I^W+ZaMS$Za)+J$^-SLIEcJE#6_MprkSfo*cOU6r$q z7LyOBz0CYUt9d<6IFsB{ndE3eg~@a?G1N*9&Q^cqtkBEMYD^515wByQ1r;XKEfOP~ zb+2Qf0=>-a%)~I6{W=C(P+>CNOboMnK*vA@dYM_KiD6bK=on~0g~@a?G0Z9m9Rn5U zWoFAJhFNK$W1s~UCezKtFsnIq3{;?(nf03(X2pn(ffiJlOg9t5tV+=_P=Q|N>BYn_ zD_`^q9<-psWV)FcW_68T!Gj9)GEZS9hFQTAQf(J4s4$ssCWcuhq*w5u0=>+0qKRQv zBIy-8XhDU^bTcu`Y9~^?78U4ao^eeKv!Y6<>p%-COs1QOp;mJ6iVhtE73gK2)lCeu z&P%9~0WGL78FVIwSxcs4paQ+jI|ma(t>oYp9eOo~$&(3>aN!JWJ*t^(82xv(zV@o% z6&+Ho=0J2CG1N*9 zUeV#HjCfR_m&utjG1N*9UeQ4+BOWcNF!|IbhFZzND>`)6Ju1-4{6Y5s$3|YtyX2Ffr6h4qnmW ztE_vppu*()nX*zVIe0~f&g@48dYP3ZCWczc!7Dm^RUc?Ug~?kqG0fT}y+Q#M=w((V znHXv%2e0VxRog`iDop;RiJ?|<@QMy!wOv%8msyo$VyKlIyrM&w6e#wUUEZ zbogpD2P)9ZtV%L5)JhIs(V-;Yhpuz9pu((5GBMOj4qnlr%L*0fg{9y)Y9$A+=+JE!EvPW7t4s{F zl7mMFedVY?FS~TrN)BGpAyo#p$wPEirZtZ3CRb7ao!4gYN)BGpp;vRD1r>NNaU8Xh zgI9Futb0_Tm&v&_G1N*9UeTd5`_Y05yeB%2TFJpHI&=(FpqI%VH8Ipm4qnlrW1s~U zcyDKd8L#Bv6&<89;!$CFg>zs{47HMjS9Bz*tb3DBt1YO&ISN0q@JbF|(V;W@QGs42 zm)FElD>-;Yht9f33o3A~#m_ptl7m-t=*)gppqI%>HZjyn4qnlrW1s~UIA`P>7GBB0 zD>`%xRG^p1tu`^#N)BGpp<|#06*%|hY${&K!7Dm^RUfE8FOwr~VyKlIyrRQXt2xku z3Y^0`j#|mVD>{5wU89eMUMAPw#84|actwZ44z!>GpGA1BKCk596&*STD$vX1?3);B zB?qtQ&@s@03Vf#GcEu|>ctwY<4^*I+S$kk&sFfVNqC>|(3o7v0kYn&l4qnmWsj&nV z=w;qOniy&&2e0VRt2xku3VeFy>^5G>!7DnXTFrs;L>#+tX29=vc_jz0=#XkP2U<{p zqmtvOl^ndHL$6Rk1$yBO$8pq34qnlrR}Y{C6*ww6j#|mVD>?*ZtLr-pdf`lscZ%he z9K51KXZE876*ww6j#|mVD>?|W?sW|G!Wk!LfAUHWUeOU!8S!XA1&&I*HiK7k@QMx( zRu6>lkT4G7%*k=oN)BGpp)>m}3n*|@avZgigI9Fu)dQ$NFPu3s3yD{9@QMx{11+e) zQOR-CN)BGp;j6Mj1$yDkiE}1+B?qtQ(5nZ~f(jg!_!|qaV?wOk7S;?DksfkT(~MT za}j6I{oHSnn^$LMzPaUXSGYa0WXx#ARQ-h)PXc>AqT}LR_Bqi>S7@(w(m}GZ**kFS7hQ(HpU}qmLF#@x@}gwsnPj zE|)s1ZX@Q3p7S<%BQLkK6nVf4%g}M&J2p$CD?iu!WshCDmZI!3n(@&xck((_x;c9< z5Hm6@_O2XlZI$k4;Dt5oI1BpC7YqI^G67wcnfZLhMKt=<3imgi znc3rwJv1~;G4B)3%ru!NuFCkuax+<0uFC#(oLLQC6Ef`-Z_t}vBKcR^f(k4{UK3Y3 zR_tD}+H3nskg=r|=w-6EbT4q63Qe1fZkJDb-?wWK$z0YJRG8dI-B~M$R}rp zct!clAU8@!$9Q(H{cb`@`O&}Mduh`>xVJD1I`a`G8VfnIhi$&uwh z@lMNU{6aNy`Dj7K*er`E^^6tnFrAsXsl`qq_dW0D`Z2$yKrd{ee6PKENVpqn`kB{X z_t1ihOPoRZ=C~DZ3eKQ(oL@%>ai?ZOKh$ckr9dx}e`#v4U-ma-hH|I8iXFCkShwdV zuApKk7r62Lyf`d3$65SOEt&4*f8Oa)(rP8B$neW@%8+c48_vv})HX&gsGHG`opjn# zpcj@Kw_Ufq+H1!Jiiq6bzxbwc4)4Y!VRT*h1&dh+9*kqYUgKb`X0efX-SKrbAL_-kLM{UXiy|GeH~s#|vh zRA9g1eJw}M5;e~y^M||jECqVmBiz|DQ^d}UPx%wa26^Fn^g#uV^HDQ|^qY8-1F3(T z{7dtOK1mZ~WMTvnHRN$9JI|eGy%jEk-iGgzllf|mNOm=G& z1zJ#HvS$B>0=?|7OG#If;G+cj$S5XGs;<^ z1r_-H(~f}(^fH;JQDUG475M$rj)4mFGC8+VVxR>T`2Ew4feQ38xx-Onpam89{nL(t z3iNt>D?tk?@cXA70~P3nEtL7YDMonH*8Jo4`KE_2Cv2u|f6a7Te^)U=Ptspp>lWBd zlMl{v7k;T`;jjE%%)7X0raS(pcpokJUJS=awcmDUw^f~A<975OU@6ecz8loI+{XWt zcT)O3YdX(l(CIG<_`RjVcUx${vZ?OI?^Q-);WaJ&)MNI0!%GkF(1HqlLgu%exf=OH zr|tAUyCW?Hdad5Eh0Y(E>UOxTG8)Tot?j3XP4u$XcYL&xQ#;S}yQG7FD^N zIbTcXPso_yEo~NLX6n|5URZAY2C_+Ee_s2kUW!u{Bl)8GJuWJ4zq5tzd^O!&TVKVP z_(VDXr9xkM{kj&l6zFBwhsn(JR4%8f4L-bBaOw_v!N&X~Zvs=ziApyuS8sin=26D_@9yB|FOp zd-u}*3}dNMvW&485A3C;ImS|rMj2zDIdYJ;?jJ=?Hl^6y#S7i7mmtdg*h}uL@PG=e zPN2Jdte-gNZpOU<^i98vv5Sg7pzXO6%pN>@Cge!$RxY;~Rj!{z3o3q8nSdqw)7?5L zI7Y4CS8ra@dVT21)d7|Qy;R2DHQCR^$o7>-z4tekZ%s)fv)6h+9hMBFfmsX0cB=n? zjx-!ZPrVoy`x`6nO&>^Cevac9ZR`FT>Nx*xx#w7BiI(5l>%f44bfJ3rSUeK1+S-30 z^zK?;E*)9Yih+uwtloGzfnw4W;usrWbm;3Ux#fzs^(+N?VHrBk;ExA|+LlZ!Uy+Ti z(nZBVj`3fw1X|u8E5~?sWxLRvo<~I63LjVs^um&6BG6lVXg(7*uB?v{NV%8?JP|B6 z=0^QInz}cLm-Xhv2(+LA$t1jnH&<19ZC7`BspSkyfnHeZ{4G`74gLI6yqq{bMxX^1 z$YkMnucRD)t^i<+;T; z&I`>aipujpkR3P8uoURE@6>U+c76oCs}&t*w-lGhy(!zDN+Z#NiqG;~qGkIA(dbViTU)$(@ne~RYY^)Ixi465y#8ZGHIeLvUUJch7=ad4Akl@{J7vp@a)0-dLnqk^ z^uk`iceQg%#Irfl$l`Zv$y4d}(Z8+6Qm9Sl*tSjgQLQ6mDO;mLv0Gm~L@_Hy(_CF2 z4QG)U-93l=eOqOT7F4Wa^=ejkZmULyeNQeB71HLDLsM0;6zFBwdCRoliVS~0Bd@M4 zCDDS4i_7-W*jLBVhqcRb48PbGk+q~NXI9B-DbNdRmcQeyJ1f#Qtsxs6`_rm(RIH$V zwCw$HboP?!A3gs3Q)D>VKo&kX!&0CZwl~K~RxXwN@8YYnK+|bfOGL%javv>fH;x*< zt9Eg1IwPGdUHxsjb7(nBfnG=^;qN$KwH7(jtrGM_dx>{4tWEo_Rx8ag@yxq_h-{Oa zNVK2=Yu0g&wQVMDA3Y(CrEh5|(976mj(eUf6a>1ANtdRi~IIcL(qGf4m<-8j7$JhaK$e4rl?JJ}7J+)TZ zy>zj}82$U>PxjLADP!oV_tJ2EoVorJb&$EmrQPuoEjWL`Bk`ApBPqnZG>yftPxQ88 zpaM&sSB&KNh$33CBPMdM&tpoJyS@YGR-QEvUdT*l}v_Pb(HJ>L%OvpJCl=@h*zv81GOq;78h( z&`2I%n?|Aq752O&|IP>W)5q22?HYwG1$x-axM9?S7m)W7Yr!ktNR2T`@7=b_#gqA1XU3fvpij)4mFvUd$l z(j>_17f-qkzpkUNV@Z!c-Dj(2)4$F2ML8?9pknE`>#kd6b(|`NqzI~Ap#r^rU%cAA za;9sP7}qP#aGjQI@J#gYIs5y>&L8=66a`waZXRDBs6elbCr`yrXm%n>478wv>)Yl3 z{vQhT;@0AFtBIoERzkcNuB%Fs>zsJcTK$`AFvP7y|F%mPEvVr75Akla|3iUZ>PS0I z-Hf8(5+!c!q|U0dV%#3bddCcUZO+*eBjCddr>H z^Kz`Zj>q>8w4lQLPE=|;MihniQYFi08Rg2+g2y#y8+tSbD$vV}5>aAc+vWNQaSghr z27_K;UkCONRH$o+-bzq`UR+PaJ6r2`b_}$jf@_d?SM4Z@JiR`kxa;GzUBKg z#cd%NQEdfU@VI<0cX^zN5(5?JWlAB60>=z9N6}t5#@J_t7F3*m>L)jQz5Y>RpaQ*A zA6I?-(XuiYS6Pfg|29X`zoVYjBMO{%JzjxcW(1EC11+fF`c`vPdh|L_fnMf!lo)71 zg_)^EiGd3A!r8KY3K7Cx%Yoo+K3o6Vk^M5GN3+G+-S)m0Lraq#?Km~f4+Ki%5 zGqT7G(ma1?FEdknj3P3xMTL3ZiJ~xfXHu=f+>!NfbC1%$?JLJ);aK~BJ1bP+sBOo< zW1*KB`J!A0T2Nue$N!-~FKj*bS)m0LX4H-n0~MAR+~MpP<3dYlU4swxvG85S%ePk2 zru*UN1Y3a?RN#~T;}z(&>c}cOvozW}0JNY2-woI?@EsYx{lZbgR-gqH_B*m9O@c%P zdSMwR`KxDVw4mbgZ;DWXURct04Aakb4Pu{Xuen7J9FEdT&|)j9KEn!nbfiWF?<^H~ zu{xOBJ#toHc|;K<1|G}&)?VDE)hs-U!m{uzHZoh{5uBnwpX2C*BaV5>h!O+uUij7- z+k$=NXh8+ODSo^Hy|7K&3cNzT<51-Ng;gRTNswqkg;J{jezeX}fnHco5Q1AfT2P_t zLY?uWF;IbCswN}PC3XxRsnuH!eJu0#L;qHPkGxHIR1vYD!n|#Xa#m=;mhpd!feLJ6 zk3TE);`@qvj*fCxXhDUVXQ}ztqos=q^un68&k8N5Q1ehV_j)u2Dl9MPkG$W+urbu> ziM{Ta%AoXN2|!&vvP|1!kl8(MsG>o_eYWv5B$2l(&YnM23wOi5{TxAJqneM9VL#jwc(-3*=^`|m3cXivjIuFA65 z#eW~#VxW7o__O>R^;fnyYOv*XzjyJR5-q6s+j_pgUUNJ2+A}Hr%7vOr zw4kC^=?9c;b%LvMTO8+`&)*B>ZT^GzM!F9z1$tfM7&HDI;Qo<6BP*_c>4gT=OYmYj zPX;Zhz^@Mc{rr^&TS7w|Pi60*0=?9oI`Wl+ckOv)E1mncumAn>7_t4Q81;!fQ-%5?T$RIMzV^D|ugFbmd?WtMQ_attC#^&aDspWqvEckOe!k76tg`xyvjzGe8S6gXqL5W?Tpxwjhy}fJ`^lcGBJo(L zFnI^A%2eQe0nUyQ-7=)|dvB;`DbNeg)^Yk>A1^*kchbu|v59pZs4!o~U6mQZEAKb7 z7Hw0k^0x99cRUt)nJ@9K$|-Z4Z9{j4sz3d}UBRvWhu?+sfnGRD@E7-b>*&b*oPLA&dJ-+D!0U6I=KnRIy+v+&%d)q$6zGMc zgyZzgn2|mx)8A{v-%`ErplLHF2+sm=->W4M%-wB zipnn@?iS=$-R#p7^v7Q#T(xTt_7%?kNVi#BZuFtQY*>sy3o1%qI8IgTjMQq*thv5R z6q(-E@3+NPpcnQo$JxI18F6`PZ~yFcdxYzM^D2FweTe%jk9Js_yl-FA%Ho}`diiop zj6e%2X4k(&mC_A$uj;#6ueI&P-7G!*YujuEdSQt$BR)f2@tOC9SE6+1NPdZK)p*~< zUf?(dPNoq1E;sU0W$A784@+Tvea+wQXX?G@1FsRs6c*;GjrX4VYL z9UsNGd%I`WfB&|5S+_%@Y|MdFio}|w{KKtUTNXulj40IaE)~nW3&ttMp@NnCx8Kh0 zU%9^P5k!QQYmDF{e?y%Imz&-Mgg~5epty{jPkxgnPcbQtXba=nr4J#oN9p zk0z_4BI2cD+^bN)t^bN*v2N^G(SN(#IPZ-CMYJMf!Q-mmOs6%3*d^&>{2U+E@%sGo z+#`yJmx{p*Tf=*u!0gXZ{0n~Ou8m!FtVsDNFD&VQE7WkOmDu4rj#4y;dBH#1dYD#3 zET~Ywua&Cij?ADGrI_Sdtz8Ab@M7_ZBI2cDmw2v~`&*wHM&X<&?^oJ-Tq`1$|Btf2 z0M8<4-~Zvkp}4!dyY|imcU_>!vbeiDEfg=%;!cY@#r@6%cUv45Us!Z;DeNx%ugv5w z=j^k*-}m<%2gh@7uj?~slF1~QNv;I1tA3x#*M_CastA>;GHYr5c`ZM?W+377QW|fH z1+%O_OX_Q95K+M>&e!BgYZE>TURV8IRD298v1&gNH`bTopF>OVErll9sY1f%r8Ekc z4`wqLY#`z~5yeWBg#E%Z`<-`aIFo0M>( zCXCz%%s4~S*o4o5g! zA>oO#EqGn^o1QM=JcH^vr>9oJQyWeAyp#q#|H5fYbju(ses39U3tm_KrdC2YZApG= zuVUOTAx1thS(P+Zwr8KBL7OIDH zS~zN{CA8GG1+S}qQ>!gh{}|nKO4W1Xwa`oboq9Oo^n<$Rl&a@M3li!#^|iw3Yjw{l zRnPfv!sn&_PCcA(`awld&nZ>Ui59%B`c3_#aQa%6sys7xT4Ro7;QuCkUh40@UE1kH z9qKv%C_ddPMLj24@Ve@Ewo+L{BfGENKs{&00ky35)N}ru@Odf1xBELqZT-B*`h7re zo}f*Dz_B`x^zRS3Ba-Z!#I|oyr&J!vJl1<)Nf00K{TyEVdy={?o!raR$-Ons#j!f2 z3TCT^s#bK!U#Uf^;Xypk$mo-MZ34aUiv{hAQ+b?7o;ipYnGhh*f<*7|C_1xmEPE_e z|M6hYMRBfHARkEQz9NBM_-1JsWk$XhneUC_E9e|v^cvgogD5&b-gyhngQ3lj6LzY`VDjb+EDsZ_lWOKxpWIEu%iGbfQiFMNBU_u7|vtdiwM^3qgR zXh8zsUg({(LOH9{kP*DppqKkSD(vbM>+m0g_-#7H6)i}N?eaj3oHLP?zNzZf z`Jk27;3WO|mO*X;y|7jq#;&OK*3p-J`B6HJ7A;7`u6cVZR9NfG*?cD2f61kzj*5^q`Y-P+|M?L zjeD@Mf?*7pLTAftE=&AbiyhU=(QpC8Bw_8ELQ!p8fAR&J7oo4>&_ExazE#o zTlf3N%BmDTV`spYqp4fq*4*%~cKxW5i| zj!G!A{MnRun&&3aOLVv_)^?i4UUQZ6L8W8LD5DimPbc@H1qm!envPuX-s%+8mitlN zMFPFL7ri1byr0Ty*yjo7D*x8Xn5!KRru%^wB;5Doa<1aCPvdfY`35@K`n4s*&2V}v zp);}%92c)2&tY+T&)uBt;c+qY;vClUSy*{$sS8$=zb?$jH?|EB`m9%WcIw?VNb7T7 znRD*z(xc_%s!hdsj=cc_El9XEKJ_RsV}2{jZ%8+RUR$yVk$2TH7BfnnEt}wdX*q$; zf%tn>fItfp%QhbtX2e3)t&O_pRpaE7=_4!h*mPPmKHKEW#UH|ICKr3NiAbH?h-Z?{@%4mh})#R-VCy}rI&!9KU$V$*Ko z&at+paik~z_AT5*3ldkGFJp%aI@)wjwRMvXy4a7myyqs+3sY+tF(-d94<2sFZ&wO8 zv%grwtTK@-|1svN{&h7=C?i>3ZhA1abmnC2`{vWz&G_vR;jVljF>1j|Rx-;Lc4x3U znUohlX;xeF3(q;zO`sR%i6TJn=H^wc;=F&GrRK4`o7nA{YwfbyIeY_4K6C>+a?A6t zRGoR8nm63U`9FywT&Y5$|BH1jfAUQ%^q@MWa%z(JeA@L|JkLaTs?ZBdglgiWW_;|U zd*;EQaPzmETiDYnD_QYj+;iz@BzqNe4Lib2&o0^rDQEaGWT?W3jj=!8d%c;A$hlJQUtQ5YM#d;WG*IkvW zdKISYoJaYWKrdB>af{B> z8tpSS;&(fLwmLAUtb7(EvK@$IZI1gi4kc>MXZAa0tv(-N-wz*wUW3wH`t(T}ID|5kK76Ye6=OI>MB=fzqhZTtazWTODF zaFs*&EJ&#KMLoIBj&hHV^yhVRPh`2Dy9xAC8uxZA)f$7h_T|}2BsDX~im+4Vvml|` z5!F&S8kx3q<_C)`Gz)BZ6X=C?n)b2?ZO;>S+iK2XPU-rd10+;Sr=E33Bf;ihcwnNF zX45(D+KyiMq!~t{!o6ks5>>26O_!QCwoHsJ#XU6Bx1hUo4@!-g%nE&(rE@+dOMB_5 zw%z)&GQva)5-&4{u(IcUwdD5u06910p_RB}xQjrqwjzWH(^nJwR%>6%N#)DYxEg-N zI=-%@JWn+d3G}LD%w$4yc^nvXy)Y=i0j<6VIKGVP(6j%vHA zyFEjl-b-CmQR*J3=jQ9hl{)8%2ep$e59~6#^mCplp9Kk(Yn4jp4(2=6ODMuW5pTy$)8SZ+{kx+L}mA0di|8ajgYS;jg{J5JyFMQ@{r2pom zxc{ghZ*(@ozURJi8;+1v4ZV`iH-^jhD1%j$_Vy{$$*GAx3lgd)P%XEUs=LD@tX)St z@f6411bV6GX7ig(x^&luN-Jz=8(yIHQu~SWS&&dYn(BcZjW{{u%l5l#@dZzvXV6EW zmufLWPHoT{chC6Aw9jhrmuH=p!Dm52^~|a#bu@z07nBJm7vfLyEVJ7ZAAw$2dkiDl z%d)cX&MbW2pk=Olg@hVAsM_dgl&;l4CU5!8?9%4^M-D!wd3< z!`hfZn@jWT8MdEd&+uLid4$fZn`Q(DrM?7?ax4YNJ@E8`9KR2s7*U_CqBZ? zUr)(0uMOlElWk`$&n&a|Hk({>8+#VM(*BM4qsaSGsm%vFZ<~Ma?!Z-wRLWGURIXL- z)jrZH*DCkwH=Tk(<@76+mnti?Afd`n>8LWKJ$_?!GW~l@Vn<#Mb(JobD5jQ9^h`d^ z9F#eQC$#YpS3Z#VvS1s_vunOiRj%`~&61&8yjhNqauMj&x&3x_efE64+gq!@2b-O9 zc!knH3ljBuZ)ShDpYF@~=HJ;I5hj!d66lpa!xlF2W0=;Mm6Mw#CYG_323nB#sm40C z^UY+fF)-yqmjB`{TLTI7n!SG=OH*gE)@ZxsB8%$K-_}425*IQqV|zPJ&>Hm{-1nSW z9m`VrKmxrQR$s;vg^$-7=WbT^FPn3mt$`LKhR}Xz18e&=5ZU0>;_vO)sA)b*83ot8*5?vw|W7o~v~Bvd)6d^sAboK$%!4J6P@ zm6OV&qoMAFx+h8lEl8;Qt?rMbq3*Z3?@9v+^iua*-77~!)hSiClm=RmQ1w>TGe<+! zTUCFR1`_C{>aD7Cj)rK(^$MzYa5Pkprg}EjtKqj7>_zdb5uJ~7 zsi#>v?N7Y);W!*ENVxmjK~4P3^+snd9$zt$Krb9Q(W>HAp`PQ*n{ofg2{>Aiczk6( zdvMd&pHGc_L?rIjg~xAt#q}Kyy>R42d!FqWZ@nn<3lFbx%R~zjI1Zv&vN~I>YIiF0 zsMd)%T9D{;YB~!#6{-94DWBh1*_Kt~<(Azrkw7mT2ho|{+v3U-MsB_u; zwcjn(8ck+(mdmbxW{F2%G0}nqj>ruocgtFG%$pEX@Rg^;H^BS=KJ`)eOpc%|)P>JLi%4qpVG7s>-hZ*G+uS#P{00t*5gNHA8gH=jEii ziC+uKL{z$HK?2{r>HF?)*=3%=esU+}90~MN*H<=Y)TdIkiBhIgg%%|63j%!|j8j>* z_TOz)S&@(avetz^RWQ>~*xH%+u4;eIO;iMq(T-5p=!FS z@v63?1qoHtRV{TiR83bkUe$Ia&`+Z zFd;_^66zUOPlA&wRnt|CSG64p^m4z^H_4lXhel+vOBXFjsJ2SAEsnJ5-UFVz#M zcG$^>>Iqbjpn3zeAc0?1>70guy8Pm(zLu(qNT3&%f?=3xoAAHN?Y07^-7?XF1b!W+ zv#_ZrP(6a`4Uj-Dcj?;iY4pCP-qrBU6yGNC4T*MK+>(qp7?{ialDh#%3ldm{)DM=A z#jSDE*sydzy9o5cHzfLA(jXV-NkjHOuV0m;1qm!e+EX_Co0+D+pQSXAKrehlqBr_D zX?e!LF_zLm3ldm{hLO&D!QB64xvhZ&df^)q?NpfKp&29Og{^@WB=A|GxuV=-%=#rC z+Zsrq7rr6UyFpY>GjEmjQso0JNZ>PX7}e%=XQdXzlB%qbKrehlqWiI8k@pqLWow`X z32g1CuPvI!TK)bXJ0D1(7rr6UQ`>!#^=@QpTLUdfV5?1YMb;W?`-?NS1`_CnZ%BsG zbN?IbbHp9{exL;j?Cq#tWqxM$oH@kSKmxt+4T<`wxfx{2ldWwHv><`~BaKD>h$Rce zsUXz-Kmxt+4aqRlq{$_}1o$y^&(VSej)`bQMso&vZ)7)>1`_CnZ%BqQ?p{h6SvAa5 z8fZZRM^T0`IL1lqWsi-v1`_CnZ%8zf`F7p<>-0xk11(74xRjp3Jw2_Sk6+jtNT3(K zA<=%}BN|#+E@$K_A80`W$JcaHY>NbOiP(d%S&_V!v%TLUdf;G2bE zs1{VUq^cD~0=@9t8STqS-}%({KJ~2+ElA+kNLuN%_K6w#uBGoZb4F*y*=HQm`IC(H zqPKt3+2o9N9A_DZwxaJ0bYeO?cI2w>#B@eyi`Z{*bQS=kUHI+abY3o_J^b|<>vSqR z3mI6?K9wCUbmA?e(=cr>I#nS0O0@d(RSq*-<-GP;@n}JU&a!26UZ>We^XS>)f+7Et zD)geW4j7$MqTe~`%zN|kx|8;q_h>QE zffgj_EL%qBz-o=GNw2ZX32QK=fdqQd85)ev1JN3vhj6p(nmDG?KnoIdmMv5NYHTk< zwWP`PHB9|e8c3iQodv?wKj#~Oy1vp;8fZa6Rm^ip|H`i_PwCskfb z11(6Xd!fqC(NOn7-4msO1bV4^p~}(GQ1@HiccpY3bxPGOrGW%`sXC?V zgQKD9t*XCD11(6XXG7IxtwGO*dPbB666mF#4OOol4fXt~=TK>&1qt=^s%O&CXq@7R z_&N1>TLTI7Qmuu0q8$y@DyY`sN!no?El8+#M70`@hH80K3#9Ua1bV4fNVP_e#;1%; zMq=N}d0)^iUfaR_K+vbzyuHEl8;L zP_>Irn@A_vn}1$z=R3ik#V9=1w$MrQENkI0_HQ~BmC*^WT4UX&#pdso``Ks3qXh{% zL!P}eMrn<=V=J0JB^qF#d5;8o(W$76&bHMWk>xUocEd;6XWpX)2|6*It@t}oYg`?W z!5Sw9+8Rip7oCdA=!{;i5%qAP1*ft{Tacg=+F6j{lme}}n|sEJvAG@Jw_&u2*FrBk z6_wFh!&)QV+n6#-wHChf=%X!2(7Ew!V!UxWAAj}EBl}M&>pPD=nm{kC3)I)nEhl&X zRoFg{9xX_0I}b6A^xzfdE;1{f8Ev8k2~}@ZopUtugbn4Z zhu1d4)BCvy^it1;s>_bXh2=x|$>K3YMbbbE5~|*+I_GF?IXavt*q+XcAPpqYOFbK^ zE;|~vuEpeO+q96Isb#=Xk!nZOy;feTeNpwn(NHx+)f81$XhA~NDOGD6jpVuW^Y$r9 z%f0k`Ac0=$*-+1jqw!*XC7$JFPWfh50uwDrsAogfWk+LS&*uCHdt<4xLIS<86zD97 z>7Due(U+{_Mf^;(AfcXd^-MY%s#W+*t%J%r66obF-4R9{xqJK!`;2uuorlpW=Jpvp z*tXMY#EecJ*JrF(oOs4Mu|Ci~V;wC>U|&Mx_8oVuQ*}<+XT>9dUUaH5qm#$A#=#wn ztb7Z0`p%<|wjhChqG8NyFvUt05Qj(Qpwk`UTIfZmLo+&gTx%@MnAggm`<|_V79_B5 zr*j$t7Kv|#Qrj9xpckET&FDmPtq~`Es{Ip6zp^#Zf&`9H=ya8HvCScSQ}9oe4<_FEyMUbXoY!e`rr2bKmxt!)N!W%<%m-2cZnrj#DwKdR!1il*@M&64H%pt2{%JMbqb0pA9wJ)lj zaWuBo`tywOugcq*IjI7nUh6T{64V z8S6M^KmuDOYIpz6BlpcoX`dC31bVqgOH=2^mDBR1^_@o_J@!EYTP0e7z5kN+E<;t{ zdGyf)df`Zo&L$r^+p1T~V{4!V32c?zoE zTLUdfV5?*pb03v6m&9yo=K~4!!jY3Se1Qc8kU%dSIng}l!NR=ntn+5eLzy^Qkib^S zFtP_X;hoG0rn(1L&Ac3tC#af29=6BQP5_3oc3G~8|0eyR2 zT7#Ep6US2da9N;z#8$~LuJ)6E%d@X(buT-jK58kUT*IeVdkj3 zUadW~Q>Ef>D8fdl7#vJ3J?AfK@&2#l$(57b`9MNNCs9m}P!URW3g6X+{7vmI7OU(g z&*r7Nap`vzF{0+s+2o-}fe&TAi8dsO@sX=jh-1v zT98nYH55A|oama>@00QSW2(r^2i*jEVTl+dJyA@KP?1m6 zpT{lAmlnz|z2n>jdSSWIiRr8EnHfJelV=0nImbMycqWRr5Gtn0FkU}6XcjWt$dd=c zO|&5KLsg1n=AUCT|NmtJe6Yx{(6Y31-WOrAKs)a_sJ42SRlj&USu)Ww7lB@#JquN&p4K?M zW0X~DWp~+l$5In5Na&SATI0cq&0=ED{&IXsxQjrq;9u;>K&^3eR&!A!?f}_uWw?nJ zB=ia>ts#@0WaFOnlSwId2?_MVlBQXiy~WHNW&6nZqa#eTAfeY~X^q3BW|-Mqb(Ke` zCL)1e?mPHkczQW>gopRrwA3zLiZ`%xsMpEZ*Hw3xqPcX=8y+epUxeh~%_cba+-E^T zuYl31y1ufGjO-GJm#4@uycT*5I2NKJ!?Z@~Yz?Vo|28A4QxpVPkkBh&v_>+&*0Ry4 zV`icY6lnnjdhN(HNkxWfjj)SdWU8o{=CeN|Otc`O*UV^*w4Q$Q^&G>zeIwjOpqGw< z&>A|Xfk8}zZ9zh>#nBoKkMx&W`%Dx^o<&DN*aUj1)KdJH)>s_XS5A8w&r0{gNtMrn zgkFoKH6~Qo2m^wqw@eGfwIHEJ*0pTUz67gZi>u zg&6X1d*=@N2=u}h!!TBd*Ooor#g+A1Ikm*smLQ>5g=vlatc09eEw@~>+THq~7q%;g zA?Nq!@6XH?ebYvm*dy!pCH8gQy|a$(V=A@}ElB8CyH){ejKq>{}6b@9eW6q1T#djmMt?xEb`&e5Rt8;acdWdS{Ao(;D?EHsX_? zMVTL|-9-x$dJT)#s1>UUZ`m$6-?c2lMWC1J2Pwi$Yn%%%$O|?v#8;GEYWIUa3le&D zlGc!?6Z04ss_|kJgN4^ZFV$aBgqzmzQhd};Wg2i5AB7eq^eQW@QFHkf^Tpbh{CA3Q zLjt{2TS*aaT4T%6)n?I29r@D!PP^-~AfZ=_X^jzI@|iVf_TkS4xe4@AZ9YY~X^kTk z{TV<}pp#!Z{fEzjgkHm@H6Hf$6R&Cw;Em{>!4MrZt*w5@M>^pZ8zk^lCl} z5_&D3)<_xm_J5JoaHL0M35;*?5lsWo1D zm6lNPIC{O8of5s0OQ%Z3;!sSEQ1LiuK?1cY+R2GsveYVX9G_#JupNtD*Jr79eP}_# zopZge&r<99kU%eN?V{K9dDXf;v>>6^d+E}x<*b3^f#26a+O+|nTD`JL6KZ8Nt&p}? zN23J^Y*#2%wECJ>VcRRPkw7oKLQHF@b$ub9-T6ns&D9EQY@@Iguw9`& zAZUd*t@O6b3N1+JRcN}b^x9gk*483{Uf8Zguixdce%HR|Na$5)T0^f9=4y>FUJJdj zT`>%`GMZLMbG14eEl6OyLVG&V>T6ns&D9EQv>>6^t?5*$72c6)s&ZI+Zs!BN-0f9v zT18H)$?eib3le(Wn$}P&)oH~#SF6>LKrbBoM#lo|SEZ}hj@j43QJ-G7rZx1sa0ctb z|A)YFsbQ!U-n7!&js?JLp%qa0>{_1|BbVT-h?&ucB;_JopX9( zRcwY-Pc6RD;Yd%fLen`{E2C+Jw7ohSElA*)k#<6$)z`ENTdGyXNT8QqO{X=~3U6xV zEY-rH1qmF<(w^kBikw!HTWTda66l3@mUhRdmFmj_XIU?3wK`gmz!5op#c|?41jK*X z=|wNBG12ScB&>(Cdo{fV&ZhO+IGuA9_e%Y(RDCU4kkBzkb{|Y%&uR5Ft-_XS1vcJ6 zENOg?rrp?Sh4=b^y7v7*3le%&piY&JE0U@eMFPF>J=!q5PVAC|*d_ZpM*{Ol;}R!6 zN_wg1#A~4!zIjK-U`dFNBY|154|4J{;lK6 z>=BM(=y)|tMg5`$iPv%&Gj49vV;>!_W{;MTKrbDyrU@MlXh&!26{dDdj;5H-w!PkL zd+m;z!3ue{YC=Z?+7X~gpqE}ps>fG48qkhpMXx(a=CgUVx7*kKF@Y8&cFm#v02(PoG=pTRd&QgwmH{Kt)b(c z?KokyAfZ>|YYiP!ZNGUTfnI6yPG(cX!?cEu^tK5dJz!t!V`vzgoYHw$8+#&@Jq&by z)2e%l@}_@wL@pBOg?fg8sX_}9`%i_i%ekiMRQ-rRuOH_F(~c<&iZ`3JSUW*$=%{!* zA80{B$86}*)sgphWHA!xbu#UIR%z3Ct)ce=un8SwVqa^jxr~+D<9MB}u$1NO;Un~Z z0CuX7Krhsz*;i*j09yksNYs0|fNk;jY5a&lFLyrlP6&3Y@Xa0H=rOg1@uQq0VeDJQ zyoo0MA7zDJSZ+W5&VVWWwmFh*`RJ=xde;a$A80{B$294Ct|H>8CAFUqB+zU0)6Gnz zn6C4I1X_?-5rcL-iJYYgye=kx04+#dp0J&z^F(M3y|;*0wTVce7p9QbOgMXs*!e&U5|M+q zvqxzcXpJ8c=;hA2-W|qLBV_!Zgx`ShOGtEVpQWNw(1HZ!k4^xisF$86s|yufg9Liv z*96+>mLh8?!p4pUL<<_X%rI0G z5=A4~8c3iQesiE*ZYa`eP>hqd23nB7r;FY>DVmC+s_ZBsB+v`LInYWcirAvaEn5RE zNVr=c6%|I&VYUVm=!IVpC<_F6nYb;s7Z>R^r+_p3G~7@WZIFGA~PvM(~bs23lcciqFO@HpA-dZ zDGemh3*XzRkD>@uiZr#<^MMv5aKuUbMo|1xOGoh8Uo7anB4@`e`wKl;kAoH@^a?1Ork&EAHS~6*1rq3`*Sc$sy%fno5gq<yV`15_;vj zCI(Qn$d}%E>_`i=AfeZO=~QK=h?MkiW7?4xNT8Qq>#j9a)C)zwm@4uGElB7!Y+6IF zp|>L~kU%fJhF)u^=$$JAGT4z8XhA}+#nT!pLTF353`|8qAc0;wIznrxD5Te8E85Wm zXhA}+DbyM&(upFTFw(-l7JBKp5Ursi2PpS;+=Pzvu`N2T$o{QYo@xyh$w3hvQso0J zNa)BXt#OK?MJQ@Ss;Cqs&`Yl))fy@yg(6d=ib_EX5;}rQYm}S2$fW2OsUj_qKrg+H zRBPy1GCSvJK|)6lX$=*ORpo<8Y)7FB8BXT5wswoqldJHibA4jBs(8S zpcmdv!%&e<6!9cg#0XlD(9uI$L&p`_5hF;Tm%EmHq=*!XOtCevmf+pg5nNj15JkOE z^oyMjv>>6^Q|q!)ku}ffJ7t9gdg+)it)ZfKD2m69;6V!#dM&rs(6MCpJx2n)bS#s3>oWWVJQWf<(Io>)DVf z-@CJpWVJPrKrhUnVdzL!TLUdf9PG83)oU|V=i^5NdSNNhd3R1^u~SyL=d;4UkF~Eg zu>C@I>6G(Z$Ia-RBY_qq?uUl6&PyDcPK0)1k?ou#fnHeZv}dLhi)^O~El5;|wSxUU z&$%~0CeRD-&5v`ADO?a^CcA&y_f1B}ZQJ=k3lcj1N0*h34Y%`w1bXevG>siQI!WI_ z9e-|XpalsX|D!c@jJvIY1bS6?6T;}9*3hx~_MQVe2FJcutT$ts_qy}-RLB2l4IQg* zYoG;*YU{_d=XHGFMRlycoew0?3sV>!t8Z(d1&OyuC$W*4d|!$%=SZNJJLh^Q1dn>o zb!3p8LpgOUJ2robT|QVMw9lQh6N0_l0$PyRabzs3)?uM8-5(L?h2=)E$j%-R_TC9P zmdHs}jEU@BdgqHdrj}-xoIN1y{Ta|AfoM2w94j!&_f7vt1bShf+@o+DZ3hO1GXKY0 z?A+q$+)bbbiEZ8xmh^>h{zLDuVXFIq1bShKP_)x{dxs6C+IF-cVf{3T4L-YG-;W;= z=!NBG7%HA&N-<%nmH$^JV_NB+yI8F=-7Ii*rA`wXJ~`Byfys7%JX};(lxmB+yI8F=>sC6jMa8MN-A% zpalsWqZ)>aTgr8?u&sdvdg(YOt)XJ0C`QWGKnoH$Mx_}nioc>bEIZ~03G~u&Oj<+5 zcuh?Ir=?>X4011(74yP;vIxIT*SGnEDs=%wSBw8mSC9i$jSQ>El?D>%rQ?{i#$JknO!#*mJ0=b-NZ`9V?H5jQmdo20=Bh100=;y6 zl-5wOoD|c^RXitJkif4LhN0p`x9)0X$Bg257uzlzKT@woF{u=rYN@zXv><`4l3}R0 zSBihNV_%U#FC5j92F2D=jIAACixwoXRWgi;6u;YI#aUYe3G~9zAngK0F~SrpELEH^ zT9Ck2iK6Hz4w>SSZ4D&Q3&(S`K9ORbDdySMKnoJsDp3R|#ZyyUwWVUJkw7mT&(Rtd zirJ>vZK-0B(SiiFN)&%iap4pnZs!9D^ujR_t?Q%MbBaN??+03tz*fmHRD3(dx!W2@ zpcjtq3`51xQ!Kr$ffgjNRWb|}r%&B<(jq z`wsZ4*l;A!3rA6gq4qSOy$zVUA1({DoY*SS+yw2Luqb0*Q{8hU&a)H2ZC475js zsWi}n1hz_sq4s~EeIQJg4 zd$&+mti^p@F6NYr>P>&@OZB62&Y1SObYXd(L>P z4=GpSfA0rg3%$;sIpbB={$CmUqbu+3Z`19FeJy;>f5{ZX+rQPJ|Ik1S5~aOWy-$~I{|^G|F4nRC|8kDR z{pndfF(bU5|1Dj-7J6ZQbC(s?pV>v5?(dTH|D`4(F=YPT{S}%W`9D&HUfA-vQ-$>> zWc*3*ihpM8SGmRfxe2r&QN7$rZ}whuZTiOqdSMN96Ie?s8ol;UTXo95&v^gc1X_^T z(Y#WHbi2;{M=e1Dy#{tm<6l3|>Hi?m(mFw;f6i#ED)RJcl=n|Iolxq1VWR zr9GFX?D`J^Ex|R~c&cpM@c)o1B-Tew^(+mW{T~{bD)hp-;JzQ&B4bOPVb5Go-p-Rf z|NBIt1&Mimk9y{8y73?N3JLUT|M0YDcEt?;2Qf6Q<+)lbrJa%?EmnA5CLi)2sX_}9 zHB0UGj80SbKL}JW@a?qc!SN)eRcM=+ErZu|u$tJ%gsKHy&Y0WSD%od-L9%r&#k@Eip%@(!49%JW|mD_Um-a7F-^-em) zdFon9nM6_I&&XwTj(f@3bG^SU43Zz$ z1c=TJZ|)C!{z?21qx~BC?XP~nJKS!~qJqEe{}?Aq5{8DRdyclZzF?5i8J>E^ASAX-V_vENIT4Pg;AS-O< z5V@gyfItfpFLFQi{_)crtx=|KXX|0AVRBRlH-TO!6QA`y@BL0|G+$BQGTIK8lLiF{ zv>@@k!b%H^llh$~AaDj+=5hzp8^MM3&miI|&YWXJCqbI6s z;CK;{AxN74BG3z4KEn_hvdK*KYsgoT0YbOoLbb@cZ5Jc^pNOn9ZkCwz=(yN3bpy3N z3npcdx7XB>RjFPLcrru0Eqzk_v^=B#vJ2D2wUnpC#f#j(^OFdXVWwq2n{?9not*Mh zxvFyd61N6k*G;s1nNbGLtu3bwrZy3-g~Yznv&4qNCq#i{_bFAs{gP3(iBm@=9quO3 z3sXy{nV(ND=a#H1^NkA-nD&9^!bJY_r$qdcwf~im)d$kabzkesU#7Y>ka)0Vn#kDv zjEMEA4c(9B4b#Z0C+o|fSGWoE!gh>ie$FP9p{*Osv(zS{1&Q&krim3Z&**v;;Fm-` z4Q(Q){)<2_Z0!uA&`6K$xvP*oG&VrQKDb}hEVDwqx<_Xflj;G)`x8?9VEj$1_99SASk?eh{mY zCrGaA?Cx=ppr_08{iz+XXfEsVK2Y`==qAvs%i|`VG!H)N)@Sd-qb%isKv|Yjg%%{9 zzH8!17sJ;w#7z2)6<;$-Htypl&@1oLa8HlfAGC&l?Ud%`zedX1{Q?A9kf4^x^Sy=Z zma?ANV&HIjZ;P8iuP+r7u+zz2X^q4C2b!_U4VAxd3=n8RB0tx=FZuJWE~>Vf&}#p?0b(hZq9P^ueSZ=fPHQPz3R27 z%6^;uP;11`xzntfypQ~QXMjKp64b-7?>%SVtLM!Uv%1ONz1#$P)jiRi<>~Dk0c8K{ zs`=qv7uk>QAX<=!*wvhsX>nISwc*#Fneo$fkRQjm3G`}tb~syg^Qz8AyO!_G(bL=v6Ea?Q_5Kq}E8^JQ4pTvZ*XgBLK7@LG23r z-ukdfDf!kD4dtgcZUVi6E{Cymr%#EYCF;;~{wO>Z-xjl>97y*ZEg2_FXJ6`^5;<#C z^G9vNn2{kh&$_;WY(NBBkSI$hJG?w_QgrEBj5I2hP0P1tuP?XIy8#mD)yta8a{O^r z=e+BnwA}A~Jz0bZ^qTT)2Fq3Iq!3jz`n!pXY0~izBkRd8)SsgTi4C!4u|CaCh_aR6 zQy+EbNp@cMS~Z#Xq?^}$CO+pT&`Z6I(L0<_?{KvC{BU-@=0i0(fKr7P^`1uWYvLTe-Jv#}qI9+( zkK2&RpYOOekkD^;_E^F&o&}WVfh9}HTGSihwa}~7^sVf-tDAJrFHiOGEGrAiHj4rT zT99~G>ku2>dXXlA3smRtg0sue^8o_A^gE{rp^*%YVwf63I3t-$Evj;{E2k{&brb02 z)>wb84xijKgFM|OK%fN)8j~Tt#-oji4Ui6iM{1{&`ofnGF%Vrp!nMo~0>ey|aL zojZjrPfrw$B$(>?)o9}WoHOi#cdDIR8lNyV>QG}8+KaVqeSYVD8hK!7fEu|(TaZ9) zI!mZaJ$}AqI{A$HS|rem#&S%Ji`00IcE7k?m+$y9ot#E(B3h7e=i{HwP5Fr{0Jvo2C(R zV>aM&h|$dD{w? z%_-FSAc0>0?0&#TRjaEtIxg+X<0igrjv)dqNZcv;fVEEP(~z%v@|iIYn2-0n3H0jR z{!exzWh$-FKCmy3=&{MnB4}g@79=JY{FBWnlt$-csox-;@Zb!yb`Lj!Uaw=kX1OE& z@u>S`823{T<~2h?%)UJX1X_@|mgY4}vg03*x|=knJ~Wi4I@ZH17VIX_E9ac|EUNEz zt&uhNa6UL;V>2%GgJ?k_^{n@-cl=#iqsyU@{Bhm%X8L(<0=-W3{ltn}1+>QY8>9H% z9Bn)WmSBB5I@ynjpxa3H-TRIO8Xs+=|uERy2@L4Z!}?BkkG&PYYj?O z)|t~p>hGyS!uHbn^Ew(O?*;PKAHv03YN^qJ*VTFQIvNe{jiML6*J1{J@j?Q<^qtij zUFi-UsGHt`J7`;w(Dz1bq^DYPJz--j-uGH!6X>ODsMff)b0~iu(bKv_Z>eZOLf0{^ zk-6w#KJ)5iD*?6CNT8Q~(u7l1Yv_sk?Z6BRo+#Ubgnm|pQ&v;g_vI-DZ?yb(L_dQz zfnK`B&>B0>^yGCnAF!s;=oKwU=x1JQOrzGPaiYss(D&BIz7~4vc1&w*Y15Ub$alq3 zUk%WLgl@aEMun^$`Il3FScx~e3G~t}xYqbmsSS^j?z1Jox74-;3Ec*3jZd-}Kb$Lp zod3NyunF|i{fgFT?AMe(Y?xTypgsyMNMN5xW1sOq@os*}Wo61a66i%^U8dfpoqL|F z`A>XV-Q==15okdId+lfq4jN2dOVjpm?BVFt(94bZKYl6rPc#BR3lcP*W@_~8jHzYo z`uxc6Y4~0m0U&{1x~FDNO-wqh9yc4rwi=NehV`m0zkE3zPu|;2 zpcjplnHvA9(XwGwtW}q1*`A))rzZ+6G$Lkd1gl2Hs7*17x9jk>l``JKYH_u^}ZfgZ(evU^wRHeI#tK#rRHB7 zG~ntx1A4uocfe-{PqGSwOZeU(H8HtVYCd>g1N#}oYau~nU8Y91&Up9Ru2g*3n+AM1 zX&`}KGy-R8^z4kn6R$|g#mr@KvSHBT&KxKs%B=mc< z-AWin*7}LLU!tb`5BdU$1bXRj13Kq%2FKwa6Sm~(CP#k*uq{aFw|lLzzQucU>-4t# z==bjoHi2IH8;8~?b>@lrba4khh`!dM1quC?LTj{0d)<7xwF}QgV^Ji~OMk1;8pW=i zH{;Ff#`{p)jus^J*A}fYsT!@h^XtP8QeTS%dg*UYT4O`cW#)pJ{rO*;qrWZL79{jn zBdw7vRj9dn_8<=5uWSOn^p`NL5hr+>d1&1rUW4itT9D9RzqCg3=l#v#CPVoq$_EnY zrN04cjr8=b@0WqY`Q0ti-}-C|68bBi)>u|IrMcj*k-XaX?};{nUiw?6*2sCM8T(v2 zh_|H{j%GvsY5tU{`BR$b^rzWSre;I+{GcZGw~t}wnm>vs9uOe#y84@?of5Z({*ub! zOR9Y>B=lERoe%xBmaDI|crEmDr)qe>Al9^45FgMf`unb}fdtK-cxaA=Idd$jreB}%$awt6nBaD{(>N0eZ4)y8*M>?W@7i# zd@Xb4Ya8Ya7Gc?gculIi^u2vQ&9XB!%dY39>~f>|+Wj;W&(usjoi4xOt+(jpAU=e? zC!z%jEJGS)Exh=Tvi*0?qt{hltHdgZMroFt>4 zDVUn4pg73d^To*5f!v-SbXGmsC5m2p-q8L#jV$j*i08Kh`7P2wFRHt0-qC(0+=QOB zu5XZDrD?5k}-LeIo%4L!rl)eJ9Q z3%&GQvDS!mW|29}BHI=us6|yX)mlT(RC6^`jn_giJ?E`8syMUZ9A?993lh{bs2O*y zp=aE=nsLW#p_iV!*BURJS$+N|-9fY>70)6`p%^RAY&R2n(?PJJGaS_UN0OV223jryz8$r>r@@n+Kk1bWe% zmQZg->TSzSq~4QWcBxjE9~c)s!)sp)33`VT>MhB6kGj(*gACtShkvD7g4aSXdWW*# zn4I^hdv!C)Rw?T6&NR1;7J7#g>di>KN8y!d@12_&<+D|_c`RD>f)*s`9m;W!B*E!%W5h||tCf_5aZBUT$mED?8m?6H6Mda+oXIveQOUAqr;o#31bR`FhoCq!9UJ~}_5~~Dnl?OMxk={3!E;1g zbDy|5vW41vM^OB$z3;=N6?4U)TKmL`Faar)_=NOO+3kbj@OI|S|ZBWSk>`}Y_6`y2ZE;Q_6PNIUSVb>VF% zo}yKJ6D>%f9>x5$y=pbP(}~CW=;tEPt5nrFB443>B0)Z-v2Vc@YeW1_ymNR?6D>$! ziO?BUTMk(V4mRW`d*3xNhe*7*Jx|1Kx=*BNS&cNV*V=AnH7j!2I4MU95)@q{C~{B7 z5B6BP$};8`=f}OdTm*XUtvFwN^6V3xMHSLmoI0*`;Aof`qsst}_xaM~MdEzhz2ea2 zG9LFmKfNuZweRg}bINbMRm@LxZ9w8g@kOHl*uCQB^s=PUt3fVnZILZz=;fX+0=?Ge zTqI&l-YXJpR>bhQ<*nNtkD1wecHwBLRBoXNIJ8$(o#6kkR2{w1);gc=jk#@qOP2-` ztNa&;-@fe?Emx`YyjH#*Ze^Vump7Tw&_$pZmK)7lmY-wYiII)}-mbhlpEJ7LkvRW+ zzNnjWpE&=vB59QEyTl5(kdNP7Qq)DDm-~KPOczhiT$Nge9LdaQWQY(2^6e9)GZgZC zEfXPz&{H(lo8RNVbcu)`ykB^d79x#`*)qyq`-;elrG7QvtPU50TkaQkWlqn9BTK}% zI9~ChaBj~LBHoVOFJ^xzNW`;M8ReX6Mda(kZUVhdjEfNSSMC${E9WGlW^fXD=yGb= z_C*?w>X<5|4I}+4KiRrs2D$u9YK|5pmX?hWrRh13y*WQ=)X0}gPXCxoW_$Y0L;}6s zsmi?}z4a+bvfiIYaBS7EecXOzu}Je~ulT)-YDMeE{!{qvTj{A=A&{d532cKY<}A-_ z>*cE~R_$~B_&C2MB3-k6qW80so`ZDVf^^+eblpZ}X|{vf;E@|jkVb`jU@^R_|~TtIb}KF+&Lt=Fc#~yKT0DiY>FAENJh_ITFo|go`|f_ln@m zMJZJsuU@d;4qItWKh@GjpqIDu5;6GjKC!+|aU#aOykNyn{HygXK_iY9BzBX=JkrRQ zL1`@Pc*nYyPgn=){^TOiYjl+*;?t&vy$ux{q4&e4JdK4}!ym@S6v z5dWhUwx+C$K(Dw9mx!G`_6xH@VbYj7I)U6(If+a%Fb78q68PL0#y`}nS=6hwj0*Mi zSr{hjU*9dBq~GkpKB{W3nW9q+%K64n(m(<&NMQd+d#lUW*7o1q@nvnpT-QZC+RaYT zUQBi`Y8d?o$CX*nwBYfFhN(UCqAf^74GIy;p98TsXr!*mk-mZlkA1kcg}Gy5x)gLu{E9y zo)qRm3lfJu?G{I-go%j-&QYqiQLcwj?w3=}kw7msc2H&KXf(c`g^!G^DgRCy=II@G zi*|*WxIG-YLYly zIUkKK!)})3o~&hLvm0&#y|6?mPWVC<{_y28;h6lqu zXhDMZLKC!Kpf0QJ2@Jky`7iQMDk~(=>-SiZ;;&M{VrpHb@%C_}S#wTbd9!GkhxX4C zv@f82t^Om{ilmE2iLBwF3~4&?mY*?0cXXGJ6NY)vg2dj|>qWblL1M|D<4J?>eQsVX z-9eTa|L=11>Wf`-Di{!yW#Lm+y zmZd?Qscd*Ficlyt-Gi31k5-7QZ-$8x)s`{562&wuk82+Bj*_PrPIqY_@gc`bu{z;! z;n#C1X{`F1!hBMHlw5JnO`sQ+pkxs>8_k35qWi<*wS%` z*thcprRwGFR@SSR!(`XZZUVjB^=jv?vtr!(Kp7IpU3Zbly=Q?K-fM^`oA@wk+$qzK z=IkgIfSxG47J6aLH;g2|Keftk?jU#39mM;Lxjp@Rh%k-^i2@lPkjA5lU#yE|+Q_f; zM4<%<+7nXH4ve}jNs&0N%$B&NY)3sO66jU?Qiw=+JxJs#rZkeRN+YYjsxRMO3-h1_ z3EC44Q5fnI6vjTIkPjTb%hsyp~FkjXB|3(01g!aQg}!kv$AX)DUr`SZ)D1a1PotjMwA z&uinwv2XWDqf~oZcfMkV)gtF~k7}z_4ODk+_qQQpQiu6sa-AKl-`im#Rr{IZ(#B&% zOq$tSk z+;E9BmQ8Fg+cbG;oy_Sb&c*1o;2f!ic&cv#HM$PS?!)f#XdTfCiUs1O!bYb z)o`AuoyUXZxclkFXddQ43lgmo4Hens0?~NQW=d6pH^b#YtCnTGpY9^i%U!xR>kXF= z`~s{ON8EQ1iM?-zh;^ZKH;->84Qui+S@TH;Ywlz>fnIq3=`_LjnPl~Akp}jNg~0x?P5)V#FVQ3naaraw@dPI z)Ry42&`XU&)p*M(-GVWgY_+HmPq8%2gI--`jTg6SZ53~0eniA&6QmIpCa@O z!nKfC-DkY0UwEt7TRIP=s_eCVt$G_o(zZVnv8ZV`nXm6fb6V~& z4_Y3~3>2+euN7-E4`8Tm75KeuN6fP4Iqs-^ZLpZ6cAFEu_@V=O1ylJ?&)nbL%S9}_2?BYRk&#d{3Cvy|%g-^3#WO%~l z7;kQwKXyqI$#5#Vxs=h#e)$$Tj6l%25G584~Cf zP~wOf{C0u3-9u^gZ&gx0Tv1$}$Xmcf3lbg691#^SE)XAgD~+cQi%V-_S$XF|Cx!%i zl|Oe}ls!6Eyk4v{_|Jvq86tA;%5S0tiOe&OiB(PKi8hOrMv1L?W#zjS<*P5<84~D~ z{{3kYoP|!JxuP^Wbj%^!45%c#yv$>w*OKk0#6SPc5~YW3_jeOl&Sa8#Ggg;#GUPVV zg2dGOr^T}bvqa(EDpj${WReGesx7;}ZO4#6uT>|{h!E-rH{VmKx;HY7-1WG&%yBKZ zi54VoeLg4pOr|sM8!L@BO_InkF~=`Z)1Z^*Kb$O;Xe1!-mQjQAtg- zAaStvpJH_2IFYp7HX@32$Zt)kFj8JTU7R6-UMt#v5U*)`)p4QHIK4Q)`X|Y7`D=1_ zs&1!vF6L$#FN*&wg@#clb4x4m&M-9~*j+KY;v|vyfVzXZ`mDCrXYM1v z2BkHTK(FiOUD2Y|B=O+1(sFbyYU~uzHm0gqACup+YMk#Rb4D~`XhCAnpew@v+*FaifzsIa>vQYq z?l!Vck*p>X=;f}v#-JfD!6UoYsl)aYwnP@?x z>dw!i#@S$zB9_vquzG`7dOuLE-q+ON9sb&|v2e*%sxjV)+ z(SpS7Tyd@77h}YWAxfjMU#K_!;UJmKo1GznUh4Paam{8e73la;eZxXFCZ4(2p?I4Xrm5a-4 zkIKqwc|#Zy=!Nmzv>(9TqH=CzN%t2{q^SW#v>c z_rhe+_Cg>ZnrNF4u~vyXvEI$)~F^U zI9iZ+-+r@r6l0y}T}lx(A1<)EeOP3rYukm#DzQ-%?YB`B*jd7JtLjGaN2`q@!=4hJ zsuwnj3r{x+{~$HT^4I1$)|8`jt!B@=a%DcHfd7cdDkeDR2F;q@Xo8%}|aOBusO!h%qr-oLi>myb6~8*&1@8p_Mdr zpo>5+cdBC4=x9~8ezLB=9Kg|n#L|j;MfSuu@oE&{!&)YNdcHsY zM%f~gq9Q3#NQesWnUSm^p(6XfFNGHEp+r*FLfN-0*;>^5eeT%zec$(e-^u!$+b5sj zna}sX9-Y_oeeTS?GjnF{%ssb1tyKI&M@jb_tMJpK(Ht+A00-V=!06r448Ln!y>&el zHrWk*#B+?xBu;>uzXtmx1EqVdNa?L5CT7mq3{%3zC(N3u&sEyjHp-3Z-4xH!ArgUA zxJ)8KuH(QPwW-Hfe?1|!LEP@@@6Lk}&g-GuQCs1oeS!_&W73Gnd^<&POU3V+F)iMI zjI7T0Y3lQ=^*<@LU;@9j7Fpj~8}Z(Kta#Lj>I@TDh2M;e{Uw3rxalKvZqT_F!xsET z5&x3-D%X{-N|A2`zPqTYo$9m~t#wr(Cw~E7cVy93B_IAFEa1_p*ubv2N>E#V_lDcyw+*9B<eOy6K9EhZ1rtfX6zKMJ87$9lBZx+ie<~NU zJ$RK-HzfkA?(PCO{%JWpcTkBy$J%^t|K|MhZ=l$MiFH#HSaf_j1eJ3Y#JON=PAW9x z-mAqV5B(Na8Mp!LJ(&SVEYNZCqLYWy?&uJ5LA8zNNu$@jd6*8-=i{QW}g5 z@YP0(zpdXdg+>v6f-rM#%kFRap}hNXpT-LdS(XOBQoOZApo1!_)8WH_9@<3l{{a`% zAgfU~LAVUDW-r=R<&ElBV%UO-Piu4#GH#iOo;nG_>#H-X*YdgIeW|KMVAa9QLdeTc zhf&8m3Sz)PGnO5@O?h%t%ZeTp!pov%F!*d+?Wq1@KjN-sVE3f0w%5QyxS6#K&X{-z z!ma6IdSFXCWw2u)dpM&2s=r+UwifQh88gmtEAW z`yi!G)>wuunAmGl2pLLGV z8sxqmB8Z=<+iB0uL-?<>?G#&Zi^45UqX`)OgKm!T@+xie6aA* z?0a1{b`j;#1N%|`6djBWO@q5>gSGhnyNmyK5dWVn{x90#gVroHp&tKPb`r%FOvq2k z!ppv_^}~w%h}Rc_39PE1D}>r1OH0;XJ5;w}H-0g0@pOQ6RruPmKe6Jqt`b|D+lfQR zWzw^Y30w;r&5Z14wBwvk-00XXiNLC`0eUd}m<}Od)c$IGjYaglz9)~U`kP`4CgdJ2 zaF_$#U8WoNK3$z*0;`_i*TcD2%b?pp^=Xd{o&|5cD)GcAKye8UX4rxW>`$W!3W=uyW%3mLv5^viRk&9Y&sF>>k*#@!GI!8GslUR6 z+?O-vbWA-?l?lb>9nP&D< zF?lvrBCrZS$KrmBSWZ8WeyD{1=);4eO0rcDk3Tz6dtrONiuTJHq- zZIBK!WOl~$la7-k=JJ29IBmi)%g z%hKqK2^?{Xx$~5+?5bkGKh0Ys5m<#IS+P1;hS3{OCh?avQ;Ntcz0ku^5uLUEPjsfy z4E%bYET|jA-Ia9|M`4)2txK%+87(6tUXJF6hFz8jtisWNh)Wjk(HpHE!2`^nP;9{j zZvUbj&m6U-9`xdiYMC%hU=@BA#9PbrCdw7@?v8p@l-8atz$!d96j8=aTbA&}gU@eiMsYNWqvhF0_5v4gMo(@& zE82PDvLP&`=#!HD!i?bE%0vD3!olAuka6{l_K<%84EeE8%!*e2hrkw0$Psem1}#_| zbK#?NzYy#lUlpdsp43zqR*k#x!FRqBY{3MM&c$L>ziw>S*_wQjZoNccm3&p97prj7 zjUD;-a|>yzUJtD&r^0=|^IANX+}WoCmrtpni8wDxZe042QnhzqUO6?5VhbklxT4W) zyqT`pjUL0Dk1mx6tTGWZmKnwipzjRT#|Z01%0%0-yyDk1iY=JHqsciY=Is$EZu~t1-*H-FeZjhSGC|?sMw`9-c!lC zIGG=+xs>AT#k~(MpV*&x#29MD1oIV@Q>Bt)0{4&N%k@ryWTABkKel#`L||1Z^Fp{% ze*tJeo)hJ89@2xZ3YfxUy<#c0U_vg(G_O>;+i?NEoR4cyjtW zJ(xX|myYjAu>}*j-oy&awJFN%mm&P^$k$~5{0t~vGZcbm=}C_&nNaRj2-xk?llV>> zVECQsuw%;_v3uu>PZPfAP)pu{w7f4!B1eEDFAC9-XL@anD^!}9$ zvkfl^;=+=)%zdf@kM}A^@ScBs7U0wC9OyB74%jxa7DS3}yz=-!7$>HE2;LWr_aPg) zr^A^aA@HEe2|*mN4&--F>{J3KXr$ed74xRUg6xIhfBFc)yBjr{u?NQU%O4Lb^D;V1 z7EA=EO^2WR7Q&y)>ORX?n|kt-1FCT{qzl1&UGbj8t$Sl2uzC{MdEO92lT*I@#lFgX z(ZwzVTQGrlH)=Eo%X#xMc{& z3ASJ&b;nGwITa5-BGnzg8*91qf~n1Tqij!!z$&~GScGt!n(~M4?!153l>}QbvH4Ow z)LkBI<_)>PelzM}05$aOjXJg=UIL|~O%@-0OxmAj>lEEp3P8-J$GMT_CTyGjpgA=`#5mw>+f`z}- zQ{&zlpVJU|!*@H-)!vc($U$p@&-vhUMUPU~!-LA&WnU<)Sj znI?@U@>?I8V-(I!{be7R#wUiv{;Ou4=<%iDe4tMp!4^!k_Sy<<%who?64dAFz-rpy z;uOAQyMshvm3$Iudus!>^kMR2$9Kj0)O*0RU)toU!hnR-F1d;`ZAWg?r2P~1rzurnrMSj+4MtTAkSIj zC=pmCmwaajEt}iciJ$pep5Rd*pC6PXfaZUivV#5Yyv(8U1Y0nHPdJKQNJp)h-DEFr zYLzGvSam8e7YgssfxIa{UxY!A$VCn2@T z7uy1nNn#FktXoSEw!QBtH%$ie6CN{ZsM#K<)q569XzNd&R?dNMHnYItPH%#LNu#OQ z!H}<8-GiUcOq6_JV&&z%ke56MqJruOA5-d-;}(wI+|O0MDy+g+DE6d!8FJU{J$V^@ z2%WudJGd1^!-I_pWb=pZP=SefBs`wnG1(4>H^o5WeD&GwJg79UH@G)ny(Elc3nqpH z?}j-aXTT=UVS>0Y{EpJN=OEtb+BAv4DqJHX`_M5BH%;ixy?C5dSC~jUvIqLTnh7yO z{e_SB*#`X1OCO&8aE3%+6|Oh2Ke2;``?&k@q78vk$#I!Vx7-4iKSaR1>_x)Ir>;*F zyS#yXRq$YnEtq)uaRY4in+}t&sJ+k1BW3vc8@>7X;UgsitK80Sg#MqxAR<{k2l?kx z1->cLhp*c)kUp|r4ZE#FVCDEcV(7XWHrEM(Hx2U$rbTw({uOxhnLhm5x1khUFrkdt z2zL*M!I*c&ed5jX{9K|BFEw?PL|~PCRVS90=U1op=6%bzrnq;mav~j?cM1Uq?-OLP z*>c!?Cm70gKPt+xzkGRq=xA@Q-`ARAOX05NQ1@{#3`##t@GpsT6F(j(o|<9JH z2PW{$LVTa0e3HVt2lK>Ed!^sPDtY_}D(Ijbi3sQ0Pb?wWf(bm65pPBlv!TVaXui0k zi9}$Pe15Q(cBf)8NX#JHWlLi%9$)2>N3{E;g!Jyued5fdl4Bw_c`?+<425fT)mc&0 zkP7^eeQ(|%$W^C$A2D^LD~G0lQX>Ku4!lk7HBE)d{^9Vn!!0RZ z5qr%kqx{`tWb9%1H!P;WCLR<7{Q# z)wCzyKG&XN3nqTuSqPQ3gu&7dSA~xuzE%17tKMAc<17(ag=<0daAVAP=N(;n-TL*V zlH)S%a-9cem7?L~y8FUM+L&s5h;t7<+^Pb_7EItsO?(k3-jd%l?#%u6*OdsYT4$03 zhr(mv@k}*(js0!OpP%f+S#BMQEtuF_dJa@97YA3()tEYXl_hW6sSAIUY)G*M6F6EH ztLNjac`3&Z{N6}wiNLDYv5C-VLL4|csXl&RvF2;^?fJQ~HWXVhQFm?vycB)=nwcuG zy>nfj_|lW_`B|1?3nuV9L40jtk}c2N;=%no*h&OeeLfox%G#MQ+FAACx4@P!4DsMT z@9ZeHVB%%BSaYhGji`&uimdul|n1rvBS zsnJv^<-nJTJXJ9-9V7y)&RmUy=g-B--!7_;Jg4S-j9&}xJ;j(}3nuV9TDQZC*(NsEuYOPUQfWQIG7f5gO!arz2?T}*KbO( z1rz57MMJmmNf6dq?Muq6Ys{m5y72)soFoFPNFN=O2fc=2b7|O9WQo8WFM2 z8_ExEx94`rb)~w(gz<+^$X6CYzv7Y8zhM(TBfTY`wp%L^ScTWlL=--3werGl4Bs4- zDy`PyXcDh2i?1hbyrY!r*q=vu&6n1YF(F5NDX!DT@ayXu zO9WQQE0BkBFDoDV4(C-`cc9pU2^>XfG=tsZl-H-H^2FZG5`k46#h!HAnz8VCh#Da; z{<=yDc{P!j(RQKOf(aZmiXB@6oRsAFP`-1Kr$k^?E6r~4RmWNI@Toexv%NM$iE#|# zz0(I#Y{7&aQ@4D+A3k0U<3q{}kO-{WnVSdGwR7Q|sXCjO{MAo+KYI#q&^?S|3nuUr zBlfCYYNSNPPvxf~W=RBA$*bo_`=l!0Pmkl5?c~*SOyGAGVmwdk!_J(nz&-1lOK+F( z>M(x4BUV_xwPP&?*z?HGe$sm!OyGH<*sE6Fm6adUocCzXB?7DPTL+D1Zf`3Vy1EN* zW^hY-AB72d2D#>54R*RwSKhZ=MT&n5tK{|e9b*ic%Xxo(b#WbvEttS7_u`%Ku(h;p zxrsc|rI+*;0IQB0<-sbOxiImZI=E&CJ|UA&()%K4OA?yyilsH8Ndb| zPlMVmJ3z%+W;E;PVz_a%GqikAo%T;jgB^?7!RLNvRHI3@N&#()NWNj34NY}B4Hy5o z!^&n=XjYk%@H(g!baJag*`E_owyPUlSz#gweT(Tzy}^_CW1}RRCr(a{cK3wx{j1Q2 zm$$*niXKoS%Y;6kkO$NHYGF%(N_e%g*w9O5(h0Z9(H-5<8a-ZF$9wp4{@$ zFUbccHbstx*AcVf@+{Ry%YwT6%0y3|`nrPjTUZt8KMsl-CIB2!iA=o>UkmN{A@RNz zTcRok!n4Ggu*9p1^h+Ae=pA+Vl~V0^^Shps1rtyI1i_d!GvIb;72#vn#@gKfP+J~6 zaiT1Fa5!r{(iU+T$1`hL~RqAbaW963LOCN4;#~y zi3_27`$3@NYB}CMuguqs>BwL9SRoNub?{pp1ei^OnNL(7MuFyhcH_=`XOS<(7EIW> z&xH`Lap1XB_2DtpijVhd&sUZ6mk6wq@8Hn&Ullux-h5-LrF6UZ3iwjd2cWA7b!nIZ zk=DH+=DV?UwHnRTO9s5=F<%~(-c7P#!f)3Su-X#OUcrLwmv`&~xykS+5i0;__qt%D;;ouG59+M>2O9aPqz7|rckGKwvjn7?2>q@C^p z<%@mXuX#!dXfc?tU%fygunO0@ShLjJQWBpGE(eTnx? z55;$WC=ZKkB3UpoetRCw7)l{W(Bj!0HcTm-70fp^Y%UR4h5Ip)1$^&qSa&d(-*TEI z^?kTclzX_tX%&=dPT@TCPXoyZCgO(cVa{kR+!~->)w#t^%96A&UZX=}iNGpcBjSrd zJP{6ejO0xX<(?Y%&g~bShPvO~VOQ}z-_x=WjO!c9pSOvl*n$cDwtG-^O-r~iOnt7L zKURY0VpKabyp}{@)x8z>An>Fc4F03GsAb>l>20e;@ygbgR6W;h7w-nkb;fi|?qxWO+A$%2V1ryfAsW;fVXr22T@Y>B>4g(yB%Ybg;}C0|vi zP4{&Z`i|sVraq*%#8rJB)D%)Cn$m6J@1-+ZLU%_K>6b*m8+T5(qER3}=O*^nqB_BZ z`uE|4mO$&Nb>;1JL}z?Iln*!+^FPF26|NBxi+aw`ANcS}Y4c_ym0HY732)nN#bHC*al2hHz_%>SNPj3%FS3fO0Eu z0>c(eBxGEK25sv?&qUQn>xGqJhWk5Z&6A-LfmOJC8qJdH=k;sO?pKO#PLN8Di4~u3 zfm<^haWX~qq2IvugJQU1*LR{sU=^+fvCr~@3p8oBPr3AGf>d%`ra^adq4S6O@Nt9c z!>&p^lq&aHso*_~VGAa%*yO?<^QQ1=m0DL<+-HD83Rl`+pCA!f<+UXT?B_RtDQi_9 z^Q+HhUa@B7b!xl_DIK2hlYFmQcO!ca) z#;*q-4@H@Fbb>@+)mob@2p!=BcVbl^5hFCp&@oRGuYh3;TQD)S>>8NpqXpZZst*hC z%V`l!18o;Y8Xuk7tSQ6jKPzABUV$CdE+mRwt=8S{UX1gY@@ zA->(+ikX&S3nqNmEQC2B-mqe- z>LcK@B{!+Sc-bq-6vu<_2SfvFI34^}SC!&NanGk(@T)Z_FD$c6vS30#G#36Ohk)a4 zHR^jFTa!nhB7B9@N{PTK91V*1A45#|<-0Ap`T0vy)Q5@d2jakR{#2-Dr}mxa826 zJ6|j>5m@!$?g^OOwmE#bruuko8UPNqBl-Tk2NYW{fk$fbRh2FK!FZ5A|8=nf!vt16 zewYhU#|TblSvbECsb<9c0rRNMCyTQDI<$kuje zlm-{vxRbw$)M~K`_ZS*Y*`()+PY~l7KfXx43?}5KeR##EiglGH{Nz_tsV~7Q+>eQO z^b0>JhK|nMqFQCChr@*2K8k!z^odGk-mRgZ6lLJHB9G@y5)<`pitPBEr1sM2j0xOs z#J4QomxJYcTi$o`yDPp(a;v$I@g6^3np+Y5c?B%mKL99u;wp|I!FXo;Zan4J*lOGl6$o&ui)8& zVGAa3D-b6qX$xgV7c2fYtfNF=6&@co8ttKxig9=&vA)|<8V50fTY*M%>f3l_T4Z(p z+Mu&UU=?0L5+^{t7Aa%1ZTaL$Zqj&;3EXbP4hZXcO7gKvd|+uWiNGqnGNsWRHd>}E zo>!GWf7hO23nt`o@Ll0Hecom(W%JiaHZOY%+}iR*f6dE+M!eV#*0HDcp5-j*xo-+w zYjaq?*w|9^SA|{Q=q%rV)VI7J!#?)Og@e<*bVH9=(SeI{p{~POU7F5{_BYD~r^K_m z`gvA@Fg13EG8dESmb_pV0@is9PxLO{;77!>6$dG^&z+!`Bv*>XCa8OHO=(L44PA) z8j%cJFmX-LtsiaI_A9HFqyOYl`o;@wXwDg#z$&%mzuO$vE-5Z~$4!0ob`@t(t0keV zaLqmNZEHiii8;s6CvTz2;yPquFLR2oR=nYD_(1PGW(GYvEtG|SJO`zRTakBP&1u=K z7a`_?4H=eXP6u^40UMwqX;8DKxT@_w=k!gy;%P7QP=+m-z`iw_K7+65eEQ9$Gs8ld zI+saZUWcf28TIe)F4n}it9*rmu)n7JJZBDFyCj6+YsZB8_p7tD$kh?*{jmLhOJ|!N zO_zKM{U745N-lZcsj_gob26RrBA8vDvkyibup>J*nNx3{6VSMwEomj@QMg9L>W9}y zy??`G3ZH|ey26Ae`XY?IZbLSRdJ`*mW1r{)@6V%NWkMtZt8l$(G#78oflcQU=}Pku zb|z^R#E)%6wmdSY*F;q8_1%^17Ey6+$5qh%TnjRyI0`>HIuh2W&!rdN1~Y7VpSTI; z_H06;BFriNC2@MW^B5@Dltg>n4wigi!hB2?-0^WDNpWg9n%(q;yE_tTVt{;ASS7cQ zTdWg=e@~{hHv}_m!NiobJy7RX0}@d@kMgL|3LYO%rY-Vi0;_P_6mK&Q8N=AkJ!#Rn zaMq;BCTMG4iByiSNvE{h2uU$jNv|F?=}?Q!uqL@WSz@6+yT1;b!IN+PRIv_c*n){U zWjDabPiEwukxF#bv?^+uPHZqW57xvS97pUs_ku%h=4!f{wFGk=o@g z{?lr`OU=`p76sCshr^_v0k;XR;uzr#I{) zBm%4O)oL`8a`W{w&orcV0g+NUFd_GFWj^oFf9zMAdOwi~tSW1r4d-5;(i&G&d(lru z!FrwFCz4bznrU_x!Xy7Q?Y(oB^bXqvM~jwg{ZIWfe*AwgIxjmxzern}-g*$l@b6-x zf72ac8lq@l`lvpZw_2dDmRFI^TNcHzXC5>iK!zKDD6D!lNv9b?L zoF0@7V?G_%ZnaT;aP#H*iwCPxvtcrURdUIFdQ{X0?e-;fLkxRcE*ExfJ=^BqZYx^v zbPjxcTTz>|-ir2&&xiHa-L-Fqs^eg(?CN^|j3_ccCWc{^=NjQ=m;)Wcf; zt6)A!9~i^%Z(+iD(H_VM>Y;TDP<;$t@1kGbZYzm1mkCLQ?vwZq~SN_zKYh-XbL7Z+nZPQ1H${f-+8#Q^>$djv(-`I~W{?YqAIVK$ zVnr+U%?10iL)wfM@q>-{f99ELTHQd^N2@oRbtiV#A>OBB7`9-dzlb=NJDhE!MjRT= z-7md$-3>;N@*;;VCa}s<_^8;8`w8rTh9jhBX(KjC*Bu% z{5EUvcK1Xkf15vOaKuh7{)%53dkLj0{OOpITjE5318zqP@2)kkBVsXJHgN1L9%c*F{F&%`hstKk?f=ywhjS$@)`?o@ragqPP>KiCb9ZH-~rf{9+@X&-Fe zUH`iHX}=v{svlVt0+tCffmLs=?}1(69{PskR3ABot@Oif_P{DlOmSaw&_7MD_9aIw z_CV^WK>f=$Rut1>&z)%ly~nuaP(fs##uiKjt=R(`JM_>m9H9EpfwlhY$P}nHKqjzC zzN)3^OZEL+jTPPWD2Air@Nzp~k}ucS>HOaa`Te>1dfyl2mAI^b`jWq~GbSD@J0PcJ zp8j@_+WRyeI75GbvqtfHCliuNwA#NlqS1`|I$1yP{Zr`F`=2)W*Mf<$Zo6Ph*%kVr z6RHn7$w$BA)(IHAS0=Cu*PG}QqweeD?1^F+6TuF>%>qOHFMYm^1q~OGw=VLnzOfh+ zGfg)^=)_7;DMlU7qh{aLTN-v#8Xpd4*n)}SBHmpJ72%(F*ZGJBo~`b!ROl-cShctH zMz|SN6&i?$L+qfdZVjiR1}e$QbavBx1LR#dgB;_UbexDqQj)8~ViAkHGFuPtS6ITg z%W4GRQ@=iRS~6Lgy*-R!3nl`@{A0sAJ7`@z|4`D}LYuac%G&dx5`k5HLRUeH^hWUd zo*KhhzwQXBiHS<)xDbXdn82&iq7A<3125B)6rVT2(yB9FPsYC_=22C`q1@iN%Bk1E zk`GMCtF>pu`4r8~M8(=nzACK3YrP@|Pd`U+UYe|wIuR_r1;Fe3xJ)9WX9rg}cO+Ta zUl7c&1rvDXUZe3ebBFMk$x7`#GJ#ccU9J3Rt?zp%R_Svflx2&V$>|40`Xs-a#d91n z{}B7l%_)Afq0tz8nW4{2o2OXXgfMI=nb#B(^81ffrA+l@Jm)IW;UNrLFrof!)502h ziaC{dk7Hd;-_0~hX*KYFiN7k9`2V*{uG^aGpM2}97&i`QJB1~*+GqXgz?u}72|xK7 z&E|qseYXKql)xQf3|laP%cs%ov%8}Aa-X3bj0%+qtcnnG(Ko}aK%I+T@{jB6=x{zNj|8>sc;vu3^C z$Niu8pY7JJ*LN3xi+riC=ju;Ca8s(Cj`$zquL{?QM&tCXzJ7VF#)^C2NU7wikH3UE zyB~IMyZ%cV)kl8S#`+1ZJ(bp85fXt__&$j@?j6qP*EVdSB)yXRM7(x_%O}1q(mzLE z)!tFrG+r(_Ce-Nl?_YnGqL2S+p!_};RlEl9w?;9c zM(2M=39-L@O0Mqd(8sWPShPf7RTUBYY@h3|?_i{koVzRy^*z4j!-G%JOtPTg#bdB| z!>h#WTHnotDcTr`z^aEVuc`G}} zJSh`cg=0IB)$08Q-PW~x^)uhdQ6DDox|T+Bs86P@ex|cN;)hIN6^;Nknlp!9>&Dip zMi&o`Vt74Cy=#m4dhH4EEq{5&@;U02uI02U^iQZf|G3|lZE_tf^D)xa-zk`i__Od_xf z#}cAX+*=lAPm59f4~9xn1}5-GBzB(7F$E`|xr$ql5Q)Glyu(AZ^PUD!)hk)q_EL_0 zFd>g>H5N_bMMKw7laPP2r4coc+Q{o+5Oi@dahbyZW=kXgWKrsF7RqBb#?xxHsamY+ z-aZWObV(=g+vfa-s9QgrYhL%IlXd^*^D6!=On4fGLDs%yWO}@sW$dTOGWKX|7h3hR zOkh<>-ldYOx^{3VFXi^0o~!$BwzOi4xrN9$b!r|N*z@v#u4?6j5uDe5On;P0`J46a ze~3ogqTtD(WK#e9MR8T0ea7=1-H+4yJ~Dw-B^l?6>rm|SF30$efeqO~ixlnICSrf+ zgap#5+kJ96b_Uq>olTx!y!$tsU`aWg5<2il$8Fi?p($FdT5?OgmrtET{&c+cA0qBx zSMK)Al2uy&Z#Kc=-@=4**I3Xlo=f)ER8Kp->*>uqM%G}Kr)2`GN;1xsTvbYJ0N?hm zENdgOhGGjQj#h~Uhu?EaRtxpCQ`@@(xGta+dnhvAVgjr1z0qj8FRRAwF7#x#L|v8S zfGqZYEi)0?jgBMM%O8>xB5UvI?Qz85wt6P+<|;Eje_IbWSLC(CmWESi!^ZYAh_AsT zf`3WOw)fQFZ5_SY+E%g;OnezL8w|V6AT15mlX@SY*5sxgy0cTBGJ#bozY<{Qx*248 z1(mQGR*TnM>&4cLOwnS?$l3|uIc_F#I`i;9R~6mDhF4zQiCNB*ePCi-YCP0`I+Hxu ztd{)5cRSvBPJ31aGJ#bkSr|+1;De1VxX!mFGZT46u>})Hs*5bj)8k41;{2Q^&$Q<8 zKbo-PWn}`Z@G~veui^}O@UVVtipb&i$S4V3t%xDcFYl8ZBDd)GBQfNL<%9o}{8+8B zJhV(dHcAlqPGO?l>A4VpH-?mTRnI79{x;(4JNvVfBGVrxunIph;=2Y%S1LpOr?NDW zg|E%cC9v&&C`o*AnpCg95PGecPDYKt@;C2mNnPzfkfT^npUl2Erf9KhZr}nq`F1+l zZ*=WH#O)4;m3GZ0FiXpSGu{^e7A6ipoG&snL=f9ZHLI?FI$pyeG>1T2kh1kdlJKR zTT`?h$FG4pX<=k^#1`_>HUm=Hh7xL~|C<-Nq^_zJoF^Wc(JZQ6szj7zrY%-gyuJ>W zGz%vujMcOHrfyYf*qA8xS>%Jn7EF}nMK19%BrBD6n;pzbIiyGgRwblvf;}4|$+5Ky zg^!;HO(5!247)0F&za{60i!l{1~~Tla5v;9?6VI)$Wx<*rbYI`X*i zL4M6tCVPjnIwmrKRrr|}`%6}5QSaCwc1&b`$9011>g$xvV3i+5DyGdBJ{G8Bc zwoBwu#1>4HWbQ60N7aF+Xw&R*Y=y{WiV3W;8M+1T8^)4-2h==@``f;vtEvrWy<=0f z*n)|XrrA)>V+N^~J5~^nrj};!+y}5X2U4`yf{BvM<|S8US*r$1O7~_>M8yj{jz` z{~yBYPaa(EnM{1%z8Bx1OEc=lu6L})x&+DuR+VIzFYz&v3gTw0;}ZvkuAQl zWnI{n2iyLeVYT?G28b-Kng=;6vk|DKmY=bJZmlLKki!F71Yr zX_aTd;&@Qtw* z__n4pfmJ2>U`u=~?AnocxL%iE5_N@Derw`kMAKcQk>$U+WlM;?RR|xS)R+$t;~@Sm zOw12Rgqw5skSVt+iL3IoaOKPIx$s=^lwbm@N;2V=_{evv#~%!8&wrJc?;s`u=FI`W z#X01WQ)%I&+sHZ`I&|g*V}^>e-!&j%`9359{zmy^2RxBks? zTyj?L>RO+SV>l0RKHns=0XggXHgbv%#;bN;(x-Rlla2T zgC}W%sPrb9k59=5pE{{pY_T344pw8T(1jQ)^|(x6RY_jkl9ErmH;r#DvqY)V_1}!Q#THD|Ul0v5I&LPZ zd!`B>VkF>=^0F0mG{C=wRVCSWOMJNeoWQS6+OPEc|IEF`7EClxi-w8aHuz8@G;xs9R#&ER?6uk7`9;In@a|) zs$D?7j#r6MP=g0`YtEqhS^9pX$mP^eNA7YvZAk_&a=)FOHp6WdH1#SZemm6sIEi(v zc&+>0 zm8F`!?x$0Z;DX4&Bm%3-9M6DG9|}mbv#O6#Z{n3@DUZnMiNOq8FoB`NTBJTlgq*^^)?yZ3JHw=}xf)6S;eqK%{pe*^%up2yOQZ zibKp$UdbRxBCu-Pl_lUQh}~<{Oij;5Z-rqe+!Vt%;p|YO3}{rhfcQ>tseSff0X+V& zySSZu&RqeX!wQHesQIJv{f|MwIe&#!n$EBV6RqqQz_vL#q|+Xi*j%@UVqJNya^U`C ziNLCMV^+Yo$ps{|l$u>-)a!XryH*Wl@{&mDs&Gri{xq7H$35X~mHQA>E1F>oCUBb< z_v76>eYrX{VEgeHiNGq{+liTQ_8BE4b0D{0m_~6eCS)!JP4`0bb5jp3zE5KQ5qm;e zWE;TKM(0TP0~4QjFNNFP3W-IT9-`#qO+ZO2^x}@1B8kANje}BQmP;P7{ibG*xDcAJ zj4f!-&+aY9umuzI$ECrZu7zY@bQeKnM{ZFXoN?tp*4LH@tXj}K9VUq$&N9+d5QdM| zD!(^3;jL#nFl^b=I$eZag(PZ#rxyDb=Q+n@Dvgdg@G+a5B_Eh@c$N+gEJeu+)qF); z7sM*3ZdTxXo^_W9tin%>SXB!it+aFgrY!UB%diC#4P2K)zx@Sd!6r3Z+WvJeO5)0W zO8KW_Bm%4CCvno``g~6xExRY`Y@cO-5th zzP*;M`99}w9^PV0NxodNU%#LY{w1;Rb$&BmCDV=NZkjQ~k35mx@pNx%X6$f;e%P4@?oHN{p9gHUC3*CSn(48g$nKc4a20t| zoZa!$&spG>l|)Y8ie^*SZiYo`c92)ZMO%_Jl&E<|R5@uDvOm_@a{l1d1|iaGJR3TP#Ln)h)x!92`&e|cGF#(p<((C z(yg^hxXv+DG;OQXCp97%wqOFsLE=5m9WSM<#{k;?>@|(lFP*zh?O-fVF*tq;bIlCB+GH}*jJLdnW&kYWrDaHDzl=$ zl0|PK7`9*{z4HzjeRebH*Hpdd#{;`6`=dPQoTecXfmQfw#r~2>_Poo1`mBBGN!mnw zBjw=O?WEOlM{U-;?O>3#o#?*UYKNQb0AG)7BO+d`*b^|jOweSM;iB) z2&}?)Q)Iiba^S6LJ+}DA35u^5_Y$~#VvH(n$B)dmV3q2AlS+;Wxi87esmSNmF3Wm& zI57NMSS6SIgPk!S(5wury{my#4oox@nPM+3SVcYzR3qdM<`uY8pI>xW3ulSIs*=o5 z#kDSGcN=SQ-$6~-%d4j;o}*jd>YM;Rz|#)zZFX# zRh?l1t8ff2cFKwj#BmSJnNgR2GY}Wg0Wcv)`mMJuRj#>hpn8!D8}|k{rj~1W>$Y6w z-s0ml&n!TyD@@?1Uqt#@uSBc;PKQn;5`k6t3dI-x44x|XFMrd%%ZPN(F@fhLV$JfB z$g1mGfvx@CR3flSE_t1>B-(lHIQHYs5*la>z!TC*(!0Leqfhm4-z1%s@*JjJ>7s|U zBWYy*3pGFIpM%!S&{4~(4w&~hOC?crXL=^<;PJFHQZ;q3Hbkd`F)P!_&Aw{X_cU*T zUbkZiYun3b-ed07|0l1mw6)0&ol z^U)XgcDNrC8HlqZ>4#clsZ+fmW|>_8U-MTGJ1;k_+lm4Rc(8(Ox#_AkODKfugEB~- zj~cfdUJRsF;)c_aZKg16!31Ae0Ea%TAj6KRbAyo+=hD~()9CjDlO!LQHab@T_s6av zmm9eY;%ki&^ybE`bZ6gj3|lbKrnC-b^;khZZC9hdvA%lhOc&D%?!zPkt7exg1k;@5 z#QCO5j8N>^<+p`&u}33T`J~8G?UGJnu6EXb2`GfG8P;iX+Dk3ZNv<5C=Cu`j2OE3P zJ!dDeBet0mfmOJ5iFMI64HR$92-e*7x@#Kf5pVW$^**T_m{{4DL&ULk z65Ga0T-9NdYW(6}4|cP^d_S-X-y1R3t~#LP9D77FdiG#=?877HuTUM7ev(0o{M1#0 zwE^c9Bj56@|6and1rz&vh#bJpGs&tnb*z10pQ)^=YsD7cZ6gs_b-tP&E?ihanhk6v z2;b6rC51L-Y-~M-EtohVazozuw48itQrtdl?OCHA4y>QWVT$`D++X46Se(tc)P_~J zwPRTmf+)6N!rod3t=}vqA+HCDt6HAjo3(0Gj?L6|lnAVn+lS5KKGgAmKYJggVYnZ} zPv6S`kx%@6Itlu$_M$bdHqgyM1DIRe;}lykA@|fl?VnJu{+*d!pIZ`vRk%jPd4n-V ztSWS7t%s*eb%lwNY;feCOv(onYO!qxh?qwuO9WPxne*w`(e|v|+m>wD z2OW%Dv7Ai%(pHPhWH(d?2|mk-zN4DCcZknLI%KdT8`R#0VGAbYa-3`UhF+Xhkxd@& zA`w_6_i!=iYOtEWE3)ctH5s;G0zV5PZg+QLZ5uzNr6-w71XkhRRimlUsuS~0yh+=? zenGJX6L^HvXljI&;b(gounK*h8E!>53d2vnnB5te@E2ZHS-qzg3|laP<2kXa*58cZ zv#-vY+&7U3timy)MpL<|33XL%^gv%F@?=xiWpFczz$)CkihlP;N}C~z zYOwrn-crAd2^?{VXZLP2-2G9JO%h`|{w=J+ql8#h>tv!GaPbArn?76`4KRV@AhFI6 zu^X07JWV@H94ir6mG-s(eooCK9z)eJDxlgKQnYjqec2|MVGAbY7>@O?Ob_2|N-J!c zE)iITBTn%h;cqRWR-F#C*QanP7RB)=_ASnstZ`Kg){Li3o==l}U;@wX#hT1msuX(c zq60>cmk6wqYj@R(1Z8IG4jOc4lvG!kkmt1tH@7Ndwx6RmV*(@st8io>b`EqgXBTX? zQHR-DhNDTxK7~+k$1-AR|KG?m#KedxV^-64V>(H_C?@3S)g|x|wRwAt4tm;MBCraN z5*p2|OS@^mV`pi7*S^wdfC>DJi5xuL#?$9s^Vv*aH%@(^xumuyi&5N-%yb*nVrYkeO zU0ouu3P&Fr&G{#i)4yNMCTe!jl5cJk zHD|3Hm(1BPgl#_aiB6tsMlSpAg&Mz8NcxpCTD;S#Bug#%Cx7k0hxJ&sA#GXV=xWkT z82i96qxcryuw?!+I1?Mx^dCptkcEwB|MKR`QkhICx30q`uWPnYhzjL&42UP7F#fZ zXL{m|Vy|?iZuA(oHi_j4+lP@IQ%2fe419TvcXtkWpAU_vg(@jsP$ zV5!b5IAx(kU{y&*1fu2u7N_DDUxUDhQ`w=%3;yP5D88zaFX9t5lP;bcYBcu!14*=X z2&*bG#bOI4O1@7{{>c>kZnO^_?mdOgY7r|DSS8OnqraLk+tS{w3Uid&2W}I8LJHvX zy;O3xznUrbkE;p0FwvV83~fZQ1rs>x7w=MU-=wKshcabB4~f7ke1&2MUC3>E{n`*_ zp6v7Y%k{-2!~~v;h}?iT7E)R;ky)7pNd#8OC3n^t@OsyMSg_+v>i<3mYJQtVI(_sa z{`x&I$zT?lXzNdAinHkF0%nn|rPM5AOM9E}_IJElKeM_tb?*YWIBGhXJ?uL9a6AR- zYz`+opWh;L2d2Oy&j@nj5duPlOkqaipK+ zBhoH65wg0(k%r&Z-Rf6vHsE)Uv|_Es_|cwL(?NG}0f}yUij?I4AZnJ7vD3oDm%ta1 zn$6X$B&L0v@E=cFGIQsaRNE*LEIj6uNrNttU#B9W-J4|cr~W0fWN{S4u9!#G*j*Du zgp)h(eZz@GTbogA!9?o|F_11!D2$w_o`P7nyD|Uv(2Y4bHjxOd8aX%`%6v~E)*aO| z4WG_5;7tm(thTNJeLZ(3?7bCF0!}<2A0NfR%k#5|Rrozpw$TjuvwAkE(L&8#tFvcXB?Adgmd?ZQm zqDu@}(n=-nx><7bE}dDQ=XEKzV1f)zg0H1w2n$w;-Tf^2D3{L6ccx5W6>bIMJm+>p zJ~Gaa&4_lT4zL{N8ikM!9S@WFm6ky_;}Fv7@o}Q_ONaemLddKA>Mn0D_X^zGqc{8H z?@F-+6IWdqL(5~Kq|#+ITUuWHPbGg|e^x}yBm%2)^A^JIQqze6zaoe*yQ;kQ4{w&# z%9&ydCLUE@1XgpxNXL&V;dSGW;<&Ca``VGvPxUgv`D_SDnxrQi?`OievLR$-ww~bf ziJW0$FDak44`&&>+fzT^4e;yfbfOVCOD||Pg2RyMq+s0|aUcZuMfLmX4MPtRj({p<~T(QctWRiG(3(<+e-BTugdcS7k${BxkDua zt8h(gH0zs{;-9MfvUd4lbkM}z(DmmG;?!;!3BQ#MlN-m9i5uext_4w7;_I!g@_Mq0 z-k}s*Ffn`eb}+JwA*K;(_95$>QharLUzT$@NFuNb*PHkPf9r~T!p*MCYH1S15lf8* z1u*;N9OCfWid;3=3(w2XB`dqAnSo-AME29>-fXz{T#7B2_$D%;wmvY2Obo6q2$Kh8 z`9~jb*4|wvuqw`q1rY$kz3y%wUusIUJM=^wAt*Gt!#i9r1WSy%?Qa z*|Xut+OZRbb0h+*M!wB~i*x3XT_$R_o3o|0EPb{Un|-??!4^#5a{(I7oPM3yqQN%o zQEi#PDtrz>e93cdYr1^xbY^H;iUu3(hT!yBq;!@jQ?IS?!!nk5{EjF5^-kzLc^2v7 zsOENR?93@SIf4CHnJQT@fzND+cD~$z-OcL9LS3~IfmQP9fuQ;;X;qJ@Y;`LKf=|BS z6DruBM)RY}4!YPskY%_yO4p7Fd|E|(4>|2DeROav`#PktL|_%ZLh;q1v`RF8XcW_C zTN8ZR=|JXsSY;kgB08)g_@tFMGrD3{o9IO`?4aRz$%2XhW9%&8s#w}Te(Z~#D5x0N zgWF!9!%`hcaEzYs`GAB*V-^uo8GxE{{!rd%r8ojO)6 zt-D9z-A6y}p06Jv*W~)(E7^Auv><`+F>!rjrJ{20A5-bMLvA_(z3}ZS@rE0d-+7Fs zw^p?y_~snGgNOGn{;vMb)$;w23AAEDdx91u^zTPm7Tzf@xAdT1M>psQ^ujvv^Ksc< zuC&sd&a!sZ-M5jz_p$g4U~vz5b9P_)_F4}efnL}OJfBz10*Wc73*8Y^Ny57@&d9NT zd@SjhOF8q&l{U?rTX#Q4LO*Zs{Ozt>{OAx$YpvAP9KEpB`L_+9UX=SdjG#7=t#s!D z34Hs|V6coWqI_A`iPG))bTcxXYaz|Q<^4Q|GRe0Oty5*G?l}Vqd|#1|KCPa~er?@p ztIoVs@MMBs`cegNw^FR1yU^56xphx0_>_Y2_&jlBNoAma2kNXW)XgA~(7$EcrFUUv zRk3dLOg9G|fnNBIDqnA3kyrU~t0#S2$AO>)-+k4WYS$MFMQZO#e-zWlKtlgM=e6%S zl)5?lQvZC8x>BJRwj0kf#=mT=v~NR`UP}buamF{Ku@(3#&aW~`?`tk}TTZHb?n46K z&gSdwudS5r_1n|w-g*MPu-*8$+nDEl?c+>$pDrumb0$8E=u0(na(U%lYD?PwT}}xt zNZ@k`zn|YKuXMF*MJHM;)YSvMutoUwG0;{yo7R%nYDaZ#g#^9<&eyMgHdU-6>QZl` zBf)p4@ttb@GtRC<^_4mo8`DKq9SK^Hz<0R0R&8TVrR{AaT{Li!jzBLgA%72YR1L)< zMWUx_w$MGrA%X9rbFFh)6{YI~2U>VP)e-2WuX#=P%F3}165W5HvV>1`_#BP(<6q@! zP)o^Y-<-aR&nuw?34EsJbJ3hl6mqv7t$BWluIA{4tHmp^j}+8SEZxUn^@AlDeH9vdSN_+q1(moN}i1c z=!{+M30jcAuRHL&bAc|(I=f=jU+$zM&`V#BY=2c#etd35pG@qmTPecTAzTmQ`)YUU zDz;(uX=oiM-AWM>m!f=Fm{%N$t1i}-@}Fz0jCxm_=5nc}BhU+1jrcd6(pxFt?aR^< z4n-uiAYsq5>aHjkM+RgUF-lqWP$F~Wr+wD$(6ugl;kn@&`k%d&JI8a;+eV(b7rr`z zL_)49thQAgne^)rk8vw#sN!4huJq#B03Cr|`md2p`jpB(uk@kKhPdnI?K^pn)L0rp zY(Lrj@l<4aAVzNdXcP^!`kl*EUDL(YY_~vbv`UeBQz51g=7w<|y?%=S!oX1`)I%p?@k` zG}M}GY#cxnu0GHa=ryhRdN$f7i1;)X&*!!kUK=ed^Y6Arm5|Vagubm>&n_n~IPOh* zY;e&L=%rt$9$IUH+#zKG_1-;3LJJc5o_OZkO?gC>{`7Q6sE$A{TqEc8Xp>8cn$wAP zc|23MdX9wtiN5inAFN7kPx`WSl!QANNa%L~cFeA4>T2sl3(xb@t?477Kj$ZN1xVJu z6X=`ogLDLX;hqIoSyY`Rt-Q$JpzG9Hw>NC8q*q%^=Z4)vW`G6+$-d&u!}BKc~piby1MFiMv>63e)O)L8Gq(n zIa}Ty&c9i+wTF&CFT6H+Ho+_7<-=<|X`6hFbk`sfxQfen$yOd_jgqF)w_kJW2=u}+ zhQF)tSYLK-?n{pz_@En0kigXh{?*eq73H`DKWZ7fPe-5^u50jhhUs>)XRsfAcr2cv z1quB+!@8!y%-AiEwmwo+N1&H}y(H(pUu^l#%~HX4V<~1@NZ*yfYPWJG8%me>BkMxF z{FUT~C$39Yk?y*z3rG}twv+{oFp|lgMSiv1y)UvS2X;#ig~sX#^ui1bT<=pYn>_gW zL#fon!4xe>IBs0aJli%RK5Cx0^H)$!}4P(=E}fK8$aWZvF2NAkhf}%!(t<ZR1U z+h84mURXl@O{aE#tiWVN8uMffMGF%8FBN7lAIctjDN>yqdIG)lHQzSa-4y%YBw0Tm ztA6#=oGS&hpsZMXhZT8Qjf~`(CHXT>rPZb`TlhJjK9-^d34K16iU)GC{&`+W&Ow89 z1bSf`8VnP1=ViV86sc-Ued{8j&tp=1UQuRqRgsF-(i1u_U9OauL-U*Lo>ZWXTv|~r z3mXv`J@fPLuNGTbjnuDQLc;p-w^GU$HMRMWk2dbrQ&$fp#P5bns}Y6MT(^|V+GN+} zxm2^SdnUr{CB8LkZgu{iSJcb&wf;ltq#O6t+@f2iHzGZGc2JQibY4g!BJzyB;pgLV zY+ce-&19Bs?mUyVg+FcJU@eu3y~7fAHz7_ulj@ig_ZW$6LMHHxr-gZL9_M9^h=sez zkXQV6r0GIFe_DcPSVapGX)gC!so*B0=4X*FHNIK_w&3zqx^_evT@0j;%st7j?Dv>%%dYG^H5{ z1X0DHgpXk?n4Uk??UckA&G(#s2omPYx-9?NCJqpXqhkMeuHKywb^uiMIXSMFP*!EI>G zok+VrBF4p%%jF5(J?PI`%_X!Tu`?-|{aEKh9@Q7byZjsE%VmerD+gvtXhEX8yn+>9 z-kKZ;6s3xb+b>_k|rdx3&&kZWi>{EoL{Ljx)bf3tFts9W)AD&I)E(N zUr;)9GLE&I-H+TnR!|yzZw|AI?n5GZmUFI@y=0+u8rg-)%{u8UNR+6Rz}D|~B|*2u z_2E72mt1RMXL`P3f{s8h8@hn`mF`R?@eJgAWcdC~?w!9kZBe+bgcc<7lv&79n|39O z)x5}F)o#jXuk@kss>kUF^uku)>!Q*%xkA6ev~{?Xgcc-jA6Ul9+-gVWRu<>us^3xB zYv3^IJ*9J`dBkF1F}|?GbEb_(*bTo@lEvm5L~}vbUtOXD^V@ zf`s8yF#A=~lf{czDG%D z`BBS{HL#ybj&?7sJCeb0@=IC8;a3a#^xiO?1&Kay$FaPAp`>R!aX!YTmsc*OJJKBc zs_6*yn%sR9>soy}*>XtKeAB`TN*7lr`rv&52`$}rjbPPZO((0D7StVyKc$|npjZVs z(L!5t>nunlyN+P~Rx^m>d=VqEd_|=LbE5NZejwPo=(VciP_Dn4NxpOzg#D!t^1Hfr z^x3ogwAJ27*85z4;$OO$RIk-cmKr~lOd45Kcir$E#g;jhx^o)QJCPrC79>v84P~=m zjVEJ=iYsbkzI;lahRtb#{g-rv&I`^zzXqcUDbF@Fq$ii(l&~)$vGPnX`>|&dxluvH zm^iJ7a<@=pTJiXK9f4lhV+@88$F|CET#M1lg$cdeF_w9+=|%?SEH34!JDbgD+LP4c z8G)Crn!_55>qr_;6?u4n-rXjjt6@W5UuZzlf<&2piOg?LJMw9g$d`IGW{Es^Z86%Z zgM*GhuZnBqShZU1N#RW*hX2dC^3b}4sLRe)6fH=s=r)fzly5_heiKCDhDYV>F4lC< z@p`&?;Mv3yavfRi$MUl8wdv(w#VA^k&|UL}sk^SqaVHwk=t@O(1bSf!`B+luj@&n& z6P@e#K|%`>IJ)w0p6%HsKg>m`U9&do7^_ z2^?K{UVy^0L$Ow-ifB~$w!euujKRF+1~L@h=-cF_uVKL`DFhAG{@y95?YYJ*#Or-?#?AIU)-G@ zP0CA=(0QFb#wIw{Cze-5J>KlP!W>(<)2=-pN(QhXfpa4Mw0*W8tFyzETGX(hNT8Q~ zzB_VyMOJRmP-^nHr<(~QfwN45VcHijQli+C10hI?LSD6nop7cH0=J zn}s8xpCMN%?w($mCSmevvIC1&~+!;j=n_Z@ZGK{N#2m>iwf3MGF$xr@2}^v6MV}LRtE@X)7Ip zUigH}wKz9Q%TH$1qi(Gm>YkmEz&>p-%=vMQMRDEI7XB?gJQjNCpHfRXZDrrGH=;9^ zH_$!NBY}OIzqd^&vm9BGwx8~-BhX9#%vq~#X%>;(n0B{mpnHNuLVtbq_Y5;ln$wsj z4c8Osh0nYEoOk}7zWf<~6C%t)_aux2K7Voziy=r6|116xy?WH!VDhoKo4xowAzKhR zWgV~nURWfAcn8MwF9Q8Zm@R)2p(lfg_mw68L72S+9r7ZWyzt(f1!0#|mH6f_q09R! zh<~28|11^eDB?6T)Bofv`jaqQ#Bt3;9=--Jb51oDQAMl)AR$^YKBN&7Pw|-fUC{dn z)McYxMRs{4@Jwl5M0nwvgPuSO5?Tq>7Wvp+^z>Yy9`lmqDyip7QDyb#G_@GkL~k(c8@yB<^zhd|)tp>Qw)K5a=aJ z#jju{u3&wsgyoIm&&CzaVSk4I9$YPeeRj$5|11>}=Qy48HIVJ~&!0sMb3M=tTSQ-~ zKU>s%fBpB?MT_{2#Nl-kA=7kc}zg zy@~%tn7su3w7CoERBL-ygmylJm$}`<@7Iby5$7p$4724=g3~1He)R{TdcEN>l70q~ zM`ivzgJ{uWsD!xE+Pn!OYhIT7qf|(s*Wa8N&^?HhKUVM$LLAq8#}S0-c`z9}t(WfZ zley;R`w|joIX!(|Fv%y8EMk}m^uju2j$v*^B#!YIVFQE7hpM%*h+!ts3tK@SLtNXd z_77)gAKDP{`)9{~tl}YeB1(0v+CWykT+1waiP?gL_+2}^Crc%v|3R3&L=4`i*}wL7 z)q=+rzZ*R0!cK3Un?(%svC!)}C%PVL!+L)eZ*$=Fffhl$UF5*Fti7hz+VfGS#=OZ=CJW`_tk1PIe8`gwn%=EDyNT8SaZN5Kdu7}xzgc$h_ zPH)5{zB};m1bT_z=GjMPV&c2utj+z3{A<5bEuvING$sC|{Xp>@ zmOpFGd*W}x>?P<0^@2(LmFZbrA7+d2LgL?NeMp$S1Z~wMm;_Eq%_4@`BD|0=&ocG( zz`NxgPJB%aX0NUo&7;r1+&Rtn)ISM6jxjNF*2fSfF%#mq*-QN9rD9pnkj<7q2|m|m zS!wo)y^3klwCEbCdg`B;K5dx_utJh6X0=c)yX%bf7+I+gWoB)+Tm zXTLHZ3%vww9{Dm8W(yMH3Z8anI2+YNsHy&pVJ6T^{5FrrnF;fKTa;wa`z~ZS9|y&6 z^UNSKVYd89JhXEqxf%y&Q7RvUpRciX|OYqyV_)XbOHjGtWxr}80 zEWScJV!lyPdR3+Oo79t#K(Eg;_pr#xi^%lrTRGwQ++LYduQn}oVLU+#63aI3XVQ`+ zGIF4pQ+qfxR$ff5L$5{FmXJWN#u5A3w16b?NER{Nc|MCZkG4<~E_D#`0YNI2L-{pL2x$ zJ$)W|J4?jaeXWL)ZYj}QV@D9QATiYLD0>z&kCaRmF=ofwDzC=1pn3XMm5@NM#_Nx< zai8Ldy|0L|{Z|F0UAi+}Yd4Uf1&MVzPq5kz;z+9tBF5fhWt5zjt!ND28ASrU7TiD1 z9u=gV>M6Fj(rgm)QN(!LlCRM3>`1%4tt26VUY{19 zWtUIPB5N9n7Jl zFEPJSQDi_b5yLC_qFi_AP&%zxX$cARYPSD6D;^(C_B;?VM);qQFZLNl;~d%&v>9$F0lp=$eQTVn0VN6grW<^eZkQfnK@DBlfGwD%qOG2*f@=m)DQf0?xd%P1F468SmU^`;`ssFn?5?YY(^)kq|E+J&oNwJ=Iu-OP^ z8Wczebg!hltD%?2;?L}Okx=rOiF(9Y@h?d)oJu#Hvyjk&guWh?-Jh_TsFk=e}-B?A|U7%vL`Vo`_vY2|k{30jcAc2jfLNak!eJVy;NXRqS9Cx|&O70+oy zblGlx6KFw#=bj+uyg3Gg$a}`~pD7~u8G2zno*#?+lWQyDLoRAlrjPP|f|@z&w*`qj z$q}S}$L;)G^!I$$S9+oqeQ>kAa;%D;Krfy@N@O$BzN|X?KwD*UqcZdn&*CcnDy-H% z{fs%6Y$L-H!%5*?+0?kAWa95!Q`D-La^m4%^mCG$UyYb8NQm|mrOe0xCbEC=EMStz z048c@CeTZ?vS^iz7=ye%%ihNZ(g)dMjda3VvW*0h^)m;Pzc+6rN!HWIvHJ}O&r2t= zfN8{&JNcCtTYFIN-mylsAn~NiCXzIM8tHyfWB>~qXrYw);!0oE))VN(^R5w|hf9m` zuv2xV*58y)S*zw(`)xsDVfa>3t@lha;*rSb<$kMy;#s;eoy+ri;jz#QTb;jS;^m}l zaHve%{+OjZA4r^}+sM?K;Us8QE*_)nh*nC09TjMCo>do*g9`i%FUOKBUd9C1j&*GO2mVmmHWBA#yc}>{(jPyDcg#Ul`&~3+-1kFaEY55uKDw zs!M)kXVOews^tT$WcQ*x=j0kRXv>3M>ljJ&uJ!!c{F-Ei?;oUxkY?%^3 zqECpdRy)&E0X{W3kmeXzQE@tr;f|ECr8nsyfM07g2eTvYl*RV5E<=1gvY2g z?XqmF#WP?O&=cr|J(SC z@;-#Q?))Q$)ww}Zv6Lya-7+<=R)#K`kk9}?E zwvsM%bYhGVEl4!{ID?e62q8V4#aE!-)GJKy`gWr=%IFF78dWudgiQ+~(>{r>C*=(( zMQ_A*pchKT7}0`+$Fv#5&^Lr+3%SXOXFpofZ63CCW|tV_Tq&4%mJcT#U9OXBJ$Wg@ zXOKbuH`V%>>%?_r#~r9sS z3L^zsDDjQE#fhk1HR$Yol-}bp(1HZU<}-ltb!lslX7t|ASvmr}+Ioi(T4oygbwk8R zx!8<;%~6;B&HFA|kkHrTF#oP|<$Ja1zy^8(y{di>CBcbdWYI+tqh&XDdZ_htsW`8P z=xw4uiTj-x2}ExczpLl)C&j);lb7|+abnQ*f%Ijw&(e8*2GR1ZY9JZ;Jd(uoOv-p9 zo^N7iUpir74oY~gMzkPdT_}h&=U?R--C6YAjd?rKfq|CvGrvb6fnL}O{M!k?c-Em8 zCF$nF`g4v%;r>D7uMrVsT&U=Yi{`YYWxdMqe5QH=y|BOWnM~g)bW*Y5(q;cxa%JgpUXQniQFPyg(~>XGc#CHZz3@Eo>!Xb? zeKoPC)F_?X+_xQjG{kGp6=Lfo0f*qbq1>TorXrZ#(L zEZZ+eN1#_qpbr^zdNFBUW-*UZ`T10Or(aol=cibabCQU=r#M#E1V6IqZ8C{%GD97` z|B12Wasb^>Q(;#!a%cXIj>NDCA5x;-67pceLLOt=jX-J~eBac1n3~b^H-TRIQtdcn zLsz7?Q92ciG2)DMZToQYq4_p4s9`R3e)`YswQ;e^)Ml}hQj1^bIIl$_XwXbDF<>ic zU!VXl)r7K*soRYP$|T;~kw7mo;}f&BjMhEX0Bpxk`bfMp>FiSzCy~rIchfA-xeem(`lr`{*9#5 zxB5KB>X82QS_^~X@kPz(`I|tm=DCB(n#1eJqmHhe=&uZ=j_dEryZPvYmM!D>_k)(L zB{jCWsq^W7O65jI(WY*vWORAjAXJlAI^uqqe zb55R~Nauf9Cdb*T*-wA>L?qtWO(mW3uOeamDUyGsAbm1@>=+~8;xlAC7J6Z?K68jCJMkQsk;@bbv><^`FZ_)vo~@8)EtJ0VjD;dAA)(BlAZH79f4juNAQeqtrn0seMQEQGqn`? zW83=DdZ&>TEl5}%+fDinOd?a>iyR8pW8IbeRu`nim2D-g;c(|P;+;F5(6sJGY!QRu zSa3h(^~#e{HM&ICR!EfUn?}M`a5`D!WARwfR_Xu2Bt`mt(Gln+vi$M9dRnGGQ%W1f z**0AYnP#A9LBcRNjZD87PnvFP&tt4|a#rNeJEgVzbL$B7YCJrRIDU&KH%U8AjA}xZ zUf!Fe5><**v}_}3WbT~=GIxC|BgW<`y$!V#=e*0LH{WXLVjxjHUm7|0X+BZPh-?LC z=2$2TIs{3jDs|Km=!NHozZGw1p;WsYD1G+qNYR4CM~gJ#|8qXs^Ht^Is(1)=RDt$VCh|)fo@CgMvbn?#AEViQY^TU@pQvvQo(vNX}+t8F@>g(j#pF3 zsQRMsTF}kXR}XtytEMG=P&Ap;+Ovsdd)&-8K5sJFyJi!qYHx2mXPrWJ%}yn$eVTKk zUz$aQ7)5v5}ZwfVjaoa?GzFI-TBdJl4;s}D~YIUz3v|rjjDdF-7 z9f4lw52ljW*;n)TiX=|>47H<9lgiWNJUoNT?sa7B_I0GRO*7+m-*u#j&pLA8hS6Bj zeFNzivW8UpY2?Ju+ZE{jFSTj)(XxbINKbsRhEy-Ify~+~hy?c{bl=W;^u(}x5?YYZ z*Zg5|3)<$F13i3S))DAc;l*kqH%=wh4-pEiduSe&2!nrOVaZ(Phiu=?L_~c>J5>?)RnGLY?W(5_=`IAkpgQDw0o0B~__t z-3H&jOBY(WP@|=+BhX7FE#Db;WzslLCV z@!8^J65b#q+baJOn~R!24!3lgVdQ%IXh8;Omz$Sil&CsnHIkt*Hm!gEMf zT2DrlUr#E(Y+#)2vYu3Iv!29lsBdKazkl)n@5O)fFP{9|BDMdyS6b4yuZ}=3jK_0G zFH4jRxz#3X`V?}ihKO-*ydB;8Em`{8t|}GRxVYBEb#A(nN;W#CkPeNS{BhNe zX<3)v!RUq^FL zv>>4$;R?mqqbcFPq;qd`>In40mNpn#RCJ8g%~x&h{4xO9w$g&T)Rru z_jpjWAc6gu>-5vNNadV~q|_O$BhX9S>BJpR-0k>#!X@uY?c2FY&wdP`XhA~U4@I97 z_e8$Cbk``^$8M3H*pJqYaCjHR5rgj)J((ks?2n{(^Lyz=1|+bD@{H*t_elG)y^!*s z>YyXg3$J-TUUhvamAPf0m8%oo2!{mrP`+R5|3JFi;i6P)Z(ALKUf2o-!<5km`k?$p zX--8)iWVfWhw_!8)!FHog^MM(0UdM%dg)u&e`;BJeM*9qR?MEF1qmFLgucZ5Pmr!( zoh!VR^f|Fi?PEAQH+zf!2I=PQNDLdim0X!SU#0(@Krfub>j|_VVP(CE%=kMdix}5J z!bo(1jObqH!pQdb8BY`Ye#|6wLbD>!g2azg5k&ket~7nAkU%eSd|}H>palt0IuY}K z6X+%CChC}(KnoJX-IB=aq|pB$(5rK+WhDRNtYV-AiRJlMklJIXWf21j^qQN#hFG=> z&w@Y;61ASJCC%z))w)Qa*T44?v>@U3eG}O+c2*XpLIS<8hw6KY=%0cTXG&ZTqW_BD z;#pT*RhiEqT96ReqPW8TH-TO_8`PHyV~8hhQGRh;EUlhE3lgH8L`!5Y6%yzr&bK&M znF+KYAjqiFitGy;Tt9 z#$A%8z8tD7%xfXx?mh0;=iU@gE6JrB@kQI+-$PEv9Qf!|d!3)TV9=l22l}(KL zwtDs4O8S|1rM%Q}97PKf9a}FTH#~Ne3)#im(#l^oCCjn9ZQf1p ze-lKp*)64a2hPbsMTStcG%v?<&z;&$hAg!Iqg3l1Mo612zQ`4__tM2cV&S*>2|?Bz+rfp*(NfQAeN`wwu8)eSCtnaZp9Y;#y;h79@f{@La-1i9 zZcL03El6m}8ZAcPjMB7R+jjIiSG^#CUfS+}Mhx>BNV_F}kvjd1F@EV0L|oRcW#^8# z5uXav$gtFnY~_On=GAkJcwDUqeYm9nwdK12+FH13L84jeG%{(#CN|%_HecDU3`Lrj;mtKI}NG@iFSQwlF`$*vO#ZzB4tRK#&q1x26P(V z|G;CRm%irXq{?*R6esG&*W1y81g#fNF57Qon`49`B{fe4`u1ZhIxOe!Jr=c8=!LCr zFuZIWNH5k~NVay0H9q(CA*DJlW{x+PkhNU<{H|9ri&_#0x5>WbviEEjZ!a?HtVo$eR~=s{pS`6g z(5qm5AL3gwf%y;H#fds4eCU`0Q{`v%VvT5-ZRbOjfCN?~|IR;3<+Ei9eQq^KwqFrz z-hEX|g~X-`K4gxZ$lQX&UTS;3ml}4`MGoM5soMUjN}w0^1^(sX&4F}iNqcsu>hE34 zOvGRLeTc2YB9uxt>?dozNO6=IM6(V33)#VJeW0w>T5>A<=n#4CLU+w3A# z7D0i7sl%jKatPPS;5o-uIF&z$Ec+h87PyNT4qPMiJp8Mii|b_2f`q0IP+Npw=O230 zlMQn##PY=NFYFKh+=rbUn? z{b|ujdB#ULO|hdLE0WwU8pL*zD`pLg_V=8{tmwT;9h8abztstuh_bK4$^F$q>|Iy! zUg`q>vNZ1@7iG<~7$aJyRSPFw8wIn-F4zBv(O{A-t^Kv764+HA1BrVC$Cu59JouMpe5# zo1ARs%i5MbLPiC|lJFLOY|N75W<8vCW+UF5la@9esbshMt+`VzNHpjiO@1u)XW_ff z^B6Z*yppy~9ITAxJJp(YOeN4u-``qzeUnbSAD|4%r|*eK6nYg&_ErdF5o1IKu*nHRY}1=KUaD&Q->|lJ0g6|6tPw3pxV}y% z*$4QsmP5Io%ncSQ5?BW2ItX7xkjd7hj2E9>tytE>hMKQ%A;bH zm3sWDMGF#1{#!}JpqVUZF`<*`e!YP*#ip_1&PP!s&`VP^YiBUYyQY#YucW-^IvKPe z;q-J9@v9leQX_;;=H1DBirt8wN{eB!Is&~k{jL^c#NtBAt6SZa*qGm%ZPkKAkpmlv zt2B+(Q*|<3dK#3bUj3DZUw-R%RRX;xoL)yd8h$!KdmOspYkYe4F6p^@Q=7?z=v5gHk;m63!_1}#WvD;6wc-A8C-xK>8h$smDV zLL>O%)Q%vj$3XKfkXJZ*U8KIHkS{YgBWVD?sCic&@ zeQqX{E6HIvJsn;aV9cbTXRug9+`2rU_ALgFz@PxY9xvDhq9A zl!-l4p|Ie4k4&g6v^`e!>f-N5afJm}TF63Wffgi$!h$OlScb|%C@ik}q{>2NAruyT zzmW-*g-}>zE3!!r2Y9~b~o$#FFc@`=szK6~-luknB#MMrU zP&%n9r`_wAP&x^f6W1{@p>z@|C%$LTGL%k2<;2xaicmVC7t%uI#5GMUL+K<`PF(Gz z2&EHRkkI#Cp>pDCCq*cokU%e?a^fl>mZ5YKDkrXXl7-RZsD4m4LiL0Gtp>#q5z4Y}E8X2yY zQG`xL)0C*!xzNb)-D)OuGI%x(2BDGRS{X&?WYB_y(8zEF2FuXN2#pNa$|yo7g9Li% zdx_AOeyS?FYtKrd_szQV#aGF&U82%QXCkih=N zwK!ZO!?iMs(8(ZyUi#J*8X2yYQG`wgElA*~q~GDK;I^2oT(ni~S2!boBQjcF+oH`G z{$YYBT9CjV`j5X*)?kbs^X8LjT{6eh6L?%CZWWwQ653|a|4yJ6J}2l2v>>tb^K4Sf zxH*fOBY|Fp`^1pR^Rgn)g2ch1v1H4ejakG%0=)tPW)b_xo3bF#g2Wb61S#}lLly*D zka%z^icH_}Uj%x|U1t)nlWVhxffghN_6a9`scZg&Krba5e}Bm;D*`P@RCzL!G^+kz z1bTIjoq?B=q`dibHWkH|?iF1#)5T||1{)0d-oSp0Y zE|z^s&FMsP%P9N5*8?p`_#6l$`Dj+9LIS;%s8Dif{-P}EffgiEtA&vzc^3Z%fnM7V zgc4`>q$~)uAW=6dj9i?b@E-(v<#-#)XJ=UvXhFhxZ5VmpZcY|4(1Ju0zZqm>rT-$( z>)pYbWNMk{EMg2wTuZz^&rmIWuB|2Y%SWic_m162It+};f!i#0l`nEy>y%Mv{A$O05Wl<`$AQ6~n zF6o^z{XYowT3>lSseL~*3j!@j94$GYIBdwOR7jwg=inrA{#aHq(1JvVSBYekeO57$ zK(D*A7L#F%vWkHgB#t*i?%`w5>e7J(sWl=F_1tndNG-} z|I8`|T97cLtt6)W8DpisUm<~BIJ)Wyodu5TyJih>9GO+$MFPEW4Cd>iT>qFW_jQxd zK;j68N3L*W85+nET>r>*kg5g}3G@>BN3M2c85&5Tf8;tyRRf6@p?~D6MkX|ncqH*v zl`k^aL8=-^v>+k$k6f?FGBl7v|HyTavd};xfnL~d{HqaM|HyTavd}=H1qq>lGtMxz&5*} z)?^~kOJDQ%x0)zU0ER`FSos@|{FDxP7Mc#f*e&sz}CD4Mz`8$n_ zr8n%*Vw8ILQEn3HmWe1`_Bs*RDtU@Io1_&b2tP1*zY%j5GKmz{_;7#tJq1E89JrsFot zv=}pt4d{y_ja33INZc%!Y8tiFRcos^c9b5LYGfkNYs&mY(?p*cS_~y-5@o9wsn@x6 z=cA?~Gve*V*w<e)eDcr6+%vZ=&T~C$x(@PvhyI%oe^COU!Hd(26H9VI1Z6>PhI$>(%-L!eeUCq94Anjan zHWOAP&cuh9ygV=+Cc{ z)Yioo#g;DGbdRZYp8}?gdT`}AHPzao5@kFog)}8x#Fl~9}MJ58h@>JMlO3v9u zi&1)G8QN-6TPoV>atkk$&#&dGC1-_Tlhvoi>Tm7p(qgQtT!VIKMO6YVNIb5QWV zx)$TbAc` zn8wcRrV?0ltWzUXOViV3TeTSTn>~~4ligJUEl6l%rPfvzd+e0v>a2Qo+B;oJ61WaTDJ9aXkKc^3H7&j_t9cFH~MB@>}Ljn79?8myr0o4 zk7+ULH@Zt=CI+Z6kU%diA^$SPmNAlDktr&H791bXRf z?y@P5TuS!ORC6rh0E<+6+ww=W7`Yb&%aLomRRS$YXmbgzt;Q|eEQeZ+&qSctk+Igs z{TrDUqx`3)isSdXD&b&?H`X5)u3FZ9jxsKdnXCTRW@lOqr?%CVxW8Jc1X_>?X+6;B zv}K(ZW8{z$%G&##G7;#7CFJ^&u#a-{m2N7579^(bZDc$jxkHQ5anTj|?8o7m2=vm| zJbs9iA`h#q5?FJrQ`;pgjqz{BYcX6K_EcWj@oa+pAG9E$&9$|*YVdHd5@h{S9j}l; zuLyaU(R8$~7GwSGK;^{>gL?nKXPm(gjvME;uvYI&e9Zs-yu)?j zf6zE@!&U9Bwz;9NGJIJtwNyx;7nYE}&9PyEvh`|;N}vUaS@yE=wGQJiAEeQOW%~_Zv}o)$fdoDRN~;%y<~jx1?unjF8he@fCUKv{H=2TS_f=En%i!GPB_^hCNxrtmnvVB(H5?^BJttq%$hb$E(`Km7m!AA;y)l%T_3DbzO@70n_l%AT7`oGnPQ>O#v6}cxVeqEg;v>=h(t2|?MpKJ9PnloO` zTgg)yyd#nzfnH0yRAAkDJlA4GuU{^2Pamt~5UmRqBx;qZz{3AB$C&N6MUL+@PRU;~ zk|2Rzc^5ddOPB9!F>E~d$(!WiO0PUl5?YWL`MMXYJL|Sq4~x(%vSp9qN@}i1f&_ZK z+t{0}-*Q`vk-YV~Z2fhRV&L^a3leol^=9)%n`1QW^-ey1%1tTtGMXTPUivdwwj5tE zDBnxDH>{~98xUEx{Mmrj$FZiAyqxp#TV z*W0hu8Xnt|mzZX}QrqWi3k!0*@N2E+CrlG0%e#}5Y0X<%1}KAWL=Ys< zOB>;|7*z|EA)AZ(DTR1F(1OI`?D6(@T9{+l#I>~FKQvJBY#T+8K(Emk3?{FipR^eF zI~HdlW&ISdL?;O?NCcFyHH}LCq}8MMqD5@piU4JQg(!jqdW}9@&D8OZImVckDQt+F zuacM711(5Qm|4wKJJK8@(j!Fi@iOp4H_XFO_m7y&qv>;(zeasZ^ zm@#%43?JP)%AKD~R&w)FA%R{vb{P!GA3sX1t_@TQ^XnYPa2(s)AL&J^c$lyAWvlK; z^sJk*>YJm479>UuZAIRmy|1-ytEFe9eNRUy{Xa$!B+#ov@0R5H+y~kjd|KqN^mN-W zr2?-9T9D{hq$L?8J}X{7cX+`8TllbX9ge zj3j75qHY!bwVULlT3cm*Scj%hMYz9h7ihDx3kJ*RALc#C_9d zt#!w2t3lhpCu-}W1&MLzcqW0*o3&Ea{a{Bs4QQYkd0QcYUbRo8lD`u-X)$UxYe)}& zYN-797D>>8M8nw4 z6hR9T+Wbn3u_mb{O`cpvX~pY-1bQ8*wV$*+lBmTfy`~-gRl!>6@rdUb01Fa#=ba#D zOi@~l-9tOlIYSC5bDld&NT652!1H8SlMpRNw(735@=^=s$ju0X79<=mohJ`H_?wgJ z%<^#Cp46va4y7xv2NLM@CE)@&wk$}CvDvLJJ@e*+oH)3pgcc;OUARlm@9L-#_h-4& zkZX_SiszyUT9C+AEfBeU|4p}pB_ANj|Kk~MbLtTYczkBJ6l6LA03Yb&|Ph2v9nhqbp(3l z>G+u}e)T>*qwls)^Q6=2&XJBii7>Yn5tdq}7i7@05=4|lJ5R<8B3HXfw0Ewl()E|W z&$((rV)B9aq|)j=#*BIlT0Mo%*x)K{fA{;Gs|0#!b<$!4U-P1dN%qoe-nwW(!m;89 zGS9SKi!ncFDqTO-O4{%}(%g5|W1*MU3R;Yq4O8fYl>5ZZ!%0F5600tKBI8X3wHOn3 z1<;{Q<`E-rT_n&;YhC+{wlbQ0Y5j5`B%ap;El5ni`H6gA{N6sJt(Nu(qd=n1 zSYS>W4~|4WaUvbJB5M z540e0@bFzya(hQDM#HgVsHe?dsU+_uNT8QC@@X+T{5_g_B(9f2-F}avss)MGh8Lu1 zNNFv`{1)TrhTueLH!l?)3%&4~=PTwGgys*bOg9YFudrZ`Ipe#5lv%!6i;<_1J+)1* zO*_<%B4|NEn?Gpvn0c`QJ=UiY9mcP7B+yHn)o6spoiozY;v;GGzaxk?dsQt5UOSNn zQl+XdeSiD+6TNCd!e+oMGB29=9LNcSm>p#ifA!fx{j8*I(t&7@$VIuOvK?5IfzB-YpovZLnEcI4U=g(_unfl zDuG_wGn^LV!qIT)*|G`Ljn@M$NW4kTOBxP&rNxN8y<8ezV4~VfkU%fIn)!}m{ms(t z(xYkOfZxxxYIGz{{4$dKrypuDrhVKm6&g64y6{rrvCs>zd4r*fU3SwV;z!T-*RMKb zk0~5n&D6NhCoRT2?-Hz8^FUgxdlW$n656VW)>ak9FJTr-0_Z!wUV;RAX=@xBF>%8c zxmvs7^d?_t(AN4?i-SF15o~x{Es3_ys1bdq9+aI+52xk-b~LY9W+DcEuFh5lJk{!P zb;x$vZNCRiDf)ZOQYFw!TQAjOe7LnzE>dSKeZX56ElAA$QJ(pnd#1&RZXGXgxALT4 z`RIcLdTHyvT8w3up>j;pL^`ka?=@uAf`k%(%T%N0J1vG|ufg*Af>Y@G_}^>DDuG_w z>W&uUTDBhY-RQ~m2(JfPkSLpS!ZhruIfm&%HF>~oKeg{7fnNGEnAjkP>})lK#_@iI z79_6iZfAN_)7-CI%kN;*oBPrYyi`b_7xo^WPqs_*ed|TS{m_;_ZM)wtUA)t#wx)%dh-htOp%lFPb2MUfSBS*1Dz3 z=T%El7;9p1~#>&uB5Gea)tfy4aVBxep!-z3?h981}DxBe#j|N3Znz zy?U<3K;l@D!OYO+rWT_XyCu8Z52D$5sqk3ng;$rsum9S4g{8$Z9*l)akflD_i0&g?o1*^hF&*>TTC#?K8F zvL$7AvrnTN8Mhu-$SmLPX7`7SZ!X(K+sj)ERFN(<_0bXNbv}FnJMFfc?YkhpVQQKj zDz9$5R5F$vr7Km6?E;o9d^fY$*u+@)=mOS@f1jbxMe$AYdMC!q-5$)8E;k)V(SpR0 zdJEXZ(B14>tRT8w8!l(R9w6l`HbF2;ZLUe%ezE2AlYcBo>~1lieKMx8Va$mW z!$$6uUG`O^>3QsQ1bUr*&h@Cp(%9*D;(WB-`bmDkvrhljuAayW#JJvB{o=`2{`)Qe zy?;_a? z8#k?yR$Pr|w|gmUPWCRw&dNMyOBI%Djk|G5bUb@!C9}8jLpTvPqK;DMovpGzV!Kqm zN&*XUQdq(K9gRpIEt0@?Qkj)4(3cZo2P!FdqpB*eZH`Mx!xGub(~PAzcQ7jX6IsD@ znZ2g=#ts&VY?(=BIbB7rlrF)Il<3BJm1}LD=m_+>xhsL~Hp;B|sVAG9kBjk~`1@D!HZrqnCvsZMm{d(^KCP(ICi1I<79^UFU%;x~H?jMY=_e#HZ7Nly{KK86LlVLlq-w~lJacgUqys#5c@G+kNo<``9l6>bH=!{ zggZqG5-|=7Sc^O9%qmD^IGSpiU2(EJMcRMqqa)Buf1Ph=93h{Iyhp0t^rUzl;8lz9 z_!syimdW3(985bNPt;veNbKb!Lrp$198*UI`@jow>d!tbSI7t*fnHcbgW*$;OY+^s z{PKr0Ln&I2n3i`DE9IKTJf4Yc9x27%$+I0t%V~#t>j?BRIWA&e`_tIkcJ(;%FrU5h z=+;uQb4hJ_@_GXMzQ@Fd?C)kg(jbuyI^fXJ?8QB(Oyc zhDI-YD1&Gdsok5LG~cEKW;B>sv*2zHiS=0^uE7^e9hCZAJ4pG5m($f8 zX{-}hsDG)h{H(MyT98=#YCbFEkj{!+6>ViWTv)l{7blgv=&U2q3+u#dzTu&q zeeO-Efn6Jl79>{MC$j6mcC$V!#kZrcuUs!bdh$xT(4~uxKrg(~_^wRpM{@049qF?0 zLlWLCah%uRIUnVICmS9%p`+Gir)WU}$9%5ebu6S*?r%eb>0+q~aSnLh`J(UP22J`WV@}^i$4Mn=4twT+$Kfg+1S3 z@So?x^M>D)!ej18Xh8z&#MQB;T1uya*QBJ5*1D?}y|CvS4CjUwRyNelM!h;$rD#C{ z`xwt4dHRNY`BW~t-_fWe&zA{mDqnuXUnr2IHO3{LZeqPf2oU?MSSx)8XU6XFk zfb#_X48T3Gmy$DWpUgHW5?YW*j*Vv%O2{lRNz5`FAN5wccQVQ2OnL&nyqCnYz6P0X zU#HGXM%Gk(eJd$LkINFy6L5~ApEIx?R4KeUm*U}kPC^S3SXzG03-nZStY0F}&huDD zpjRQM1okw5F}F=(+^yZIzfyP6JlS*DSqUvj=FN-g*QhJ zz>RNPTj>Vv&Ee})fD z%p`)UXfz;hT}T>?3!NLQ4WHJ5Jxi)mA`w(Y`+QN`*)X*Hu}|IGV-LUeG!3#(7ehn40)4Bm zX)v%*)b{oTdfHZWItTNyxNFKn_2k3?PA!z6{zOb&c_RMxslQsYQ9h>@N@Ubp485xr zgXi~rQQMz13`W0Kt>IHvmPAmMoQ{nxKC2NfBbAKtt(iE562vV9|J)=XPO1cPL&862 zSl+3T21{8HZ2OWce55orNBv_TC6FIu)Iy0S8`7ZMfg&)ik|&4>Z|w11KvUdxE|b%~ zmd@_%o~MKOC=sf6P8Y=P>s|2~8lZ2zJc*zx+6U`&^&^I&>yu*jRkb}*?ot&kCvlop zMpw+JSpjuEc~S{dg8CCJYGoIklv)u-^^^&!`t~plZe1#dHMRvJ9Wi-!_-o3J{lz5e&1}>+IAl+8;@otwFu6oo!34#t1K~*&36m8J1GrIn2s1y{rNRcHasLi zsJ8^-ejjH!4iRuKY$ZI-)XsG_T55>CYX&NRV(p~fhxRL9!{)(8`$9Mo{aHMfxzZH# zb2}-WBW5vbp~R!8d7$<#goiDD38J`tGj!_ON$K9Ui9}G;6??mC6z%ri-R;Mg4!K~;x* zW`Vs?4m3&cA&8*z6R_&=OFXsO07fm8SYSE}4(N8lnjhT-f!ijd^A6zAH}^{fRarMo zhDx6K@F1_5AZkWN;N(*?IaHQYPE(tCItBt#wnC9nk{}Koi^H1B?=qA6D;Tv<;zdF< zOlMobI%J_B2JDE%%4;ln*;6NppeoN@(Qs$*W;h^L@x?iJXX4T3uiZ>J=+nNB8WHV7i4?F{6*7Qnz?HjG**G1Mp$8skdnw_Q7p{ovPVjQggjH}6C1v^MDSBL+XX+N(d~8cPIK?SB^mnW-ya?ui0HbV~@syN%P-Dvv9&s(Yhg zaZWl6ICq={zmI~tqtfB>&f{#~p9q*US`ghe9}}C#pie7LHR)h8Mt_U?kcoNG({W0< zW$MPiCrZCXiLi_)v38aYf36-EKE|94#;4ZX)aI{xNd#5VrxkhC$^i{4wnHBeZ{CeZ zz|{K7VC$hH%=mo->{FM3zwZe~`!R9b<`jGU*4+VJN_t2HRXr#SgG)ZE!2FYz@)<+D z@zDMTSf_zKrxr@ced4U#p4fXw4a`&BB!a4{ZHj;^G3()mn^v#x)v!gc9Zs0pKA3+! z9uD3OH$a668(IDG;ZU#Z1{mPGiJh7r2D6&4hV3)+1raMwt#9qx68nZu=N(!_!MR6U zA@c4*cCd3ecouAeZ#z~o`b#=p=@AjdY;KRKFJmMhlqjnb4xLgqKyi}xRD1t!i5vSl zW9aB`iJ&U_ggV{Ww(aqxIDua=pUvlm#X-Mb*#K$N+1$@j@Hr_H%)JsBeOj@8)vFm^ z4|B!-uac#7P-2N!Bn%z54cdR#+WC&&Hu$`zD;Cz9EfG{j(r?-#TLTZmCjUQ6hG5ELgwH2IE81g^zpw zHh4178T$zz^tY&r=9@TyhBwFOnGSf~W4V-anx-G2vtgHeA$)bP6+X6=T7vYmYV#=3BJHZ#j1O^5$xZpepx@Nsydh2o+R~NOf(Cr^Yo$KP8jX zNSMYbG}aa?!W%oI+tq5AWsxmK;gpagnWPJYu*-mpYN?Vd5mY75CL9Ob;>RYfG5PF9 zP9r4x?35PoIXik_jcs+%@y>cqEtH_SAbQdG;kc{+G1X?@I*FjF@wMiIcl9E;^H_`F z{ip8k5?I-S|}k$eZ8hm$NR(Qmdt&V!KsDDiS(C5d8`V?zgmg6d6ruxAC#ao z3lY733dB9n=c@VDwo3$6(Hzm~RuqiF5l1(ub-LzCDW?RT6^o~u?T>b!PpT6FWP+;X z63nmakDYo~RE8K#Wi)!Bahn{;*i9Ua>!6~N@Mkrn7D~_vP^TMeGYI`YR8l4^I4TiT zMdMO&BXn&KjGNqCIdCzUQ41yHSoGr;TRbsH+$7-DLL#V2j(7iV;)}K?YAbKWkMbsMH}BvTd}UdVYtI*w5(>e_m-Mr_WAjNYtO`spF>M&K04&pg5LO3ngf~5%=R{ zL||OYHEg4Aq(o2^eM0dK@9tpq8sMhp7BAq`LJ8V}b-HU&LAdf&j2iknK_aM1PI>6n zk?6GijJo(w3a1uI&|X`_)S;8`%JWUC_xMQ?K~)8l&2;s5^}V3x~wx695u)0?fOduRncfrL}Vo` z(4mqmmb*7qiux!a$8dL?9C7(@C#6onYiS*hwqV+0h(7UDH>{p%rUbsO%Bh7Cv^9&B z)ER^E>QDovaL+fXFQF>h^NFvp&rQLDy|Vd>=}kDbP=dB*apUcdFmzuO#%Jf4N(5EW zxv03^adHf1Z=J)enG>fLO3*qj?xK4Zi-%WqU~|{jlL)G!vq|yBeMU4|wtoVVJM1~N zP=eNJ@m9Y|9A*V9gDG9ANCZ{UxuJLy_bVJP1rApC-?HS?LJ3-@#rK@+qp+Q&q8=Xo ziBW>8=uA({Im-oO6Wg`wif6{0S|~y5w7Avkeh9v`T%kU_bca!bs^~0C+`+SIJg)e0 zMy=aT$Ek%9boL_75ZXN+|E#~DmUta!l%Og)Zxg*w&Mxe-n5cBy>BcGa2~1uOZ+|SWdgj6$a4>=R9dlsxM%oE=(op73|mfJiH{|ubM zBdR@z&wY}>FgoA8W{U@KY-tJvs`>85Q*MK$Sum_CZ76&U%cz0hcKTq&`w={4^Dc1x z77q`%CA0F*Sy26b3@pf5!rq(Y!HzB=&`H&9mK(6YF}_Stuy>Q8oX$*NH4lf9UFi^Q zb)Ky$7XwFnErJJbmjqG%b7SmqTEUln{W!Hy;(CWrIQ2RWcJ;a`h%VKw@Z)_2C%@?{ z5mc4&Ed~tyQ{j~76+s-fGs8{~yWnYq_WZBn#ZWpT3a*X0$?n^yLC}C`c;a=3nO$27 ze^ng|6HfgUMC(K|9J;3q9y{T}sf7~j0v3T9*wnavLbv2cqyelX~Q26G%awQLqq@zLlRP?q@cKTkEGN&{?m&>Q2gJ4ik#QB-~| zRIQu<*G(S@9|QX}!14>cF?*~`P}QrMbHH|T0<>(S5!IZmFruCZjvT>xf^HVf&k;9} zX5D8gFQ&kxV+-M6>MIttG7-fx0OX0`0Vv2fb*Fc27KT$Z;o5EtIgDmkcjH%z}-H8gaL~ z70!C!5eI}SQeK_Eo&e9Dr9iK4a=wW*GJh+)3>`7|n+K=)Ly7XHGvHw7`LOV$b~9iS@xC) zs*+n&=i~LTPjDA>F6qsenyi8ycf+8vSb?f>dIdOi35OOvPqX5ID`1;-5KIZxd{miJ zACK4Xg0EZna%!PO;licRXl(@Cu+my>#1J!lo$rlxLb^!=RsFh~4n|p#u-xmqAXcW- z!*&b0;Lfjoq^F|(4&!!VOFvvkmSY zi-hrSH?l>acfz8lW8g#TUO_BsS{(!L`C{UT(VSW+QPE`s>}V7YuUlzE!K&(5>839Z zGan%lRQ1Sm1LRwV!@5ZtF=>k_4!PF}vr3crlj?imYvb9_;%+~7V|5{HSvnJPeMhl% zSBqfp!nqI^+(-~nlj~uAole;MO){qzO5}_ccf@U&1NEY{@neo!7Yow8aD(q`$w$WV z0`PyC2r~i(NdCl{Ol)0TaLo(L?j>^iyObCimJf498{FPWTaAkIGRCd-x?^fWyhKoy zJVtpq)x@ipy5UwOj#CRIcD&yOhRO_>7Ok!6ADmYM%gyt_)CSQKK~;2o6!WO-_84)q z6a0^O<2Y#jc&rSA2OxaxUwz6PynLF89 zV2x6aL$}Q3)Iy012K%AO;kocQT&pE(t6SiRmmKRYkqN4z^-bKKUBv-M%xZ~Y&*j{u zxlq9spyI6I+9DyJ4oJX~}H8qHb-cTg*jks*$F_DOSGGI^0i zP*tb9C2-qqE#x}15I(*gal$|2Y%uBkB2F!oxUjVZ_FUKqSL*B$J_a;)#hO#BaoWtq z5?Xp;YxnlJuWAzgb5Uo8<- zbvJbvjLO~xH_BNH9}b&ZVY+i$9C>Xurxr@A^xg$SE%IUdbOwPY=)7D~_)!NmJ0kA}GNLI-@7uudYV>fN?=5bj?L z_fYduqr?JjJl*hH#5ztbl*m=rfv+7v=CMB_9mk3+umg9)$r&<1Rq{SEBL`bdEV9Q| zV-|AS1JE{4+lttGUeFZnEnIPM;e4t0p#*LJVmEG5Gwc)Qg5g{ysH)-O(>%+j?{>aYb#;n&b?5Xk;IQ3D}`x~Qo+7Mf%~0r z=OJir8r<$z;O_kJ5OncOge?oT-lzPo>e#fO54Ork=F~!o1rN@^bHgRjW~%0+*X7!H zGsYW-jZTpWs*;~-z3m>=H7F2EqayhYeh&r@odXZg2&%elc^n2` zn+gM$XruGCgh6oVeiXXD9LVWxv~%G%=yGlr)HcX>r}JI0pL+5}=-4j`jjj!rX2O){ zG3=9=za_#4>wJ;&)0ea1VQCazis>m4R7K~}V#n{zkML3#iI1X&b84YP?uPf!|7ap) zx7U2^dR9X{+&Ti^4jm~GRCUPb70isE4K)HZ;+E~^lJN=A*tv3FX?{*~;g*=I&%PfB z6a6ejUQMoXv1Ho!Xmn`Sl~W5Pe~UVsQ854iZ6C+AnQ85(uSbnvbOq2A52! zBla7ZI{ZWYYxytnyXR17a$H+y$o|?G3Jqe>cBi94p=IPSz&ui+PKHz_vv*d zf~qthj*t4lg#wMJ5Vf|zBTAaDDmgf02F}l&C! z*@uv^!xi$r8T0Y|9z)VJS4e$pEKcKWzQC}g7OgrNWBmQW_lQq4e`}%m?d$Nd83njW_UWB>xI*V`Rw7jY{XAW4!$K%>} zITArtO)s5?thEg8dHoW^Y=d*q*(e^bby>m^Mwh_cKt0?UT7zdAoPk%t9iWSA4K5R- z%F>~!8jo`d=QFBGb3F%_|Fnm7?fy$t3R?iH&c|cAI6;8^79~0_IR{qX+e4mx4UzKq z2L?lDlNq=uH(4U6isp#eVVc-UJv%rWm+#)i{$5oCBlj@4JE{hsZ7J>v@74+W*Z;)~ z5ATIL12~)=tNCz!(^b7$D;n?L%8@LTn6zsz%nIPJ=O4ni(Mt7NC-S8~AD=aDhi`{FN4JExg!-hec56=p@>gv*|cx~)c$wG;p@!O#Gr(W>> zm9{2x$fpKozUzbI(>}2ICzinQh@tTAm@)UuTLujZ21D!xV`*JWr@Qg~iu%?r5NG<` zX3iEHAYq0t?5kUYr!L+C8Rxn|6_KN|j|tb#sBvBsa9PF;MlF=^-LM6QAL<69{wa@T ztyR^=aWWQmxgrr%C8yln%>euK9E=OPRFIyRri1#{>00*sqL%g=jw2JwBp;M;Y_$er zE&IZZ?^^q~xwuTdZZ;b8-R?^SRnZ&~t5HqN(XE0H7L|Tw?BgtObqa^?GmUwZ_VXaz zXCic3{@>hP-`WJL9`wbcxPPM=c z=8d<_TX1TjguIgaGOID3Xyl2(X-*PBRq}dbX2LD?TXX>W*X=8<;;g=12#cJD0_@n! zoagU{a}UPDoh#aUd*sFHIOM!9mRmZE)Ab#?0!3Gl#LO$P94;swfM-*CNIob**RsU> zkE(aogxCPQyu?!?sER(JSbIHkO!fae5UY4OaB88%h^%}l>(>WDi?mg>mdDI+c(gaJ z{JRUMYkG9Gp03G>{Uw#^p?+aEbdGnGRtG6T%SN;)#SmF~KO9xwULvT9KB4HTKYUax zjUI+G8(DB_p@iJd4_-Q>E(s6B2_=>iK~-|f3l|iqpRA@}e8cLTS|~w#RGlul$!qnu z$zW`5Ig8U+oz8b?L@vH7+WSTI4<3MvjwWzwp#+`#h&?O=@2l6uTP*#vaEYKQInwva zxvyF@AC9i4r*dkcgj{!ny->YeF%Wkj8X^;acZYeVR*Uz zZ$=5KqGP)_LBKjiy&n~ZPeZOUYM}%j=SA)+6V%W8Nb#|0p+r!X95ZAttAll4d0}J! z6i#Qnbbe0DU+e_*uYsqhcSG1cTbeslg0B0D`FT$rj$GXzhdhmx2&$sxFW&Zb*5Ocl zKTNO;=F~z7y6!9HYN7Adb^-o4Z}v!upenf+-Sn&yK3mlXM=KMgK9LgiEvZg7ca9M* zKkbXRqbEuPRnfNtV#TXUOV!ON94)qw68ixD|G6c7cS~olV*hS?y?SI(7~cA8h%`&3 zg#3p0T3RhNb9N+lDCaE^R7GcDI-NmF2eq+%1P;@Ab84YPhrk=q9Y;gZ18oh!2;RWG zvC&x5%3dOGIcs0Fj5aOVU&PA!!1pMMp;932QQR@&@tc|-x2gvDa1MNNsI zDmt?e-xXDQ0F6JyU_(D+PA!x$dvggE^!9}sf3%+A&b+-)sa_oR`~F3mt5Fr5i)f>o zlX|^Q46X~zlHztc7olxaoGmi1j(VX_EVkIcM{0wVptB6IP95r?dQOVQqrIO<1Xa-< zLwp%lqo(SxHwJ$WcqR2El#tW$bANwz{fvM5%vENQNP#;=wXcuj(XyWv7Z^WES@zERz69AHgU$B z{*pM$Vz@O51?>xCW0MFcH4BN(MM?%#U@P2+oel5O7l?8kk#) zw>}=|?pRl{P-1&*AiRo6fvdAMBIs5VJQ~1oQ`ATvzcv~M`^7@yrkec8pI{ijaTfd) zQA6@A_Np0L;fP5J?#~}AStt=#bs9XKlL*UvwE6kBw&FdJS4Z45kV^zr(I*rmXI(RF zbm-aMQD6;nf@wskGx1G_gA-;6rp>rs0+wa_$0%}s&D zi^qcPpW1@38ext-uC>Rcox3C-?}o;MBEIhM+aUWBU*w){fTqtnV0qXqJqab&w~K)a zoy88Q{xyYHyX7D^0wG#}EEhCx!(I)b>IS{=8u`dhm{8UB163(KBp#K*bbX#TbV z{y5o^4_`bV=IaMT_yiN4S91|K{OJjSvrTz_vouHz_l3i6wA@W!-xdA+%rGmZg=C?` zlITTXf65pB+G;9@OF>?kwn^OFvoc8{sH%DM70~pqBRn*$FNm;{J@M|58fcvD%Bh7C zn;WFVGE;9@9If4WTU4PR4$L*gg<>BWC8(-;S_T-^b^@V*tU5t_iKLZad+|lpf@iJpYK_hk zK~-{@e+sq5m+jr~ZCQOO<+S(d9TWujS0zH-9a^9GxJPsRxn7TFC$!_#LJ8XEi&>F( z3%q5;@zcrj5Rl%N@-!Mv0 z)fn@M@To&G)cc@~A8V^NMMpDFymsd^qa)ej5rObHAq76IFy^&_17S&g3b-%Sh|+aU zG32xdK97CHsD%>e9*9*n?-b~ssSy_4t+DF_PYi8q!08A{{mG-+ZL!ZF%gYn@_ttT0 zp#=3Uc7>H#3k5eO5nw?xIi&CGG_+gUQW3;8_Qa7;E%Y-DB`x{TAsV5mXiMaV0D`;{--GHNx^; zIXwLOhx((2vqCMDNQae>n&SjvKQ-cNcd^^|yfL17RwVUTIc--!>TO48@w=YXSBh`k zBN*<=HO7704oVhEl=NHyi7y=?^qJNt7CdZ?C-2lo7vEPBK~?k##n&|x8)KB#Mw#&RmmxDaLyf%nl?xG%O29GMn@mHPpp2~ z6(28ZiVv5~k$N~v$YWHwBTdomv^DNAzAh0|MI!^TXS=;6el<78J3-~72!IkaM|3)O zi*h(-MqS*0&{`s>ibgo%?1XWb)sU)&n72tUMKYA2wNmTbH>fS$%VPsSUx}b9I?E6@ z-mZ#L^|minmvR2m{DTs-b%}ki{cDRas>;-HhV}|ADO!THw{M1+o>gJiG&51=Wj(uM zg-_qrp4*OcTKnj@+j86{$o*glmj{^(;>pvhs=?iCcBd#-v0G9AYl3^}T?aSdE$M;JE;NR|1uATKhW!I?rb24fX;Q)jol;FV{5~da^tpwjdwM$IA5Qyt+O2>rWk?I zjQYIDZ5!MUt_jV1Y2*2}rMJN6`)svOL73DtP}ObIt+4l|3G6Y}hiJmZ z`Taa_->8(d&uqY7-z*oC+PMNf&P@Dl^<5uBj1MZ(u2qVvLD!h8N0jKE`Ujrr>s6EHt+3zO^YN5ow zWrYy-CbK9=&^q0-S5?*i)$SC}+aMEEMe|McC0BLomDelSDITZLKC0=tJ@Da8RsH-e z|Lw0v8&*+E+9$Evc5w>r$tdxrav|hpUvR&luRYbl;F+ram^X`^86go=Mbjt7+RR$2 zXYx9|-C#K#lrS1p2+b;ubPp8eFVyHl)`4oY-R$%pkHX6xV7|L3Vr zR#X4V0cH~~6I4Y<37xLt%nIr&BOC5CHCj10JO{>qJf+WWY|byX&V`^%Rd3eYoYSWj zZ(j{6sLlhd`R&wbDIJs;VxJ3j!d3kXL5q_L-Kwe|Mp~9+p;R^k2UGJ*hr#oR|sTDdkwhDrWq0_*UrmxhgwXs*N}|j~l9os*mG;YDOs3 zLJ8$ZCTyDbOYdT>^`aj)MySDGg7_q(V2PkAIpub)M(V2!SDr8~N=i8;Dp}^h#aCzb z#W&M``QhXc<%Wp#eZIS}d=crNpT8cGCfKs9 zN2dJVtkq!W=)wk1*T%udu`l3S#v=aUW2izcl;8oI!6vjJ3(nOd%fMN;;nBG{d|b;g ziJ+>vmA1l%k0$JGH7$4jdv?GEmfyHj_;)@@tS5B%%aOeo>j@u3OuglnBXbck^}>Cd z!T66MbD6H??y%RcICjfdp8Ni{WT8YL6JHTLbY%BGYESifOAGvZ_Z@He*hHbfMOAY} zgxosHiS76&Lasey6t<{!hvz1>=aJ!?AZ&{vTRYU8?}^_Cb&geIwL3T9eGaUKJX>p4 z`IYumBMqjZ=a^3X%hRR&$HE*KUBO+ysB1&saGv^UzN~M5M}nExVJ2kn?95YstOsG1#^02>urNHqETuH z4(&IWmkx8_)N-e3CiGi;K>t_chLUgbjTzXd{0f7Vxgsr3x! zYL3QNrG*??W=I58(L5CEq94cMWUG_>{u4JTcPTMNd^r$*%a9!ysQIX!I~K>pT;L7B zQ6i{{mW{Y|Aw2{?UN{0%o37!>vvQyZu#)Xw4S8|&F8C4RRx+i%CI3=;H*}eiSyX?g zmRIx4V{lEkF|hnAmn@VBi^+vny{w8`fu$gNyo$ltvBOHfj(3&_s=6{Z7Zx}M9*Eng z5kLKdFl^^q^@p<)FR$)^4*ta@riP*n?q|ZT?BbG}mKNMazXb}8{wR6yLQ8qqDWmbb z#Xj|&IJ1UYC?Ut~RZa%tv{}d0wB^ncK~=vUH$$Ty<-sgR^U*P49M+$9Mnwk~PA!!1 z4cQ1E&KtrzQS(L2kQIz=D=tu5m19ymo{Y}~^+H}re@8h@I$h66q3CTgLtW8Z)GLx& zO5EzU6AZHFl+1Xhl}E#~Q?c*X!RknZWfDPEv}DD1sX38YqkJ>fFUCPCb4v6M66IgO zN+O-L@@V@u5+8Q1sg57UC4#DG`HR!6W_sg?obT%Hwr8bz6wNC-^A@{`cQ?ms>F?BE zCiN6LKcgynt`=&RaB^j5^_6V zoal{Drn<4C?X4t&s(QT=U+{#u>!FwCb1TKx@|7wcGZ4J1Xa;dTbwR7*bmDJ-}92l#nO0A33=pP zUS|-#O)ICwr8r9jRr!gx0JUm4v4Q`*1?WA#3~c?A`HLZ83XLX0I&6daGitKFVr_xO zE8^>#&sQO=(k#BRMYt4~P=ZE-VzqWu57j)lW|^@h1zr zE7U>>C1)i>ZgpZyDrvFL%X0x}v*)flJ*WexeK>9BXDh6NRf}6fk2zW-V>`G%=6v|1 z4tlhhQwt^Ns*#9f%m!j3a|7%d86H>f+!`PeR7F?3#oO1y2da_l zC3T!%4{0r&t}V(>75L?+dgH?hb@nZ9$p8IueQ1+6!;gRrMS4?l@c`s7jut_BE`HsU!Py_mJ+=ER_;; z>=OGj#GT<8p(*^tm%$Q2RkZICU$UlGL$92z-1?iBG@5*g zCHIK~ed}Q2&N7}?+fJbtO33rUka`B__o=QDi&hF7y9@&Bda!&?Q(p5+8q|#NWrON%^}ph`cPnm!I( z9;dLMQ^a=+gg&=;9BdT-e=7d3)BWAk8XKSSRDM2v&!~kG^l8Q2fP$zbhzg%&f~u%* zv8PB7_e9DU8GewSiV||lBSbnTiFAB1lhZ*}^a*vkr>(8gOb~`1Kc&2)1kGtNceb_0 z@O_?&?IM|=Dw@+`_h%1l{Bp`uDUJWYsD%#~SgZr()mWqeM`ZT!L-9t+D5E zPo+}-PmEe9(fr&vusNH;ZiHwh_@}8gt}gIYEXMqn2&$6vYK(7FJn_~;(dUSp*GV0v zb=U8FAhhh2!cK3~d`vuPjlN1pWl~Uc9@c*%^lh2U^2Kg5|93%9H71b_=w5?w+Bg}e zRZ3z*x@db1I{Vq6@>x;7#{FT`GAM2$d@)RB^>j6)UlMIFzZt%c@2I?}uahj4IBPZ$ zOgkhqn}7Bij4Iz0+YRwhMog7i8Ce`3@^2|49~ zYpgL)=czPEti&lnRa*v*hd8qo=J`)Mx7%xtL(Dyu@=eQgYM}(pX>l4!6>HqJ*;9G- zP9~^|mcQ7IE9$PdsJkKAKc&8e60}zmD-+Bb0}gpAKaPEo2&$qrM!Z)`vc~z7Je8V7 zKN+=9g4Q0f&vLOfb`SAX9)x|92&$56V!1Qz@y5hfN^Fq_pIwp+4PK9BK~L-OcP_~= zMjyz^uns?zEcRv18_U*L(Dvelg}P$f3${w=bWh1bi866wjP1`!Y^;q&*spJcA0D(* z7QLJ<5maTrIvT$9i)Ch8wOx9v&N|?;>5j^y4RtuRP@?+zD2NVZ)|~HQf|-jkbF>Lp_&X8pN(bJpJ_gB)aiixEn6vpsWL%T zv@VFR2MRd$&oWjrP8M^z3QX6K<$>4I%%`JChpy_XoRWKq^gxfP!)|n#G3xn zb82ocQzi9{qvCyNJ`BDzjKwvm!yoiagNV$2ETBT&|3orp?(I_)7X@;nvYkxwQ*iyTc!KJ zrxHO`z3R^qx3P_7Q&(#HETa=EVQfxoW!b?B3bjz8o%bBbSw5D9PSA+vrwlOI=odHl zbCgy;XbexIb8+sVzB;yCUrw2l)l!PvDIrJtZzm5>{VrYRM=p+1HuqZw9*w)QQ$Ol* z`o?VM{pDa&%airps>SVTp1sw)yb@l=b-Y3?l#o}Wu54eb=9Dkx#%aSOf~x2WlKB4P z(HixOO-03^UJr$~9QuT`ZHnC@8#k)g9m*@aYxzoTkP`H1#eRm}*VUo>43+CI+$4gk ziLg3wNOItcVAjHM#HY=N`-=75s62lC!aH87!(aw^nH zBB+Y?`QpT^SwB>hy*A1Yle*GqKnb}Grk$UHR&$H_puk~l?9E6BzPywD3;lCk`vO$yj5YEsm6#>A++Ey0w7Jm|HoW`^c5Q*UgC%?kThj6b`!GEm zD!gCGjIQhv#LM^1(6!7>@k$=XCrpnN-_9>#^&L+9d;bU1?*I6!etz!I(Mm!g1 zUn%37EACzYzq<#Rb_-XWxb-XLaxv>GZvFbRYaU!|e}J9d_eq>IWuD#{S3Rkwm^91g z)Iy0Rr{=+HwTOMGq1~c%V2>?sUSzAR+P_I6sLHL}JlIgMpDq8Yo${ZM%%dtc2RF*|>|o%wl{TeDcg@XWmX1KDGz9!n%5U#kb!QiFna} zCY-Fjn+2+V5-r{?>6;__<)CaRS<30}Qes2{apGzDJT~yXcDA~WV{<&0>!7R~yj&uv zs{EhXU{O%Wlq=f#?ei?#qh;G>%9q!P+^lI79J;fW@t+IXwA?6Y*CLZ$NT2YLf@yj7U+(dcUnoN>TGc~LG^BB+Yyp?L3nr3F@XcTu+a zNAT9q!eET=2G+dCCU)j!7~Gt@fz@2Jk=-~J4s{!BVBW#n%_mlWH^ZYV+AC#^VmP%> z!c7+rqt0(+RaUGO#QC-^IJkXFW#r~iiJ&T)BjW6xsW$l2&{e6HCFd0-mUoQ=W#~3m zR4-Ndh!c0Ew2pICJdY$xxl2_v-^BN|?ONfR>CTE#Xt0!Wnx+k@VbEyoD)#4?);``p zbV4?wwZd)<=hQ+8xeZBH&ikde)+oRVA#!7%<6l#Ac8I9a828~yl#90$4# zgNyHkPtL#}e&r7&ylNpmJ53Y*iG(iVMAwIpGlY-LooC>ZomJTS8}k^oP+~%CG<0y; z!s?`H_X2dA6OXm_9f#o++DimgSq4T!gYlc$vVIyd;!G^AX=SY5pR|&F+7u6|zL{*5 z;dExRI38ws?_g;Kp^VaEhmemrhyFEF)#MJ6g%Y!7N5lQin^~Li1;WR|^>O&3iGgbV z*i9m+N`9&y{sHJ2`cD1a-jB_Uo(-Ma?PgZP?b!6{vta4lo$M^@!Jc)V1?wv0u#va5 zJKS!aoPgIpoL8F__LVG@7~5?oM5JdiN6!F3jJ*_&0d5KEkPF)-f~shahRNU34d$@;{6L<9uUN9H@mhNGX+LRYQz7H6Hk8V{~s=ltoX}hD*0Bv1j zg{6LPT(G-_Qn^PXPA!z6{fbEW!GXA@rGc{hO$&*jD!J7jzuyxl6&foY&Utcbp#<$8 zb-J&whGXp|&-luv?h-*&X|hxf0bIN|_KEtHVQkNfS%;_1p~ zcDXY%;RVN48-Ae+WdQiBztO>E7g*d zHPc`uFJfc9Y4_JoDc=l}s&~RZixL>M(0WDdn~34wJD~42Cp;~_?xzG*6|WI@neHoM zndP*5Ml%+5!+@V=IA(HHPA!!9a%&#^zE{Y6DrooPWRB}D&e1c$Gf!Gc1Xca-o(}eZ zx9UDB9)xYTU*y>xb2*JB|97hq({3ZCF{3!oGR7aLTAbqJM(1*Bp~V00M`GIj#X4Q$ zx&W-(I)^WRvRxvm%1E58Z)jY^oStd1X#R)^n4yMp<0aXgS||}L?kw(WRLnN~b7yho zH^CTn{}KD$eXT@LRg$=w^iPj{tW~(?V{wdl<8EEAq-E`OoLVUHzuTwS|J`3Z=xZq2 zk1|y+XQoI5Rk@1$irB)vtoXcE9#KuFV2bGiwRhTVPA!yJEbg!EFl9d*bWo(5Qc!%B&us#E64kkT=qT|TY(_}Fhe9=u0<|ITNpt+m;NZ&);LYgYM#d;g$hmvyMQ_}^trmXFz911) zMeBmtvDGR7`#gG~ngx7d)ItfGBjU_~%@fec64mkvt)yB)RkTiv_1%V{Xg)PjHF)4E z)m=)^Jk;sD=7eLMrRs%YC3(d)HH+;hbMPIs9qwLwbAHTkQ6a$E|&TdO3XZ&1kEq+VfkmZGCvV892ZGkr!bjhpw)m_?Yo*JBjS@js@{ImjcnnVUbmj%s zW2LyA&J$?tE51d(5Q3v-tl+zy#F>C(Za@hdeTdk{FA^{7#W`U=#F>DEpei}u)xQeG zW9R2^E5ACNS|~xI50O_3W3f$QDa+bbULvSUjx77!h{WON?6~1~YfdecpwWleIWRH~ za~@4B=@(K4=)3J|^wK@Bi!z({vOIwc-<6xn$5k4K{hc#QL zv;Wi>5iIWvzOs{h|T<*dcdR6*p7`K z*m?HL48K+Ejx%;0l_D}4Ytdg4JK{@P;)K_F>@i%&sf7~q$l2Lf0rbJLxMx8X+{-NZbl}T~tveQKTQr4HJmF96;QnUmk)-Q)4 zI+Yb>Yb9uhV=!>gB7UT>fKv-4XgnuwK3O>o%cAyjuNr$Kf~vNpEf+Hum91Q*`50h1 z6wmYkzPHOBPA!z6xgd7RHX4GPtPb-DI+>uVW($|YM01s;E!TW}?b8+GXH-xIcgW+^ zLJ3+;sphw@A6W;p%c|lvu+2 z7LC@^b|X&tFPnzN$7-u@-mZ~a6eaZ6mc#Y<64rEq=EE~<3O4qdss;>ODiKsgV@9$2 zGi*Grt-D2SWHFCZ3nkVrUJm=Qn5iEEgpU_B{P9hPcWSxW6D5MGXp||wGVR_6Hzyn7 zMZf<4-kteRluC)Z1D3-xvtl-3@krrg^)WBZhXxqo+xz(Pwcs;{Y===%r6yyBu`B2iVW;z4UuVWI)(}V%9CWukbOEm&b}* zyJG6Fy_{MovGdw8=p=mSZ}bzy$l8r?!X^j&6e1H;_4Dv@$a5=Z?S>2%#L&l;(WF~% z{Bb6PQwt?%`oxV>jUK5#ZnVNPN9rr76EmQo`vG<^zMI~_d<6^{T+ELC?yg_#umYy~ z9AM_LorI6XjJIm2yD3_nZ=p~NC2Uu$fXt!;tiy}Wf~eU6RIAf1aN^qL5j4%wRP)il)h;!A_FHw-!QKijDO!S*7GE`v+pezqSQ9PsJrru8M2n{@pt-pyrvn{@ zk5;vc)PCoiVARF75BNCob;6}S3gtbyp8TWCk_G{IcfCW}`C_K~;QX2HX`d3tHalB8X3J&RB6{RppG$Q%)_E*uFOd z4ltFaKj@>S!^9Tf-)O2F*`rDXRTVj8KnGW3$K84gqFvpIc)e$!>Sef-(>{v!iC?@j zK%ZB_&TbhZh(czAW+3dR?6GT-+!aYM@XHC1{T!-k9`i zhZeP;sOPKJlnAQI&B=h9v*au%oDo~ewJ)^6g|LJ2vqMqV0#Tlc?Gq3U9ZpekAy#5>{H zE!FgDQEFQDbcMDY+RxLLrqdlAI8jw~iRzZ%X;K@c1npx)yz7*zHeGL^4%-(h5meRw zV%ft;nS25iJ&Su%7YHtZM9neD`JYpp*T2R88 z_wmxlIIM&kVmx0|%Ucl3e>X$>EvEVk_dOMAp@bX(JjpS^&_=<_uAcx-5u9!*R_6U)cd_>KEFSFJbXOP>&foUdv|u`?3{Ux%QW=} zY?N!hZ=ynQ6@R*@#{GFe{m1^vB6q=4QTJw?W)`JEg0Y*C&kgxo)L>X*7^pwUUM}+7 zj|(2*1fM4w3|2#%=nr1j!3mqv1)neRH!`1*84Ty*Tk4}@3SpnVN0gZtC-|}HJI<;e zdb{n1g+-g=3c*!;W@#`)RqCZDHPpqre#ezLCnwbF$jh#*zp^QbpPN<2q46uUHvu{D z<)W=JTB???LUWpt1B0?`>G?R-*@C>CEihx80eOUvmiV}fb`W@8Rj+%iG1mWbPH=*& z{y59QUv^e>jFo-O^oG#|u=ZO^<*fMZg&)sgm~f<$Uhc>d@j|YZVIw_G@SceFddafZ zCpGU>3Erd9dvGA?_n#$*^p%wrf~)v%Lu-nb zw$`iJloq=x*FqlQ1b^nKPo%ZZKfR5jNVhTy!BzYzFc|vu@1k!NYmDY;X2>I);C+|D z(0uJc-O6S;9O?K`d7`+AKP%*+FmRae*!^hk*FsN}tN|x@A562mTjTZ4vz;~PM>z_? zRXl@0&RK=V>rda6Fu4raDR_hveC$hm%GN2T-&x-U8-%=vBd3>WUWQbVGK;|Q4>Cs8)@?cF))65 zbvRD`wZ&IO!z%ykM6?=INpGFm3iW)^;=$r$+Q-Oc@Mb}#n{&nqZQ`dT;1-za){)!< zr?#98cJn0BcvDR7Yr7x}E!sv%hb$Keh7JQe|8ixYGkX;De{T-8$=}_}YZRCqr6XI& z-ATE=SwVQ{imTueN&id8|4(^463+FMMExp#b9a}gUB9dx{y*Yhl_W}a^?@0Oq=#GA z(^9Su<$GPT)WgY0@elZaJ#kmt+qFHHhdwkzQK22Y7?|EV3uFD)$I}= zw4w%od>J%A@CYZ=W0<8bG38r19^+3=5~=QYwAeAxu<+Clx6?`Yv?r-i&?a|>Tg~w| zv@umDgY`N2oA0?CVJdZQB3_`G7mskF5Ioj?R)_?rWO*G%(-u?MoKYAt#ZSy8-^Zbo ze8D}dI=CLZp_wg@fqf5mxbb6C#w$L*zMxoFTxuCEk{+DY9+z1H&B=}OQ_6Ym%BcmA z?v&}4LSBvi<_1IXDtT5fd;D#(FVY9k)Se}HgcCV-d0NuvdC<11bdXFPbH=pc_F(*! z>#q=8#m|;}m&Tkl9cnuSU#8Abu7eXx{I6+S4$gsMpX8NSUXf$UyEPnF>k5Op7pvmcTybqnh&63 zY|d?@$5*q%k*`&Pt5SOFTF|k0nCaG@h@3r*^^fHmVp81&f=99%>Drc%1lY3^|L3gI zHrne2i`(MRF$!q`W(Gan>&34MBb3c zNN{%21MXR2$j60(M>vs0{?4`BRzUAx{?0S}opodHx_EMZtU_?rACF}C?Y(^7teL)O zWF5?ZagpE=PW*9khTs0qTT3_7Czq*%g#wo-1Xn#YW@%1K*1@|@(zCecC@1}1YF!+Y zzEtoCC*E$`t+_NxgKr0<_ws5Q@7^-j$ALHE6oRY1*lf`{!FITOTpr{3#76pt$2RD; zDnW47&~jU~?(P{7{C91mN_-Eu)q}>`;dj3z!6TeVpSM{nn7$cuKFYId)!JGQYwCbg z(vuZ}tNu71Lv_1dbXJ9aTI$OlIAQa|6@sh&_%MTXXjX|o-peSxmwAK}e;k%U@m@yh zz03)&`s1n$8@Tr}O7CSJ;eJ!_y!TAZ{3c*!9b2GIG1;b%{?Vdy& zOe~{cOK*?8p81J1_l?^9OF_)0H)|#8ghGX&NU*H5U2D~D3LMXs?p%x36EUhi zHry8|c!U#yH@9dL8_tCB>%xdwvaystJJSmtEoLYLSMf8XK5sKH z{0`0Q+bpnaDX)Cg5;Ohj!8RzK%~lAmQm?$qnv%Nhi;h@x%ShqjzfPOF-yf>$tDxn) zbz0PMf9M#p3J!hD&|IGlgUYl9%V2o@t*~Au*BiYuMhG6^1aA@g#*#r!m}R|i?Ayu8 zm2(1SY|uQa1VY`UL^{UUg=O@P@7v@3;AslMRs46N-4HL8(jTAgh&6il7whh=(8d(@ zh2dLrVffaSntuUb*r)ILpX)GRTS~ujr6U$TFhIEuPMoZgs+DWx3-3qED=%8NlwS01 zM~v?`R3W&Ew;}CSJgBN3yv+k&_3#uAOD)l=#rT8AyUTFJd8y`f%nwTDU4pN@;W^I-b2kI=14sMe_YTxhyd zy3xLgv(#&DX@QqaD0qYu&&;Q2=UTNx7}J`S@#YK!BxX)6>EWi=0Xh* zdF9udSn9e>3taxBgWwTPqFJwFi(_ghJ#b4^QqZ}k=!vAB~$aMiMbd1&4EcM4T-0??nBZc6q&o{|%6Mj=_ny#}{ffHw41AXY$^Ct`$ouO5AUjP#ZT%uznSFzNa=4*lZ=5C|@`!5Q?RqE~+t!r88tG2r1`T0(QKSlgmQJ<(<8!hw$B|R|1xxU~LPN+}R zJ9_SSO5AX;l)a&?E@|0<^>u4;O zdKGSxANAG`ouSir(b=;R@O#IqIbsQ8`k z-7sr6Q>nv&n0b8@aMi?|ENxZ-z|3L)OZ@x@CSTeg{#9TG@V~{09|>97@N|HoM3ei_ z%T}h2-2-vwsm%((RU6mr){4dp*g`Jn)Klm6(dtzU#qb@G%GL5#s1kcui`&}_TK#I> z*h2Q&qE{ifE-(#vgcFs1)@5L_kyUpt~1B<9Ft+;_^aUHUs1TTl85!#h9I9$`0V*JCM2)wAZF z(7E9*;K!rc#MZL8_K6_~?=C43PRRd1U*!&4H^{ciSX3-``CTF|nEpTFUzH^OyN*`Z zHfiV12Vlh+odnOf@mwFz&(U*!%S}s43BvqaoR!QSC*(2y%W|e4o2{)655fmUnkocW z`NzD_j(H4#UG_3BYToZdZl9$yaL4yLf=4(Z|Np3QFDT?JXDoM5bk^3*n1PS))%yR4 ze^tEIY5(@`yK{d!2V=j7W`alf-_^0eN~yb@v9x-IB;`7-2e= zISteAl@L6_3EpGS-F|DKX~^WMm_MYTLU7e%^KDvCR6BV6Q;y+wt({={67Po}2b={S z;e^_k6!;clN`5(=-Z&R^ZiF_C6oGl-Aw1cSPsPeU*6>pXsTyiS z^x6A*;)5CO1&?r|>5z1-zfT`{mn_?AXoV7bu8lVi-Q7kZxaxn#SIs_|+M4-buUs2t zw8RPZ9rgE}!g{2s2Tr(OTOqiLzeVZ$IXU*kKJSC?KNe6%eVkC=Q4e~Q*7qfL#Zn*N zDx(ap;$LeFh7w!vnr>SUz(?d8&cCI+sc}R*b$J5RUNi*wJxye^%gMh2@oWou z{T{EVqeE-FzAsA2A#;LXAAOY}FYMT9p7?^iu=(HODxTw@ebvYdyIN9r{7GKeJi-aJ zt(vqk=q2oX;E0-&6@shO%tZa*d#1ET1F`XneoCH!6THWux}u6NOyO^RutZQVh2ScF z=Nk-{%AYcwd^H>wJpd(ZzzN=C7z~>C71P0tq1Yj-nL=6{hU^OZfiJK?7A{Cpw(3K zcWZAdk$cPcPfCOn&B<@OjCV(9`dz-G_T5d^Vt>xSs1`*8AF*&1f1}b$*)^ZEa`}UB z&8iy8o0Aj%x9 zBLi`gO>w~quHttL&F;nyFm2oKi!pk2!6Ted-ychwwlQtk<%fpq^%R1u_#H!j6U%3t zY(7mvi+SY#!R}E`@b?vs^uLWYwI4DK-Riq51XuAphVt$66HL2CPr#O2y9plQ1b>Ut zcZ1;@O_R5e!Btj66oRYNo}p>)yQcM9`eXVtU*#(@C;0n{o{xG3^nKU8(YMlUh2Sdw z&6`%eF1IhUeS+rs*++4>@*sWC2s@yPGdS0P>I$gh?9Hxa&@na} z^0^F<)n|;z=xL5kP3`qsIfrHS+5bg2K~*V`FFWf`<-Ny%%6OtyN8R#$wnA_fKU>;E z=$<{^oLm;8CDq7tJ z|5a2~@$jif zh1;e6W3a{O&Z5jW^{l9t40`R#`L&k;ze8#NtAi6TuJ9|Ew_m+?Iq{<0BB)g?2YkQm zpzDY$Hw7)P_0)QgO;hf6uAoHh2`x?V2q&mA4DL6{{{9S%a~n*2SWTa( zxhe!#QAGq4DW3DIGSpz0(YQ4>`(9no%yJey!U_I#(KkqsmUy3X)fVj?6oRW_TP%lh zMRFjig{%yF(aQ+~cG&9$np74%!U_J&lM8r#FVx1F;ni;NAh=<_tLsSd!Rsx zIk4Kj2oXc+JEy~dKA8VYJ{VJO8$`7YhiP>k;p6tLkZ2wbCmu8foV*cs!c54BmLto_ zJv(Yn0ik#_tqyFhlLoez1L4qA+83#N3Rv{_hjzDDLYsUmVN4T$C|f?2h`^0j_;#TS zitE85!`m0mKUxjrizY&!8om%dcoprclmh(vsCwDe0WHTm;Ou(#V*9c%aG(`izMXFY z)R+Y}rYJ~$a0_-Fn+ZOPW5D^^4LU}EsD}%?Ho~Zh>0&p15q&p)A@sG%Hp-_|KCN<> zJlQMAKHzuHFm+KSEVKaec+C}JY~xJ0Qzsn!<~ad5u)<#@!XcqmV;E$X1-0}T=sDrJ5e^2nMf5p!U_9=d*St)XsFgz66H70USuzA@IwDp3c*!t%=g0D5;5epSeS^# z=bGXI$9g#FYOJ_wvjwV0guo&DVNkyJ78tNK1im~R0;!>!VaAzIC|PV65&xWNiZyKN zVQ|?+f=4*9^ZFJT+aMI8tp^e@<5hKhdCv|14pj-R;w?h%L-U&8h6?p@<@q?JtvF%% zArl%-n+;b|oah)wJey$1+j{soF+m}?inklp(eH4?qg$-;^pyq5mGf)*Fnt3!+6RDN zktjOGwK8?_!FCr+@`w~X!inyV>mlu10Dxx<5x&M|_@;*ydgYH+2(J2ha6Oc{?hm%Z zBw-%xjMIJVqeXXr(ce22dfuK6pS)H>vzw_f>gjZ-n2-wX$E8B+)4tFlNZ##x_qpJ; z)mGU3b&%i@PPkoK1;hTC4((!B5aGVx3CHbgfN^^L_mRM(B!-ybf|QYh)Lj# z&v)5kZQC9S!BzL#EQ96f2Q{4}@m9CPvDKWh;;ZIja(pb58yN^>#tJd_Vj;IcAS|^w z1DrNcH|mJJbM5fe+Kz%pIN`TrDa4QSgF9Ca(J`J5azU_ffPH`TQV6b6&+52`16ID> z1iuw_5wU~kf=$OzC}w^Qbf1OvYzM*BQ|E!7Ej_i)%`k78Ev8&(uUrQwd~;*riA5l+ z^gTmoWm(t>Z&q)Fi~eb&5M0Hti5y(UIAZ%Ajq!dEh=nzyq3+=@IHKQzJ>TYlcS0z< zFMl2Q*%}NN;+*i>KX!P08Y!T=PmLxQf3^=#7)r1h?FGz_cv&jl;?KZF9r~SEJw&PL$VY!qxZ~h<+^JQCH~i?>^K7qn|exJi>{j55aIa zZXOulTqa^+mqz%hnG=?4*+L<>>VOsu$K&V0)Sg#}$a`pu1)DU(we{Kv9^ph<`9PSp zAQqZhoF&5R?C8+z0zKM7v?mICw&Ph2W~!c>(a_ zT`YuEllSgN+K1KO!XA6B_7Z&bQt_rQWW8JlXCw9lr|GL@uLfwh#s%$ty9yrRMCsuH zuxHyMs4wJMIe)Un`&*o`U%Zz>aFu#ix3@OH$UaWEu9v^yW06^3ro)N$sZgck>i-#+ zJUwEAPxm>ZXg^gMk#Qnn1oi9hlEB$)8=ckV4vskKU_*Sqe6T`r6>kxPq4*nX{9)^g zs{=X>-7# z(=J*G`i|ym-bZ_4-Et-L8{zq(dEqcfKe`DXcj^Tx7!Dl|ZiUWY9Uyc-IC$D@gQu=d z>8!pr?|{9n%ys-~P$HaI(CBeE7jCp9=B8ouHt7)@4;5hFeB1I zuTiA5avhwQIXD`ogk(a8Qu6oMeY_zK-D=c3&MT!5T*X^~su~NA$C*!c(}QI#!6JDk zG@7#s;@k$qj)^nDebq*=**QpQ5nAIFItd?APBF%~ULkn94P8MyXJ>Dtv8ZgTyhD>P zutSEa?YI`o-{r?U9vA}l?Ki;e3sZ^Ex03t!4tLY>YRiB}I58|C2+R(zCHHLEUrkE! zM{~1Dri!oa6@sf?H=Y5VORj^6aCLm6c{nbA1ZpS zgol%pfzwoJaX1(!uKA&jDcMAcaH4Bm5UhBU2C>cLSv}Yvh$9Ahnq2SMD+E`mXVryP zKMbtqCfvtWgohRV!MsL1bT7OM?!NPbD-rSFc{CHI9rA;%Y4MQfDBlKo9y72~aT_uA zS_LJ-iSMQTp^zy7MlIP&M90lRSR}oPXgFemLU0vt5gPT)2*vMN?cuSlrP5ZM*bwRu zgU_ZwbBh!@MwJtxcz5T!oY;1C6oRXGyOC${7e5@85hNy@F;lLbUv0j8f#BYHF+44J zl#XHcY65<`zDv}6-UE1q6A4-%JfXQl`ST}<$gVUVa|iAd4Ym|j2(F3{LC}3>EL=^M z#K*Ct@bjxY;TK#Cc!U!T3Isz1+Bg2C!v!L49v+B3exJm*+HHVGIPoPtglY%p!JgG} z)YrD>0G#0dT@;Kjpb%X3wO%NUelZu8kCnt8YY!a$z!KZEH2|%n2V*q3)P>xF>pf>d z&zL9}9DECUx1I&-S44sJnp;FX3i8CKS=I6WiJwLu;lxrA2GeTAKqpT*dfn*U9;?P$ zAeL}d{uWmiED{DkdQ!e*z9eSV@Wu;MD&YBQ2H+7+lw zHgGm71XuA^pbTVeFRXg47{(>$10Laod6}8e{Kp&^+eNO9PB80>rSl45%RH6fDz$a* zeXEZrYq!9KXTBRJgwu1}Zx-a6bqf|gj)2nIYzSO(8^nhQIJs^%L|wd1$1vJ7!h6%) zFn^QpMjqird%p-ki*WdPQxc;;yJP9Q)_9|V`U~>krrx*N5S9=DEAk}Kss>;>?dsTg zaWmi%P9(jY4gJ?gkZXk`2HkYVH(wnv-sZcJ6I`X9Rpb;$yyNDC5&N8gM>sLyWjKhH z;b8bRS6ipqWBN503^}F}T*X_2YJS!h$D^ft;h^n5jrD%cfzYxuVPN~Kur+TEoU)z? zx00{Iu+np(&tIXi`IP(xYmF(00dM=FZL|S6!ByE)=fmR}!BBYAMItU$J1$Cjj76Jw zg&`zmAxwJ|1dp$s2KRii5Z5aRGE1F-(}u<1Y!wKDG})KD-jXZEQ$9Q)s+$tw#2Z6A z9KGoW&aN_FQo=9Vn07D}-+i=Ha-pMcu7EoY{Na1Ts{hH0-n|tD-t9y2lz&Yn!U+rN zr7i0E!|gEHQwR5NE>5-&!uU^P6@shOv$}r6Roq${gmb2s2Oi->sc~^|tCl}#z2tSw zsu&^siuhs84iyxFtJJn?lH+4KmK%U6N9|#LVj47{9&=A3)!2?)3tM^w!S}pq@awPv zb_9gL{8RFMUah9ll>I&s53OCQL^u)Yy$P-c%!HR^t46)>%7*yjKyf9)iR73}sNW|VMm;V`L?rD}Q0KNgdWN-C2(IE;b*iZ@UPm9= zqzx9&E2!k#Iq}qb8zfE&hwgce=@_XsE9+$gJK;ownxW?^o~@@0WUEUeq+oB%n7T#C zub=X(o7|0?=d9ISc*%@X_|L*tSmJHE;1N!!dFsbB|G2Wl4jcWwK_R$`=izBqv^EJA zWKG6*rP2id9wEO!$?rvSr)>4x#OQF7vFEXAXgPkF;1Nz-N!krh8q6U-w<6S53+gzE z+*^~e&fNJ5!Bu_Yc7Vl{aL5=g^VA=b3X54&rsI0r@tsFF5%_95EKdoCfej=v<6Jk9 zH-0MG9UiL?T-A752Aml=6KbrH_ih`bNxWM<5_6w+7jb>pL7PuB2B{PSJnO6yEFW{LL`N8qfdfeOJ@{Q79UXwY*pJ+e0zHJ_(k2Pf380NuOn z6sK&4VRnnf3c*$UcOp-ul+$90eSZv_mZbb1oZ$Bu?GzHTL)5QH73=@3RS2%)U$$sX z(aMv;rBq-1kh(?r=EVvA6wr)*acKGG zc3&_2xZYau2q!Aei-(%M{9yMO*^9=PsEXr)+M&HiV};-PacUO~52>PL zojK8P)l!(_>rW%U19Xh1*K6SXh}Kx)QyqoiDmCl8vvL*8y3`(R8)NYJz{A zK`SiWq80{d)`CYk!E=BH1623GyQ6F1&??0hf~yYo2!Yk3=E2Ala)fLj3)tv%J^WOt zir^7W@Qf#|L(WD#7i^8~3*=V_uA200CKUIjcS)uk@4^dL-09d5N0%!nc!U!?*Gs!* z2f0yB#uis!`v#ogs)w|Lht0Mq*nCWm+tYeD;fJyIXg1bD@CYZ=%=VxyPB{IOJ*BHl zC-xHbubvUt_pEx&sDUHpQI>%>|Eef@jj{+eBPb9D2Md{j4o;}wwinzPgl7ld6WMeq=_u%VGc(#pp9xl@tzs@@;+HTq+xQegXQHc+Qdt;?0 zmqg8wElTE&6MV%DRS8vWjc3l3L=Re>!2cFk@vI@8)l5HZ5Lw#Peq29ssm>f2c6S$K zcPhNL9O&6hZ`N*~S*ykgHOu)ftq?}k>8l_1siF{E#aFt~TW!uT?BMj!lwKi9 z$pZ3RsG94m9Ml)hatr9y`=kSpaDty9?SQ$gFYfowuX|6utq@$b>3$5XvEK#ZPvp3L zU4kc`9%ZiQZOJEigcH0C4F)IMju=q7g8sqRMj^P0ul=Ff-JqSOVeKYjUI%yJ^9(-! zP}j-$zD_m8*Pen^YOPaN&~T#es%@}8A{^d?$(;V{m>Z_68%Chl+(?DsDs?vDQ2U|j z$MT`L;M5gmHo=KQ^>@M5yck%}M)q)j4Jxazb?S<>24^Y+SE;k2(L?j=PhR!JC;i=p zT*oEXUCFgva=n#oBk2soX_|Qr>#cvBRutEauKa72q`ZfuCla59$(5Ay{*|jKX-(0i z)_Ro^b+Er*pI>V%|BY}$J*(j3uKF$8Mp&@kd4=GrF>AA+Wi+jvys?drk!e?5f4`9l1&?szL96X>JS`mh+>rO~+w9e*=T|3U zRE3HP!BxB!Xa}0F@ur4OlhD=GLGTDCg0JoZQ>8iJxLMx2=9f>IPT_DYu)eKAa23Bp zsnVO)k^NQG0oyiq5`49QofZL=kIjbS-gkhHQE2V?83%-+4%p&_wcrs>+%QB!ZtQGG zsV>(VY%1%3n_?aDf}x~BaFsgtac|fdAC-5(U1vW7k8r~3a}>arFo+73qrN>cHb~nd z;QYH;3c*!t9#EfLW)}R_M-l@|TVh5j58R81z$2XC`7+u~_f#eP5Yq`W6WtVotH#uu z0}HhuI1q;l%dh(NN)D7@SX&S8nXs822}&bzWafDg;;YR-n3~7Y#7v zsu3Srd$eg`mLoxaFv?nta<8=SX+4nPJUYic!U!?`$>BnR&>O=j~ZjDQ**&v zl&==ztw3v74mZL0LQOF*#ZK@DC)D}i0I)@mE6p)tbXkSqD&7jz!{u1wob*=Mw0l9p zBb?y#Px2V)Sr*H^@kYy0$AA-D#an^q22+Zl--=!sf8e5$1?B{w71R2XANK?9hbjlMiqGO3*4vwK?4aAb`r0Fx2Jjw=LLscUQP+h&R%N#pTa z{d|H)IKi_Nbc|6;M2{s?P%lziA-IZXspwnLjRzvF`yjOYY*g}BoZu@DX`OzB{Aj;><{4=6O3D46+n_t`2ko9K4xWWgZG&;PXP!cE6@OFHI+@en z!pGAeU;R^9@CYZ=-{a89x*{Yn0B^ppsSsSn-_%q^7uifS$nnF{3!MayaDwL7Oli(3f@Ej@ai}UK3cGV{Ux0<>r1XuBQJ7qb? zhil7y{V`(sc)=r_;F(*4;qNj5rZ3wk(I|YHLU5HjW>~zmgDL0IB<$%mPZ{rWf@h$q zx~8o&?%G`+gG>4=>)ZMKTwR4UqHHI;omi5pEru&=ia5bD2(&lV%`P~8Phk|prz-?k z@zp}qQ$Oj8M{`~XtIE@qwNac<=bUrhdgAkt58_e_%CNANSzN_e3sDYv)*y@=d0K23 z7A1Iu6MT+Kbw$qo(82q|}-DDqaOc>z0D1 z;l6?uO$$4ROBbd8tGnR@&v8&@`}#Qa&WtrZSRJMiT*a$kXovA{=2#})3wQ1?C?hid z)tZk6Y5vj98b@_%iEBDFQ$~H9P`}saW!qwpCq~?JElwf0ijQh3!}7`=mzQwCVh(Z2 z=#>-v`>?@ax2GvSyXA;)hV4-ZuHtz{gW>E}XFS%^0VkQqDH%vk@UPaid(tRZbSuyp zZ8~Qu1XuA4EA3T04Y0d~Ew+e{2Oi-B|N2hVHAfIneXfT=3$qo1t9ag*b_(%tjmiJi zM)Qe@N=BFyd@TjlT0U-rDQjxs>X{~m;3}T+raj{Kb-*Qqs$l>06yOm~@U;}Q*5GL; zv`;s~BBhQg1XuCQJ$)IS)*CODDuM+3 z(bMaq(8&3RM>xUP{!s4|KN=sIj*5!|z9|G(@eC{Z#EqGTHAgNGtBza&9^r(#Hmal5 zRJ`f6P>g9=M#p#dWVSIQ7VO!G9_K3(C51Ss(t}rE=?r1!C)s zVK{kPrr;4ys9&n3L*>|n{wQ54Il)!3o?6yF|8}XA4wd9oiPEK#M>wHg$EIlq#EFvq zFz#ojLU7f=Y9?@)w;cSJNta5`bp@%0r5y$~-7a{96TIDMe!ieCem-W8C-rodV84N^ zDwoyezg;Sy7VN1#D?bJAjZ9No_sz^)c%4TrI)A8Y7Zg_ zL`5~Kp+6|o8pk(uRWNT%i!dg|Xz;cRL$Y^&6mjxl(O6@J*;0CT797dJd~ zc-1csR;_Gr-07}Et+8=%qiTDjqmv0veT@UB)zTqPKWx;W&-y5KFMKPUM`lCIuT(<_ zUPi-^Y>1@0#ARm({zW!d20A_2^* zNMcckN_yW`8^!0>Mup(255>qm@<%-E`$xJvhQ$`ucOOU=me)LyM>tXG#9r_jmM(%62ReR@~lF)nL54bE%IB8Q3$TuGm891J(A#c zKNliWeV3c|uRu}Z<3!{UPTc6S7hFP2TERdwtA~u8oCbPK)L!^sq>0y7H((d%YSu>U? z1XuCCOMZ7QqK8jvi({W{5%#t+$x z`YgU_D)YWIKAHVSaDuCND^MN%w~wZduFkk)TYlsbPN+TgV63CNQnuDjzbH7tRlF4_ z19`?p-!;Ajo?due>DxKM-wc!kxYk9__wtE|ESseeT&4EyD~dJJ6Ve`vyccFl-_GAY zyw|4hgAJ?cAwNrE*9Ya1M>wIJq2bKMlcp-xb+PxGdJ4f+BVXk}-ShFV`b|6fJ>Ep^ zHl0p)z|sY4B9Cx_w=`v)mpGeF^l`=1r8Ww|Rn=CJpEtcf?v9ej=xc86`ksi08iq^g4LRjj68y8EnekEe9N4%x0VMhN6yk2{gNR?b2QF6 zuop@lN`d#^8W}rv+Y9-Jr@**QvKP(#SwqCUj1kj2PsKnBsu6Tffo%sIjQk8$qHEbl zkmj&cOnNdNd4v=EY-x2u(jalH^I5S4hAISC@w26w*XLBQ(hH&1w~ulioKUa)FSBKE zrX{V;eAhuCxavTkT$o-s5h|w25x~dd0b+E=KB#wlEoOviaNHsuI*KkvK6_EeS1Y~Z zMXf@#FX!-6f=4*P=Owge`)3^t>DC0#uTK|zM9;@_e9mAn*!vX5YF_U6#PPT?H{b+6 zHdRO`92K(yx}$5$QwqUVeC|Vgh3(%bwiW7$4+or5<~W>CuOo4R8J^85j*e@pp@n@m zWLvI;ZF_8$5$jxXI4{zCB`jDg-G?spsDqpPRl=BeKLn5PH?lfrm`zV?m-xz9p~V@6 z;Hsu++3+@eCA4l;hmLXXb6uS2WP_In?-zVj%tsvjnrK9}vm_3`)dU-by;OcdPVmu( z!QkMtTg*Dp5*;4W)w9tySMj@t_F*}lDq^O(;pm;_$RnKKGXR4jsG?Eiy>Y?aYi$&Q ztJHfp`TYv}E!q?*fswT90*`Ql z-wU)8bkHr)V9hJx*`|#`a24-~Xa#n`lBOZ8$6>wJS;}aM&rH~ejt_Xj8VFH2*Fcc}G#V~_V&xF`fy@wXjSvd-V5?QUs> zt_@l$Z#7Qv{?TCYpBQP{Y*rK7e=#ZqSMj$tt>ma0XPR@hEOw~cMtM7Pg1@h*%JgoY z>Dj)YV!vlgh2Sbar=r%4j5j3(-4ILr^hF-w1b_P&3`IIcnr0u_D*Wz@PzbK#GbHMF zv*+gaZ#q|mdix@eaDu-dsb?780H8dGI)j1~f~)wPio6Fp<%sSjbz#%GFAff03pPJ? z{CW%j9FhU@pL`<^vEK~xpX^;}ugOc~7xu#fFDI&fBJT%NCv1k#lQ#e96Z^jP7sniY zMdihlkpJC9o*7WPT?Q=K>|hL=z7^Wu*Z^~D$ob$`de093=Z!c*>)iR1%Fjf7Y8Q6B zE}RRU6;Eq-Mjqh=Kent5-y#M+PZG~}4OIxP;$sP_=Uf^gMx6{0WvfqA#tfWLufu*y zkf?WPfT)-^Ss}QJ|2C9w5AhM{nO;KMH%%G)aN-SBc(=;f0B3AuTg~!x75R@^iSIrA z6@shO-+V>b6-cdk6pH!;Bad(*rs)oNo|5)wwq3bZML1OVr*Xs1P=(+sb$m)bE5Q#jnL)sW@zRw&no;| zl*pViPi#mWrx0Ale}DQuSSmtz-HZ^YKaW@Lc1~z?*B7O`-hF=IQ%fVRFIP?9JSR!nos#c6`6?w2)=@UK?vKv&3od=zP+YxV#iEKnExURrd4(}?ku%}s;TzE=U|ytyWz7@6q!*;AA8t{VejLi zeaUR-P{-Yv{52jf7SD#XeD20HOn}vt=?tqTXLmiitQ32Pl+d$BwnZM{MDv=7u>H(l z7?$it#Qcg`Vr-!^rj)2&3c*!-wkN`oQ`vC1ypf2KzDq^5x(7_L?*<`{aKdSGB8=I- z7an|-Im`A_(nZ0f@g|%4V-$j`n%_=>1AVh$&wQD)yt8?_xL;tA>F%!a$RnKS)HVrj zPS^{V^2=k4o<2l0Js4=3pFUY3xQe$rjl!>IiL(Z4{qiDPrFD6`_4bN`4@0w|Vm?ng zMuCcV#m>_W^*5!fAdhe&!Zi-wpU8&GV`OH#_x)?)NYS>sUFDa86I`X=T@F^gvmxk1 z2O7mm zP|Qp3J@l$VaFu#i#m`z`cUL={)8xDe-I@#yj^)Dh+x3hW*Cj*A)45QjSbd|mDj9}0 z&4s(>^4mm!!2+B7ZHEP0ofka9iRV`mpxzJ@49;*OB6Lq}oIJQPMqB()2(Icv-$6b` zYtX5*yc46g)y66(>!ZWA(}G7haf31+Ivr#7c6p3br|fXe?9%8^?Sn#a)&4K>KnB`S zabIg9_SUjSU)nXI^rK^fM>tW1s{0?c&|!Wx=??7F&IxaHD30F`KUD~>YVkb|+B%xx z(jxhL%*<|pHO5$B)rI>7k8r{?C=Nci)?sXrJVpeqlc~P2FuI<xUXKJ*LLp!fOyGg_xB)0JM7pCRutXdmIA zL!xR+9lkdvUkldDaDpG3#_bjEiM4sn_7;0RTp_rM_k5J0UsVuWM6QHXs*>grPW)Xz z306PL0gLbQTM-79B?rC*#uU$P3c*!N3MGOQWu&&Qli8>dU+Ut)HOEYEE7wQLqXAm$T&E7MXx3cM*I|}Ia24ZxT?{!{% zU>xX~xp1duU-|`?wjGB@HkLHmnq>(d;RN5SoMzka`s1>*9wx`H&lQ5J_}xQ$X6_n@ zyJjvod9*$vc!U#tuX4&?*?VB;^;b1iJi-aSS2@*~ zlogoRtBSrgiZWkp^*6a^>jR|u}+yYW*-cyJ#a{xnyN4c;$!g!?A&V^eK-J|FCTez}n%nFgZrg~G@qoLEvd z9_E^Iq4+%zE@)c&sUm#~;}vk8py|+YE-X6Az0Wo*82O z-~EukA-RgbeQ4*FIr*@1rK{q7YzyUG%L#rwy7KZBFyQuj@$ow<1XuC*mBC$F;_(X8BCD4%JfLgPh=ZC9SL}=#5S4*qFQ*lu`(;;{7r8i9hm){cTNpzWiCYrpXd*Hm?e{9Zg*yl9$$76$-RhddeA_Je@Xtc6(YdY0KWi>ES^NBF zou&4BEvIydA*UFVbcy-%yh{e!0Z(2q*rm3e$eqB6qvh zL7$dcS%2S%{NaDEB>i=CuHt7)HHzdALryWebcvA;G4vMDq)W`7FMpa`%lBs`p!R#6 z<@4Rv7<#6WUL)%N)^cjnX`$q`9EiLft9_`SY5cQFQhu2RoRddiTuj4pj;c!U$`FDRXE$ni#(Za19ZD&8XG?L>Yr zL# zxheYopfu%f=c+$zbhO`VAnRF?H%GB4y7if~f4@ilig4o3I!jINw?%Ut@_QlQ7hQV3 z@V~`X((i>vHrj8`mwOdAnDpx-^~-%?1dniHpwC`NejKX}IVwG0e2pJXx9|1VuiK7P z2(J3Gsz>|12GXim2|d1f7rk+#uK%vy`4!>BpS6*i+<${2WdFl0=fv|d?3Y*^eYSnU6pw7+&a0~R+Mv&)=uTuha1wXCjNV(tZ+AgE9 zyaaS3ruKH6y{%#fsrS7 zYJH~sG-8t&xZ<``+rF?6xJ-|Mn@KyhYuDut8;MgxF=6D_iytNXJ*!x4l0xPxUzdc_Tcfb$Zs_IeA^1+?1GvT@a9PQ1xYY=Kb3w(2; zwC$d^pg2{lUwjayx%ZWI+vZChu&%#@-ePhC@v=fV+?o`jUFv%0SDil9ifgh~Ka;BN z?-(Mr>|d4l<&CueL+^UJ?Z|W?{a$FlIn9SWU;gYN^Q$MKUI?gf`PCEAmpF2k|EX8f zUs|pZ-N^5yg?*-$N}ey$?}gk*v_$fJS!9ZVeigH{@xMG@22Zg;xBhnevwo?9M>rw< zUdYi!`|bI1`ic#H*Ba_)`mRz4u1X`n7uqRL3;yN#vb%OYs_bv7``w5Y((mP(%@$31 zzDU0pa&gh5=gYLyq0n{aX07Ef&lis>_3-`eruwW3iv*8wLi)XsKZ`c!m*>kY-3^aa zs-b_4R0*!)EkgAlKkMPll}+>p7vhw*;)L{jAx9VOx97|9+x0Nqr-?o^DM2B)inp7= z@G#jL(+)W57p^Z*uAEm3Gp3R5)58xJvrHP_3}`+w&!Hbbb65<*cU-^cT|ag?wK$>G>l4UdY8ot4N+N zzNdUa8<(n$`{ns^eVG-GI_aV>`x+#8gcH*5g=&+v-<~he$~VMWK~41yd#5VL;I!|l z>2Ry>O07Vbwe);=4tK_@={CBp(;zy=e-TcUCcl?{MG~~LzdT?+HcR7@AVqs!jUfemEye>f~(ZC zGG1zehRzOp@men8NrzC#7(7?ACeIh?_d<>*n)H0(XG>o*CfMRnw`O|9JMES0;Dq#h zAx9VOx97`-%8k%i!bz`F#6uytieD3Dw!Ir;+IUCZDjJ0Jd!c<9H0k*w{a(n$MU$Q{ z{A>+|pC9dL&kuS>g`sjCoREGm0w3ieHn#ApKs*_eGbU zFVgRYd|x!_`6B&ZXkQjhdcH`%7jk#eetW)rCBK)oHq@6yxCkEML^Aokth_N>TWXa1 zu!ND{OH)sKece};;40}IM!VQ)$>bkKtEnbBW9op0decpwLb|k&CyOSXTBOGdIl5@l z=S3yf86C0an#OvI-EM+MCXo+W(y^IZH}WFme~D_`Pc*@d8xFct0ej^boOnWhFP%OF zYkhusz6_`Rmg{$Dqz~=XLLs{-tE=Da>5Ow; z+v@kzycB|~)U(P|7l@S>yq+1Mmz-ZDj#$c#($`QZrwb5Vpm@0Tgy26l)izc06)MI?f*981jA5q)UwSdm(=o?YHO4N6XrH z{+p{lEF@YXxQZW}_F)Ne!t#5qb?^Cel(XW5^m`#k7cKuU&zE@>nqkM0R{HmtXocV^ zeod5NNved_0ko;gfED6(^(?4=Dn?sEE-KQ0h1^y&>A_OfD-&#t;acV|2bWIR1RKAu zr?<;X5In*O=@3JHFxqdIm=0U23&xkPCzPDo!K za;edzHxKO;lHrIQt6S?m;ua|cSMlG*V5s!BEn59Qy3RVTs;v9}$1X(0E^NhCY`FVu z5Cp_dtWn3p4oX1;13~OU1qHiD>}KC>=a{38oioN*V~&pXTl?PoJipKO>ob4(nzi2S z)AyWp_F3=o)n&_^EB^C6r|r&L`CiE4B9!w5w}@d>J5hu8JX%fqj9ad4DXP#% zTg@#jU+*~ayQk_kIeKSt=`^#Y^t+i^iy-0iWD6TxeX>ZOs+=#;JzV9bg8|Yb!%rhH z3zwGq6cu)tb+0r#>W)8U zy|wkqk#fU~b?j!w7G|c!iB8G&*p}%V+2|$XMJD#MwngYJN8f3&Fs#G=UC0I z4Ie97=1gEODz9d)lgEnSneoi~ICZc~9xE={d@NTA^|uc2iIjs&yK50744-vu#DW+R zc0=`uk6pp7-p8Wk^S}iffmyhOhOzbhMr+RNBW1x^-rBMwaWHKI%NjmjeB0ie#&Fsx ztw#P~a`j>#jle8C7N|o1_)A9Sjj{5t5tUfy%W3S`urVT&YZ}YEa5-x-EK*#`JD=s4 zw3N;1JVwN}SKV8;wHzbd+QrJh=T+7sNZd+W&hCwj6kGnDM@01B#WE%hi^x6#t)lD>732zt4SW$rmv`1U7*g>hiA#VUJ`mErkx0<&<>(!8aw?&g9e zW98$bBUz?3i`cBgqeWnYoh&~Y3J$uA5iMqK)|QsK?;Y*J&W((f3%-@pB1qhumqy>d zjuG#jmeNu!@)+hZ;B>64kh7vjU>0t5`r653k2x%IxIF9@#J1g^&30!*iEwhexZRn< z&NPVEOYnnI8M@yH9g){=Q zaGmJu0rHFFE7VPPe4B~*Y3z>6c(I#ZW%*uAV+YH{im5}duqF+rv*zn#gv(0RpL(p1 z!T;_5lblmKixxqmUfUV$OWHV*xaT(_uKfM4Ips`GnZ0#0jleA2B8D-k=QXqOvS8Wz zVoq&aAu%{+HcRvxD~2vrow;LvK4hNWG*mYDj=(J3Zq%*EB@eH7yt536($^f=VQ$n^&gK+Ctphr>(q`PL06fZ(&xP zTOw=UV1k&|PIcxkvA7g}SR+t2>gT~Qg2Zp+#;M^uQH-_uadPh~&BLRb%Poftjlit? z;}clcz7xf=k?Lt;+^+JxY-BT;{hq-vg2X^GV{E&EWFexaypm$;rKozgdvLtRB&mS<9kv;>vB+XS-%kPtKawk|7#_;s!Zt8XuU%mi;kVG@f~zg;$JYGlx$WDR&gHpkX~eVnsuFX8czR{w*9sC#qFx zKwX;aORonFwZDZ#VEFbBM#)2YdU0N zXPw5g<@7AOxbIcAq%?J4zcp2`l~>vRr?Kpm^E8qDjOx)?_((TCWM@_>Z|DSOZJ9Za zjp;o@6q={bs52V}^Jx!HTdNPq!TMbt%gU{sC3@dH!!kOP!z9yeQP}w`>m44&ejhzY zEbu%@M3XN=`GXVEy58DRiy(35#%R_g^CGdniSh!x_&I`?Kb~lP7gR_iFw5C}42vqd zP>dU}hluR^VtI}i2Q#vdFR#^Gb2^P-6}(eLj(sb?tG$k>9?OjqvqjXGGFk+QE#=0r zxz=RSd%W_>Bs3Yz*KG2%_SrH_BQOh>&@fIf8q1r+G_jU-Eyyr}#GKk=n2cE{3OK1X zZ%Mu3%(9)Veys{?1ZL@Le&={3fAnW}^TFP_tU`ma?8D+!Vj+2D=8{up_n_4xM$x%|>Ww?28*Ax)LL z@k9CAJ_pUBcVe^%5+6H_XU#Wk5EoCV`;t+A4(FTu>@uIfX{r&Jr7u;?@4mc3cm;Be zW@jzBPhmsiw~L?uc4AG^<5=jxEn-pMn%WZ5+oj^I`R~h%^6KO`#3eyuOu0BVAbqn~ z{YO1os&9?E@_r3-@H{uNXar{A64E>2he14g-zDo$;pwKMFTCx&ELPI>3VqlhAAa_J zUOD^OdJ`i^=+*OPOKS4Yu5MEPxlSW63*QdVm&F@L@of*&L}=AjCcY(cbY-)>8PngG za2dusT=+G^nv`T>1c^&zp{bX)OEk---mz5MH;Ru-Y-o+&J3}KdYv!mpc4E;s;W|Kh zWg2%3=V5NStgPV#6C+6YlZ9r|tF5A5HATewhw{(@ovlS04AltC>P8ltKf`|!_iQGb z*P+3@M-FLiApsI7fobX3)hKdOSKpG@`RZfK>};F^I(OkE%RIIE*PgDe2NL?bi87!1a%=US)_=Oq)d18my#K&*eoyyz9Iya_#%dCPt8`+<7#+ zJ$;e*I#^wI4|WgWuj>?-lVfXZ1ZH84oO~=XZTXWK`Q*jp#k5*D5*x$Eu+z)ui%m8Y z&8xw_+~p59yJUhjRl{OR2CVER&CWgrtO^TTqK?3Wr^vgN3GT*tL z%V|wBYXoLBA`6Z8lksA&%|z3l*WjOSH<4w03YZu{0xQteb0DHRZ!pqRI(7QOkie{F zWT81+d!qQ$W}-PXvJSofXdpMtDrI5>39OOR)7`&BtZyJs^~$3Wn6-v1H0)2h-?iN* zI+d@-YYBJx&!ZA1Mv%bzKHUMFsK-|))sw@zePBpn)&R259Q-s{{An}MY&f;ZoU&xN z%+|WSIVxifTVok3K9GrK=$2nt?rG!2V=~bUVVjso(0Gw8x4HwUnAF2uxMrlR(I>$y zy?q<&H#JVQkFL)G^U!y2yW&J|ulj5qoqJh|O%>@j6HS4ISJ>uB;j)H|H!*^Q@0wk# zN~5VF_d3<4M-HFMSZNroP2r>zGP zdewPHmiy-2t-a;?KTVCmtbhELv0Yb3i}N-U%_yI5=BMbc@}GfqOpG9bXBu^5U%Jxt zY|}^jY)Ch877EUK(W`@5j-EF6X6h#YO8>9V%XSsTSvETHZ0#j;z>^?(DmGoK4kCf` zi^z+dEia$-(nmh;vq2*;%h8+8R?DPs$*SeCW}ZJ+KdLZ~oIpBQOh(O8VYlU-N;|YBR9cJNdI{M2BP4S_p4j@n8Cd_i_WaT5 z_e8d=`c4t)pIy5(Ly6I3!gIR3+azF zxLcfs&oc9B&mTzO{3810^bO+kj%4CH>ozrMt{9`aUAFmRj?S94d0n`KG$X!HPM)!} z3;*d^aa%7-IwEXyD{&4J&An8|oNfN4VJxIhx?i8uy@^v#H7oPK5hQR4X{o-|;xFDb z=52nyq!F0)XzFaXZS5Xm+}%R&4H8=f@Q7xm_|~PL8Ag!M*W*$3K%R4DQQl)v1rrI( za+ru5b2*bnw&KPb7hd9aH4`I9;C7>L`+kby<1WASs9f}s_Pm_tF_x`*uv(P+FhzT^ zB*)0kaeVow!~2~Ra+>)3ii9gUWgb7+D7y8ud1a19@i?oi=~Xd{Mqm~`AsfbT5mEf} z!hB|fttCy2An}o$GJXBFijk5onmFW`mOa|(w}Gh`;>Y9aDYZ&79OE=PrcKf2Ul>H&kxryaYh2pTf;jJ zvI%~0=SR1@%iamDCPt9ZXSe-5qds>o;4TB}I%x!E>31^aoEr0Wb!y8!%|9}XAW?#x zGCm&?gp5@c$fHq=f0|oO?wh_>BQQ&!r8nnOGrqK3IXN=tVr~8&5?Em~j0~qX+`DKI zc|XIV5txND1nHa6@}2psyiT%7LKbcAAQD*jqk4(84(~mso=iI3z*JtJ|I8OuP8sr= z2<4T*tw2XfHh13ok-HoiUERb85(YVCthuL%=Qgj*{u+&V>GrjytdUnEFblVWVH`Vc z;Xl2vDyt-aVOj+K?w4h;%*|t(cxLm;oGS0f>vu0J-+dJtfmyf}s2k$2_B^R?ewnyr zxmN!~0;`eqp7VMSKK`B|{VMos1ZL@V(Jb%!^Os%jS~tbzWEepL>!sA=_kL|Yxk!Dv z!`s8eEs8UeaJ$j>&fmzpbgHiGxVxr_5hV1dyUnLO_~?M@a?s-Z8i85373h1l`99ow zp`5Iml-0xt68JPpo$-Ea$19A>FSk@W$&kP-+zM2!9UH_ytjr-jr(DwN#z^2ZE_L7^ z(U13?b>CWK)h>;|EUd5^hHs0$Jf!0v)-{(OX_ZtY@L8SiUJH-n$;qp%br+q|2+Y#w z?>-$hjQ7g7!+LpDCKDq_V9kNv8w?KNRXfhNW=wO|2+YEo6TO?L(wo1J{=*v9ifPp- zBye^k%}xmI#M3%vmOkm-Gy=1*GDW{?*&FibZdK*!Y7r(zkkDsl9%xmW54qP+{#0YK zMqrjcU-W*~Xl?}6GWRsq>(n??8Y|F-akXtMAK{mY9exw9{W>FoTiq~*xsT%;_FWR5 zTd!yYX5lY2-St%-!`Hvhlvp+^!?GRdnEU*SjGBmMp=!(Ec~UW`c?91?sch& zb#bYNCPt9Jsv+45wvFY(@01bI>vaON@Ryq2hF6T@r4CLOgZ$c<7(oInp7g{L9LXC- z9b!i&w9^R8!rykfTZ$aR2i1;d=Y5Bp7(oK-u=E}Moss+yb%(k9EleXYOTTCEd^(bs zt{rF=m^EFy-$erJ$z*D};Kr}lXedJ}j?w0-;nTK0(`o2MC;sGNE7`X60Bzn95?BwQ zn*O`&{NelJK=zfb<>nEd1_YNfBK%=-e4es6$_f#KVX)%Oy*%S?(GDPz%2aIhQ8pL z>ci{gtRy=$G_)@`@GY`_pZMye$xF1VCNmZ{*6#X{(BJSLy=CFc4po;~(-vt2X5n2e zbz{%on16d!M-F?pP`i6Y0^cap+t(ZQ`N&=Mw*i@N1N zZ4wE5&rNeba@6LQpPR@M|L)NU%))x9VdSk;o!1}CWL%GAh7lxiP5?a#XLI9M_i)*t zdLAQzSy;uT**i`Z`0v5KGNj>Rt-gx{&W515AA8F3gp1AOrn*uiFbnI~hH+|KF+Ocw zOIdgHQic&Ea8`$5JU?BCNB-JcJ~?(mBQOi=@YGe_%)uvh=pyrXThB0pgg)yf>qCRb zjqEOWF1w`>n5EY&{h$A4x?BjBwNG2MZ>^BP8BkO`4>@7Z88%2}3;d!Hn1%IH>dMt_ zmg(#pCa*od$}ob2K96jP=WO%U=MXvLcs{N6idlL^c>JOw=BaLDXc(>1%2}ST7$--C=ho_pNa(Zl)^@*>(LW+up6*yhBQOi= zrQ{92*Uq}O+8DVnD7RJ@MMAIjU7Z$Yt$H;~&dgpzBQOiEc82k9+&=66!b4=MbXTpu ziv(8m=uJcLY3uvg{_@7d0FA&b{VMA8Ad`GqCrI`%o0=FwLa+5@KGlyODLl)1aQk-c zO*OuEbbKN0_yN+Uj#e8MW!#8P5OeFtFMPDr{IgqbtLh!hG$L*1YBW?OKftYgzc0XlCYvD*V`9lSjmV)W$#p>sp2}kK8!q z$g%lx@NZ!jt{?e157*+44^@^i@%qdG{2DN8!dy1>l@NEgETGEWh*JLiV%zL;BAHKc zt^sE0?`vHxb@;F%m81)Oi;NK@l*5L;Y<7I_OkXZ@`hwZ^^)eEerMxxt)v@E7>LFx^ zAybT1Sz>VC;y!nD-f(<>t_(3`im@t73`UT^vFS=ph8Qx%Sd}FP3CvQ480zgT?3Ng1 zh#^yqRF)WwAfc~^GQ^N6Mk-4T5}4)aOk(@8+%R0s!Tg<1d+T4nZq?RYS(B)Dtx)D9 zoUdURsjj2=rr;XFW&H;2{6IqaWvIKZP>vbH7?LZ5zntHkO}VYl{lF~!E?ik?$VOu- z6Aea?aP*dOe1$Cohw(e*Bg}}Y^E3jp^k)O_W5K-U^>t?8nu(2$MBW}?9e5{_;(j<2wlg@$Z2HWLjJn1$z~VJHg?*=TGg z8jK*}=yK!u3R_ud$VOu`(IA0Y`gyJ_G-RW(Die*e&`{54p-eQ&LPI^Og)-473k~&o z7IqVjve1x?Mk*7Hvd~a3a-mE#%0feZw}mp%C<_hs#};-Ijk3^?jfN`|jk3^CcYmQw zG|EClHUXhbG|ECl9r=abM58P;WTWBAM58P;L&gGOH_<2y4cTb8GSMgt4cTafGSMgt4RtjZ%0#0qG~}ES(q^Jj78EHq@J;mSmV1ZF7<4LN6o-9)1-G-RXU%0z<^B$S1QoHN31 zqEQwaveDQ~G#EibS!k$_v9OzHl!bnz3k}(5Y$h6vAfYTY zqQM9f%0fe3aE0AOqbxLJqp_K2kiaZQKRRJI(I}@3xn-pC%GjJT z^Q}U8Wt3BfOff=vW$-wrc>v^;A-9ZFUKxxap`0@0fDv}DjB?75TSh9c3=){7pC6X$ z^!Dm%O?fZ(1rsAkC{GTVVuW(#7>2UxkX1)2qYe_7rEEIX`(D_MI?5?SZW&W~W$>z| zoHEo0T_~>%UWw=#hnzCxmNAuA1|vu)rwkcOgxxEnoHFE=F_l*a3CzMP5%uICrwqAe zY+f0RAfcQxWGoSOuZ(iakXy#)l|cft@Y+RHXL8DrTgK*|Pn=lp(i_sk|~6K?1il-6xV$hTJly^2#8A zS;{FxZUABT$|$D{xn)e{mB9!Sc*M{<7IMlIYkZU`uZ(iaP{(?qyfVruLml#k^2#Wu z47pQ;-7BMwS4KHy$Sq@4UK!<-As>WLUK!<-p$_mud1V}Z z%7ne!v~tRjTgIxqGRi4Ko!5o(%HR^}gmTJ|TSh3a3`UT^r6m;vIc3N#V^v-mBrpq? zmO7YGuX}RK2<4T*2on05E2j*(WrXs|Ac0xRDML;LVfV@?rwqAetja5+oHAr|5Xviq z_tg5`l5)zBTgIxqG8jPupJeE0C#MX#Wu)@T;4=W;o#8VB^&}^!47p{b^2%TY2^^bx z-IG&>+%i_>l|cft@Y#p@k&#n|+%i_>mB9!S`g$m*47p{b^2#_m;|bMI9e)#*Q-=D7 z3%gfFIc3N#Bb8SMBS`4KoXROfZW*b(GDu*SqgSA?cmGyS8FI@=<(0vET)gAJb)q^o zIc3N#Bb8SMBS_%A1Z~|z|ff z#^#kl0<-XWha7I?lp(i_MR{c~f&~6P(z`oy%8*+|R3NVm5}1WgNQSX=b17b{bS?RO z!GF7++OA|PcK^bj$EMr{non0zve1x?Mk*5x{w>VX&vRwEA>)k| zY&W+14`sR`i-%CQ8)dp7ql>WHZWgyqVB4-w7k-yxxbnJ?heas2i^FMRd(PCKIhDPI zEG|MBTrh(B0RNIOz4HB58Z!2Y?AsdYqOfJ>iH||UK!LW}>tEH{?TdR`Q3JJ`@ZAf)$GTo5z#;R;L7(qf` z4`sR`Zjit%{U}k!9y0exW$nT3gJUR@4|RhU%H~5eoybB%HX5l+G#EhwuU&?* zo_rJ0A4w=Ql4<&+^GjIeuUlv9S>GFIi4!3Yw{DMS7NVfV@?rwqAe ztja5c1ZF9x3|U-+-7BM|e?Mkue0a>`KuaAEh#D5ng$Wu)@T zU<3)}lpzOMR$|*x#?S~G z#0V18$iDJ<+X4~wz9U^rl!bvy_E~I^+wxiAGsy$VOvTCK`+&q5pm;3k}(5tja`#R{$IjuNX9IlC}fcXspUa zgApWfZ0bBr78 zvy_E~y6_9TiAGsy$VMZTi3Wd*l!b;2D?*uQl!bI=JxMpA`1=KXly1LBrprFt~5uOEHq@Jv6*Nvf&|__ z&|7`7(2$MBW}-m?v+!4fzU?Cm4cTa?5Ox!dve1x?Mk*5xMv%aM z=!T&zG-RWZ%0z<%X5q0wZyLx#LpBV!ZR8nV&YOf*Pf7T((#hBCyEDMl(w40goFE2`cdzqV^8e&vy$jJ|(B zGYKG}Uw3buD$CR8yX}Jmf6)lcLJt95smVe^HX5l+G`LjgX~6NQQbZOSve8IoqQM9f z%0ff_31K(UC<_hQXrwaHAc0xaOl^7EHq@Jk;+7a1ZLs0k6|ba4cTa{%0z<^B=DJvy6=&N zhHNxeWun1fNX)`tA9~s*3k}(5q%zT91PL6Ex*?KcBbA8;BS_%cMNU1k(2$Kr zDiaM7n1#O*^dw9c8nV$yWun0d5_pv$kNbcB8_x%Puv%WeFPM?;U(U=#ASaj47cu`hOFc^>e|^?B&y0`~UA4KDkpf7GK}M zR3xzW-Tgm(I$}}(9fe|F!Y83UX{QR_y{@(;U6!ab`K7(wEbv5ZNdd_Nci3CzO%ua6Nvuq|8gaXM3LUc6QfX6{;K`?vGFhL+A9 zcmH62U<8TTLD`sZ`4u)=9|H-@!hNF?7(t@!KYJ`C$Xl$I_J0$Y^}qKyt~oAY-l$P* zTfLYcjDZm(9DDW$+X@NHYBnl?S(AJIU<`~P@wn)G_G+o;4+xAP;W!q4uvAE3*5%kV zmi=tuAB=%lfVJ1t*`eT*o@yW9HAdeb7(t@vr;RM)X~GYd3JJ`@CDg~j2ojsduVL}S zZv0>jBrxlLuX&}s#l@99sY0!-<9d~${(XI|DY}-KXZ!#9Qegy%i&r8tii}ukqjjR{ zI$zPP{2beMcVyX?{c%hgQOtG85B3K}kiaXdJ_Zt)HQ@5gjIaAw{a_4?Ac5C>eGJDr zVOzthgWXx|lLfZz<2WjRu;v&+qIQ+e%=avHHu^v3ITDzKS8#o)QrishT<5mg_P5#v z^|$nV{fq72j%&;hmI@d?QtjPXlKNtfE%);%a zj}fvUS>(%A)%Le$=9(#%j&EiA_pLJN8H1Mv{b0>8f<#28@nYNc;Xha^BrxlLAMF@H zVsp=*#k0WpAB=$nX5pEpuQ{HzpSI6oRSo3jahIQ%2A1oCTn1#oJ zJ_bgRcvSk~{sz0#e=r6Tn1#o*J_hb{+&8Vytq^gUGXG!?a7P+2@8I3*M|gV zb(_6jJkPxC2glVvrDu!&%lw%-pB-aZ)W3ZWO%!{k46^-yeLXOO1YYg_H-TCF$^g;# z&7>cUfe|F|daRFu>(M`OvFN?E{Qp@eoxo*BqIRiO;%m}-+gAAB1ZFw5wC#6SCvdyt z{^%t)iLA>!ey~3J)H>ffxe%~BZ@G)9h|6=JTr-<5?7*dV5~+-Rvj zqO>_YeSU)x7nKV{Y7x%6!EdGv)Q^*fAMAN6yX=( zY(`x37R?qU319lRVVsOEDVsF&I*)fmS7JaGGpBIqw*QUJocVi$y^GJoN5GqS4 zIqys6mHj&S@vAHJ^}sB*jCk?%_A$pkKjU6NrgiY)dk?0W7(s%*T@%U=YPX+Gy_HXf zbnun+)6+~x#P$uJgRp(oR@F5@6q#~fsN;=l`Z4)smm5AZVNaTg5hPY#TOjUqkz#J< zcC;R2R^^t}T>_-r9G$?dSdRozG4wxU)V-KrR!;Si(`gKhAW^mQLNU=t3TLO*G)CT^ z3&_{*KC=8?8UrG&awUu98CH=s$kT#kG;jk=}BdOfxa!I6s6sKX7d7i?h9uyqE4J z<9F#}AmKPa#Ckf@=quA*h2+I;Uh>5Poxm)|*(F?Ud+@n)Ub$($pWHMh)x7wY`u=6? z6*K<+W=SnRRm`})S0tu?u`FCVQS@4LlHR2%%0KMG5>E~meQNF$pYN;wqPb2v$$yCGSI0rRo!efA*~+*Tz=gjqxtYNmk_nvfRoA+89WD3XKz+Ja>u@?$v1w zxiqI77!oM&4@=ev%+l9^5$_|#ds?az%_h+pzfQ?3CnN>P-|EcKh(yT3 zW19MxxE7PgGW*Gl3qPC9&Cz0bu_Uqj;9=IUL|c)4!7}lv#98M2dbHSWohQ1rI!myqYP1jr3HDw!BT z!n^EHad7)|ad)9w^Xsl9ejvd@Vc8i85*n!9DLE-$xXvR=y#?BwGJ(L~0I%WLzS zZAXj{cT*;bLhJIG_*6`;t+H-1&m}HLByD0CL88{|A!1YFWU;tHKDtjVdaN={P$5f< z>t>C>tbQd1i+4@pMbS6v&a%t(O0vmeZ#l|s3!Ml5KXT?C?GL{M(PF*xcS|*>dL_BG zQ&XA$*%oaKBo6fo77r&RhUQENA7Rva$x0Th7ly%c_j#+<^9C^{Dp|I8i}!&s7T zk?sGeE+bZ?GW@$p%#{;F_VJ^{*l-sb;}>f^`D}3m8T5?&u}~4hEIi(5TYaq~U;oxf zmTS9G+g3=dIUgwk!=uFjmjX0KtMxTy#xoDOtl?UXz$`oq45RkiwlYtvg7RYVX>4W5 zxgx2EpO_O>)SMSJOVl~pO59pq#Kc+_eFagrjZ6(LEE8JKU>HGSYyMfn{ab4h99M*v zY9aabF4c0Cc_RmE1ZLqDF^t)}{N(;VW#yU9v$bu7M9(?X#57A+5izJRjd5^(Q`w?r zCHdQ>B#poG2r*U(yiYk zYe}Ec3?oSVnl(kF%&96`PAN`f1nur7b9Bxs>xFdF2+YF$WEeHdbd~Pwv&)JVCTRNu ziM+EH3MZHPqS?D*G)C@A9pxSWyt2}j$r^!Kc=XU)LH1;?j~I zXIP9p<9||w4sNTh2NL_EXq`elGKMvFrKPIXW1Q^!FsF6n>h>CeS-4KrORs&5y#Lz; zwmW-UhP9slWzt23>!mIA`nu8_mvnKb2l;U>0se>WsHBRt}JV?eF-g zm9}+}xYU2Mm|ib<-?-gsjNz+dW!={C8Fh~71ZLrurl-`aQSwbwKQm>fKf|gMR-)hn@7=Hd}r<|G+x`fxZOI@RkT2X`YgzH6}^zZyX-Bp@cwyz zVi-XJYvk0|AheSl*~y8|X%nvznB_HSj)>&}thrB7T95LZykze1D!l9MWcI3Iyy#~M zW`D|pW*k-0O1|jNMm#R~-Ft&Vuf62c%2oK~3CRqzW?17zwkQ2r-Y4G^8~^o^RZCal zff30J-!vf6?@YYda=1U6^IYALO)BColYWsgTG#c9xjGtrcszR^6AhEZ0It zmMzIMjssB-5ZRt4Fpp?wvtsXHac)8aQ%^$r`>6JPTxIu%{(MjEtqij| zoedUM+a$14YrZE26e%OmboJ-oMs8vFw~+X?_+U|_Nj$4;d%7E)r>wkH(w}pW$r^!K zxYen`a;b`JlHZH39<*88x=3^xH(30WE1nfK)HCPYa5tGene&F*(lr9J@aUmu=XE9J z!dHI$kXL21W{#oa{Hp0JJn23AaAUBDe?5);k@AUsz0pd1e72C;>kK#dmy}*P{rQ0* z6-5Et>PT9)wEXLK03S1Zo3=lYaJ&&> z>WvWfvm8@emRcOZ%a_*)%);Z1I)(U`lr3ZYc%F~-w5^NV?MaCcao%S(yBB#=)nr~2 zlqd4E;2U1~nixSMaBXK1GB}N?njFpk99BX;2x`W=Ol_wTn6>Ili1_Q&YH^2GgSd~(%(CPt9>I6qv3bVy<5Kgzuv z_=~ID9OlJcM-R{l%yLu>nZ2I4@`JNnv&f(4%{0dhuNfld?AyjvT|IMfv{-y?BRg9z zoQ>QZDeAhdXXoa|(HOVSJIN()n)BD~rfURdWl!!S3VE(&_G)d`lKJI}vH?7)ccO_A zBo+jW5xmD5wx{S!8Y8`B0a^LDKY!XSUL!Ee!-x=l&Ms#;7o`&Mv6GA3Il`a6xH-wh z$mwU{;#%S|mVefAhGSD#m2?-mvAI8YYcfe21Bn_>!bQJU%UG3`s_NXZZ9dubRvFd^XIVFCG(OVg!k0Gs8uh{weI+QMCtG8bxH`3x0gv{h=CxS-3ap zJK+=g5z*#rUO6PupWiB-WcDgKK~&AWl?ARnl}Y~GxII@R zFbj`k>favYEW@TX<1uqmOU4 zd@HhxwVzjkma5;-JhDSf06&qMtPz-{ulb{od1dM+KmM@PB5gg8$owr%l-j zPs*pfGK=ZY{r4`=2+YE*PVb#l3-LZjz4)!!FroK~D-##Ku=lPPt zyp7?-TP;j8F@gkrnaR|bl=iPP2M;a8Z@ls1@gsEtvp$Vnz=GnAI@Tjs^`d;@36qba zcfuG!g1#_i>WfhOSEf0?7Ujpvntal1oxm*mqLr!dRMl6lbT4|l0H5)tDIfYa)of0V z_1C-ivf1Sg=IEwtJByl}oXP&Ge$es${Cw_$y!R(>?nz@{1PMAHRc~C|8BCSb(1JX4 zjW<8CUMDb1-ydNsa`LGITks)`=9}|>iDmWtHnYQzyR(luJF;>4GHloRRhME|u>t9< z$4}~vdb}qmZy(%(H+(wJ#0U}x55=&A4(ZH`-ozS4cyvx~)@{N4|4!1z7&>s$KYPK+VGdNlQjaf8oe08 z@_AoyY+bj0Ir%@i19`(9OH7O)vEF+M+tF?h+Z>jc#+a}mC%=)@oFB-ZrV*Hh`-ysz zKhDqpyzj%eIHhWP5Q#4?iOkE`%PRe&%vnuy7U0)~4{y*`Col_-9_keGOCdgMHuXW; z5NCFEjbL#I*S z{8@*a_;-;=9uUp~-YjMf3vHn>Qcf1;=R*CsaV=CMFbnsSVf-b&4`TI>`|#Gwlv}_lRaj!)p^FUtG`}g?XJvY>pz4zo(=Xk z^Wvp`F30!03otQ)#OdQRSkJ739NX&DOvd-!tH{4?_BAnr#D=hGEUHv2D_uuDO$_N| z;jbrE=KaFFH3GACf1b+PCC9S2F4u`z&OQ0iTUGe>mE6S0tTI!W@`fFgw-}CX7%Tie zc;!4*`K+p@HU<*pi(|@Jrkrtx(Ya?6{#)T{+-Ew|2+She98=c0-0kiV5tB&0=X~pv zx7cF7zc7g@Kj7RRci8B2WF6i%nJuS(pE(xILYyW$wpCTH+Wbjkect_=#l);vO(wC7 zF7a##xsY{YTc29|T&D(nMJO{df&_D&$do5}$pf_>wIbBMTj0=d`yKheDkzE=DlV~Yylt5$}~94MsJ(X77ZQE?)-k_yQ3sBl=H&#%kr}+ zJ+-3*iNt%eSw@y9Houg*`dnRP@{bS7@z2G&YXoND5lZLBY=6Egv@q}9eW2N4^>P+@ zx~1(H{m?#{{hc|2)!4q9?ebs1Zv7p>_H{WxV_Z1Xl805v$=BDIX?|F_fgP*U#rDe* z*=rZe?i_5pXSiA|ot2&(!;aMHN5qT0&3TOmdHIao(@l)L3tz|T*NJ4Kb0jeQOEgz) zU30$XUS3{wd!jZ565kH5Wy%{?y+1`9+{Y*Zyr2J8v}`-+AU+9>019!3-vt6 zkGA4J7t6!n7aOAyn1x&2FgE9C&P()m;j0>jYWo9;&^(J-XmmJxeNN4+dFB(qKe`m+ zd5;a%2+YF0N#9FeY{r*e$;+=zOEVo-X50PeuJjD{X4ov&t5|TRZjNCe|4{dd^<0|swso9%qis5YS$OnNonfvY_x;C-4}6$v;TXQ4|iyiD)o;a55Q=7(UoEE^}UeCk7^|RF7HZ3!pdd zO?|oZ-}$&WkY-}U(V4*Z{E2^wtnBA~`R+RT_|2XA7)YoY#p*f7KC3u#baS3QFDI`? zbDi;TVHO?>)CaO;GrseXGw*vkP21;4sHZOVT%~F!^xk=RGoH1JGk>vJCol`oG{abQ zu^1m3!T9}|X(m1?QconNzVKIlk?>iRW^7rDb64u-`TDzOP9z+CYni=oZPe4!yb)`{ z!=~y_shAa8ej{_Qvcqwdyhy0XefrkpUNiHldtP_}Z zK57#ywPLGdj56=4@(w<=_^^aD6C+408@`Es7`e$YMy>aC_|EcGcsSJ=kie|hA0@kT zFx4?ewm%y1nxY&(w>r(l2ojDi4304-C3*1Nol5b2@j8K7)P0|+F2VK={PQ|`^1UNU z@_w`)7@@BIO!e(oo&9lax-y*eq=`S{pd1Uo{}FU~(Ezx$$y>@z>j#0d7L!oNf=({Pi&m{(LTq?!yy zkihO)^v2!O^41UTj-hx&v6ic*urgG9R6T7(oKNfYBS1=N4{> zE-vrWFDDY1g}uqh;NorJv)h!AU#Fy*7{M+c_?PJSe7q-L)ug0cM@I=pkiZTiWXKC@ z$j9+=@;+@VBrvPyuj%Z4@)pOMH}WFy(w!=D_tG>IBS>J^Lc=&br8-aARYO*otP_}p z-D0V}+lBMqp+#gKs@&m`fqPT$K(qRjFHimGEQhR0GckgMbL?+yK%&mI-{PNt~^5pMH+8CFL>`%1nyyz6 zas2iP^{xQNrZ1}c`tf|9ourlS05F1t<5$#S0DD)!k9!B_l?QI>1ZFvYscl~m(VL&M z&H3X(`DC$Olg#HAe_;U?+S$GmP}L5qX9!jCP<1n^X9!h0qr1MGfjoMGvvj)G>>e3wmb&of;kFbj_b zs?fiuJLG@!$oz9=Y5N=rRUe}Yn8<9ak&XP;oKNVQNA@~1MbfzF@l7uk5SEp`irWk zRF{EGdG%7IWDGy=2m z7^8dY5O==5PhIJjVKG%5gX$SV)iP8agDMq5)iNFxoxt7F-i4i1J6@+RVLRCU&9=y`<<5CGP2xx@D|0>QrV*H>ABm%$RpO7{ zTjX}ZO;rb@s+Ul;FjeiM8kSHMuhbg7S)o>Q9Qz~mSs9*}d&xOfx|^!*LX{PvYA>qh zN0k+!>VEYO3}PiFF0`F1hLL4NSw7+^m!3zunixSsRSBt*Csd`-FwXWZ&8toKkrT5u z*9gqgm#W@h<@qO*%PNO`O^hI+DuYz}6ZY!hKeH2S?R9mW7g8#hON8XMes%Dx7jE$8`^If04Wv_XCv@wuS6+EiT301|Tx8W(Sd^gRatF)%4 zMqm~mJ%-_yHwP~h+g9!zHrjkHnzFZhR@si9?DJc(p$|6Mey<{a4QIEyEfrbXuBI`Z zA7|mCXS9(c`AieD#_sCQieKGpyOU8hxNFtYg}n~vTRIP4UbTh1Tza~R5mkeu%9RE;`CHJ{=we}nOZ1?c9Qlg=%*7i91j_gwNv5j7 zQB_E&I-IJ(QDsd`r8*q$f5XV`l$%Gy1jo{p8(f0Ft6`CK=n2wMBN3|hf-WJ?qYGJk>k-HEN9xovyw)((V`hcznFFsF)H(84AzpK(mwdcdzm_23n4{r%#`&_l5Vz8o_c3&3 zz`uoAcwM18OJ6t3x%Odv%dtgfgX29t`p}97n!jy+n@(*)#_q2e_`;x?Ta6<7d?xz1fy=oa(TtEKgtv= zFH(zy@l)B8O^hJ%SIHy$u2=hmWjkJwma6lgRmE?4!}ya@I)PcAQqSzGWchHf=Op0F%u|M+eXmJ|WP zuSO_e?wqDA6%vPu?$h=!R0=-<B!X+1j9FAhdlRye#b>){v7t;?$KmMZs8 zl|&`lRv)(MV<0i|=I(vf9=%|jSFNBiL>X7HyLKp_PyI`9sW1!AG{ac8;FRaT{X_X( zS}N==G^qQhJ)@SqWMOV87MI|0+ovvm$t?9!Xp9lDk35$WkwgSWdY=z!@+J8tJKQYA zf`5t3a;KavFZ+e^=2REO2ojUi%6Pnse#vSrUrb{-Mc20EC1THqn#$K#_fSpWK~zFVrb1;Q)?`-Jl6^vj7$g+#%K^Bz&@ zFW7`ut7(io9j0135RrS5PGHtI&jOy`mON)MHPrmwjt54u)h|Q%dYbY3LYDNrRP;G3 zIBt(6>TDIyim}hwiha^@Zh4~RO2%`?70x;+g2lfG;aBPX2S$)+)BdeOS+_n=O4 z)DMEf*`)2ETpmg`F@nThx3Zpd9{gLxH&>Zk zkB_nu*k2O6Q@*Qs%5v-Z1_#lOo^f1yb+!@MixWFi`Uf{)zl=N`Q z*s&AoS)wbOTyBPg_?(I6UuCIfBe2gh(l?Gpv0guoa}d+nFy3yku&S+#eUGspa>dOn zSlJB)9K?$n<9On;99Fed*y$E~U^^#nX3v(4&am%~CKtx>fBHORionjZ*y%R*#8x)? z_^+OJVqDn~ywIlYrXsN0EOw#Y8MvNJE^)_VC%9i9o~_7p8-X2rk)Bp%ISXxDjM<5Y zU)u5T&;neIfqjIL{xWv~n{mW+5Ub;9hIf@}HUfJUBVA%wBJ0wzkAuiu!;P1rxr60s z4D6tcbjsv#_QYd?gV?t#-RzZTq-_lB%#3}V`_9Y3W?x(7Abva1&;0e>7#o58o00C6 zKf~hlVxxoD-G$~bmx!?u*!>&nN?t832ZFaah`H|TGW`3++6e4Pj`Xuee|c=EPjB^Y z=itC#7i+I`(KZ5m;39pZf=fo0)>|FKqIQR@jrdR-f&F)}v+kp7Z!$*3taT929{+2# z#Pzfh_yri!e^e_k7Vb}T5KVup&L4$XQ!Ny{G(ld_Aqoi3HY@4P)5eT0Gx}`tqf-sS%ik z6;}FEPK%8+_|B-O(4Z($bBZlykVH_LFj&5x_29j`vPg!LYFV3j)0a-1K# zs#M{f%W>P9V+08tn>v44U3n3j<*n8n3CzNo+0-@kX(fJP2jeIA)YE2QBcacGt=hH{ zzcHQhC(lfcz$~0EPMuqRD#(wNZ!6V4$6rhQeZ@1_Fg{VOuWg}Dwxb;*NQ^%0!8(6T zb-c$3>FUA*H@CJO?MPr2p276>*|VJdx=#mLaAyYMW2AuMXD_ND&ezvy``kS~b_1f_k^K#4nv>q5i;&`T1*5Mm-Y~6leTksKy1#R033Cz;3 zC0^w^aL=20Z2JQvNHiM1i1nV<*l~q>kQQUUc;++NFi{O=r-uCTn%X2NrZ#!!- zg2cbs7PEQ5zRdnkIHXV@FTA>#?W{!tv+zn}7)M{X=Fk3LSLYoU#r3uEQEXVF#u7^` z*kUEI0lRarHDX005 zcgOehjDJ7pyED7@Oxb&$d#+b4T8HH>DoE&k$c|3Vv}*4LG=Pmc5*URm7ufYNasd4> zt3JIt*GK0)M?&u;Cu@7rA$xzMSAO)@5g3I|dA3v2y>is?;0Rj&$~@hgpEv%$io@Te zav!>W<;&@e@>K3Tl1_4t(XC@a;@>iZcq8?1(YkKi;aD}A?JOATrXAI`@E35?R;ch3x}NPD>b&c_@TBx1koBDUE+ z+FpzmXCzGH*9X3T;v1{}UGziw^Wwv#c&fg`p@Kxafxj7BretWpZrPIIjU&3IyxJvN%pUKHr)p_@4tuQ~&?t#Eh+$f3HvF*^UYlI8JOf>fIEn z(Q#{*Ac0X%QS~id6Ax%vk~H{l%e?eBTASTPQ9%O7iFKhp9W6DBilu=pOOU{*E%%yO zX8kT}S(2H)*;1#|6rLrhAb}&x-pB?;Nk8AWW(g7)6}z^z<>}LtT9$k+*=U)taWc;m zRFKe*`GIqhQhI0Sb1V&-af_c2QUb9qNW2TP-lXX=9B=j|wzC|^pwe8Hba^VUc zfl*jVVSeg9&*g+PAO1YYc`BU0nzpvF)Wdtd_RipCUry`$wLa)@M}aicj*-OWc$(>=}g$68dhsqe~vktuA>g>b(RBj52xJOI<7(lC>wtMVk-u z%(1SDdM`l*34K508mk`3kGHuiYL*~@Q8QzW(mSUk+?~R@x8}W*XZ`V;lC^9(K?MnY zx9QSjMRHJ?o03IV>j;dp%Niji{CGw4Wz0PoBPWfF=2?QXjyO-LpMm`I*?WU;KKqJbg`+qCRnuz^I@d%Pjl0rfb9x`xnXULnC;Wpn^pF>o=B# zO*6DHU%JaIpYt{;>b(RBjA~zNjb);1jz)y`TPSCh4^z}P8B~zS@F*`O{H$nWp3pW@ z-g_%tQQwx3z$hnqv*qcb;~HU;pD2(0D}-kWDoE5AUQPPf?Tj|&^NxkdN8&?rUT2|6r0lHaSE&$g%_pj7lm#YH8i! ziAJn?dDqfoph@|Ib@}&8DRz*(<)>2oYI5q6U(Ia&sP~wZfk1U9$2OkXFk8Q ztm$u3ikXuG6(q{~MrHSMDU%Y9sg<9-u{Kg}ZeEj8M&xLTJk~u=B)A`wUV|vn3Q@G^v6KL+rE8H`NR^bWh;dp z<3h|&Qa5&1m8hP;sFAFe8bAE8blq32rFysQEG6|ZDGO{;2r63jRjSD9wfOzmdS}1R zQiiihS$AWt?wccF!;aBp!y~DtlUftraWPsVi%m+i6{~avM!id`VR36$pk-p}+m6!G zVw1A;^-6*Y5}BR5bM}H$h0>#wwM0BNo092XS8CnZtdzCZ9|MV{PY-9OI}}Rm!c-r? zp*UMc}DZljKOV9gKl%TpS=Jvm7aWRF zD$%j7?C`qcbUssr)gG)5=_@~LOl>6F^r?zEJBSJrf8BeQ)3xw`cBjrdUdb`J*Hr!n zfCNUZt{-7|?U|_&&r4fLJrm;;^*s?4Bp!AAkTYVxtlg=Pc5C6dtSpw_+mXPi4t{Zl zHuj1}Sd4bkFBPZoHvm+SFeO#66b=7JyHh{t{*z<4R}8nK-UvW5@KOD1L880;86mTWF}Z|LYZ1VVRr7CDp7r`Xv)okkF5L&`o#a ztPy5qo3cVjV3gf$;?TzRzU1Cf%@VhR6OEmRo0XpruOO(j`FPQ>i|>8u=!J$N9-GbS zhs-fL4mB&k=-0qwbA^mS-EgiPhiyf)@e>_-`|%ed{n(r z>v!%pMpCo#^vw!_%A&HPPOUl=O76$&esfkK$1{yVPG)6rwUxSWj>MIqVyBvO3#G0x zwb?Pc46@%tsWAOByYJo!ttQ5on3VbxSLwb7MqNI&*3i`E znf9!mx~$AtCBmdcrLHBYAd!8(uVKNIVyXM#LUxRvuU{Bn1hD7FBRzppsSEoV?yW7B z>U_G#h@8}7E zAwQu+a%iJI2g$4J#w>S}a&(-Yz^EN-n;Tx*lu9Ef9Arf2lgEth*fElr-v^b*#^;=_ z?tLl=t+#x0Rt=k`8qYAIN|OEYGf~@KBrwWr(8lz^tIH(&9xBnb=)E|;{#0HiLmvR% zweva$8EvnmYX1lSyzsYJy{7ePfC>_LKW4`;{wKC|jpI)PBrqziPPnl{)eP-v;A`F@ zhCGbrPXknt!22=l5nukT7*Tl&e;OcxQEgmfjkYH&+S7oX-z2{Ejp0uNRFJ^?F`G1) z_KJD3C-bKP5*Ssr#cX5K0lC`q!}Z6FV$iiH{xm=Z3H@Evsrn0XY!x$q8X$pDdwVQ2 z?tXtsd%x^(e|38Qd5|zteHF`|X)W-b6m<;mizaX9^NMO{H+=k-+!c#Tk z&b{^I%KeG_{~#(z46XOT*gxa2Hs&Kh*nSORvi`s4-8C-d^cM7q3> zMOL!}6(n+|ZWaG~Tkq?8;>}R{>ep?uT75+VqxOfTiq4}7EY`WD6&Hf&l`Yw_I=6%h z5|g&<5v%z$(Z>9j)DXJk;NP-3Yk&ks4SIS&>^$#|#X7e%cuF80eLPE6XAMw6qOW(B zxVmm@ZOl`92h*hTTjUTnYk&ks*)=&VZmLvjvCb_mZZe(@Dm);ob4#coF|z7$vGXK* zZOlz&fppWjO|m+-gak&l^!ry#`R$X%y6aoNAN=Uzp&7C|Yk&$8Z^?DBu}eQ~%aQHDFQfOiIGR?w zGS3oJkhq?;UwmFVO&jww9pmZkUD=YFB}iaYYQIde^0wq0YnIr~nL;Z)sK~Pf6(o8^ zSj4hNv$Zjgy)}h?D$bJB8Av2Bs-&SJu4}M1$C@SmDn!#m2^Dyjpn}Aj(i5U_*aB_L z?T1Cvs4oX3b#4g>jB1qgj~I}@CC8d2&8M5`-mW%0OHe_g!s<)nzb}_*V_xIBnXc}h zA*oq{1V$CCED(nn_vTo$EO%hlA0w* zVASgeW#W?V$8)U2L?NCYUDAZ8eg<^Vp=++_#valAmjulZ_iRu+Em!Y>sNPFZL1L(F zra0x&MT2$BtMp=3hS`mYIs=IWMy;v5U)(=nkzJQ@9ZefFYedw02@)6;nw2A_jb3WB626CVzSqB>8lQ{Z!@DgTK3YCkeq$9zn1 z6y3O>AyKmg35=TA{)AX#?HZ$%__s+E{dvtTQLPE1g2acB1!8EWcLwX2JA90!Co44| zYL*~@Q8P~EiQC6*HCl<3H<7g8@*ARhFF^$f#}#Gb=a05V>zL2089~L<^@y4!NMKa@ zwkP6dlC2T<3xa8tYbS{M#6jO9IwkcU$c|}~Xy)2|M9mUZkQgv{kJxJ818vL$y9d#q zrXDBiy#xu2TJm^{xbl1x(V8VQcTA-IP4*Ji^@0i#W2FqS>C7^1%(vAEq$PWg@+?6D zqpFtMEhfye6RlZNd1w&bK;MWEI|UJ9;O^No?#ukty!|L z-7ZqPG=!>If(jA=iM7R)cWK&~udKa-Y_$uc>b(RBj2d0|k8#ysSsKx2(hf4KdoWe+ zC8!{=XY&u@Ul+2qF=s7%$u9Q(qrR6Qflx{K#E;-=G9;&F03RkH*YBqki_A+~9MOB?eKSCdHh z*a=jG_?!t?d+EKSu=#tY8a5@^T0H>DI~I zS%U;d4G7w4Ayc!pED;~ql(#cNy_cYZ1Xi%wJ`EW?yI z=ZG5eE;}<-?jU%7~!q69);5`sjDq@*v=%mL>N)RF~y15j;y!K?2uJ zvE68cyUMnw!g!V-fl;nq3M>_yKGw2ik3+tkxHFKdPaJezqfcA!z~0m0u-q#zn0s+h zK_a^52TO3oE^W-a9m$h7)(qfTf&@nW^}3BTC}fjHY)w$)V|f#}7Y7w2Di)TP`kqVI z#(YNp1=;bXAI}mbFv{GZvos@cheljnC&`Pa2JkFF1&Ku+t4e>Lm$WgTn0ikBWz9IA zB}ibDUv5w7(YP9hULDF*42mCwvoUnbVdk* zC3&yx>|&iSK?Mn{zO(LokB`Y0yZG`s86+?Y{Ti$@g;%Hj z=4^jHw}b>nq3?vvg*#@*{mTXO`72bAKsN;IbNBkB9G@S+=g5%2DD=+=!jVS@zg*0|E?ddjAv(s z1V%;7YiH?{_*Ofsdvo7Q*BV&o^l=3sx@@p^%X&wbYa>sa9?M4%6(rCzqCk7=^W4)~)A%t>mj?Vt6K^f&}_!*a{xsH_{W^Dcs|Q1V&-)RuGy!YAIL08^y0E zRFFXb3|lvG`K6Q>XPwhW0;8~Y%lx~&Tgca0Rfc=KpjwOs`e)evD)PB>sH$~NA3qDD zuy)JdukJLHKN%wUY%MBCU@oxzaaNQ`BO6)g^pU_Qz4xP=@LZZSGeW7!au*dO^m&!G zWP@~dWu(%dmAQm{3Pax-}Yzr zl5wm`c2s{1B(P4wcD!BUX(?g#LH|5Gfl=sAVjUe0x)_UCm8>aq2%&<6zDm}4bz|`f zF)4%DH^(zM=&;Gqv%mFwAkDha_E;;PT^*^6V&5DUBnG6X7%v-MYgcW%yb`fWQiQUQ zeRCu*N?(-;`qGpX^axi*u(Lu1iNo_Y8W*+vdWDWY8s*pWoLy7Rsryn1i`0SD9L8-HuawuDo9|}f%V0iK7hO*7sj9GNMID!sn|Y> zwZciIXsaI%6(q2F!uH4=Jdj+U9>K3#Brpo=ZGy0DN+g+k)#~d*1qrMIu|2)V4JLUX zP5kbI1V&-qko7`(Zzc~|?yCRjQ9%N$S!zF6;jNFox_J9?d;Ps33vs#M$0X=3iQw_Siq9|H*N!nTEsyNzGFmyz`eh)2 zQU8U;it%$VYed689+2%D+?4Z2QV1&89}GW#OChIg+`w3}z%Id&I1qoc| z#~ebNuabzKKD?@r1V&+1RuDpFl#&Luy!kbV3KF$(vLLM7 zQ$~h2vO3~XK?2uZvb$*JO;SJ1pI?JWU=&u#nakq$=j6!_A6}zJ1qtlD!2F4}w~5Pz z@%$P@0;90nF9`ce>rwGARc0nLH!jPk#d?1Z{hr>a(OWUID+)ggqlV2+77r~yu3aB#4%KOX>95LP?D{|j3Cw)9 zALKI|dLv;7E6(W&j9Py$UhMQRUpvN%4{u1(sS!#rJ1bO>z-yDasY+a_%e^OZ7uFr- z+NHZ+fg1^Zm*#f4{pp_k8p@H}ZwTvd4t&l5 zyMhbCy8n65s_n1I8xHHw3hT9aJT_

      q%`wuJQ^mDo9{`m_411ZgipigjbP~z$kr} z<|%ewG_&<}Ua3X}39NIoo@aLMwBURxuX7@SQTkrR$-j@G38QZEiaRPuV7;F8Z};}3 zg?*m!dMy$dh3k0*VZs(4T7BbfSzY0V3KHl$5QNW3Uer1L1+P0Jfl;`gm;Fo4^rbs8 z?#gP_5)~xSKf&gfqQ}q+r(VhGYCt3~3fJ?pd4?hWbilCtvRb1@1qtkz!p8jUSh{WC z8{Q)Y35>!Oz=CkM*qi!vJSnedR}@|!ZBN}3`+PT;Un`hn?5zG7NA0d=$h(+N9~C5? z9WN1gKB}i(wL@LT)Bepi$pI|ek-#XuJ0WrQ1RBtFiM)%Q6)H#=7Lyz$o+qvFm(%G@X>}&Rs~TAc5`_)-7~p6g_c!2EPW8z$o-HvHu3mrqCZ+ zdGc!z6(q0&5nG$_eKalF`3LW8gak&RFN^K5zB-KB{LoQ8$g&+X(Y*haxMBG&p0Ai= zg7CfttI_9Hkaw<5A*dj+0n*JN77zqv)7jY0yW(AC3MFN-ns``T}eYK0dSB+#A0=9YR+q5fA}Sk(F;5*UT< zB-Wqdd@S9R@Xo0Iuhl8wVbOVJ*j!W`?XuaErHI9D`{&ZzOxs6Gc#K>~Yvu{&Jobh@!gTZ`KL0tt*l z*P9?zxE)DbSD7PTX4#IJ`1j?vVz{NIQO#G(F+q6oDuT}c^^&+_72C5I95hJuY57WA zX35|*+Y4e-I88rWo6KO@js!;Ooi%4ahf+HSM^ebn3Kb-xj=dCHZ9SwNBkXnveb&H- zv}b391V(kVl!)UV*AuPR;6wLdS{yiw3}k183OYIPlUS{2eJ~x8G>1EcP(cEnBW(Af zoJn-yeShvRK?0-DYs6|3GeT(h?SFC)3o1yU1BUIxn;%A}y$Ikw86+?YJyUGYms_Fq ze>U^DV+$1|(8`q=iGw0-vNSW2M(I3kf?JY_9@~|`y-}zjfzB#HSa@SHZJ#!YsMjD87=>OuR#$V5qAk`Z67?EH z1qtku$5!fj#!ySWFy0vt35-Hdp&&f?Bar^HIGMa)*^ZewKqwI%W;W*eia90-q22vy zp6hn9hpqoW1&QOicf|%7!?bMQJIjYIDaj$kHz5+pDRyXpwSs4rva;wtMz>zth8^@Ay@V1V-uiWbHQ7lkK})NK~IC zDoCJ*O%Q54bEVVYzUFryBrr<9cjl}W?)2H~dqnj!pn?SEf*^G3HInZ8@{-?0k-#YZ z?vCdNj-+<0o|9_|d%uERPLa^()ugV&XuW`PR9)|k1V-V`l58bwy*e~2qYs_W_Hfg> zyo>5?l%@NU#IOswJYV&D#kZPgOD|t?rXt%d4HYEL42%^sLN9CC9@nNET{>tOt;D_u z5*UR$+p}FNyFVwk(Icrh`yQwu;a%M<8qHUTgm%GA{z$ok?#d?z4<&&9dfxOccDo9|@R8~v%d&K6c{dlJ-BrpoQ zPO*F9)EpAH!-s~mY{yJI^TjAuKlgy=E9My6UFFp_QaZq&4rJMm3KGvYR~5VYKh?6` z$u^l3&I_dLShgd9QF>=)`DZi9?3iHsCp#-tkjSlPBiimM(~i-`Wh}8N38Cj$zi=cl zYGh)H(Yfwxjo9a5AYrMo{MW^S` zL;|C*dluX4H+USm;~hoS=O8Lbpi7s{;y62yjXNiEk1!G#h266Rp`g`Ra_M0tzoJk< z0$sX-P&}>&Im5i1>OV*%Fbcb834+~SFXA~VoO^^(K>}U6f-p0=8(EiSb$=p(QP@38 zy`ntH+u@nE5>??wM9k9ByOEu|xM-$D?O(Ce@=i&|}f^fC9MS3!Xt$tx6h-Y%`;9yHp2kZAh znswk`T2cPKNdygG-y9Vrnr=H|2`GM{-F+I??IhQl8Ah*4dIF>LKID>tuCgDSN509< z3Kb-j_2`oe=k7-qi_WV>&3cdlf2>A@$?PL zcFaWIcRxv6rWNyi#T*la#!d(1;hE!T49j*@kmzk-e(G+wwQO&<@}&Ikus4lm*^UH8 z>0RD|yRXToXL!)+K`8_kBu>@#l?3OT+A;c)5;^6PE45)~g#<>0G@2_#8qaIQp8l1T zrsu8wMX}>Mt_%3%zmu1Qk#OL_t9%C$l0(FpD{$fLT#l zU0s;-He8p^Ly0Q1KbrTqV?S|=%VbX)JgV!)$~({>!6+#BYP;3f-f*@K+3YRL~WDFG(SC9=iTTKxNg#p^8ht#O1#{DoDJK z{d2c}U+?@^40u$~wfe+6H~Cq~s&@Q~fJ)2fOBL4+Kga*_s32kd&_khhYkK|_10L1i zF8Qby9{rnu&$FbLt&~;0#K`~h%>W4)n|*5Gy9ByyW(11zQEf{5`|Sf2Nc_{RsX_!t zIsJ9!@C^s!-M$>B5F^p(zXBK;`ZEuF7@(e(}FODoFgS|3RVqUyk`djtaWqd!D_5^8b^MSH6G3W-V39 zs;Jw4d+$Qx%ammbeck@==L246==$HUx%JPD%C+^bMa)%e{dKMK@7m7juQP`Vyf*IV z=P1Op0M%cF@#N!*k{{+P9IHO7{N3tqUnU+~R`7Qr(PYDUg-#eV;I9~vfUc>I=M;h* z82En>>ceG<>o=`AOUITde-8^A@fQKhs`AA?#dXir^S?X~NK_p>s?e?Ceg298&jY$( z8M0*s&k!Y?QhwLKZpeRmRFK%@E-Lh!gpmK^sGtj$8+%l+6k9nLD8JjJ^T_}5s2~xU zl&jF4X`6_R0m}-y{?q$PCZ~|lkmX{NZ-3fYO$r>vp@9cg@-x}l#z<}P=1)82e`5S0 zu2d$g3@2<-TzA{=RE=F9r2O5d>jSqD-~Zg#Eb;GeDaRaLD~a#E{Av09?*vpJ0gslA z0Tp=c@RwKuD*u5{&gp+A{-qTcED@IYS5eL!#{0M2lz(RlsQd@wKO7Y#;Po&ba7JY? z`_FrkjRBSaKq&8bmiYG?D93x@{CQDU<-6qHQvVO<0ToEVtI5WI1a$p-SN?|>P=N%z z-#G4!iGlKzY#p10U=0B4kLNK`xqLJ$F32sJ4KJm`^8fq&J4fl~{7)VA^q-|}^1q9H z9hv%yD*U^7{f;}1Z-1J z**;W>(Q>!kPV};=N92g{nj;WYAOYL(9Jldp6NUIXGLRvlEAU>H5~E>nHyY!9&z1_& zOmhH&3M61JgX22dTPZ|kTX%+lt`Xx_DKV__2rDd(ar4 z#|%}7==-_|Dv*HvM2?H|h*XHd`(Fu=fUX7eE0h>#H_5%!lY?Uw;{CQO0#qOYd#oH+ z)pVjlM6TJ&5YUxE`_b~9)R^|8IWGUxB!w8*W3>PkNWgwH$C2f!3Na^dGDASu?1yKR z7z3L0r7?bXPyZ9+YOnwmNWh*x$NjL+RtWv<4?HBGE1TvSKjO7>@xU67)&#kpaKb)tD*1q#6Q===|eI@K$m6%qQtnlT+S5veVD8q zmH*Wx5>y}ovql_uWO|%JxV<^X5YY80w@is~^iU{`kw5Iuy*p~w6$vVkfVnJ=>oRks z5@ST)4-5fa2V3k^VkF;`vuaznhAG5~T|XqKKmumlIIjE8feO(wz8Qf8bcLBMS7NN* z7(rw7KI5klmvh?^s6Ybd{ph=-sf$8fukOYW&^2pht`Z~FUTz_47yfxCHXG+ipaKcl zPvp3yC<`UVojebQfUZ29WF-c<8cAc=p6{R#){))>Dv*GA4f;fV(pQM$-Gdndy5u~H z{0#odi)z-^SBPK3hY_g!P001&A7W_DZAs>j#KtfL%+DMg)?A5^*h%iuFKT>NA!?n+ z5vV|d?a}WWxPHFp`s+40)Hrc2U@z*92s6YZ{5IF9p^F)O(6;l}k zx}08kC^34UlCvKs$LtlN$RLwI1rji?!EtW8Rw?bP3tl-4!MfzqtwOPbPs1Bw(J2@~;{O$X76Z|7L}lGLK~8Jhu%eP=N&7ciu3>NFgqz2QUP5tue_}Vq`|hZyz5QGlg&+AoC0u@NW3Amqr01*LYSd;1S*h#IS!8NxjaZADs*)i0=nMbJfOsQ)^Qk(5&SS*A$0oG zN>G6Wn_)RUZ?r;O*!GkmpzC*wgG!8cN9CH+uwRTq6pp_mK?M>pqr-9SYvUAR<-sEi z0bTpA9#djy-Wf_`SRbFH5W%AgC8$6G=9xH7*C<^fGLMEb1au7xKBvS89y5r>*vMxo z#NziYC8$6GX2Ljb>AyWkJ9H640=kAw`x9gGA-P4C@BOC-eD32)3>8Sg+#<(Wy#7NZ zuRbF}0=lkD_>)0E*ZpaX9YueLu%&@KR3HH}o*cK@_RpDntTPfI0bT3UPAX+}O4pCZ z=y)tmDXViO5du^o!R8YW-b+@9@ENli0=n?h<4TN<;c`oV=Aa~ncrZ9$fC?mF{*ty6 zCnPF_0bk4z(4}5guEfZ_=tW};oHkY=>Vhr^P=N%@s&d>qk3UZonN`OS(4~colo(p2 z?leaK@F7Z!&`FIER3HKKzO;1P1}H?k>qZO#U5|A)DKX5x$vw!&llv%y=8iT9Dv*F# zb((Ez;HeO~H_aIWx{h61q{J}r;AxEgUz`*|-OwIE1rltAet$g+h4}rzgCU^nN!J)9 z2Jb454;oE1RERe%`y;480_J3CJ3v=QAspzt5fae#^Vd)%Mo_VwndoWSP$8N(4nZ8$FWnIsnyd93j{fAMD{fK)inL3D5oV z#9EuWi|vn9@vc=N*ze7Baqxm?lo&F=PP(wGJKEi}2bwmhG5#>E+-+6;!~9vR$Kt`k z_Nq>vd-!#J)nY{VRjT$O8z~X3A0STXZH~UDd7^21^DMX2U#9xKrih=tFV7O|Z&7VL zv6-KjJ61H%@2|R|CAUJ;zNC|d^(XP>XWgZuWeahq>E3wp=cdBD0r|MosNPu5rYU)_Z6ZR2sxKfA<~yC0ZiH(Wg!FFEZh?%aHp#;{y8 zki^Y+E;woL7wqh2;a^J^h;@Oxd8>&tu=C&xqLa}X{$u}%xOqQ&F{x8IC6WeZkW0aL z_;`a3LZa(JJo-ad>|8+j@s&!wd6omNHM5+#<{e*Km}mKjJUcu* z>mA?1O-Jl*^X~BLaqsC-`SmEn+>LBBc9}LmK5wu3`oW#_UupijMq7MS|IgpcE;kY# zb9eBeg<2~5L>2Xt5^OS1v{ffQCND}1*;A?zgGc3x8Iwztzn?FjBL-YA=DQx&rbI<` zzSRHKWb`h}m-k$FP>gxAO>yPVIxjYLDpLMlx$T@-8oZUiv{#Q3o0}e!w)BWY38yFV z-^}X7{#lz8*W8;8@yEd%l)s(EH^h0S>-pI9rj*#NTO*C{I1=f0Uc~3OZ;Q7^7b>oO ztu64?TPu~n`|mNwcZ3yuszysnsNI^7h}(nF#>1O=`-g70Y?ON3?)%hLxg5D#y6F%o?PjcwY z95Q#^4^>3}U>+)vFx|KlzYPC$_|W`PO3b7^$1Sn-c)WfdLqONn_?`HAUbpf+6RuI> zWpXA7y4OK)O6bGark3FLQE94>XBBSR&q}a^)--zD9A|H{6T4^0*FyepfmI5bX+KT) z;uFIknp%W=&LygOxXewwS%e>a{*!qOn_Gf6EzJ9ua0`wj8+DEf?X;%x!`g1ZU$!<< z%4db;MlAi*Q2y@nb_1>%!tr~nVY&hLR7 zMjhoFKc0yFe`F|%`=eAGvn)yZyQfAfE>54o4?k)_&!y_LE9nzzi;fOI#zO@X+tX*_ zdjX^Vjd8-votzwMftmz;VF>7&QhyG%z8b=R(a5Lgv0-g*l7FTHY9q|!p#q7vpJ(Gw zSBL!@qe)F4GF{&UeYIc-=z?WP&*Pz%f$wz*CPd(*t=bZO{ zy?yStK8HO-!%x0{;Nj8IYyN($WHmUCKf5rMIS)uoQDcpx}Qu8I(A*E_5GwepFM_fkrr4ktAQaJ!l|T2%HL@6 zPu|f+3+wxsme1<+lM-jVPD&}OKdBl#8%Ll5i62H<3O&+6CbnKaAT5Ya=c6u+X9(zm zM@V}`?so_Eo`1gct(}Z;W{Qj2b@Fc>mI%jfNnY46rmwo~ z(1t>aeFPqJGE`l@L033Y9MPn&xyG4wiX z(HIY0jEK82;e%}a2~;4#p2z7Z57IAZ9Ul>HPO3`M@b4vYY8%?xEEzBdU-p@z?q$?U z*kwFNiP0~(6^(Jgh9@T`^x}UswjodnJCdQeDsq|$@RvAlaHJFY5aYqGbFgP(Ktjtt zO`+#Mm0P-5QaAE*|0{lQr6WT?7rZv~dNl1qDo*9`d$#ffDv+@MF;a<R)PbMa&d=wi$2@PKf#X5&@Wo4RijY!$)Q()bDactp=UwPXACG{&sxVWi!bT$Mv* zeF9xC78NK*vfa&8V2QyWhmvRO=BWy6bqG`-(by|rq4y4yV=$F^q(=z{kG$4Nmk1RGv; zGjzJcv@Bt{J#yTr#5lg#j>c$~GM0R)X`*_ReL;c>BzAdh#38Cp>L>9sF8SzDu36K<;^sDVju{huv0} z>#ku4=vr{MNQtp%uS|rQCKJa+Pt?Cp&Xb@5iMMyRDMXF4JX3bbfK+0eGE|(iJyn7V zB#bVW;Jsf(b-+_WCc31P&u@E*=w~oPK-a125+w%FmopQeZf20Zd9LD=fld-sAR!f% zD#ZCqa=v7sZ5H`*XrtKP*HD5ABo24ni32sxs+*7Up+t;tHYxBPD`x+Ci6H@9*W7k0 zG1e@RiSB1%f?I$ zNPIuB16xJJi}?m}4Bje-EY4km;|?}s2y zA6lA4raN-dxv_o>0bOsJl;YEq%0!bMa;D_0Stf}eWhM<>Go3lAHchwVgqKgm9$$M2 z37OmRBtLFGLl?XaPlIHU(7%Gr}=SOq;mm5NufyLhdSk0XSD{Dk2JG+ah?AemXMX&7GWouCwB$Fn zsgxPJ8hg$iime{^5O!Z(jSW5r;w`%z1o%sI!^$PJ?lR$j4 zjXaO+S*H|YQaxJIU!yHSCHwnY9KOyQr*w7wD~8dC6moy!XlecF`b-Q+oKvmCHm<$# z+GTQ<^L}IsLH?tqvph>c7c2!jj`K8`6f6pt$mCYiG?SGW4GG5;X#P+!>a7+D>*szye*P6aeCSTHrOUI_QVF>7gCBkvj24<44^CWzKVpFM4;6fZ> znuy;OwGe9Z7vU#A6L7dwYXN54=v{IpgLGMO9iOl?l%T6}&|=)-MFNidV)7R;a9IXX zx2VP+U0N}jJ4i$?Ta245O2B2f4Ly&@e=^94chhlYv<*W*7tH%{TuMkf*>t+0^vv2q zf(j%;ujS+0ugBvhF{U)e^Dk+nG+1By=FyoUpbO^bIPTuvY_i?rvZ|xUVZ5y>4~LZs z*wIWwII?R#{`oT=uZ`6c9>&ebCZ=9^)I4n(V}4{di8JeoLrz@5P=Um=qx12Z$nm(r zH@Ut0$}pSw%m~Ks8doy}bVZ+DfP2~`;P^VZ6`p@5hg@oYRQ1uaLX7J<537!b<0ZAV z{QdRwa7@n_++uZoLG^Sl4qEAmRjWVq9Jl^L4za!1N3}Vm6^05V_La=TOFzfpia`x% zjI*?totT%)Yv;FP2yE$eKu!n>4jw0#E; zmEdvn@D_0po~rYd`6U|TayF?rwv>-8$z~KttQ$2C@4OL++Zex~F%DeGBG-p}=A%>t z7y`QBm8Grl!W?qq@ld{#|6CPRAdxnF9^%jdpFV;6|GXq zvbY!gn(A-?Dv)TgX))ftx(#kvv4axbf|AG+A6p?acN{}N7rYnf`1$oT^6b}h{{AL` zxl151J$(`0_uL#84=STE{Ib)@r`eDBz#ZKg0=i(XpW_T3rjW0-6ZxyzslwgeoAAmI zfAL(t86Rr15nqTOCmvgE&nJl+@Vg(?>T^-HG{%Pf6mo4zHve{KrT`U43@BZPmuD>y zZhT6r~HiYWQKq)c)!se{fBh2ca6Y5 zsqhkp94p4L+X~bR+U!@gc)kt0&b_V{eX3PY3XAZ(lnySnCNF62HGUXv^=veCOq{%oT*hbmJ}f zd`Nc@O*5irUe_&^wDTLs=lz<*5YPqhH;$`!GL!5&*@nae8mkJ= zE5Yk;Pf*9T-k_ReUyKiF`MT99^DQf5vdQ6hy8H~6TYPlTPF#K4r@SQhiQCnr9r(V* zt@1f1eO2!Um*Q#rcDapPHj18k)0!-@q@)>dy`q+f3M4#!mE!y*dg?V1(Uf?U8zP2Z0>$Z--7MW(iP%#Dvlrc$b40-=?aZ#u)X$nVh(6ie~Uj7y`P6Cr!dn z$42lo7wo5mmz^uIf7=`#S%(FvKw`e_RBYsH&HH-m(`&BVs0Ycu*b==qzrqmEH6S(~ zn;i4umv+*ngwt?DjyL%#JXOCCPE^gro{cZ5jD~sfkO)-G#fj~8`Fh)$Q)1$Eck(bx z6V(?k2vC6pJVH8iAjF6K+^2!M?LeKp4b8o_zH$kz*O9iMv z0+uw#1w86U4rS<~gqBkn0=ky;S&XAQIP=wedeRt6yY(l>T=kK?mXiP#NWeRWw%bnz z6Nmj8=;Mo43;|tm42k2)oktLN+n+*A6k$e}An}kH`Dv6tl9+CNCu}XsWeMPdV^j2c zY#&25&$uM~^YIWfN(RTj*rOVfHJU_@zb(Ak-BN%GB)* zpM|*5jtl`^uncLN+98B|TlG#@XOYE}6(nN)m*FNW8uHsN$@AQ|L=7g}E_@YgJeM#8 zbisRp)=_4INy~q#1#EwSx#o}=0g~XW#^Komtg{rdVeQ1n#t$P#P{DE-oagooqHur6VbYO!}V@w|}DFLpT1#DD~>S7^JvDuWDp z|C3jZXduAff-YDhw3m7&l}t@D6&?jRFr^C#&qmvD*CQ?}iU>)IU?(}~xeC4Bl?ZviThfUOVOKd+ZUg5PTj zZHC4&1a#TY--5N~=%@+`9?*rl5YV;a z**dJ}z0Xyz%#uDItzJ(cvHI3RuI?HEDv*HfN4jcpOBlJVvrZTkeq7*4K3=V5tQuoD zfPeLEIsSewU)8NkTYl}fLOgg_JJsZXjx>hKX%yLdc!Oa5Y_|XvNDO>JiM!`iW1}w7 zGw*UInmF8ECTx7Xfgzxay@J#0Vn}rNZNkBbIm}ZFiG8Qn<7S;dsq8m-(-=#C#u5A9 ztLc_5Q49fH@Cl|hr$z#qK6j01U@yOK`s)1YO-b5R3W3uw6 z7BZjQiXosYEF>H^n*2j`^ll_2JRh_smu_pKP36W2Dv;2aH4fLtN2)$Ikb4uW_cSH0 zLv+y9{Pqk1UHqe9YY-+hn==G-!E>T_;%6%ob3+5Y zuFyqLfy9seBwTND7q!}MGmW7$v?Cd@L>pZi*n}aV3zh=M1-9%?PEOQ8uN!_A;C%(# zqOe3b&hEJ*35owHq|jCwR3O3D&M!VWke1#x!ULC(!>z>f#2Zx{n z3D_E-tArZ4kuE163*I&j7y`OrxzSmA?c7Nt=Ldq-gr5RbATfoGSKTvORqi}Mo|Sg7 zpA)$zeiocg)I*SfE?Cm^PCTDQ@_x7AcOK&e*e8R1Ls%!$K4)eonKLGr@0nmMKm`)8 z?xJ;VavJd+p&_6+o*|$M)}kDz-y)fexZhE*Ss5)r1ro6CqT@JC5=qpw5rSYagCU@c zeYe*q<4HpaL)mQMf;VOe#s%s}j`MyMO@>~XBBZa_$JCsVU^6Ut4SSK$$hK%~gE+z9 zcM{gCtq{{UKjWX7N8`6Q7KpV;cljKziFn(x0`cKiIcJHTtcdyb&ghfZK>;d|h}t;- zPl;WpURy>e!Dm>LuwLy@=kwPY0=n3lvR$kK$v<86k;l4?BAksoFfiUr{ z-kODjO{&CCtA5cK+Ha$XPU=13Vqz|a3M875IXJ|y6&|f6=aAQU`w`1~4Uoyc5&=es z^LOF-(UH-hVMH4EO6U2{X|*yTqnoP5_nIFp-)U!JaqvtBn9Oh!({HE$k>2~~1VKlpVF zE#1w+$DZ>gs6e8<>kM39@4gsnp+kwA??#ZMUeAOsXMz|4x?ImBVt@BT;sPYkJWJFG zAr+0j2svA#B&a~5W4#o-DXm;ISyG?IFfH{V1BbLlX%#gX63}JPA`HK+UMQa8YiNx1 z2i(cAIp(Nz`wt8iNaUR#g)2HN6J2J?bLfX1vLa`uBJ}*+I}sAl74o?+wp%`0+?)ND z5_!K9h|Y+qLdM0>%$dXa=CIW1yFDtE+$lNF8!aBmTn|XVaVm~G*e{JtI$@xST|9;% zpbL&P(lw)R)5y@NmH0wkFJ?p$5^z>IeZy^_`NRdCrSSpX7y`QB_$SBZzRDmUwJn56 zQ!PdGlae^*Naer1iX*wXvV^Hvi`|H;c3k(H6)-5jzDnSoi>xn z&aumdQJZ3Us6YZfU9^SlOvld;WeCT;N*DsV;D`{%o!b^qd=0h>PY&A&P=N$|OVBLm zumtkce}QoAL4SsTE_Q69-ijzvf6GpxQMX0RNCPC`Is}>nFdR$1HCQCr=qzOj=wfSw zcGtqm_s`perw(OI_8bz?QMq`1T~l$StK1fy6A(^v53Ln^*B)UA#>Lc8T}RPzoF-qf z$>*WWxbsk>mDs1P6E13QA+YzZeRT>6)t`%#Ba)dr5fY0&EXB|End9#-+tD|}l_M$S znNE<3+dqXNpo@J5J?U7{Nb?!IX50eiiGsxZgvHq9QFDCpjuDN4&_r_bwVqITX(>ZM z7kod`k8SrqrO{U| z-D4J(_|btjsJ3$-1Qkda4~`UwIKOKbbag7jEAmJQoguQO=S5Mh}lM>!zb&0i^7Yf_4Q-JGk z;94T%Bmv*C+pqrRewGqaX#--Y*B6DI*d#y&5^z-#ZOLR`lz#T_gNy@SF$8q|eq({F z+KzI`8Fqxm=((bo6w)7|-OW2OXAajf!E>VXuRczdnuqp9WqyqjR3Onz>Vn@6R;y<( zzCvSUOqng^*$1PP5pM-ZKo?t9>vMNY$*}@mkJAjn<8?n}hBNqDH@hyoc~~N}$1;n~ zBzJZ}HJ9}eR3HIcXS5aGoFnJUROs`(=S*2a7rag!clV1C(R$t!of~(Axq^^@ZASXO zst>V&%(X(Ko_4%V1 zDv*G4Lg?I&%vv$o(;U@=dLsBd!{;16!L;XfE&@+(Ym4R^s1Q^jv1j9MQQKQbW!L)< zy%UqK#pAD&T~VLYb_@YscR~({_e>4l{KlQ6M9X^z@ju^v(d&n85L6)X&(Tj}K*p(Z z?UolQF(B|Q_V5^vI_v%tAOT%dZ~hh+rEXWZ?0J_GUDZdO=RX*UUVnZs4Bwn*xiZgH z?S1M7-+XJHn6}=SQbQ(8UD}5mX@IT$E>dwd}r2 zmkH-75uUWmW!kF2sCUbz3;|tHHk|l%wwqg8efi9{;VCZ9W_hE5>pLK*Kw?pGp5?Zq zC2kE?$nV6!*O@Ny&jnPoz?vbT%cLaF@=ELpx2`4f>den`_0%CJ?2#|;grEZ7&g|;U zqPdCU;Rrj#N4g=XKmy(i99LRVF6wu4K#wbWG6ZzNm7#RZE65rTu~VV`DqCjFC?w#O zrEQ-AKYV$=KRQ`u#1PO0*Q?UmB4r|O-838xIr>F_3MAOO#KjdmA3Zzvm?s&fXYx3{=WOSi`}EA{7?c(idL5ugGI=a!AcvU5|^{T9l1;`g52)G3)M=*qik z3;|sYH|AM(^I4!?+(hmVUU(iVZl0fwM(w%5Lj@9LGqlCgm-5wt@lWNW>S`;V`J96` z9*I#w0=iag$g|Xr%~MA;cua}j8|}o9HCgCUBV7q9kceNOXE|m4boJ<=@(iJmBVUWB zz9*qiy7MKdK;q~JZ4p14s&>Bkk`h5dOGLNJF{qi=Erx)u7whsYdufKNyAP3P2rWwv zl#a#z5Q6=K$$6^_;>{F0b-#n3`J%(QqVAo_a*xp;_|E0I;?=A!>iFJrUu{4SV`(ma zCdB`aAW(tCPbVEQGwyo%z*BNh*ubhI&`q4@4 z(EAM^X`>@LjkZz$GhObhwKny~g?>(`iKjh*3M4+a)De5&}tyt6rV&i~cXNP`ci4=C_~=UQOB-ofeL#h2@}`>m4vu zAQ9XZZg4ds}yA#UAstJB*?Sr-imgoy`XTWl! z`vSG2?Oj?M?9oKflIS%uQL!YyV1QkfYbD}fP z__uga=LzWMwo-uyMd}?3==yrjpwt;Zs7pgjs)GcmKmy(|G$%7=0^YME6^Q}y3;|v4 zb5DywU5eDHjpX}E_rg-?v$r?evsjSs#?ns`B%tf?{`2Clew)-kZ^+Mi-|g3=@>nNf zb{q(dEpgc2I)hDJJ-?(R3HKO2B7cu_}^mcoLNHq2gwWp zT{GzW_)FFN@)H5_70kcpEZvGpL>sLaO7PmQH9aR5H7!#&sCmxAdx5TGHSQ_x2}wa4 zej(;AfrOy*TGT8%q1M_dKZA4BNzzM;Xw+(snjxSI-qUnmUtp4yRu+$Lm@k%~0*Pte z8{$#jD%Hiu<(0*)w-!pLtB0c54W2Rtbg_GKEbF&kilIBVmaIH0z#iSFhF!5`sfPHy z-W{Ip-TAndO1GwtLKls<2vC8<`a||uC$*gz*7XrRDvgze(%Ydis8!NRhJY>~(HKwG zdZ9jI`hXH*eIk7i9D@#y?=3(D67$wL;$MBciK$=Z+Q1|vg%q|QAO(hXWLAv8wIFaE z0X0Qt1rj^wt;Dk@8PnARW;DjY!ep|#UlN}EW+p>G7t8_CH{8<6WcRLM(N%Z3 z1Qkda-dln-9_rx7!`sprXUV~*A4@)xenNrPehDg&FmalV8+EP}L$&p3 z4ELomWH8DVs<&-t2@dYUh}8%`!S*d@$y+ATo^5?eDe@k;YD@u+Ph8l&Q9C{ZoB zDYP1}iXos2X6tEYTem-POVL1=`z@280*RqVWAMy@%fwkL>d_cS%L~AJU(s0n_Jh%L#*VLtc!h9iPvvK z>B$yvhJY^B%=P%3bt~+6kOz2A|4qauPYjLyg%`2vs>tPrbdDaB+j%+#1og#5H&UA zwM#|meMn)#E#b(#YKDNW!JFgo>d}kDf9A-eul}u6B-c)QZUXd2ov?D zYEa_dDtmIFdt3DIlgJRzb*v%~FB8X!?_K3F;k~okl7b&j=)lP>5>y~@`zw#T{&W!0 z%UVhtH)%o^m-{2v{lgdnx~5Ea#UC#?iJqztl(;qGiDaHP3RMr)ke~vI(JeaQPi1=I z$=h!zalVd7S_9+J>BcwQAOT%tb=%>l!!*Ui_VSKdeN%F!`mK|YM)EBlDv;=zqJcSs z^Xd(+1x1^wCCnRXz*>U2OlO;6#};r^Ezh&+5taCLqDK6Cb}gE^YJBLN+IQF$8omyPt69 z7F0?N5;>$*-its55^!e{+Is!X$`FhT>@!36tv&Tg8lwG;zqXU^w+$3X zz`axG4g&KtiTYO)Nj-Kav(g)`EQf2jX*P<>B%MY+#$P7rN>G8sd*AIiIAepD8!3OU zNcTWGv3~d%rxn{U1auX=*@`_oRf@Zh$ZM)w?MWp$tG3~e*CQpUK%(CCE%-pqQn9y% z10@RRE+^3($Gr`0bM2$%kh?To5g^$9VpSzm42;YdpQ5u`lSRFNVvXQgnQ{l zi)l;b6}fjKBS=#EcHZyI2Zn&I`&|~|0j5jD9zEomGxc{6>9Mwf&^$zwKm`()n$E_i z1N)2T2ehQbKRW|S{~LBf!Wu1xfUfaVX5zjD)5R0dn^D37o-a0~rFkU~ZY?Lb}zL5HKe05`+7*-5JF~VW()ycur8tVkW0*^u6AK4JoUW<6-dAwAZ=6cbdomL zj6zAHZ!-jR!8{6Gk8`zw6!tt9e|GvyXk!}MaEV|@Ko`u<&~ay%DUyGu$*7>hT7n8Bc4!%5k4ewevwO&^ z;;(F5E4f94qe&r07y`Ory-UxdUWK&zlP3zgr%9j!37b3%eCBS2x*(YDX2z{pbW3tH zZi&*PyE6oI!FreOgs}Uo)aug@!Qs6#feIu_dU@g6V^`H9*2wevMigq2!j4#|zUsvg z&;@rIqbv0;wNsD%B&{B^R~RJTEnJ0z zu3L(W&zsX2>wbijy!nm!L4IE)_*>8gcj)4{<(Fc}gJvPB&Svi)pF}v%w`}{eEfG)U07ySm&#{|-#^Dyz)wNeQxkeH!Ygqxg z`#FLkpbPGvMfXBll}S>M`r@Ez?Ifr`g53pb#_cQ;QQaAvUarHCfG)VR70m%y%~KmxW= z=*%+@4KnOjOLTBW2Zn$y`0k=}wo6+QgGf!(ygS_)54aqC{#B1eqV9P|yimVHf(j&H-;jW8j|v$Ay5PHu?g>bDRjGGj9BvzuEkOkmu#Zc>`4W>x9y!F}J-*=#0bTIj zMSJv>8DvJEZMehiP7+ig0sHE7Cb@YQd0D&`m)L1A1a!f77hSugkxi;vUcx?&3z&WG zAi?e^*KcAr(Vlh@_l@n!5YPp8<)e4|$Is;%i`|fqiybqY3eJ;)Gr8zp^7x@zYnLZ- z)-z{jY(av}MzvYEN?rAEFv{Mp&k)cB=Y-ICmNlKk;A_KBoOOL><{2bl_KR)-T;(lp z@sC2`iykraOP~vm@N=A5wjQ2VF$OuLToa%I37C_kJCYub#wpVh(X8MihJY^EBB!h3 zrJI;MpNv-BpDREG5-_(&-welFNdcPa=x|UwhJY?u6VVYxqX|+)pHwvE@_ZgDkbpT- zI?H0k3dy=`5~}&U07C-0V0}f~y9Sq}<#kcW?U=O$6-dBbFP*Wq`h(QlJrMPKx11rM z3-+n$TFc1h~n^IE|?pj`>^EpAfdgq&>hXs z5>y}obMJKSd95p1^ZJ3nJ=0{e2G9j_9CU`zMPJg-bDwZfzdn=8fCL;vpqbRZ{^WVt zLSb<|Erx(Dn5&^P2POoOwJ(AN`?y~cR3HJzLTKi0Q79?fVkQLS{bUH}f;lIe%jiFf z*rGf9@h{IMs6Yaa>CiXamC@wb{e`?Qe#j8e1#@TgIj8FfRb6hVc5OY!le3NNqcY-N~~gCW9=uu$S7p zE@cSlVs|86x+#lX+%OZL>-iDGefi*CitH@!m4#VEYsLmKwuO!a6-clN;_O3KG!8tRCU!KXD}4^t&}?>cuLkKmx83q-VaRE%_AXgX%hbWWFT> zUCeiLIGe;)ZY)3r5+l!QiWcd`{B~{mORJw8jd1DybaZHMUxt9LM|bipMZFS! z?y@D6I3Hw$$ElN1P>-td zyL)SR%gx&KTKx*0gSTi6K_Tz;5L6)XA?JtsO5^2x1>c$yKEvw7;RpL7k4j^PfUeh9 z=(m#cR`M0vEhsVmQXN*k%0lPnHRj=$df@kX;I*Oq0o>^z#Rp`f#4jm4R3O2Awda~~`TSA)J2c&)D$0Iav4-XYcu-_7T-g2iD z`YjGQ-LMiM0bQi-lz1h3BmeMVAw3Vr7ew+5iAKf6qXnoyBG9}6zP)2LUlY5Y5;uG8 zkyd9!B1v}@LqJ#Ob0@^w=WF?k@$w#9w#F4w;oITJ(td{k6-Zc08n~;pobTp#ff7B= z?T{Ls2tlE_7Z?J%P~0(bVD(BqO8iI(^>r1lD(Qr#WO<>Ms+a13`|e+mXi@euM%(V-mLo;ji+zlb9KqBFvJj)I{^7zPHdrI^iG#Y1) zbwqx;Js1MI;GIu%WLb5h>q8f`=Vn&~6-ey9m}l8fa}i(p)|$pxo>C`nQ+c3k`4$WT zUF;Lp{iU-sEq5H6%IW4AIMWGauXbxQe|KTaD@|P52p!cBEGdP=Unt;%Va4 z+3Wa4U*FKuy_Kpf1>^*yh*k{{B%lkPAI&=JbdsWb^+Pvqv|!Ey65kePiF1bJ^NlOo z(lc+f@+Cg(;)YJquerkCf-ZQS=zdGVT2gItcN84aler#{7<_cHs980Yzhi@FjI}yP z@S?^R=*iGt3;|v6?xDNTc6xwU#F`?zIlY;GaW}YX9Lrcs$*sDALoPA)t#r^Hi-;u@Nyweed>V&I1xVPUl%pjGVyF zqE8y#%fhHsj3{r13Qzem1a!fti}pG5^ho6AAxKQo72%vjILnu9WmL8PC?)2Gqs>A! z4;4tj`NABRIf5g@`h+5%=7s_!pbNHeXue&$O1f1y0$G2Y!hB5-5^&x#?c*$YA^G$S zMrUR(WC+FuzC}pCKe+w06#pm)ZT1!gxY8FAaAr2g&1+I2U3}9YEf60w1a!f5w{(0k zWU*u(?St|<>oY5IAputa({H%F$dhh8aYYS6Oc?^Y;ObmD7bh)RGC0~D{j9S?P=N&d z9mTEF6Q!|Dtx%Jxjtl`^=C5^e?znv_Q^%F`zDjlRk#t{lKpyWAf(j&j8$A>k-g%(9 zw77s0wns-w(<9oV#&>%$1a!^5{7Ss>#*NQ#9!H6U34NtYM~qQfMsEZaNOax3N8~5> z=fkQaDdEr{PDR)jzMeoWbp7yi12%du*E?~^^ZJ~?j4Urj^8fxP=N&dRm6y@D(Uv`ktl4GAV31T zV2gvcUYop;Vta+6;V4yr3M8(7=!jpmD&S+cZKh|gyZfGGb212ds5UYLbip6b81(*T2u<-@q+|NKo>khj(gEnm)!K}haOwZ6rci$xZen0eK?1A zNZ3xx>f1#Pa%PGTiadCjA)t#r^9Pq3l0F7J>Nfj^02N47ZFZyIILYK2FRM?>%6ems zwEc(!;w`lhB%o{OS7Ur<;Y7Z-Ll;U&wEk$i!W!-G(i}kr675qR@teqD{I5G*<>$ld zvecruBMKpw3;|v3>%=x_ot`a%3MBeJ?uMIvbl?LT1X1G3 zk^R!mcCFEATW5xVt^@lF@ZjU-{E9OZDe(jymfG7IA)^v!1Qkdaly|`~s4@S3eL5xf z?%gIOZ8kx%uUP`R4qBMw@l&R$mULT3iPl5Qr9FcOq1^2c=uT<>UuzrQ$ME^5-@@Kg zDS2D=MFmHy1*kv*UMKn$rB7!iaVA3BT-bLBbiwx+-Qn-b1<5bm0rlSBl6hZ20$y2; zoAIbr>Xv4Ow)E}75YPqR#~gRvbeHr})e&u7)17(mLIPe{j{6;zFKLFgLDmg;hJY?u zuW;PX>B}U|wXKnPlEBm-kbqZ~u0MC4DFu!7 zkYKO*%+&?b>;9e5dPjSPfG$|ib6mRXE-CGh74n~K&D7_R_~5R>u1;-Lo;h3SeYGy| zisXOX4qe)3%n;B8_vhd^t;&y5{y;0VZ%7LS6-Z>h8-OD-J>2TIDWx&YZnhx9GCQL9 z01bwKF1X(s9S!%cmDHc zhri?-^96w;XpD)Kjmhb<#%O&PcDGRIf_t0NCu)%%Y3A7sZRy;G*~1hPF}OcAn%j#H zEp?zVHV$h;l1*D6!*CsjfG)T*CdVClXF}?{+Mp(D>M?t-|37x*hN%tm z=$FqB&;|F|r{8>eYej6=^hD>UPGt7ehXng2<-}?`vMkgIMH@F`2a z9fZceI>>y77ZUKx&2%RDh)8MLs5CTvsTB{uW(~ht4Rcxa3ofaf*2r7_({REC9Q#wlRvO1#It9mg6biup^or`nV zRx&%+7Wv)uLQsJO?C;QBnmg5(Tt~G=`v&!42l z9MN2#VGaJ$+Y0q7;Sp3I0e3c|BcsJ-cwU39C^O!LA)pKHazyXlPcL!c4Hx9K(iTAl z5^ygxTGuvyirp`IqrH3DF$8qMeUUiM*vd|7XgU;0BQ+6JAOY8m)Ai2vdrG(NL?VZ_ zH-!I3)>%MR*=%9>hyh}Yg4ig6-3i~!RxDJ+F2uw_#Y937?83zE76Y)0Q+8sDpSus1C;zhBrs=~ z`)z0Nu)6dqKx?}h1pvfqX-*=$zwAd$e_XU@*t(cId||FX=s>$pOo z3iCWU3!+j->k98gS@q*#C7%-s%;DzUj2E4)rih8sE#kaFpbGO5}1q5>+_C%ti^NYk~NzgR|r&L-YwsW(}Jwa)@~6#v3r#KS|l*1o_iL*9bk3! zDJ^WGb}9s_Fn^fut64*=jdJZV_MW#&$rDBbYXfjiz&S&$XJ?c!?<%=iAy9>R&;~=< zYs0KX=C3zXory}mGZI+ifTKkggjl^#-ZI;jiBJesVLrFPuzyLY^<49OmU@d?DtX&T zV66szJ_>|czs@Xcsh_K+LZAxs(z!w`cf!1S#n-a1 zUf#_l(Siid01bw~=T6q>Z}q8xM-PQS75YxN6V0kNN7O2I=lo*PR2c2r^AV)m*nuWy}y>7mTq z|A9mc64)JqeaP>cTYI%kmTvbiDg>&OO2>x%wm#N=LCNxrU5Z2t64t75 zl;f;76+%%d6_l^PYGEB_+AD42uPaslk-&ac?D2Zr&YCG~r<}F0vpbMzBJl3VY?Sr|5GpYsuEfWyakVC0dZcK4{!|vC06e-OL0TUn9FhpbC5C z7!3Cx4z{}ASs^_OBnY%1v9e;EIZNr&?D^3D-MkcReK93gTBijm1gcDzye8X>+3~o`Lw)8Bk`$e@syJ76p)&A^S z@%mHyyB`&rBVG#-C1_P}UHZ`XZ~VoOfqx@8c&FO)PlQKm6q5EQ3dyGD--xE+z5YfX zaYTXV-?*h*weHG$4|~vD>ufW}H;X^DH+V)a{#4cAwSo9s{o-_DQ>o{3uKJbFsr{+& z#hIGoPbDsn)9MqfG=kXx_P zETD?D_NR(9ua>mGb!**DZ4;G7mY|z9Uiz9-`%}N0SCiVGYTUfi({{D0tQD`jg=Zc2 zUWQZlmj3edqCFZ{t`~ngLUT=e@u%N1*NYc_yGQgZ(2=(HUnR$Iu0GGa#h)rkJXaTg zsyHu0sY z`Q@o1+HJ8goZDe4m#&}QDfaK!2HWuwlyP(odF_F(sJ$*;Y`EPs^{#GraiggGW>o5D z?olO*^bFV9Kiccby&w{Y(XeY%`?-5>gs35hrq1+oWDFO*whl}E%>G2NVfaAdzu%4jn(Jm)uIT7R zo?CVbt7CU@WscsziL*Rnx(MsE@u{DAb|yMM8zbJAFUmxnO*yH5*_L$b*cu@+H4sO9 zf6XkL-mEKjfBN;A=Z~V`sc9m*PJSlpw*DY*Z|Xw6Av1+<-jd?Pczsu$*Coj7dt?lKp>uW-p!=-+rw)vo$Ld z?V47jmnJXKw^dbZh0?!{I@B+x49^*!N{)D*OLFe3_&K}3v23i~1^j!92DI$e7j4#N z7wec=zmB@}K1W&Aeqt)Iy;DBPnXKY$!;!{1PWhNL4xxm#nz7|qwhmKJ99#EBqd}Orkg*CT981M z-Ls9UW0v&kIvk>-V}zq&XsGc_1C@nK#L^)mc3wH*Itz zh7@0sN`EX+j>nktvOh%*4NnTVvri#VrGBeo>6?B&4-c_3dCg+LY80}y=<`x%o~=v7r-ohd-`)=v=)IyTnp0i;=w@VVGN zbqv=0%!(EyDwNorN(3F&D^r{rFjAfj zoh-Ih3$>yJ39c5aRXzA~&x5aTm^fLitGwvvBt9$-R|r(q8#yU;jA=FBGEuO-l&ju3 zi*0@pR#yHferZ=SD8P~W^dp<8A!6YwJ5k;J*E=@lV$|0I-2r6p zFi?;2O0yt=vk#8C-=)!EQHGk$JD|+3a87kT{X{Y6VMjh{{a;L@wv_v=J$<=4MVJ=N z5);09rdr;Vj}_~FQ0iyyi!Cy46k_1Oh5D>-L<{PjJ2y=lH&vhoiMc%{iTjpc&pP{F zQ#w<+ZlC3cm6P@E*&@kQL^$_bvO6+QQS(db4Pie~ zW&2X`%z1%H9BKJ~YtF7d!>CiZMFdTptgM8QI2Eu=eCj{bl+e_N$IwO&qpQ7=#5k^1 zgzHyS;Wy;#Q6`LDwtOsH7k8E$7ta*8;tHD0#so3OHCDv6%xCVsW4+-1YGTQ@Lnhj) z&#m2Ngp&EtW3fA1px!Ml&4NV!4YNgPsI9rU_aY|ZlS3$<&m+;GPKZLF3RmGAFFGTP z@~=n{j~BL6z7>wwX4?!=!P(V3bQnaVB7RgQ^9$#FOa%3bqT`2Gi>d3D2>bR^MC`ZL=Ja_Ui)>Y< ziml7)o10X;B)D^)@Go7|eCqXOCQP$N(766)ab(MB#e#&xwW%UvoHX~goMNIgdsrTv zEh?+_&!_j)OZ!`>!f(jy@JA8UvB?Dy&>@fBAusI+k%+B4O{_iVVSaMsIFI4hjfteI zLi?|XLZC`L@~ETH)NO1@ac6%UkNz#Dh@hcu%zxJD{5}3OK1HupTr+V5P+!CXpp)8+CuX9yqUr@ zd62oWrJ&?&X;FMk1M|%HdOfmyXCi27%}eJ0N;+E5g2ar#8N!lvu-P+C_plUv6i!Ee z=CoXER?^}hI9r_Z>2FRr?kXR}#fpu^2AZ4RDz>-tQ+#b(+x(?-5&5ab9C5NhU-ORdZZgBH*p7E{Jh2snrABYPG~i-L<;ik;>j3UGvYrn&Ed_|r#|qb9APRO(#?%iJlN z-rpe2f`oc@dxeM5+zeSQp%)q}1gf|{XWHGv>+_0X)IO@3Wv72Rz1wD*1qr{{d17p% z9_DX#^eZ^DYZ&c6RKZgCXL*G{72cKH`Q&UERm|Mpa>wqXxmfAdV!wAubBCf{vO<QK2=TK~HgmPgx(D)l+2K^9 zVFSx}-z}UQ@z;XH<@hyX0FOSlIu^1K~El-s(h@&#H|vMG}*`1a$wvTz0O3M1&QjT){9I*A5AV*8!?gR zaRg1eT+(toe3C+-YS6TG;?SrJ=4(G1G7*zCih}8hdHZ2c^X^;mLabbDDp#`(SpRIl^aFZ3kOXHO--2SQ!<+R zafSWGXL6ezN+$|S`v#^LVZO5Jkpyv}XOO9igRkT&P(nC&GnF2xdxRgqh@!9@8_fIr z=htgGrCE@8*fc?y;-;Cp&uz-Ynvv0TIBKrR`QA{)>x{l>^e1y|kt5Nxqi~98uFq!^ zT9DXjN)%_pFB&J?>7MNyYon>liBjf-@u{`+(!ANIdNVjt^mt#&bZ5UW6A#^nQobfj zZA{I;CcI3|?ll?s;! zO-q$;g#_LUyi4{ll)BgKBIoV=q!6gWv(E3t7s0fzOO#ykA-{5Vkx=ie*gV5%f4VNR z!Z0s|Ko#CS{APGFh&oy#}FZ(K3;(!8VU9 zJKcHSUe#qN&BCu}6<#N!!mx0E%a#L3MW+1d6F=y;3F{jsP?fkaEOhmM*L;2TTlNk?u zmq?(Bqv^zTr-ey1o6lmxqeo3zZ~Ig(ES{0jf`nW52(fbBInS%Jr!jHbrv_axy_Yo( zrBeu0aa5o%1eY-y%dckQVE4vk{gIclwWu!fUb3{AAbOo_E$Y50r{VSIzGN%B$u1-p zT^lk|q6LY8@nglNs`W&{>q&ggzx8iI?F!nFG4ou7Kowqp?!1_xF1^WWM|l#shCAGG zNK7p^N;r9!7TyhV@NuO7QIGaL`XLLROjZa~;q_+^WPk@vE?}VD*I!DsAW?L}aN#n@ zR>VAzJVuS~p0xJ)8)@wLMIlgy*PnkmohndJ{?Bq|Delz(cN`Kg<_{6w7VXtqtnJHV zyckr8QbxX(%Os_^=AZg>Yb`c(3VoYm2R(1L``_~q$Zkx2@`|3L5U9fYn4j7%)o4>z zXG-~Qm1seNb6-V)0}aKT;#v6Y+H9yn&0prAa&yip1gh{pHW;G!m!VE8vQxJSUnE+P z;2d5N(zk@Dkx+}rxZbBMwQFTdOB!;IDtOjVh4-<+;OkzPyxi?*X@fk379=!fabxvtF3bW8__to8lsKkYiD2 zg+LYF`Khtz^e6TlEl6-oy6BOXe_sEjGre5oK$EQ52nkfFPt=#g#VPwL2Xe}3Luf&Q zW736#Pi51v;z@iQk?ZTx;a)#w%+Qk(2~?FDGFH@Vb<$MB=@=6)U53z=wZ&x9&oh*$ zNt{RHehXLs_UuLT0w>7A^|vZJKS-#toNYh!p_v1x$c|-~DFmu;mxFVWpLe71mFwm0 z8yl3}3?w*GUi_Fd&Ge=9W^DgduvXv`;`|Ob+-I5dn zRk+IF{qx(c$k}nJ2}-o@|sz~;0h&wklayQ2`O!h4K!`(D?j)kp5i!|SrBOv%1Gdo#&w;?H=zvO zugjL_uPOwp@UG;ysBd$6J^ZeGnQxz-&5?FjBcVRElP33}{Kq%SX>+0#0#)kWey~{~ zs?e}JZ7iHDqw5V3>*mff-CcV|aP15c9k|T6bf;A~E@~xaAN4RLu0GFC)Xh(+|b&u^OsUC$t|mYF7MeamMKxuNezRT$Nno`-yr<&!LW zKBxH8RTJaFIU7{`?Ra~4PjmYGIz@)I+hsuu5*T65F%#hpX|_jh+E#F^LZFKK+KRm{ zb4|6zec|IMb}xWTpEAn^7jIg)inaLDNfjg1xq`O%+x@iUyH2#{S)jaRx@$oT68H@{ za-eMo`t)w3ta$agLZFH(fs4Q0Pdmjnr|?o%xwrT|3tEuCbI3EYZjI?ihg0&K!!w0I z6<0JDf4iS{jq6LM{KvHLCdqo$Z1JZ*AD#uS{w@CY)cd%wC#|2qRz%IR~+w{=}ddgEGM`XzkOYm%o~kiav-GyQXI$uYjEY~M4T z-cv7)Ko!?q7k_)|g--IN!}g2imf75W2rNjb=jwYoZ|Zn%gM5EHlR}`1tICVNJ@uLe zhEv2EZ)soSz8UvYlaGxTr;q10=e+w(aNTOr!7-n?hppZrFY#wTD&ccj-kH+Ggcc-n z{TwE;e%fmqzWNd0yHCe-rwpTC$Wr4SG$c^f!Y^EGu6)*1yn-GB8B>;9J90mk5;sVB zYVk?s>eeD>qx|Nm$$Av)!iHhAe*0z-+b__979?=@jAu(thf~mnH(IV8trY@Qxbw?v z&L`niaQ=Vhk3Z`ud%{SlJG{*ogi``%{kF(iN+D2%`_a7SJP<*r7LPYuZkAPc!|~dv z-|G3c2>NPSB|=`gD`OymXPt8}0>UZid`@ZWRaGHSh3C*w)Mj=qe-HycHPO&*Z2T*{` z2r>NdLkn7vz+VZTGraFYd81Z~PjlZX1gf}ella>y*4w26jrpESZeC<#MGF%6yJ9e8 ze%Fddk9C(nT4q)VRB`ty@wZd#_Tf!vQrJk@aBwy&T98nGah_kPM{$Fv%IxzU6arP; zMN9nc6#L*vDDCTA*BrkyQtxmi{&bMTtI7SC#NY09OV$sig@&BwX+IX}eV5WKNZ^&_ zm~9$N`KGKj9saaIAyCDArNrMZd}nO>)3zm-JyO~p*84}LS&+ah%ke&I`;ZnBs@aUZ zs1T^){#d*}`KOy;#Wvjgd~g%7;NEk+4_2B53B0mgTZCtQYrUdG{o>yh0#)4SOZ@GM zcrmgqP0sjO)YxQaMGF#mWqF@7T?;xs*C3lU%Bc{j;(le~Z+FKg*}X~I-Bfzla?<;f zrCE?rulZvCIy7TO2Wi<+SRqiweb>a_E|p)Ls*+dh%4FX#r+ieRmw55tG}FgnH}t*` zqS5m)rdHD)3GPE7UZ2`z3caD{X1v>2nR=|MPU3R3VnKrYLWmc4rkjokJ=3Co<2qC< z(Vc!ad}qSHg(~h=A)40SZJI{knJCvqP}VGE$hdKp87)YtGyP>(8&QoBPP8Mwj0Fi) z6-yT?R)r^-3d~N=Z@4~hn^Hs#dvX{#!h#kgaAjdIJa5~PnmZ@UC*g4lfhw*PBkW3E zGWliB!DBpG(}fy+pDSI<9=4zb30zrlhokE~srGVBHrke~5UApMGGax*9n+&-dY|f} zU3ybwou}em&hvV8m^2F#IEUxFqT~H&yG4wjmH?(Er?3K zKk0dUz14yiB=9}Y_2IZP*R>(J&D+nfQwUUX*BB!&SbPa(^{D^+6W`7Fgl6rs@;gB1&3@cd41L?aZ5;GlodzBuZ^I7 zli!XOfB%ia5rAoLGXNd&PGCA&* zXBlJGT$bR$wG{$YxFX};9G)DdS2!D2KFsI9z-z#yNz}w6O^?95?FtLyYS5&N|l4>o4!{l;aNqDl;bcz9XP)lWNg+^$^9PQ==Bg1_tq$h(#R@5FH6$<+ zm~)tSji9i@t;`kXel_FYLX|o%spb|qcgYeo9t$?@qM}hIvuz7k zCDQ^4HK*Z@zpqxgPBA*h^(MQIigB-=!QV~w`*&}uPdQeQ1sj%M09 zTfNfMgK_qreuqm_!cIx|$8#mF^mDbJOX7szJ`^5$cuXzVLz z%Ijke4oLJJaV1+(7Md?o!?o>F#KQ3zDw-D5Ch3Oq0S?P^Bd&z#pgX9?R? zl}tqrTo?I=NpY?GcH@uQ#|8Jq5-(aAjT2^`<8L*(`VP73MI#!r#z1I6f_rU=TZOvU ziteaq7B}FE^(#s=rJLI`DFmvprW^kbb_th(9qLikXD6lF8xq__OS~POGRHfN)owsV08JH|u&WdsGYwDG>{lghy z^FE`t(lxg+NL*y1l5zj;skgh)v-htgT9B}x6XU)h#>3d)$bU?HN?*$J{^owv_v#Ua zKvm7WcG}JpBaJ@OZ!lr|yu4?lG6U)Btep}qNKEH3jM2@F>+@V?V$NlMZF|uOI@_Uv zLZE8r*vwjwGqJ|jK@XXjb-#kvdh-Z+e%Vf{3>_lgat8E0m{D^#LNg>u@l_tCU+ zUvCX9NStIkb6||IXNLPc#@=_&wVvxDDY<4b3lgZ>|0c6$el*Hh^YjxY)-{}~xpMZ) ziTB|av>@?mevJFbpUgvMD1zl0%Mkm zcbWJyeY|#kDEs2_FO_J)>yOvTU?~5hwkXE+^tKIOE091{`}&i#0(BM`dv?^1ywSoc zV(8vzTKajE5iLmIIpn&|TD<5TGmLgOoNPe?Rm~Pm(k@4hHeN08g2#C2GF!yP4Wj$Y zH(1bu1fF%?OTDr|*c9kQ!O=ey0#)zx+H3VEbuk_}`HaW#T<0$0O7^6j_3l~Ff`obn zug*=%~KwuR}NooVEq#GHM}n2oC;@7>inwSl|kCG zz%tY|za+FEfo~;VZSPIea#XBJ_xZhu1gZj>4bvh@?DK51Lx20cdRI&v;HOc$j^zj~ zNZ@;nuX##Kt;gX8w4jlTLZGTq@<{D!wVky>7AEr;?h{?KIh|V4o$I*>El9lGI7VyO z<6Tm*Eqbh4ABPOW_Hq}ByUWp;@V8KvQs9ubXV7S4r;68@xc9xY2#5+IKS#4f3leHA z)*T_wL}Jr0vgy)MAyB2(dtLA@qjbI)N#}}f5okdIYrk@?Wv}9r)nP)n*pbDtjTJ3O1eCScYV;^;JT*ptqVl+W7Uch09$VZ+Ay9>HC4-^X_dz1y zZ63G6Fo>sQv#@DLGEvLRJRr1)&xpk9Vym*J~v9_}ntKlJm=a79F9ahWZ z4T7b4WnYCr6;`n0UCVnTWtGScvf+w8R&MGF$@^(eVMqpZ5Br3`HprVyyY>T^7W zD7~kY9MK|DAy9?&=y=Xh?W)-Jb_A_hH`$E!kXM)8sC~G+#8@NcnZP@rYm2nYEh}FM zA=^tdY&81d`81jxmA1 zg(~iqBkEn=ZXCH;uWaEek80#)3TS(KmG!?ZO@fBVp| zhw{|I&h#}~bG=)0ngt0QkDsV#nMw9)M~(f;>K&oe2vl+B8?o_hkZH%}4?M=V(cfiy zj{gW9)l;Aa2|NqD|G_Jjr|hNo+VaAT1gf|PkCQvThM|8j%P5muk%WN+|z;FTMtzTRQ1T?BHr!H zYC3#X|NWRX|RcihAYlS*X+j9ZrIN+q-2P>_zI}-S8 z@|`%Uv22s81NmS0st~AB{S5K@r%2xw9qDe3n-VQZ;M2ufjn+kSB1d8Oz4A~YP=#I* zj+z{DRyMQsqf5KvBwCQb=by76mOPNADs3qwWw}BqD)7~C?rV#Qa(h@X{pXy?g74SJ zrNxCt_NI%@@058Lch7c-l>G{ZQM!qrJaK-7M72<^wwWv0xZ$9U~lOH939jS8Ktq7bOURR+g??BFh&nxGE01+63U zoYd?qjW=G){8qTNuoXc&rx?#p|14w?TXAObW+QL3^BDf$H%L2=TI3U#--;F_D3g=0 z@3Gr>^{Jl!ak|JlIjDGZ8tneTf&{7(Y#oKy&_~7zRrFfLS?}(W^}JhBq5tk$(1Jv> zh!VnK=x3wh(`P1Hc6uT2`ogt31{RQ?|f7}u#!Tc3g^MxRrk16UK*K?zTd5;%#e}5^Ts`q zj+*7fVL#-BYu*ZhDx58|&vNThc{5v4^6XT@iWVgB%5s(JJ+X4~)Vx%_hnGU23TMk) z8EtZ|UQl|Dz^`_+}sWy{cjZ#5JGRk+^aETI|S#L%x^6mhkf6)i~M zN}ppOqppdpTgp?fg0&O^Rk+?^zv%O(Vtu#zv|&s!D_W3HeE`Ofw>9H1Pcl>~uMnuh z6%zM$T60F8@A^)QhznHeh2M(O>xi(=rc^qKYaib8`gu!w-F>S$IrLK2I7nd4b@psG zyDnE&D=8m&1SkZm)H~7nM~b}TI7S|8?Wf#VNMQAM{&jwIOMdL}NKEpbdmfE%KrNTM5PD_N4~u>cj*}U-Y0v0|t*Cz9oQi)J3G~TvZ4tXgo+o;@rxE+@ z6arP~*WlaWdIN1u)1K62#yyD^B+zTfe(KFGBJ^Gm{g>OM5U4`G2G8Lx*As6FgwpQe zV*ilmz{ zIV?z^3Rjct-xV)J%aQ}RCri8qElA*7f;*qA%qtJP>O+^UhZO=ik79{ZZk>3?%#>p{7 zy3w$5$rdC~h4U`%T~jG4-R|`-dw8s&ID3KFdZs zcV_vlAD19?!h@ozat; zd5u#DRAHV5zZ3m((1ZC6$uE4mL<<{0AkL}oUy1t8 zu13?(q_-e}D$Gka7;^S0Njo!3D(7vZTt$8IQ-+oaDRAD9>-@9$A(1K0rD0YLviWVf$2gG+tU@cnk__#C=$*B;i!aOF< zoV-<$UURj#&%SxBXh8zKRP3$IQ=P7iStTnrE23!-S+)?-Sq6eK2ejByv$6GVJ%y{EYKNFRDebp+o zY)hw)Wg+amh}{-{bc=ESRDHF$bzkoVVW~Ay&It|S9mRSAyU9)H5u+WS{;TJi+F5Sv zfFV-L&Nahl%oJ!rB4y@8&G+I4QDIMJ9^-xBRPL2Jgp$7(lt`e;`sIjrE^4K?yK6BM zbsk2_PsfMQ$5~AzT99abbDXwrXq*@_cL5WD%Vx;KCHs;&-E4(GRml^Fv`;BZ#pxiu zmfoEwQF2oGz7%kOr9=x7?^}-5>Xln90t@Ng1rsk#l?w)TrB3aSDFmvh{{gMVodu$& z>8*YoQ$l4*`7RXZa#f-QiHjRXYojJC6Ei+OXCnXm(NYd;Mq^%QA|z0y_UD`z`bAr( zdC`SfH^L5^I|5_eeKO7vmtK?>c>Q^mTBnDY8d#G~f2&AnK_X{~x1L_c2_m$XUd^g% zx{IP`cohmCxSpwzX6VRH;Y4#3^3unpBt;AMqya!@7G=jQfy)fnxmVHUh`vw~uYSW@pV$J~x^W zT9D`)7UORJvzqX28qH^S+n&Z^KyW?^sM}N_P=()+s|ZeithsN@OHX*6gBBzTjfio- z`#QJS5jcg%c;nwn?2dP$A*Y%u1gbFdkmrdR&01)md^BxgQ>DWy5*QE5S#)mh;@*ye zT;;E^LZAx!v$Fqc+$U|-yJB?KyFQ@>3DuKYvDQ+tZhjdGd95h~sxWSiuep7^=sc@3 zbuL|<(1HYdZu$58-4oIJzgkppK{xLac|T>fbz zKf4d0%IP;N`#4CTf1h^&61vHZ@x#dXWMzdw74ACm4%X^9ve~I%`kA$g2`xzAdYAV< z>Ryxq2fEQhx9%1sP=)(#TnVA)XIXz=14=rStn8~Hf$LrFa8w~Lh4>bt(XMt@{9CBP znG@GlyIz=TJ$@sDFBMVt2a&+_E>~5_Q=Sf$TQ46?cUK5hsWY;^yDC$C+d%pJSUDx5 z3JF~Aaz<5(Ak(^h@=+Ieg+LW%S8H4ml$_xNiIQuXdQf8Rskl?l?f=?;43?$qwHll)Mo~Y<~lE*kb ze6xII?Mm-lHz)+Ea2Cbyk{x@c)4ML@RBEv@TSB6Bi45Xu!XoiHa5;|=Q)sg+a4(QN zUUyOmRN>r?bK;sjlD^vlXy=is0y`UHFG97;@%tNBqe}U!?wB7iVl?tEl6Nzd)_xFwM70*DL|36JQV^}JGSK#tqztD^N$VTG3>Gwrq)Hh z>6Z6)ft|mxzqdu{0{-@t6Kx4-LZ|FANwgrLb^-tPrV#nx=eG|>pdo>(9nbwl&7Q-B zv?TJq8@b1czWRF6{;!iHT9D}flf?PE6GhcQ>zUY8r2yUPRh5?PGARVAtOweNN3H?l zm9*s}pZz2^9cf&ZHhsP*(SpSF)t;hL`bd#&Zh9sH5A#mRf)Z5!lMNw(s@~>i!fA3H z;TK<(iNWJDQr?cPbm?jiLJJZ_!m5ks0UgDUYZaJyzrjG`?&hOm8H*|es>*k5BtFLG z7qeP-Vj}a4C$iF^eAIMYNkR(}&F)tex!+b5z8TsvaeLbXS@DAdZ5UNvAy8#IwXP`F z`GFP@Fp7!p56{ZU6Y|nQ_Oze{iCjr#L~qI_UM(NaM3V>SWX3g*m#h@nwH|xZ<2}Za9EH-;jPo5RDe|R23ljJ~=6LFZ_T(>{ zQ^L!35(!k{J;wXaygzulb_<&QVw6M+68NsVu}!SVx>w(~ z-}*7DYU)HvQUd?aWO5ef4-!E;+qhVVZraKA{B(%q!$PuUlnh z`J%jwwXUc@A0qa}M!z3#pW9}Yn_NavVAWv)El8jjm;KbPRi!pLocwoXl}Mlp{eJ8( zS?nN7Jqn}u6EukyB+&26cggx%(*N*aO71#EAy9>WKaS+skw-q87DO-iY?5d}0`F<= zsMEcg9QZwe5{6$=2vnh`kaI03mz0Cnw59DoG7wsjz}@j_%yFVpbA$@ zyz|qyqkLSmDphM&PFY7Gf%i1e6E}{KqYjj!r)R1v1gda$#-7ytp|Z*2!ZiPbB(xxb z_cV7hOPMU6-^foR*N{S>3g1NR_lX@Q$5hHsHy(QtT9Ckdnxj9raJGKQLNvm^wnCsv zeZz&-YACZjb|J4V1qsZ% zG#G|^Y?9%-OHtF{(h7kpbo+o}T9DP58BbRDLwypX^SCG4%eR+^d=^CZW)xfB9bR>$t*${f9C zhW@Yj^NLh)U=1?%+b7V1M2?K%qSsdLCzSfnI6B&T(`AHN|BsW&$);cb@88e%{}ngg zY;ep}#b=)JmrX2>us(^Eh35V;6rU6=;-$eJ19jrs@ zX0qzXffgkEI?OX=|2*mUaeQ_5wtB`F`G-K&;$rhnOA1W-J;u)XhnC|pJyMDGU8g-F)lF?%@A^GP+?aIMy65~;3A7+_KOoFh?#jyFW87Jg-?}J^ z&p!mJ@Eh_BU~FaUy~rA=1X_^j*>Ij|=7T@SA;$`9kNjo-AyB0r`6u&nO9qF2sRSN5 z9@FS+FOA#JANYM76Z%iLl-)Zll|Ty;CCfS)-JYNLeXjN$;p)t-BmW^#^bJm+AlrE1pWp3B1zr+#i+;kIX|uLpmR;dr-!v@aTwN}vUa z%fSac&JFzY?AV8_6{X#y{~=I?-;md}Ma!6v9R5Y11&Iy0os4Zp|2dAH9Zs8RQ&j30 zNT5nR@|Z%arG3F2SMnsH&$?{igo@J)GSRxAQ!QO`tk)h?=$-ocMv+9V@A7uP z$MEp;p_EGbQwg*nap24hjsN$1j8elr$h${{e+X3JH#8VFOejvCAL^wNXhEV`#Sra& zmQ}yU7urM|E5$nlsug&Va8cU^yvaiDP!dAsaQCD4LI z{^rNDTodLRf4z6-mJ1=*kSYHVsG42wh*oH=<@dXN#H2_%e9c|z@5J6?j%p82&GFPf zXRmQWdo`{}>gV6I=dUrYI!Dv^$X^i~Xh9+-I9W^SZAsGq5_|66MpNw6<*7%71gh{G zvcJ982znfwEA=?gf<(^vqndP^`};Uno*hoDKKuMbph`XRh-Trma(bVCjvT*Xu}S;2 zirEd?uj6RfXb`1ax;d3V3lhJtjrQwY&5!CuZ;#&mhd|Y!D?7ATf!gmeKL038`&N0A zKH`}>!?bLNR;F6gO&qUv>bEfU^Y1(K_ZSaDD$trf9;pOckjTGhxz_sTh~HxjmvyLI ziu*qVs_+|fFS>56$^K>bR01tXEbW@0ja=XM_Za0ecA`yX)BQuBN$1 zJaRlH`7sH`VaEm;S7?1?&&ocj6q`}p@5?54hzS>Y>LI>Hn^*nkTo93I2ybm3ri- ztOm>Tk0bs$a{PwYkxPt;U-T#^{hx2ENK1_ZzrGb(kof)E{`*|DAGy(zz53wPF_1vj zt0V_g#thcqW7NG}!}_F9lGM>g=jV%<1|3sdKpBW31TbX1(X_ zl}exmiBkvLnReyT_dfK0Pi{C^3w>$+4}mKDh8*$R@QtP5_-?5LT9BA=teWZFq@BOV zusphG88x@hKLo1OBcD3i%lfUCTPlG^j>ojsw8|7?AM$&Qc42L-)0<{XCD4Mz@44^q zb5-qUSL<}ocd73yBv7T#VtH=*dyK}((bkZ}VySD3KkEVg9Ny;{SdGVCslOk8{{LU^ z#5I#gSbN82OC19(NW8spz*PUl%T$^puoJ_rMV-6k8!Zt3r0O^$KVo@AP0ZtdARl_=b9thvbBUa6lKyclgh zIV{jTX0{$L+N@?BYqqEE)@JJ+HMAfxZSP3)(@g_YX|4j5=xMF)T;6)1=WtIXP&IR1 zp!wRqG3Ies^lw!^rmEFDs+#qD^Y$KSLBeNAKXbMHqkoT)V`zEn?T((-1`+L(kU$ll z5xyPPcC-fmkFmFot7?h<{*R~_*oqw(V2~os*?WV6fsNguA_f-Hf*6P(h=2iziiskK z0bYZ%X4&1{-HP4$%syU!-!(kH`+Yt9bGd##@3UrRANHO-vu4JxGzNTGtzBJu8NBc? zh4QaQX`OB^0pGn2`p-=q&)aNWXV7*S#Y;7+xIYG$H^SDVhij=qi4emSuva|)EtRpo zH}uCJ@v`Tb=Ls+Q|>EuX?~XvxniKZggn|qjK)K&Tq34 z+Rdx;Z;S^M$KjB-=h&H@8?{uSM8&+dfVV#DZWZ0<-`~K+6LEe5W3K{21%kS!o3DfP zkPkZb?}lGN_YkZ!IDvijKcX$t8e2Hoqc4_qI9%Yn^qIeHhRd5rvNX!6f;w*6I< zmMWCE|7;x$vn&2L#=)#9=#i1nW?cyp2e)vZdbpH8P}iBtTVS9|_g!Bv-rT~o^em$A$fq%|uxBONK5!$f zJU&KO*y*0O*3*sPGXGMMj{lxiEe{s&mUSO$j?wZg3y&z=G4+IQUB#L*RVdN#z$O^C zaZyoH!$MBn-4=xlGVkg-+ZoDK8Ih0+tFBKj3aGcbL=4NOGce=XdtJTo*Ak6EiRCZy zz(2KmQOvLLJVtE542-*?fxwh&0zqBvf8{~y;z~s;eAIdjHw;H7S0Bc{W=fGO)`3N@ zQ@VU!+f>hNuq<1k+sc2RF>fP0j@_!;JH(F@z84~}fssA4+kg^PDAD@K2Kdosj;?^y z8cm%lk$B*CJ?8AVQy{2|){j5cZbV}1HrL?Z>*qo}C^5eDM)0UQ^WPZ7Un4Q#^kIm( z@=hSAi(Xlt9c>ndrv^-AAH0)0dCmKl3&M1^@(Q363-t2(ZMMpNJE^7L&L@O?De-FV2Bw(`(kNmvT~ z3#?%sSIYHT4vxR;!Uq03eXj6(yZ1Q!)cZUOZ+lo!C~+!oB}{5n8FKV7me-qrYrY+0 zYwMJf=x0$EEg|pk?wo`p>~^tk2TMy-p@apjgkjYy{Tt)O-YNL`d>(7%ZYmJeCDuIY zfj1^rtBy0Zak{QHiC}QGH>~94&GJcvweEj@r_V>eYu$zZsBtjDvzq2Qs!(F3^I~{+ z*$LL@YaZu46y5t8;I2B(!jqG_Xp8WbfpA!(JRY$v>w+DE7YiuE>;0TZ;AG5X#Myuf-}40)Qxo!bNB9{3MK3s zBtUbAe)=}#v&fyjap|k-=(}m5&{ot%Tb-{r*xn9*y|BlM%R0a$`!Qf}G!_=|R=hK8 z447{J^E>Sm@prWhCu~xtEuOw(3sj-RtOhe-Z{SqO&|i-=^CfIq)&fr*OVCk*x@evF zK9DUtVCyhbY;>tCP=yk9(`Q2Us44%(IP$s^=I&{NmhrcAl%Ou!3jEH{qzziTDR}t) z9HGBU`?$2UymeQY;Srnm`0J)ds5vF}xpae*N0Z_Bpt1bU@LbahZQi)yKh`6s;fuJt2f8`S! ziKV3mY^gL$=q*t~d~!~Uoq=^jQlamhwE{t1v~Q=;w2q&Fb{|W@o$F_XULPgIKEu*h zLvep2eiCiPESTId96}=&f#s_GQis?W2y>hZi`x}Rv->Q7UH1oq-I^dtqv^de7-y%) zvd4aBA-~dcSlOU2Ty1DCZ@rKS)j#%y^;_)Zf{;vz*)bYE7s>qHw5NYC&Pa)2u1nv+ z>;@U2^cw+t!>#3<`RQO>)fZ~JTgh8Gro&|x2)7zJabm#bV7&Mvl6BlzhCS@E6sErN z2jkJL&bbYlcD(d9C%`_p6%55M--+nz2iEhqDG$TvJghUvj(R{D9wpThJvT2u*v%$ zDe_kmoEX;;_U}R7Rv+s`;_f#+b^JsQ+E#VzMz zf!@{VJ+b-D2sl$^CbUg+;W0W7G{;G!T+lVW4qHCl6Y7**4JPlSq`UDRu%hi+sFXEN ziXS-?`go>6od+?T7~pAv&FV?GbGC_exSS*8bvOq#mb=S$%pGCP%d>EAwTE19T{jq< zcLbdL6khYCITqL?(iN2$luY+K!u(Qa;OMGu^0F6>Fg^G*?9S~WkF@Cln_~|_ZSyXi zaOZFHpL$$n+eg(?!Y*`xo89AKWY`=zX1E7T%#VRF&0}PbLLYFpoe8b3&E$kln2aBb zYr%*UZIq?TG*I6vlhfzPN&WwfP@Kq*kuSfV13enY>0%vYIN?;cA6h5Zf~aJkJ;1M& zN^CzmQ`VMA(f^(>eWu(!B^l~Q&epB?5zUF<_)%CPu?E;be2a`8A8m_XgSt-gWlC@**N(Fe-lpoic}-B_pA@oJ1aSQyjRiAG^5ARk3T^1sX0hgCgg6Ib}x|sQIlfT+WG?-@NsQBI{bPBp{X( zFKd`$i^*MB)moB56-wMGJXT;Cjj6trOP zX1gg=p+x0PUT}QtC*5&BwH_Z|G{eiTwb;`S?gBwwV$JOW&Cob*47+#GS*SU!Q{jrv z@cyVhoYAS@#Da&G`1*MWJ3FqfzsX77`+afqZC)jdj2p|a-%$9zeflxj+raR4($l;34U-rG**t8Gzu=(7!FF? zIh>gOtPP&ppTn}&w^67- zEoJ?u+bC3_L2_Ozpf0iI0nY94WX=(G!=#=w7}yLMa*DE3xS|6+Ugoj>I56C zyRkAlCA^m39~lf@rYj-aIauCa*9}g$SqD%wT}~YD2G>p3!16nhJjT&cHt5{A5+*yp z7nDhx-C%0}RZxFhl<-Nswgd?Y^-s?(`U>qs=9CmDdAJ01KjSv5Qh59<}ozutnhf~UH1BqDgAce0bp-%!!+`tnvM?R`|Nb3b}6`Eo@s*1XTx2khe=( z=zL%goT(Zh&-vXKGF=PdbxS`^RNG{YPb;@X>(q6ELJ9L~5fRUBiP#p`=mBRx86qtg1W?- z%Rbh4*uM=vo1Z4soYuB+q$?!sWw36-SRTXjfh|s|VvbV|&X%b{i5=s-p{{`rvMh#j z;%255-tJ_BflVR>g1Y+nxxl?r2VtqXI*)i~s3m%qcfwb>Ci2%?PO#_Dao8R;K(6=O z395HE4k;T3%HvFW!QLJFpzcX;PFQWU#O}i#uz{14pirWnxeE-he+Yiw^5KNb%(j?p zV2eFd-35ZWXbE{1QhzHn_qWB@oyW*jp+x!!7l>QCvdko4J|XE-5-#pNPD>R^oInTAzC8z}m$>p6N8By&n1_Tna!(2bbbEi3OeXhkU$g_XV4v&s9% zSz+2?7yMmos6bE`Z9|Rb#Rqd#x=T2Hog+|%5?+N4P;~7q$YJI@#*b1KnCma0&BlrX zL0$B_pwWc+JD^!(8+_lPGIKfN3!moaLXhJtX=i5_h<>&YE*t!mtoIIwTWN)mkz0Ys zkeL-$n&F6#-dAT-p+rUl7qFhUANr^KmiUPwm-*Q1MOSQl(}1;X>_=UNuS_+v5n&lTX0cFk@b-vexF9S5b>j-Cqg> zbp_XFm9%gKir}uFy8E~HODhc6?SNxK8wmt;(QCt3XC5`j6y}Qj3^V9x+68{) zr@@dBEv0CKE-?I88k8SpE@=<=!uJac;Nc00#|SuNj_($`qJhs-pb90-8+C?@t(Sq@ zI5$q5+ir~z?T9Aw4}qXAaWv{zm^rTb?1FOJ3XCe0co^6b`r599Gg1CLMjL-~tdr(~ zH6v>X1a;AoFuq6pZ*#OCsl|BDJfI`yv=!*MI6pnY#0J~gI-&97eLxjT&=%p@(L?NT zLX;h@FJ3PY)FqC$&-1gxhturP;LdtsR)!LEzJ>QJM|tCiiPf>&+qOVw#^`L1RdO6y zO&tk#bsc$IT|V3!dwJEsyX)?RG7D{J+z(J zj>q`vGJ7#=Urpnp%kq!hD^te=hR;hCkM6FDYNVFdbG5U#5FT|!M?36 zWvWm@j4{Y@I_4}Hq+6ZrArRDcYwKFb7}Q;NBDDpNvGeG399YU1cK5cCsX_@_C%(>W zK?JTdX`mF@P26wE0%8H#LPhv*sAI}*9wpN38i}2Y&i_MvO{P6YrIfGjmEE0 z1P(bA>5|rcuuMxri5eaGtbWy%x|$FB^BA7C({WiTE%+W#1cJI~yYb!k+C|{gK8Zy; zHx3lOiInJ-mj!82NxJKMy6_l_2S(rr!{Q=aUJv?N)Fobz5x=9b@_?G~?92yYo`cSR z(00>kR)3Gg+Nb+yN82=%sX~cbYg1rrWmPe{lZirs7t&a;~&ky z<=+6hx_@*|bWeb(Zqs1Q#V=C$&_uY|r#~EN|3a!hED7p+wfmM99C=7aG=A&p0&P7mc@!jNovC2LeG|11BWHdYw1Ss;HjssLhPVr3Z?1 zg+)CissyJmfJqzNp!&A6B}&!3e>B#J9HM)$BUw-=(RA$saB^`2EBCWJ#<}XzIHvR{ z=oA(s5Y#2kM@_gk12^n?vu8r_KH&;dVp7W_nEb{CoG%~eF}h5jfxjwQxE{{AEfCa2 z=fe0Z?1ns>%0dTqSw;u0+^#b1dXqmz6ypB|y6yGa+oS5%0tO z)+^a%jS0uB44LiR{u8Ln ztM5YaF_{XlH`J0v!mxb=MptOZd?VffRVXp$XcE|4Oo55ts`D5Dox<_NfFA6}?W+Po zU9{EtP9d+SW7KhDwq)lip>-+oWd8yE6!y^c6404-I^#}D%g<046pWLr&SAAZ zOEIcYqQ>4ds2V;BjwD#{QbjBb#+ScmGK+Sl1%kTh+&#~Y>K}yn{Zd(URzA=S0h&2L zORLdjb_vGmE$6XTd+!VNphV=jOz1GbKeT?>j+e^5PcWvGk7bz~p9=(a(HsPxb7vBY zbIZ(PeqH%J>C0;9-q`^{p2%{cZYAt$)CUZYdB}dt*T9CRw(#q+IvXx!hG1r^I9Bdd zEuab|ntfUgXPjiXYv#p?*>^(mR!}&57w9Jt)V0oNEo|#;4V}W>IFX4V_~g!P)^A6K zP^#{3S@7M=6Iw5K5lYBUmYWuWo19~qo#%R>C85L#Z5CL#c*4r1>L^Yd=U|MVvyi=T zogom^MXwW|m3beGMm=L$Veu~E3Q}Um_mwart0RP3t1;q_1mpSHvCQQZAN?a)A=E{) zNcerXc?8}bJc!+P4c3P2+yL{HN^m&FTVA$yBm8rqG*qqMS)TZN9sD!N44PmM9>cs_ z1b$!Ak9~ZMI;v3OdzlSjc)SL@s-TXlt-TeFWnKC1PAy z7moL4`LG^=zl9i-_=9Cpso|WVxVqxC?wX1RC`Osov_u9 zMriZyAW(%8yEadQw`JzTjdXQ)v9KE*ar%tL_`2mwfuJrrR>ONTRx-W|XoKz6Ed-iP zL*KAzJYI7zXRPjMjkTr~097bK-_`j@(P0UH=vw2xhL;3_x@Zac{#VPL@YXUbT=4u0 zP=yk7R79hxF-(gO-nPc{N);F-s7tK*xrBCTyvP=ZIo1|NqbNbMh4@KkbFJ}H1qYr5 z(L^Aqi;kV~^&c+>p##H0Pw#7a1K}=1&)bSip zg%WqGOojy(TOe?gI_f-lmp3kpsft@ncMAk{1#gdrTi3JU)0d{4U>&>T!Mr+HIdmmZ zg%TfYO@%>e+d)@a&2CF*(i=TL*1!uqD}@r&wK;S)+)K@duBqyivvd9+T&}GJ)?*D7 znn6YLq-d56Ka1|!aQrRLg0fq`3VBwP5VNUXI1j-&UU#6sV=0Ax7In>L3t>r}6T0`S zX7Ex?(E6ZlcLVm!jnCaHQ-uhYRq%zMU;Q~T+I9$WVHk52n_R zfq97&II&{daFkb{VY{UinJSdXY@H0*(bHkAk2<5+a`zx?xAP(U)iy~Ws4H_{3>3sB zL&C4ooUqIpily#9X7}AD%2c7mH~y~f+an%Myc)uZ!FdBP$MZY8mOM%zsB3P_Y`AZf z3G3DkVeo0Le2WpHI{NA|gdJU`*SXxIFN{IJFi!a^qO4oWgu+DOUpsqvBra{n}?a-l}EswEb zQ#V{XsUEg|*aE0R33?Ca?;jcuTpL^qYE5XN&|FuV#VF>zrqB1nJ$q+C@7)a)s!)R7 zUHRI+SzdT5_clClTwfrl%h_cPR0+SJJDQ~CUs>e$!leZU?B&{O3RNgU@5lVqx74mU z!Lki|($QETsB5{yY?yPo3LH(C&0{QE)*B5`W~&U16sk~y-jDhG;Gu4K`~FyV#IlM& zP*>*5nb7g4Ep%Qqc^|ZkU&-owzLTj!33@-~W3M4S@W|*L?A}0;psw;h(_!Ms5YSyvpC9$z z`{3d0z@!$}WvWnu-jDfT?W7(!yX++vZhJ)_sLQw@6r3&R!-b|nJVyLxZ#=l|2D{4- zm!}FP=>1rud7s96`pe(3!5?-B1a)r6L15L+GlkMfYILJ4|zs`?rxGQoE33vB*x7p* zEPTwpyr`64cev!53Ee0~j=M<}t3X^uUELn`7>~ z8ak>_g5Hn$8HerMu-ore7`>uMAgIeEegrhz4{$lnn#Tw>_rRkjEin3lIZ%ZX;=TR7 zr5lzV(+VRdMF<3S8NMC{Pk--$zVYe^q{&$itm@wkbtdb9DwLqTe!h<0#2rVLH$%_% zX9R+}XubxYyPMb%8+$du(=!&+p z>te$RFM)m*b^htM-@tlbM%eE zZFtUh4H&>rG^Z;R=-M2bv(HzuzH~&FIy1p z6EgcLLHjHGFDl6eAA5{t-^ZE?1a;92bAEb6tUEToK7%#UG!Qb$DM9-y{B3)g7VGs~ z$`-y63F;Cv$yb_oz^?(TS-rw)LS8r}Xn%#TAM}?7&P?wk;JndPw7;U!9F9@& z*!`cZ{DFG{L0vRcn!g*g@WAe_eEh27F(LPy612a<^T>9}c)qwY{(c1lL0vRIna?{z zdz|*YDo%X5UdThH1nsYAG}T*3crL3xZZ*gd2%n0UhmSJXZuWc*T>n2l>b)&(6Btnlmpg+gvE zC1~%1_Y?Vg>Lcsh;nN8n1%kS0b}O&Br87#oHW-(`Q^;ba1nsZzeqt+ojJwP8$b2Wc z($AtUnia}N?qZzK!>=tinvtxd3MFWNh4+w8*kRfeJKWK&t&lHDU1Hwrmhny)w8I9g z=gk+gSSdmKD?G+dJABI9>e8x%0zq9g$5W#@eZYzDQ)GqDI^Gj1@m;1;9Wii4Wg#b(5@HtXf-+HfH@N|;o^GtI9gqw2mmSwF ziRvmlR?P*=n*4paN>_QZ!6rC0;jZpYklJr|%Z|k2%BIY5=4w}}P@>PK9C*3vz3%sD zb+zoO3K8SW@GqmT5s6vS;kvR}__Os5-N{ulzXgZ#K zq_A-FYC1|#7o9QVt2y|-IFUzdu^u~Qq2{!N#Z~g)=(K-y4ce(=OBGv0VebAatm?%9 z5>+U%_(U$W+O}S2vSa`!CN-Xcv-xVktA%-5N>EqflRW6YDpR+=g*qB#+a(&C9F2pn zQRRiTuSS;nVEEZXcWk=24wmOkm__5+W*P9=ptMBSyHeu&q0P|RXQD2(x;mq{w&x7& z6NF$_Ax+BH+E*@UsX~c_4x8at`($171hpQ!N6f(C9`~SJ!G3|D zF0tl8zo%luRh3~*^=x7NFF`Z=Y3DdjyfO{ORfDYAQoD&VRVZ9MsNZ?O~u1Xf95oD zra(~Fllv=SRANIgJu-$9^~(hDnYfWG#GsE%6-qRowhp#TuLb?~4dukhLsM{ncnph; z@)Zc`ibz=w6Fpp@_?tRT9hDM@KX>uHUw4;4*X)>^r2ED&1%@h9z%dIY-Y)RG~yt)#Xt4x(~d%t^P&T&7Od!nS0rj zL01KWy1EQm3?DAef_l@`wM$>yPQ-!(!1g?tBTI|-a(Q=rAu4xDKDVH{4obcS_ld83FblyI%L2v#(SgU2aq&V+X47<^%O zhqaud(NTiB8jntdv2&Ngmapo_cB>0xv0V9!Y=&hWpb90PPfrGmL5VP^SRJR1@8E~K zKi+2@>o*bz>S}B;AC6)MbUdcc54t&y#qVt{u{#%|fGU(YW|;&zw~`>WnmH$I_l-uM zg%4QofwKgHy83pA16$ur=n<$A|8y9OnO+xI?)>#Y6-orSCPIfR3&F>@IVYmV_~Fue zci8q?n+1Zp(h}yvu_epEcDb5C2Q|mzyYOS|eES1H6-u;7jt7f73!t%4O->k$8;f7e z&aq{Q`viizUd@bww1_1z`E~_Pc$c1p%}ecM=lHrJs!$?6FAl!rJos&;<|p>uAAkdg zGj^&q-=&Ov7IlT%&V|5+3jpuF<8#}s-2<^WehrIx!*^{V3MGtqJ=#}{0^gBOI05lf z(B6JCgI|3Gg1UAF&4celW<%} z5RF%?W+yW?3Iuf>_%RuH$WcqO}a*Igi}i>^c98K$p;apI78_PBGZL={TVRRw(aq_{wQvU@cv+qsWGP#0Yt z!T0N{9E53W(pb)#DH2sEA+Atpw<{dKO)vzrXTyaZNa#Kz^hwP}IeA|+`^hLcR?%MA zr-Tx;7sXey#zo+d7kyIm+>aO2(O~=o*wLwqOchGdUKGEA+2Ocsd2JTN zcLAaVbh;clc+)o+ArmA!aiYmH>wkh8edbU1a;9TwMJ8}UpO{% z=*8^jo|33S3EJ1@nHR7GDjNLCVfVjo5D4m`Pinq$azY?B>bj0Su9>8x3MFV3 zqDFJ?)nr^ZX*(Mc<|+`>MW57sFN^k5(R*DEt0lPrRVX25vCcg=2_MKinQe@zKu{Nb zQu8s(#Zxe@PcFN^D+#DV37VzL*M^%{u^R2>3Iui0CpFL6o;C%YbUDniUq~>S+KAD1ZwCh=NnX^C@O3=(~epX}ZBs}wMJNv!) zus~23eNyu`;g?f!rO8T`W_1&&LJ6Ap&hPE*r{MPM8(DnYa{@tK^hwRvvFr-Mi1rIu z(9lyr6-tO1@#pFUVdVBjtWMPefuJt>q~_nm?O~XmHI^N7NC2u(g03o1*E@${WPB(a z>fKEssEa?3>TaOkB(3F@LxYQEP? zqv<$dp%EKjs)|e%O3<}gJZJlDIO>kbY}ehp!Wu>DqI>`HEDQd0zR;;HGk$enSO-Z7 zagAa~XMfz=qy~K2b6waOjqZO&^Y3_`<+uqLkQ@aYHt>^H$^L1S5Jx6_AB;tV7B}I+ zz*7Q2T{QoW&-`o&zz-I`q5tq*GF2!+#~=8f1DD6*t$SuH>F@!8pe~w!$5)w-3cxyL zoS0wkW|=CKpyLlb17hJ=OdROLc69hhAgGJx-|=~zQxkCC#mP+3X312c1Ra0iZ$+Q| z(Y19V3vRStAgGJx-|_ds+v71aE|qneu|TE@CFuAAKfm_d7`(A4n@zZzED+R1^Y1j8 zZpq`YQtez;!7fmy3MJ_H1AjkH;XBvwX6(+gAc3GRnt#W4rg-X)r@!rGLl1k(RG|bN zf8g`A2S#D}+83E~l7~Q07tO!pqt2iFaP@@?>|;zFnJSc^;}3lPW4$lF?(vu%39l&- z)J5~}_&CGWQJ6FS0dtH!FHwaObo_zO6%8AKBdtHOu44`h1a;B;JN}H?;ft|(ubJtE zK#3}pprZ*IO*4~Wc&D2Ny^r@32gcRCFuAA-_z;zAWRu)h%sjSM1qW8(EK|-3ovvT zo~oe1^cFHug?=s_f8f2oaf49P#}HjxO%Vv{qIuT*@BHmBT=3>Q^M15i$iSuq9e?0! zcxw$o-^m78E^enlP#4WG=d0+R`rt$MnmJe4CuEXSf{rF=G^Mr;$3|N}vmZ?l2?TY~ zOnKgK|1uhDMcrk^%L|2!cuLUm2aU$gXC!7_dd_l!3Iu|>XvRO!-U%Lyv7;}r{Dfp7 zv!4=l{DGgCUdIm&=iOu5KBWo-b{Q5C_%>`_zH!zF}T?0HZyU#;6e%NqB}kC5#es*@Y&|`%;m&DVdr{Eh`TND z^_l!R*@f5fpwx?Orqa-dy$Ma*gJTyQ%#546GF+)U2>SKYxfQuenn5#MOoS zCdJ6(=JEB<{e~7!+dfnNdp1($8g*|fN>GIoGb*M?M=ta#jEnBxgKXH4; zV|5=$TB`OxzwsT!`F^?bcPVMdpR>Fw2Y;6Sp7>VQ$gu=L6-ro}?$UqK#KRx;*GT=; zKi7j2)b;nAJzZCa5;3UDW9FaJt&*JHOaDz!g%aAH>RA@NfARZmiBeI5y8fQ{*Xg5u ziBkPNq3-)CC;9IwZ^m1l<$~5){b$F! zs#v#~rgw!7uJ->JgAze$BlPrS#Bq*z#=tC;h&)l$bX)N&k(@S(+;UJ-_S7Wqkv+Os%4) zJ4uWF7lM8kCF(36tf$={rk0373F@My{acPd->VhP{+uOhnUX61JqNk$+_CbU#LGI> z`8p(}L=37>!gc&rJ<%bcBtaEQjCQRIYK+U|DC(+STY7BsO$J%OMQ$3h9zTAg%W>HYR+|3bI)l#C_!D~4$73E zcb_0PGyPxD8h-4xqV{iYT`v0ob z|NZ=+F8b^eW6v^uUU-o_y1Id z64RpF>{hj+ppr2tL0$B3{;%gxTOA2559+@tLA(`5ndyJ;J;*@*d!p{omnEO)f4NQ}tJ?QQs!=f8Rx^LJ6Z@$$I+7;YKB5P=dPXvr8-$RVZOs zF-{+&a9G_EF(^S@^a&@%pnXyLED3DBS|8(c1IrRIs6vUqr>h=ctL`B1=jTuBQi8f3 z*{#vXD4k+ef}qc+yFnAA?)@4Uo(hYTX>U-BK^019ET>8t4jl?hT~qg`rlq0;b#e&Cdmp{^wi(T63yU;_u0~hvuvMz5W+LU4gdw(wI8M1(iCeSud2J3MKxY zv}^cJ@Bf9MF5lgorLIeA6h1vas02Y3O8h;$*1EHry+cby3F_)MJy#lfAffP~i<*B$ z3EG=*wz{ZQwUM(^gnrP!z`yr)+C!p5Ro|<6dg1tzeFjQU*WYtYr#3J7bfyX=9+_9t ze@oJSm+WOwg1Y{m`P!+Dn&b87=g(g)RVXp4WfOgjg!?6X0Fa z?5t5T1|_KLzk9Fr5t1YNBn#-Ids(cYOzP=yloJdOV*sO!IbeUCE}TK2kF zqvhNcucg1|&!?ZVm!+{g_z9SNw(I+A{kKK^{m*xoDwO!|H(^RpS74=z`oG$?o8FX& zK^02SH*d8>>d&82sV5Dq|M#TX5czklo%-J!?;kAFSs+zcfBq0up#(i$=a2s{K^00A zUO1qSSN2B#65m8hP#4XC6=MwHr$DR!GH|T7a2^k(MS?0cPllfP^WOw@{dcMQ&HhuW zpk2LXdOi*aVPowapiX{< zG9Aai5tk{M^=MGAoSzf--(&hzp+vKPR!RL`78G2a9ay4Nl%Ou!B4RzLLJ9wSYo&~_ zW`)=7CY6Xm3F@NlCdQyoXL>>&ea?#nRVYDsg!*rSx@aF&B&b3Ox@XmY6Vyd}&LUB? zY>)oF6o1A;F5PXp{$AViaZ4GN9Mu1Nvk@i#2B|`c2M%lW^uhmY41g+;`~*R@1gnd! z{~u#eBI(wjQwEc_m;5`YrJ}A?;fMA0IAT=tSxXg4yt=hfU&6QiBpI=-C_!EHIWH1a zp~R7Uf6hL{swKztDM4Md_aVk82OIP?ESKjdKTBSuFME!wiA=AoNKl0mJAN+H)2sMw z=6@5^MX$d|(DA)}9hI z`Sbjs3MC%b?5K}Xsa3iEg`lnjXaCGVRBvDMsYVq_9NIHNA7hqL$+;p*P?zlwUpvzq1GW{-yHKz(CDtn~r>FvFnl&Co+sEdAM#2B=^Alf4N|cHc)J0oFj6oGjY^fiokI`*l$+1^TP#0}CzRTvJ z-ilkV8hCZJEqFFakZST%%d`1u)_rUerE2^Xc=gQtjN&+cwu}!vxMd^p9eeY_l@)H~ zpm661nLdT-(>ZWVj^yCwtJ~}_ir2i{?WszynN{G<*=(VoK%Z*s#;%pjJSORmxlZK7 z`Eve>Y1x`!aqNanpO*CLY*;T-+I%QNxAj&CC%mqAP%`@(!>Y6v3LVX)qnu{1=19S1 z<8{C6)p5}(->ntzku@Q3o3ld4Tj^-+zQg0CKBJO!M=Hc|VtQ?J<<&b^+}ZUbj4yJO zEEk@DCVUOvl@?Bt=c8kAseX0&&8DtW+CK=swv{>Y;;6ZDVyP=08vF!)Pw6a88&Xm{aP4l-=1~TFZBSs&gktTBh-r62E2fQ?HM3LN~@*>2%H> zzs@&hRG~!1TX*S7rA^Q!R-Fy_HmjYoaI7s(tXf|nsEd}6uRe1(SBBZ~{Y4HmWK^NV zvs)h0`tE%Ht6}Q-&M70!m1z@Quz8)@0zqA3&G`vOO44t8G{4kNhf&$>~ zpq_|OySbxsvd{`=Wz^#<XiUgp~UGc4$|hUXJD1ql$R>0z+72*M~h#jLB4M2C{^ry4tnsD&Ck#6CM`LB1jfe5JjP?Kg(CHkaE;Y&EmbHn zb&rE|^z%9RbxZ9n?Kp3x{3zv$Gwh>XDM4Md4f*QjDi%u9Bnj6KA5cUUO6>l}K^pbq z9K2Yl&ey)EW}%dc=hvfCT^%K;i(XlcrnhXNe6A^B)eK9a=Cp)eZ5*ZDPtU>%4^JK= z+{0QqX6k}@BYQ|xp~N7g9#YeThhX>+^&O|)QVXSb11&#iBtsymD|@e_G^)ZG2w1J| z0kNXHrSj6#3HvLJWZ%b5(ypB2;QnBMoN&WQ`f=enbd4S$XMO4^m9McM-dFMFL|I2m zrE@=LoR(cdP$-d6>?k!4It^YgdvM}G1si46M@RGtxhT=kqAprOe!}W%zWY;{D?awx zFHwaOJ+C@SXZM_j5tr35%l26oO0O(e+}LEdKv0)h^KnZpm6Q7%@L0KaLd|Ij^QyT> zri%|joV}XSm^G%YvLnzIKg4Kds!*b_Mpb`+^m#6cWp7--&Y{0t6dit zsrB505HUlY?OS`?R@sC+uk>3#pBR zjvSS#LWzG?4wn3`t%Q1))tx*mthG_B&FWyV&t-w2uD26qDJdf#>J_Rnww|z7Uful3 zuGTKElwUVYYOhO%?zz+DO{VRo@|Bjt*e0{&g;(6A^8?di;5Ie4Hng>kVpO&?_RlS? zP-XvSH_5BxDtNvzN~WL0R|$pLDB};5L-#E|1cegb_1vWU&g)?2sp&jMmuP!sN|o|> ze_*jdP#3L}Mzb=If3K=k#lsC=%2c65{x?PP__7XChN&^mrQ0Y&oogbrz9$gWCAQVb z6l>-5t52-vJR^m+53TLI3LT^#{6y$k`V*ns7T75b?>}V=OB*Rvp~ST%KGKohzqe5)W(@ z)3p8UMDqp$L0zLKR9(J>@42 zf8qiSf2yTw8{1kr+b@mjJZ%Jmy3UO5#P2@6pjVO_<7^?{3vg?HwkXq8Daz|2-F;RM zV%EgV&uzL$pVH01%Q;>SdF(F@u4@cFezBZ*9c`xE+3nAcu5wnWLWy#zou!@pbXxcA z>Ko**&z6eknJ~84uB|{&7cC(_57M}m($jw)+i}rOp$a8FHRvo&E$#dac zg$r3`w5>o;mss;h%}kZxdtPjCu~w)#t<#L}U8I1k)gkCnJdfe)Z?1THJF*rDP6|~h zu|IX3)Zxrc-Nw;s>n_^dT*(eHWl2-r1cJJj=XgmjTR!Q!`KdYdRX><0#wq{6_Whnp zhX-AyMdpii8m9!g^MS6C%fppAn-&SO_4hgDI?z0 zVtpRF3j}qEHP?2mue?9KNoVNXO`&-t%O-V`<``7gna)cnvEHEj@utd)>6>)E-W?U1 zt40YruE9?MU)fSgI_w5b8@nr1p#*J1zJ6hG*kL&>5-mwY1 z=C`(+C_Ue;hc>n%L0$C9@?8XD2PsP%8^iGph6p{qHDEliev51yk7{2I+;m^k!P z0w)?n%*e_LRVYE%oA4*j)o5khT1%acbvcPCmh)aN}1e*?ipw=}DE!U_8NFe)l6=dRVC@jQp*>e>^%EuJrHb!?xwO)>4HM zmmjW^UiWDUtJBpO_b!DiJ;x7Yy_dYuQG&X*FU^*&SFR0hr>QY=GQyQ1w!W-;Lj#}+ zC9dYJmu9|f2r0H6oQSpwSNy{LnLMZ-P=ylB+N_iIcWwoPOw_eYalbk5G z6-xMDTrF*Cslf2J>Kseynqi9j+YomD<3OMUby*v&l@7RDL(LF3PI!$CQ9ewHVPU7U zA)-c>wCjQ=obKo%A5^j=+h-o&lk6hH;+4{<@_pgyY_%Sq%R`i))H%%BYb8*H62BU+ zmckuf;mI;}g#NKlh*EB5Jc~~-6$t90CFHq1OG1^t$0J!_b~sRl5^Y1*NQ1B2g3B^> z9%uQ5P$j%v1gq9_tUyqgSo0~~ARy@Bi3NTTG+G@4IGGo$q;8326`P$92ot^j;#JYA_yl{4|pXr>03U zT}HzXcMI99!4j#~jwr}Wv*ASRNx_QTVm1p}V!)_E34=XpQr&%{z$ev$6GNH=DNp(* zGlQ{LffCe3OUU2PqkJC(af_wX-2!0q@fMu;H6cuyHmetV@Usj{9+xb!N>jmg zLtXiJT8gBbKLxy4L-|qTWa;3oInXDgDJRyy2vzKU4PYa_m19()#L4R^(zA(EARxOD zCn~aF<&D`a7H#kiC_!DcgnW*QUU!#kDx`BsWTV-SioZ{FVxX z3lpU`=lmhRZy8y4Gf~1)Cj3}kkrPJcqm(&mrP$@`xj z&+>$>HkYMO5sA{rgkey&@pV26&^$L<@z-6@&53L$D3qu;Fi}eV(HBbBQfD)&eVU=H ztFnt<#7tNES=2>aglA#pMJsI@^njH^@?EJyiGbdT(!^=~pk=liV_symk{vPwx*YGM zqXc!)cH^aL7p=^n+)`&9u}Y{pEn%u{l9YYk1)kqhPis#7F+-W%Z~)}rO_iuZiA0Bm zQmFzD`0^Y$VH-I^S$(0M>wdr60zqA0sw|Z9X0?S^_4aXMRGUcUK{-F|#vj&l{Y{Id z(9m+wymO{Br$wr?!MiT_@5qs!TP~8kJGBO%7=v*KRBSvB8W=c-Q9``Sl9)7W(-s;6uY~-JN~or zx$pa!@6+|I|Gn1xuKjo%KjxY%&zU)AX4!0VE42b+nZ{kf-yV#oi^~>e<$9PZ1iJ7D zbvn1`csl(=C4IicVj3z)blEYBG_a|`rmx#6%Xs}Zo)(<(#JzGY6NNyRTJ!MPv9$i$ zj{0m5qSPGg)W>WgIX3B)p~L0rvW%sr}Co#!nl8{gbEL}Ua?Vt1by z+U8)2dySG^6arm|cFTzF>@Gt+lL3;jSQ$feirO3MOzxmLG+0aC$9WjCOH?7Z>L!!V z!v+}ME@@2Ov|K~R`fM@`98_Hr6???cs(0RIo`~(Dp@KwC@0H~9z}be)?Yt$?&pDQU z>(`7mG@%NCE<8fH?~+Xn^_jaou%dDc|+y}je3KEHr z*ODNsCI90qpk;H2?TMyr(xiH_j8unUde-t2 zKNJ{lKn00=T^5k96C1MhyfW4f>qSEo-trNVZVG{}J5v{s-a8unkGTKdn=ZL#Es95a zD|s@Q8{-_CM9RevWh?W_=+sc7T72EwA!0);>qW_ZZwyq7P18d*a0dQqQY#txo0JVLqF;(~NhPqU^XX3W2URo5qop<-^&~z-U>IMzwHkd`>1q z1qt#5J_hKTF$OFx+lwUo6?oiQfA_k{t!b2iN|rHNqv`D zY<&e|4A*x~C;BO(h}e{PLm|+WP+};F+MCM8j4+dtWt}DgwDijSA}uY4p@PKh0|}(} zm?dmf)$g*5$E7;basG1Gw?5|-0$mL)hmezZ(%JGYWn>wznslM3qYH_<9kLlJNK8wN zCr^BnS*_?|lIWV`Lrd)|BXZ`YD+IcBJsV1DOxVtxtJjhQ>ElZm^e--!S*~HIAVJ0_ zk{Tj~t*&ZpK^D5=P0ezxMb(9a6arnAFNTp#>D!r4uSSv(wK~%DlBL9`3auF`NMv*# zLz-?&Vg8ql{S0%%degZPrP%l(Pc_V%!(LT2gRW9m5Bj~z7@5EIRYL^{>|vE_Ayo*b zTTO1W;)UKQ1iEJ0E+Ls?4jJ^(#!<_wLEY%vNoM@);$IpnNL<}FlPv6Y(qOwdK@uDL z2h$a1_PmeVBZWYhZPp@Ew0u4`(>GEQBd>L%S8i+ks?U236(rt_n?XtyDaa}&#z~^a z;$ZrEaVR%;yP^>2n*VD7aqVc!iUb+=`t^0`PQR>)<%`9A4HYD8zD^@cuGVGM=8lqt zNDQX;gJ<#n^r%9htH7gqgx~gLqsALY!#zB@)0|&R`S_Z-8Y)Ow+f5}Et$mpD0pr;{ z{JAIff4GU?-@i>E&~HKmqf&wZZx{mKK{upLqi3LvNn^+h`NJV@$bf( z$35*q%@-WyE<+b91iHo*oJBgx9cj0fHRc+KgI#H@p!0la@l_fsNO(M)KvMUPWAmF0 zkVM^fK{O-l7WeL!pb+TVI($00erqyIo@LCkC|^2|zWDi^?{yoep@PJ+ zMIT9QY}kzse(;{#y=bWr=&JH)3UN%F%lzAQmc-C&ezaL56Va$fdkqyNu7r#sWtJ^v zr|JhuqA(Ajja!(B+;t@s0$o!gCz0h9m$G-mjJY_AygSnh76nB>ud*5{NK|r7A|1@u zvJ&OGNMc13KU&bapxA4bNsvI-t~wLQhJ&lvHyN+WogH>|q?0cf7f-kBC#WFd-#3no z@3DbZoN7F(_K!PJvj)Y)7Y8SWKvz)3apc2{wXDEGcS)G^Z%>OXEF+3m&=XXU@Y+9; zSmwxlhV>qjm{HT0u5D0KoOs~pjs&{YH=Gl1M~`;476W>YaYqG-A2WxO`=ht9L352+ zVR4VV>Ar3@V*P9x0mIu8UHEpDtJd9ZPj{9q%l4EjLva)dGmP=wC9|W$+fdWwF|7Oj z^2&G=5^5fD&9Dx1oXH*b`ezA+Ko`EdWL%Qlh7O1@YcelpbOt!vaMFV9d($Q$Qw2&L{UK^`%V&RQrM9lDLq=2QQ^HW-8On2KWP6&Ljqm+ z?viDc@u7A-SMhycbrcmOV$u`Hf+v0~I@tKdInulnomOrqFRZ_-A%QM@cgcRAu|9P4 z!Tr3e{)vVP5@%dv$*yf9*q5couR+UazI5x%vphZJs6wC%-(7NdE=M1F@y0E_Bj==s z3KI6?N047vrm%b$jo-m;XFAdgcVF`D9vc(_UHI;jeXqsa(c-he^Gd5WYp5VmcxNP; zSalIgwKnE>4g1`lzATw0=5-RFyNV5)wmY z8IH5t(Iy9rijsc*3V|+scj0HQwVh7yGy5ws?vhqomf$nv9-}qK_cJ7z9ePo4mPQm@%z!OXDj+ErlJTvc7Py( zE_`>%uXBb6HSXg2^$R1YAo2A|C^@rcFRSX+YYY8Wt;z~@7#P;x> z8EnqD z^0JIQ&05gPk1LC>Q%)%ay0GmdSNSj8oW4u0Axar;Ds3DjFxOq~$5Of#?R>O?IM?)@ zLZA!VaB?(!s0StGtBH55OgSn@UWzc+z?{RYc@l zOO6T>IQKwi#FuG755KP@8b#?80$tdqmf1T|divs7Z4olof}?^2&cKkP$SVl-m|a`M z6o06+w$X)s19I=07cMmMOnosycT4F5KmzBq=yYXTyVAj}8;DY5i$b7F?Zs(q*O1nA zauK%|2xSHj66&0v{y*zbM_;|z|6!{_pbKa7=yX5KG)gX&VYzMVP@EHmGoLVika?C- z&a}eEB=#V;5mgjeX-drydV7G-CX;TmT61bE1iCPO(CMD{b*5esCj94`1{4(}Fw07( z^K_u}N*#Odc)o^0pbO&%ncv>XmDY3Bc(j{6MFk1WTa(e!i>6dpsy{E2RZ$_(h4F(N zC8O^2X^AAB6IP9)f&^yo$-88AbJ~2@0^Wv}RtR)q{2<$$&V(*MmCWauT2oYzzzMvs0kDK3rOs-c1eW_-)h4BCvI>1i#(icD7s zbYc7;`>(w9)G?=$=s$3(h6)mDMttOZjV>)(O?X;#RtR)q{2+S`9NlQyTQ$XiI_))7 zkWl9vbWhh)_wuzx2mg`^fi8?6WIwfw3;n9EF9u&Jtf7Jg&Y_SwcUf-q{hoT_z~FR( z1iCPO(CMZoJ5e8(#-iSWH3StTa3+ad`?S9+{n@Ia7?)H`A<%{KgPc7urwR4;b`(WV ze$=Ca1kTNoF-{IiDpLZjSgPQL;_t-qt}!CgFYFmIvUFe9~etRCpP5{)5{uA zK>{;2<($!S33PJV4{XlhjrzT}HW8A%%uugFJ8f0gMl$1IilOFoe{F54O(bo?ZbPoC zu@|RO<#-w$R*Yw#_9LhufpwDo4DI5n%b`-d$plY566kuAypaT-&oX2gjO~wph2m-b ztL1o;FdIE8NZ?tQGkAI=(DqaBu$+XbyqAHOH0yl?mVvVqRyl5aVv^m>^z)h zRGFipf`mGcexh|W{ppa)s(u@z5a`ZUZ8a3l=_Tv2zCk1{=K6&#_MNMtg2Y$< zWOCds!!R<}*ju|`&~V!5MMdtmJxU?aWj!^8ynOZ2aC=QpN!U*tMng(E@G!f{8Y)Pn zoLogVAOB|Pmex-aW&1_Z>`J~od|G#fKv$JsYl(kA88$1`xG%uCc@cEW%WyvJSG0x- z62s4~Ahn_^vXITjwI*Mch@{?wM)P4kHHAQzYwl|DB)k!`KV!_mp4nz7tulWaFTlEJ zs337HW*NzB? z`$t)5s30-2_(HNUY6$xnXRP_4TZ8B{>wVl~#BzcJy6&7=M7A{@&H_6d=cSG+J%E;K zc$g0QOam$pq~i}~@$avyDg?SZXU``-abwuE2xHGgEw_I3 za9A$i_oWL#1&Q>K*(9XgRQAf$_`cdcyFcwy^b~J4Vvai!=yG~ChpdR2#GaQj_9360 z5Kf~yUFAEMN9$2R!h6RIvgPq?mKJL4+4l19M>pD@(>Nl_!uuSNpQl$o6Y9 zS;hXC_P{3E??+1ouPt6Or=Src;r%6R2Yxy(7t{&tkg+9y~TEgKv!nWWKwU# zboRJqNl8!z40S2y~6yJc;;p zn#iX4n@Ykkq(3eFFq`-H+{#cvA}Dbj5#{Ey(65$~*xNONW_3;F8$u>11iDIWoJ=Zb z$Fga&9>}rnuFD70ssnfPK8MCLRFDXiyRLMeIE`(2V_X^U@UAFoJ8?d*zwM_133T<) zrjaWn`>+9i#?>!e_eRh{D^huZ@RAG_Bp#+rB&`;XX1<5dNWx}JG;L5}3b!jd(H#kN zZMT_4T6Af{mcLjpi2;F;wCRf#+_S;iOjM9K(sC-P+M++}8oo^uX6K{ntIC;iDm`o6QMaV=bzz{=u`cW$ZVEg`X?&k{1}SS7Zoy1gu8M(<&?>zZW#sd7h!Ko{mr z$xIF+-=ePtZ_*-Hj|vj`J1is7zpUBzyquy_E#qk)({G04aV0dI8HDTbV7wx;4JX7> zT~a7BKifn@1qqBLZPQUSPOHg>7Ok$t>PTQLA?E^I8$}DWYQ|Sb-z50A(1r1} zPWSZ22-^LJALrJElsQpIU@Rfaa2QFw?+@Vjwr(K!x6p-ijAYH7qG|DuNxWW%>jV`f zFfx$6oPDBcm8z3?id9dAKo`#Jk$D+1TB@hb<%1_IC8!{Qk%3M(c}Wy)J9hz3sC!V4 z1iEl;j(q#98b)m|t>!g9)F-GQfsujya+*d`tFNng=_d~}kw6#Dw2{w;X#|a#v57xx zSVfNt5*SO!{KTvXx}tL`_bOV7A%QNO-y$=%WVCc=`+JX1<^cXQ;@T_s0j*9d~#0ke^=4d>kY&GLZWTXAGqd<=6Axx>SWg7tRZjxdy?5 z>C75?`0iV?7%E6$WFXtMmJzgLw{_fZWR^mp3uku7{qDvNrbQ<18z{o(> z{6PdA_D#;)u6maAvC~c3y-uss?35w0%Hl;*H=1<#yy?Q&0Zf<2z05l zARfi9dQAfxcN!)eB>$^3hj8Oq!Y zBrukcb2F;N(rq!Gd|%IJ%6tQK;k*Eum(hI`onR5hb#-qVP(cDC1NlTfh@-CgD)O}E zNAyUb3$yWcx@Jvc=^$HA{_IWJkIZ@P!*k`@X8+AyKo{oI%dhi_ zSep8+5zjV>QD!0_fsujSBe!!L?e|W{!(Tp72y|fSNCzzjjz1G#4)-Tn3|ODvbE5a`0zy&S2&(U&$2HsK9c9oJAn0y6|cZrowB&`?1FGX&)`Xflv4`Vqu^!qzGTy0CRGM-+qmQrDM} zJoLg=4HYCXLr}Kp9R^T+`6+zQ>bVMmE^OV)QREHbw0i7(P7+sWs33tEg2t@-{-BM1?>Xw(e#7V|p0U7_e`qCZN8N5LM&I*ApY~9Q8DDzM{ zspAno(5{b$3KEzhsMF~;gi(uor+BeAJB2_Ow(gBNslDmx*;i#|zk`Mf5||+<=OQod zLx;!QU3L1h0wN#p7GX$=MyB*g{^zJ z)?{iA`lp^EW{LbIJ%g96mUD&#papL~2)ctEdQSsBZ3{;T7d_TFa+TI{q$mJLBlV;73 zKo_>|nh-+_o@R^+ofi7&_>vUNcy3^;^e{ys4y$ls3FsodyT35RdjlFb_ z2kqak5a`0zz1%~3PB7gw@(n+_Vh=+F3Cxa{eHjc$d}P6S3V|+c-OKO!vEHDJLF`K~ox6arn?x|d()d!f`W-!0yue*!}V37oAUuX(}% zs_UK2Cs#OWKmuLZx|h37zYn7ue6REOy3YnwkiZ!#a=!D}0n~D1HZL}Sxg&utY~9OM zhjPQ{{jeMSM$)@XRFJ@VGjeC^kbZP}z*)ZFKy^J5=u&$P@}>8Y^MoJri?u9$0lNW=$Gu%czaBtLUGZ~g>Zy5FQzTEZZ z*w~8H`Cw~t|Hx#+h-2Pl-0GPu*e+=6gX92mt>jc@T+O&^8*lO?brySWA1G(hRc~!a z-4-?%g+rzrP(fmPT0e6Az*si^N-s%l>1ju6^=&SGMSN2TblFmG(rEuIHlw7Gh`3ji zzAD&EG+0%Vp@KxM%(kS~&DpGHnU#|8wXQ>pr4jMv=_F-sTwD)VB~H9*NmDW^iyxD2 z7;pt;oL98)faQYCr;A zSSOj$xY&i3&(}!sTa6hiNZ_nAxwhe~`qcc1o4A(cs1WEx(XXdl|UD+NG#`Cp7W#TPK87blj;VX&xiBXruLsneAl*OdXL`n?9RC7 zOQ#nvAy(=q8Bjq2=gP?(uU5Wv_RA8Y#fF&*fiAqV@{4n#7q#(x!yn{Na$jY(guL*y zWfre`>+vbVxrB1%mi*2F!Fb#Ix%Ufre z5mb=CUPBp$+YF#UCw;wIzdzN2rctnp168OfD@AhwfsPDD= zyhTkmR}2`p!@Ybg460pM8m=KBtecs+ZmpoF|O)d8ZfOL>BDR4DU)Acew6* zEsoZ+zryakdP-110%z*#bXG;<=;50-+{Jm1LZAzeP^as8E{6ISYQpoS3W5p}I8#?< z73UvCquqn~^e;;l0$pm&Yb;ElQD$arW3Q9Me$!@>xXh5zynu^d|8*1b-BToUnopP> z>nC#!1}4yqQYI{6{1v4hNQ6J$MAnQbnYr>!e|fIv&5EO^KgAeKqwJJ<+jyq)u?=MN z)_Iv1O?FBmduTlE>^zhW=x(N=f`ochyX2Y!*<0=#T3O{&2y|KB+(-%z3e2o!vq+Y4 zpn+UF!Tpn=bGK&%6(rPpbRLvQgG!WUjrxWu-$DHL+3<7{S}$|o`{~o9Wg)u-qET`W&#>Gh1Kw=9eE$PPJrRFFtLCo?Xp zRQ=ykEgp~{d%Ui*{U^Ir7yTiu8ei#li^0@UH9z`Q%QU1u*2Gf+!d-$jc(aJSP!nMd+a>?iY|L&`L$0BHUku>f! zXQV=)3$MRiJ0YnZ9h7D*cBbvmz^^dIL3o{H+aS0#y_`>GO(ujZ*8_>qbH|fCOZ)t< z=C`l;P@AJ=MVp%e3V|-Xdvv;XXYJ{;jhe7;QXvx~*4bkRkj2}^s-kJt|1- z89a`dS%v?vjAlt5G`yLuh{&v<5a`0QAmftDL3CcPU;N$JL_Izecvs?mEHlXyLa6Bd zl6Tm!L5UfVz&liq#4QY`+Nvvju>WU;Ko>>>a;01Ifwc72!`xr@NskH=>b?6qUnC7$ zw~{Artf53p=)!NXT;<<6ny%S9gt z(Z0RQ@ivvhm2WK)_y(6VKxZY;EV)|NPK%WafiC>c%M9$AiL}|v!t7$w0wn@K0$X~& zzf-^ef0BsKKbtk7zu%lL*XOfd`$oz-h@_v`ww@Tmn zX1xAC@9$qpqNwu;{XhGphL6qGKg^jg-)!);?!ss5KFp7mNo#LcgH%Fa`% zB>VR79sa6KKB#Y4RQCr06(kPdNh4i$?fHKY=)xn!<4O{!AmM*uBWe70^dHJV0$qQv zIiAr4eI}FpJmCLvcJaI;@wWaPlJ=A4(P}-AK-Y@k&HAMEet)P3Do7ZX&LtDSx&NUI zB+xbV$}auue)>O@f%hohyLhyJuLlyv%tw*1?Z&-v)c=wM{w;LjJ&jC~(5wsVugJa5 zjsH5a&s6>KnZI|Zte!d9{h$3PRbrOI6vIEezZbbbjJ5k7n@8tl`5X3>PX9yAQ9)u! z|DNn={O_k(EdvR3O`9FSzRRpFbQ^ysiJy&UF@4Jxc}m3(6WRN7zn|LehBbzNcGgBJ zN%WYqk*%3IHSc&0ms8p855J$mcjpfo{@J%&B~U>kxnU|RWPkb(HAezn&D^-*pMA^K zGFI*1%x+cs9Xq#qoX+-5ADC%$+-z~o;NZP5@3%^zg2btlzjvlZxAAw9!1v&;Elb&& zE5D<@zrPbvL1K#i3g$4;iv8bZAc3y%nZjUqx47Z|CQv~lw$56%DEgnM?>|nyui$T? z>+X}aEXeW2AIiWl4t^P)=AXtoyLbLWJy1bnS+zxmfA$pr@0g5d7YTG#@*l@4zYF_A z8TkGf^u68#)$llL?DgzZHGPB$3 z2PSO&Lm5b*%co2&azeJT{_lF=`xW22qk7+R|7VY0q>=>Q)%U-yXPcX@&%49%DNqSi zkf3w}Te0JxmhgX!`b41%-!cFBjn@MeBr0^+%+9=M`G;o^33TC`Pc7r+_(J-B_7q;S z#*#SIT%C7D@l2}(DoA8&cI4^jKV1(b(DnB#h+h``;>2uUV3^Qr@*nOJRFGI7GoIb_ z3Hifaf&{wo8?4qG6(pM88_B{K{3&KY0$uo}R?EPz%;_RqSb$r*y-}3h_4k}2L zXqnE&`hId3{e08aGLS&m{eTk&=O@kc;%k*a1&PLW(^=E_!hg6PNT3V9+G-i7AW`7a zM&@WS<_~2cfi8?b)G}_A&D1C4U(byHI(__5{fO0@@_suOKJNa{j=L&>3KF$zbkmQ0 zw~5_<)nwJ*33OeKI^_1xj=L(+aYWh7(S=Xs)o}3C?U@(${Eit54|Us@aN^`2YK{sL zk0Ykm)Ro?1yxZ5RWgvkrd{?RjDoFTLEvPqfN+;e2AFTR2fi8@LRl>Nl^`im5Bl^1o z7PFh(YUMqt`24E`DoD85&S4im{;9=+1iCP)Rm;F=a#77>#((_&BL6+IL~z9xY+{oBfVz{!X9^&znkM9EI`KjQvUM*_I)B&x%T*f<$P` zg@)M=CL7Rg{GB9_K$rLO0j$Zv-+gjOB?(lJXw;)GTNOO+4@ZRx68C$LH2kyExmpGi z=t?-|&Bn-4@(v41%Rc@8{!0?5Ad%Ce5eu!b=nqGQ3KH@OFc`1ye}Db=uOxv4y4HGE zX7}bTV;>vcSc6oOz&9MeyFR2})^9nV!aiqjuC5ZOAaQfmE%$$RI{!O?F5edS^s5S` z{GsNkAo1&1E&V?`gsWvBfv)>*C5XA@sy~#0BMS5C9o1J%;dw2(;+wMdn%#mwwC<)x zozy=L=NZP5ag^lm1S&}2c#B#OB+!LNs}k71v&mN{FQ8ndx7%^S<=qQ$r1b+cxFZ93umj zKn00oZweS*nEj3){!X9^;|G;^ol(kQo=@Z*)t4Gy4ejIC^oBlRFG(V z*PZQNKR2&Ve<#p2>sS-R`^mfW&bmtATOYp$b8eSp`!=p*=r;aN5~v^%(9_BAtMr~f zd~uLKSLM4u4Vzc4`9m3~ATj3JtIVC}4*j7FB+xZ|+-1YnohfW#aG@$#mn4C4^o{f9 z+$~em^N!^2F*PbkJRbXS*P>tPY}MDJtJE@(K-Y$nR+(MKocKdMa5OY%RHpvH-5Pl= zb!7CvQj!EJNZ|MCKfmz`B7rU(OIHb0kofx-=Tae$%x<#nXZ$*4dgQVoA89l7GacZ^yOB+!Lt zL?uu`qGwo<8`@=Jc3KBSKt(JiV zx_TB{uYb@W{10WIf&`AMt7Ra8E;T#hKPE}w7hs2t9XogBcTd{izXqrvF{g4xmJ%lS zGWkFLOA<(+3%~OSB?(lJm~uHkd)Mhtu@4gH!e~G(w+Bb~W-!Js1 zo>Wwjzzh$y3?$HnPnt@gf&^ww|D8Y=K94GacLQc`;N7DVs33uPAb%&&g=bwQP(cE- zQ~pk%3$Kk_L14u={=9mWD7T{m|2lQ9VRwNC%-^M=_O9(AgYSkrY<9y6+Qn6e4Le3& zVNUVpa(#vZmrro3jp1U^Asc@G>>ERBzztUPRyoajU@=zB<}!=$veD|=mtfAzPO~q+ zjB7v~AG?wdYZfV*7ycUvDv@!Yl9YSap*nl4r@Q!LYsIp+97zu3Fc*H+!HBm=T~ib^>JL2 z`yAkoz{(E9sTIhtf%fbknI_9vZhl|u(RHe!Q=L#6`Lk}`v%II|46S#~%6Y%1-kqWK zv8zlJGZJIo&eV$7 zSI+z0?cNNnqg`cI`rn#=t!pM~-mvAv?)%Fh*lkXa?t(c+}+0cd^-}=#TT<%l6 z>TpFi;o5gYi-ptWQB~>xgWql%#eY8NLTB%4%}RZ>W*65_)*KtPW)+s$u}ry#^rw^x z%yiH{*JGK@Ri4$avJmFAXs0U8*#z$eY*@w7+ThJiS%lvzR&HCo#_N}5Ukva|8U z{@d8O;_D@mfABBz<#fE*w5kI8FIJDKf>D1xt*hQx#`C-~o{yTXeQYsY6qYTYe|x+> ztf_&0SvwD0(i`hhJg**?i{z*MM+b^(PD#of6PyuoC8H9lD$kWk-nq*CZceS!0!0t6 zaD_k@&WMq7GoJs@;_~$n1+p45RFL@ZYhYhR-X%Q?Q0EW+VpY`?Wv&dm@LM9+DO#GP zWxEX&#lD)cfBVRis#Wc>SFmHYe$Op5utZ= z3V|*>LY;1P!D!8@^GH$nK`G^W;5GPn^ko0oRdVI8+vbdJOcXOlt9J?B8UMuB`{!HA z(Tw0yExGfH7;)uFdF4*TyYJtYMUt63yPjz~c;V?oM9+LBl)D}8@PFI8@p@TC7gj*5 z+Uqa2Tw8Cz{#|^!T&OpjEoL#-vc|bfyEp&jX(xijiPeq_6(rPWaQiQF(J?ttR5cx- z5a>GK=FLuK&tk^|`^qxP-ZB@>7W#`b2lLC_Nn5iXKNm8~-gQU|+t%!7`a;&NXH62e zvjTgnTgTduts~$4&a#a0rU9Zt##@F85>da}urpC}*{HlVYhKU$$Oq>15bLI&RS0z9 z5$bdo>f{%`c7fv8r=<)PB=+*Q?9PSREYR9GYs;fVe&HM+C@R^ERtR*dHUIe2OiUW+ zC+=Kw;kPGyvgM7|u)-@Rl4U)-n3efzR^?qh8Fo$SWQnr{!uCk`h1iS7>? zb5xMHKdc4o+;{~$9Um@TGx4swpJ;oUDmBMC1rBb`itI{br=~5J zW#n4C<||#h3q$jE92F!yHk4)MTJB?4Dj0hRzqK$G8{GXw@-iQVK$oXaGuFQNCidxu zaos4-Y9^ve;{Y+!-i70LX-_LRmiXiVyJ-63|M*6QS(u1ful&W-DjLVH7ZO_w>)BD3 z$!>=lceV1__nfCR2oej*cq;_D@CbFfgPtbhU9O*a`qPJ_f<(2pguS)c%L216$TEJW zn+UsDKd~UXgF>K7t@*PlCL;4nfan!wr+l5UP8pUiEYtru3u|Ls^X$yF7rb^*PvP^X zJVylyjAUis%f&Bz#+B~krKP1ppsQj*TekjnE}Ir=CCm7=$wCwy8z4?}j%OHUwAtyz zGOwIr+Q>Ruxm+h!!{Q8E(a}y4Et!Q#E$%OVw13LHZaJ}8D^Igx$Es`Z);qIV=TFE8 zxvZv^k$!8ViVOAqm^FKltk{L88*@2?~L(TXmdS^7Aw7&T8WxJg=AN#MDkfqSH!$<)~U3 zoLJK*xy*E;n{tG5&ge6pFtZO5PPLNV@ko&Pn(o93pU7n!COgS8+O+(_1LpM<<@Nmx zNT3U^ten04GrxG@A1FFJETCL-BrYv>VnvtcvO|p<$}&Fow-Cec28fW;trY@Yc*n@E zbIb2MDK=1;J#VUgx#7Yx4j*UR*s+isIqauZS6RlTTF?1~ z0X;-aa~DNHVrSoCta$s&>~l&-N%a2tkw32#B;2c)QU30dXU;5kc#iDR_R&-#^7toi z(j-VMTvkL;kgz@I%%+%}X4$KZtLeszhuqIIL}WG7DFnLk`pb8s{u@7#E5GL-G6^b3 zJn(6*d_6!SV=t!%Yiy7WoP-RTLx~>bS8UgFBFta7cABLS=u)rXyCR>s+j4(VrEaux1(C4%<-$sM9A~prjq8hc-13EQJQEtH@q+fMYX)u9Y_y4XPNl1Xh=HI1=; z+Xu@s;_^M=bqcf*6Dprm6eK!Z>DjjFnXH(*i3xrxt} znqzH4%`|rU^;YKg+_*E)g>EtjgUl{P4~FXPB)>e zXikwpS4aBMYr_Y6+X+OWGA<#9ge^YkVHkmEE zW!&knPMs?}ZMdyyA5x8?f&{j_<-F}@S9znYHsYaKJ*9n)L}=6IEYN>GyW85>K95bw z=Iy^&iLx&pC@M(!e6eD|&E~MkH{&F+XxepdU#zIu+Q>;E&=p+3gWdF-$+`!Rk;Jl` z2mGY%EpD>ACEXbB#SVH#vw7pjYg;;cu~Cgiu{fXc+T0yBtZfCkfBD;qlHfJ&^WYYb zxy@WJiV70rdU&!y>El>fb>mTqvN?QRt)KkF15brO7apNbS33I^ue9D&d|p5(DoBhx z=fSSGo6JH+8uumZSNSG?`r1Oc`nf3ty40G-AAQ6vBQEmTajlh_W1S{+Z^4>P4P{qH zOps-aczThKY;lt3?&v^KK_Y*v@+`ex7iQUWiX;MGz2GQ<~>Q4v1rg8&fhNMtqTSy1iJ7DULZA!Jh)%bzRX!18UYOVH9-y2nB&IpHW#0>(HB3Kcyc0b)nu)@0 z75H3v&GB!c3wtJYy3kS<;_NbK!;^?WdVGI9CObKGhw{(R3TAt=@B>%sf7l^+64~#~ zuGl@zxU|(+4xTh`*gez_SoC&f`z zkXT;r_lQ%y*~Xsjp#lEd<8q#c z0$m>W+LF0-<{ES^#xkONnbTrh53#^%ffN-aS{-Uj-0rV1G^}AHrs&LRx!t!}?-v0S z6(r`nv?WdD`U5R;j8D`fr+3=r*G2iH0X--xNbERVk&OAbPrq-f87(os0-szUKq1go z^lcl`<-C$ouEwa( zuGH<#n1iI9ke~Y-M zH5lb8-aO4uyFaui?y`l|Q?{_ib=SzT@9FGe|KZx3K^mE{Sni9w)7XyM^6RQLs-lB% zA6-%*(1mA2u2NugPpiAKp0NK}MmbkVq<^Kv^YdCZJIL7b+Lm}%ThOGIIMA$uLZAz; zlUz@x!DDS$hgPE1sH@ryliH-FY*mNJR`mzHUOsmj%&p`=t>0BWSw43UyHa|HEMs1m zn_AIx9^%`~cM5?nJR@>(m;w(p+tO4pukRWvNYuGcNbL>Vm`{YUU2A*jp7zetT^w1O zPdQiU!ZR&b>#6xh+wrKAIA3X*=Fr-W)E=M3ViJ03Z-d>4Z>cP{(K1A%K{d&H*2u7!etRutzccAw;4~Y! z+FNUX*_oWl$YDJ%wv%PJPW+`=CkBbjmR=+x!--^n%4I)qxM^4OJClN~a+#0pHy&`c zC~=ZK!hU%@!moe+(5`L_60h2hC8!{AvywA8Sv;40$}sK{Go# z(3$Lee1ve+1j&)Lr5#Mw)zG{$&aqH%enJ4AboydlqT((E{ z8}HlgM0!8VWzS~1$})D;c&VLO5+Y{5aW)`&481ruYVm^*;+M1iIpvI1!KOx$I0z14-<|j+>oJrjW zC)m@jWwk4JoJif-r`h|7)itE$E*KXrXpcq#Lad#~(3Nw^iEO@nnyu2?{vX7iZ5Grb zCP4Ia8_n=+hy@*aJwP zuo!7*bD0g6nMb%|oozu|k|9TBCgqLFTv}~G!-n_?t*j+S1&RKd&ZOSV6Rh$me+81qZLUl6N;P_dhl+h}}jg;+lfc+ZqRVhz?ohzBp?sWnL zIq$;p?;_!1<3?^zImjB#`X!I*l9vfB*Ec|vnAun%(1kky$`zVUn9}SveqvesR{Y5g zPqMCEGIIzTM;5_|GhT!p zU&%u18fX4ayZug^_MyADl2wPJg2aHG704SoM&CAXj6S`SIc?e4Up(-$RtR+c8rq6P z1}JUTg0}fHj%{XI{B$_jGla1s;vEq>!e~% zh-}`vp~XKRm3RN(>hl7rJs(kiffA##bXZYG*18 z5MqnJLZEBI*OU4QLk_VvJ&n6Ttt(Sm`?(`dc($m(FiQ(_eAJAs+c!FD6$-=%;Xj6< zf&`v*nKKdQt$ni@B_jJiR|s@1oanFrGJO|gOB%|fA|(>E(n-U`-mZl?DoEg2mn-%@ zZLOK^iWUtzxhMp>R&ML0x7^8D$$ZAubWT{tXw$Vwaehz>jtUZZ)@40HytI>sDA8<4 zh(e&NcVv5g+M;93H*kk6!`VAZGdmC=Uf&Prs34(Uk9J3gYWwRC6JdS&C$i&JFGxIS24s)^OO3)`3k^OrUgx#@;3>75s%F1{9vv!1Dix-WS zy;BHueVbC$p=a72RA7 z?ojdMel~x!@d_qSJ4VJ$9VHr+ZYSH%|0zh|m6cg~4lPNcGNVL~>fs83E;ZvXPD z5F^CPu)!P^B=E}0D17UF5?f}Z$Xd`(A<%`{#xeuqA=Lt7hl`Hox+;0dNT}C*XZrx{ zqfN9p@YGQu(A8|(Ts@PS*nG~XFyk0UVU&q+ zm)sxcpeY?Xp{pnxl*>>-0^>*7lgeLdhmwQEwbADl0$pm&8yW6vw`m{Y-hUxO1qqC= zbvo}hr?l~9`-!-crxgNSc-D2gf=v%8<>R!caxTC^ITrvGB=D}3S>r#OlWHXr zMB}lKn8%4@4huq`uocrQY1IyR=_f`#V&gwl)VjR7=y3hYGZxywUY60+I*XXDi5G{b zWHD5bNGRZ?uki5+t2(W=BeB9wL#pp{<}lNk>6F|0C~3DW zLCm;OmY{;fp_QKc!%LsC$<#Cw z)4)sEKB!7(_wd%6_1nwRJ0)qS=T>p7S8^Xaxi?93aBib-eC7zV8Ewop7+tY0IljED zIDfnxMFoi>_iP;ZtvxD7l1EA+uJ2ZoTisvW_-3gP=(-fpN?+;jS@vS;AW3*^b0n7! zbr`DJDz)UpPgF~py4&B{@GI>SoblrA85>5TJZA-iMbUgipPB+s33t? zQ$}PpT4>hpF~al0CWSy3KL0WbcW$9M7m5|VM!waff&|`UvWGsVhvs#6lyF<2cSizU z_?FP=Vl3)u1*^u1%`+-6RFJ@DMYe1GJ++pxF=Ac0^v+S>E(qr{1Fl{gaUQoptLwF4yKaIAP*r;_sJL;~MRvY$GFlIe?M#l1UD z3V|-1F(h~T8{I+68tf?sY%EV*ULDgHAGVv>`6OugJh~k{s!#UMVnwPLd!0Qd)Ykfb zletk<%2HI2z-Lp&KEndFy{TOUt8A(e=+Yh^*6%rYnpL$MV7zzxH_|FZbrbtMK5M8T zflr#uN%ifm-Rsa>_>dfhK-b>hS^AJum)XE+#@@lU!LHiRu6;%6hX*uNkichCwzh2s zY9H$i63%{$6armg%@678c;8}?NnK>TE9t=VoK#U z3W2VT;}7baN8Mv1>a>w%T;7pi>-ECP&`Yj)kF%(7t`v?a%bvT)G*aDilVND7M2ZR$ z>WnJKN~efP`6w3FEI}dA75^wu?=n2iaCww*YL5ZwQ|Is--=iohNOUjI-0@6u z16DqCmLyIc-9uIk+s2(OhbRQPykooQUySa`UY(sTiR*Ta$(h{;c&l9lWlZ{?f<*1^ z?vBX~y0IZ1#*7qe-_0b!4loSQiJ~|!5i={)If@VW#ApxJXBaZ7kEEy|fzOTH zFd=1&@-5a=2gcS+wOCdDxJo$)TQui>o~>9mb?xHF0>3e0`P=SD`BZ)3HK zE~R;~z~KskuEZV}^#S{JtXDo`8TCC|X=xU&-0EO7MFk0bZgje9wIj8zhogDxM?)0? zUA}kD>&@HMW3iKrccNh;)rP;GE_V%$pr{~$&yCyzbVZn!yLSVh-@U&=plevsbNV~+ z0W4*labD_;YmQp*M+5J(updPQ34CsJx(U||KYs7l~?VG=6%|_PEs~S3CET5lvWWE*rw9yYV6U`bzVWD$GqBl90A4AUOWr( zPMrE&>z5lMa!*wus33tOzp`(szyWQ($3XGn$x4Ml7oG(%xd?YIB!y0^G7s~?+p*)eqaA%ByAXpGkKt)j$ z5k!%Q1wp{rv6rY(NmL|a0}EoA*@rGRUNDM**q%gVi!t`@x4nPlTj%|~*YAQjcjlb4 z*V?m1?UgW1OrQI?M4$@SsO*^t%v2kcMT@fD@zPop39DXDJjS=EGIp1a;h&M0zESP? zezNHM$x4Yp6|S}U&OjOJ^Rx(Y_u)QiO^w8$*3UfFEO;G6;+03S zM4$@y42lx$yGi{|T!>g~T`TPkkjR++!ed!#k#S<=N4H3JVY<3AAV?&xdnFO5!o3fF z2mA00gFXYrvQR5&kAp<7F0VbR-yAWnto)ca7&K{-dUbh!;r>wGN1+OLWSq3vt7!d> zj}%4LmXZqrJsQ~IXUEo}=cX|uFwI}kjn$>BXP?}Cqv4X_ne$7mS3NILMwvFb0`QE@QYWupQML@s`6)Q-{-VdAd z|EOQo8zr7?%#;XJ9gS>m`my|saoP2wv*x(lMfKS6K;b#1NW}^gva{yw>r-mTL4UE~ zX^ljnO0Q^P>g-iueCalwe@0M;^JXHEI{BXGb{-=h>Yk0#)dGMc%?)n0KSXq>YlWlN*4LaAkAN9ddXRu3r$o5zbD@fozk>9-d;FS9EP@LiG z8Y2;?LRUHGwq0}8oTNQQPV_VlD@aKDL}l`!GIi&U2ITwoWQjl(dbxRBGIhV|IkgAv zs23}_yph0tBCi1Q3sl#{akL>kQX)`=Zfw3v^0U;MPZm(w^(e`Ejs)%#`JACVUv*iO zL6uSCBm!0Ff#&;F_YC!I)*<>bb-d(tMgsSV+!GEupw_XfAbnY=M4$>?%!<E1&nA9ag9oxgEvE@IKO=8VTGdvLj{83U#`NlW;!PQzB3$f1^Sk z`l?sQI}6`guF@GY67rt2dTVDjE!$lLY;cqaRN;9tzc01tPE&YG7vVteQm+UJ`P|3z zNf%Slr=N?>TU{gqRoFM;HC*InB3{X)G?^gfwiEj`GY0bNNc z`Wk)~sxSe}?~0#SNdehkh`j}kHLM_kX<$WZKcbep?f6{uZQDR1P$egeb1kzd-9AFU z+c{ptX6dm_)SeZlykaNvwtyBrsRT{=`Q)bfno_ax zKI_}ixSSdf-fvW8MQd0=0`qZv%4wHFDQ}z757n^}fhyZERr<)k&-&KRDJA<_2O1R- zrC|jLObPP;;H_-BYZXI3ctlGCsvh0As9XO3S>Jr3GqY1EymW$w6(r<5r^~hNG+5h7 z-AE=-W!>aw{T83~{b)Yxdp#hJ=CnOP(=5koSV02wsywILe={BaxsvX$9W4>4y7uHJ z-G$Hk3e0DHt~UEf9KT9_ZANHVK>`!Nit?n}TB@6;h?zJ1B?46*KUU~Eqfyr`3*%P*czU6!Szxm#d1gdU7Jgv9nE?^Jt0&-9I{&sqH!cELYFI%6??k*JJGX(zDo8Zk z{!~Q*RZo5|)sJ#Vv5UE*_#t&4<@p8++oE4otRR7RRL-BfZzZSHaB-j&Nd&6mB1-hJ z+);vEx-xZ#+>Dgt2juj+uGNPiCX`ys?iKp&kpQvG07pF*KwwLqMm*!Hd$`kr` z&1XxgUnKCkqA1Q)eiV^2+h{p4Q6f;);dZG0v6otH?xiX&^QhYLu#xv_riK+H@VUY{ zmOp&S>835^yq_fzs46KB(WC$FrEXi9NTbKQ)8@xtYgj=7pDR3bAi$H}7)jL5Q6^B; ze^9VK^6y^i?)*4vek7ghUzn<41qpnvaKE;19~!=GKm9&%ibSBQY2tAGPwu5YGWSx4 z--)1CT~1KIx=9*Vkih4PqI`4IiB^yJm0a3JNCc|V!UOf|+)H&d_fl8S52oHN?@+ZK zreOsMe6H}bwu3!A@vbW#+XqVos+L#})0c8D^{}~@x<6d(yapYDn zi9l6a*dV<=JGpY%$;AntJU@EW%UyJj?4e-=34E^b6UX^qWFk-T-L&=+fvV4X`|8f@ z3Tth4g{|xuKo%=~Mb+$2HLM_kPYL$*4RWNn<41@$mh~h8Ro8-j^mgnD`_t?SI}oL3V|`F}uQ+be>2yu9HNEtdlBM zkih2(zeDtd2W_u6P5AfPCK0F_eb`GcWmi~hvn$MTMl4xgm?oZgTBKqH34E^bbjq&% zXgT{VEiMd`2vqsK@YI9ZN7lpaBb#penw)GB#3y|mRIDI@PYFH|R=w!Nx;f&|+}}({ zpz3*sr~c7xxYO)5%+qF4UfwM6RrhTstRR6;2~G)Rj-mObbHss~+a5@u>epjy^?U43 zZNUCiUXdj)rd)Qh-dKL~I98Cr8PAGx;k&K0iu;5A;{G5`n8rEM^0etccO52Q?m=!& za3-uEfwTJ*rDWBQw3GXsr_KgQ1ge(2KBq6{+{7SrZsO*3L7TXjntnW#u!00mFjN%R zSJ}Lqh!&Yn;SzzWrS6q_1?N8|ne!i>_Qll6h!i=w0fZGKa3&;YUo-bpOY12jI82oY zRQXz6(n~qVvdNrd*?hH(7PO8MttEAy#2D-*jafzCO^i&?wIN(8F#TfkGGl>T%mY=)rXXz6N4;#K@m zJ)5&Kf#$5thq5?2!^sybPQKu0p$fmvJOT5zMiV(VQPFCo^sPl=_dk8~nLO8hEzfml zx8cwbde6BDC(cdaXQ2uw+Vh+u`<_&^ajv*>cdL<5;HA%Jhx#IRsGn-!rMF_gd1v;U z<9&?JMJ*laAMBKMTiw>c3KEmEJoV%3B+oND$y0Ya(q5k=QQ6kg0|`{&-IY6W!@AK& z-)k!SUh#Lw-%$Q{biUf3p0-aE@k0v?tRR6un>{R_%^=(OS;A|-OrQ$y$Gi%^zKDWT zW{T#%(+#X3A>Z5gxn)qv7x5zJT!}=W3h&zNFsN=$&(0F;T%|=Jp7ZTur-BwYgj=7_i%j5nK;;Zc&sf=*qtO1s6w}?qWG^lW90YMXt#T!h7}}m52q+c zGQExCvGXa=G)p2-g>F+tX}z?_cv!oJ-a5|Eu!02c;rL7@+GK2tIYhm)r%42=&~3^) zmecu0R#5>hw3?z}1qs~4@!UasS0lCPI`w!rQ6f-2$GfPnJZWO7^NfCSl~Yo*~wMzgF_9A%S~1_NtxgXUv&6M_m4G zoJ61s(>%Op__oBzoSY~sk9bJQAS7@{#u<~a0mjmk$)ZMmXTr}y6(+{`&hV0V>Uqh+ zd&@~F8HR+sW|))iZTvDnMZ8(vMj}v!IW|Q(?RCm z(u@**`%pZ;eFzCuVd9u)K;#q{DV!``|3ArMByjDkD1+XAWenLiTbvA>CS{RPg~@3? z5#Cf{eD>vRF-41%64FTE8lLmDs<&aEkSO-Nl~dTL!UQuwx%0%kQ*tUE bRq}gG3PS2oaZ$4H-O|>;3KIBs9Yy&+Dm`nH diff --git a/data/kuka_iiwa/meshes/coarse/link_2.stl b/data/kuka_iiwa/meshes/coarse/link_2.stl deleted file mode 100644 index 4a51b27efa7fa708bbae9351e7b70da4b5cdf915..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 219884 zcmb@vc~}n7|NlQESrgh+D4~>;CDMJLGZ9MJB1KA}Qi@QtFQUy(*+LN&l|5^7=2$}Z z$iDA;vhU09+_}0wujBoFf3D9Tzy3N`&*x)ab7sz*edZ1i3k~)+4h^0b;@iXc|A)V> zEd?RK;Y*8ID`N`g-xVxwt~B1Ywy#4C!h=7S)S-~J6Ec^=i6dNNOi|e3_2p!-G82d3M63u{yPC(PF@w# z|GShx1rmJOowf3Zs-%mm5`QBkzpTEc6Rx^&Qc||MSeqsuKUH>CDF~35 zV4$s3DWxulm2K;x+O%foKBcGg-}JIe`&ik9L^B7CT9;|sQK`>?ISLj1{m5zQ`Iw%y z>0uqu{1XEzkk}Fbmzdyk=ARglfUf_Z52!%md(orXoLg)=`%er=Ko`7*e9qw&&5PBQ zYIEL@{4ZA*#(;#+uQ9cB$&}*%<*cCVWx=#sqH{&wKZMqx-L=ZI5T#P{!q(b!K(U81 z;b(bmx|7<d?>9@@&r^M@%49QEwSCc{2!vt>vc-i_0c?>CTSnf zu1(ujW=MH2kJP3~Nb7$Hs6gW3o_V!In=d*4;LhrAfXd?w3d#Eul!%`Aaucd!{5R4 z3o2@l)poUdnHK(=zPQj>VR7wmDN(Chq2LMloWtkwzt;>qqS+P zBd!0rgRmZK)nE|@1i=kPg*o9tS9+`wad z{*O--Bw%bl27CsgE5c)cZ9J`h1OCYeR3PzxyC3i#z}Wx&tRT^~_nz9b`nGlCKX(uw z3%X#f#K(Zo2Ye>}`x6BfNGv^ZSW=b5kFTHq^F%=cx?l~?pB1dn=ZNcTk87V3|G(7j zFa{(pjGS9b$F|A-=MF*wx~$6nwm1uq=lw%K#kZbI?Qvz@o&U$Pg2d_E7Pa(_5c!`N z@T{QgzqdH>*)I02RI2X5yB#J4u*C3J7b=jLrhcxLcFD>7r{0AGboF0+td{W1(_|&_ ztp9i7p`AcWyF{DS^}G)|`*(tU_`38A?T}8j1X2<4L!!-~QkPbZAYgx95YG6=;1v5P z+FUn+BcQ7;t%@xOiErQGMe8TftqXn3pi-As#en^JK`3paEe6~iL3h3#!V%C_m)=x4 zg2jj$+Fx|p-kCNz-oXqib!k-$er!+?KU(x0*qjC$HQ@;8s!Q7s?a5+P`OgqNql)CY zE`^<;QkPc6fMY5_SYj9>UI_D&JLrw&2{7zP31Tp;1AdOLZ*hs!MmfaHS(VtI81Z>A;itL&~uNsMMuZG58Tn*IXa* zgsC82FaORF&{dbdy*iV{xcsD#*hRmGIQmAnLa5ZGRWaZQNf7S)7>frMIElSu25 zb()hXE|?!(2$j0DDh3=O)e=NSSdNV02-f}niN(DmAbSl1{~=L!so$P zWmV39-}dJS=&DQqy;cu=jH&AC;x~?kP^n9+V!*Lz?H#15I~WktjU%9|F8%kOvrOFrByND=(V;aQdLQOy1twvpsOzZx9qagPF1CSj)_45RO-^I7;yAj`$SRI z6Qwri-sU=&>R8ZKm;U<JYM)+b8=FC;F0G0I=N|+ia%g|*%4)c+38owYU3KZdbt0=psj3!@ZavftDs^d9 zjJj4rm9DL+WmQdm>$VR^Kv!M*Z{5yX16kD?#4QZxTAVtU>bS5i5rl<9<7hLf;g%(V zR}w0cp8?b9!Y0kO zY}~t(BcKcR)CA#f+!UJb*lf$)>E~pqz+NVdEeIy*5&hJcfpbLL$Z25G>oI)4utMf!rQEzILtG>m1Tu%xW zNWfmdAgmqSp4#30U6>l=%n{Ia<^ZZaD-ZYm?5s5QHKFUrzbic7#gjq>5^yXc2u)_z z$YCLm3s*W#0EtA3CC^h`4~Q3&bhp| z@YIbc3KdAevlWE?_wr?~wU)u&#s6c|xhi=MP(m;ED zValdNE+24o56_VGuWs3*HRC50`q4xR6-dBY5katsRl`q$?F!Q##B&66RX(~{rn+uE zKUDK2>VCg*iS^e`A(rDQ>=oHXkk1Rx0?h+OMu5qJzU;Gxvd~WvD;` z=1CA#Odnh4-!-e`xX( zLj@8rPlC|g_X5sbf89)7Yl;YGvq8-u!8vO|h%ow$Q=2|BYaZt(LIn~qPpsd*UPrvB z^Udt$q2U|>U2xu)jXy?p5Eq3B=IuWY6rlnMc-2`?=FNCC+kJuA?VLmr&isRVUgB2) zzT`H+{tI)=c5jXsp#lk*Cqd}@AQ>;de$Z@lLL^5(7hF$Z<;pD=pFe!uY?@2B2o*@c zt1bw~E@jITs&;pNsum%_*;>#Jaw{}~u;>01*}Qdqvx8luMYs|J3798A7(MJRX%sZT ztUNA(BcKbew+OP$y(udDK z6k5NTjiB-`Q8!a42;Tb>soeu%i{V)Z0tr>R&IQLig3#wwB7JR^EsZYFM$63SlYJ)! zW1aR|_L9+jQaRlj@5#5ex9OijLT5W;uMdq_uP^s^B6S`zx$Nhp-HM{|^NFgb*Z8Pf z?;~U9li}{e@uBPyb}~!PWd9F1u)?18sedHWh5an04IOqVpaKaPTM!J7CepOL29k8M z8-fIMH44cfGgu6Jo!@MpT5?XLk%<;ki>0d&R3O3U!(vndJsRy=HuK^Oj)1Oa?ipk{ zi;)}EnB`nUE1nuCv<`LNW`LmriIW>s$@(~Fy!S>jBkV(C>B)pP3X7u-906Ts$5Tld zi;*)cjuG)WQ>d^vMHyCn7EkS$Os*w6f#reLT*A~W-E&UII)uGP+%XxhoBt0HG(07pO< zf31S2jG~3Mqm-RTYKciZJV*%3t@^a?$mD(ynZnYyF6p87je^PJ#m>0=m_A~?C20(; z(05bb>Cs4p3M5{R4X&lne$i#bl_DSNw{oX)=)*r463_+jjUX7?PoxWXTPo+SsKHQy zL{f*pcW}|+uPo=0>4CI!X&2>_C3iUjy5OA^go~es(#F}BmHnRRary8#;6cu2Ipd0z zJrKMitS95vpN4P#sie`JxoZUpwLSgF&1`3U5WBFP&(c-W^v9V>!)z;#fG)!){m3+S zr9-JRBW5-+rx#ltQVwX+PxM)0LCo`=@$%We=u@~wZ7orD(+8PU{3Tx9QxOd_ZD|wD z70RZQdx`K^Fa}RN>|{*`9y3Ho!tF(E(!y;55 zaWK<@Om%R=Ee@#8>SLxkU1t!DCTTcu1a!eO6okV~E$NW;jj-25g_!ckf*icv8^2ag zLFkMH(bq-TL@fX{8_upPVwz~^%{h+tlOW%RSYIno+x{OE7M_AUT zgSN~>4NNS_-FrQ7qm@$`VKT>(?#)nOPis37Dli^A5}W@ZX5w!6=w&M70{Vg{kBK6x85(59^XZT3MBC7(WLb{5ic38PgP{V6vmd9_p4AIi zGe&G37C=W9T|`ai-Qi+Dy5IKb+Sn_5t73Hd9!&3FFG3k^XE0PC;jTG{Ox@iZt5w}$ zwP^m1sr1F3d~_rGAV)w~q*_vKjPgq#8PPQ~nl}7i5Ba$J;|2cnYLyOa4=Ud}{!M%B zDpQX1P9Y16SLjCXJpoQIY&Sj zJVQZfvwjBs{w*E-+Mkc10*McnfAi6z^9L3qqs?@hRi1?=?Apc=(8cHcL1t}zom4#Ui^H~fN*El+=TvzGqV}+ptiLdw4Nag0<*kb2UMub+y(_U>y zmR&bd=LqPUC#TlNxce-L5j#|~oAPk-+9grhqFp+<=+Fb(AHJ{XS&&xia^2HJSrYI! zJ&1ZR;#ol={rRFR@k#uy+=UYL&P&}JF*z<4kpq}Lp4&*vr?Bn(Zp<<#^lyd4UT}W ztmq60^7cr55TWt2*OMvGW?{Sub*fZSO6XhBn@yO$C}1ro3v3qqDbB;Dq6Ly3)2 zI0CwU9h*bGCyUr|foi{KU!4eg`m8xx{(d!v3MAmu%&xBQRGRzS9rb@eI0CxDLn6tp z1tMOaQJ>X`u{y!jF?0c1dc6`u1ro4+WGh(3e)LaLCVIc=Jx4$nY`X;E{9TU6C93k#~(wFa%IP>Qhk0{dF9ZD;vtX+z1e zy~t^Xod^|3zi#1INm}|G0bTGK3PMf2QPk;-Gin&D#a$~%z)^-E=%4YX;YPlw=LLZypbM4-L3n&| z0&Qs65p@{)mb>SWfa4NDxY}q69n#AJB~L!j5zqz8v>+5Uokp*1eyxnIDC5d5B=|As z(^(PJ?e{6A`|MR50bTIfWbL4HB)$68Uzt649`_7F0*)*NVKaNqKfQ5PT$sZ@=gsby-q(_&`l?+>EarG5+!TMMb5-Jku;qrVb<7g|c zriKKZZ4rby7HM+(3>|q)s|b3cn-PiGdl+>&s;!J~)SmRrK7eMd>a3*s3KBkaJ1Y7- zoYg+|HfD0w^50malNT-4PnBHV_M#lc4aFCqRB8X=U8wOYSz%J|v{Zb)1nnAqjMda_ zhn^(MuQa23M!M6O->rz@?HfpQw25MILA6w}h>Y#@yco+`f$?}a9mtRo+;Hb*0L`lE+CvdL~AE7Z@~hSgUyoPzB2E`v-n%0}zenxH=Y7ZOyo2>IP_juw?>lAG`S(ebl=8S$-&xqPE6Ms$vUODwu+ zNKrkuquuA~@70K!Cv`YpjE;A++3OLUD$UL+LB7K**;!TWj-szSd`F=jM&PSy8_DqS zjY`xXqgO9C5WmnOWsBYY5IkE!SQ!{Y%|G?QRfn#kvbbd=R`5lJK|!cu;8OCc_f&K$ zax#*SE+PYtFGg9Gz1dlLv`(aRV<(VStd9uWKGpWNDfWxllX^FaPF7*b{YBhmE$C#?NsjyA-brK^qwk|z-cMA6gnBdQnr$UR*Ia_W3Ey%m!tt!A!}o2jIu{U~WUOY4kJCs|!aNm>n^vFE8YM!Z>H zP27`TNyZil^xkJ9X(4lAIfLvoK3A5^(sqIK$eTg??npQi%n{#bAJF8|fiL}zFk0jhq;t1%1 z^T~qH;#E8?4Ll+Z&=O>*K*FXXja&$H!GD@Nu^8jWCsNPrza_(4Ndywm#kU4$isI>^ zlo908q(1~Ikl<^deTqanWK|!stMwd?fG)m`>feR++ZVf%_j}m04Mr1?fVG_<++3SL z-4<>pYuBU^ICg^l_V%AsNUy|R_)p`CGPb((CXU+N+e@@jJsB#Hfbj&u^Lqkab~2Jo z3Qr|afdm|72!gq0BHf}fneK;d9&O9ahX@Wd__B^7yqBH)!?oeMi z=7eV}2!2Tk^z+~nQgLlQfeIwxIFa>tmn6_@Zd=IO6X_fQUGN&R^^d9q`X(WZEUHc< zDR<`)zkaQ7j@Lous`e?QnXV3gS6!mK-hVEsuhRxk+WCjIgAGn5&_Q}@NZHaP0u@LY z+og~}X1cfxZ&3PwC<7)a&(_Z@?U;O z4QDq+TSzjgX#ES7D^xrCFR_vE#fjchMLRnJ6-c}vI**k7`GG!+YJ%8|*QG?N`*Nuw zrk@@c1JZ3D&m;F8AEH$QIx(VSbpqY+vb*%B=^+9YNLW|QCA;h%qM6RBb%Qo+?XG+C z-%9hcn-V0T>&J_EWZ2~gD6>Qrql;Q1oe{PNwG=ifQdsLduKPZ8EZ!BZ8JkM38dsnf zwg`=Rm_qb!oj@+ZI*f?4Poy2Ia?sgtEz6(+iDd?7_i}SGHEYfYKM&Pla3tkbnGjj)fqFS6ouYy99P=N%w zmPWFR_M&H(U0IAjrxK`R#&J|W408l@!8~`aEsC)^jYEb9jd2=92VDO%$J9`OpOK*Dv%0`mUJI<%3hdio7<9KD=rg5@bG2olgW!Db=xoVOG` ztoCEX>$Di^9M%VW=bz_#-nxC3l7|ncqN$<(_QF^1iJ@`rd*jMm$GQGFBw8L_OxD*V zpbkR9dVPROF06%_?*`_kESIN4tSom243ctMQknmA*1lgD8@RIlp793U9L<<{gy2y zLT(be;ieiDwHy>pml*fM8+X>nP=UnTeap$kmLt)#Uy~VeO&LW;J?oEmem25zgw=cE zN>Vbw3aRh%XRisYAjgAxBd<>ZjEHcLq{g?6aI<`OTw=eTq_usdtl2XX;fZU>@&^KH zesl~s(i4Q@E|JvboGErr9*N-?5E2f$*~Gq}De_VCVKI8#i=_Dl7=OQH!4c5Kk09@@ zjie`b_QuB>^~F$u#MJX^$eqrb$fHmdW3nlGrzl_q*7t4B5zy79-74Z=<&0t*sMdGU+*g)=#OMEenv#n zN3Hd7o5MT-U9j}97Uy>?tqxy>wpE(qqGyG~>Pai5ZgdND)w7W7+-IU(FjX6wO9doz z(IRE5Jk`pNZ&fUP9<~m(E$fV-0*S%eg=BPzxzhQFYK^{MWDIq?bOcqqC~=Q<`Q&2A zaHY{cQ)CsknS5?ET{-!uB`V#viTGOXQ(kV+fe}k=W2mm_DWr2w#882R(seVbsSa0; z{nnKc-9JRrn$4AHZ&yc-fUY%7HjxdZ7by3hvSq~dL-Djxlowj;^$oQ|#l$vnj>7TL zX=SVGt;Evlu);6wowC$rEBRUMrQB8Vh_&a%LGg53auAB_uFk$^@IMM9VjpiM`45jM zHio=s#1q$ex~p#(vbwIp5zzH^{8plGcw5oe@HZoFv-V@VMHf_RT8h4HDj|4o;_pF~iBM1uvzWO;6Y;`zHH zj8HC3q-L`kqPt}S(czujh?j?vebNUDrNOdoaulqJadTp}r(;#d>nojRH&&YV*iJ5V=-cOv<@BAGJ8UO&3YOZf+wZ8DYOKTs*Oz?M80A(E;|S>5K4Keb@cXOcXWNFo z1ff?_BCX1ZKwi!(lu&`h$zj{bIQ>70HWepXjPAP<==6=}kW2Hf906T3ZsYo65~N9l-@J9E1JJ9Aic%o%2WAzy;gqMN*at=qg-_^iN$bRGo7w`yd9rzyR6J_ z+D3AEl^U{l$y1y_8;QEU8hWALyazlI8-IAtq*i}66O|gx45l285EDLP>5vfaGR1Fbl z1b-sgnd8ZzwrQx>t?>$@8~sV6++}Fuli`Yb4*iM4*QLnH&SI}1tbc4s(=uJegYEnX zRF;19B$qm8AlIfhOW~2&{MEb;G2i&N2|VOvOcR*3a#lF$%Wa!L|=zWVoR(9=8 z9?5U#`il*pZX!_mG0=p>e$7VHHs2_PM`EoSelLGn<0r1Yv57zh5}x@TiO!ETXmZXg zcCF5Q7wF+nV?{T29qz243*JpZ$n({p+H1y$ikJ)n6-Z=-AdDb1^vpgVXeWk&vRv)8?(g8 z$8Qkm3LQ``ZKx_l`4dY^dE#4DmTVUhE<8S%SRwIXo&`3{u)%Ya?0 zKI*AtABqy&YtE3N0*ND|)TB)|JCN@yb4EI90=l~O^&l+{_Ql&x4H>aia;4QRtmG%xwJB5}0oN?pny_s@`nYhE?B(B{ zBcN;1xB6?oTUjz1mATelfQSv zL%tdjc(&|4`d5hh7p;+<=Ct9?3KCTlN0ZcYEBw+yot@Ru;K7s{q{!b!wBQKnf>&J- z=5`!PkDD%*)eAMas|$&q3;juMbXR<=?RAOG>38;|@0!k*O-jGY@L13V%L1FT+&qCQ zz9q@A%g)Nju0@j;-;MC+&=X}gS+S&PQ5PKXW~>BhHa3_sktXH;zT?N zl6&K;k5%7|I&0%gn~VyU1AgA&2W*3zlQn za?Th}#RmI{n!`64Dv*F{VXW`d(2eeD{DM4vszo6IU9cRpe#vMz`Z;bniRsgdTf2h< zze*OgZwOuVimjMfx8Vrrf-8-J@U?$ex~uwz+~lDF4Lj*h*7WXxXXRg#?k;pB4=YUZ z#EN=kzt)Zu9l3b=qA#^!UDN< zh#}RQH;s(4xP%@UBrA&s1rwt`&(Qr#rpoP+US!3(8noFkfz@z*_al0|=|=hWO+5+~ zNO)HUkl+`;(8UHGjIfIBMdvm+C=a(Y;t1$UQF@Z69qQv!wLxWU267;#7rXD1cWShx zP=UnR$CF66PmS@=Hz|zp*w>qes#VA}m$f+py7-)b*xQe49hT%@c1Pt=u1h?=J#l_$hD=LqP6_lfO$b?!xfu0AL`IT=w{N5MM?>lHx=Jl2OQe^9xl zl`e$}B={JoOa{^>x?AP-q$x*07pyS^;q7r}n$)I5_Doc#P=N%@lOXsH9z)%ov*gdN zPr14Tx?nxVN{Pd0YVVUHTi$ue)o_r2SDMwkXJY7Z=S9+_?L%a^8VXmG;R+_3hr2wR zx<1e&yQ5QOs6YZf^MbHHD3TtVI)`lflE4wr1=kG);lzZQw2KYfAGs$-h6*HL-Np8W zC(NcPNA8mR`tckAU2qkUy_?Zu20eAHm3;c;T5g>a60iIRd)i zT9_aVxD-ZH>SLMQTE(qeLISoWf-vey1pOG%P0sr{gCn2|t{bxV&wayaRq-(Sc<&W5 zR3O2Zl4m=@Xv6eDa^tT&0bOf?qlv@x26$zTi<Z=}4GZWV)(HPoSHtu?r zBcSWuz(g|r)ireTugyj?Dy#7CBs6YbNsBCBdn8~yrx<}sEyUY>L<(`vF zQhQQ#dhRn8BSi9|1}?gCkkua<-< zL*B6%zdlT(chbI~ly4<6R3LFZW)4}pcNd$>xXuWh4HIedqE=|o)M}1^uI;C1kp_tp zTA^0Nh;rL-+H$oAuDlz{5or1ng4@qQ9ZgzrJH%Mc&@zhZj}F5%t2Yst4@kh7dqFUb zjHdT@2jC8RIuazH3$BZ>eXnz)=%QqIT-oXiw``=z{Al z?A?q>9q2aySF)EudkWidb-w}RTk{t9i%XgW+b-7AcW+DMv#aGj!%Vq03KH7w2a(5C z>bU7<)psE8d3U7KTiug)Czx;qbip>5y;l^YM~h;f$le*2Tw4o?uX=+?v&Wy&U_*hm z&Iv}wwBhKBa+eMk906UhFTvWV6YXe^4~OL|?QFO{10>9c`I5dyx6qjY)o%5>yL!>( zTbHwbNhgkgF21yjdj05xoI!GBmND1&fdpR?yJ~pTqVBuN#`mo23wle?1)nrlGc*sN zlM{zaJC{7>odl}{Jtv~$ql!2Jx?WYJk{vMxXlJ(ui1kG$&ZPVI-9(jv zYh|cF0zQxIe$0-hhZlCii-#L>1a!f5L-qxMq!@ZPei(kcwi|&8B>3keHa?mbvptr{ z)5DrO&N%LV{m|ltQ9uR)>CgS?`|+u4lqsn(%A|VZ-?t z+G>7(T%DE7ofRbby__`>u~aX;8&(^=fy+5`!K==`AaE#_F8ySHCsv*(P=N$oD`ww9 z3XG<`e;h@vr@C?X1G@Nfb!A8#wcS^a$U{x8lt2QmzO$VJW25Mhwt33U>mxY=x?oGh z)+WBh(w1ZDBd@kSxE2Qza1R38liF-HeGn5$jFj^^0=i&}DhR=GF*J*|A@^<%=UPrk zz#Sg!J;=y#`pe`S856OLBcKcR37u#hK9ZT={7oaaY zx?;GV30E-T`X_tyrG6~UxpogF^fKdCMj-)LGue#r${2e8M>|~U)rcdYOFMTX(bN5^ z^qZvG?_-=6O%3!!>{9##K?M@$#2hkbT5GglU$v)5852dnZwSU7CF?i>x^~~mCU(zz zpq^E#7`EplsgM_k4ZkQ6R3Py? z(VN%J7%}J>+v%IzNlJa{M8}%=k;;@ksQaW0<*#@CBf;WT-%5jj(_uwTMJ>MjU5^a??aQIAs@ZyCsJspsVW2a$@yhEQ*?R zml1D92GRweWjwxjkPH<_7zC{#lh-;S$K$FP*Or9R21)y|UBgBk0bO2S*AkB+b7X6N zlMzeer_pw;_u|EuiV0L8vD-d}jPz}TmXF)Zh*_U!((`l!epq%@f&_Hs&e%ly4|}it z{Ydq7vBNtfXv>6^xZm%AWl({{SBHEOJnoj#W$Fq>GjfW{{}{seu<`qle}<@sRn`yBouB%7 zxT4JJL_19y+GDodx7?M6E+0i=Gb_=(#+{X4=8YrO69^){5z3Yo)5v|l-DtI|>RSD9 zH=+G!RFf?k11MA=arJRHv3*{MT;&o*s8Nv?M9fuQUfP8tpzB9;GTFU)EsBU&Js)-p zhf_RTz-bd(QK&#-LSPCJLzkk-YF8L>*n0wPpEeG^*?L`u1ay5kxsX_0OGdK(7e?IM zIGNroUWkt^E|8%D3FGHWh}GR`XzaT;jEJnBMqB<|jk`Q^!|puv6JM_%e$zHz}5u<(T0~+50&Hy5Qax_QptM z96k3=9d9Yvji3SvxbKAR{iunj%8E5;fyG6RfG)V>hV8!!Wbc+lC{Q=AN^UO>B=|in zMh{xjVP2=@57X@^9Hm@M8cLLTk5J9<$;cUkVjS*!&J48_%6U zY42j#wOWyEOFzySEx(%8l_Q`Fjx5*={f`0k#O=K#_N57h3M3}_CX(+53XpGW)vsV= zzZ^%$gs^w}*45_-=z=4CRuZ=a(99F9@$w5-xbZn8eDX4gb>U)^7^o_{`QO55LB}!J z_2MFqfG#*zXS>1<&ZOBFlW_YNgJh^cf^W}z>PJ%Bf@J(+PB4K4biuK@AoTQ&q>dGH zalO#>Wl(_x>_4!*we_RuxToPbIbtD#1a!e&i0u7yn<(ml!*KDjRouI8kbu1!_SJ~O zC>nfb2-dr##_dmpF8+PBZNAYob(b~nRI1DE>w^UBow3pO$Y{E`s1Z(npx_ATg73;P zA~u?)ufLCO^>*goqJsp#yUlWTb2_TeHo5(u{uGvQ*p|Rj$?B`$hV*{WR5{zIKZOb; zV7tQRuRisq#@7kCKDrx6Ko=~PY@O4|g~sInQdaIUqELYZY$e$HI9k4RNkud4*X5lI z3Fv~Ql3gp^$@GfuSe&(&%20s>Y**MGuf1XP$c%Zos$MupKo=~Pg0T1244OJ(Ies+0 zqYM>Dz*a&KPV3L2r=~5%UZ!yb63_*E&TL)n!z|kB+9F&oP3QX5kbtd(>MNU(G-Oi@ zUekIo*Kda|IA#!pRqvzdCFLYM$9y?AHh=_dSJ=0s7sk+J-5ywT$UTmLE`C&Gb2gUl z+oXjbet*L4B!vWQR|Fv?B#s`>lF(HpdmjMoJ%ui~SCy5-hjFw;Q8F?c(vsW73JHFn zrJ_Y&(m|^W&3-6S?>3Vpi|U_9wDOm>b_|s)R=hz~Hq~YDU0b#)GdhP@rT3&-A-1%z z+C$ntry15g^HhTL_rSZ7MRx(OYZNT8vGZU(IqsY>HCygTZCgK)Tuk2~S^GnoQej3O z40?#HA6VJ*#K|?ItoZUL)lr$N6m=aAY*Dc#)-n*nxxH^UL3uLb{|=Lh|l@2xdX_DKwY}w%rFWS zNcayrBpKM>K!Fka*catS+OYlcy3J|po9-L|UHse2rTUK!t)9}1Ry6mZmkhp@9kafQ zuGtF;)jp6P2{+M_wuo&alYZ1>!edv#S-MRara+TE7#|~H5aQB9d zQkyCz*Yka-gGCSSo$Vm-n(1Oc? zw5#O_buzrV;taV1g6H%ImlJg5M5|Eonp#lk2x=2aTttFRP zj1QNONz>~OMuT(ylc;mmRMeMdSR6$6PpkF_=WYp+k~I$^1NOcbRN!${>F+6J$m7s? zMmQ~QNiGbF!)M+`{s&R#n%F^2deUMq3O`90@$O5p^!n~bJoLiM+ML(9RL5O)d>`t# zNLKK~z{0IkKbzY)UUM>q3M5o%{d)UQm$zjs#>{$7q!??8w`1J@gQ#iSob=(%M_Ml6JYZW|ERdQFFI=i>{ZE8;n6-cPk&(G~f zax2v@fW3GWL3C<{iS=uA{)4D<@q4^RJyRo<=Y7S&4Zg}yfyY&)OD%Vz_0P>%j7f9r zk!As5Vy}|Y{~+pID&l{3o)z57lso&2;zRv5)b)ls@o%sh+5gVwzR6(R>a;YkXAx?> zUzLxVvEK5TtS;i7U41B2;8z^r*B#i^Ju^^#ciL9mI?9S8pzF`Gm3!noV%G4BY@F*$p#lk5&$HdQR#qgf;G;Y>*N-Eh zYqxKb<|w`IRrFvpW4pbNGu?3ZZV zw563j+R#P1L%9|Q5~@=2KXqaU@yVg8a$P$2@i2~nE>*g&y<#FO7)2DF+yyprh zJ5s!FAKJcTAS)#!o~@8y#_G!(&di`tfdv2klGzt3<)v0f6j!BSj)1QB`X1~{A$h39 zxmXsXQ&I`h3bvvhbrf8`1ooC-pGXkqd(0=MtIX(X*@5dVK?3$Z*vwsoXd73*|onI9T^_YVmSFelppzr*@x!@Pyr~A z;P3gm47Q)|ngL$De>g`#SFzzVvN&%g+V&ue#qhdnPv;nw=Q5|X8@)h_?ye)+aBw##2DA-^~8>Fwtl@k;k0bR4h$C9q^ zvk`eeoy9m}{afz*%Npxdjipe51T6Wix8(R*&U<5zt@@4U2Z(1;{{s7>l9X zWTzbOovU>8oKB$v30UW|J*jVV<(1|)l*anu906Tb2_~dt%}zA5s}+k;wZ~Hq?AT1s zIvq)&0twhkuo>Y6SiUr%p&Y^baFBp5v%>nMQMW_Lb-N~u5kBD=v2t4|hb2T%s6Ya? z66_tt+;WnunIWr9o5c~(m42&S%Cb0$UT%28o~ZlhMv{(ikI5Z6g;J=lx+Wwo4oc_M`hB>48@@vd2tbJYde>P;|5 zKo{&ev)S`@r0j&^wXEK564yh9gsT1cpE1sspt)sDaxTcR^`>wHbg9yHJ#zL=b!CQp zqFXo~@^%`H2sI^E=eMGo$!1DBhX!Q#^W8`yEtRd<+Z^{>mY|?_>g*0qFL#m~PHlkK zK8m7HfyD6%C#8&%LuhHqPj;=ol=PK5YWKm}OCmV}x=xy$lETLAL1|{68PP2DGHG3& zD-|wFpiqItSHF2uzSa>W+`GvLo$_O3{!>jC6wXY~e>e}@nYJU4MBes6il?|K| zaE{(A3YDZCrzAV}jzN37M+z95t>b(Rl%GXiz{ck%a%Tkzi>>O!;>#9vbF8X$M)`?y z_4X6E7rTS-SkMKpA?w4Luan)ny~OzXXzp4;!ro4Ye0*4l`gLr^?#KDVx$*^<{rHi~ z1df0%cxTynCY~;ref+eSVTK0lHUwMgik7LaS76TVgJDS6Wc0KqB?1 z4oL{gL!LSpSxz4hhH6{mDt!HE8Z!6Bc9jm8WvD z@(P}3=)w`u6@Srz7*EedmkmTl?7P*Bj@i~&Y@BLJp#q7^H+;zIpNr6$Yuy>4ZK_QR zjtb%`uZ|o6T_)PzWZjcYw0GSYMrf@tr`y}L5_Q`Bkf8#J%wMxf=7Krs=6Xj)G}>uR zqjxtJ6HC5x1a!@5NX%PEyNKU_sLL!MAVT~(z$yOD%+&`dTUSi zHef4RLyRylBl`#_1Tq-=yi8IRR+}H9S@CUs6gUJgEi!7pcN|1Ok~8f z_tWW_CneZP*I0sYvey5$fsAaZff_%zRr2q1y4r-$(9@^z?5UL!R3Opw{Th-J&>8hP zV$NbjM^2`@THnOKwx|=z?#CviXucM|$b4vFNn4wG0(V*s^z2_bX!&301W?w=klQOU=dEf0}aybiubB zS*upkojMlUh<$pEl%WEN=ex#}9&!fS*6|CguR^w2(CZ0y;`&wnIRd))_c?F&X-iYD zE5!k8m&j0o#1C~x@;xsLUA(30m$=u{rKLj$iVe+@I0Cxhn}}>z*qDa&o#z1Ya0?dL?gl!qOWpVjXapL_;+?$h-fO8yd z2i>j<^1I(-MMupdj({%smLPjG%)dmA?l4+>ZTmom3MAmH2x~vq=E_^L#*0pU$~gkM z;Jb@#Ueq^I&bZ+&`s)f5Dv;pkODgil%fk!(#Bb+ra_>Px7kq1zmBid2n$rI={xV`P zfzLLqKj8Do-XFX=fyUQ+jW5nTPM`t_SQ80?*=Qe{&T6=s#XJFB@Ofl=ysF))`v(oN z-L6hDR3HIsR5tgzbU4)u)e?7~XwMPQ1)oRu{-D`Fy8nf)n41 z13Iy)qqux&jSLk?z?NDN7Wrt?W~J6*=;!+!0bTHUWN$B%Kk_NkPW*AtfIJpFo+F?O&Umt~nEy(Vm!#;4Z@V~B zs6YbtQCVFwP$6q5U*gK+<2eGl;5T#G+sk_D^6K;jctZ0C?rXY`fFl5QKaRT5AkFvK z>~}ubXMl4Ku)o4)if#^|?*m`pfY>KozXTF+{y`AZt|EGC)n}Y%T*DF21^ZoW_9N7i zHr;RoFMnxBp#ljw|G<80%gdDNt$%{m`x60%H&1b!FX=N$s7S) zd{2Kx50bTra-n>sFIb5#|o>3UbKj&Z-5w6g&5oG8o zlH6(+?)+dHM?e=`Z(;Kc*R~Rq4(D**s$dEgNWk?rL3o)j$kQX*h>_!6I0Cw0kAwZD zUc(z??0yUJca@St1rl)ejLjOP=*uNjMvB{|W*h-sd`~9C@Hbg{+fPjNe9e8C0upfb zjLqW6>T+r1Y_TodK>&{hUGN*SJJp`#Ky_LIo0VXRhk^?$~;B_BgD)F^40d%X4}Gi8MQ> zG>lMGa_&%S-c-|+3))XJb z!Sp(T3MAl;Z}tnT@BHb_))(>8(Fz$7(AC*z5lIgYK)*NdVlhTvnm~;&oyH$xlVzwt z0`6QFgk3K@>4)pb@yT|SBcRLR&>UhmI|G$a)js6?<3>>D$Ax&tvQIKpAOUyavtNlZ zMpQ2;2|KqprjUTH%-zAH>|8F=u3W`p$cdKJxw{%3)>}cL0txsg0jsIKn^CQ8J*8o- zJU9Zn6!nLZIbTarr!T=Q#^P@E>GIs$#C5k9g$g9#yAJHvBh+uorCr11{U?1n0=oKa z9Z0N7PNM!_ELn`NvkOUJ+DmC=<3tL-zz)B&&VP-4p6E_lz9zarR9f zp76TSf~+qYAt$nL140E7s`Rr}7%Oa4-=XjFbRls!SSi148}T1Roh#_xsj}Wzd*LRY zNsKUeZ%oF`-zsmNJcB|79#@s_KHUxnwp4u`|J#Q~?0c9e<)Ltn zfUfH6Insjz2;VAJ55A)oMaKph}&B6@(hh?dCSYO z906TDH{?h@9WAg`b8ki*u5p)JUaL=MCXJ?0fy7&1H|dapC0=_cfDs-SyyO9sb*ScI zXO4ib*(675FwF!9vtMCl_0>Xq*@*s@TCR$v@K+GvZymtv##XSr4CJ$|rjRQI?CaU! zw-O)$pER~}d4#o`KB%eOk^SldB%ljkH};*>`kHcVjZ&Vd8%?1C3HaOyLhp^;&A8`Txl#H8@7*?t56CRNWkZY^#G$7{V)XS$0j#Qd5f)4sYK91>0mwoI>p#llG^OSuh&3ThFB+#1r2in(Ot7k_$ zVDDCLwbyFZRQzis&ub@+PLR7 z)o)sCi>#1d6m+KV`}VJmQFqr=uDW>eDzI-fKC>mCW?0f?#}S1JBw%bo=$24SzIN+I z3;pal0=nQ;V5>`SXObX=Eq!Cri$Vnwd_MGM&LMZA`%vdI-8llf_^Ug}+f%uU zof+8i3kg-aLoY2n&xUQD-Q z=LP!DF2i`4P$&)y(f!d=Q&6Ao@+o?ukJ^o0tvpw`Qnx+ z2kkPYem3?T0bSjFE=%v$>*0ZiRlgGB{ijCW)3+P>d3OSZzaIpDC5Znmq1;Ii373o{&(DzX^qNJa)WtTOHf)LVXIKlh$kk1y z7D|ZqYR}>bWpx!hHRww_fuO3sDYuJn-mJ=6x6LcYGY!)&E2qAis006XQ(fOV$@@ZT zv!k~Qis>1H?d{shbx!|**MGkh;d#zIIm+&vb<}DLxJoUQpr;k^yz{mKWnq`{XLq)IK6p#FY%63JwTV*X*Vvg`X8fuJfn7e(JFr{l_{-OZGP7sm;6PD)UJKg`H> zqO!W~QQhL%wT21=Rna*$?$;hPR}VPVVcSEy3v*{mP>(%~&~(jJZTl{f^=e})5L88H z`nanf)LG5cFJ#x8jf6D-O3>AMJi+s*k80>~nUxMZFRU|A6YYA&Il%Ttdn7Q}g)WennMuB@Fi< zG#-k+2R&Rdfvy_q@-;s%V^bjD{FKO=)w+Mtz*%rqZ@=z##*9nMD;g{oBG~+PY%K zso7b|4F6{8o38DJR+JL!-5SXwH`QfhN*-Y=I(5k*WyY*V>e_Fv0zp-@m%wvgPcAAA z2brm+X0AeSK#AS+8p{3dSTMH~6YLGTWL{A&RW?zF2f7OcRnguKJ?J{UR{Ta9s27ag zgr87Ic!xPIGocLGiJv3kWFvwRRsEUq0Fb>PMYU=F3Rm$k~KEf!25|c+Xlzr<< zY~)+rDC6x+J=MZ|TlG*6^1#&1nEqrN0(&h9T{kfa37KZ*BYZz$VbeW_GyFuHuMR27 z+xE?~3>aaCK|Idn71wrT3*mL@Pm#aJIscU!m3j|e(YXIs~L*?YDdg{PGzACj) zg3hVYo2o}UC4O{c)kf_q5L87+%b4RZ#7${~v5>pG(5loz2|B07c;S2fl|z;6)UZ%@ zfuJfn4$^2Wtn3u;H%{siOIMXzC_(3m=!N9eQc3&eq&5i<396!P3`S5s{#_2sb5^7B z+X<}?CFsde^kN<6tn{hXN-cEnAP`hVTOvH^{c*HnGO(qZc0{XE3nl32Ortr!VWV;_ zrm?#Eqq{&*6>W*|+})E4%JdheYC@5#N-dP2<40UQU;A7c*QK_acG^iGsEW2km~C_N zZ{_u6BXxwmqe?B57}3fJbJI6s^VWaGb~hyck8&))K;75TSsyt+6liSY}$*#RXP!(;7a7^9YOzmTGQP~&ks!|Ij zt~7L#znMERgC}jVjBhrk>bWDiN*5m{5L885BHTBaZJ{21yG*GuPEx6b5^V-K$(IAQ z%rrpP?%pV^ueQ51NXfbFDG*deTOu68&1j;gg*z&yUR_mcp@f)Kw??(b>NT4JdHXAG zfuJgyZ5QvnMhkV`R8RR2o{**%O3*C6cuL5uy;}K~ue?3ZMWwl3Y2IHkQu>`4PHLKe zvE2C|H1U+6W$3F8xW-E@l%VYj?pm&?q239tq;4N% zFA!8kV|3z5>bYOav}0A&E`Aunj6?;c1f3z{y3eXg>QrpyCR(-=2&$sdZ!l{1rl(4i z{TkKh1PF0)C_!h)*c)8`qO5Q8Ua2(zb77M>qEtmAh~OwgxvVtX_d!u6dJC~dC_!h) zxccGyOz~QHLve}r5eTZHaYk?-r|NNK&ZbMsw#xm5_*aymGi1yXv+bdx9g(XHRR;(J zRnb^jICsADQi-dZq?8y8QK^LzbSD;xbEayTYc-`#f}cQ86^(_3eq@{NG0tmZQP4G} zQVS($G&}T9%=1)NrThffVNC>rs%R`MjizCf{;FN?(abJFPo)-0&}eozgIqdFebi$q z+hJX-P=cyxEG&(t*l(=5t=~45Ubs-97D~`)cIZidZG!sg)^=9+k&Qr56^(_3W1p>) z)YivxnRmoZnOZ18W7A>lvw50&$R(2v>}n(sR7GQ9;cTMG4E6DjbQTdct%zDEL1WWl zf8I4h?U^@|4X$hfl%Oga3rnL}b~;iu{WXMbzt9n=g%UKH9mes({G3r4&Df<%DFQ)N zG!_l-D+ICnv3;?$K}lAzD1B?3WJG~*oZLFzKa-mVX`+|qdNR6QcbOI!_IOnWH*`dS zdkuA~{Xlg^kCqa(P{OMUm%9&JChz~7=zy!7XR4|`dj9I^_IX-LP!&vO^2vqEWb0~4 zHrN|v#q*!jU1YxTryXZE}O@T%sV zis#=qZ7B{rRtEx~E`Z^Uz1g?MZXTUpEP%6{9vDIFq;O&jBFl;ktH6nT<(f__3U-$DKe3%EEs^WS&!ioKy zJ(wT#zlexx_B>$EGg#sQoc=FL>_vK99%t`Tbs0U!6x#FD2n`FXCJ6*pdC$QsoZ!w@ z&mV_Gm3Fp#6`o77THKL8>DCSItnp@tm=F9mb%Z*7daz&q!=WkOpW#+-_9su5hnG+6 z%v)~!Ej1ZzEfB80L*U#pZ+2=$TbMR)2!xL7!}dPc<>BRLB;KYVT}r#*z^P^LEH9Xd zsxSGTK+D$oc(v!vpDmM;54#9uP{Mpvw{m*iR&Olh@K;A3as8`QQ0O5LR7LLzPg=aP zPs|yp6|`>wD>9Ql42kXi7>nGSQEcC9?r*4?Ipd4 zEMwGCz1BnsLDeIz8PNZPYclTsy#1%%(&@0OoLVSR|4CRmeYjMYnY88de%vGfs?_zn zi9k>leVe$Zzq2QQ>^eg#)~nB{g%ZIwL(9w9VbBK4nEuL}Tkf1GS!Xs82&$rW0cR|? zrt{0EA8S`kTFx%)n-7!lZjWmtrR@{u!UX)iz2+h5p3z*mImerw$x-oH1znuNO=`T> zJ~iIPsD%=Poc}{N4Af;rXy-YRZwQ|&O{-EQ5L89q4Q7OX62h~YjnsX?Sw=0Cm{T>j z{0)ARzF-+KrNLa9V<&Zgc~2myioRJ~_n8pK|Hkw&rL!t(E+*%7_=^q#u5SO}N=d$Bhg z{oHYd#V?*`Jlb2db@mFN7D~|j!>Feh;(5!m-o=*V>WKtt&#Ql40DDe!XZi-UFk+Vb z>3E)MyQVl~vnfyu{lBzlz|*pM@x1>RbGc3(eR#ey1$vBjXPf(`YxTM;0OK&u0!o@| z4@9IulPR1{ZPyZ?Rigv(yj4p>`7!47rWQ(^9<~6s&Fjec_ZqmbW_2i@|1r^%lPrw{ zf~vIBkdQmE*Ta6{edKM5=jKW;xqaVwY15=+h`_$ccdwDqCpK#HpTD0|bthRXN5u0& zPZN1}$S|N5+KY-kXZtsCyzcg_;z92Y2n1Di%a~tY_R8xqScYR*B)|5f5@`F6W`V|u z<(7c_BI!@-|NQ>8=8$y6DhU?mwrAs7ZbIV3;3%#Mzbu^!?$4-&5-F3C%Ky^=1D(fj zQ{NaKdAy#KI;^!oP!+vG93fwgX*y&)uLp z)b11ukyvB)x33PA#%u+76L{5qTcC8!Ax15fcyVraIeqNPS1e&Kx40l?56$q-LPXzaIrU&s^o$o?w_%q>IQNpNJ zM0pvr8tcl)?m31B=Uj&RbMFfTRng~$zRvo7ynSAEX5wwecdQyzK7urg@`6HTSo!bJ zh8_Rco%j3Ohky6cV^w$83g%Rq^+ z)CBlBhqEpV&SDww^e6DMjpN|@Ekz)xO8jcy4;jzRT1P{Y<0au6q(q;xD9B&H+0x|7 zSg-!(2J*kN(&6)_&jLYJv>v1XZm2ESzY_+<9vwNI{m_}7IAdAczYUKcmIjq~bP(nr zl%RDCXQ?3Z;IdiJLv;`cs-k0UBpP?->Y`Q9?}C*urlth_R`843K~;3*jHmk}NAhW{214eqkHQF< z67=2R+`v7ApKWOZiyodA2&xjtqBT!X;2CaBz+iK+Fw&<4tug3H9y6Uc?YmcM9I{d% zsEUq*@uasyIM3g?O+qdLog{x7Pct0K5^R}#-BbiY%4WWKSmUP1|REZSr1cF7mx zazZvY{lOIM_ZPv_0 z(nVYyg%MXV=5ozOQoa9)da5HT;+E=u>*A!U7$^1Tl3LP{{~uX3zrjSEs6o zD5d-T6Qk)~$7s4wZy8BPFv{*jjIxW~xV3t+xz(R5Tg^tO{!8jXqkFf(Y(R6Z{|_hV zg|Y2^V{E(bZtfss47&T}G3f5}$BYYVmNI8%uu3hIXt=x&=*~x3m!FS%F#IR$J@b>| zcSoxxopOiT=p*<7eFSgj^nmJ^y{t24FWXnQ59s3ef5!OzIC>p0ia&NtVd*`NDrsgZ z(BXeFwOneG1Qj_Zf|e`-hyR~FqJF=@yri3}@~v|vwY1(;=!+RvpJ0a7l684MLUXE8E`a~n1(vaEQWd5n7aMHOit&V)Axq{zLtjg->yclC+$<(e}_ zO0^8U*`U+9^HG(@rm#oLjpbRrW~y1;Bc&CnDlJWtQyXPV%klTH>ht8_;B0BgJumi= z>(2Zf+F8VYU1=;={W(D$*Q`KVhN`H)3G%74x1}Wf-FWycdElx$lGSD}R%2%z5|(e? zuru#l%dW0L>ZGi<(kxWzyT;0U@~gmP{M`woyUrSD03C*Vv2a)2DWUcks&l_5TKRnQ zfvS4d1cFhuVc8`4uS;VXioeI?1k1;&HUVvQFE*bAA(6VX8GqpCDPMo(sirbp=#Q#I z%sscJrAs;CZ8cDy)X)_!XYLLhRLFY|6*Uv3r?0u_0@-R2Ad zpEKQ<%NRQ(4ktzNvhi;0#PJK@S+)e)KbZi0?pRn+V<`-5KLH%m$3p9cY0&lfB3Rz4 zJ>cq~XC%*T(uw`rSDCe(wG5`2^o0Wbap3%Y88|fXgSdak!tNnU;qSUxaJx?jB(6&l zeCW&0?D2OC*0IA%*c#j(yuOYBf7?~?&7(C;d^H;W#4d;1pGU*-b2`HRQY0Tf{5mw) z)s?ONwF$x^S4s|VJ>X!2Y}n~FO{&$rHM9ud0z+Hvm#*qtB60Xq49~vVjFtG8YJ)Jp zy41IZG~i}K*B0k@z>5iUB-?ipu0h9kK;<w*VR(p2KGIUOUs)!a2;`O8#MJiA@!cR3yI*jllat?dszL3lZ)WNR=9NOiZpld z50@!*H^DYbJ-EANb=!+>o8Zh!J#h5NLgK=sF?>3E%nCQV7oXm+5thF)f(r|L_Vj;{ z0W*Uwq0*E&`!Z`~!p-}ZAZ=cOME#5Yyn3hsuNshD{J>=mJa)E&g9EeoSy-jRt;QW8 zthu>M)R=Tg+}07stzUq|_AS2r$Ge6+NcmO#Z}1Yhc%mDaKB?rYew_~mp95gHD>9WiBD$gz-x!0PF z?l^1`C*%}VeS1*nS@B2`GGN|ItDe*P8mG)=#Jg9v$X0Jw5wB1

      k!9xwf-m&RHZ9p zE7rNcUvuox1LDU%wxLM~A2qSN^3de6bgs)bC|&2I_4hFZL!T_TzusM|eyax2aT~$= zPR<@YQDwM|HRwB;C)d3xQ%iF6O{wjRY;dSOe;@r%xOaDUB~$-S<&Fn$%G5%MRVyz^ zkB4jpuOVykS+&fb%Y1K5<`XWB5Uz@<=-b4cFLsmIc&l(;-S53jEtCk_uw0tjDHnbo zw!?S+>VO~XritV^D@z4}s%Txn3>DX&V7oSwA9Hq6GWOU);Qlo*q+u6r&UkAGU9<*% z*M7B+J~uqc8h4$IoH>@C7^TS6LW!;WjNoFcjo|*}Y(B2_-8sR2>+j zF`$zzysNwhdUpGS@58q87uIAzP%9-ed)~y?fNE1SdW5kjgz3o z-Qn6@qXJ-TyJQ%WcXuDXTFh5uXvRB-_Tv2xr^wVoiJmvQ!PcLPVT4U9e1l6fYw{+~ z`|)tAu}5SE6kwN>WF^P4}XLWXlE ziCQS()*ugtH2ABne(EGXtJ3T7d`aea=}5!%0zp*;`?0OE%IG4h=mdv%kto1ukRgF*4D?__LIT!-0)=tl=ztgwNT>kh+WX$siw43e*_YLmdA6~ zk5%Ag0uuX$2}@7xJbgSu%q z#uiAF#xa9_Jg;}NIh?w<9;k&9L&xrdpw9Z*DQ|QUl%rWZUu28B49+P)E!A%9f@SXt zJwDBu{lCgc9U9M9wljg-Eu)1pDB-Tj1CQ40JuG-Amf;&2&mZYkhq~Fr1%j%?JFnC; zmN))85mv0P%EnsfLh8bM+6AU%QjeXvP$}VvwrR6ZQVUaTL34*ld8eLY8Bq&k`6PKH zv|U??Q41wH`|W_AS(~)+M;{}he>|4wg{_4yHSYo?sER&yjC<}B$JO1Q;Q8ae@IEN9 zS#Kwt(x0Opa_bD1ksTGs?>2IWdwORDf~x4d!3g|@vE2Gj49s|AEZjN0!W}bnU~PDr zHYlnpj^SKa#BkR6Abfpf#HfW5E9Y&4C8?=Wt*q)uys(eq>6Yoxd1f<#pek;;9h??5 zmwH5*B2k$~^9xx!;O1l}<{6s}f1SojMoa8Lvu+#2KXsHECz%7KF$UfKXx_5*dI-K| z%LEG{);`$=%l@^IhQHG7rGB^)&Fz|JLakfY0zp;cRT&(K;(hI2!nFhTjE-yRcvmP} z<6jWPtBom!;Ba@L3`#75Y$$S@Bo#V2;8nFd8O5i16heb|H-Vrk;fZJ}H;v#evZ}F& zJN;Ort{Y(VzKhZ=4?oDCyb%^@Whrm4H|#Rb0)vJxqyqugPz1ZFfiI@(N{6q^Q*7da{5L88<2<`${Me=i2@1R$@ukfrW(XSsy(v>z! zuYwqs@nT>k|7iOhUZ3wS5L88H8MqqtIGop>S(CMx*I&4EdQYuv)`Py=W9jwXK3K-Q z$`O3Xw`Q!&t1F`xN?e+;4nE&7hTdkKk=QdXoaZbsXT~cB2n1D~2wn$;hVLcQ-~EwT zoe;ru5(lsYtG)>HB|48vez^*Qu6jeXzHYt!^5Jm4uXPvpW~wct7D{Xwyb9h2wgUe> zqmi&b6wb@mbY!-59Rz}^RyJP)joLPXsIovLt`&syrLGclXyweP#ahaMXs6mRYTt06 zWurH4Q8?cc*MTL>a}mm*MC!^6$aJg;7cz7{6BmDl^FJp$vW`cs1cIvQbHg*dwzw1L z-;!;!>&vKx61EO&;lu+CTrbh>G!%J-^L2fju=X+i1%j%?_i;NplGk3@oBgmX5@x(~ zCM?ct?UN#SU~5lSzgBHVEtH6fSPu2qdO_v4WAUoqkBs0a%DOVgMfC)Ns_2{={jZ)y z@oOJDu|GR!3Nv>)qZjArR}MvTJ;#pBhP@T;gA#4FErqME$H0PiIuD^4F_C=9n~to~ zp??K}s_5DPj;SGrOZE<|n*Ud+$Sf5;KhK1XsuLtnOM@y|iSXBMv~aaJ>NAbz8xq^H zhhcjK3nj*XOM@8O1W-qh!K49`z-bTZa6C&h8&2+uUUMlvMynHu}PanJEx{a3|dV+Z%R$OM&`7 zbD&>;J1pb#o>+dUojz+e!9=i7!oz+67^vBhR5$<$vk~!p^`S+8nfrJOP^iU#v>{gd~%KN02wG*M^Yz>=xNgwFyClY(&`JfqdiW{GoWNM*AbgM)- z^5iG@4$_TF(s1?s>&Pm_8`rfF2&xjVs_}przIfm}S^MUftnfsrx7?c5TwB;-h5LLk z4{O0Up7Yg`O7h5 zhAvW*z%|~L{WUyQM7?Y)RakeM{S1}| z#>|x|K~>Z*2UpeV#&i8iBjvlJ=E~GU3312dWkwvAlQzqbRwW7dLHCF072@0=Esk&Q zvrV=+F<+(@N>EQ8Tq6sJ;cly*%b&Vw6iQGPt#9~r$HZ~Jn+N0u6XpvwkrLF`2*+?p z6nh?!Tbd;c1Xa;miP0%T;`#fg=Zg!iXUWvZi~3@%Uy=+LgMHXvV=sIkLx#umL$}L{ z&F{~Wsf7}v$JUXYSUx7Pw|sKUUxA=1`ff1Rixxf4lH6q3bhb<_ln{5x`q;(u)^WbF z{@ytPK~>^A5BnC+&rF_*uU;xPbWQ@@PQ&og>BaPk;F*R-QGA&9qT+Q2{S|7V#OT!Ia&O9Q4|?I#UH&ze zubH>1xMrOAtf)%7Dp$`q-o5#%BB%E6g*QkEm%x7M4j4%y> zg-E|{VlHD0(_8+0)z7EJv$`4x1XYC<%!D{3ey-I=;%urbSMU^_fnhr})v6PWLCb>? zK5}k?*MGbl4|S2}_4kHV9X(m_T82bOlm~xi*h6mp-ch9%N^JA(52^T{hL32EL<)4| zbITNYb>UV7pp0!mHY|xD%i6;i$|$(OkGHs-jN>{TXg+c~o{kW&aK<;aO24tkesJuJB;5 zbDXh^&&TR>zp@WX<|Z4JDK6+K*NDxWn+Xfgy0LrFSCMc$6wJ*r*TlSlqYAZ9g6{m{ zEVW=b*NdI0bPu>E5L88Xd+|JH=3wr)W{Gm{)C+}LC?W15e?0EZXPNI%2F6!WDM3}@ zF7k~JfqZSXdAO^8UZK0wbZ?u|=-+NKkZ(J*Qt9UVPN5b`Kzpmhv=Ils@~wX>=!k3u5_f~sh*jd5{SPvI^1RaUH9Wh&G{ z3Hq(zt|fZ!WH#R-Cq~8!1Xa-<6}@*hP30ZGuaq^%)(L$rCFs|z(OklPyI)7m<+2a! z1%j$*KaXn}+1A|t{zK)$ohItD&tCAau?hRfC#m==`cI5mT!W?fwki&~I0T+sR%W~O zJh3L)FKW+ow;WNrpQ)!(3njEc<6+$EKX6ljAkHRymNIUYyH&aM-Bci`ih7RV4%XrU z+nhA>bKPRlvc{;5k1u#^+&+_kuoSFrb{1&Ooc~*dtjCC2FZP25L}$M7o3BVk+9s_ zf+x4!EN7nXqEZVb_JxOo>#MEctLSE4Tl$aXjgs&@=kNlB`VLW_qI01Oz;Wv$m=*jF z68qIaetiU<1}T21PzxnOyUd0BRT(fn_A(MLEQ9%tzfNqr$pwL+s&#nAM2%PjNj*Lx zF<*)2CMJ#H&(ES_I`5~e6yiI#YKx}<$2EWm$21)2|95qO5_J6mM*xqa_=$i)#l=H> z@f-XvK~=QAVXT*^aPAy5plIpuIYLdO#Idn+A<;#Jvk5QpJ~k(g<@5D&Ds@;S=*Jhs z3cVa8^uzpl%jUZd<+iMPdhW)%H)+dOOms3{2vpo?#wi}B4@XU_v&UeoWG z*EBtD2E6+JxlC`3@5Yxesma%TU#tA~PXb*YH4n_A_A+HYSYZ~ngP4VF%Hk-{WqrF@ zp7m`Q_vD|BH|J;floeA?7rF;6dcFMnt|OPcZTP-hOJr)H1l^Cu{iqk6`5w;}eEgMC zfuO1uPRXFl8RlP}Gpw}bD4zHD1M4dDV(Q~VJ$XcbpJ6`3d2ZMrX8*pjOf8fU{eAkM z9>G(l{=+`ycNPe$$|}kLT}C#S@{DYanh)jAvMTZYJ?F~QLWzq`>7dK6W?G(K?KmIF zyNvwEZu_qg2&xLbum+xEX1V?4ndK_U!}zYuA8fDbW0_hgF>u^cn2+a5>y_ubt8;J^ zAD;4@+1vjs5LDIBdo{elDF5rrqx{G99KlOV-m=$oFt0GNP-1zFC7{cY_pUrc-r??} z`SD7(SoKUBfuO1s=amqg;RT(KAII8mbt{k;YQb?9wr;*cE%g5yo>>U-CgCuvx9+Nz zzX|4MJ@>K_Hd`R5DlLBrI6RmLgFlrb5hjQ6KUa=0bLYe&>Yqlv&_rJ~uT|rD{T`QD zu*dvjYM}(Jp_osYOM>4fgg4R$xGg@~Ne|3B}`x>kW1XW3z3>cKE zh3u2M{(SZ2Fy7IjfI&xNg<2>!*>cl_j)yRYh)%6R27}J41)TNhthX7u#C3(Q@PRH`s@K) ztPEK?AM&EIVYj0`9BsJ(CRnV2b$Ui1jxwqmPvh+aJFx8G2@17PBD?w`kaAKX@R2c= zvG&9y9`o6Uy?T`{5L89SMCh~qb}AqIC4`N?HB1=$P-16?B>+ulL(AqSSjN-+lenK@ zJe%$jD-cvgM{2lIbR&-2oGAf^z19-lOQHKlbc}*;FguR#UwIr(rWniALJ4tqsiZ~> zPbi6j{kv=wN>CLYqo9Y7T_jJrkPC;-4N<6t67)UcPF$rayzZb;aJ*lRKu{GOqi8g_ zVMl&KVh&Laz6&f486bPyk$39(a59jL5QkanSk3ub!pd(q_ zyOSfhzu8n4FeE@rcfIKwq&vSFOvx)ItebWAL4yi{xc`!&&o6ABrhK zRpJisjyn;2;6oqwc&|pG7D~{XkG|(Gqj>r$&TMZd%9Nlg(J#E_&`4e-rWv!bvQemo z67=1mM`K|$U-GRX3%qnerUX@qyRY?1qxt@u`Yd$9zcRH@g4Qwg>>m}&_kO9())m&* zQi7`J&aXxz`Nr}~9>(m<0ykk#m=fY%>J0Z8Tw5ufy$CkaQtxrYZ3bEtH^rFlHc5p2pu?T+0mI7Zg&0s!nv+2D;o%^~!TQmDQcXm%8s@uk()0EmG3#P#p#<%NaV2%k zbpB+_Di;1>i3cU9s-|`ebn5w8`u+46ma#KnD!1LTndQ!1R!l9Fpnb4L)8q1Vel~YG zE8;UcP=czWuVulp6V+hTCf#VMM1LC3irl~~tj`ov3ngeDjL{I=%-~O0It#AEkvt(oBV zsx7p=s@vP%88Dr1KemEBdd_5Op#<%NHJZd4Gx>?X3)z(6S;dr~s(x)&Lyd>NaD09f zEJM?L248$SjosZkPo@@1h`n=+Pc#o7(S?n?@Jvh3W6)C<;@ONw>mqrvbrAb=PS#Qj zCFob6(L5@RkrH!LEU>VihM)11{k!;TIs}i+Pf_??)&!9%~67!)f z6wkp>f~w%{HmEalw^VifH7w(_a|Ay-DuQ|C*92;z1pNwdk0k_;^R6Dw>fD<< zLAtto?s_<16cEjPMiCQQ@zXHsN@HdthKl~R; zvR;b>ITJAB^ObPnkV1%Z7QQY86BWCwlPw>X2D$(zC zlyMYa;N#Bzc$Erg-zY)98$6q_Hj+D&^lr!V+fQi6Ur80XG4g5Pi$%(mK; z0sUW8MaSBBx?ksw`(hePn7&Z(J*9;B4OaRR&inU{V<2G*n#%L8CbMdin?eby5@&Y_CX@KhZp)by>o2U(Q-aQlac?4NEH`<) znq91(ArMqW&ky4~Dt{C|_%et6owh|dSxgDK&V=K{JVVLPueG`cBPi?6zHNX18b-$N zEz+NScUP%} z67>CJO_U^Q=h=3uhnuTFP?hfY$X=D%sENz449CvTJdPUwqipIBSYEFx&g#?i`8uK^ zHURcGllQ>FjOR+~p&&I?Et8yfTn0s2puORu5BpD)094XQmSH7QLyy}qefoYpgLSgs zS{U8tx>EdhtV%7ExN-ZGbmrJ;aIAI+cl&NFZVgJ$Dr%_r5Ro9Np5y08uZ}!~O(hxl z27T(*fGb`9D3-m4tJFgO@8o$&Qoxc+5K=S+%doecAdPQ5iVe<=EWh)LcnP|@{V}fy z1{7Yyk3~*N?T@Dr2W7I)TgI#AXB)uRCtIOo z%No+Bm(}1=?Hw@oQx&QH)vB=P)gCC8YvWk-pgfrE@eO51+Ducag%b0;E=iLD_QE`y z?|4;y{hP8^R_owUqZompsyRs)q~sliuw=(?BuWC_!m(xRq20V#m0BnJ`2Z?Hbd%{znA#$Z&@hY`YLX0z!VDVhq zs;^aYFn1;;s7j1wQTSk(G{Lp0qPZWVQVS(?@1`QI1&;dGC1^)mCnz7MhYJK%>3&zl z(ZF&0AW!(2V96cEcPpII767xB^&PK zp4AbSTUhwJE_}{P^c^Jsi>mCy3?WE=Gq{$mK|;>21r2WPX0_{17QR~grPAl7(d?MH z6r6`{WD~kfRjGv%<5;TX+ou3BwYRYh%|F+mXy!vU^7Lqdpep*@G@6cG&Dob{w^{p$ z(JHl204mihl z@Q3n-TH{q}5r{il$lbpmcBOU0GCCV>XDNF9m3v1*1)?EQ(Wo(a3c@LYU7I{hS@&b2 zFv_6BmXf9rRd5*WkC0Z6Eu&x4y7PPxs|h zc1?jrSu0@2W8L}M7C)?c^xNIc>wtqwEtKeQFbo_%uYuyvlac7p8}OXGL^d$0vp`VQ zqs-ZhbR!BHQzP(p3m8E(a8L&GXPk+^2~gsph>7ZPR$2?SNG zb>}eEZx`fz?}bF%mi_Eu!%fhu`$UymD3M>=3R-;F4So)-k(lsv85=UiOfFKU3j|dK zWLSdBnu9QPr8N?Lmw27YM4N zV-)nEzy1-7cZMpx{K8dgp+vVz=cHx!N8sIt=lBgeU{s6FpR<(dd#4BlRnajDMq_{N z4{Jj5l|6?isnkLVR+ua$KR5+H_wL0qrgp9iYwBEA&aWCL5L6|OeLk*PE;VlTUP-(* zN~IP`&=DZ|4%SYToEjUcYiAD<2&$svF08xOrqbe;b<_zCeT5MjC3HP!MMNlUcAJ0D z{uyAQzAf+(2&&Tkp8NF`d>OsD2+!j*`=IR_*Frt|t8000P+`%jDrQLHRV`dJOZxX- zOLg#tF8`;D3WAQWFJHNaEz~MKe1y>}CFnc>TL!1a z@Yl>(t$U}xKu{GOYvT@9_I>E_NTZ&f79fnmDIvB#Zw{2fm$7G+prhjif~shp#*t>Rg10Px}jPA|+^_h@Q(m8uQ+9zO3%dE&@SSw9UtLpAK!gQ`>Q@XsDym zwo`(7h@r1qch1+OtYSCoHV_D^qTXT{5y;~_o7vHd51wGHx;(%*F|F6ZIM18f(F4pO zc3c+pHM^{(^AbE|+Wi9CexxJ6<6K1`=(vs28296S5qowLc-@;ODz#8T9GCRye27KV zZO-2{a1scr60hp+knJqer#8Q)-$|TDk?|)T2Wd2&Y%`g^;~OU38Xyo3-)(GTcqOhW()5J;t*? z8Sz8cu!}Rs@XnO@a&g({Kdfx8I3Rw=m^?Gae|^LW#X$BVpC=R5*Rp8HuBw zHhij!5s$fDRi%WW+ByOV@) zdkuNNyq~Pet~LTeRRN>BLbJ*1;c7#UL<^q}tf*fZJLjfVsf7}(yDiiR*aWjK*FmD> z_62sn=5h9Aa({uKs=j}%q4kCB@L{YC5*ywCUsTD4FS*u4p&ppjGt(5K4jqu9p)jlp z5(dqjxkGbT4tuQ>YN3P}L&#Zb#e;vf^chCD#?)D@*jNXsd%It`G>Sy1mL1eq=3!vv+l4xF$hWdHpGV{8nhHLM@b_ z5vXvy+wTwax$1@Is*ef;RngWJ*RRe#WIHeP=X);aDbzv<8hZ<)!$hBBt;~D#D#o`3 zf~shXierXNc`S0_aBgA0U!fLC(8y+Z#-uERExk05+w6ZK5L89y?bve`#IrKyRHge} zvF?X$;`rrkt3@KK8XqdG!_n_f?A6Mo{cO$G^X$WiK|&uz3Hk+N6sX$g*-+m){9S;X zKu{H}Z#e&G`;N`-)R@nC+Cu2hDM8y6U34)$-dAwqrOqaO8Y(LksTzDoJRsC_(+{(Ie$zSFZo65ubF~OCYF33 zimtHY87$jw(EjgYm0AKpRdf`Ey@3S0O7I)j=*4egL`DgErUg$4IdZJW)Pf7RY+9UTf#z?~JIF^0=c0ZM@ljixe48@K_{+dGIj# zbB+HH6&6Z#`uIv4+svDV;;x5Av$1b=u>NvI_Kl4zFQbB>DqU~z(4q@F9;G8{oJfVf z0Zo*M9x>%ag@qDVM!wWW4Pos5i$o;8DhpwUU5+y5!en*m%op1BH(Z&~pjqYD?mXF@ z1=pS{i$vugCeXtpMH$n7rb;ckE2$uKzhACoOzWhJ>pbMP39Q}GTZs>k`aeX4O1uxu z=?xV*z1^=r*H-$`ig_#wE5E9WoZj?m%kzdqMc!~~(f!{FLif8OpE#aB|56RK*(a5t zWugD)&MQ#_D3a$BG$_>PynbbM9)8 zrSt#UORXSuw54k;mf&Q7&&oWr7Bo`b)qKpkP5&2FS#}sB?V4SKnVo%6jDF!0XTx@l zyLz5GtJFe?!LEVQw66`>o|?J{0x3Ih!1)?)i?2qx1sW_W3)g}6|Ft!Ei%H1eQv;&$c%8ImQdn*RG@U;;_?~BCFzA~6O*{cVSfk04I z;<@MAH^CO{Wixjqj-0p)dyO5{J^MPS)ItfdUhVlf6~<}XsipR=0zp-}TIt%!l)3Dz zk7cat(HyEKxT|kkIhTJ?6_)=^{P+7P?zBm|)xMp&^suWy=>G4@XN}p=iy+gh)o9Lm zZ<2Zhw^2t2dk9xW3El6PM=aUUI(_h}n!aoY-=?%ummG)xLsY2fQ^)>1{FL-M+gknH zp|kLG>HpRJZd1pKeP}os%LvpCh12Fu)Nc>H{|`~2qO}L3&_4Je+21l#H%#ay)DrrC zb-zuoJFqG8BrN0Iq7Tvp-x}%_&A|UdRH$@BMf-@OzF`BHa==oJ=)u(UHLT%8n=g>^ z>`>8xh0i5>XAN6ZZG5py4ptL+cR3NCT_MkgbhpxaLZJ3EfeXAT6kdvW&PaCaL3ng;O zwn&c-0=t_#3kla(MXV&mPZ>3ToIp^On5W^pc`iH9#aszG@g){*I-pR#PQGSkLc zr4~wvk#uezv*qzw=}P1Yk)W#loi6az+=&@HX^UliJ^Yg`d+jI}ydSR8Tp2VYhL|_Q z%fAZuZjd9-kM&ong%V=k40(Vaw_k3jj9xoPAgC&}ivbiLlo-?-k5`pC$A~|+8m#07 z_g1Ne5-GA4K5H=WhqN=YUf)Rnc#<>fK8=`%s%s{;@iKIN-dP2 z@j%d%qyAeqzSe!^lj)BlxHrmwu^A?bh{F8nuc>Goo>^aJ{6n1J8edTQPdl zP>6p;i55;?VC-zpzIva)_t7%65uda8lhQA*g+Ndhjn;(`tuMv#PES`9PwZ17(`cGB zq6dwOgniVH2yR|;gZwclP{?pZ2^w1l+r;5h`N32ZrOxPO0zp+YB9un+-E<_sC5=`N zrQcMjg%UJI4&F!8{(KGo|4Gs}fuJfHLrSBW6~TEY=R-=n=$b0EP=dz#!CIndd1%*T zihYrZKu{HZH#mlC;K0Mz-BS`R8miPn2^x(E&%|xE=B&eWrT!-ifuJh-HnF|>TAQCp z)u=0`TdUMUi8}GFurH)GJ9@hSYe`r~WB#nOp6V53D-cvA){;Lx&#||6o5+EQAu7%1 zM6)*0kpb?ddfaEb(lX_nhQY!JfD*JP!jpPlci5bt&6RPQ(E>qLbcBOmdS73&=f(Y$ zhLOXBkqjkhPlP_HZEmq{Mw!Z>)FA>vRdl3=?QV;w>{f1p62GgjFe0M_?TIjwr~hg8 z=*$a6-^x!QsEUp_@%u2j#Oh}LP~Kk?$D)*=JrTb1>U$WQXQFlp>L`pwsfv!AHJal? z4zPuers}~3T497t3EC53ZovJk*}e|V)LNeI0zp-D27s;4jde^rqPcqCp}jEDrv&YZ za9y-d5>t;^sWpFy1Xa2Qw}1(A9IB%8 zE9|2lZDJ1dYpETNb{1w{l%PEk#^wC7mF4WHqB_s-E)Y~zVAmO(OKwA_yjeBZx9j7F-W@gXrILg8TE zbx}vfuCz>u14#)QMHGDpCk^9zm6|GUy}t?sRna(?n9ZZipMTo?Sf1KJPo)-0&^WN@ zVLEaY-+wM&UibWs5CM~_Xe2&7OJ;|}5H9b{D;45$QbLRnTW!U7UVQRoas3vT1%j%? z2!G3F_GN2t{4I7G7p2m?hBSL2UBATaDt0qjgN8UK{u!=P3nl3M6VJXjn#SUn*HXCA zOo5;(x_*f(EUgzX#oAM;)PIUfEtH`1XpP1~JB_ukvqsrDIZPm^imqScD11Q@yAyO! zv9B~nr4~xi^#F}#P`!~%=B0{be1Jeu6l*0qbD%R@ z(z~9T6V_cIsEV#%q95|4J}m96g&H}ci%Kn&pzAZ}#roKiIbOF_^-Lv!penk4i8HUY zj%?noR;vDXca>TwLD!kE-SzwhUkAIWOTM}Y1Xa?ILH-T8wCGJ!6ffeB?4Xe^`U;fXeK@DXUIe92XR!8z~`e%)v^6TYFzD|ZtRL~5`ixK z`cTXXZ#hOgM(K1d?uBqvkdU98W>y!ew#{^%@8f7zTdw~zFN z0us2Rq)IiXX;~$0`7IW>y|+Z53%|e+Uo~#ARMzb8%qpD@kiN7)Lf)P7+jD1STyPUo zd!||<(1rUEid8RzyDP3;swttX)@$*+Ogt46_q-Eh;TJk9E7NN${;3@pDoEg7fnvQ+ zLa>t7t%fpb=n9EI7w&l{T2a@I%9gIi%9D#%7%E7}t1Rwx@1}SvRg@6#vN|Ntg?rwK zC+CMwN?*(B%34oP9V$rRst)nJ!HMolo6Thv&ud*I0$sT0o#^j2>Y}W7ET_~SldeMr z33+Zi)GS2V;`N5Mcsx@g(1m;6i4oz~T@+>U3mQ6miw+eea4ub(P;nQBR05;a&?M0p}9dd zi9naUo7MD`*2`YyIQ2CHCHPP|-r|$9M4$`bMOCVK+Oo=v8D;p&x31D#DiS#MF6LOq)Knbq-PeU( zk_mL-8>`rpkl`M746 zY4uVBo*|5<^)@)xPjlOPv&MItUnv3=B=Fo{IaPSlG@hP}za$fT+T@dMlMUIsqBIA! z|6<}$t^unWFyEoY)BT$2*&bT&4sH%IfxR&7&wVVjR&(J>oaWZT>{9ta1qs|uS&o4U z?%0gKBonA0f&1kCoj}*$uQ@76;7-1B3?$Hn^-U&>VvlRLhpiffB=}=@Drs-3Ac5z`|D8Zr#)Vbt|9zjMf&`vsFULRvU9ajnX}UexM7mZr zDOI|7Z81+j+SsxQUl);>RoBJo*?2urL1NSR&f5Ro`XGU>kk$6g_(v`ovg~E47@oJ5 zYyV#hFvTIA?S9&a)L0(r-lf4*wxw(YDO%IsT~5{PYXxkc-bLDmO-u`m_ZyYE=GgY($=`o(;ZQ*W&k&bWg#^0roN}2!1y4-JUy=z_kidQK z|4yI_TRxdU1qs}l|L+94u+5hVtfLN{GBsUtHu4=1`unUgUNnn*5JInaAVm@Ez5a*VSci|l@6R03D zZx~^VcFiU9if5_ofdsn#-ZI1=SitU@x{!(8x9$8Cn8nIf@*&-Ct!R!dhMX!?kVu`B z$(COaBzezgmTF6oKo_<|a*Ws;1UM5gMBHDH{Gd^#w&W@Sa{O<(1uta166(lxy-o(oP z{;K|2uR^KT2MKgx%O}Ucc5uOm^{jl)TusjDr2l9WF$NOVUaess%2Cbn)u#WEDs*9e zlT(GQ54IoJj>!ZnNJQB_@``=DnQgTw-TEMbE^NW&82HA5Zz`0 zRFL@l+cpyDx^jFrsgxANPV8D+Dh9S>xNkAGm2y5%L1OlgEo9aZSI?I(_ip_=fv)mN zXEp!3-;N3rqph}(n-8jL8yht$l@BD)wRz=c@?xW-_U9m%{~*?hUH88(JEt}KH2got zGO$FE(7LQ5_G^A=3ua6y6$1%$;W&z1R``Tm zz)sXJE|n@I(1p)kIR=jPls&eHq}n%PhCLSiAIl1fR~xg)@)&>Cy5;Ipslu{C*Wc?d zUfV(G1!4o3ncA^!10Ap~$oW78iDnx&kb67UYa=iBDwQfE(1q7uj&Wk^Y&OoY9Xpxo z?!G{q!*U9pS>5VYnGX$@oomBwy%q-u?&>|6Hj|KlBngn1KVvgFuumPPNC z$~oo(UD)@PQ-xRRRG)lSd)_Z?SdoD{URjwy1&Mk0RsbA5>$Riq^(Yks33UDa9cObvENkX6nVo7s-@Tw+65Dw@hK;+M=k5}brv2X| zcc>t-=SV7>e{=x*Qhr0JR3U*bED<^9s338`U>38S7Q~u_bSf1C33TE8FUN>^ZOS?? zS;mH%-*uSY(}PWTx`543yXt_cl?hakAR{UJN7Q!5O6jF)I}+&fH&9r6aYya`lUC}E z!Z*4apAKsWTd!kjvCka-{&t5764utm+6K<6S-Z@~rS1Qwq3#NR>}mbx4R%VcBI5OyOfgB?6{)D3@0CQw0QcVK^J{~(Qx4{1`WmLP#HybHu` zZ)Qe{lVLaBd$tYHc56l6dStU(4W4Pb<@%DQaoMc)qoL~KQE?)#F+5%bvS`GJBk ze_BN;2=Bq~W*KWxL84uHD?*#hV|JJHF%FnkQud$f$@8-ZN(8#(R5?_ysyy}W!K+*! zr9lM=9}&Y*#HipGDPl}JQB`Shs5`glo-GmRlFO=J`MO-SYcq{=_f%}!H)S0IKawf$ z^2w^^P1y2bpU5G)lK3Pzv$6ISX(z`VBEIvQTb+OEvYno<;H#j5L|u0$*22+AvT?5M$`a@W%HSA7*!kmzsV#9AJ$P5Bu; z@ioqpn><`XKdwi) zSr83)J#PDRCbfQ|kqC6{`R>Fhv!O~EJ#n&U9p2+iCbe$aT0sSgps2=d^g(+XzCBS8 z72K@&lh(|B z(@H@FiSo8i?9Schw9v9RUhTNQ1zysbo_3$MTU@+H-RD@`Lbw04kESW(>1 zVuzlO&i%-z(f|Hkcq5eb|IvtrJPV>XR`(MzF5a)llN}5R@7`WP1&PqvjakFh?daUN zFhTs>WWhJI>Pxz$21*3FV(>z;bt`+6EN zeAiAQ(1q7Vr5d~7hkpHvqF=|t%a>8>bDpfuAeHM_Y4m^pHk?7~9(F7Fzhm)9@vKF{ zc-siA-eodkr8ae56V^@qz1F1{JH}jCPw{uTzCD;snA@Ky`CaeiWHP*ES)!*M=OvJn zdr8Uvdvx1VDu&6F5H?r1hHAu9IxB)@h`;yMH)nrlZYYTzl^3FwV~E{6*%-a6`gyII z9W8OyOkYrF(I)4DahP6k|2P#N7ZZT(l1%2^wM5)q6 z0$o@u>$XziI!GD%{5j zcZ7nLp;TGr1!NF?df%@8t~PHtv*bRvIaJPLW7s*3zLvNha9Sg$3Kb-df6gHKnm_*2 z&_bCobWJDvI@)hgwzf^ip_1Qy^SQPbe@P}@=NXl>?K?+|AQe8BE&03Rov{RJk47d? zK_a{C(~@hh+dZk&HAeznaGgrUKn02X-rGuIJb9(>?_#||0$o@uWx}?|m&J&(dU>~< z^i;#t$^_ z=7F#OL7?kJuc0hT#5?uHq*Uo*o2ctGqomy(ym!7g{9k-6i`N4cBq|M?UUJuZ8~^?f z0$o+RO)qJ8mnRsO$_GAEzpiRk^1Fw|wD~`_qDWM))4HVQ*T3agsx5(Qu0n9P zDoCst(}QJ+(xpT6JIY~MA%QM@&dUV0IQls@efy!`OY!fm4=PAx?rl`4?*Tlv&M1{C zB+vzSTB)3)g2Zl{(}nsS9$QA}cXh;^BY`e#k7WW|=bPixwF|}X4!e=|A1yV;Kw{J5 zW!m|IK2bLHKT?G*e9p_MGL4EL`W}F$mNgrAsTY~0PnE9=Yx!zXNgG`K+w@Xpg>AT7 z_za@&i;T~7{g0L!+i)ZXWlk@l*WD@IFF^ub_>_?IQKd!<(YFBi)W&49W+KtIKEoS* z*1)r*)IEp_63G=OmC)}rAO3?tSBPs0(YJgS;f19L>=jpAS)t^~nQIdFA3bE~v1pKp zVD(DqIYvW?oO2}5wRn+p3GqR^`^W?;mn$?aaqSmxMfgiHfeI3it6fW;=kAYtmx_S| zx}aW_Dl1fwFdxu{=%03xYulBIfdsmCB>9&RAGWnEMc|vz+V-@hhCgpN{XgD{pe@lL z(Y0G<3GHf~UMdC>=)w~Dd+8#vZ{*&R7~ig!?la(Tp$p&0T+v*plHs1JEjIWdao>aL0nb6X=5b zrc?}6kO-?2Mf7hO&#lav90Lh-;d4bMu&-u&FS4ZHcJqQMfxbkknurP#Nn3ibVIoxq zF|MU*2@>dnK2fO{s32ka_}{+va9+CgK>}UaJC}2g{lNxD|9y*JHg=*0YR`Z4ERo30 z{+BkHpIj;*_*>}05|LAd3KBts{_W5A4J-XrLjqm+1|Y}4cXHgJ3EHtzH4zmgaCay< z1`_C!_kqMd9QJqC1$HBuqAv9d^Z1Xx57u@hHcs^~d5YTXE8Po60$sQ#q?`}zO{|ap zw`Z}w`o8~TPX>uIJExWOua2tq=O|*%p)Jv%3;SI%feI46eg7RB*lJb!tq2Kp;b?*! z1FsbB#feu|CQv~FcUbv5fi8Hil&XoSAc1?p$T5&W7mmEh1l9)JYZPmbOrU~<{2e4- zb0pA(Whlo$1qu1fNsNI6x^R3>j)8r((W$+OzCGXZxEX=ema4m`AQ91^Z^;`#K?Rpm zPXi>-g?E9RDpZg#eK5Qv#(~$R#~F}77rvK>6ARm#D^6?6&<$|`N@}t*si#%w!$yNh zH}Ut#kA!;F8BBI`Y)T@<{Ku?O?Nnx;6pC-%n|)e z+_t1uFQ19!(YDg{m@KZ^vE2&2Gi@Nj zD=SVDyl17HOnpr(liNzy9Er)k;tJ02rMdnCM2xtx7RsHDm&m?haxFoZ_f%(6OU%Sp zE7Z@vz7DOY^l{lhE}d+rpn^nG`=(^c%661&)6XuwwlY`h)y^Vi`UFV?y23?_5oi7B z;j;P|^SsTKh_z|t%zz*T6(okGIup&>c67mYeT+BT>nS6ijnQ0N-d@4CMtuMLS*Izf z)g_4j=%s&4P0F-TCWqG`kM9R6s30N7h`(M>Y4|FPjH=#VBG6?ma&9P6^=pehRh~EM zDzA*DkWU5e6;zPGJgHPWE*mLrr|qT}%@oBZ*oABiD@PwUTukO2b|H6%e)YakdVvjO1QOhbkr~!H(624JGzj*#tzi|&?JKQqkIqkx>#4~d2$I| zHO*Vf`SCK%NX~RK+SP0t!BSVLRv)ue#yc*e-#)3O>w$#h4Hr_mqa}T9q+j(Cy1k~d z_1Gf%^?;v5pzDc6Q?lTa4J}I5uP-_MuCDT@*=+jUktnDjVL#J_j5uIJHyY`Qy0&$c zyQTuA?5zo_SE5-gVI^+$&CHpY4&}6 zPJCB-vY~UnYoa2alh4rsY*s@f@;L04h+&o9nr{nAp*hwjO7zSj?0e-LaxiBT`Exsj z9q*AzQk}G9aC$d3#^e}@xxPveh7;m>%fgH5gYS~*!FBoU!{#$;i^uKBkRSOhTV<#A z+|q{l)LPCaop8|f3DZA0HAT&MwM(A-K*w$5;@k-K>t{0SJMEjs(Y!y~K01~Cdh}T{ zV0btyYdw`kDh&nEHo~5Fp4*DQtaXYsDD+{6(&jL?5Ep_jd*;KYU!B8(%Q^|d|4AeM ztSaT9#|sH6NMJmbs(-8vH_U6xKkUes2z0$a;=_^)=d$|mR3gTn2wOhbvMt{~DW0H$ z#7n!5?A4Dw)%5H9NcQgSD1F-<(9T5 zs32i;(uZxb&Socko(Uo?z7x;vSc~^9E=Tu0&R|3DwqY(Gsu2gLX{=~_FdH_tGKoJs zi5)GDVB`APh3OZ7KY^oaaPls_xWMVUvIo85$Kvw zJds`ViDqR7mlK5T&!K#4>@M9hO#t1bTFP2$Uuegq)+Ynj<*-LqCTx|?g3Opck3|O? zv6s%R1))9}!Jkb3N4G86hoXYSH@bi=8Bv$TRWldFwKjuz)9_2W<{4fRfv(^aSp^kPSrL0-JAN}Sjt}ZzNvjZ&w(_3xr80JKdl|%*^*4n&SMp7ZqRmh zX(EW?o3Y&I`4F8`jR6!DByRRt!M>E4t4)d2_jh;S9L>+1@zzxyHjdtj%xBkA!nKuO zyAgB^y_m~#YAn^(G8rt0s4t_qm1nrlu~q^_1qqBN&e}4F;Sn*Jy3S3;Nd&sE48=;P zvC;g->BYLlGX12oLIO)f>}+&xIG=DoUpM7LSBXFuURkjN|B^Ut<^XNVpcW$M{?o?tFP*NDnWNI^+=UC+<%6Fz z8%YW|a$qr2d%w|aE8Fund9VEqXOr6apJ{v^59raIV z!)0T+)}|rdyEaN9(1qnDPLTW(&D}eC)7{RisH$Z;8`ohv>2z`yIdd(Q4f&NrYI)2c zp~Y$Jbc#4z)_=N)vB_f)Po2?)w)=60&QDBYr<<%NN6yb8`5mUP>MycM-y=C>WpW}5 zHQPu=b=R*$u6Zqt-+SMS{_?#`Q9&a3+!*GQwSweKTqcM>Y_fSHO|U z%(r?0>6oLBQBdU1i_+3)tWQk^pWBlS2eB@nPLSPqatJ=>#V*b7I&r7V6X`7fic${% ziSt&mtp6Y_$@-ElV&uQ?$}83$MJIGFD-r0z6pB5UzlHEW(_?7n`Y#j}B<>}|vMO&2 zN#r$sjKiP%@O7&P(-Xs9N(8#(oc|f$iccOsn|9ZjC}|(MGP8l#$u;d_Qu$pN+v9qc zv?-HYswd;@+?MBV$e?F5wWP8_qG{>?_Ac!d=^C(5q^hukKX*)?LHV~D5`iu(H-D|^srD6 zw}&<7?+cbuk4y)NKv#8LGxqS>2Xg*`{;g=uS#ffmc`{WWwO0;SYrzJunLv6*T_KK- z+*$K)Q^?ZCmxycYw(RBB6w<-tgdmoMwdB{grO;kFdj%CFoRi(zXO=-|@OeSBxToeF z;-=D_zicD|UD(T1sT_}Z@y))|=?*VD1zn8}yRo)q^2nSEMN+?1T#vMt{OhGz^zjHg z1%C?(M;kY07qpFB&N?Vk^~YPo+xpL<&c0R>fi5g*mCE^y2OsqzhmP%RCtY(S?iV#@ zb5c|v!(@erlF+FkDDUK-u{&LWesVXUXu-@sx%4}>zY~Mc=F-|=s+&`-=UERlCBG84Y6{o(vQS(oM-Kl-7oDU?@ zI(jfyV?xs2-xDzoO;vO4s=jnquuPx}OF^Yd8Kv+(du!3PALMr&%+ryrEm`cg98E@X zv53(!*O#x~U52*oX0M=vM2j~;jPB3VoZNU{5D~+DdFa&3#C(o}M4;>1nU*Z4a;C=4 z?X@8Kt!l&1E_2r$-fX9QoaoK=ew@2Mq3>IAw4FDb-aOO0j{jToXk{nnc{EM^v!%Xt zN4;##i^INZCJnBypzHoTFP3$#nkMAen^HvA_O1EuI1Rb>qP~K^g~Z@#UTn!a6V2#* zZ$ykowc7A=9utWw-%cXXg?SQZF9)>Zx7;?77VR7qRFDWU^kQVqNX>-(`ka$(zC7bw z5g9yLCeS69RjYgce9i-RW+cWHr?*nGlmQmn1cNsu*G$bED*h;}KkW^PG3>&Qe2y+$ z@A^Q*II`KFkE>?ITpw90s3757Ma@pnd{!8{NT2iLTifxOvu0|4-m#JhbYU3^BD5`! zrJoD0pS6|B3W?~c-mKk{-TPN|eJf(Pic>s(b~vCm8z+}8y09*Y_u8rLc;l&)*~>mw zQqD0?tq!YM(Vtjt!8Xr{ z&y}t$`k!3w-Ua&Br{=Ce{^xT^Nt_3OZss~YMyo5}>b zFomLJ$O+)qLBCkEpSgkx5@-IX*_Xz%v^|==5-~!*x96McUSJu3R*q?2=w;$5eVOVtn}Ak&j~jy2A~sE2to0>d~Fu%e|zXu=%neGAef9 z*4u~Z3X7{r1iIF>A*}L}U)s43^|k%`s1E$qffc%gbIK?gvwE;vj|`Y;@o6%!Hf4

      =*E+#vW%D%Fsz4&0B< z*R88YwKI;H>%Ejt1?xWRk4CZpbPUP&R*7Z;FBIq))iS*QBXmm zt=P?~hOYrz(pTT^IyLIR`{~B$()w1F2z1G1)vr|tK5uh@?$!LC6w3#5+bxT-W=%X< z;(>D_#{HL_xb^$Zx?|?=DJn>~-3?(m#@6iSz$1baxLX@6JQS-9}+ndpoh6#z)BE2EEwUQ7zbQzkPxj zGcSPqO?jwWT<$7G1&QI`DI+fJ*~Icif~dcxBexlTM%OpzmPDWnQz+UJgCKsX;u+n< zRZl1?NL1QDnRBF?UE6*}#E3`^;_p$8%xC3xK{(!N$G0Yw=XcI*mI!oV3dOwIvo<`^ zuL2*rZZ|~*iTg_wW;%Z`YZ|*t#GrlK@=@CI{DtE_i9nZ}^BD%dJbzss-pg~Tlyl5e zUjs49xh_GBtm(&hM|5e;i&V9E`mO~O6(sCL-!pVs1Y2D{OAyzS2>?9;V}nzsk<4?U%yZ!= zcD1j5gnqzaPyX_BL+(0$C`AQ{2LV2;My09jW57H?nEar8irB~7eaR$=Ko_P^rQ&Ke zAH3X_zp9WzQ9BVn`7hxJIxWM%I36fvsLa^=V7y7Rj?j46)FqYG0g`l6mq`Rdai+_F(aiV707 zvVGXy+v012HTryHZFJ%PoOkCZRLvy7<#1MO%LPsM=NAMKKCB~;YGFb*Z>goAf`n~#Iue1d#VZFfgNDsDPgY+NgjN^KACK8cytt8q3KCx5u`NO zuDf*MUTuTvf`^6*mgvHt@$5l|bh2pST7sn@POo$9&cjdm)8uXC6;zP8@n-_-(6AR- zRDO$yaVVfGcj)L$^B);X1iG*k#2wWqgjbnuOM?fNS5QIXp8-kC^PC;&)MBTIVZ65o zFK_yRY^+jABG84UAil4C)|>C_evLeNQ$|4riPN>Gvatiyr({9mTjNc@P!Y4zx@la#k>ztDm6(m|c$zZGJ`e^-DuMk9mV+6lFCrFo^{EtMS zYew@Fwy4of?OZ?o^ZZ3(B>#QdS2x>+Q&f;pMP{<@?`LT9qjLq};1$8At{bmgKVzRn zplis;RJQx7iZ#EcC;mx`BMGFIG`hkhnE;4*O|)QL9?7-~GaG!ys+_XfTDuLnmbwSZrWSzu7_g;F^Lc0^;Ji7 zFNUQ_1iAt$&tS9Ov|u*(Itk+DpPu~DowB@Z_nI_j;T)E|y9LYluSIa~HuZD{i&a{) zMSf<22<2UPmuc1cc;l)R6(r;t-ggzc@f%i#T(z~KM4(GfRrzzB`IAU-PPO=4A6T!B+ zKGW`+&d^(~B}mv=#IcAU9_-G~1tP}EeqvT8c%QEMpS4oGLYH(GsD>}@%NMmipj)zj zvsBxW=tIY_jNy)K{K%Ce23-@*EB9HUD=^$A5$M9ZS-f+83*|i?uF;V@2c)|eiL73+ z?5<^P7JE^pSvKnK1eu?9LbJZeAiyB zs(-I7^D&&;b?d7u*YJi!pbJ}9@jhtRkJtJduG<;#NNPoq7&JA8HF#R2U9e9-ra$3U z7$0}tQRn#XxkR7~pAurs@^)YTJ+h(B?94~$X@JDNtl_M9c(yi$>EE{P%k|^xpa;w` z>#Ibd3!ir4-QaR>-YM`NyLi2ff(jB}a--PI5iPXitLWdh-!JIH$DfF0M|YQ%2z237 zTcsM>wkO{iFod0QucV-Y#EvDAtjzYwg%@_{XJy9s>%k{Z+M<1Tv5G{X3wvrR)w3kZ z9Ss`s&8FuFuJOQ?JlJB0=f^NFZXMo~_x*B1S}lSEz5$3eES7%!fyS2e5$00sgDz}W z#0ioG3bz#JIyrS}LQz2i-xyCqNpH&Z}(!A-Z-&CTEG+C$|vh20$tdyh&w8(3vXWGm2Rfh zR*DJ|IL0ByEFX!z$TCmrzVBlafi7%URI2meyYeo1XLTREj!{&Qz)>Ty(kZMb|MF_H z?#%ED5`ivkS43Mfu{%H3bepb%#Vv{o5;%4yPEk79lXp2bM^|U*6Nx|Yb$ zzD2B6yWf#7`DeB|sz@f#h40iV)vHTl#w4Mo#`LCz^zMv=JRj9_S|HClIFYnXkO_3* z*npVFdF;=fzONx*5~ZrrgWeU)q@jmaP(&pY4v7{jYR@uc-C zET_0i=Vib&W^6T^)W0lNP{FDmmC9|&NZzWMJN@U{d}+N85@&vh)s!hoq{Yjr;>kH~ z!U+DhohywhTq+UhGQ2gNeVjCaOs+Ri5Q)X3c#Wq`=(Y_`SnPnK1wp+z=D1qob{Cgu$ujN(7HULbv(mrDe?I#-;>uG{Bp>ITmh zFRtKMFk05Qz-hPxuf}^7)uh@a*0HsYyQm~)^2f4&Bj6c_m3JDW4M;D&^&sVOHn~$ z_4!ot`fd=xTmqF^hNi z-tSlP=H(O^$EV-wsZ~wPpr{~$>$k;;o^QtT_#Goz?#mexfi7I*DNZI;;(1JZ2X@ml zSz7&x#QG{L**44j-c4@mSNy)Ti{~3prLqehrbq<3aP6o{)%oLCKC#eHcV=h;#g(ME z&Q?y9TfH&dZC^dznJFn!3?y*Ptx6TYbu{;z{E>Z#nA&JKLAlb(xqe zl@$_$1}|XOuX<_gRM&sgP;fPtFY7*oIR`D12y|gx5F?PINAY5VjqK~TRnj#_B4E`# zb~OBEVckLc+TNpUEPqhTocaG;DG}(x8Y=p5FGlh=^}4bnb{nO-i$v4MbD28h-2Uo| z=j-#aWfZ?gRN8w7*GUAr@JG2zS`*YJkI2LjhZugQuo78VyHILN zkXZRoCfm1eistiL{rh?6pE0~a)(p~^?vx00VOuGBeX+y&_TV{Wz_SBVn~20otC`Ge z*G|p+Gpj`m2k&UUdgOIdYw2EzKo_?8VlUSAQT)cNhr~VfnAEl-ap>hV)>)}e7F}K= zVk`_C#?wvf&_gQ=G+8>qm0usut8H|G4ywLSp>SROa8H6)E3QKLQ!uHHv3X zX-eCj*)I{2OL{twtTTkquik?GdRQbqYmvwvK9#u-A4^`>(9hQzw~XSKUubBPb9*EL zUAUH4JkN_G_z>gPG`Pw!iV70AGFP07oH|qtU$v&YlzkF`uDZ@CY+0YBBx{X+zl`;p zBlz0gf%HbJqZAb+aP6@8ChkffzNYaHUFH%~X><_B{p4>Nw&eHWr^d)2fZ|eqG1V{wBFt~2^>!rt5`E*_%;_aoyny25`ivkAH@!_+lF(eK@D_9u3IT8NZ?4i=!?3>@PfD} zENa$vi9i>&k1EygfZ^Q5O{FW_c0ZLA7;l%x_f_GOqj}#BOPG;ap+uky+e*GJ3RXQTIqDbI8g%}+iJe+6TtIwi_9hL}mVT&rhYP65yr<(Y&p>t1DRFJ^=7O@uR zc@$q1mRx8v{-i{p3tLptrydf?J35$XW7l4xs33v!Mq;&y%}_qO#&1pG+Y1tbE^JX% zs^R@2c$~{)O`~gfC@M(c{Fhjnc`$-EYdMd&XWx(rbYY7s%F1XU|9NIDvDo*FqJjj@ z<i5$KY?%@{epJx@1`q)CrzNnctZA-_A~g`L>I1bkGZ)I8635bEf2<_}UHFZF$a#>O-z+zhF1uS_`W65QjkLZ!A<~Ph zye85r_vG&l(1l+vh!gBxop{@S2=BLVDA_;0C+l@)8tdBSgJ$vIaF%;Fg)N!(MYGhe zKRXeV#%d=EuQDWF@e0+r8JsVp{g?aQz-L&b%soNy^!?E9LP*_&Xa8MeN6o~16gj@Ow5CHnEdAZM}~?_SPKOx{3AfQP(@^Lt~9;{{r@rz#N3KDo)o@g0PPv-q99nroz!HMqHM&>xbox0tfotkee z3)sWsWzc_ks3WdcH)UE8KMxW9}=xJ?(}GqMYSqzNtxswo!#Iq$b(OT0~4y`#n6NDW9>C z&0RiN{p{UAO}5DfR-wy*TX)-PGNS87 z3u0i+@qDT&AvMeNkO^=(k66V%R~o4q@>Bn%_p0>?{Kt@7@>Mm2HvXQ+a_TkGSO;|^ zSJGFoPNP?7NGnQmE3agE-7_@1j<*oR?g0rr^LP)^yiBY_pex#Z1#9-kR`c;(2SJSJ zmB8c8SCejiqA30@#(Vi9kA)B4pfTF+D~RsrWuK{Rb{%&$i@gk`ndn z;clLd=Ucj+BNeVkNd&r#HF@mdu$`LTX>A0tep);)?s1#g&K^!tL89UKW$fd=vl=V4 zJ|AkAc)s@3d2;K)7>WuKODvbMkk{)p?H2VC#1KyrW8WJxdtkIgpv$n|QfBk@p60$; zupp8j$MNK%Vlv%sG(`moHfAxqX?9nWbTeEK_nyXyFJH=2ljp-E0$l~(OIdoohnhD# z^f8ua#PL(XHE6`^C>k2Kkae}LPAsYpB|avLnD?40B(z*8L0as|u_=xp`D8@5yo{u% zAVCK#W^?bWNVP-y>)~)ZjxYONiM}mAOd`-Frz)7oao-z_=;%q^smFi?te~|sG1xYU zd~(ZS1Hv50-Gu|m>Fx8`gvt%bseL0vjPvv2czTQ-UD&W6MFj~r+l9*KhSn>{@o(}$vh#Ho;ltf#vrS@K(7y4vJ8KFzQmy`~;05$M7)6sukq#_^iQ*3_(5 zxKz4GM4!oJw;ijK9&1BIj7!;ZeD(`Vntg46M4$^xTJ+)W$MGqFjp^de!F2b>x#G#J zkcH|vlGSA%YvJTe>W&^#s;pX7iRX@+oauL6kW^Mk3>-0^9gXxLy*~{Wsj|Ku#~(j( zqOCV}kqC6*brNs%?(ux#B4^6-+tX8GkBKeT-N?c-6G-92EH*(EMl2&E$<3g-%)z=1 zxprK?hGoN^cz(vdIh|;$rl=tCcK2L%zGg6a`fG?F&Wcga;i1kn*gH@n(1j%;zFr<5 z&oj=u((hw^q_RR{yh}DaV%dQ-x~z|JI53`jxw+EqJ6cNwy0F~DIJJ5lpKaBczM5@A z`!}1(LQ>|C2gTv!=B7+`JTHy>syv9?yO+UiOp-}mnj~Tj+@HX2HE2q^BsZj}AW`$s zEVlH`WMUVjUx&P?Sv~$PImr&Q1xui&HcD&ex5if`p0Z z9QNQrG>I1H*oZHxL@oI;T*EGHAkYT%^dd9BbpqK z*T-;vAJ0>kxzd_i4~ak*UVkwb9yEccpQ%j;M*bl&o2Ri`dp41^UptfRtJB%)J^4gu z+>;~^o5uEbT~3H`tcX#5)p$NdTbG6oHl(N^ks(e^TadhfbT6;pp~+)j0`Jk&fxa8> zE)nR$>m;6ohsSZJst(jI+)TP2NU#?fEGBO*8Syks#0XwEjz2izNR6IYNCdjD_K5pq z>O{Wzk%}4~xkk1>O=W*B6%w}(p(ORVSn=t)n;f1LNZ8eMwrImH^7K-mh|wxxGXLCd z6;YPukRQ)eSjS8ENp^t)iCUW~PJp^dCY)$azIIMwQA@9qWTt-(E;gRb*IXj_1-6lYb_Fa=cW0Y9m$I&0$rFwl`3*;BKPXINE4mlE#(%8_Z?DL z;h!JmL)Xe89}6cZ@;%0NNWg$#i9nZ}^R(lMe1OLj?dE6iq?}`(I(JTEi$d(^=*fdc zJ`7?Kd6eB4?WxA81QjF-SERCXxwf=r%tk@f*`CO&oN!?K=HAgDfv$}`(%9J9c67*@ zfr9A1Es@We;mDR8ysJS4iT5MYSYC8}`qDI15Tm9i@+CWeYYYAfCa54$FgTqhh~4+v z@*aZNzbcVigmz+4oknYrK$qK^e~G{yl?9PDU?N}CEJb6!r7_JIl)}b|-?Cf0Pg8GA zYRT`8t*}~y@x)$84=3@kGUncvp5-XIQgmr0#GR)}rHGTOC-W}7?X?%Y&J+ACBrcu* zmo9r{qDWQBx5?ZvbE-DQZl^?`3-hE>)jL0ij|)j7#W%C)2dAWxd>A=?&@^yPF8O=F z%iEehzG9cDY#UnO`c%Z&yEmSz)WO8}$wZ0@5^w$fEs@^a^!x9Qa39J)9=lIorktep zCygoj-OPH%#CP+!lD`*tR3Yv?CbK)4)---c4N-S_t7z`Atccvr+ecABBEHN2&uf(jCYyZ)P6mt`)3_;aoqXWC@C&COX^+rKMYy{j(m z@iL6y$%1$Spi1@dgA>1F5loBK9@4pe?q)tEXZV$A)K5CYPo-j2nsYPX0DAFeGX>A; zL!#(Zo02?5Ow;%Dn}<1b<#adtX^Xo=pbJmr6C>LLJ$b=Jf9gERNkIh(lapObV#FTM zmsQ&kHJ`G+744MKKqAnEr7l(idb;xQs}|Dhq@i@KC7xJmUlhzVl`7M@FB3%!#+vbS zW9QRdqZ=uxAc1F5ik)<3c=1zt)9A0Ib`pUuyiVfGNi$dee&7r`Wtfw61(CqBC{?PQ zr_H#Ml1f+4Ya$Wo!s{>QwtG4AiDCJ4_|HbtsiAltXqh*J-5&9rOft+9Ij^wEogbmO zbV+}E1r;Q)M8v#7eGMOVE}MQZsV5PVt7lhcy7d}4I8#6GyljIHU#Xr==j56xDo~K{ zoYal&K5>ky0rjw46=Mf9Ym)j%R^U>Fd+ANjqWU*|F^*-{{RKG9InZaTFNnC$w+4L?&1&IRJ zNz7P%h&1@2Ute;hP8grFsXyI1@Sa4VYe4tWtmDYNr1Eq9TAbLq;XL8!k^hsZL zm#GKw&Fi|+$>wJ${ua`=D<`p}UTaBOH~o5s$q7;Xysiyx*<>e01qnIE$J8kP%DxQ^ zs38;RGBugPEPJjZjngtkj9Tww`6Ep;nxILS`qZAWX>3L3xg>S#v{Ly9j*a0rcY4z( zpA{5;7YTzWV!uP1<>aaLOnr>S%m|#pdPb#?F`rXJs@`85%ad&y(r%MF7u-wG^hs`+t z^LsjZBI+-W)@cG)u{Xt|HNCzyA@a!G&VJ*#-|IwjF0~&;1qpdP@%i=y-t&SpiGLI$ z5$MW@Ucq`T_@e&RO8>@kquw~Ke1ETb_;@Hq1qpeS^Gjd?-+uFb;bYfv5`iv@vH9%2 z=X9?(zJ4Oco}dKo9Ct_SxhtNcf<&X(e0HNkqy1iftpqW`D}nRD-Pptv(1JsQL7ZVc9G+IFSYcI2^6S7&Pefxm1Ttskw|*e^;c9uG&x# z#V1B{U-KB<*A4*`6(r=DpQ)Ck_`n6zb?tU{ln8X?E?Ua+4K8Z8YJH`yyI zRl7oXHBALxB_g;)!^~t@--*6&Sv8b+p&|W?(PQ+W--fYL99tgC-EB+mzplsQ6vi5C9$2iW7xR6c_PL`BMqmkocUx`szjg*OF^vIYSWX~eNc(l zTeM2bIi_%dHizXDI6*an1wi`u>? zEs9^SdrFsg#F?Oign?zg*faO5wy;Z#NYyOA81dc2e%=4a)tkrl_;$Q5{{nGI%4sFQH$F*H(=V*;yiWQ2^R(WOg9Zfk}6Lw<8H6PVzmEH<7>m+lu%QL#VZj9U?yy~v>UgP> zwj1f;#S>V??>R}Pzf|TqitL>GiSra`7{&k8J%h-r zd}GenhY8*fH)c(LY1#GZF!QLvE!N$j=(B@|M8*QY-x=~iTI*nAh&MED}B5oXQzEv=SpoIQ^o6Lg9)}^0zVC(~X3B35*w!XV$;;b|;Vdp3TQGrJnytborbz8e zp9qq!9!Fpmj+tURuf|lV&01Yy>b-6RTQI@LEzSNXO=|JXK+#TA;Rvk4kz6cVJuOnQ z>V8;^*th}kZ28E$Oi+=%SIqLMm*e@0o%Su5D=oOVN}TYs9xjYaRQNtK4J>m=&mUC9wx zg=Zhu6BY9$mApK`_tHu(5)c!7JY4&jbg6oln$SZvoFlLbM(mCgP9f{5!`g+(TKMjBmX3u5Ge7 zGxaNA3nuW}WHXLpuC#6BV)1H64X*EE75=5M`v5x4lBy>k6o1aX3D|-O+}~Ktc1@V1 za_5xzt?&y+U=`luvZ$A@)1>@gpG2|qZon2y;B_g>;hp3!Z76IZ9Wp)55m<%yqU`>X zw6T&nyNeW;ynx$tVuD|{=eHgu`Go07nuRMl0;}+zn#Hh8qLQqesnl^yA-8wN1m3Z- zTO%GiNxwuBDe&fgj=(CsS7)9H_I-n}JzYuY!f1m1#`x?Xdsx{mf-Mpyw^D6#@0SPX zNyP+zs^61+J>qbhA<5npz!6x*dpQfXu)f<*i+CF7az0B;@bL^*7gMCE7d6PKqW4^k z2Ug*j5EjMSm?Cx0+X$O=j0ip_-yV`7B-=N_QeQXjT%Gmypk(Q6SQ+S!a3T0~8WR)S zEfDNlbtKExm1mIW9nz#xmaQPHxFbhk6+V@f$?{`Uq&JcsbXn;@umuzN#FXudwxvib zPrZ`w8)?rGScOlQ+33T(wJjE!gLO_IckYY{{`7TA@Lb97a$7>TEG4+M-u@}ViGvS8 zfC#`($WHZdL`z1cn#7&mkdG~x7~elt`2JLj?0#j*+G^{~IO*+H5l$@1<_N69Psrwv zgL5SB(92LQTgROuV*;Q2vVGKqxzYxQEiiV*T8_Xfe1gqlg!j#sqIU0xE5Z)$Y#S5& zDY8^LLu#k1N@~)c5PbHFPp$Djf!&#D5F)Mq(ux?XU*`4(n84++8w50hrP<-V$hCny zfmL{)z@ohM!=>@xZ9g(7oX(_timTvY~0P8CH<5SAoB~WxHB(I;2tWIZQmX(4Po)3 zPO)n^0;}-I$4-%dCP?uwn&93Ae{M{~1RgQiFY0fSq}}N){9R?w5m<%CN11Hml{Crx zLnT<5T;gJ*FoC0!*v&1q^P~|iSHkeY1ss7@IFgI4cQ>6AKSzX17ylhCAF@?jFuqYD zob`BMJZyosa6_#`s7|>pk9w;sc(QDZux|H_*$sb5H^lg-A(EZfHO_*G*M25~q5V2x zK*a;LhO@SPA^z$eB(1j$;s~tDn_wrTJYOZO%)ZXbcp29uZmyXkIl8oiEhBF4M>q>63K?z2Xw_>5|9fogVH6dVT(BnCLXA)b8MGV zBdmFQhSeizw-$K*n=YLxZ_5!_72f-a{hX&Y!mjShGMo%D*ka%{oG;L0cV zH)?8x&ij>R*pBg1jQgH0NsrYz0;?o**LwI?BUo4{%P70=qp2SXe9D!A_OFd8y^tIe1xGs6h${5~irFiR3 ztaLeQvm9G6(Q(jOg{ActA?L8Nj4HovV!x0WX>HrS9D!AMRASMFKX!}74eTzKsJ+~H zg$aE>HQ`1;nc)8I1}j6a<0)puhYw*w+LT48Vb62{_PurNmS(A0b`~%7nPUiQQ?Cd^Ox=?Y5vtVM}O=pvTY-l3U6;q^z0qp?)Us&b4))}nW$fxtS;dEsV*0y~YiLMwX>5XyY2(0R6(HSBHZ8#E zdxfxP$`e*b+o@ZLm=zmOUiv(0vm9G6;nn{i`QTk!gb{YiGN3Vw5S;|6@nIj1z^Zlq z1^KjLTZP1BFIgEKv|`AnBZ<;Koi@s`1rw8wFO}1&+lBSRmA~`rTBAs6ixg>FO=ph4 zs!zU=@?b-2f|??(Ijgb6Y91ZF zC021_?*~}1V+TAAba5<8tCLr@+5ru%7dTG3!Lkn@Y==`Gm+N~qXB?(#rqPH|ui@C4 z28guFgOwJCpwm)UC^O52%iY<(bpbG}&4IT6)Lf}L*h@V3)I z_*Z8I+=-5bH!KQm0E$g}5TC&ztpzs|E@9kCyci3roaqLjob7_Te_svGRllNrkwI^5j5c!Gq5(^bW+U2#2 z)H%}>umuzIuLVH^%M~zu`u! zzjT%Kj~;<9Z3 z6lcN2NV5#+WEv_sv)Bf{Xtq4>e^%bW5?hH$Em%?23U4vj2y!J>b&z|e zjnLDp*MDjr&^45vaXKkRZ#C!YfrfEw z8*UR#Z}nLw2J5?#(1K!ct$3{%JiHIk;8NJna?U%mob$cuB~WU5NwMgoGN$NQ-x&JF zDo?C@GL~QqCbI68K!@KA3N;O7q|?;{bLgrIapIhSaRgg1k-efEy4x*LbZ=+Fh=#AR z^xPd^G2(y+!4^z>h~Er-S!9*SBCA;JhgUq^yum_zW#Z2fShd@+0_wA-Da@Oc5nFdg zC(``Wck82FlgK)&3OINByJL^BZeZw82~GJ;_9SB%jPYXmw}a9h)0^{zSGgzBV#`~K z)RPGWTQKp*t`b5fS{}+E%6K>(-6T4v@SehBTR2Bx)tFmbV8_%w2V1giX%;z9kw^zg zslt%h2!bt`xMffY{f22Na;7OG=q>~$()G3qp}hZ0j=-u(A(b$VMYlOON4FKWPN2r| zKZLe6Q3P8sp>?4G9=(XC|wEW^y=x7=-#$-l4bB-Mj9?2U@SA1#8azv)Pa;Qx<&p^;fmI{YHbaw5sJ!hmGgii@ zKMC~Wj|Qj?2_uzz%i($SHuySUl~|6zs?|aXXqQyW zPj#Kdh<3IKRCn+Pu$w%KU<)S9`<6iK!4KsxZ+kJK*MoSf;_wdQ^yhK}RtZkUFtW{k z`Qe+&T;#!b;_11ID#Ywg1i`A4!5iU_`Wtzt-@d>T(~ic|xiM`?<%4j7Etu$MQ4A;V z$>853%4`m|LRLm(JEA=!k|VH6clbJ3b*ddye+gy8-F5Nwt7bQ{ft`qB3nrGVUJo0r z+Qa$v$`#q0x_BD-y)W6aX*^lodmZ$!?E%Rw+q!hZ8h8_64ik3=L2Alsh_vbp-H*>^ zM2qF|^vI{4WPtMwg8wfQ`FcpP(S{j&rvffpCR1AzPrEMFCqr8Wa8HE^TsF&(S`bg~ z1?!Pte`jz6R-M?e79Iw7g4gxo?5QT@$J2vTdXsNkrV(tx1YeJHXX5F`17>9ES093F zJF(vy_~Kv*QS6(`JaOTEJRSSaoV1MgBG`fnC;Qc~CD;x|epcpfUppC3Z)Td3K7+?` z1Xfu}MR3WTLbgLZBP#nQ(A=&zWbHgxf-RUxO=PF0#Ur8Rs}M%`)+NxL&-;^aiyev4 z{34jEr zO971kj-}m@TzD{hIW!%} zg~3a6!D;X^aG0sgP#7hPp!y?*lZF4(61yW4FLE&!z0C^g4&oE7oI( z{@h>e zAC|a(hU*{7Vc43X(09`dh`w9`YW{wp%y3)WoZ&XiM^3d%R*+3Eds1w{MA2(MfRY>F zm!r(V+JE1L*4gHeb-Q#p0;^^n4~AbX2P>~R2kUQ({&aYJE;;qooaTS_17(h)C(BVZ zxn&J)$Mzs^wX)%K3maIS*OmBmRrV5xCL8+i_f=%f&3<(MXd8H6r9;|~#nA7A4fM-t zL;BXO{7*gJ$M>g~P1cd^<$bxQ!bImb{o!d(HB!}5*;Y3O+S0i4^(1G$2}fWRZbO!X z^~ao!Jvo(>I1i$owhsek&S*=PEqUgV6{N7gv#aJnx3ShRxwA1Dcr;DfR>PgBj@oGQ z-Mu&cI%Rw_F_&d8=1&{d{C5`1mc%W>{5}I5>7_Pa&zYnb zHRqlRKM7yPlOs0trqw(W@ZORu0~1Dztzq_I1F~I9`PCj*mihTHaUt1v)q*3i3cpPj zxm@H!typB{HWryVZa^3)^PNYt{MzBqLYx1#VcDz6ze2!;<-VFW=f18t@T8Ym?(0C7 z`-&}?I3!MKZnp@QIm^zxW{#$X&Tgc5bSI9$D!%6Jj=Io09fpz_{d#cqz(n<$|GlTS zEK`@Ak~IyZ>YIm?mlk>)fmQg;vb#mbjiav?7?YJgYFy26oz~<;HMfGgdtX+@?;jKC zjYXy;<>+66Etu#M6A#K<} zXJ^~NUot?M%l_K%H=ZqPp*fmQekWwM!>K{Udn1@S1nORxnKZ9613mocAZfU{i7(iya= ziz?Z`PTVnpRea6AImOV1*V{onwTY`auG6xwnawRy$+Fkk*UUG>(%lvtpylIb1Y0n1 zwrv(DbKK`O=eX}bkU&*gj{8`as!r&j0>aX7^h}-$Prk@ z*L-koI=%GMM9^=#Ctt0#A*onDot4qRh}C0EggznnG{)|GNXC=~6n~n!Z_4_f!VQ4rar97acM}*ef6S zBpc>;>P#+NtCnlC)_u=z3NdcJDJ1b?I@SKTSE1RBdD4&t6J!2lLo1UmLpHPjDNr92uN)(&>(oZNWKnEJt9Kk#;sX zWyr|Fi%Q>X?$}gn7|;k|)0#NnJ@)DI9{On?)9BH_W1xS2E9bk%glbt1cn-S&ANwo) zKBxQ5qfgfDhtQaEj=(B>Iv|tDk0n!$ZaoOysYXmKm%x?mRnV*dRB$j`1gg?z$T>6) zJ`T)>lkC=^Ud^`-?Fdbw1MNGKjt0Lu3ntFT=R?AQ9dNhFlRZ^hcru+=+L1i&+MVG4 z3#<6kjKO14>7#wE$s)J=Tw7tH-}XHCP+kW|%ar-GE7zyeV)7SCzW&P*ScOkgm?!mG zA`K6-Bv-3V2;L9m%`E_x@@!}_4dPB6m?zaeiN2m=O1>}FCwSL@iNCv-fNlA5_|mAn z3&}n{k)E4lLPoZ=;|Q$6EyC_3@10DgD~3dBrOmY!CRArH0byH{UPwu%sqHEpw@>xq2&}?BIhMzAF_~stYD4Pv zQJn7;6S9p}kp9?8u9wq|m9fD;nKtBFz?~2;j=(D3*JqxZMtj@m)hG7SBKY)e=$LBw zSzh6oe(a(Ajn+2E6%y*tH{Z+I)h3NTzio49z+_#5EtqiMu^n1u9(B|=P~Nh6;ZrJ& z`rO&^&_X?qz^V|F?XYC=9mhqT{xV`_aXPL0tR;*JwSc;PJ3-rcv;DcTR~*+D?S%Ut zU+wdYb>(?xH86?Y_qwI|zE=es+Y8e*1@dSVU<)R?`|X4y0b?8*t~;4+_usHv!d#_cAG-$B-ln8e0*kM4Sc zpYKdLR^e9Qi58~mG->o&p%eU;V+$s5{aEV;rBUI6mUwZl#1U8(lv52bq08&y4nwy%C8dio!bJC0lr#;y7anxj`5OYhe~I?I;)%(5k0o?Hi6My7(g z-zrwdsrFN8)bBrHqNhG!3nuQaDu5R(FIA&CFZI33L^^h-nl$8FCHH?})$8rcpd@Of zFnq`+Rz`ws6ipf1OY;8H1{_;101cK2{h4J#=NaU{gbRU!irF4xOtX{G!(-{|2VJCx z)unQ5!Nj%G1<+=`yKts%3oB#pIv*PSS4+}ZSk4hx#Xr^CwtcDjH)m;YnVVdmH5qF6 z<_pDn{}{J?6$Im6W(!T{PZ{I$VHV3d+L8u_$fc#p9&&8KM5pEPaP3~2F!H;^o=U4| z5OwhxC>6Z9%Mnf4RF$Yp$G@V+$tm z2|qhAF&aVRxKPKJU9ZY@XCO#$ljz->*6v+`ssn(3IG%QJZLZ=l@{4Y$akAta|Bl5 z^$NRZ+d7Tvw=fZAY|!TBb6f@=SyS95g$6ynB)sfqPOt?NxE0ub@LLjXcfYgPImnPB zu*%P@3LIG$U6ZLYi|&MBJWZSCCq7TGBiMood@|0yws~(Z{l05~Xc1+~5m<#|5Lg7= zsAyW}ze=3sV$VesV>_PV z@Tkr1nNW?OUCy2sS3k1^Y{3McyJRxMv`DJSGWDWarXD7+%CBbyTxfcy2x3`#Y=n!S zOSjst6+dg10JdNP&vq;`Y%)8K`m;cs^R}KNuxeY}Ru%!ZUQyqi+h_7JnT`-0MR)i0 zfGwE7s{uArr=-%hHCm$fj@=xAReV%fN5wokDmPDvVwrl_f(d>_wzp3@{k7?t;vBe05(TMBe^rR`7klExXwa#2W_z;iH*baL^a4}N!&@`kVH2(02Ggw)k0QInP` z(x(-Rxp*H;;Qq$eS1|!}=L|A-;s*SJU^OyC~MZdNUt zMIE=+ilwD(xp*I};(zBg2j|jk>Pv57EIv&#&-12Q)q6`Ut#>|mfU!SRd{q|@uJK#v7uk6;Q#VEU<)R2 z1SPvsE^QutVY6CsSAevsU`7w6UPx) zh5ZjQS%$}4nwe%pBIYmT{0x{V7_=BRe#wLv*Ohm-)f|hZCHE|dvtt}bU=<%{*)l4f z?&%h%@HWl@>~F*VMC{RHUgz;?RL4k^6IX45EttSQS($9SX9_)^=>r1~IdTM6{c|l7 z2D2Q+l;#}8VOH@}b<|ccW--s$f(h*9X1#s-9J=542|O)W#}Qa1Kb{UhSZ-fQb8g?G zZQ- zhx*YjPyI+`Pz#C)timf!c6OKIPA9AmBoPK$+{zLY{OQu=Z6j!LeF}L~(}^Rn3ZJpE zSk5?mdZ;d&IQHnnok3!PKN*dmZ$kxx<>Y>(8Ao6hJ~3r`gY%PUv||LBHtsFKvB&tF z8=ok%II@CibeqO>GO6Mo!4^#5vwL<^NKFvE$a4EWY&gpiST*?VJUGMhN4K*4QJHMQ z>PULV%8}gMyPaSQCh)kz=8sV^bX24@4aTQeBOAL&&zyELlS5|Z4L5z z#SDTin7|_+TUq8M)8V`BLis&gj=(D37an~njlK@t1Y4$E;yl}!z)|HaI=VwTJ*GPc zPCrfM2&}?>cs5=|xzU+dvPnGqCK8S}$7la|zr((8WbI9B-lvnAz*ZDnFoEAJix$b5 zKofGqh)LsDf(fj`zZ;hAq%ng!XL*v0yc^ta5EJ;#vTqNVg;Lo;TVm*coFlLbj~FZ- zE^RjLVyI7y>PhYdeM;;V{9! zbGj^*mYj@%po={?0;}){&U$<6bXo?QAXnW4*n$cE{Nw7Cbb75ve*LAXojC%l@EH>O z)&BlQGVK1!uV0x)g9Sa98|p<0wZfoXg=+KPYrDilm!ql>+HC}J%}->%kJKHNWI{(3 z=T`xS0vvw;Yg1Ja8c$*p2P%`vz5VGOer)v`I>#KE6wu zRsHpIV9O}d{P#=OJkZZ1@|Nrt+3_p$8Ii3nlCqJa$?nFt{(W=cZD62D;B7cJKeXjGEBP6CK>7t#QS3)9dCO`{=Jtb z3GKWY%HCzlM?O_2nlrXT+O`97r(!jtZK@d7?AD2gqZ7q@>ta6$=h#ynaEqkI zhr1{`v(htJ=?Pm^6mjVq#(-lX=u`dIU4yEP$ z`zy{rZcFB~8uqU3uW)DWGm^E>=wpeBGcVLhuOMa3H64bFnm)OJ$$|jKg+yp%bnhS$Wv`EX<%HLpz*oWfl+Y*Vs=Si^z6a62y7FJwoLCo51 zVZ^d&cf{p)6hwUL%@J6&XI5*Wk&Puwo5zx_O@as`j+1K(Cs1s`M4;&_#pwR6$#btN zR)+qUfJV`T92$sB=IxE0vh_T}Yb)1g!3$lqxcTQKou*dE1;3^g*Pd1TOCvQTt; zaf+mx&)^8G;#>D_Xbb7!twm%>mKTk8HWR+QG9~kJ62U#(jD5kyhy?6Thuw-+!h;2U zh_q)BtA}-WnRIi{ax$y07sVD#xaOG&@BTF)e#?|GUWS*xiY2Mlq_w68RoiSPe6!Uf zX1ZB0UBz4&azckl=NAKRLw37Z#V0W#X%DHNKbC7NOpG01E|fcHkw8ndHf#iWaw`CaSho_Cv-8B}+4)U?hGa0d z4jgmGQEb74<7-o4Y1}YUe0w@8V@25qF>T0S`IDv7IYRYoOF=oetKDPY@-EeC{(J9i zWeokV&l=M0v#GH51pidHyy?G8h4C-k$*oPwZzBB&Yb_bQGzI@_lPI=ef-ht4H!W$B z2D|5BvkymLRlOSP$Lt9|TPn+Vk!2-jFK+|ZJyU7*U>k*UH8F{;CT9M!Rwz{s4tbDJ zIJx=nf=Fe&sL7ET;%3cxu%S;9M_|>oj9P_qCDWyOB{SA4U(6k^0$R-5iB$zBwm1L3 zPv$NJo^U!-EZXU+K*P+r6k9M+KB=~ue)d|KYdL+!0dc-j9Nh4Y;s~t5?Z*05R)aWv zOq1L&Jc4_Jm{`&Bd2<=!K4pZdhv`ExdC6b-j8ii?0;}-*XC6qIC+vTu4o=zWv~8ze za%GGDRnG^hbqh!3-wPZUf!_Wn_NlvF$lcJztc+@#w~l?Q)d6m%Q*6P+v}aH4m2{nf za`fr4$xpcFl>vVYc>=5On`K{$Wna=vy4?nhWa-=+#Kit9ih5-kUH2+imU;#1qIG2( zFwaZl2&}?AhJ9niyPj+`Q-P-LQQUeLuW=)Xv}|52n-nQm$iC-0(n%S|cyktOJ~bR;8}DYGCxsedD?&&HB%R+Fe}J2kk^Mtubv z^~Y_p1grD5q-0(cV4B^2F{dg)r;vWbm#r)B)zi_M_?7M6U&gEafcLLQ;=!TyeZzx;5`oBy|5e1 zm^W=h;vUjz-dKt)m^ic23et|~kS>RmBg5YZpUKF_yU2=Kp1`WnSyu4WrZWkSSB?zf z4NauoofX8RlNWu~-3nG+H6RUH3*fto6_u2CHRgEOqUb2Ew~u&P6zjUx28 zB?+@vetqby$}n+Y|01&9D4JpmCh%UA-N{jZLQupmBF}Z=I0CEMv(~LCvn09gSF$p^ z*0Z|=OjeN(%vZ))(C(Mt*A7_k3|fr%{2v0V@J^rIs$!D{`C2t(ykj)CqsIjAXV~mt z4Wp9kiGs}H2&}^X2bruOut~5Pcbe1<2;+9bcz2KYxNPk+t(Dj+q@Fxuegun^edpNhd!vyy>WhYOSh`-DCl4F;ra|BlL zJFny3hs30>l|=W@G;ZgG3EV5$9lukaiZOr z-H0ih)vyH<{H!LHp98IJ9^{jM5=USaZUuHmzwSASo$y!gVi82KA0O{h@cNpKaQn}b zfDf^7Y;PFF7EIvY!=fw(T_E0UUE;>pC78e}ymFSw`gW-!m26$IjIB$s1rxZxF|YH_ z)8w}0a8jck%n?|H*TKv?Sih5OkDW%A-wWf`yO_Yehh>w)F%rn;^X_au$Nv{r@gqZd z=vFe2&F6dAe2y)c;CtcsKQ!z9cx`|!3196 zuwClcbkUWK4E1bezywy|^_)z0^X_QzNN_NzWg`Q&U;?jj*h;4SoN#li2l>W+ADF-@ z{99q?&d){(wyVO3=i5YzEtud|II{82M!|4Kc>IUJD*iV(to{V-Wb3P!Y<-0-nBdnw zr&NZK-!?_0g00~&fmOK2usZ>l0ZGlTCR*N+6k9NXPdV7V=Rz>iZahHpHid8mR`ESC z-+TZ$tkFQOObX#qXeUX1y%I{L zPJm2!8h}mv{474pH$1P$KBd^+uGkwP+9HC~8*I2An$A6KuhR_o*eITbUuh zSXIG@O@sXDlcj$|FS{;e?Zg7Op5`FDZ0Z2ob<5yajE&H?RtLJBTLcH4h6_)Ib!CLn z)mWM~(Uf$miYFP{7lZod6wn@!3B|n%;P;7f(D_R?3|UwJ{WNC63G?}k*x4zHnzV5s zQL8IReg7PIRJa0WtLDMP+gWht!D_I#%7-(9b0Er{<@cRcX7@i|A4y+q0J7=*Hi9jf zIBdEQPWctXrAp;a__u2iHJai@zSW&48`jSU`ME0Swtp$?NJ$4T&F#?Ns{p2s$pH74 zD`4yiWyX49b|5`r<3rA`xJ0l86I~C?gXikiV6;-Xk7~KwnT~$n0Nc}yY0J|?U{cd! z`3SwYaJiK|lrD^xKiKyczP@#b+JmL?Z`&U-;?pHl`ez=I?6;S}0Qq#-pO+=XUHmFn zi3|WM{Y+s#?Z-|UM!`3sK&X1~iba?@dK=LU^)RGtm&j{vOkq zFEnhA23#Jy2hzZtZfbOpGQM;m*n$cDDkpf`afwhDrM!XWt4Cj26-=dlT|WS}XtQT8 z%PJJCvTXiS#+Pa%nlfUjlz;02XTgL!qb-&e3im{1&AXHs(Wr4lrPJMc0;_N`so) zZz!1cj1?xUZ-qObD5Q}%;o7M!;JMBp`uCV9*i0#5#Ew{J8ega*E$&}JumuycZxjyP zh!fQGl;?wE_fY!rv99D~x0)lcYN?$QxTt0biEGy~f{q_SPaSJ54eNW599>0WUrdnT zowE-#Hd2@>&J^tD*MSf`335)k3Y)Je&ujAJ+TDzJ zl{K99Io?)!qq>tLunM;b^RO6>w-S;mc8U=$1y&=j0`VEtpUlLgD*CA7S*jBa9eQ?M@}tmm=BSz!6x5 z>&N0`>POO7+D&3=4f`Y_Y7E+W~ z#IBiN2_~=#KOvjdKDg61YwE>~XFd{a!NmR|0zDfB3vC8oWM#zWxYLzSkBgnf*BpUW ze9esqkD(`4riy<Zn@8(-!&hu^@ zfmIiq9HGg2siMO2H6#3QjHK&wt%bM6`qW;-5uAs=sF%%s2OEbvLc`?liaDR&f~mR} zy#6(-{%U_^&0mjjrL$iI3Y#wWqS%6ogE@?DH(KHC`<4+7mq*jyVz%&WbPtZeD*S{j z9&YU@+O1)qV5`@YVhbj$&pN{HUx|vK?r&HbyZ?-$LA@^v-L-pg1Xl4ij~nDl*Y8+b ze=1j>mQ{Gb(WBXp{p=q@YNi7uZQFN98vp)3H8*}gg4#S?qUfsCo2v&VW*>2YS>X%n z8+*QIPt_}AB)xU_tKylz0Y_jJZgrNsR6CshDO?7JuNhLj9>nWJ{Iu+(`pPic-aZOS z?2IT@RnD@9<&TZ!PXD|Ep2)EtPS?4Qgy+Bea5cw7tA+Nken%I1?X7pL9t97F(?QNM zaE{^$tlBiv0Ww{dIEd4gHTPQJLI)>=$)8;@q}XzMyaOcqU$uW1`TjpoWw6JEUdqvx z@7id{JryPjGaTSpzv@HFCo0Pra>IrGyuI6TRxD3o6@E7?_Ph}2Vhek+YOgUJ7d{vc zxTrxt=NE8j)@bnPrv=&pci?=i9h{nM2UK6#+q3F`u6Q|$Jn%50*n)|${;oi8xI+i8 ztBf#`9O=oj38Zb1F-Kt4HZMDP)(2o`YvoG+c_v%+RZb?M-o_MLFcH|>4i3y60m<`~ zzw-nyLOp+&k}tRUdi2d73~}ZyV7=x`u1+kvErC$eTP7s_u`$KZj)}h;2g90zpYqCx zm#mEC7o4c4nGWgTXT%X$g?lKAZi{uIeGaxD+S`q}zKaQ$#33LiY?X(MR{m;lyE@ah zE_YzSDxSb9yjx-`OP3*ZRBZt%$}^gU+S% z;QC@9T>X&&1uw3`&tW6r%C3bFZ+C_f`!5Wk54tTN#wUy@wqW8yhd~fgmjeBglq(te zbqAUs6;B+__2CGt!hMXzku}-VR_o@H9V*5YTQE`TH3%kUN5S16H&_{P)`9B03L!Jh zc>=5WzB{hMhU!c$BkC7SXnWBH9^d!`moArs$$1-idG!O_I?j9x3*4Z%@Bvs>6|*vo zQ*G&=+KnVG*_dJrCivDh`7neYpSOm55%oC&tLA_3fy%&}@U>ofm)_J@4%DLkD&o+p z7sVD#;J3*l=rV@V(ZK~|(V#9IfmKmz0dT&@1vvI|4J)H*zzBMvVi6fQs3XM|OnhEA z1GI9^!v0Z8qU&H^+QN_B)?3_ys?D7PxgYBx_{Ivbv0_;ZZVK>xzXBQ;g}}zPt6}7t z9gNuX&4UhVNF}4F8pRe&98e7c^6d<)x~KGIEOT(9x|1`>>OSo_0;~9^D(fa872 zZhCIyd@|VE^4>icf-DNa;ARdh!`V5C%8w5qqE98k7ED~Zod=szW@bvNK;oszd8DlRyzy63@(D*{aGB) z%s6PMSq_uF^@Y+&%BNC&97iKw8IXwn5d>Q>@y2ll{E~))|E>f^B!7yf)pzvCq!uY0 zfmPU-#pd(UI6Ap^KN6K1POt?NpK=Re?b9F-Oq3q4c5~zC`2GFJfHt!@0;_l*Sq1Zl z8f9yc{izGMr;1s#3SJ%hBEL!&0&Wo&$+0Gms`|WuePb7LZH0+$$JfE2uBGxi<7D!feZDm z_@~lMOQ0Y3S2z|vTR^;;%E6x+IC^YxfhMUO{wfYR#@mkq{Io2F-ZOzdQ)q$MB9p5J zCITk1`>9)G%O}3}Wl!}(ErH6tq9OX-0*=5cTqov%Y>cCCM`?&t^%Kd%+2s&=F+kD! z-cSq|&2KA4t~X|c;5D0O zd|DxP9O*-_1rvtu8zA`lXT>cuLq@#X5lP)r%fxru{sdbv(JikC+p{n_tv$9^sGT3^>8Q#}UuI$ALYpEYsrMAeywmR=W6Ba{7Ji}1{eXFHZ_nLV5>$rqBh`dzqL4HI|; z$fA($x>D})G6+z%)Y%8am zmHQ}rGe7#WQWMU6*Wd`ODtMOylkVm_mIo;75#K48e(thRe7~@cs7Gf(mzy#n@5Wm2 zZCnby$J8n^H44GXb|Fl(xUKlezB$A^MLD7L_RuL}?bQ7QTQE@^vIGWw%~u#lDgD$- zt%K>oNt47~RmV62s~&t>0Jp`R3P@D0$bwjQ(2NQFMJJu(1Y0oi=;-4XF>mOT4OH!@HuPu zLZyZgF-0?Iuj{LX?_*wZ1XgvAnFkvOTGrEnhZ!+dCx}k%Xe!t&drq(g6NKHY+WF~4 z$9o-=K79|T0D3j-iNay=SB}6czL%U6rqer{*E`%y_&~4)6X(8ULDeT8`69($R>saJ zld1odMtM)`78Da$h5I!7)$X4{Gh1ar#Hl|7TQHHLlL?huugl$|m1Bw9`|;H9)Ok3h zsmAqotir!dHp0!ANDXJUBwlu{xZfZqlGrz@PM$Y}c6Q2oz?d;P;I~$Jx@2O>JoIgXS#GL2M_?5{8*IMlLk$DNNJ?-kZfwWI z(F?I47M6i$+D2A}R(oF>do7w=Gi%8aScP|FY{ybEg|^#TBU&t~C#NA6f@YZrd!pHT z3XMc9C(eNbJ#~cI2g={a^~L~NHDrz0da6XQ1rvBwVqWKnsnlFj8T z?fFyDvz_uhD%pBET`@6DtZBMHumux%RAS%e@SRHSt761HgYR<$R^3?;1?OKhC>|VC zo?vw?3!vF6T*cNF4+yqk0*^}U6kyyG+I^zE*hTi9Be2SUStR5|tx#MM8dw=ehEAgo zo^=!-WxgZWf(dR^l4a!jQ}Y)xvBi`oj=-w;wc+q%&LG8E4dv;QjqMcrwO73`B;gOi z7EIt#iJd{}Pox#+RtQJ@RVgO0YS4yIXeG|8@4NRBE5oC561~=^pKw-eO|bVzZ)PX7_{L|m#_+- z0&y{Yh0l;=vQ9@mX+!%*irXzZaVI92zv05D@xJh?ucPSMxBJ1Y zqzC5<#{^#c%4FZwU8r$yRdVKwK1W~`_S~~?(VcXm1zP$fZ@nJpp~nPX!?U)^bEcIa zDXCauz!6x5{l4sm@#3L$v!55ad{>Y22x9{8McCf?0-~!fTp?=Q2B=?nRTuc!r_;{Z& zGY8Ym^ZleTv0)s6RXCoBeNC{{0GhhSR{FG0pNsLrzJ-D_Q(@q^WMNidFspgrPjV_s z{iH8}Is{uVfqerq+2PwRR88Jfdi1V8M_`qqc?#s8n<$iz^k-%Cx;>T__0g8jwK5{u zf(h(-VLLCG9}Q;tOPb%EI0CC4v3%PH?*|FF4?I{IZ8rMT=N-R`H4fGUTQGs68(H22 zOsB2(1k;huY=IvwR}pN%1ojTgWCy;+P)k!0 zBF2_-1Xh_&DTJTbWzel^6{|<|)j4$Tfv?b}aV5bPOkh7eTVJtLfVys~#6Q1`Bd|*4 z{bIPYzd!i=QkK!8`y6^j>`JO`tRUEe3G9bw-l(IqX^Wk`NxLDX9D!B%)Pcpxe2$^D zdS;|&%R+)Jn84AkET_6LhAw|%LG+>vI0CEq(~SLDF?7!Yk=-v*PFl@e1)m?`X@tNFic=FlI1XA0XsmJ)2i#H34WVTx(GW2~+6 z#3Z|A41N49QP4m4{}_Agu&SE&{d=K=fQ6V?V1S~CbnThJL{U+&6+5sC>$WifyIbt; zM1?hL47}~`F6?e^^Edl>d3es*$M^Pl|31&pzShi|wf3y3YlA|d>tg0C^7+QOw2Z~( z{c3rv2QX9b%XShzyix5axXDoEh!Z@CNm#UNIZ z4&}qIOj7O#)-=vQXxhid@vQZ!BRrRR^(V|)Ac1XKjzCr!z;?SAHuPV!6#`vW7Z;KR zg;Mk!Ma+BL+idE?j?JiJl-RPEqJl(x_Zj3?`HOmw4HG2scavW1`JvH9(4x5tfv%7{ zGfC>CxB7t0fs%+!j$0x0Is>OD2WHs@*e`b;wAlD}M9* z3S*UvyNa1kNeY23TmvmvIt?Ghc5N(fcvl;w%#vXn!+9#XPk2u}OOL5!#8e-r%wQpb ztw&~Smj7x6!`mB1fuRb4E}UtScd%6-riUjOEpH@JRFJ^dBUcXe?8*MBpJI&NF-#%Q zg*^i~+vnbuEnU6Sa2}bY^Z<}h+tr;-9oWb9XN@a=4N(YmVGl?4ue!Bjbql>P-pm-O z^kk60Uaibh`MNRt=434*Mt4vMbYV|TmfWr$i?MMM=fb)uJu)QJ{%%Cxnk?#Taj|$# zj6$Fbdz^Bd+Bt;1@vJD=_$Z}kiG;f9e$B2r3QVHn5OLDK|ngJyTe^F@ z@u1ySg+LdMS<5xTab4Jvx{Hi17uPB?aY*35sN6po-i<{S9B;Ul*r*Wb!dW@F(kZPM z+wU7?ICfk^Q9%NG19DH?wqESZS6?Ho?G}YV7tYGbb+4WKu-JYMMx(l0C@M%`Ut8|4 z?a+&D5RS&C^t}p!E@f6uJNT$Kdp7?BfA5z{Q9%Ox+M2dKOm9@Ss8{E|`^* zr&BugX6GHp@YL-F#Th;%us0~zy^id`O1bpscl=K(1iElmPG<8s(UUp(T+uhZ`kSJH zgxa$#akm@GePXr#xyL1iKo`!+$vxFoda%D|%agJ)&QMg4!1uAHc|GgO!kuQAPTaYr z5a_~LIXQ~cq#G+e-=EC5dYPhv1iryFZIEkcw$F1MIifvQ2z24Bob0y;$mfF|CieUe zMFk0bgKOG$InSw;{7(4Q*9w6yoRyR7UQ2dlWmY)TxqUJzDoEfPT+VY2Yr_WD_oR;W zy+WW1XXWJDkAU{9c~}tLJo*tu1qpnEYuZnFN{@A}x^&>)cM5?noRyQ$d2%~8=X(Qs zw82A)3KHtO-F`=F7Vx|^{iMHE2z22*p4_RoK)&Hdx1w!J-J_@=q3-9b`mr^O+Sr9g z41A#w=u+ngGpghlmHirvz*UqyJQ2>Xl$g!e<$Y$7`z!f>_gD6r%=pa7v$@CVCvvZ) z=komG_w^WYC3iiAK-c?>a6UGD7BBlwlmDE3OXe0m);1NVW5*CwkZ4|p@jK^c^8I7n zBvE~)vmn(P3CDLS3W2V2Je*IwI)lgLFt71?oRL>_rj3Pj&V2+GB%9f(jC+(kZXJa611`skS8k z@hT=xo{tpgkAGAMbh)k%=gr1U}h;cf_Yuv z%3dYKo+`D4wNXqV&{be|IKO*)5+AU(pCtN>FC;uy)e{X8%TrX4$X}E4ro*T3W3zim zV!Lf&(Pn0(c)ZeAA<*ULMR~WYlR2?ApLurcX;E>pQEf4JSrb~ymhwts5^rHUf*egJ zTysz6IZR39OhP!{xjUI#6&x#xxL)PN(nTh*baV@f3KDnwg!AVjk&kO_J~7MZRuK{4 zQAbP}T~mpHw0c$BUERdW{?)|3ln{yv5?^M8^WHZm@u^45b#-EGX|cX?4RP*LRfRwo z)}b6vyjewrgn5YGwb#+(pBVpoau7dQWF3jMk!0`%!u5Y2?eDLT5KI4aZCHa}wB}KX$5zU59rKlh=u`JIz4_~#DG`kwc-JIh1KMnTE z7_VA*3lCp+v9^iqw?j+B-_7x!@d%eeT-VL(Wb!?76MH9B72DSBrl=s%bFhiOZ$6kO z@(q%>zurf5p6Mox?mH9$U3i6>b|s^%a1E>^X1+d1Q9&Xg#Kf&G^y9nxY?Cp3{wgb8 zZ1oU(FP%{cbg3m@!2QINyG6vh<;Rt}LRU4p4|z&RXWo9Gc{SCib>+n5rDep3$2TY{ zNIcmW##iL(%y%6yuaj~23=pP`&f?{ha|(g3R~;C4E8LoQrsh3AtJjnl1)7!;+afY4 zDoE5`62==>>A=h9)g>{lL7+%>$SXRUZYc!126{2RCPxh4xBHMJzLs$ppZmyt^j|+x zRFL>kEQ~vyis7vqnb%oPEFC1uWZH`S+6#q1m%l6HrS>)Cy9;GVVoy_dQQ?J?crP@D z3KB(ggz?`M8*!53s3gX22of(>KpBCPXxt`^}hh^&g4^x^iu#+^bs{zqZr7dZ*%j50NXcjo45* zH$w%9<{d)$%6JpEDP>-Z^Seoi*p~6c2(DqH5a=TFDBqqlnE!5mP7*_=c!+)7ei|pE z3oulWc+n)3pE(@LLr$4vv=|a1#!t&Mau2dq2y``>NqN=EL45Q9bBvBnDu@+vpAGM> z1sN(xSi6LBuMA&KY%fc~XG5r1Q}~jRe~_a>pi557@`~whe3|2QNgUfgszFjSCuI4OkN-YvzOHNPc^NixRsH9L%Dqlzd5y6_5R z|0-POh$|+H4a+N}UjqxVXQu$I6|d zg2eUwgqIofLLZpxktB{j3K1Sd=NtF$l~V2pUdj4eggY$xsn2@&KoVolyNgQtYGd(r zZ-xpIXAcDPx0^J+^;o7PcFhhE^|VRG{yJq80$u7=eQD(`@-Cfi6msxqs35UpXfR*1 z;kiC-fVt##qufQ&vQvybvjP+XU05UX`#gug5dKMfbJzy5BXvUgMBk~Q1tZ>)k0V0) zzK^rghQ_`nRf-03NB75Rhl{?KG2Vsx3kT25>1R&`FjSD}JuZ~jS(2Kzs_|P%#2$1L z_ouGVC$+Av5a_aM8_1I#Hm2YG_D&LetNM$5qh9KVb_6g~knnO0M8 zaTCW{*5Qu%Ybyl0TqgzcoEb0DGZV})!q54Ol=F3Yq2vAx6(klG4ddnQzNeQ>Hpkd; zx{UZwrlvxmtNOJ-e$Bb6zJ8OrCY}`127X^auXt7*~@6h1-aiyrqK=Lj{Shr^5I!@|QlW#(!e8 zFDGuh7c%N^4Oa+sbz2d{15%djt?HVI)+>XAz9+Zw=vEbm3KD02hw(3-)AVLl&F3>X zelI6hck?r1CsBn!*Mjpwyy5;G`o<<^qU`Y?v9_z6^ZH(yp@Kw@(I$R5ZNJ`N!ZS(S z`BF~on%mfL9A;7obm3b`o-+{5y{S_=~6|HYf zw^9jo;k!%Iij4FTjXEWejYoo5TxbCQt4R^l%Q^2zm*fz>WPM>%{Jl5i{+tj#^IRTN z^PlEBxFy<6tXkA0tkd7>Gx+jO0MB?dDYUlFdxFou-2c(ZRVZb0tV2&~@!hFrV)*)l|mM9An0~Qliu8 zd&E9>1VaUhxP|_F#)+w>z}MzG==0NC414;3a6L#N(3P=0m=D-7-!%D^`H4CfQA%8@ zXh+YssLfD8V(Je+xnu8)smNbuVn{x3ad=n(dbwhdLZGXW9>fdPcxT%G)!cSd8&Kt`V@F2cH^)e_uP8dK zpF~T<_%ZiPf9@;K07!Xsi5$!mz`Mv(@>r_NZ-2V{*}J3qOjVQNC)=u zW2hiuS{uN$A*2ODRzIb2+ndxQj^=0^162Z0m z(1(Zp87fF5Mg?-8LWCr~H(%9ty}0PVaS&aJ!LNL898K zAl`k(H&c(U|7ll0y~H;!A39}(N}vndv}}pVWkhV~diu@EkHv5E73Q9`@t4t(KD+7tBP;lA9d#+26HEw>MUot!|7%qs++G}+&MT|_i1K97!hz?5eYiMu&``0q($Nvjc8WQ^`- zJ;a?x)9IdR>Qjp@ud)98GoMUojQM-8bX*Z(*rd?S&nZI%i6?ed`Ga{CYD+Ida2_pQzCy2Qy0uF3g;#5_qTZ4q_%dl|TiFk>?8VQ?GxMTlvf@Yp@(hpbInE zsRSxWBy6_jw=P-HbeVbc-wAYKCOeft1qtVcJZCGrhMGPd+rRLPb+C>Ek`-QvoecSEm7(dGxNTBQATL~&ij9xcVxBXyGdvxDq zQ4S=~g)LOAtNo8A^X_+Raqka#NS_5W`0UgGxsRa$DV9Ekd$Vx9c5pt67^ol-b7CeB zY+IGrN_GANfv%IcXYpU_D)4}WuAk2{OBLp;jXx3Ss$F;?Zy#>Yhx(SXh=B?cTeK8jQ-7`xoKW@;1iGdlTg2CKgc$5NkME^e$==xbNSx;@eiHnA3EMlO7#GHs^{p{#X ze5LE32z13cWaz0|*YOKM7c63+f<)k&qk6l&>-eH7exk|%oxS1<=sr8=1;eHm!N{gZHF;@Ov`m7vB@+G0>7hN>sH}W^*)k>cPj~g zA*)w~3KCXt2*2I;85wDBUMGY10||6>8c>hlPLZR=Tg+#FB7q7LT8qZK$o6aG;1u)z z!G9yrmH44CFDlReyrx?ciUPkIG_na#J#m#ZX!s`rT@LTs@x4B0NiC~|7FUG|67iqf z@M_vSHl=cpzD080lY(Joy`0)+k!v^iQRkvA6R-nc~az0 z1iJ9KQLhRWBsw;Y=TZIk5r=29EUpR(bm7yb#yGfsCI7JXOqk1~x@5BKS+tz@CG2PQ zdL-`qN8alHU)S81klCjXx0R+Tgf~?|Ki7E+`79|&~uVXOF@S{>4pe3=D-3KE~1ujE$m^XhLqhx~y+*T46cP(dOy=Str0 zMkPI9P>@9oB+!L@JM|6*4M^lG8qFdTwkOMMz=^zt_e}DsV={RWDbLiD`HRY4PO^xB z3KEm*$G5;O$%u&rTc}E) zg2b6?6L{Ru`J_PLB#Wy;0$nzbI|A9bPk-`bQ zc#GAAEA`+14@!66jKMVaryMU2;6p8qcckHa&&ZS@lv6 zs#*5`YbDtPp6N5-${b?zz=OB@QHZGL`(O-Ikl5RC0U30y5MOgXYrH)>1`_DPD^%+W z6(pQKE+WY%a`6(;StIn>F_1vl|G$#sSx8tW^{P-oLOnGb>k0{UO--Ig;^khJuK%5t z$u0*fNZ={m>Qy0uu3hfaNaNiy-@8*ji+hfBvU~J0vb^GXee!#Ef~`l5feI26?kpqu ze;m{89J9t=v&(@5y6}{CH3lk3B+gz*Tmq-+E_te2lmiKLsb_NF{lGfGx++y|DtX~q zi_a~aHQt_G4pfj(&kM&GNT91m&G95|a(lk%bk@8~f%jgqr;n?>Q3a(wkH#Zv$uZTXIfMy((0Y zkYjR?{S;#$fvzSCtC1>l1kyP(YXma89H<~6M+(XRcKu=uB+zxdswX++zKD<6mo+Y$ z9Rn34(mJ`3f^Qb{foJbnlpG0kB|8@)n(Z=v;J@R$*)dQ-;!A`xDQ~rme;l7RBK&_6 z=vtQIAXm?=;3J=9jZ8eFJkU&@JsSBoMA?tX@Jz3-J*)dQ- zV$-6drgb~l@r{0eBG47>bJ7&FeI2hIXi504yA$T?xs_L|b<%`$Izg*5L#}Pz$_wp1 zVNs4@NgYTbISTmg)dJ%Cxdka{eU*3>TTC!3k=k}qL1NC!W`r!eMw%sMjag=w90|px zOQA~vtKAW%V~Lz_aR%9h`x_OCU6 zAkcMXrX87f(Te8!?+T&pa-f35;la5`^~+ZD-5&{bt=?oy(mz!ySIt|&rf*N>D!o^hF;GFG+sN`J+Zv8^SV_yTA|%j- zUr6dxiwY7ueit$o9p*@XhFZoz0$u<9<%NAt?2BS{CH1OML1JgvDv~~-onGm8)~tT^ z{Xha;n1e};feI4&&aNW&pH|Xq49ps*&W?cux-e^#8Uz1X?%6B~%QJi{U-0^b3IB;y z0u?0Yd%Ky>nfoUK zUEP!Fn!Y~Y%;OeY5~v_Ccxnq%w+owj+MYiV==$z5%rw+`GmoEj+T!0C6(m|^Of#{z zoA~0IS*sJWOO6D(J``PMy3lkZw`qUYA_gi*{Ch7033MeqIA9t~*Yk5J=PhEOf&}(z z)K=2$@0BFqxr(OtEusi!GQ&J*DuM0whU;olp+-JEsa**9_qK})5a(H}_!J@G?zx-{>$u!hWKhP4t>dI_kNFnmKm`fR0jtJ90$msT_acEyGRShzthFE6Z5I_J zFf*+h0||6(t2dauF1VjucFtP+ksSjSB-E4Guw5a6t{pcAlek{{gXXH`mS-kk- z!m^c|Dd)_}ZEhsGEuT$LL88b0a58k(4DQ_8TN1tZ=Vdv%HWufXZB+<#IhSFi$dQ@6 z+z9ijj(5xDV=kF7;$3M$P(fntcbQ}K>kR&=hdD+)o5IZIa|7{m`VoSz`tnLDPn*H- z7~VuBw1S0Mx2Fw+bM)Vef`pT#S4^0}t4uJ@6?vY_#}?Veh^wn^CXc+|n9i9` zZAs+rP>ju*7b)^s|3gqgqV)Q3^18rOzNb$cNpy_!VAk^kg{yA@#jG}%?dEw|Lhg+m z%L7lCS4}!za$!|ntBDP(#!^)5lL=|uH<6cpFqPmh$-1iO!n$;*A^K+aRbn6!x?OI8 zJ(9%hoHRe@RdbYQrTz*NO<%QF2y}hz6HZQ~C-SIPW+JVs3%mELhN#{nj-rCZ0G$wr zD#>y`nR(?|KxjFZaK(Hlb*0$u7!=~b&2W(!J1iny6UN-iNJK2)LP)XT}-D^GtJL-cKwuM<&d7fpGJkJspByQKFWZ?KIyw3u2AMS^5DOTp6 znj(L{@(O`2wOtMP=*&j6Yamty7o(^kQF99=@0v~L_pg}0)jEbdv-1n1L{dgBg+Ld! zX_>uleMOc(ho6`jHj!d`U1$m?b5jy{u>AspEmZCeukFdIfAbO3#!pt-E)r@Eg`9q+ zSf24=q8FW|5a>ECpO5(?#`28Q=I3LTRVCK6qK~LnbP7cU3C!6bPrq1GiXFEN6~|A{ zR|s?!d2Av{dB^ZpiRO8OQ+rFXr}cwGof@ktDoAWhGLdcvhVT{5)=MJK5+BxnLrL+j ztWeHY|G0w@yqY*b|u#l zix_RZ+5Rf-!XbJCRTLm@ePCoH9mKC3HIJS*J>|x}FR3aX@7t{q=o&KAL@vb*=I0NZ z$HKQ(s>-gNFDHEJY@(_fh(ABw~iM;MUfIt7d zMH2m;%CMf1mBjDJqZAb+Eb5B*v9|S!2~y-J#Ts>7%1B$I3lABy$D($t8h-4_y&_`5 z;^P#53yDMX7)kBlna3oh%B!lC>Bla|7ZGDypHK*NJ(La+#Z$()tcX1&N*e!^kp^&V2ZZ z{W3jt$H#%} z>PtIux&AYy97uS1GjcCb?om8`NM057ac2XYIg7zde<=jIY-Np1e;>oEwL2n-j%DRZ zKo4z2#;4~L6(oMRGP2=#L%z}_LlVP3yEE-nesS5)iXnln(yv0v_kInyXQN}1sORj# z9`$e(tFPNKRFJqjCX}3u59c+)&q`vle=v)&{>RvH{3k_M;2}x^v6N8q@md8wEAfgX##@K7PoEANDf>SOt}4s37sr^ANIXer3Kg?W&A1D6RrqlJ|-6qm7F~pbM{7 zp161~gi)Vm#uTfPtkrNrCgsV+J7nA=HV1-9^RpUX`Z|-8{Y*%eWhMBaJvU^Gl3nHf zXq{>_yYIoEzgS6;w*TItL}=_m<)#i`-CZL7x5T z8Oru+a`4(Zrw|2a*)SJv>vMq$2NSR@r*yGBuevq)O zMMzTePu;lkKweeq40qONdy4UPhmS&_%iRbjd6G1K!|IVFn)!IJ^;hN^KTi2FRFH7% z9Zcx)$NHy*Pb5+LR|rdZJ<|A@yBtFWiI@i_a{k0kz2>6Fl1Loq&Nf#cZCGsyQV4WS z%oj}B^*g3lTKHTNSN8?8-_u(gBN8hxRFLr8FJtUDt>@?Ft153Q&jvj1YAie-su1Yv z{!b8@di;QHUGjw_M9*M$q*8r@=k;W$AQ3v*M7%z6eT&sINz@u%o}Hai-zYxLq!8$8 zwj_x3Td-W;AMr{OvGKud|E|i$KUFI;RFFuiWg-(xtktK#GMC)?WH}anyrQuooGApl zR!l>D7L;WHubqs?qpK+d zy5wO8r0V<;dUWU;Nj%;g$fn=^#s^NS%1}YV`&1a&`F*I~*~MJ)_%US}Z~C0iI9XjG z(6#nbAaSfvRj+gStt18y2xRXB=SQu487fHZPYNT)@Yo0LGpP_<8h+`P3R`Y4P7H_WII?LUdZAukhB(%0d zpewIWAn9UVC%t-*`P{)5&HUNWEl>1LQv(<(Nc24zN_zJgoBq6nxprf#xG|=u=$9_m zRtR*hD;!8h_j;W6Cej>Z&1FBQWo%yQ%iuPlhUuTAz zb_X(4khs}AlniZsDdbHrbByLmuI$F99bsj=M<@ik#@r4dzGEkamaS)wam~?>t=sBj z3jPqtP(fl%L?{_oYig*`!5rgJiYq%@{kmyUXoNzb>ukFKGPtok)$xnDmE7p)%N~{R zBkyVjF;tMqIX;9e-cs1KD*f{paZHX-2y|Vo6+j;Q=Qe$KWR6j`VQKb! zS|V}T7Qs+K!Yep{wCq*HH0qF73U`30r&q$Lqe&q4I z2d2!iFUhZ^L1e-7Z>H5f&F}U$OG~naGb+)z615mANObt+NAfp5V;b_GQymu-_GTr0 zi_kTX0u=&XwT1>0W5@PBCZ zn#Y@1r)EmxdHxdY?xA=(VtO@(3KHLgeaXPs2oh~;KAp18`buo)kM8vCHh+e$jnRSR zu^cDaW__Qi#IY`wn0w(qw8KJwh6)m$+ycqI_}XOH7;}I3{RtP=W58H?(z}{MpzGTM z9};4;B%4g;zG#tto^1B2QM6xCe})PY%cBEGtHeI!_CMDoar#Ix*5}C-x~gKhLZEAJ z2OqL*&>(WV#dS$U_AAE5e3?OeZDtG=B=XnwAy>e|_lp@PKO z`~jrrp5dgzU*>O|*w01T5xY558_E;{U1eN+$nG&?$=D8NVpzk%?8(nHH0nNKk9+a4g;{~vHFV4^!cajX+Px~7>XAZ@o;xXH#4m7X z-Pt0#vZt>?pi9jzpRm3NYj!P#)|gC{?D9yc<)B3>ut~*cP*T=UA<$LlsXw_S&w-u( z^pd=)*QYD6!2VNctdAc<1qrM-O{+P*5F72Yk;+r+mAb-OP-io0)i1|(JFlj$#u=S31oHamTG_tDD3$>|SHy*Y~T8 zQQ@BnbiGwFJv6a5d$?nosdtOq#9^RD-5t59=9m1$(fcQPD$-3YZnYwDU(NsLw8}~P zEmsmPRGqKvo?Xe=2=jN;voE%yyyi}= zCN^bwJ~5td+<2!OuUj$QbT9u$No+W6B_cmG7yiKkN){!|A2t6&0q$RW0smg6za&2Q z`ffNpXd~9X+DR~n7v>CGTF05M?VZ94IlD`u(fNtAPW8bex?niLwQ9INt=E{NroF${ z@MeQ6N@Bs?7xe9tifP_Komk!+Wy#2$3&WhWujFFOJY;UXLzvf_pCs~S9#XI8vvgDE zpORQ{@g=>;57Y88+cDl-yytZ$+7ahzH%WfaG)WXZ{DKy-K0>ET0u>~%Rm#z*Qjh4V z{YU7~kx>j4TqBOZq-jMbpQqo89-~f9jg=Tk;OcMLr_PZDxqEZXJrpDoewAe%SexM8QtUO!&?04F4!hCve zd9?CBi2rcv^U>ksHySr@F}+~te_vffenC8KEtX60nVOYJ7_`?pfQSdhRs zhCJ7~t{n^fXiK;3Y^KD(J~h&s*0{VKE4sWejW5%Tp@IbV`sM$}8(S7JyCO~L&{QGN zg|#ln`dBVjwtXJ*c}ffAn-jk#)pE4UpNp00+LG{|EtGd668N1cpL2&?ET?BLGP|`( zpi8aYIu6z>wqXQs^QDzCmVu)b>U+27jhrlSi4Bje-I}3-1db-i*^GaF(FXBMkNnm~ zA<(6kJkO9^Z06S2VgB>fav*`D333!CE*Fc-J;=0fp-P|&#|F%~2dr2`+W=#7wHC^# znkgYKIoEH3J|f?Da@?sr*?D`f?oz-!&QOckFxv*jjXI^8D+G?PAuY4re6nWGzE~S$ zLs~FYkifAsndmR^Gd(!r9CyFbRw2-ZwXSKt?X20YTPt`u?^a6fB7tLPGRqjXX35JY z@yBCT0$n%~Ccn0y$|q{&bYn_teRl0odD7yqU%KtP7X-(X)w;63>o+u1VjzK|xSBTqhyyG4sJgKt zIa(pmg=4bvE455s7IWaTG0i<#nK!_>f(3ou$&wMSd|UU2vXzXunTL(FK5kTc7RFFP z0%r$gPd}eM3ooo2?mMe11iG-+<+#t6+-&2FjmFeBHI(~-1kMh~e0O?o_IK1OEnq@CE+q^vSahBHcO&K@NG9Ob=7nZF=U`N^Jsv793GmODcQ37ngf z-v*-{nB&NAMx)Z+3V|-HLrwde=Vi4TJ~ezl`6zXT1kNGJ=c7elcIUuNBP=jbA<%_0 zLNbG7AqVy;)k8e!ZO3r#_edQla>}&}@74H>GHWgS)DM5rvm*zwU zuN%(umK3tCq8d1`*3}CNQ@s+(JZFRB`AK|YByV!;Cc#-*P5a=Wv5!+ri6t*xl=)gD zFrLhR?%}|uk9QM&cjQ$Fbm3gFruA@hU{f5+ihN&lE3?Q*V2#Mps4BVG^nT%@^6aC^ zdInsnu%=`I@;!GFx1Y0BmVBy_i|t=#5+wpIQB;sn=jgr5|D;_bnHUoLP$AHz*6#cP z_U!rtKQYYV4MhbBToWMY?nc_P2`79-i2r+qKo{OwOKzs5Ha{u|p-tRE~bu5^<*)(gF*S7@woUtgc1g2c2B1<3!tod^E1 zVnMT;iz_8V6#`wj(oN=AU;cu&tkYgRD&tJ;%Q};>O&0S$dOd>E86*j8-Zv{qTgitAJ7)Nv;N8w1#9 ze5Z%?HewasOHe^VU6XpS)KfZmb4O9X%Xx)B7uJZ(L}U6zkNd}pu!^qrJlAZ1aoO<84IQXKj=+-*#Yfg3)P3t8QRFJ?L z(X`G_F43wzyNQl(S}Fv(@Eip>zFXjLx_eho;p!ekP(cDuMUbOv8+_@)v%|&DUqJ+S zHRA5W5gqHAn9n9YZ(Jq$_PJ5`G09zKl(2E|Be-W2cY~@#j|@B7f8pI&wCJ~_szRU(&x4RHF>#8q=I$WT=W#f} zvz+nl=#68J>Z#cyUayw_Wjy>fL_Ga&BB&sNr(4VXI3*ewPwEd7vkHw-2y|hM$a#ZD zC5+YkMu^m$fl6H=fv0q9n%~KPxZBl{;?_1lg+Le9oBVbzlVU7w952fEi%?3AWx|uE zW#--kyNpbizT!nf5B(=`@VG$5AsYWs33tOo|@KnmL|5{jTKMZ^i~LT$z28ff2YGldHpi{LSn_% z@~=sOvd%mq>)n1To$|^Hr}Gb$YLgDXbg-JmBrCo z{3T5bS)hscuC2t*9fc_>NZgr5dHU>Wd{aVG8RN+E-$q8Y*1|u;Rw2-ZSEy+>U2Mg% z>-EGI`S0vGpaB1Gj|FqAPgHWnho83*neXb0(l+xbDwtg!e@U*)^t2HPriS8l+sR4{ zB-(5v{6%UKulcum)qPyckH*Q<%|ykW6BGhnj{6JnHCcTkP3!wBr*QogBW}0sM^QoI zXgcAVdos^qN|G@WqTdrs3?1{zxEuWs33uv<~7ah;y*@y*?TP@d#^~KOTB~K-A;TQ5+R0aTa^2O#Qkd~ z-aT|QA2)ZoEQf0kTj4r3QXJ5iD+Ic*jmfd4Q@O;zK$EDEcv&eqULod znFwtCkfMUbvNR_?DEnJ&{Xl!M=f0mPZ~sOi(1m&9H7$KoKGC{HNioDVFUzyZgEt=0 zlHcxpl3+G-%$_dS);9lbOd4E8oGEV4PSZ@c)e(^y{5ZkOB_E>aD9npbN97%f3%^UNN`)4MUTw+%PLQ=Ja0F*PZ`wOeP{F zuXs2!)A(4!kD-DDW*wJvMco`k{JGD@f>Bi!0$q58GB0w4eBxx3mH1q@0z(A}%+RiB zm0RT#Q|jA^#?8wr1iI9ce;S)xjCD;h;$%)%%#w}Svu_+K&zonB&&gTKGr2`Z*VV?u z*jfw~BrsdI{F*3gFP=E*M#ARm3V|-HL;3$9@`#5MGK`vDM5!wzFzdLcnZDffiAqWnrv9P#iK^Ej5pQmDkaANPp+cYwb27_po7HT^-jn5xu5#|~dAoAFcS0Mz+NVzhGf*R~X|E1Ah;^?` zhRwrhh6)mxTU!3B*~>NhADS2m)fy=Ty40%*m~1aPq#HbPelsNtIOg}ptJSm<2kk|t zP0#t(BWgL2z|7s6wq0`&H8$HA^>eBOy0A=gU0=CeqQ)C3J5ea5F#TAv8N*q2%vr3?xIb=VCnDtcX4I8t3>73W ztFp}XJ0zz#Ir}7;E64PaKo{1boD-J+=TXOJkdCF)+C>7hL(6|omt3O5^>*ZTTa`c; z-W&OC5c1Qgw01hJI4?%Y4vcw!SNJ&a|E*4#bNQ$7aqwjN(WNm%1qsaPD@V4AeKH=e zOQN22nkfXj&JJ+p-?QdFWp?1vHe!%16c zU6{pLu9=8`Z5z(iVO+ z3LV%%qvl63RFJ^TwDOy?$7dtG@MgN6HB<<6VI9hOwGuCl{3kQ$OuatCe6sZ>+VTIc z-oPBNnzr=nZKKDBzv-{ajTkCOV6INtXDIvLxK!;B^_f#oAgb%g}x1J$&3A7>cN@1Lf_pR`p7 zbYZ>8anaN7`KBFb>870Bl#*kaFt4rLl`?xF_tUS?z(sKk6(st36xsEA<0aD6`jo6I z->s$j${OeB{cV~DGIi7otw4CA9<(W!e=V(zG0||8D ziFtAsV1c74UygH>KI_i#ck%poq~#qvGCuUyud{T*%kB&nBrqGX>|V`1o<7y;99{HW zCD5go{E>TOniP7Dk}I7Up3#UWBkmX(Y8sr~5-)uBra7$7(OpIth6)mR=AoP=3(P}P zGtN?8FHRxQg(n!wQG+h8jArK!(OFm2cL`=T$7fUS&6sf0co=zr-fteGJcCH!n@`j9 z%G-^?X~*ebRaz+oy42^R-ti?y>$@5B!W*@pb-- z*hzUl(1q<-_QI|GjhRU&=-DG(m8TYo)b%F4Q;%un$|&>Rr8{Xm_=|Iw=#anT6arn? zdgN$rMj*fW^AtTE)kA4lNZeozcJ1gimF!(<-n;a1QUm_Xs7E_Z9me+mJdhsTqMK=q zhb=9$Ibm1(4z?uzW)5nzPNe^LHKnHQ3OKG$6Uj7v>0pKm5_#))+m$jgnmk(gO~!cS zG>g+d^J&f7@d|-1{U*`>w=(nTct4}#SaH7TQV@wlDT2oDX>kw%aZ4gDss09w>g=vd_I7of&|9XG>7k>_zJluwXs~2iUhi_4mB-#`7i!?XMO5< zW~fqENMMb~9aS&R@K<5w=*8B<6#`v&XXP8Ne5Nt1*gD#!TT`XCggqo|`I^S2?Kehk zT2F8Kv{U*FNMIexJwNZ48-@PbMRQ;8pb+T7mM=%u9(Ok$b>2ex#_kLiB(M(U2+O8m zW3K-`Is2}*3tX0BHayr#<)qQ#AZ2YZAY%x%34)ixzI~J_Qrfur+k`hyQdtt7|p^O({;{0 z87fH3Z1r64nzh$p5>Z8h=UC4n#dRHcbnmP7m5CF_6G7GEEyZ z=BW|mWkdI`>Yxzl!Wz*uUi_mG*X00t%G)U=M?(F&d$#qtk*h~-($Bk-LZA!3kmZ>* zzkeE|a{Vy1E8AB2c1A+|+V<|4Q)KMhV%oN*wL+i^zoX?E$fC){qHd+cX+qe8=nQ?$ zj#zG$d5^TNS6hF+IgST^e@MQi9M&%kq&(@m`QKnvNNeLm>HUV( z<XzF7P><29n#;HF3Be(f0o3UBdv^+k)MsQO)VKJNW|T( zslO;D_v-gHx2r+bl8mI4$BadbJ17LYCY3y-o4&r+Bk!Bnp4;zfX*@iaW-Q6mjiG|X z?9w&$vrVmePzfvf43=!4XnZ{~%@{GFmqMWHRm+3=kj3luy(7#-gIX<&c6}0z;MD#M z6(r8Jt)VAg2(fGNk7`cRubFJjy3#mX{KAFhA4#Mg13^U?RSVVev{`WxAgARQ*(?!k9cEs?!n>;%TJ>kAJr#*U&R;PYDi88*VXHVY~W$BF=S`aqxxE_ z6})54!SbGaC)6}%yc!}>ca)*1Ad%aut{zoyE${kes3dN-7;2n$i5EVh^%MeKP0#+V zAG*4PH@P`g5?(j!7?oxX6#c7rq^KYkeJu0j=ni%32z^Ri$%yqOq`AebMKW z149B`<-TO-ZG4CDh4(K=BJy$zV|1yy;^l>c3>72}zpAYd%a_1Atumh!(stHPV{c$} zQgLZtr6uA&06qnpw$kB*(J>(>xm>WP(%O+w-|cI|b{i#wKj{xg_EiXU;nOTfST>zB zTAnfSBeQ!bPc0HSUaD!%`}Y|6CcNV(diGWbbm3b`)8?_$#=Qv+#@J7B%Ghg-guMK0 z)_Q7{_>u3hVVBUXdO8BZ(R zGuYr5<^KbTPaEFr0j5CSpt||XYgOZ|MuotyMkI|=2z24Uou(}-o^D*clUo$?l{-M; ze-MdrQ$OhUMm6Dk=iZSqj;C!kYV&SDvae^rG?5#z~x;5~vX9!kU(I+Yxt-*xseZ#rp0H z6(n%xSN6h7A2ph8FDGVPsGtz&Qtx1Jackjsr#^vr~J1fO6z zI_RT`2SICj!IW6#sYODaEBaym+IZdY|5bJFaXsCC96yu z`gS_!yx*_)`+a`38vObxBT$8B57kRjE9AguZRMrJ0Crv>fnFH>&Fejo3+wpG?Zuox z6`o@>%~9!}8ylM_CzrAqnpZAPF9&q~_p;8#P(rDKHJe#cvQX&>NQ?P)No@2s<3m2`YikGl|6kXsYj{7tV0M1e74iHu*gDbJR75) zq%L9vs(5G3x4)#z*W*G}(cHDHPX-Bmwxi8>K_}$A=Kjh%WgjC@g&i=OHYy}bw#^Js zooGiRMv%Z~J58H^^|Y*iV3_*4?iEI$3j0oI7GO$_ylCg87T^Dib)+DHPik~mODdMh zzY5iCb4}Luf+~I{PW$Gd+?Haf@)P__L;|1fG|e|ASH^bitRiz;vNI7?{JNXJCQ&}# z(MydfZ_P4cB=~dUt#AEh#f@(2*|AQHKow@iG@WVxfS!zf<#%*V#96Y~#tz1Ts=G6v zkIG4UDEwP~A%*Z`(@sd(?R7Ag*zV5uKm8-l*>9A~_6=tQs`w<*YekPmlhMcJ(8lg; zu80xB(Rg)t?$-Z5(IEbubaIOI@ULw6;v+V}g9J{&P(3kGGjB%K zP>ptVVFaphLWwqchSo5%+#OVlC#~5e5)!zey41?m1~ROo?Lzs-AY}uZPWc2gbnv%I@5wl+7M!w6J`#&65?I}?%TJ)`nB559E4T0j4& z@j7W?}>htay@N8xdqB1!$^? zV-O=ywINYvshXE#@kI=V3eRXf~| zWj^!|x0Y3}+?l!dt1|1)?LI+PKd+C}Kks&B1gbLYpUiCe+kESt zm6e-~_C#N?W_B`Fj$JzwBS_%Aom~Az0al$^!&F$76C+S{~}3QZqjBe{jbV;qIdVR)}04aR8T~=zz7mp zDWq@r7cXm{eY83@^-D&e>UPsVGG9KWDsHQlbd2(ar!1!?)77-CNdhBCV8v6@YP?HR zUaqlf!Mw4IKvnsbdzo|JNVA-t#?moXm;PWiNsd*QqC5mfkig0<^+u%+w*LBWmU8de zkP)cD2_@RfwW7f4d}NmTJlalR1PQD_Q-yxjVe96h*~TpZOr-!KUF~tT(kl@obZP7(qfyI;O9+IVK+SMu-a`UTUCIJrfC3HNH1kkGHuQ z3s)|pQ*n@5f1!cNBJjD7$_w<-Hpe8ge3W=_qL0e;e~%HU%61>D|5@b^(BenmKi-{2= zeoV>N&)J;n4NU^X^Sjkm-(nv|pz7pR7yYiyMXr4;QMAv$FHaSWFfoFJ{k5a|Lz`3W zBmBkOZl~q)>th*#s(;^c(a+diktCKozArjue8vb=VZKW{ z&)ic*{rkhkg9+VZGRLS zca1bLf&||Q7Ac1|Iv`sf^xQyw&&A59ymJv+FdU4JlpCIq;FEK(&XR;0mB(Q^)X5!i{mrLmi z=S^2Q>^4Ld_7PIe^44rwQr2GV91+cWAd$eXS;{8XFOjF`3>WFuq8NcH?1!X|_=<&c z7j18~XnQM0kigzi^0xP+$XL227SS~k2~=ShBE2DR$9_4Hu8FJZnurl3um_fUSUR1M z6|^C?K5d9a0#(?nNZYKOuFEu!L}7n4z{Cg=I5$Ov?|qq5&0l!#-~_6$SCJ;e%Iws| zYaSvxnNPSO!6&NHFVs|R-{?-S%<*LtZm7b2w&YZQxg>bS#6zk-M|PExS59j z<{oLHtbT+Vu*Xp#fhx>*Xz$00!(w&TMCClzSzrVS-1|ejaS!Ykey74!k4Se$pbGOH zdecTkfk?<3r&1aQ3ydIvTaM^0m7~5BtFpt?xQawZpbGOHdUs9K4jhmE#G`sVD5wjZXKiFyzBsNxgDrpM%OlxKo#aY^bVftXGQh#A1SSy zgNYF&a4TD7M@p`kPp;*3axIZS73MqiQ?)-Q*1qYiHe|FlF@gm8U-T?`D_7ij&`53X z-B0lDcf&wNpbGOHnyzVnMmWcBlEWqknixR>eO2nrOv@1y zI?k1|J`7_7sxaT7-jBf3;#YeQ+2-3&6C+5V^Q&oJb@*NsBsZ2F`b=g7sxaT7|MT>d zqCxw!*83eNnixTX?-w1uCrd0}5N6eC8o>xuVZKA}S8H@aGZ}U@{n}7@p3GT#w z*dSB<>|UhrQxS|n73MqC4;NM>p4Oi}=uSj6fASzvM36`ArOe9oVSC zH&;|{n_ecYzfXz%JAzrpf|G%mEz!5z-Cu0p^s~qvAHuRCBrwaME&rzjMLEsHeMmEL z_*tmJ9FBIYSMMQ~(@fkMnu)^*5}0MsPgOXc#w>G0pX=ipfhx>isdM>rUDUj`Pki$* zoMovK}>Au-m>AlwQ zUy;D7A4s6POk26k^Tv|-*?RI)PM`{_JDN6oho9j$;K89T-^^iE93;?Prd;jp1*3W3 zd@Hhk0wYj`RVtdCd^*x7Y+PuyokE!xRJM>ncbTf3cS?;-*{!6r9?u9=VYQ8R(4F%) zhPHE;2b1GiRSgMrm+4GQzHAI>yI2nE$LnyY!m1%{*&G^ZY;BPu9R^He)j=fCU8V_z z3s(%!aYyBlUg3;D6;?mVEAkC8@~2;v!RyAeDkl=?E>o|;x-w(%%ztIYgg{213ahx( zpI8)R9~T8jj_%bND{iZbKbs%ENa>kvku3aio7jq4R;H2Uv7wP#6xR&_>V z2lJiF!>!qt)pI1!T_z8*`X%GzF`gQh!{09Y%KGmP=)T9re&`hY`89p zQ>PDbmkbGXmuWZE^a7)9QoL$dqZRYjP=%fzJ!QlWFzk2ER<4WfnA?X0y33SpucY}z za*;jBMaIuU756z^j=31^d(Tk=%Ho)7i3H!7S^DETBjU|DYT$#ej6fCc9o4k|0jUO= Ak^lez diff --git a/data/kuka_iiwa/meshes/coarse/link_3.stl b/data/kuka_iiwa/meshes/coarse/link_3.stl deleted file mode 100644 index 32d6d52827cee8b14727b78621bbf4cbb4237237..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 230884 zcmb@Pb$k`a+Q%1{;u<6n+#Les?Cb^z?(Qx{6I=pBfH(wcafc#>;+~v2i?_H-aSBC> zQ=nMkeP;G-_$>+d-ap=cKDXVQ=l4C&%;K`OwAmD; z{jluD;d(7~h5nhcz7Q{SvKQ-iYOPvqTONM0et&sAk{9ElN4v9iS7xY+GCwY}QS@?a zNuULZG(&Ro$)5+Z^^#b(BZqOaM~g%Rs`{QP#V;T3!k!%)Mn3io&16j6*+vp*LE=I2 zth~mqA?&Fn?hebY_paB{5cwbrBMTQ6q8a@z7r#rXWs{C}=Vq#E70;-*o7FZEfvVI) zax%&XH*@}}Og25dbSp`q1qmucMrFuF87fNsVVQK#oox~ksG@RXRMKu@)Z_JA2X)%J zSy4ia#fMArx(&@T!BX(s;$UtZYoONdI5UCl`z)z=~fLb zNZ3=AqI`h<`gj;y9k9(tpbGP(C|kY5w}zIQBT84tv}2yEGBocX5@(y7=~i@?E~AcC~~<#nS9w;WwR9CV7mTWay&5TjGaxz0@QqNJtYTbJ|Mo9y!X#PQ=&nV87*gSWF? zn_W_cbjh;0(11(7qN%%m*eJxd3hW4^@=Ul4LhdWP6 z_&`e%gfnr@k-)NY-5rHb|V_+uJ zr0a86<#cAM&^!9T)GErl&#zp!kMu~C47xk~Nc2;f*<`Mhg(efaqr&DeN(&wn}TX$<|LVIl%m zSRynpIqhXQD%6(*T97EXr~*&DuDv_w&;H0`?4I2u5rHZ!H$};PB9jp|)+{S*MU9qw za+b2MYbpLb`J!%ZWsOl3B6K1Q(I=9M(Qk3l_mPT`ii`e{eu+^Xlh=wu z?L(*bAqgt0gn2E_8R-r(YAf7q=X5`Gx*s;eeLoo8K`wexDmO;=LtZNi-4C7aMNEuVh8Wn)R;@1n}?gYKYCchK|!b5SJFpKP@{wc11k zs&F2xC~SF2om#CV(1Jw9>^|&Fjb?nXY_%Itdg}f^G)zRG3h#}gY(MR#Q>&E(T9Baj z$f(u2?;y2Womy=o0#){VPGhY`W341;^ipZ8mGy_lT1I27yr$8P(O4_%n{4MgwR1^O zOHHU5Rvi;HhT1=)vDSSDX{^<0td#^>kf8Aj=Iu0|>olGxB2Y!6D5J66?Sn>VjYell zV0ux7`IDowMx(PN(1HZ|QS4BYpuHLm0hRNS^7W=685^=H#mb5#`p^|ubV3oR%Pmwj;C+`il#>XIeo&4%9HA}|H zyv>@XH1}z|bhcLQ+{i=(s%F=ZQs>8pbFT=M2=9rrwSkvS0xd{nYr9I-4o~5i;{1si zTOdN)@OZTJfds1R`9`T(riXLiABB&To}t>^J!2%1u6C6AW=1&Q`Es-Ry6sGLvQIb< z|1DCzaw$sf8WGO3jNU>-_sHp5KIbS&paqHLl=E#FCi9TmKNGS4=xlAqaWfxCpvo#k zbNpDp_Ghhk)G%9F2@4Vft{zp}j1T3n>+K;Qe*QbO-n|175va26jp?Hw+;i*Rim}hS z=Xia1YXJGE9v-Ewm}{0UmMG@jUb;7*g=jYovvkpd1eUs@be%Ft%UWcd%m)&vnmnhY zI=6cyH&b)6fJ`>si#1&L*8zIUci6Ul#_-JXbc zrG~n4T^lP?g#@a0&WUmUvoM@%&$ANIA;SolW0OhT%N^jXeJX==3DQ)!?+*qR@hbbv;GvM?`v`(XI*;?LNeB zp$bb~QFw<4*VenH540e$MOo$yEg!}&%n&{GwEf{O$GgM?s_@<@%Am=+;@^D=mbIkQ zt<64OX=AuZuXQa-q5a(P@!l7sWhp31#$P@;Ti-GXv{=_7PZn+F{O`zQyvEJMK9E?{ zJv9FM*=W9f>JZAus~OkhLz74qsuovW=F>Y}3@_cTArT$Rr{n5X(+66R=$9ire$>fm z-swemA~Izw$fut)iCLc0;&c5P&98@dR$ty%d}?Nj;l7{Bs&*nnlb+5K?@R(MNSwIX z(x-fe7{2Rm4e~KLthjUW$HWAxFtv)3?!`1dpqEJ;_uLiVYfd!pIw+-j`G>CYWp76F z5}VVg$yTq8Ke#5EPfFLEd@PvKj~AL}5@{-6zq!cgM6uTxk)?eI_O*P<3zN zqWEh&qxrBCEr~dKqzrF&*d)+`M3%!H;-*l}PjARAeDtZ$n{G`^pbAS}QL1ja?>zFS zNuULZVL6J%9VQ>Mp5!GTtJiOJ4tSoJKo#B_MJW`qntv*85?EFh-nrs`jfv)mA2d|4 z)D^{l=uST3gW0#E1&LfC*Ww>^kLDZBG@w)+V!!iRv55&(g?f58kM50re zrZfq(Bt@7$uGh)wO73UQ`jD`$g^GK7JA0S6d^|~4*wx^$IS!%)iDA2IIsKkRy7N(H zR8?22Pv%&Q1gg@PYvbG$8tKl*l@mU$2HQ;nEl6B^(8&38S0pbvtPz#fg?Wu#Kin~A z07#$;$45m;)1;}Z{|S>o3le$vbacjbi{vjdi9Ye%^;WJSlM@rD!ckOF{yf=9&wD4O z>=W}`+N=&<(99{`IkY&wL0wU*y}ZVE%k;K3I@tK*&`2&+*86C@7H@$=LXS8@+Rcg= ze^->Ed&V0t`}nxTHCilM5V%gEC^Kh|G=^22n}|Tw+&+7qPy1z%DO8l5Edz{U$96~p zEl9*}a5)1vXLl2gh7K_NOP`elT9C-FeX}!Fw&reP-M&u7t+!@bp#=$iTdyb$cQrO1 zr_Coz7YS75`DckUWuZ{FkMn(=x)#Km&$Vl_csskE+$k-d+nYJ(p4u$0akWNKDm6`K z9LUl^`ala3vkQbdhpk-b_R(=j0pn~g^UVYjsKOM|+w%w2jGkUq&5;vUmyl?1VUDx$ z*eJJ;HUYkd|Amr?2vpf~ezfQ%SLdevC4o7|6h<7%<=iyL<@Qm3?jqMO@gpRG79`v& zH11WIMXCC@B4?R1G9*y7tLN%?ugKrrK76JP)_P_)iPmFpIwt7{rNvQqu;ZV#N98rH zY$(dl(m{i&O ztGp>|>2=GPH4!aHQ2SFwZ4^C}qLi*%RsZ`yHR%HhRACBfRc2#;ec6acl0XX*g`134 ztEXG(_Hi*?R=w=s=I$LNP-V|~@z&$@kdw7#e}yY?JCYw!ll7V-``QALzp0m~{+jvN zIevuRrpS^+1gbE9iZbrT5WQS2E(x?CLG4c!ZO8PHs%|gcIsRE90#!J!D9W`>6ZMtt z(@6r;j(MWCp}wZNZ2H*uAz05d(MNhj3ljD;%~M6)5-NAU;`Wj2=Y!h8E`ue379?nPql(&S`WQR< zsrEX`T;W9mRhU9W$?BC&KV7+%^nn&6e*QE{O?PR9+ehhc1@vDFn`?JSpvs=}`$a;u zR#(O($~mTx+PFisNi!d#pQY6LUzjKfv>@T`^WA0j@pe77ZEJ8M0#(%hd_>zZeLQM= z+EwxQ0g@P<%G;TH*G_4n+U*pzQK;PGuG@#t$;GZIQRW>)3lh}+;zeyVeJuYx$n|T! zanc78sKOK~%5Sr7@#7Ef*H5-A+*(#kG50>h{sHS{LK^wB#~XXhDM7pHtLELDRFrkXFX?qgfLX zsKOK~%9fP6(IlX>B+!Dy%H(sMMVCdneZ1*e)#$#aS|S2f_MD&o5Nu?qT~qSb6NE_Z zsg1{-Wg2wz5!cq=%^fKdDg_(cN3M{g0a}ot*5njzN6?D0sMUC5+V8bx=^}wDEJJ!? z@gHGS9JxdiXhGu1?=I)oyV>12zdGLEXjwQe5rHbavx@SmS!UytR~tj5F#14F{;A_Y z`L5Wy7Vlg8vJ!k(^=|IUIv>;*6$7d?5 zf8Ax(kIG~xm5Ep@u*wRr&9~=)k9NE2@AkLlT&Tv?Jm8$^J&6w(QdYI{B>t`_-9{aB zP5FMXB+!CHHm?iL>AoSnq?dR;?;Ll@wZ62Ob0koe&#CZkxkvLna&@WO%ImJ?hx$n$ zXhFiB^R;y!xpHQ2vVxJZ6`)U;55z8o5nF1cUy0<^sMp1e%eC_JB)SR~? zfvP+QGjiX00q*sWe^dYKx;U+y%m-SK=u|f&FEca1z5d}mmC{&!rBfmTRo2}!?_guU zG)AWm9VLO5qzH5UBdHc8e#@eT3TqGTviK#3(dc_~mjzmou(v^4V{y@{r7l`6t&%ut z)sl(dwXQ|0rInO;TD4^6ipj$Dn_RSNDG6F}bJD6M6E%)j#+d(b}YwRxO#CDq6L4(W<2+(1HZ5E;?z|Qr2m?YU!d?%R~gKtWq$2 z(5j`2RxKrgmZS)?)h5-V#BW)&P+_UdRZC8*meL1Wk|NAI_%wN-w%K>ABzBaUr{>)k z#ypl5SKIv%qgGfH&H^51RU=Y;uX?13WHo*e&x)H$4Am-JGYPaH;a?$AEpjHD{Up~p zyGC@=PTw}~2NI~7v#qN-*)NiHtlENn3_IUjYd6~@(1JwO7Gu?v(;`^Or>Tjc)jo|@ z`(!?7?M|iDKIUHSQ)#tNUR!@pSnbnjwa-Sl*X|MsT9uR6=9<^7nxnN!6YV~b5UMV@ z1Jrt_BG{oJ{V7#!V1(A>57P%)@ONj_T&C769mcX;6RR@ge;J|quQGigfvQ4z2dYP2 zL@+gZHzLBbg=^)qn(YHENbKviRPEyv#!9(r5ixo5Q0?(K(+3i$!uv$;O9oHYDh)P$ zpaluN)O>aE#xPdAgIE&|s1&NT-IbU?71lSoYU!X=OL;$Ntuc;PEtz}OQeL}PEgiIK zDetCSwNz=5U-Q9~kB-%EImRZD zDpZv|vNUc`x)?U6qcuXcFo`ldVjY7I zMYH4Kom9Qrzk6zBiebLT%BprEd+}cCzIP^p79?UPwu~#6A%@j@FIFvodR$zc|1mLv zDoicythpD<>h&-QS|xMPswESvmP=1|b41>VW^LD{QBRgw?^ya%G;23nJc)($?$3tK zF$uIF@u;+~fR_Iu~FMEGQ##I}x4OrWaxvPF(dJEPggW1@XbTwaC^J8TkYL1ISL z_CB$cb7qKD%R+S;u%%lP6R5&cSCrr*57p*>ngm*q7&NuG&vEkM;}WZuA3N_*pFc}X zpbGDeqP%FjhP^Io5?EG~Kf4@8Of-9Mu39FPI?btu?_~ZT%)TA(2NJZp=%7_gX09my z=J=g8h)qnOs%~Bn_4mC|^3Kxkgl?Z$R7#UTOHzdCqj#;GT3$bM)`x_3EmVc7d8>oV zTRw)TEv&UaY>tCyL4sBnRa&)l=VSfIs#^O`=2(jas%WKArBzFJK9;6%Xh*h~1X_^z zG`F#OYFi|0GefLeUOd`ZOLyCx0U&`Y`-syjsHt}0s7as&36Hpr>h^AtY)fYGR5Uzo zYpp_PVggk-+Q}zjot}hc4@Wa^Mo+?W{$X851i=`4B34dSUcb1Pc=P3tmv?_=d1N@=3T= z+$C*e>HdibR26b6taI+stg?J!X}j{e*6L6{NuUJ@dSX@SU50$JP?QaIA89$dn{V!r zKo$F}FnSVZ=94fz*J|`!D}7-3pvqoW83P_^^z1ANv><{06lJ#OBaPn4BqC51KS5#V z)zK`gd@8D);f{82L|;ju1&PxS?yCilO<*nM`;tCouWJ`?n`MOrs;v8D&UZ7eJEisg zY`)(`3lg{J4vx@6nEBo(EYzhY0Ik9yVcY7 z(OQeR_I*=NyGw65#r1{gq4LdG(gdo0zmrPR{R92JB2YDk)(^z*cG=QaD?xA0#r34eA4s68M(3tZK}4P%{uNP; zR@H@NQ+R-;uUROs8#f=K&87Vr;_tyP>wQI_1&PmRHcR5*oB{uVKvg*HKM+20X6*kJ zfvG}&m_Kp%#6RXeM+*{JY0ru9QDo-V`9K0yV*ODNvu=ES&(U&)Rzig;#lkxO;~hjI z6|JcXdP_{5uX2v5Le=_GUE>5%G}qSzTFx{a>=3F)?f%zPA>lzQeS-eu$FF^0s!;Xq z_VHD_Q^oJ9CmQ^ZWkvoHh%_4)%IgE^n*4{dLRDs3Art;Qn>783KuZZ)s}rj4_c#9^ zQ-y?BClvH%z4ccQ`i|&B#Z6l`14q)woJGAK~whTBE-rFuhc-WZEl5 zb^Ra93W-Owe@Xbb^}fSbKCrA%6-K+CWGQTJ`xQ|tTbQ)e_ikuQ35|*J@5dv)?itX6 z{>srF8R4UT{jYll93gS!#4@zkM6@75sa1uKBZa=6WgvkntkZTMU*9S5yDRFB{tvYs zeTd((h#CE3<%o0T_J67+sM5mH%d!eP@O6vAJN0quKB+p|w2kfF*z3Hz+Az=v-2Z{zHoln6v+H~x1r~cSL=ru zpI%MjddqkhT9ClA?~3x|_7I~&_As84#n}i{73%-d+3-*69KA<%f8#>!Fg`A9w+k&u z;MsRYnJ~iNSllO!-)*$ZMxbiz-t?S@TIcBV^{Kg*4{E+zj3GJK=I5^(_mfYfsIs3X zM*=NKpg%?V7J(<$(YKvI3ljE|-sl4fR2^Sij%PX0(fzcI1X_^5ljZhQA%Uu_t19rn zN_BAiNcnWQ{`t=cw*Bs67oEaQIBmc72S1*zRbBaH+Bv@u|IDp(^d}b#*GKG%V7u=u zwGpVo6Y`2O=bvGEkuDJ|XWU8`T9B}(YR{Ts`j`q4ENbQ|8-Xg!lhp>re?xRkJLW0d zkji}XP3vs<7bZkU3ljFz}j~e49Yk{c4`v@yLvEU?(uv$GeB$@lO|$ zibjH|!q^E&eA@>SsKPi3_Eez-3CxqCjEwfDQ`li_#o3)2#$NeuNgAHK!3f!+k{?XR zmCVE4wWRxOe|_edFxF;3iHlfzhav7H)Pkib%)es`z8o;x~>efMaG zjX)Kax}tbG*RO3;bg$@lbxb?vY1Y;k&Sx(I-S4lEKnoH$`q+ISfhrvBWNp`}wlh)N zsfIIZ&s@B9#E1?U=|Q$AomvzVEeZ)#QR`yVYTak`snzP#YFQa-wP-;Cqar8@^$a@o z3{3P4NT7;Z8lzsqee#~_?iOl;o7`Ga!K~YH5sm30bFQ`zT3m zu(-PoCRmW5cB4`oOoBiQ64bg9B39UaAb~1sgDTB9-9Bh8s?%JQl`-d{2^J)1#;MX= zlqbwZ_0O-SF!x+E!GZ)vdXRHbo#vt}hdCEbAW&7T|3|gKpJUunBWNzF(_EB^xhPtY zz(@~rE~?X9l!>`05~!j%Bcr(}H{ZSHUs12*k7_q@Kg3*=(OgtoP=%2m6a@*iAc6kA zO<;5f^lc~5f`mN=1f~iJR9QVn;+&%e35=IwPZbiVqWK)7xv0BzY1U`ZtdEOXA6k&W zC@yklX%y`e!E?~e5(!jw&F{nhFojYNx-a$P#tk zi&7UktymU~Di_yNzpTl2cB^eSLb^=vcB8sy1r*&I?e&iBkt%2o(Dx=g5waTDicTGeBElAiSY*brc$f$a| zDvvEwPsfNCH~P#}&jgsUMQXKQrGEH0g_r3+pGvn`jlxE@;A(vOuDUh?RTu+AQF0tA zZ2XYlo0qCnS4RsH|328IcCIs-FYpt)ibwP-ViY{%%^x}aYy_$>Y6!&^DO%JBUR9mn z@$}Qtf&`Wb^`f_n8kNV@;9fy>Yy_(8Wwjt*DdT<>#z&pk4a*|ta26r2-yBt6Zw}>4 z@|C50Z0}LhIMz$$y~p|52~c6A7)2?+s)X@jhJ!EktYx6Z0OI#YyVMi4C-dj)#QOP< zsY)1wZusz?YwZN8Xip(Tps62N+?ZM0had8)ZJ-4Sy#I=_;%PCX?dqERz&tyFDy%(< zQm)3;EqDB0%XuP}50;x%r$xEh3A7+#)nk*$KdGc%I#Ojy7hfHtswCUqQEmC78GGgC zk}+!kWfA=PIq_~O{lSv@(=#gjqmZ3IRXtnmop-59>D%%#w(!2LqXmg^?V{9+2ds!d zB}C(A-h=`B_>wqcyEqXh{p5sJxiwUi!^USp3-*$GtH%W7VL zwryLMwp&C`jpc*ow*OF7wfLYY_nvJe(1HZ*pp4{qdITHeuf_80yFXMy0#(-E z%{!PBAuLE(*Cw&&b8O|`{#`2LI^%DlYV+B>j>|mSJ*pvr79?m_sEiwxkSd+>!OHA8 zRS5}HS${WY8I+Gigs>oCU7N&)WSzG@OfyPE|2FWqP<6n4KN1sYLBh&YLaOBbm=Kj> zD-x)({%-DJvF-;F!h(c#Z4xbJL~Tj?aK0R)@V8Kfqc+7B00J#Y;7DzsWfXs(+u8b! z8S7#GA3Nil95bVaV8jYLffg$UL|59ehreVe(1HZUhWIvts=b-oIL}cG2;t98paltx z4WTH7&kbj9E=D-YObynNK-DjI#yCsvkKkHd8uIabo=@z2u}rF0iXa^=NMJMx+Sljb zRx5hUU!B@9&_9`>lBRWPyvJF! zL@Iw9fvR#3Bb-OlMR28R7V^*{kg!KK8n8^!{T^m!UM0KQ2viNq zF~d0`Je-%?DE2_!ALOOK8DE91qFAYDK>{NwQO?^sbkBJ$*~bs%Yy_(MSDWvAeq~=gPuva*%$2ZsrRC!ch=A7Fzj9)G;_U~S78K^f;JCy|= zY^0$D35>m@C~sR#(6!>zSnUi2Yy_&RcU~ludyBpj0t8y{cdgi4iG3h}D!t-RXU%^tA6DP~ zplXInXi17N&jKVx2n!O{wMkqEx$FFU&F8ot_ks%b9BbL<22I^yu2c8F@02uYN9k{5db! z<@qtz+2raN8-Xf}kwbe@>mPTmop#sxcKJX9El6C;+SPe|VkB?(TEwQBd@Y&rq)}F0 z!M}@*K$SiAPUQG(#`HTyc>ZlI4YVM!q(M(-zTT0%{VTD{J4d~e#%Dj3|2D(dMxY9# zz$r?yOm&UnW4rLw7YiF`LE>cUfzCflMDlZ*h;vu1S$pI6J41Po_33N`sxX=z?LEKQ z)0n?=0-y8eQx{s0m{NAIvt6D@&QtavA5X6iHkO1;;V=3dHUd=`1&;dNFrU5kJ7qZ#wcnhlt{ypcc) z5?J%U=*6rL2~=UbQIsGxSRedbEE~Tj4aX>Q-3yJ6f0jOmi`-^f6BOT?;=?uUJcLR& z=k_2y|Abf;`Qwi^0#z6*j!td;FhT#m@ig|6n%jjIBr;YFi4UiUc^C4D6Ffbhjn)?w ziDu=eO|lWF!nkpC-eBDT-D}q*<~8@E3oS@QzL*-H{9`mf*tRqIxE|SAFS&FSD{v&a zfdr~BdK$%6U)@}P+p0gykt(Nw79>*tH6uRX+i1R^lQ^}N^P#3Mnb(%pNn6@RpbDeF z(L4P{g>;G+#%2cAGth#>%S>zI`Soai!C##J_;50f-t=W|_QUZGHUd=`p^akD?R~0U zot}#Q+pL#?79{d6Umw5z_h>#=M*dpY*3j~1yQuE#Jj6zz3gfuZ6aByKHP5xfRNXt! zKnoIBk13K$$?>d2$W%v;DZw@ZRoHI6jGSe%JlTTv73*;~cRe;oHEVPh1X_@=u1%s? z`{`TfbzdgO+N21fdOf(`$~kpn+)*8oKnwn^71c4Z4%=v@TutZsV?#5bI0(ze~Z(A zKgU1ezy6!jd9-$rjX)K~QdE>31FO3lcsF(4zc^k;3li@CnVJt;OaURWJtPS(zYkq92qXmhWW2NFk^cdb_RX*~uZ=i?KBBC_E@O@Jofhvr? zNbRF$abw}Tn*5IrwRN;0@zb)<%5!SR@YElQkPq)FHH~!Dn)7{iD%uEC*`qo>TJ2|e zrs~48v@W8f>UmYY<|wM+D_a-0MfIeWhLmlM`9h6JiGs;8pd8#~yj(Qpc1*J_`J79@83Fw^I}7Q^R;inEp%zaL=~ zD^1VEj~3VnRN142x;!Qr$5Kz@f6p$Wp#=%6rJ3!c#N!|%aA7R}DgQ`jBit<&TbD_E z8J|N8jF^P+mT1n-XueH(u>TWcVBA5mt||5f2o1(OL?*;Q3lieFK+Ne;Eq}>IpvsC; zl9)gX5~4qRw>VFc!~{mF6FC)>R6%q(q-b|PSdg&#N>qz$JAo>UM~761ffgi0IVGeJ zkPyRdk#S!z>JUcp0f1741ggZH6uU)GEv`chv><^|e2}sesG^ldxq}YXrVmu5geXAY zCeVTeM%6(-AqEnt61zCamPF3cf&|9;vHL&*RqmRfM2kWT5*V|{?gQH(M)kzjWhc;r z1jg(9Hi0U4{>-)lNQi+d5ob``6CwCEffgh%ekQn}nur9d+;=vKRG|e4jOuCkfds1D ztsn^>Xh8y_liGb??}KqCv0t$hXh8xaN`9L_6{S}0NI|u@4l$^QN$B-)G@#nU1eKV; zIx0>mh|>f@g>@RK5CbhpU__{I6R2|c^GT!%El6OTD!UIPQ1$Kc11(5kye+#ABv6H8 zmz}`+gVAEKzS#-1AR$hSiPA>3xK8M)Wvxb)dz46`wxb1!UACCAUpys@IP$kpg`?dU zy+{?-SBwz)?YfH=Brw*f-3Jn=5+i}=XHYG!<@k|cL4tZZh^+dBvlFPI-)Ewq`Jy$i z>@zZKkM?+$U$_thEl3Qk6T_;!Rabq{T0W3K6-E(7D#XCv0AqiCyJtWP5*T;X?gI%_ zxyy>7T3pM~K$N1iAc65Zk+Ku0a^LeLe7svczc962X~Fo3?pBZlffgh%UZXu#NT3Sm zb9Msn8l%*;YUsH~D879M(Sn3|y;#zAABhQ5h4F0d1X}QS-L*1_-Ur(R&3zK08-Kff zpaltxlWb2F5~y<5wCZPKnoJo=RzFeFX@uwpcqr7cT|15tk8l4jXn?$ z8GRsuD!fl$^rA&!j8}L6C~G)Iaylb1=utZVW2!PFBqq!CB_UHtzq1X_?Vug$*ezY(SidpfOybEPp0 z>rurhF;d~@cA2q11J#T?cb1`C?B2l0h!juRrLs| z3lbE6A|W~{eQ*0zCH>O#daTag>NWyZ^V;8c{?L7*d)H*K`a8C)KXX*>VZo@U-TG{D zwk>b&Nky8zQ3V8Akg)q$T&$$A$xG#RH~8x417oHlO))YmmNF_fW<14yT}KNNT{B;B z76=UCi)1X;<>yKp-d;M-(^%8dg2bs4_np)ICc5`>Rvl8t`0lvQJ@+ylEl6O*Rq7|Y zmNnj9_T?wB~dDXB6w#jEyVyi&^(ZTx0B4McLTAtPya;mq)!&4YVN9 z`on%_tC5r3`$ZSED`zZtR*TpE?6482vZt!j)pEv*$+da*DGmcINOYlEvW99&u|i^( zMapIsjB|zk`0WxtHUd>xBJ@uGj|W>S)K4zfSahqli`-f@TwG&`*a@^Cfu%ruwkOum z_YY{sPA9LVV}w}m_>8>MAv2CFMb&}0wI{|@*Pr<{WgW9u*3p7Q@HT~ynPo-O4IApM zcQ4R{btzoMMxY8~=29EHQcVvS-I$GwucD&`iNJ9$oJ->Z`4(SKD&6!itLj6CH)64? ztJ(-uVHr|v!?acP!b2Leku$2 zl>0Za4DAG3kic^LvL1Dy+_6fQ4{@I@LR?#ax9|Q$0#k*wNksm$v+|G~$193@h0%0( zS1G|u?@t`DSy7O%yo=vO0#o>94f0He#g#BJ?@sbjhJ1*flIYt`palu^N0FxTPu=?0 z{zY;P(n^*1T`MKx8hzUdv><{0zTA(_9nNpDe26jJBE+@zcl+*7BrsJ-n?#ETYqsRM z7B9y^oB`mR!SW$!+RF(9T9CjL(k!ELaf42CaQA5rC!OYyvCS~vE1lVJ(rFHsaGJxQ z(;VD=nj^u21V*Hlr#TEd&B5KLIT8p|@q1BDI%DFFJWQuK3_8uh#c2*yVH9FJL8mzk zI?chwX%4g?K|8Qz^k%bk>Ew$+CttWY`GN$hX#cj8PQfsfpwk?c==?_oY9HeCfQKj@?d5~xc3 zaF?@Foyly4Jk2q(UlHBwj5m8or#aAq1jb*cuTCE-tk22s%}UUT5hPGWr$?N0DutP+ zQkvH&tY;6d#-`D!6tp0Lv5^&}%KAcjmD^R>bUOKh1ghwKgOg6dxFgD~d|FIzx4I_V zPp2Tzf&`tXfT-E^0*mW((t?ST7D%A#)T3QaI?ch7trw&7tW+iR0XKYDFFMVE79=oA zx1y9?RYHG1!@Q+q@7OVD&Yoz7*j|2iONZ5VQDF}m3LGVX(3IbK= z52KsQlNJV@wBX{T1rn$l-!95|;eZt>olbKYf7fDMoaR6a5_B#E;-1rq5o3Ek#uw3v z5hPGWr$?N0DupGSN-^kE3KyqR(1HZU-==sOlS&$N@`Wd(lP^f1icWbr=@g7R4kVrC zs6yvIDvA3+JMCp0dNB&q844$z`H(84DPk`WXhFj6!`i*$N#{Q-AL2e+gt)f;o-k*S z=O&QAR3U8=bedx;o&S(?Q9Ah`@>UwciH`^ntWV(D{$bbpAukeGDsALPcjN?tCNPCxW-{V5 zhvh?z+m;V;ZT;Q!VckI_&M!i0#^90?XAFv>2)fCwDU!&XJahnVL-5(reSyE8^Du|I;v%JU!90{`XV z$1^%tqzcl}f&|9prEk8JYwPMU$={i}YoLul)$I*I>ii!fSZ*1gdcwmWT*|~%&YfvS z>1aU$W6~>1Jx`}=-2{&l&2auy9s3UY!5v+0Dy1Ke!5?<5OQp3ljEd>~A_a z49`U^dBL~kYy_&F`pj2n-3enKdy4ZPMTa#pnmPOMZUge@Xh8y_zfTZ>lwzzR}p*Y*S!ujUiY5LCoE+eT9BAwi`l=n&O{^G#%a9vkQ6ooRgXfKsXufM zV-*gG{q4gq1Q~~8WBIUvFoqT+=tKm3d*Ga3u#xjbEZ@81iHZcO=mdsJ=RaiB{4ag` zXFC63sl?t&OC_$Yzni;1L3mgheb2((x! z5h~iPp78yKZxg7Zz3wWV|8Rd7!0Ovy()kZdC3cTnDsgT7-Aq+dgs>oCU7JLkOF{bi z>9K5c1jTQ2d&l1u*ZBPg`eNB{C!Uw8Tibk^Sx5O!k#(6sGL4OWs^-iTW z(1HYh@qyy7{9ad2)}<>OeZ7#4Kvig=o@#+Uk?iONQQJf5oN&9^jHN!J8)!ko9``)% zTn;_QB{ZDAu&_1C_xYS_3)_R_Zn`S`ddr9N;_4mM094*xLry|*&hoWZ)9~G)?yEH?+x^j$x79=qGJ3V>T&!n}jP*ANLI?+a; zs^I3vs`6JPS;`1M9LE_s!kU$ltP*MK6J(f@KiHUC!9&F(6VhZtF z2h@wkws-9*GtB9y2HFTzJ)6JYvHkaG7L!Fha~|Be$5r#UQ_f0({svl*z^^gT7b-^I zb>&?2*;)Nf9~*(HTHfm%4X;MCRSSfV0jH81n>uCV8?JXY(1HYhxq`l^6Ijs5;a{0Q zc~Rd+plar{8IB2WqnYPSahhY;cxFU=Zq3^-FJqtu3H)*e%`%QPF}4-z%XdBVuo0+w z^l6&o)B9*vy<8{qadJ}!V@$ws-fvtQ11(74w@2v9@7wwt9m-AOsUMzoA%Uv!ydjPy z^ktXroy6&y29rk{h3-f3?{|l}(1HYhH$_oir<`Ey`7o6?nOMw5pz76!AV)d+9!sV? zgULt9UO`6vX0beI$aanvBc4(_&biePW+}yM80|rllg;jaLgav><`s z%Au2b;|J@D8cks%>g}@;sPcH(F0P?(4Es)=H`wyHhyM5K@hoP{OAReZ*uN4}Bv)I# zUVneK+#{oo1gf@0G}{wEtL_cxt6lVU(7*ij>@B;nqe>ASEl4D96t*?Ib_`3Gr6>_; zKGo2p-Zf*F##hwQf&_lYh9dm^TTIWqt0sF9Q`<(M%J;9bK7o1+8!}OxF^To^(3?~( z&9X0Ts-p!7{JM^!#DC17&*z>jWJFsVfvW9yclzX@nmFf)I4iTh|8?#Cu7A{$Tl?u~ zK?1)LL@@_G&)0b4U(~X>M%oBetqJPn*x?bwCO;PEiqdy&to4oPt(LqMsG|i5{Mr$n zWL;2IOPi&Uy5OJjHUd?DC-3ICmMex;y)Jyr%KM11uoUW&CP6w{kiaK>I`h-GCu^8> zf}`o8U>kude1jlYEi2JFr|3(>in~f{|MGnjtzag61%+1PRN6Tp|86JHf&{JhC43Qu zRzwjE9DY4SQO=I3ZoKwu%3GW3oC)76K_Yyc!bZ-r zzLgR?)Y}+Ppb2kdu5%_3sKPIzD9WfS)r`Q=jrmYo=R^wvI_Iwv#NIkUd3YK$G; zh)2*mClaW#=R7EFRioIDhJ2X0&Y4gqNMIStRm&>0&MDtnVs7!R;G1MIo2Y9Dl32H z+d*0xO(4*Mgq0`z8_2%2&WQx7tiPM@6RnXG31LCPx^};Te6Xext#itEmiSw!q7_U= z`=s38U7~f)1OhEc;P;s5Ti8{+jpkPx^GMo%RcNHbF77hF=YzDJsOwYB@IBCoyUhJp z%=+pRepd*8Nl|80t7^m){wuT~f#3g8l&OoW7{RX_@B_5}3JFxvE-RJxUomt4 zRrOt!jU#{8=Q+*&R|ys*tafhR!TqNy8RwqY<8{sbR|y2Ftafe^w416D?Z1-u11(5c z{c&OfEl5~>ut|jZm(eGk(Ai@b)A1Wc_=O|d0j1L3DEErui0)PdP zf?_50U%XV-fcB~(fhv3HR{FJ)uHUc67SR4HOfTkx_7thK|B9LWuX@B()bEAWWzpvT zs{{)Y_-!v54NjHOf2--s?(~!UuM$RND^;Se#V?L2%9|Et^=n6cS=Z;PffgiapOi}b zuiPu6_u7}!(^2rYte+e<0#)`@ow-_0|7l8X7BtympaqFqbZ^$ty?HIaeKw_O1-(vT zKi0XVkBvZ;y{zEPgwAvLv(8sDbFq`Oz{NrAhYC65b=AWo*ygy@^7@Njj5wo@OlG@F zZ*>ad`S8i?&WBy{+UIN-3-(?hukFO~bBn~VMibaN|G$z* z6%wejcCjZ;6{fw^oe0+5GeG|CxATD(B$Sl&rGXaVNu&x1RDJsn+AQ$9f$3>4L-N^4 z_&@?xSbOZHi#0KG}F05aQQc2WZBv56YTu6LB(1Jw4o*h_C zSNSA-pvAv(dlsrzlq&osdp^*DM9rqHSNm$FXtg-^!Zt?b?nOBzA_5W)E&CN%%klRp0Kf(1L_Mbrg$< zOP+)eBv6Gl)P4t>ov6fGylg9f%YAM_UZ4H03M=xYO%guPg2cB=7YS4)e_59`Em0>4 zA80`W@1{K;2m3^^CLgM)q8-H5k7k=Zlc|~M`eU_d=Cd!Y{JWh%3lb~3MYA>2|8Zm? z`r8DmHqgrZlzBTHiQ6Em7RE)hu?yoI+30t_O`rvdIv?pBb;j|Itcg;E1ghp0i(xkm z?<7)%79^$?iD8fTD30$E`9K0ycxJ<1R%k(DKt+1*+WBaW#ASs9s;sjhi3zkIakFp? zo9TZq?mrW#!g1c7540fhj^2YW7&uY0zN4hEm#`CPK_YqO5^QjfZb_sH2~=Sj+I^q}iEan-v2j!S zCE)`JRAEWmedH{6K|SG(DyymbHh~r- z#)i*O=Tl7j#627msB-V6NP=*5>Zneg6DcjLi`7;~dqm0WdrN%O>y6E8`~5%*5|?w8 zR_o0FZv?8|^L%Q=pGgsDL1K524CXm5`vi5zuMWF?WY5xpT|H@>xGdb6{Yi#(vldIS~t*wMA2nY(nnYM#q_@m zR+Ys02i0r@s_@I^wA1OWDhc0hWev0-AtEV>`%#L%=}tQ{DYBoaUH=^Quo0-jZ=utk ziCgU?k)q^x23nAyh#u0%F#3i(tqBM9kVJ*-Z(K;A3cr3#=bg*-mc*-6k6ma%BKNMH z(nk;ZwdS%-`b*+YsY^BjRdmW=-PG74P@E(1HZTHIY6l(f6bkr9kD8 zlBl$CzKuW?epOjfst*_^iQx17TxdapqOC|D`Q?|bhdU-pVo{k~HUd@n^6{}<}uqwpbEc{Opyw2nZ&z!ADw7Hg5rTlAE)Vy;Iu<% zn@M~gQI{csD*UQ4?OXcG%z0?PL1K8_gVINrE#mvm6>ppOd|jQ{HUd@nrC^GF;5S_QSUhZ%h8845eG~aG zzsjC1)gVdy`01#PKox#ln7)tmr`bLRst+}^AR%IJ2_HS_yYUozA*6%!acxmr9SKy~ zzggU^QY%RmFPu$B3lixrt&lzn$S>Hx8P-S=CpYJ}5vam1UMosl-};i66z`>@1ql)J zPUK@vI`Q@F3dJ0f*uSB?jX)KChg(tNekm`BV#OUgT9BYPGtx(~6Aj2mfk}BKvCy-L zjX)KC_gPVD-OVhCtMRRMv>>rDReR~9_M3X-Pq4g^>k=KLc~iEK8j0X^N6}!+z-(=B7v$i4F@}fk4G|9=R^OI#41V^ zT98QAYmP(s*eY{gU_*JA@G*vRjs&VaUd@(1{*a~X+*?}`qIA)MgoqR)e590j@bBCs zC2^VVAQGth{Z1-Xox@KOL1s4yuVrplXmuL+N9> ztnGc(hmxpBwH+-;i1KlU2wfvU`xR!AS7ax~C~ zH;a_U>eoXf`s4T ztrhbGJ<5x1Z$9GJ!zV9^Yf~@8;|^cPo=vn`bsh3le(mW70?I)ZNL)hmk=t zRpY~M*$7lUrksnisvu|K0~}_~7naTCLJJaJRJtM`xo-9(A9)6hlRjcE_OlVF`ZRT) z^ifYfO{A}E-t*nmH=+dzQG0|B^NGdSFsY2T%RjMxg50psmu!boq2QU}6vHBRKaP7g~^*dup@v(P*xC z9-Mijog~JV{?0%GRWuuvKI+P+)JlDtO5({$4+AYo3|qNS`ncMB2>D3)k1C1&JIdM! zROMI}C4F?3PutZCRF%Zkzp5E%L89^4DCuKMcmVlGF{HF4;^>JU2~^RHQ~Ed}-x~Bh zTwD^z=&b=-kf1rE^zkTqDEY{G&_fb+2RF45sG_-@^zlT#{V3isgCyGJX=k7XiB#E| zOCQnu#ru-2M<2PwIJiXZZ6i=6Mp4l|%(pmCo1c?Jit+;tv>*|zYNmH!rg-CqAirfsh1;c1gdDpDd#>J z`6wbje;y-=*FDA>Xh9;R-7Goxsc}sZf%P&;qT`f_HUd?Rt90`bW%Wm`(L`j6nknaS zEjtApXhA}hzG&ww>I!0Q#hOm>m(w5Ygk7a5!iPy@s4c!(U=rfLUo2mKw@ia>al(f? zRcfr9z3%U6_NEqrsu}%b<(&G;ZIScW%QDcv73I4hCK_l#g64B_PMtxPZlOcst|&^? zAII7VRN;F@8gYg%kVJ{>BW-UWk-&G0^aPnAv%a}}1Ea{yY1%dYv$}SAXWndNAd9Y_ zjQv?=05A1V3)Z-{2P>7T1J7`+73FzW$qnqlR4=1Pje2^i54zf1&C6SCb+U4o9ct!E zubqD`JHnRkiCL53Ty}oz&0ZpMg&xpWNA@w+q#vct{%*0#JCCJriHu^)PAyTVM}+bn z$(yl#zn)Rw&l|&ccW6$8-zyJ&#JGy|wWc$!1{Er>MwfKeql}k!XLcU8VMZ~vPV0PH z@!7fAk9)nX4L(zvQedDO17zKoTJOw{93bD`PltqM;+$}d1<-I z5Ha$)Imr6|<&q(fvMWv!~LouZdaX|N2Q>L{~-ob>9g`myKs? zJoz~}5szISdV@(0p3nTPNt2z;Zld*oDx^R|3}v0e4JYS*2DNxC7)91 zCRZnEBU|?|1`Ri~Y88*D&)#oxcsxz34Igw!jrwD_qgCHjTDiafR#RSk;Aq<>oybR) zK<&chPDaipk8Bns(4V42_4Z``r3xDL{Tk?48?cr%-Vw9r$H<$`6fvhLRi#Ew(5F-@ z;@VzJ<aAr8xeKe6;){SnqXYhqF%jYG>OT zeb|fWjx1k^oLbGF`mhPdyRu26@@T=wd$Q`T^6YJFR`StdExm`EpDKRb;?}&%!9HwY z=I%^)=GDCO^kaE1^#>JA^Y72JFeZO2$wa^OPxE5hwZr-3b=xdOw38Y0v-1Cj`TX`=)b{+r z74-#wRyPg?x)|;$!remK57lL7O4Q z{n$o3L8Fw#KJA_qAfnamV0~bPN6z@G4H;UHz`Z7lQfF(h{=9El=i~U=HUd?+14dD9 z1&r3)uAkyMb#EENor}1mak^I|E0W4Wojy2&qw`Qc%1`U52R?c1idp;{LkkkPn@&+&OM2M zzWRg<#f`uNM;Pu&!~KbK-?nE>eai9%b8}Owa&Gn0``#*KOh12=p#=%tL8&MwYSz<7 ze=2C?&V9^ApbB?v()cl?uwHwWpE2RlCWgCda9>X8*_GJZYHj%TM>#1~yIDcKj$eIa z$%+j&0#&$YMp3?33+jK5tz*21t)%6dQjztp-hxjnUWV=1o|pB1)syG^qZC7$R({^* z*2m3iZ0xx8(PlvcciAXPiOhNR;++~Bn}7P*Mxe@`s@O)awIzGI8%s8>Vz_Sw_sI-x zkb;ftGK}9lRFZPuq|d+F>7iYXZC!q5Xh8z^=+GDJTcy$8oNs5$x|du-0#%qNdfz@P zgMMIo8)MY@{kHN!!oH_S-<3sww4ic`JX?l)9>v2Lt!W>+4D79?;-0X=ce3D*{k9c|3L5n>}yg(adWnS1}J z<=8pWXgsdAt*ns1-9i*ow&`N+c%u=9bA3Y_fhsIFMd@0jrq*=Dc%#SDGz|CO;BEoT zAH88o)j%8kSD^7nu?)6+Ac6Z1=2`?&=(#s?ewPUK}spbGsFv1kVK zXc%my+jv+-3lg|zhGu=WSF-K-f{kliezOs%!ks+iwbafdf7a3#$msg+t-p~b#U*w6>-Iib zd*s({Z`dM#H{Y7P^r`zVsa2Hje7<%(>LV{-WVkIKNO)XXA?e&j@=~g%rHa%>o=xp~ zJ7J`aKo#bRzQf!8y|yK40snDaH)HXW%yO=tJVPPvlXpsaooQl0t?ba0?5`~WJ|Ue8 zl8-^BA8MWIZs5sw^)k?cM8iCP$y7y*^(5j-tt;BS*eCqZ&wXtKs<1@p`8>xlZ9>)K ze8Qpuwz5K^?6!;2M_@>P@==BF(OS;B$+JEhY$H&G@y(&D5wvamhzKYuBB5d{78sZaXJ-Z#Tf#s~|IY00*)uyk^UQN+w;VvcZ|l*Ok6JPqfke+6zDRfdRoj%H zUYw|P#)+&x-Bq(9*+d|qD%WsIWgE*b_THlwR;s*z0w zYR-Gt0~;0MOhqjDT^^2>rKeKe{5fdm!U58~C`Wu%HysUeo+zF47>h0VP8+k{Skm2~ zoD!TM!t8{UTJ6;=-g02o+CXFglRuuOQ zi6tXO9YFQRWKkG_giCoU@{h=tlKv=Xp5PNpeiZIRVUL#x1XLCENJIGd66vzr7)}`2 z$B?DZU!zCE_tWL2$>m^#xb$`kx_RTFWM$!syBthHS8tq_E(a<1)s@T`^7TY1 z`r@;l!U!Zj#m+(7?i5K84U|=~gTtapxob__sNx#UIGBh|j59$6E+g=i;zX3#-x&Q! zAAwDmB%qw9AEhzsft<(=i6(Ksb?~yB%M?Z+u_QMM1&-23dx}SLqIy9zp&r%nmnSC$ z0;<|yNk$Jx|B}kKx^QBL97R0c>*37tWi+&H0$Mb`H9EGz2|KimM~xfRMGw05!&5fT zMrmg4(W}#roY=fEifkBRh~u8Wp)djox8bvqQ?3Q_XrmAh?V?D#2whxIqplp@VHVmq z$r*Li?Tb_Ahoi8FVQ4^ZKm2lO7*Z#9MAk*UIdQgM6uJ6Z4`&UnEyD;TE>4a>NzI3# zfNUkdB*-C(3>jGqFS=S&AfU>$O%z&4`lA|KlofZo7SZIG{Z%yldtLcPNDwkS-V@b2 z&<)oJoQ}?7Pjto58vn|fj(UBcfYydub0Y9t6xnm)9_n9KSB8;EB_YVU&lr?4Qo`_) z_#5QqD6+6u8G4f^wgHLP1)(U`+zoxnK)j7Jr=m#Y?AOSAph!T~incS5Rex9Xt+p~p z=3W*}Moiv;{C{c77ks9p%mJQA*0IJ{?gpSwcWewLl&MXvKfKjS*!x3##J zd>09&FKfezq4u%lQeVt#rroAcRjliWK3(uZLmVyshq%johLy+N`ONhr3O@@Hjeq!~ zs7^kpW^rfUhTq*7;${|xq&j5+0aejc0+9V}Z?ry7d2-(4^Kd=yTT)BI1YzzK&T_(e zSe2@`O&l?~Ff-M%OnpeTOgnc&X@ApK|WjC zC;f?Lb(*a(TMK7sW&ZhR^jwk0n)4J3;pKy_c_S2Gs~Vma?2T?N z8iWSa)5E`3O+-hs8l!C)+MJjh7)M4gcceR?_dqZLiE53!QP`GY$RxWKC)&rx5s!=k zbmvfWfq<$W4ZP7=$pP6K>2o5*DvAty`<&kV+#F{__#&;Hm!vmlH_@51{%Fza#^}en z2mdoq?VS@t;s>QruMQuD2qZ!}_@WMbI-tpQUh_Ave$``1?5;#wx7uxifGRjgu2Mx` z3@7_;Kc&7pqwowl4DHS^mu9(bMmR4VJqkD`8QJbY@Mu-4X+cqBa8N2;@}|3R9*}tT zCIm&+c_nRC$^57Sxa0eU<#Xu$j}`&}ReR+i)He0EV^o?@$h0A7BL#b2qZ!x;?e#IiPDZ!i#Rc2)GTr?><#^PB|spc3Vu)gsrDg)eA<{! z!~2X7zClQo`o$rg{CQIO>@40!Q1?hO%Q%hRUG5+dPzAqDm1@3WBr(p(qSMwo;E=K; zL|Ph2{R)E-dzOG|Cne?AOz=m|e{-*iwuX}7t03M+erhDyB`v1YJN3sf0*S@D=OD|2 z>(yqr968}qE1KMjHb~}s?b&;lobbIG zP0pQ5qaWQ31p=yuyh`Q0hO^pjmYNfmo@&w}qAhFc?u_B;OV6OuXyxvfa}9LK6y*qF^2Mj!#(Q>k*FIFZjDKja$m*#ZGo z9eYefCdEHA4}N*@HoDFkLZ;@{V#bLJF^oV0UN@EM`PYGD#HFTeNdF56t`ETVFSr81 zcUmkRMqXi4_OeY43?q;bSIMU7IFa ztIqwS<_43U-<{++?~?@rs^C*wrD|?Hi;S4~i{2>q6Q0hHfX_#sL0%p~JZH_PC3l7k z1XRJX1kXOo4I=yJ4VT+)%@Cf>@wfd^_u%>YIbYWQ&nUyOB7khzm>@eWUn;Z#3Gp`= zKW{48;}<1&oj+e7pbB0?mFoLsU*dgkg}kYFsc@|z0e|y+w)VC!3D3-t50W&2fGT(| z@SRBKy@;jnaXG>$QTWaw0ed1|YtniWN&H?cXMb}Q2&jVhG~ZWrU@SQ`zd{~7(oVQ{ zApv_-m8$N}F~sMVim5Ye2n1BYb#=ZbTsE3qJE+G(o?aAI+#vz;CwQgX!xKqh+nw@z z|1B7PYw#%wuQabCJa;TvxZ#XEY0q{HBanbkRK6zsVI28#`;`2kNwz>h73}l*8~wG> zB>Ki9c|lUP(6>VZK2f=c+dCI>fy0aftX#djiEIg-}zby?nd@figP@#%c~ z$6)eso)P;|=q^0fpb9>N`51169na`*#iBOb2+vwbz;PGPnTV0d1Um~Bdi;-&IRI5K zYeA(NuWe0gkLk*KlpGiG86W|(Z1@~NiA0=3zRBI4-{Q}ygV4|6Thw!B-bIdwJE6x} zKl9aBuAzam?c1p)z8J*FUZtDrG$uxvIbCVU%DGM^uoHR;>%*C}I=@98Y5&(Ws{Ug-lD z$0NzZTKd>V$vi8o>q3@4xgf8JIE7&Z67U-Gnbe=-N%F&;vh9Hb0s&Rm;=EDgyLZ1i;@mlG)j3Hn9FuB>eqXGd{uz%#^b}uKgKz<-M zYI0V1V}S&`LshE#yuP+u<~vzGE?*#^3ckIlR3EekkZRgG?9cmy7)Br=-n)By^&$6P z8nPb4HVXt)!8bDAx0g*NPd;uw+ERy?d<82%aBT{%>G0qAlgXq($MKq7HSWnU0tvWI zrBd~uK7k|*>`X6y{3;Mo)%c7r`Vo_^wr;AdV6841M$Gojpr%(EG8lmbT$SU$!2x~A z<~L7hgk&xdP?bJw0HW!E>JCnpyp7VYjwJ2PKG|sBd-?MHzUc9+u~KW_HrTVj9a@Fs zq)TC~a6+ahveVftg}ms*3A+}E3{J1dLIQZ&-XaUM^=+}*;Pe;t{(FD)dfPzB==?jR zPUw$*%v~zI&Q`K<+sC?*?7lDL_7(Fnj6fo<)D^vHb4luw@RR?}dj$HBmoXP)uaAQT z0;)b9az(aHzeyptmE7968=>U*@(lUek6IW;AOUA4`S|Kp1PL}DAwO?E4?zN|;2bG` z4(7!YvrI;3HEe`n1QOz$<%yCwvN@&>jUB0_h6GfJbFYo}#1cIldrk5BOTt_@oU?{A z#XKi9FPeBr)#S1l=Y$zyNSvxW4q2V9hcZ_+=GV%&ID+hMGFpB1>^hzJ zbUG;eOERzGr{8;_ zHF-aw1N)HbDdcHGm6)@A`|(hs|EB@-EGg!S%fdsq?d|%PjVB+kTBWtg@C=gI3#d;#PsXjWN){?i8 zHXxD|H}4{^So5922qfUQsZuc%P3CFuqc)vQWk^63TyNncvcoZ?ci2v8`&u0tMj#=s zW(<~M$kUK4RJOR9KtPqaj$^mom5kjxTh8fG9NY%@(PJtFq?x#xjg# z)-{yw^jj>$2qfV8Ctv@t3MVGtyQ2|rW(ovU!Btt6>Q|d+(*DqSbh56Y3?q;bS4Qg? z#}KocpV2gnqrwU=RKc}k{(e5WDSDaPoW(vENMO!C+zXJLmy!Ex&tA<2om;#Y?ffMf z&30_f&~$qOBaj%|PAy&dG*h$k>LX5EGrA{z+|ZUi>D5;tpz6!6j9fF5X`1BrPdU-) zqBE+svlEM4rzS802_G*ak#IfDku%Effs&L0$$wU7W{5=ss`~RbRyT9iq^3USM2g;i z)b7&&)-I_z$u3FRCcCSetd^t2-3VSsqTgRW)ODYy#t?S``0=o zYScfaj)>i!Z$9P=Z{zj;pSXTQ3zoUnfJAiAMda!Hd^G+QYO>Z0k*TNi%{P=H__X7z z`tR$Jja^$Y`=2@lMj)}z-Vzz)4mfi5nsTisYFUz*?hRO&*K^^?303f!$Y)sY;$CFIr!N-|adBA7EA7P`32PO$;NDh+NVP zjXrEA4U?58=LDB(WOk_&`?7keKtR>#7A=u+p~76v1KRg6-khQsxyQ5UXyW4rPd}&ziatx2uX=HV|TK4P#A&4 z)xOTCPf>|PyTZisq}X~&5(O+v`i4&!8#)Np}-ssax`^y`m4YWTDxC!XI9C+-_|(S4UE z$S?v4aaDg!(@660t-Xf4cNYk#f>{eZpJ81TNsio%qS|&4vJ)U7uIfueqR9CT)$#X* z^#lT{U@isE@?QJ~YrnT=6VE@u@LqzutKj#~>z5Q5k`=xCu^(O5U>Jb}d}{Mr_qWZ- z&TzuwubK-4RKf3`@0?8QM|4WeS&%~y1S61uPi>xooiv&(%df>&?o6bRfGYU?^C}*W z0p#@%CNJ~-Ltz9G@EOc!)%-)q>VPzPp-E2}5>N%de|}%xk07ZPT5?6F9x{wT0zS3* z{BGYUvaC)&TJ{|Y1XRKApZ6tM(ZpNJ1G)BUDrBTU0%mydBv$iiQaJbuN_;71i$E33 zXHlu@-I$LpKlWwiDJH@$I=FKV-aRUn(S-GQPEKz&$f6m65lF!Pn9p)vyo$}6shNk1 zzCb_~yvO+4#O?3cxu84ifVByXKmzvQe4P^+l5P`wu))1=3;PG53hpK3Z(ct-ktwVd zyXloLj9wuD-+ff74ZZsjKUG6^YDS_!KouOx^0Ci^@x*KKYx&dlt{6rj0pDc!e95E$ zVjg%({_VB~K?17a=$z*o?3qQrp?Eo?Q!QcK4hi@s!`F&FMv;%29`YmSSmE6Os>Hp0 zzsJN8IWCnZMW5Ed2qfTMLjH_89!IKwYNWYvqqC4%166QeABK}GI-C6I8y6~hEn?2Wrz+JfTN{c&k-FBr(9i|Uu1Kb)D z7=Z-5>U`zrrx{AzHiG4}Fcb)=%3k3pUD~aqwuw~6KCy#cQDc8cW^m1vzz8JZ2#}9U z4EG_^SL4`}p+7Jrpvp*IDNWd)rapU6IrEgY_mJTUcV=<8I)M>Lz%eS%%)A&Z-SZvC z970vX?qzrt;FabXjmGuSgO1}_S>7)UBanbct5S`;F&K5Tn#_XM-4_U`S{^n+QkRFQ zi*=My-;|2o=-_W(b}_LK!w4kc`SG=hOOMcR9K;&N=L!T=S%s~U%ItQl`?OKs=ylbd zu#RpBJCrpK!w4h_%P&f=P8X|VCn`jg+i1M1)=ah`rMEypRr1&(X(}pH@6s4>A~o-* zt({nO%k6oIpe*K{~zOyVNSHu4<=YL!|d!dIWpq zA1Fj1(VJHrkH}3{k7}o6o>BF8$CXpKd{{qZYu1l=j#SM<8t+8L)Ke=1cSTn zA#rwXMy~3KvAVg9DL<+~=e$tBpH?jBvAsY*)lW{;ePyApd0E*TetCK{(y&Z9E<23D zy({PWQ3VhC&(0UP>z}WA-Hk?_yUOzWc2kA(fW+N38M#h>&q<}axh@iosQyNdZ8}LH zpbDN7pAkM`gHq}{GrZfF!3qMfYJlI$jNBeo=TXD7R6062j*T1~Pji-Mr=8?-K<|dyl<+Tbh&JYx|2^me&z|CN~QFqSk|cMxK5=)c zR3kl(wTT#m;OD}-64E@ot)U|tC&jQ0A8QM(LqfcFcj?_mN5W!R)|smk{4A)lotG^Q z{d`P){fF}AH6gM(E=iAJ&-f}8j6kCN^g7A-^9l8dManNKzP=-_y(^sgXjPLT0aaE( z#nPlvx6~h7Dfd-qL=djleHI%v_z8s(NCfw}CdKwCS3mi!998_HT&&-6G7B+TDnkOQ zdMvAs#x41z_PwE0jhI+|058(+$!^VVB2=arV0cq1K9i=7nrenuowy+xdZ;tZS`OKWJ*q+t}1^3+i`c zGBX) z|N1VZW27~kW}}i}1QHzzY|x=kizP2RW!>P{9*KCRv|w#(&lU)%^6!Yy&CE<`O+97b z-Ivng1P!T>=Nsq9Fan7y3*C@++C^zq&$gU!ARgrTfkX0ok0SyBRn@5n%C*r*wyqYO zFw+ho)q0MWKZNa&VFVHvhD<}A@3m0yPi2RK)}-lV>fmbfv$1iat)d+oU=`0&n2tbDVUKtPpMW_@IERxJ&jtW<|t^`JKSyx)bH z+02(<1QPHL<@FPXH6wbx2e3nzYRZs+s=PK9sQnv%>C`RdY2cjQgM3PD&s0*13?q<$ zcPO7#BbW^7Wx!s3%ohl#f~%x_*RS1h(r)opxq8NB8Ac!h?@+#KIc^LI*u7GI{rr|d zKowjIQK^<&`4QULLZ%ar%P;~7c!%;G3g@SiBX3X8P6H1K1XRJb5I&2;!pNVnT}Sta z&X-{X67YUgD$sGr@4dR~y@r+EuIq#+?z zv-%n^8~-R@BU_&I7YL{lcSv77uo~~3drhvjV63p;84?=vo6`NKJ=N)}m3~)MFAsN^ zo*_Tl?jsOTCGJHIpLPis=N*tgbaWGT7DFO5T^lvrLe!d_&3GF((;nh4nN#I_?ePKu zRdDAt-^X%LpA6U-L3@61VX$Hn+>tF-Pg?G!O*YqN^y?*e1|yIV+vqx5mvsBkSDv$F zq(DHGSdZ-ckDvHu-DPq~+HeLVkbvjJR{{Ee#+~xt%VkZGKtL6&g~oTwT3^Ry^>o;Q zR4j}|Apx(nN;TR^##ii`Fzfo=1p=zzxRl?!SJvZm-;G$)OLh!KAOY_fo=<%|9UEA5 zWc3}a1OlqyxRk$bZyS#t!`rbFAvO#~AOYVj`3PV|5BxBju)5i;1p=zzxRlT094JKn z-}GkF8+Tza0txY*vt}C`r2c_eweFSz0afDLU5kbd(J<8vwx6z$;kXvQpTUtc-r-$r5VK+gn$fGRki=amXe&9J&fII}1mAdK`O0pG9q zQ!UO9KV?4b`-tNL0afr#hOeJbNW^FA`m)jcx63dB3HW}+*X}m&!JiKgW%`A`1p=zX zyS>@#li0mzD6{zeR)!Hsi0^8<8o$GHGupGnL#D#r4pp$CAkVD%(~=mUHf9CCv>2>T z2&)$Eerkmbsx^^j9aHu}zFO6l{MqwVwzRFsU<48$uiK-dEuE$D50$mM1HF5ZFuGrE z6xvuIph~CC0Mzx*2lbGW4xEt929Y8*OI~MT#9#yx#~ml5;qOLEZ*9ACBEHXX?gVWi zFKkywAfT$*?g5^(Q3uea1CoFM6&RNg#7 zAfO8F$mjJkM#hktQ&Q0FN!4W-frPj#e!d(_)ENs<{ffE5?tZ9(JNS6d6#$6Zk_u%{ef>_P7FKl205~+(-sM~8}$^3%yCLHl? zHU2#=l*JVErI3Is@$GJu=V2UI;m?*2u#{m05|$2HDC9+LsdKsV<~3+P#lvSzVpFsi z3ItTa-wLmbv)~P`*Rel)^7Fn7BakSm-x#&pSW9YIS9zYtEz}|t%-XWB`Slnipi2A= z4zx2N2Wo1u`y*R17=grt*Im)>i}%z6o|^ME&W0M3ilarc`Jx^I0afrB%IF31bFGzZ; z+4w1$Zu1%-5Ksl{L-I;f=Pe1btWKY-MMC9BNQiY?~C zECqiv#_*2eZ$-a<<7tNOO!uda3?q;btG7Nbl zb$^=-Bandou}by(u@>=cOxWFOw*>;K;2pzz>f8pT@L*%s4e2r%fduTqdB5ANIT`5q zQy%)Hu|Pl-ykj_Vq!W4nM3@lAOZVh{;M@~B!fJD(~vpF0s&Ppub21KA3VwH#1yL6;DZb!kbpfnpUXHl zg$&$dM28$L5eTS)`N=BP$E%^_@tM8q{6DLNJY-0~9$ckbP@m_pyib*m4u}>AsDia+ zcpZ983^||K6^#y8$uI&5v2x2wTVC%~r!%_uFo{9}s$gvym15tYB2?*x zc~Wqef@cnx@4(aUx-#!mH-vdONWh#al}bJK6duUNu<4F@0s&QUPL96`*L{y8H;-b| zESF;#fdtHe;`h}peS!y%V72qw2?SKZIXPa-+n^m$J?q0R`0bTo1QIXoGG5y_a=x~)U=dyXD$;6sDg8HJlk-?EYje4f0}s^FZQO7*B&6xr=ph_)7XkYNN8Vs)5pZK6nBVu%BJ>Iwu@!5YSV zB%_*#Yq(Bl>Dwpa7Wtzj)!t;u3)4j`n4%lQJ-j zzpY3Q_hSM9RgIcDOMgOwsF|NqpF!_oTRiW_Or{qx62CffUF~O` zO1E1NL+}WPxnET$+)kwXyhAuKX7&hdJ~x<|e@enI0ttAueAn+V}JN^^dBlR5&Bajf!jl?PJrR@!YfGYSs@%ju!Rw(E9G`76`LE-y=#JCF?x${0J(Vg{z zc^h{#x1;A@XR;G1aRLEV@b2MbpXjz|(D6w2<=bH4zJkP?%NeM(%@%G-_4epA)$yUT9ZS3zm2ala4ea_i8{_8vbWLdcyynIoX=7 zT9Sv_?C&qd=GxG(qFtQuy43+U4sFe}Cff-$`+q-MEFGU}N%6D2Lj8VT5vYDItoNoB zt7vUUVAeGxPMXe@+KwpJynk|uw_$MdC(<=-&DNjoD-cixbE|m`p}pnO+2_64p(j@4 z$gzxElPkk$;PqSt@5KxAQjkd{00Iu9!)_76e8h0q;v$Vu_S)dKt%tBa^-T$kKmz`{cqPwgN!X~316%a9ra(Yd zv;M232bn%}Pu=;vji2Y%;gnD}mT>JJh7m}>zDuQgy5bamV(-do_BkOCP!%$~P@0<- zKwlY!^ES}-8+g@14`vp#2*U^@MAwB+b3Wpx{ajgsI!Pd)3i?9u9nv$j$joF%_Rwkt zh7sr_0o&#~KGHXt#$=%RFGh${^|ynvs_Mdzy+4{>1Yn%)-(sDjs! z&tG*sh!@wgXTw|9BrpPrXAPH2+x8Ekb{n&K8xD!{u<@3@Y^sf^KtL6|7x?=5ripmr z&t9zM%MQYK4hiu$s19k2V}g3H?_OO60;=FWtx~nt--$ML?ZkoysD*nM67V$t}VMj#2}1>`*)QXwY4O zfGXG%@s)-{k8z_FHf%?>4uKI!nC?F-4f$nD_x|3%+b}8A;DbiCtmg=0fq*L56Y()a z)799vz=}0^)sDajB;d21e;?nc<7-Y`n8!vdfq*L56Y-2Kdo>P~+cAS2HGvUGK*u1y zLm|8f?aXP%A`cOPfGRk`QK^dWNT^^yYnF7yUKsm80{YEx$Ej6q$>mb8Vm-E3boGN64+_Vo033?q=3ai<>o zJjjS#9#60abH~K13oaj|?4!`Yh&R$MxFAz}GE$pOpBH4`geZ8L(U5@R+WtUp9I9@#hMj+Ai z{WGb7Ub-ga!3|CnOIqp1#*bMTuCmdGj6K z#-`S{@lmt(te10h0wa)syDs<~8BWHpJ9K3=$9E)f&j&nPk#GuHi5u6pWPVLM3p@27 z0k0b$C$ghB|7Lsk!mhnQKovY%KJT+Y#t*bwGyI^Va2}9=-#=fQ(7J=)Ol{6;9&9HN zPzA3#AGf#rh#$>u%9iPgR~HiSKIZ#BENT-xtr7bfYa)CfPzCP=zEa(^38{0s5lb4Q zE!-uLfWJpRd%mze`Rw1BeaqW`g(m>`&BI=sj{q`Tkyyu$Y;K1W7)D?(0e{UZ)u{=_ z``ioKtL7jwfSz2cRJ+KhfeI&W-S6Ekbu8`UU6~U3!E2X#pEU2&jdVKpbGZd zyh2l_)A;Pq4(#%&)&xc%0e}B0RZiV({7cV*^;y+PAfO8N+A3ALbs8SklJ{`ktO<-j z0{;H_-0LV$Jieke+Y}@T1XRIyL!Kw2a>2t^nlrmRiNFXX;BSTRP|$6TcfD!LGQRSc zM({QYRpLA6+fC+}_Ugv6BCKtPqaH{)8@?)YKNQEZ~Up0KkR640HE=fllwj+1(M zvMcvqV)$851@|{_9}~Mi_(Jhy*2wY0B@ zI527|TiGcA!w4i`_8yook-#z3EjAB%lheX7M>>dt;(~-GQ~gS5t-&NWknp{$6|El&n3|pIJW-76_<< zt66;4*5-~R-mD!PvulqGBandEd%RCP+L3%SY0MVhyD1P*1@jL0s{Ug&**yG>oZk1B z;JgS4SZzh6YSqA&tbI`;Z}X_d;AcS<%sb#ugHuDv;Wb(E<950XMj!!eD)2S0d85de z-!5`MKW%}4Dwub`_d&MuA)jmBqQ)2Q$uI&5SW|(o8!&&8+{%Y`ustsjPzCc2_$=q) z8RTN^VbZGh%VZdV1gxo`Qe|?VxK+JcqE`!M2?SKZyaWFH$d4uwopz&l>uSm{0tvC6 z{;iw5`bEtm)PK!Jp~^p0L5Bf8bJx|JtZ3hlZE3j|LBBKT6DazUjhk&j9JflWmvOn^ zG6o4)|BUAdpS2*>8r!nqMQt(sEU1F>4=UB*n^xqIZ#On@M1SFZ5E8HgE`LV3b|L|j zyRj8@Lj(e<;K+b`99r}si96#_mvR~H3 zp?_0mtJy5Pe?S7(cjB%jzq*l6b(*kY{h2^Ol{og$Ml7+x8-ai-aYRNMbtZ?hYcq$XUonh80@iWkbI6~X6W8x`+54^f!Wa&!;256! z%EYxIsb2c*fJbctBandg==jbTsXp;tZ_LilF%}4@f@63-X3&@t^2CT~albeifds6p z$1_s0>XRP78nGrT>Iwu@!Acn1kNkW*TP53qHDG z7=Z+=O~>Cq9?T>+myVZzWSI#BRKcoKd`-Ak40*fkA>A~iSg5BD3Fzp`@7*`tCFbdL z>gO_FAfO6X|L4D`TLx5F!5YO^uzm&qTd8UumXW*s-nyJ3buvszI zoAz%_Xc4FXy9U+AxF~-)U%OjXxpr3=-A9f()R~=RJ(TQE&2;VpoWWgydA_J-`#(Qn z&C)7A;p>ea)9c)m{@9$O%AQfp)4%&q>&q)Ou7CIK@?EW(BUSr^o9KPX*V{3SwL8&> zm@fFY9~|yQ=6h}PyKVokpYXMya5kh-Llkc?LtYb-Lhtj+`@a>}w5SK&&Ud@m@ZBzc9TB}%wYz4YTP(ZTa4)(Zxr~NcrqNILmP!^w$KbUa zQ|W`tTczh~+%Y^_{v6yE!8GoRX-m`5_``=d`pYO?dYrx#^`03|C+$v@{v27P)W)Uf zc?JHA$_o6NgSO0VdMCE0#z|D|)hODOyH;sg>Y{5U{b@(zewBaoX9@l1css63k*wX{ zj~#WGgS1P^G;c>oSE^2pyP=t?j<5Wi&lGF^>l4Xqf8JOt->(_U%DxXle-7qpR$oo5 zRAnB{(QK)gT=_Sj_tpH@k&%xR#~RT_xp8cEXEVX$uJxRM-gkV4HUFQdp691`vX9;- zs{huLrCv}`#lx-Ht7iDPqju%rn}aGn!|1KN>3==LHtmXLqwNEvXWLpUIV{xwuZPpu zb*Yuap#4txwoiKH-`$K9w;R_^Q&@TGSIu;`6)@G9^sH&)}BZ$%A_zWr}G zb7FMmXN5^b@$jN6{`!PX=sd0R{}D?S51!aUSGF8C(9GUdlfeii?BaYYi3jn@9xT11 zR&4Kp*BYOCHf)@_du1edTsz#@YCz@R4n>xj=ikxPzn*A3&vJw{d*^yx6S1J1;+9qw zfrPf*;7S^$cI0hjF2?L@%xTTXA`5|lD(70`DhUs#Zk(9f(15jG9YCL*7|E{dG_H&| z7q!BvU;p!W!LL?|hcw+<~n#*0&EB_XMgXWPhsB_;~HnrlK1XZieKI9Md|Nn>y150R& z=vda`Y?0#CSoM2`L}u!p{K2vRq4^f9oVm2OQyjC3Jtq)Q1zj=u?D>>%xmJg8mab`n z4y{|NX=svCdF*RHr)YW^%&GjFuLx=WIjjz9FjbDb8_tTu8Y(M4RS`&(4^Gsq9sD1f zS3;QYD?e-*!4_XN6$q$G?j5I@nDAes_OXfb)H%FLL69+m5yR*pO~sr4@2Iv$kCy$~ zN3t2)E4@ssjtUY<{QLhfGqv)ZcrDiU_VUHXQEab?zHn4f#fP^l0*NEf zv}ncBu)jx@aOb`Jd!HxU-)N&iKvlT`+JwaZ4~;qW~++&u??&C z2n1BUkFcT5HpPmiaP3Z#CYcqvL%4U_3W$xo?V5@eOfAc!q^q)ibA^$;a znbeeR7+mSMT@`^uH5WI!Xn*IwZ3L$GXX9?RU<M5VDH5lGxkj;AfJ zU$3Njc3W#-meb&}+{II+I8;;-P{k|P(|@k)8%9rIlQhM0*7B2z$9h!+61zQOXjZ|~ zzis52db60OkL7PGPYVQ8v7S#qsv?lk=fBwRKivKvRqHbD-nzqCp4v4F!N}F9 zIh2)0|37Vv+#b%Bt(h$Q)LA980f{LdDb#Yng1>F}@0`JI&CQU{4tXRHPzA3#-y!`y zn2o7eFCRL+PxuBQvAJ^+-4(F&ZyOzMOk>~t^5j=WM+5?@;N8Rb8yw^#zR?MqEB$&Q zr$gz~?Wfu{n7ds2S!K|=?&o_e_n2qx3~GT%zVbJpnV1>Nc3odbxBgx&5KslLI?v>I z62ms_c}VYMB@1T`36HpRdatPDZyWQnqgmK{6ZuADra(Xyycf97&(3I8a4wy0tZjm~ zRHV|M$A+o(=c`fjoHV*czoEKaNjJnjP3S)tC8yuf%yHKo`np;j#S^J20*UgwY4p9$ zC)?v^6c?qCDN$^ib~X9WaRY&XD)G!8)s1CV^^@t${9@reAW?T#I^8xk-L^uvId9{R zdo0VCpGY&iFoA$7_&xE8)?K675S{sSOnwXD%;7n4KNkAW)#}XEaF#qlORnxW1j7g< zxO)h#%U!hexQiCwMfWa}rCZOZ-gA&ZK-I0(IrL^>t~&d&DMOE=4uKQXSu3R;x!;jqFBJ}In+Z_>0VbAfyB3dAv7%KowQ@@ zG2X_i4iW4_$rHMCtb=e=P{r%%(;eJvZzlKJQ>iLWM6!u5Q|NZuSE;986@i4q)^M6N z^q8cFcW`1xw@B8Qk87r{tMqWIBA{xYNgQ=x^Q8{8mUH5fbu6nc$5Wke7f`E7lc~Y5 zUTAH?chu+CWIAz0SJZRlC&e?6E-|c*v@R-@ZhsravN^jFXtzDwZ4X2salmZ~9euqs zT5qpZlv}zgigjH7ls5iqqPP`QeHK)SS9bx4VTGm>h(bMec^d_f;@FqM zJWclZ%^F@gkoJ;0qc8IeG0XF&U2?{uVY3?HtY+SH_-%J|+fu1!)&6lDYnOOKGhw2) z21c}-c+=hb?x<6OF@~SSSK{u)vEEVIbe&`Kd>Da*)-NyWH{1ygPFCt=%+|!Rh^v%N zQyVHZ;;W7ds^B^C-TkR?OuJ5BYF^7snTM;oCXh%o_on??I3Ocar5;(efH<~zh!YJM z+DjmyO1xG*Z^y9>cLFsN^L}XH^?^tDv8N9m^urUC*(?6%%_haM_qAu!Cc9p1U<4Ap zb|c-C-4hj9Dem&IYvNdkiKRB9Vmv7%pi0kdGR?a(3AMb|f)l4(#3J%U*T4D;>_*Ltz9G<>P&6 zlC2M#*QY%vT&~5kvJ)zFw*CXUc|M5`F4KV}WG;dNzU1QLtW1L)}_Z#3to;$NF{Fown7*db-z5RVF~;5n&O=dZ@F ze%2A_^ukw)M{d4TLrz zp?_osjkOz%4!uy^noq5bVl!XlqIOT(3j|cbb5g0?jzzJkzVA@M;W|oH;Hql^iO|+F z=n_9y?#!;VvGhz7d!Z>uw|y$B0#^}GC0?tqW24x^eYNoBQ@S#|KJaXBcZ#975Tk9y zgLoTKwq-A;xPNId%zNxdwaqt717Q7!Bm#abRW!~^YX2n1B!9TP*nJ7Y9L zYcMBX?TuoAyX#@ckL7fB+XT94c55^u+X=h%oJ}tTS)wg(9TcB(+Kl^@-{(H%yv|)p z6w?}4AOEzgQ0gsJMIbRJFP<)xyPyDVWhS*{+bDLmYbmO}ueDOssfvIqc!b>9VOkX1 z^s^pznDvXo2qYq(#M0xtd!sw4idX#0K2gknpCK;dJMSR@RpOaXcpk;x1lPqowVnuP z4v(<=;{@t4tSQ=D;mq4eni<8q&U%3I>Nb&K1QI4o66n?{clqYLy2fS?eZ2YXEeZ*! znztsAn$#nXh!gaJ_~9 zYM)25wrM}np_pTeheFj#3?!loljsfeTFANSDBgzN*CQwPix@zUh+o(M$hOIsO0vSx( zBM?vpzgeDh$DilDuZ5$5v8i-*|8zQb7LnNcvG~l-G^$FTAn6Yqi}{{mn!a#=bdSFW z@zK(iST=lbI`{Lmdp*Z^r*f(dP5lR+c+{P&EF z9(a8344QDhzHKx9x44dT>0%tC5uuXN9}@~AkcjM%LBIN&s!5gyZ)5%8SQh(evGl{} zoIpU8xGM9}CyssAdm`PJ;+6f*RjW&oID9Le{xG?!-r8SjW5wV&wsAl+G;(QzKtR>V zP3hFc)kHF^rw~6T`!b(@o|Cjb_xfzYy*{}gB>k@gE%!d8gQ~n`xf?C}uNy6lK!ST5 z(tnP(?G8Gz{Z9>)g!Oyf!(q zW!G!7*Gwe=+^%?`(g>kxeqyW@FtJDXxfB z1XOWPMQU2*iyYWy7<)9nI@>-whZFxIkl1qHf&TM%uJ_cL-3Y9ZuRh)^5KzUvA?d3s zf9K5O4(!yO3c0OxKyhoXia>(;cUX2Cvw@yqXGd{+{29?{p&5w z*Ksa*vVd!s)8J%Cj-Tq5^(Pf^@~t0Iu#4y#r7v`Y1PuonwId{ge` zgA||9s`*`bPU4*9;yfSL9i5SlmbeIW$dG{N$8&41O=s%^SIb?eb`}Vz5@*%sjSc3z zcQR%BM*S4W^s4z?NWk-}bW&!Dlk#5fqznnDg0o-z$+<3=IVFV2S1?t?V%@7Evf^%p5 z8w?C$U;W+WKkL$kIWkDV*&Uu0Hf9!E-{cLoNDUAOsDgP8ywcRC2v)H)owoipT*!cc zggEcBsJ0!O*S#&<=B2`LEd^#hz`lz+FD_QI+r8VfV^%#CztpN#8A$NlIQq|zK6Z^A z+uNcAW1%Aj0;*u&rBYe!l~`1K3l`OWHii*M@Z321&yW7|u)eIpB2(7+_dJ1sD%f}N z`Surt#db1bhqkQ8Faiml8%Gt_P}54+&_|>Dv)`BXS^nc(fq*L5cd1m>NA+QQ#_F?# zuSYSAK!WGSQN_!&ywb~b!c%*;+ORs?QF2lspbGYOeAm_pi79@mS^x1%t?Dfy!E@uN zJNINYuJmNBpU|J}S5?SkFWyxAQmY845_{2g{cM?GL3^g<)E9I28LCpJNb}9=V(t@1 z&A2Px4epA^9YbjPr-9P6ciQ~v9C~dK%PVTYN>AGe5lC>)4tk$E(WET{j-07QfHS!Vuu5hB zx(hoIQG=a~t41IJRXkUbj^tjyVU=FLOX?E#`141(_Pf^@Mj*j`W~njv6RuO~Cp<5u z7hCk_w>)UyPl13cc*pQn%XRk5&b&HY{amGTOH~9CMGM{N zWL~9tWo4D-kOsq9#C09^k^~C`RPjnN^q-$s+r1vF&d8^7@~IHTovSJWiAzqSs6Kb+ zB9-o31`Qq9H+xey<-r@p0j!FED(>J!b-ByfuS%D(Cpu%8!|iJ9@)sQ$Mj*lcnCL&x zFx~J0Y{;&bEJNQ!f&^5-Uo+noZ{osYF4SS`Kd#ll2qd^O6xDDC$dNg2=fGS?)idIxP#ms~2MIgazVbOtA^%F;)_htz* zuhWFc2Xf7rSlaw=4MUjsc+7D!9mne@zNxIA7}$0+Ti_Tdw-5O(!w4i`1|^^I(jCfz z2Q88}AFRnB0abi=1ie*N2lDxt8SK&Fe053Aa-~vX)f*%{LS74teyggVm~Z6IKG?a@ z_Gy=tYKT=4NWiwa@6y&uY=ZAry1aXtKtL6*=|%0T>Ofw;HG=h?(MNvxSdYO7B*gRB z$1785*PSL?3^x%7s1m=Aoo%PGo7;BMoCo=Atx0Qu$SODclpzp!SRQ5rrsVIMj&C(GL-({wbdgkYpd_O;?HU=7$&>xdgFQLK;rz6X>?Lm#rHZ+fjsLhR(3F5CJ;~sdkJ1)<5Vz#N*O+j7kUMtABi0 zM|G)e;jM)r0ab8}!uK1@p2jx4IU-*V=`O(tB-YLtL!H{zMxI-g)jrSgiELuY3mLoX zDsE|2<0zkDtgA*vkl;ROv^RI14z6^a9$G$ztxS0#+uVy& ze5$JmsDfh@UI}`EH|wKwMlSi}tLz@A8WlleU#TlC=U&*IE4{D_-j8PKGw#Vpt+xmS zRKYO{_s1#sWF@jJ&-=I>!w4k!-UI4$I!m%UsyLInL0}nfAx_~+T4*~1QKv1me)2M9L9dHnj;$yzpuENSKXsf1;2llYNJU6GiW+WPCHhF zU<49yJz8-L31)SAr^}jZ{V*h;3V#3G#kI{$cFt*xJbzAC3?q<$IRShh%gbr3#>Qkh z_IR{FKo$J{d1dY^p)4$Alw7gQ8^Z`B#GHwmv!}B0>tp4!(ep$Cc3}$r~ zJIML_6ETdy&xJDxD%G}?f$YQ92>DgWGJ$|9c*m$z*W&`&lBMx-zt@W~j6ed;gs4c4qWNWd93p0U+uH2d!PNq#eYjzB;aoRj7Ceg2GLu7lspIX-Kc5JVu64vII88l=q`scqe&-@Iy74?j9wuD*DUyGX;3)pe1DPD z{ARd7KouNo^SYdcG3;bfOH{J?x3G=_32`-Jhe;fJ+|2`xj!qT`sDf)qd>_lOFt)Q{ zp?YM*SX-hlvnYH3}@aiTcgI`LKGj9s!=f{;3^=WPrMz*Sjf4f(+|uO2&jVN zQoiqQLpXcC))+1P5G2D0B;dL#uK}@YCTqWVp5|-wG=YFBI4#C73B;a~I&m%h*&dP?a zrUetd6=&-z0;=G+RHbThGm^<4?`wQE4Uu645-@8)r5aK4e}tU{bQDR~h6i^Eu0awK zLhuBgt}fi&g3AUcxC8C&#MzFl2+lz4gPrM5UukqA`bx|DW*J{~Pv#EjP(HYlN^1qs|aVzZU(6(Sb@QB?P6 zkxn8|h3is!Dq1&2cq~7wh41{Sp#=%tKSR4LN`{DLvl{574pDu<+8I^2may4;PLB~e zLNn>xJ1)@Bf&}hiB4XGW5mmuMpI1zg2vp&UgVxk)nD{!!TMP7vG~)0k?*2jocXH7? z;pi|CGI70q-o;>vK$W~JY}QWNwG&=hXlY9sCjvQY-+q!%y!cB-=ZrYceHh_baPBUn z^En(VZbih`>HVEnWY5|^)ozceEW$IE;b=jE&K7ah8JX6x_o%TmGxlUNZF>q|(IS&- zoJNv(-8)fnYm;r??pTrf3X_TTQw}*C*?dLvcB*lyMn)*uA zAxGcf(!x!(O9ZM4$HlE(uLqcrY)(e&?nD>2vmf{GR-=yYrCYNc29>C22by!Ec_&^>lF6jfUO zkO)+D^GvI`-%MriSLPd)eAwpPj`*upM1gc>B;|ydu^SUS+J9mghcDs{-Cvk46;%JCU9%5jDb!ySd9dx_u{S0xJ)6yq>q zabgtL+%5BKM>7rI898Y6DJC@MvurI;@cBerNsiY;22 zBGdkgEt`K`6K#5`F(QLnQnDZ+r{PyE!BK@GS{3>*Pa;r-F&t^v{f4iOglt1amD@|D z=#EHWnP|OR{YOH-OZ`QbE}BH33S&!CT(W?l33+n#6_0D2mSRXFfi+FvB1cr!6t%x7 z_+HmB?hZ!q!7sq+J!fsZHZ%EfQFGD^i9i)bceUBdcO9)2UYty%@b4%VQ$$!-EL@By zOR>Eid)MBpdiJaFRb%hD$#tcZL%(pcpAn5V(Sihi6KS)Z&e&65c|KAf)NGJMpbEd* zq!al2jMdds1@yC5he_XaA|ZdBIeGU~eNCklIvYP!B2a~2gVL#|D+fD5#uwAw7LE}Q zC|a-a)#p5lZYts)*mKq}qPQOad`4Tmq@n2kHji|!0jltf1KNSD_R{*$%l0#EN*K|a6Hh-tLXLx# zcT=GDqZoa;tg8}%DvY84$Qr7c0v(mk3l*95gs*!hdb3zVO>Iz3cwp1X_@g z@AGt1SLg@U&C?4F?kN$dqPTsIkdFaX-MSW_UQ$%qu8;kaR(IRm--yDOXhA~$(z_tV z3L9SeZ|!hIKZ!td|Zd(sA(ipe*hhE}t2a&vfO1;?Z+}fP|6_tDq@~BnHxhwcdzKnrJ~{aKFQj5qF2!oA)qQ89hdGJ@vdU zB6sD75`ii@q0O;%TZ*b%&KN71bLIT#oQYN<&^qlc(Sii7AL(oI_sR77^BRec1n z!zB`^TK-!dN6KSG6T*Cc&`Kt}^lfeE*&3q54iAnNByjymGfs*?t=BLvZnyK12vnuY zb~tfOM0>W2rPWHtR}gda`*XA)A+Id+?$7P0lCz?4d*vq)sKT|D%~nM#uZLwDE=IoS zr{YN}c*06Vhck|T?5TZ=!-yN6s$n-hI?X6?oX=)xL4x9AIl>a7fIn)rOmDVsu=w8U zqJ{*jC@PUQj3Q^1G9zb=UA#))kfWctG&jhIK9p!dqRgO+j^2r}$!CAk^>S%CijE(4 zNCc`VK9<&lB8~SlBaK(yuvt$CpqQ2eZyB++5-mtjtUX7e#7N^We2?e}A63y>q&H%1 zB@(Ej$a$L9INsiIq;U@xyK`C}>z+&09Ox$~YNS@%8HW>96!p<@-x=AQP6dAcyS|X( zpP#1q=V(C!)3e#O2TawyrqmZ*mu8d*R8ho2$193vKG2M2eke3rx7F$-ZhpOL#2-ww zAc3_&U$RcTa!H7 zh3n|~C>DfQ@*WxzsG>OBj%*ac{(u?5erGSH@4g)(rca&2(1HZ^N;*6G@0av#V6a%) zFvy4ko_H-(QPgpV@ADz{3#pAKujwJXw7CKOMMQYKiWVf~Q-?g~G}Ml!`AwWn`${5E zC7(LfSIwho>BfkXUCZb=TjCm5o;jPHUr&L72MW)?Ek=~e#5olST(3|$W);yZ@9ZEB z*BLx7OcA+r`1>#f%uBi54Vqek9*3o2L7#1x1HlibSA_ z;+i_rJ#3Ij7(Ej?||e>LL-Sq8PAnzR&pIF6epO z-)r$NdJ424A9721(rBgLay-6aB5c;C>Dt?ehZh~QAMQad5tgGk_Nkj}vNN~5pX z5h^}S-{rt-p$hMRI^|}{M=e#d(c+1BA!#f@0`CHPn^Dq3uW)>jm>f4>B2a}RAAQ3c zT1gM;+C}8t{8$>{kiffuPV2cEu79swPei_S6L>9D;RsH#mmeTr4*kQ6R?>`v*TuVlzV1(M6ZZXG^t+L5 zBmz}5MMqE~94PM)w|=x2Oo+U`a{Q84h4zBNTLBT8kW z1qq51sO6&AvLnpcvR*lJi7egHiB6sJO9ZMYlA%_dqHPv7qivSDTUhLAlTq}moymw; zm}o(wZkaM#)4#cr+tK1i!RB;@w^vhs!QzmU9~OOHwfs&I`; zefQ8az0%dG$uBjuctpaRGgSG zN?L^@aq9V>jz>o>+C#e;U##yP&|0767%F}g>7nAaP=!wb-~g zvlQ{Ugx)BwpXksk)f1UU7LuMnkiglF-XfnUr2XyHKs4Q7Kq63u&sR3vzFkeVc2TWG zv!xlO=O~Gg&Vh_wu~~bQwzWvvKqhcShEIJqTdA^FwGmIcif+HXG*16cd>%wXuB%Vm zJax}{-9_?wmn8yK_`FNc=V==1k#zcZdpi9aEl6P7(CMwErt97Q7$|Z-Zy^z=!sm91 zg*|_(exNYzqI=(1dZI@Hdkl>XDIV%UGk+8HqrYf)EmWa5f&5orlZg(~n~9#ir%HYX zB(Ue(Y*Q8$6)hh4h;4OFNCc|zEKNE;ajmZqsdI>m-(E zZ}+L7aWZ$}ZdD|3zM|Tl=TE!USLy2)6_E&3;f?}Y!X#7rPekgGS^OjdRk#zF{8wvy#Jd9Z^@Yi*NPC2lz}bg(S>&xDPAxpBwJ2IlB2b0< zlWn$3>+6ZM3sY;gb$4m!G7|C`jXBn|5bpWB9eaklNd&6?b=D+v6Xm-3i$;~NN?$=t z%b8zmo#vrEyKge-3k-Va^)!Q6-=Ufq)=-lyNQBIC*IMkYrZm)zC&=O-@{7g~RPm{J ztVEy+cbMC3FPi2N^>5b^z4En`zcGR9QVdwlEu@2@rOHfcJeut-s+8d3{j1juuZ1ey z_inT8%H$yqOsOSSKAOzXf<*ERo?6!1{glP!vr!ry*On8FD^(VoyB>ESfhyd;PaffY zB}Ku@b`jBHrL?mjiNM0%+KS|Zm9oA@#Pqi9ILEhn!P?%oO(|E0-z4a}DT-^8>BUvFAR(7y%9soKKjB@)oa`ed z0#y_h(P6}Dd}_vOtg`*N!xahBYs9aZteZy0t<6PIG5b+e%$J`IC6r8zgju57bH`nZ z^f!kh{hxJ4@XB1boAVEvDvD6!I7o3#8O1fV*}B!T>%%B6S!Rk$h883!ewd?~l22>8!$CyZGfZ#z zw}(i$uSx`}DBg_2hoYapHlv@$UvkrDt}ZO{eyC|gqDizML2*M*fwTNR?QWY6)i|$52f$uufNx3hE)^+56c?SffM@= zs<3Uy>zrY;w#FF=6D>%{y}i%iGur1K#f4`^GqPM_|3MYD4ehx*t!RB>yhN#NHH;X! ziM;`dDr4f-o~LNL!4z$m;^UOutYysNAsYD9k_c2`+fYyJTu`f0vZyF}skRX#H?cP$ zaU?8mZRYdYwOb#J6Xjw93u*&=3W>V4>PZBuur=vys(nxN%XfbhyW1~gc-kzUXpZOE z67l}7-r!!KI34r1bZ#vYI9A$h)t|oCw@&CNvVJXXMB7X}8y8g+t5bX6+ea(@$vCO- ze#|p{Udqm*>B|~Mq}W6Y5;(fjY|u2B$hx?Nm_0sHB2Y!K8XfDVcF>v(3!yZYgnZO* zENdwuy=EJc7ZWW=$m8zNPsv2r!gWN~(+4C1RnKpIa~RPb?fs4Djt4?AiAir;iaiVd zU{~VuYkqz`%@b7dOks+Os`Y-~P0MlDhlnR{(ui&S+lX2vQy9@t6D>$!9nya4+F3;9 zlug9iWep?(RTS@1^GVfK%W%B~rLoj2gZR0msc15;lM&Z4(Siily3O`*T~1LlcTI7h zBHto`DvF7w{feF0XKYpx7FSEmud~pIeU@lJ0&AUi#0TdRKY1nLmF|E<#B z#6pVt<)}rG2`^D(LW+>*$WM_F2U8?Oia6%5P1x=zZN@mf@3T^OpI=m@clS499410OD%OAZlL%B%>6i*l}NKkAyN5jMz zpn=8K>*p$$5vjX+Nd&4W(kJb{a78&zK7ErOwU&v2jvPir&qNCn6ffCf#HrqD#;Ilv zXX$PCHxO0kq>~6#QOs(`KXm?9zCM$wC${pOtT#&4QS=MCuA&7Aie~Sq`zTx+l64pn zQwF!t(-ftz^~O3R0#y{pJz@OS3EGbCLx_kk;;YX;GgNe#INpfLo@haWBGV@HsT8Aa ztkj5zwevS>Jzk6wv4a{(1ge7j{wpfG*4-JE9W6*a?SoO-x1B01s{g1hava*i@I38) zd3>~=&pMi;1fJMUqv*11vsaEu|Mk-L~1P)EeRO>IO`N<94=RTM=@ z3#`;ko9tzrrfd5>k9hs1z9@P*mk|>w(SihyO0?_#X%W%(BNJsq0wn@f6h%pM#pI80an9jx0}SBGWe}K%k1EC~2-(t#l4cZVyqUzQ2ec zuuMgZM8K#-kv5`=i{L;&8tr{A5vZbAN!lBVajH>_Q`$%NEvK-@xQmYGQyDRl5-mu`L+rziy9jW8Zkf$!nP^`|i645m5`{%*uuPzeVq7{>B}UaP@FkgOTd0JXMDe50 zf&|VCbVn_Fqqn2e5b7LEDG{imn9PoI6py~28IQiB*BiakfZF0=jcY1ekihkW&368e zi~6B?Eyc+?2P6VjvokDqXdOms_udVsUb4C45k2GguA;)UDJoi!z^6&_kzHS=$9n{c z-#+$`2vku-aEEPsq~`v~7!x<2i`E-^4HN#E+*Gt6fzRsXxjU=sQ)`8Yt`(0lBv6I1 zE^M~!k;U{oZO4eu-K!Z!SEO-_ zqJyI|rfsuPG;_^}X8zoYW}cWUBygO!+5U`J5}k9Elg30OaK%Yp&Y|n|_-4Lhaq|)q zfhruqjrW5q^7-v~{>wE76ihJj;NCc{IHAuTA4|3geVGB{cZ#s?^B+ws3aefw! z(pT=REkv1I5`ijQ)za*IakPGCd<{j(2M%i?3T{lr(Sii- znx*g6@=el5X6-2KPp(Vf{GbZIP@+>jM$Oj;ALt>PtX?gBiG&31{-wEg_+R?uH$BAV zO_d}9RruW$t$l92(Ss*-6DKMiQP6?}?qa4VuU7tIWZrUD^*0S?zu=JP=)8X zQAB9wCyF)l5c#UCQqh70K9`U;ic0jzN*WUQ^g_E6=4KPFD6V)dRN*ObHe16~KlIqhVxstw92_l3;2dnTU2Ty@EKXNk z{5+9PB2a~=+0i@UV-NK_3WVj;_~u$Dq4`hFC1xa?b5e;hQbYm+nS>ifhv64OQ%L0c&s;n(?YED+N`1l3H;o^sqJi9nTnj+dKHJCQlfWPSV8 zN76Z7NZ=W3hfAlJBO#wNakhD=D7!6+WuBTsB2a~~bLq)z z^;ofC;XF1bcA6Ab7YX@@@n%Yg){a8HPw23nB7dXovPD~#xg zwICB{kqC$;`o9T$+c&dJ4$b{izyGLRRH29de-mgy0^cFXxk3U}f37Q~W&NYwf8+`+ zNZ?xzISq{5dg4j2W8Yyb?kmP;l?k*U@o-61$Bl;nbq^weD)bb}X`ls(|9zh$fhySp z`74!hjus?vT=}IpMh2`!jLC|%E)!@$0%O4bZvs_I=T*_xY-#!*ZH^Ws@YzsK0|`{U ze_Km4{%6It{KbTG>?If}7~B7s-l!|IAc4_{|2KiE|2?ar1qqCiET@44s&Gb?39KKC zNB_U;3N1+Bx$bfrNTABN$BiD8v^~&*1jgi*(?AQx`o$~B1X_^52ps>LK$S6q8e>_~ za%?^st3}M)Z8t2BI>&0G#(y$@f3Fa$RXvbaNlKsviK}&EwVUqA{vQHWhq_PH8hxwq z9|T6cHAXaJ1Tu1BjEzRWPMWJZHRH4|i}QLImbo5rTF2WqvmEn^#c4N1Mf0~@S7ND5rrIBre6rYI_#N|3?}~pbBeRP6HzwA6_4>;)uvy9b2(ln4jm3)@ouT;W0T9EkPy&VZuVU+7%DHx+D zT9ClIOD3>AFtRn)v`nA{2{|tEFD9HLfhuFIYpm&#)-GC*z&OmmQZP!61geZ@9b<)_ zG!3*MfzhGmG>|~m|Gv-Bf&@mnmeW82RXE1T1X?gcH;zOyffgj>h|s^7aE=73jOR4t z87pb+q6GaHPqXm&bmHE6$&z(urKnoHW7h6sP2~^>DEE8x!0^@uCZvs^~YTInL zzl8Do|8!9dmd1AG8uf!}#L18W-2por{c4c$Gd*d;R)2rExespIGYN$jnvFbp^Ed4STZUZ;mU@m8|(Y zfYu~^54K}g3$ELcPu&06&?HyyR0oql3ljDG-aC|l5N8W|6t$5jwNnxTRXg^l*R*ki&Gx4q@hP9`|7;I53A7;L zz3PqQ&}~;5O%^@Z3#U#>psGmk?~eKpg4sao3pU%9ZFBX#PtZfYpv~-y@iB@A*XJid?B5ojb%N(1JwjCwm<2YffM*YOObjnY;Dh zeFvJv?I!me7wU~QTgv(LV)j0#C&bx;*$XA;fei+j1X})!uzHC{gGaipd-o)Si#Ajl zmZZ^=*Bk0gV_%n)VwAhpf@nbkdknpU?2t};PSe&*0|`_mKa@_hWf|h^?OSeU5vxQ? zlRyg+@?E>FRVuN6V*4Zns=hqQp#8i!$a$ZKr}$l;6KvHk);qR`@VV*m>lfziS7-Of z>$f^uwTl*s_;|wcVcR&iB!5Y2!Jgg!)W`1WYvu|G0ji;c-Z;K(4PmtcTm6eb3lgp? z86y!z+dO(+|1(=3GYyGw=G{)_tXyjuwCYtF{ zywndxIE|u72vpJN%4nq4tdTlid!rWL*v%y9o={x=Pa26BjZvC0U(qU`xxA|ME!n*k zykegYCV>_tXsl#3+nF?d$8tC|ue-Kg5&~89Ov{W_xit^=EPq)QnR}ZAwVFb`+PoI^ z7=?PDX7oPHEk)Fsct`zm&YI8Bf<&?2-<5g~g0+$6n0RvGbG3Tvz$7I{6_&|n+p%q~ zx@X)llb}&lp;6Ra8(ev|N1;(vd%eLNMHL!FHER^j8M#tDHg||g&?uT{LE^{bJxYg~ z6SM{9C`x@-rM@eb+~`Zx6BX*OW;;`#R*bc<)k~=Fs?>K)0xd|4YBN!}^hcCd*zCKs z%HXuhFbNuQ7_BBWV-CkY=K5`|GH5>MG@qLUT3o-4oXGu()(o813`q!7(OQDhTEa}5 zR=FvDS80SZ39J*WE9?uj2XcSBdb8sIlR%3^d_1Ah2&W~Ea4L;(NeCLR5>?n^%rP;M zKnoJCv=c`-l}0!-4T*5}W9JB`(ERAUYiWd2X@oNg8sQQxcwKB+bFNisu1!Lq%5@i5 zxuUsNrMcE5(DGk|)vsu-RcWqGLbzx{Me`%0xzx{dtw) zd7`S?f0sp|1qs)0s|7RuUXtxSY~||r6WgnXD%Nv` z>vx3OQ`vTIzx}dCzCUxWZFa<)*^XNTT9EjC=Jcu;)HrSKxayRv&gl!XvlM^XD3wHj zs!g|ms?r}ZXZ&eh`Aty$cfq-h{g`pcK9Q!BXk0mR1@VD4v<5~#u*1vC$q zF0b12$SwHc>pUgvhYre3iac)o#&)7O4ae%JEsG@WS4fmv6|9t78Lh<^Tum+boO*j+ zXK%-Ap$dB?#iNf7Quk!HdOKQ>&>v1z7CEA{tRuEl8f6NHsoh@4>k^~CqKdqaifhLO zor@DVNv&OWgxTBCf`n^TWA(&2!xyLfe zXnsjk5A5%6<_ZZ^k*8iUJh|5Db=>IF>fUtLDg!M@xaLHQcXdG(Yfoj*ccnSUXAgh-|lnipT$s40-DZ47C zQulS-^^VcbtDO|Q5}lwtv6jAwS-qrdr)G|rQ!(0_*Yy>ap_Svwo*3<<-blIb*2!@r zG)8Olp(&-2a)-NK@v)T#T9A;_xNxkfzF1F6plV6IZjStcFW-4dCTg3{)}ven zRL-S;scMahNT3RHNN1j%d7-VVWsPuXL1JI6>j@uc#X8eCJZ+=4DsR#@M^(P%8xuBO ziPc7CZcMoW25P z*eCx?N}$TM;;_;<;WOV6_ueAVf&}jUve`OJ%B#ITo0LG6>~$`p%-0&%vk0^xfqTE` zo1YQqw6wH~&RF#!fhzQP)0g)#$Mulb{Y-*Jvcz3e^8y|@W_AfRpVf`GSHH&Ha%Fzk zTMx9JSkQt*=k8k_txHEZy#^b*FV^QSu%3jGK$Y?K>eu`+@!)OEbC^{Q>={@lxtGjp zlS{u=#k$YYf&}{a=_`n%P4tKRtaTz1sG|AN-1}p-`A_fWdZz^zftLRwtl3~>nf|(# zE^)3+yq1eLRKH966Bk|?udfNS=Gsm7f*r*VMr&$(8fDSOv5pNhqqPa`(<-idvz`s& z#zyI3$t?mcNR)aK?Kqx}{0#nC=|0~yH%_nA*qWV@KvlmS(;P#iqO?+5auYG~`ZV1y zcDUI~(9*lYe8<;&k=o&wCH|GGImu?}8R!&qvnM)xgOOh(2K8LvID9HnyL8a-S-!uz zOy8Ey>Lr*fRJHte(9vSpc&86wSdnXb=gz&%H0b?M;@cj2ZmrFBF0GVdHA?Kp`LYrAc3k*M7R^ND8}%f_cvyg8 zz_!I6?rMLlUnO&k(`$6K+5;^}xN5{&$-JvPS>NlHlt9&jD$5;O<4ETlEZeGedWt=R z&ALJh5^_1-wpyjH8)kXDkU*8|@5U3W&9=4KF1_h|Yh*wR5?F6G+xo1l^h)7!8pgFy zRjJ)F$Ewbe+We75dxUn~qJQ3Qt@_Y{gxpL1PPs(i5N`D=Bv6&7{4&SfZjst$ulkh6 zwF-;$Mkg%-El6Omq_<>WkLXditzP092aVqD8d3j!7tlAOBi87nb6X{MwZXp$S6?t_ zo2~!3aeDm~N$+!1;fP_g6?oKEe_GZWuh4?T{>-f$=V{H@sb5MedD=Y95;i&gCFmoG zJLwZ2&f~PMtMmWMUsCRUF~_R!@~md$7Kz@^_r+hZ$7w_3-6)NyAk7i-GAV(oF9q8s ztjrsyJxH5|i0%(lX@U2HMgVX$BE7~l!bQPvB6rsB7rKo zJsO9P=2eSu-N*^~iJ3tebB61;@%O0qv1~!7pU#~Fvs#Yjv>nUzW}yWMMsM6()L*>M zpy^cLNn!j+xuHo2RBcNc#~L?^aHf&@RT%GHKi*-`XhFjD+nNXep!2Cu`*ku$pNa{Y zwDyMwnx3?Q@i{fW>wV4NVLNSF@Qe{!UemLkDjb3bLX;ApY*N%&|G3pp{8aUXhCAHpSM=xU}vXyFlbFd@q9=9Bm}BlSF+mU z>Bjux@2b{&1GFHqo6_*5G^`ot>pwX~)KEEB#^58TRiE{S$GeyWT99znx>fRw>C%YOq1GELm&)+NgeaM`+*t>i zJ{i~Ftz0!-VH4+CTYVQTNO%vkY3KKh&{CWJk{Zw6>w`{PJrN01$+_zM>aPAIB=MbB z;wl`8w;^vFZxTYZyY~ImcPCNbZR6~_cr8@9`m|M!XYQf#pZ^KtMjzW5-DKZD8U^Yt z^-_{Ih};oXBaWrZ>ZyELJijRU!kM9=Xq&m~=;RAG3G#(I$QRC>zHkTm!p-00FLjVF zoF)3gb@GLq1X{>*n@G5RTX!uz-D&i6XA<;$mOwslW>{Rmjl9z{Ts-;6nYCIX@3}_a zbCW=e>$lT;o_HmjZRk~R?cK4YX&~X3dq(_8HICIhV0h1e<}9e4IGvP0Ri3wP;_Fw7 zV;M~E`PmKWwSiYH0xek6t}4@1KnoH*!%{e+8pN73osIkQN&-F6n`yX8YxEyin;X9u z_n)w<6!j}>WH=G(rmenY5okdI)3(_f6-%M@x|x(f)%Qll-vgUUTn<)k`*}nW?X;G&~7`s_&!Y9TTcfaJI*oQrqg5XUpZ&(fkXmT@~*H_ zhnuMpORc+hT#;^yd-oW2;$m~<>48p484TqiD@<;@J6~R>`MNo@O8OIhGZi9-ut?Ioba6 zYb>i&s{Ox8-n{QSHmuB8GgnwANMPEudR>=FZGGArMUg-i);hf({M$>dKFbx_RyO1wu>;vUGnIee^2xXtK<+dLz%o(xL2YoYfvkpeia~xP3|5IJT?3;XUv1 ze7-W^y+z=RgL4Vih|M;mc{=8E%_7i(MEJ*A_FIKr^T&!N(d^8iqy(z!j=o}_KHoJD zZVGR&uFPlkU7C@N-9|~;BRp$2Wh0Fk)*Lm`zo+c*4jf$Yg~o=)XbOx zVn5zd3e6eoOyjiML3QJUAhTbg1qt%JDCDO$X`0o_Z&m+@vt|P%P}T0-dS&s72xl7I zZ%$QXwpud|T9EKvAFRAyy-okF znJa6ZSUN09?UURhT-P-$NVq?ZR(7Y0W*I6O{@uL`;?!e}Mp*ZtvxEkLs*we!DSt;s zv62affA{I_X=?05s~l)~S#`cL<6b2D-p%yyLaw@}o~5>Mvk1%;5-SERP|}@>WV^2! z{@wI9m#L-G4Na0ORFQ{GA^)y(7c2R9Rr2qe1n&RG?*hmttB`-!xz{;w=s9&`Cu>hC zT9Bxo<)X47B%FOH?DX%d{-ateyP3&XSXVmyv(htSi^-Y?K34SZ}6(S0(?hNuUJ@^4u!q z-*u)z{#}*)yGaOC$?ZXL`}irpP9{NqQAU1I)2l*WBSwBv^LNxv8yhxb1S@a)MbiYN z;N%xI3A7;L`fc^ZPi`O7`-i&zPr^`<|572pC`hv|3;9J8i6X;n?9!eQ%+2%x*q^>v_nx+TA`+;Q zbJhIiUDbEA^(2fIB*^2bkYAKpe$lY6SJgSrzKaB^Tz%RqN2is2xxW8T^Bs#ZmQ(*V z-?6xU8>0m6eqhGV1#5-eX2oD0kZ-+7palth-$Lgn{v6JK(uLm;_q>i?GVEGB4++0!kzyT(qIW?{sXooVV?K z)BRE=ffgj_ln`c|@L{D<=virg;aSxr1ghLtmtjwR+B)BVTq{wY?>%41B+!Bcomjz) zQ!A`A?#%G!!(*x^AyDNU$DC;l`sT$;XQ*KkX!$R~O5d(1D)k)dnPjv7-7A~K>}6sH$O%hs4Qk0)CP&Cb+~>Ty~n7h zUv>44;;S3~`?m!N$|1ZZ+cvv|=zUjBLZAvybfNt|Ej>ipBDGBdEl9Y2TeVAlS3uuQ zEQj%Rlk1+q9MV@1rQ3*ERWeE?H_C(ro{B)HA=d36c>a`02vpIXW}X3IT*+pm`&__% zo@n_m!YW6lt-Xckn2WCaJdto+*HGc<1r+msLXgP)>JO7Zi?IvLH4eIHD_8YW3=%`~ z?nsgb62|_nUnAVbQbWa^f0ia8P(>r0dA5j^291frH726vzX+@3#%?WR*OtK};reZ; z@T-5?w?KRPjJ-jx%hw0Odb>+e>sZXF8~cRtZ~CiD+2 zNZ?5*wBLvJOZ?Q&Bq31c%ptAvjencFg^C$Djo5{W?O|Gwz_V;@w&nH5h~)=LB_U8H zpIMV_bBM^Zzo|)}<=xt7t>2zt#i#{2R~yod5=~n4Pm%@_%B3i6P5U^LrqxpWU~&5W zgd_y2c3h6o>J(q=Bw9c0BW~t9V-imfhG=mU-U7-bB}kykIqo{24U`^@ zMa*A$Oad)P%-hyZ8?vyJGmXA^xyanML=pm3cnSlZNa|39E-V5qNDNxrR`W?;#+gRD z@8yKBRW{Q=0#&q@&}fz6e4418tb$mcwt`8Z1&OciYiX_GYCF@&(al@L?yR1KK$UY= zbEdKUFE25@d<~O83ljTxm(qOpx}J*aEiWYY7Oj_rKoy?CKF1 zEK{k*&NL?Zd-5_pYncREkie%t8mXr?$gnQOLY5=8#U!?%awmdY9QG z(1OJEPs7;BxRlOZE!)(A*BhE534toQ3ykLy=O`L-t2=+#<$-xep{nq-5Z1p<;{3OPK3qG&xr^M{$^=66*vBny=We zv)j(s8_VzRcy9J&ycVkDb8&9cyTOakterV%L4syc<~lddW~2F>yXJEwP=#mm*lfp^ z`0zGsIImVmcYIh;gMB+(-|V9gQk7)e3v_15Xy*KU*_Rdl(S_Ch(^x4q++3Ht`4{Hf zcb%;~FmD^yx2ivjD&x!6z71dxK9sZQJ^^ge&hpOQzNcReo-5Le4_;8tfy4t)1r4gs zKF({%I%hQ^fF<)+_~oclJmRX&ffgjjzpTO1jJI-Yv(-OeftM@i&yQs(A`z&<^3i&? zc4OY?a~^)VTZyWecg$hymVMaft9hN}C>+>=cf0Dw=kHnWSnw~?!1kv({Q{jS>N*549=s_l?Cr%3gYe098eP$l~T}xL`0_Xta{BON1;!Mwqf@hVdnNd&4UK8a#WYrEEo_r8a4&o1@Uzens+a5R`w zFNXad+0)Dk(zL(*;wbLdt+RUS{dxs0NR*!)&Dv)PbCzSFZ4}@6AV@8gZLm~-NiC@I8oVHc}?<&W6$^5>>23y&W^EcqHS^2HZR<%zcnW7nsP7zsRfXJz%uQkQt%8sQYC$xWX=m79?6^ zj%E*D*EDGw8S01eD(>Oz@lr2_sjui9%hpc)WY3zU$^_}Tc`te3loR1PHK>&CLJ z1(PXR%yQIG!uZD(Sy`R+lOzIFJ)cZueoLNJJ$Az=N3&C7d9|RKY0|kX11Z?)TYpIesv10tVLui&v$qYlQyQsDjOBjK;#l@p#~E6Xkn8Hwtx%q(+jS-U zuuVk*RWr9nGvD3I?D?pjC=JiiJV$m#EqQV*oBL-3d%JGFl8Y?Zn%Jl5qr4;nRd}b-$@RxWdFrFd)R~bP7+R3Pnx-ey9fNpG z!!7FNmwA+TS;JYnDwmaS6qLjRoquF^3hjAmQFOf}KdQ z)T|MTgSC7FUr;DU&9y8eLjqM;BlK;?&yl?UmOg5)C_ky>NF?tU!Gb<5ai$UJH;Ruv z-a~D@qKZVI3fswMYhArNFEsa&nz6?k$EO^_*z&1qSPm+A!~DZoy9nzyj@lH*@^R$#8bFVM_B#He0;`efZ__=hQA+9>ybqDy$Lmw`A(iOE*5C>S-D$ zpaluHEaB{S1FM~Aq-KNoy$jpa=3hS9kw6u;tj*@Lt}7ps<%7EX>jSCen8Qy0^kVb! z6lB@W-rgs&Bae8Oj90r7=RgY*IPcO4h(!W;p6=;+sc%IzBv4f$Sr68_1NmRgG$!<` z%WqyQ#B28Lqm6IhlJ!_tg=Hg)cdwRg-gN6Xt~hAl62;lBc-Eay4eOzy1&J+s8`g7O z1!o$SZ#3qwzUAg^Jl{wwGE`v>>GY%lE%>WOZv5tQl_IDATH_$`;8S-tx3{Ytsq3}j zEjDN1%eQz-1ghkc7cWtck62ro+jl*X)}pxn#MPk9=C!IMf4V~9uPW5g(1OIq3%<<5 zw=45}UV_G}?@debQt$12$?N74fvPJfec8x~U0Kyu<%saBTa%AI>B$#{g-GpzHU0Bm zb(S}46SJKtf{VM#M`icr4H}f!(1HZ!mb_{&EAx?VWx0LT42eKh;e(uQ@omQ3%wFQ> z=f}_HugEvQ4cE|ugj|lNZOZWe#jEf~eRoL&s#1;gWk0KQXBo^iik2MB>&_^qj(%`i z`>|pmtN67GTQangnkr}@JEnGJXWc5P|I{1ErtKWYGEL_6^z_fq(LC^|n_40Ig2s3d zTjbxJ9qd<59lfU?yS%77E7PW|I(b?@cI#pYdor~$5h*=F`Oyu@)m!dMv|e+2vU03D zi_hVqb_(msK7S5m$JZ29Mdd&?>0T@=zP=n0TLQ!QjLySZ#gL55EwCr6-?$e_6 zeX}PEx>25uyZn)j+|ZQ`pVg1WbxuV@$sc2>)Lq!tQB&E`V}03-Mfuscu=WVU8AA9b>diLGJA}8fgr!MheKe`Fl z->0zJsv~1JqSv$gBlA!icg_XyZ^=^d?_GUVFPf*0_dUiY^y;m8{OQHs>^#hd9_*)n zZ&HzMj(4!7$$ApuzOo`eJohAA&WuT`H7%$B0+oKsP%|BV3icber9YUZ#2c0rF&n)ity zBF~G~yh_kXG{PxfIoZiFfy-Nq3So25Gs^nIbk z7JRI>DKo%SRazUaR{J)}{5@;)X!Y-OqgaVQ2P;$l2_fP{;6T13AvtTmb(h+D^cYiB zc1(y`+H->WJG$mDwP@6MmbFz6<#p&#BK|xc#%I=DuiPGzg-!1nYpU`EbXW6MiDQK* zSHG|7sJ8hO%R1Qi*@yP*NJLxOm04;=V|L+l3U>E)EE`(joIS2_M|I1HiA;@bs1*1k z@LxoI?=YS!b#YdF%~XchLgHN`EA0=fyHgsI>(Cl*=my39cBVw23Uh0-1)mD$!#Aa6 zFLsYr4_>uOt9KZxexUvAM(t*v5~O~+62*dJ+A4MT^rJKeJs-vQ7D>;xXYU|ckcfY2 z(IsCSg#O5bKhAsFK7Um$ULsvd_UEUT%5bk(wNToUEXb&<3bE>E4?i=#dBGEj82YUo z4?hs3__Em^Pm~o${@vSe zZ7$E#f0)OHwW`SRK0xBo17B9|;T3U`}l#)xaiH%f<(Ty)mYnf{%pmiNFuU%*?B;{lxo%pUx`3f z`EgW^$yHhC@)#oO1k~o!iukH!I~L^Q>v2}#i&Tr^I$EN z*S(ro?f$@vqXmh=*s7H0G75#hZVrt$w>$KuQCN#U*^%iJVR|gg-!3wRM z$y$D%pf+2pu*x?kvjy+MDUFOZn(>Vy_NONHrb zrYRsIgSpe_ebeo#z&P9npmE3|4Dz@Z}x@=Ml zw|gwL2NI6MJ}lYa3t1;^ypcx37W~K1HEPq_uOtFh*n8;N`JVt@ulqH1@c7kgqZ-B8 z-rT!cuJNPPQ=^NsSvPmELv2T^a$QaMGk}LzxU3dkvq7>Tv3YuNc52mjwm-ud%GHmV z0lZs#!D6?_U!d$6%II<&#_?!ako7$Fy+2_zgVh4rS%}L6XlXCv}1DO{cq~gR;{FRAYsqq&5DixgFPE*)Ya2*ZTSpJ!*g6`i9i+B zI<4W}x8|3>rsr9PtYdB37h_K*pJLka_G|E!v>@^MxAN@b zvBPZ4#0EszZZzjXA=!9v=0gr7Q1!E+CyT#&noT@XpNQl=Tk_eRvU2xy*%i!HjRT&{ zJLMTxB}EGQ;PM(=2>U$OQ#+f<#`W7;EzO6kF=mj?xHy+lF80lb-+fv?W6V zRoJpLpLcA{r_9aBw*-xrS`Z2EhQ*kE<`kQix;>@wDY!LvZ<&!tzK)OxRAGOk*?D~v zzIb&`{&w(<5MR@$#RrO`RMDbN2n z2ajnsQ9}z7MLay&RsYlM-mBU~_&0CC`}B0RL zqL{ZQ^QwKCMus|+MzSK!`G_Xjd6scSBmz}(n_uv4${*7{;eJc*Xy4a+uyfT;GH;(s z>h{4ZyD@klyY;(W&9m5pd3Eau5-}NEl zSjonGPMMs1#`JVL5~vDV;KBBOI>sCsj5J1!ZN&Yz=H!K5X4TPxM44C*W}kh8jsLwQ z5$SU^;XYT~_`Xg)IzA)gvoq54-r#P1eq?TLerK7FjuwfSPVN8d4|X$8aZ2NT=Z1XV z*j#*eKmm!^3@SNSMM716_fjG5)nTZ9@{1?y)qEW*Fg%&6M0>JkB{s8L71F2`@2hNg zp2h5sF=;4`G_=WD=alfCA79=kDd$Mbjb};YKnTg1Cy&fO^DJTE>ps7Tl3TuRR zv39A+58Dgy{t@k@xixwk~13Tv9YAD{jCP`w<_ z?Vet*I>?uKPV3IP&TPhl;!CjoeS+AoJ0t&9^2HncdD>#-c<|7B0 z@!j|`X-1Ske>$ryf0MPiM4$?5op#oouEPiT6ymGup3%^6j2>vLb(#%U)ZpvfJo$jD zmo>B?f!ZO!E>{KKMB{73Sq5`ikL5h@2ox(O}m$3L$uQ)gb(h1uKsv%d$$Q0<26&3R$&#$V-Iub~AA z^ovt`=Qn};K^>t5=|Om!K)QNs683nRkW@Pj9mZM7#*8rR;B;MZ40s_QdlV`xDF-M}vu zba)2kD&@2>+_5lPdDYEJMN8n3aJKbosFLE@w11`1anTswEHF+PSzJy7iM#tIu*WCL zDXSKSQ5sPVLix1`BUtvbX{21C3g3*=mwG?P@Xgh>C||zhQ_+INkf#xh7s;;FJUy7w z*c%zj!{3B4{nQVsJy3=3hi$eJnL>Gi%WIXCad}m=AW`TieSz)erno&DL}`?5AIewy z?Nk2F>?RSYlHWUXM=0<3Ah|lXayH3#k3RjtiG5i7$4YF^lJk^CzTuEMOBRcsTrXcW1|x z#;j`g3~I8x-P!PUjabg*>D4^NyRf}^!rA}v_1AG-EdTol{Kjq+6*~zjyAXC}EG$ql zKtxF?1qG2#ld`)L1G}4HY>#nNjAO?+*0HvLuF$=N^+6(kl83nrI>2pL<>M3zw@Je}>RoI;{*-cty4;X0L!7nQp+B{zFO zZq1#@+tmsowXX(}4VN0y*2jX#2va}8@@vzLZ~aLBoJ=x0r?D*Kub5Q!?&N#2WY2ts zKo_o<84QILl35>fM_SWo8Ak<)OqT#s;$k+5t!gLB;75~K;J<{9I=@^Y(50@#J#U-F z)>pbhHVh8pSoaRAgGkC*A2L3+R*~bFADPBZmpDUaoa)B0CP;WV29Y;8gGrqx)n%=m zf>PLw>Wyhw8DE7!7oJ(!Q{PTwW9RK8ZG*~lRFEi;D~l(~3?f69>Ujw@brJ&yB~ z&~VaK&StOJ(VW)#Hi9HK4JKu;G^1Es`F{RSGJ8L$E-gKsE60JvmD0n>hcm&XS0DW< zIq96j)~~BhPsi+52z22w$@PzQNvyMPds@5xagM9SxQeW<2@md*%vRiKNEg<+%~3(( zOmHNb(#@X~lxi<)^>KMJyHcz+{Th5-A<%{E(Q@Ap?nZJrH(|V@;5Facm4pv-BdLCKFjkWve7MYmy6{J8-W;pbO8F!O(J3l3bN( zNq@b(s+>V20m61iCPyz+hM>dmq>1z36DojQf8~ zA^u^mB>z)C`t#0MvS?d7Qu&N0_3Af{^j&91hFbNJWsJR>#Gc-gtvh@oM`c6Fbh2Th zBYCo?7sX$ayRq*|VtZL}Hz0$q>ho}!ACsB)gqGC2Rb`F} z5@W2#lUdU($e~<)mh*B@GJCM9BdyjTGam_b;kl7z*`L>(>D!6@6arm%X5|jbom1G4=k|2M%72w3#~RLAC*$D;mM7b;43K5~ z=$69lZ#Jc4QtmpVf`nPiNu+JDQY5vWuOwRilfpJltxtFR#pWY{E}OzhhVqVToysQcF{ibN zSw1RAEVws`+~nUhdPqNxq2*Fp(^IwSbem2JfiCsPLu;k6!l|Fh&&U!Q9y!)<_{J>q z=Y#d~`*ixObLOX1R$|jDQtP5dP(i{zMDB5TaGCaXg1&CBVMZE@UVnu|FPNesfi92d zS!6`wN^RmVy^N!B3>R>E47vXLn}*RMb~0wSwjoLi;N{mpbKj#XNqp5u?AuJWay5q8Y)O!Xd~lU ze$LU(dFgj;%(^t@K+lnP{TC<%y3`{Nc<9C!9IL^WM(^P`1A#L-IAbBBCQrMvr*1Xb zz&-bsxeO$5c1O+#FLY;7v6Wegze^Y3Z=uU%z+ke)w>P;Jl_%c~W`?@5A>XRAEj|_n zs34)v!*!qT#%ioGW35^`D+Ic5Zc)x`AEnH!StItwG@t+#B-B|>k<^a$tYE{;9;7G) zy3{$#GHZsgv^mAti--gzmJ?@yt|e2`gwrmQ`9KTQ~8GH;d|L!Zs9t#!*26TU}=G9Q9`nqF>PN-`^?(y4uPS zcv#LzQsvn_S%#&R7hCb57;9~7S%3->*y=JC=dw5Zaq@yTY+DJ2(PkJ^rbeFqApUGd zASDjhJ}5D1NT`u#H#Y{b*QtBSD$f@Rfv$1iLdfPaC5Xd|ba_YhuNumh{d!Gqe!4_a zLBeceEFrbOYb`PpB$4kG%zl2aOJ|O~q7djZm2t0cCR&lXpY-U2E;EO-b}t=hwHE~x z6(m*{A49hMTaWx57AFbQGokG35EtsW>aaqf>-OS6@~}cT@~)?zJ9lAxIIH?}0KE~j zfue%MqdHNf`4)}bo2kd#ZF@JI-TfIsb55xQx=dw!=V{Ae(&L1_w%xtXNcPP#k`ab#GS!}K8ch>(xPyAwP(}7%`+7OUDj4UB+zUe+1pRARg;#ZSl5SB>Cv&V z6cr@aMGq$@|B4|Q-g-P-*Le{vw(er;*Kw3Wpld>FZ_=#ZH1go4p5Og(!zi|F?NVwr zuroyki5pLX$*SQQr0K0-Nqi}cVDDTv(gvj*6#`w|$slsR(?Zf>c&H@2(nqoE!yD=6 z+NKm0B=&>`lBSt6$gOxkN!08U!9HK!PtAuFQwVhR_8v%fTC5^VYw2T#Z~I2F;x_x} z<68#^DoDha^&@}BFCb_7cuC^9Z8&QXeu55lTc!}`a#_)jyj_?_dRpj2bb17PKK}@v zR8AwPAaUyP5YoNDGID9QyCe>+8qWG{ygq>?_*+NDoQb}Bo4P*1e zFVnFlA~-5YnCu-$&i=EC9Q{XsOU-o(W-A-~O;1*zt`O*YdAcVVI(svDbhfP|T4si_ zy^H>mvBtR^6(r)i3?MIDRub#k%_UKzdMJBqca=Uq!W9Bt4d3=7|7=`D!kabF%lNw& z8#XFW`&70r!$@L`7gnQ+=SB5nLB|`B7q`q9DoCh(`-T@#NtyWg+SM^1P}7I zuq^o*rSGxOXQVeP(f$^By}B4f1qtlI4Th8#UhH0O6?*@ZN}y}q&jDoMLkF^SvK~z} zVw^8CJ#RsG&V5BuK>~YlgTedcP}b;!MqhZoQ3!M`?%1CkvF=Oadg)PNEiMMIU6cFJ zi?6R!RFJ?PT&~0g`m;@IhSMdbRRUeLdbks_dQqf|qyAJ&IugXHk4vOoOCF}EAb~x& z9Zx2I(B;*r4>>(GlMJ|a3kiZ^XmJu1k&Q(7}+kfe(5a@c_zB{p;xshay z)t?68ZNu33O{ZuL+nN*=B(MjUZxcSj%tc(MJ1Z7f2z1pmaUrk&+(Cl->CcaLH$#}# z@EWc2PJSK$6eO?*m;12f4r6n?9@9^GvlIedTi$mj@3Z%k1$myb42KHAtjU)9wCpT9 zf(jDYAImv_#Q`kiz#ICy_!bQbbOl*0;Lt1>H1v7W$BZ01c%Nfa?e1O;;&}Y?FxdgE3ec#eb2b*wIkiZ^X=8UfKVUc5g z(gSx!DFnJO%0^~-FY#k{Cw`>0Z_MVXAb~x&EThX1_W864`(}SaA<%`#)v*9kp+w5Cg%5@iTHBu7y8q>ivv%x2U1S$sn<;iw9{LKaq@e|0Ul) z9!5H{vJvrGU|LHhrvbBIFn(Xo$&~NNY-Gm!D|1^VP9F(;cFBkopU$jqsZ8Q=$Vws5 zg%S8NI^koqjB;~xrvE{rOdv1-%&S)t`7+9G4C66K8qKD%T@;{#vTcuD~^ ztXr)R=u+d5i{A@iNm)m!`Q<4}R523x?9z9x_hXOVU7>Gs(-i_;YE*I4YXQt{>ovN| zXMhqTj08Tr|NWAFr$~Au%y4f}EK!kqmjSzYh*NBlGC3!)Suz1cg8suAa%2(NFPg*4ZTb za*BhpN`}PoIZ>p1l~i*7w7#0rzA%AZb%~(KPR2iuw$FVy#4GS2~=w`n*>m(50?XO1z#+9O8J8l#FEp*{}f?Qo{mCR~g z|3)%P)}*K)as1XKveG?I`!Z#OETi1+6lP^|ij;6RQ3!P5Du==Fc}z50d!_`rIWAYp z^u;__HS0GqGM3Fa;Y;4!o2KLgBcW!?Zr>iu_Ow1ns&&dx2z0fL8B5Ndd?n+jqU3SB zlwZvXU1>^9w_fC!bB@sv7*Sv_%ov%(ERq@ZaNMW#K1irB6T@pKuqjnX(}x~&6#`w@ z6UqH7b7R@yi&JT6X?Kna5)-x#Bh!OslN_$kc$Hfg%bH!AMt`JRDFnK(Co&l3ro^y} zjQMm`<@x!jAknaXC^<2E8oA=6&)j)@ie)#qPNkM@G8F<{*b~V$NV(gaO}jbt&gW(t zDoAA99YMY>$|NJ4^;OGW!{S(jYdJKje>a6d7xqL3!_}-<=4~~d7Hn=!P(fnD)lnp* zS}K`3UC%@+ekG2*xjTuby=kiu=)#^zMooT`;G!dw=juBR%uOIWa_i$u6N_vxtYD`wXB*7fiCQc zP10vrPJE7M;fI=0`od8m(1ksbjHa@VW33A; zY2)HS6cr@Y``qD0JbN>u0^L~BLm|+GeV3e#`Vi0d+Wkw8EDfZnAc6ggd^dTgD%kf;V~Q)Byg?RU=STfvHjKd)0)RdDg?TEt_&o#dki2Wdft#_L}ZU( zL%*M-UN-wUDoEg3vHX6mUpRXqSC_inKc^7rQs;d}CHS&QcV5#^_v;p*f`q#6eDb9S z%Y9IS*{yG{5a?28qq6RGVOq!9Y=&Q$G8=^iW**|EeMTD=R@E(1kf>GUB&N z7>lm)RvWPFsL@Bf}49WxFn1iEky zT7D7uSrju%|3P}xT}e?v0{cg~%T4)6_HLU6-S;9_A<%_u&~nURh-P`uTF^eZQz@PohGg z3)i6KD5L)v7CvbV?fcS=qJjiIcMXP%mq)W_%_q^IohpGYT!WTz`q^XH>+zX1@K_^? z3KBSeFc{2AMKf_~7Uf&(D+Ic54O)(UBF3=sm1ff_)1MPmkic<}oS8T?nzbChjLxp| zk3yge*P!J$Kz~KE2N_FfrPd1wDoEgXPR^v-jb=Gcc{DsBMs?1P;b#ip!8nle^K0k(qwwh1FMlI&3Ad#u$ z8(bV2$yRROMvpXKsSxPGRcnJ`aP=6Lzi$qGd~FR!1qsY5kRuuQNOqubE3Fv4Um?(i zD;qL8db50w+BAdyp{?VnAc0v0@=DBzWbgmkOlR*srV!}Dl@0lY)wozzcIp%wI&Ka} z1qsYOk@+9f?M5RO^)dc! zHM1LC`oh$>zgMvejpUox?|;7uhpC72b)sdtV0t-Y0%vuKJ9%FlLzB;E@{$eZ|8E~r zgeX&WlJR$a+x4VARl6B~*W@pIT1)ONs{hiznR-qGmVpWqS1$}S(pQ8Yk@8;zy4sh` zHI~t>`|my2b>{bReCrx$w@f|NSOVLE_=! z$?J4tfuY9#L7>YdaGtYH?3i4%3{;R<+V72#Xg8v08Azb(YQS0}QDSk?GVt8qI#I{i zq8^nkC|(Qdk)wjdgzq*+`cq%4B1et{y6{?1%RmJQ&vG4&Wt?}`vxI*C`+Yu;Ko?#y zDv`VBwDH=#d8!U=aC(*TZ(?1W&itpO@$X?t`l>#bfeI4szt1od3r5uXKL~V{eLvTD zjXjuC^n9R#M9gw;V;RMb`#@r?kU$q+)9P`cg2d_vcE&RDuN1wmkU$q+`Dz(mBX(%| zRlU5nJDpT|objxs&hJcZrye%`|2w@07HKO~knmaho1W`jw5^ap*LZf!SVp&P`fA4S zf4{F1RFJssm0_%5_rPBN2Z63nd8dtKy!)z0G-4U3An{~*maz=?-Fkc?64*zrs}gE- z&6AON|J`4qf<*s~VMcmULc1bmAb~DCPin1DL1N+ZIAa+z2kJRkcpONe3(uxXlxQ?A zU%yJM{_H{fZ(eNtdtF&KTBk)fuK)ku7wn6aflnNK%6!iIeK*(j(W6+gR;VE1Gc1Q+ zs#)A=U|`VyL7;0-$1}znW|Y=fm#_>}kZ2p6!;i}{I`%7C1`_Bp+j`bm#)Wfw{s)#} zxgy)B_)LkUw`O+cP35!p;G#@wbEYTXU%$AMOTNB)D-yWVsr+3{Z&8-*LuZ;zHl9JV za6OL&2~?24Yx=(lbfslv8_V#$(62}ts37s*_s8Fxw;StTXI*XTu=6kD-$`TZ(#+%L z#=mFXDcVz`f<(_+PmM%oLcJojLIPbl4pNUC6(oMPD`7nHN~sNslz{}g@ENR@fzR;Z zLT_W;=S9?{|NT5i1&K}`k-zCxHH*{=33OqLsI@``iJCW78Ox|)QM*VPNT3VPtXc;4 z06xyGjlID-pC%N043$6yiLB3cjP$V|dXD?=f4`pwNT6#=$wB%0z0&!ko;isGDo9)| z^}7uB3q{L70$n-gJ&k3g`xY$&$I;l^MGT$54f38pS3%!*5Nm}B5;gYjF_z(9L0{qh zF9KaK8DI z=hZIm)O_jKA_Vq{*bmBg24fkv7mB`r;5j(lr-bp!SR2)V{`dJn1&ORP1|wbnS^Xll zLIPble*E9*_+RUyf<%*ozl_IGkW{xw8AzZDN407h_>^hbVKPsYXDvqVf&Jf498{3F zA)jjc{n4sw(eV`$=&GOfhw(VRBq4-Gm}#Ab~Et#?)G&f`m)K2tK`Tai=_E)IA;t66pHxYZss4cpYzB-ii;Z zTHNW(r0gQcfeI4x-N)EgI~wWH30Ny6&?Wcv=KpVBZgp@D6%y!TozEC+Wml@` zSQHf`aJ5&h6%y!bnDvLT4D-7IMOwGk)ouCul@V~HFYTBfX6y~_j%`QFUj6+ZUEi(f z3=1kqxR>)W(nI^|`#|E6BY`e_Pf!U|kSNiyr?Cu@e zDFG?Q-;LE6#THQsRFLp%Hp)mR&UGwOD zG}5mY6g`7Tpex$tn6X8MZZG;YKn00$S0)(CD0C@0_CW$&*y`$$qk_cxM`Mj;tXSH) zNb4ejE<87C8Q2@(mka*8XFvrB{GNhZ1`_BhY1Y?x59S<+E^-{0MTb2q=EtdJpn}Bw z^V^JN^qOCEM1};qFxOfwLyq)~S3_E23|-piv+-}!JyZ4hWaHn@P82;3RFJT@E@eD} zE)}L0IdUY>g-}OuT6@h5`rpq%RFFtX zx?_BD9{xU~NUe}4>eBn;RW5p__wRqd$5;B_|4%{Uant5|^#8xJ(aisYK$m?F-vc`F zPp6_~;PvWws0z_tHUp;6|GsunLE^PtDI?vhV$pMs1iF&8RW-KsfpJC0C8!`V;OjFZ z(Y4C7B1et{x^RT^zsCLFxE&QFVz2Bmmf`O{y+|2IpbN)cY8kS>GX7RT%@F0wH$LZn zmr=E1(YHHPFp>kmuA`QL1iJ8^R|!;*zjM>dEd6ReK3~71s%SIljt5nZe|O6)dbOj1M8EUD z=K!v|6}=LXKo|DlYOPQ~VpNOYV8o*`vBUnPdm8N6Dt z9$FpwRkV4(GI-0%U5tM_22bE0%TCtZMx@DjxNdLK1os?F{2tFErCq~$T;H1H)Tmpe z1q)(N%QJ5~Cb?B=tYg2{zI!@-}Pn$W_m+$@fMvrp? z2E&7E$>P+S@?^eO8;Y~pID20DQwE`*sXpJnz@fSL=TsXu&BCdm z)Hhomc`A;Wxy~T_o$dIOA!Eqc+-x$rAK_~!`VsFj`o7NQKF!7Jv29tIx%LI9Akih? zjxU=MK?eVoAc;#^&Ba~Qc5MFj`U-)rUbpRd-q{hvtbDX2!Z)@N?kiifmmz;}i_VO@ z&F)Jo%j;@*ls!K@C5TwfaVPUyGCphd@BeQw+z4qQI_+)GPA)jdQ9(lPXwBtTng9E4 zpF{oTVvlDFHlrZ6Ai&;+Tgjc>XUd)3a~9a}j`Jpw3uCsB?1vqA;emMa^}$A2t4^Pq zi7Q`Qu#mD*1*jmAb=QW^2%kWX-_`eY`qitoczwAUn=^f&LZA!VQ10kp+gym$)=Z1& zt+W*qKVIANsr}-~fB`dQ8P*M&i%RKj*v%lO5a_})D(+MEMY4WsJ3ie~el>mWIax-^{T5>ASO>PGSVjRVNSyU;!WY_3 zCr4|almvOyPCSdVW^r#Oio!-pPC+X>a<5^m}N@Yli2M^^qp> zO8io+qiEiuK3g3(x&Rd<{%y|qrK(HFtwE(EQQM0$s`HE&2PN>&cM# zVv-o@#>8pI28^zWEI-_-4-dC7{BIJdr&=oVd%E!sb<02L&@J+y<9rpR)K!rfp6A(X)nes_S1zbK&w~5E`GXjqwxr*4EO?oFC&{|L&FPZ4E%@TN0&;kNQ%TG` z-a~BsSxfHOSEm3KB>tRf!CyT*O1jmyk;IOFdx(XPYBGO6TZKSZ@9i!4nm)V8@r89H z;bP+=qND4winh)Ls35U)z6I|;?hv{0PLIW@{k@AY?NE<>B3%^%U6FYfyw|1zQjzNG zQNs%R2r{WUvue4L`p@O@RvfM3)@gex7BkMI|6I6DfY#b zwnAcqJWs`b{Xv|KUksVtqL;`wsl}?*s;Cg?!ZR!P_bJm~>~Jw-iyyAdpD@*ue=U7M z?)lk=E=aNDm1{V^?E_lz5xb6)_8awmIR^*!6JJYJWk*(4;HV&R-`bL&=yINv zHhz!gwR3+lCb0^uF?oPOpbOhj?jdxkuW(yYjUBO0SK11RRW&SmVZHMtw}k#(nf8nO zitm@JG5@a_3V|*>vvPOJ9{okzcU9Q!8?nlf<1w|{V98CMohOgvSBVUUlA8yLH>s7_ zh4teOqJqTt5T(Kz)Ms1?D#kh33PcBv*MLzohOlf^?g6?)bJDo zGt03aYj=@$kF2=OgEQpL{Qz2jniW5H;7{`GoDWU?vkm{&>j>H7IaCt+)_aJD=gYH+ zXJ-*qkhtt&#b+j*lV4udvrL^odx~|w<(PM%heDtWYiKZZ&KW4q_p8L}*;x}*kchIe z;`6JVC)>RB*pGzP1I691m6*f5pBfVAQjgqo@F4N+Ye`nzsyv<1%$hF^I8Cb4U|Pl6 znirdXnz&vMqE&je;~^HDbobKt3cEbbOAPDziB_K)NRVp{(cfya7 zg6L87-9PQQfA8I7@s*L1SeoD^BCdX;^&ocNB?SIL@$c#FyZe4ztQ zXbOQYwN^`C4idiB#n^+XEtUErVV7^sO?#Xm4i@@2ania$q6aI%UVp5s5a_}dk#iT8 zUgF2)+w}A3m9$l|4R85q2e~#hnQk$);g(zXk)Sj2bWLUl9(G^@>71djG+goa64vAX zp{-UfR1_rM6tm$EJMSmE2E|KaicEW%a_Jvx-7rTX(51F+i78&%CDC;e8`_0$w1R|<(K5nsy97F+wG_6o3jOqg2b(PHr#&rc5rE3%wB%HTv zyzbm-q*0;Xx}N9zi;)x8(*_ToDFnKDAGPH}&n_mr_vvN0#=D8v{uwlFSvgiS$Bx&% zlu7Br${+D+Ju8c5AL*J7w3aqFWU*Pf3ih5zdBYJr2@MDC^_da13cLZA!V&|vs* ztf#2kFouS8uA;Oq62mv!@h!i`lMQbs$udSPbQJ-<dg2R-S z%BZg#IUZB_-u9eN89;je%9LgF@a`tcr_1%SnROT{NPLOx$V*piOGcg6Yqhlx6P zzfFc8YtHZ;8Hu{9?78J6JJPI#zP9~f7ZYg<479;KYlT1;)=)kNi)-R+sdDs7cRPj( z5)0Dg6|>fvbegXpNBR*W9RH|Jr|)W_5a?2mJf*aQIQZ6t+z2DgXKZJ_pyg!kMNB5G zYU04F4xOR(tDZyW|Fq}L8_m~BndZncrqyaE_B4qmV_aJ+1iG+A42F9{T8c+<7pRF> z+ABwnMA|)jKD_Z0t?-E6Ry~Hb7IlMHl4BFwDg?T4#zKBI)Xh@-+)`J|?9-Lus>K<3 z9Bo3TX%;ndD8>iK{dZSdiMA$lwR@Ib7%E6$E6Ds0&0e_W*=g22s6wC%;~eDPRGuxx z&b|5C)GSAa3KH1rvTxt!C|tfIYG0gMDg?SPibUqIq@;_%N9iBrpuk+l4UTC9CG z|8RS*X6Ncnw=B%&ZD&r>PG9q;rqNmaxaV>$#5z!xvHp3QcsOqlNp7@JLj{SG-?O=4 zlAl)IZHOc`txFSs_ufJ*%M2$-pbJ|>-nE_6#iTYfNkhjwO6wxA#3hFhiD#Nvp_gIf zmo8lHk0*cieyR}Y!gC`tQI@5N@V$lP=AaDa$gzgYR%h|M=hkbFm+Dch8-AsVrvJPm z<%3%gRFLTKBZEI~a#d^B* zwmA2dQ+~5EllY}q-!;oc9yE7$27lxER2zNDlfG#=iI0dbMd%iN*NCZZsp50ZYIFvz zkdF!yi*9G|zVH9mF1FBPqdK-o6`@wuY1>VIYDl09YiKZ3J(nu1&z7Wz60bX8qxzIrov0i+)-d_}ME;j$IpSV# zpe&XEhY^*7<1xMb1FoYBvhrspGpF07&a3~%uiVKbx! zEm&yEQ9)wb(h0nF1#@!Ty1y)Alyi!>-_e0Ce(*UT33RDPey)A8XvQ_#?nHocrkZYrO?W1&NOrQn=MYSJHim9IjUlUre&lg=lf{oHYx@4k4TV5g+vrIChlxL#QLMcr`tOo= ztxE%%-~K2s{d_p@x*?c^BskEA@!|Z}%pkIATXVX1M=;;oEQfsb)8nreB_)eW85Xp| zj*}b}BxdJ?^Ai(;Naoe%k~lU#NjP*Q^p4{Jg+Nz^e>hKTlSI<@=(U>qBU#)Iu0o6d zy24RG;`WmWUU|we@@9t|-y1><$--oHbGrWhF@-=Ewt{?{NJ$pqT74=OT;-@BaiN`T z-GTljZfQGN#x3V$k-XA^&UU(?5a?1{w}Nw$DATt)4Gdk!_c#pWyTWov`=c%BbKfvN z(J7cr>ts`;bsL7K2!|zAC~34qX)7e&t_+j&SHWcUCw=z(OOq7QY@<2d_jaE`pbO8e zd>>3q6OXk&$YSoozZ(4c#4{PB^!!G2e*GZc@5W$q!@fEda%HsnDj(t&uV?Dru}Bjd zyGpLTisY!gYa7gaeDfzyyVj%lOLDh`Q>mh$&m&T!OO8?o5@l+K@EwJLq>=pAp8OJK z-((RH+?tk~yig&~748zit>iaZ8d=*)qSuI2G2z`u;=XVJM+J!z;URo~!Z6a$ys;$K zJWmoE_dC%whnFb?y6`;79p!4Lis@&H(U6xblrxCLteT;G)14sl{IsPkIU(xEe;!6w>R& z7H2$itfAMBAnsbb6S>#ExGZD&l2p-iK{@)U()fH-kmzj);Dzmnlia~2Br!KCUHllG zNQQm5s3C!_#(^Q+)U6#^HvX$zQ9S-RO`O>}m^_<3TZtB!w0#8kJ6MO*K6JN8(tWyW7=?f?tfAaJX=u7wZyHW! zm$D(KAkpbZ2oG4;lC&N0L6(snoGvzqQKV|`Y6^ia^~e(oQbeo%f!elajp@$n>Abg? zuGyAbKzgrF;PYJ%X=Ugp;%$@06FMEz<}Ox#M`&&{72Os?S78_-EglNDdJyePp!me zl|UEPR_^w;I92p`b3&_@RF=x`)N=bhE1YY~RsHK(nf&Vcb<{Td@YxS^FvX~PgM@z|>3W2WVZxi_X zxF!E9qxjbt5$!yOZmGXn8+|{Kzi#|pTkAcZ1g;pzhp#xP>E{M%IR_9IFHS8UM>pTD zuP8{|yfc9}p0LbF8w`)yCW>9lg6NPeH-$i#TC20KBSi8P`HhDATkw1ttVwRZ zoVhT-GE|?gVxxvnr_}|Hj(Nn4%Ja;;!>6 z8k^FQqsw28qvtd)O=|xC5HA`AiNd~*>DO9KIsO(BLl%zVHgifDX&G6wC``0-xk9g= z{G_xMy08`G6Q@Tfae0#!n`5}9MAo?P>C5+pQc_LU>e8*gd_`tYVl8L*WZ(X;iwJga z$mZ@i$5BDzdGi5$eRKy>UD9&T%$ME76Y~bF#;CIjfvz=!2XM>w|BpE4)k#$A(1^u6 z=}@rpZZBTpTL8KDI8TYc!LsG7!7NRf_h`bdFKtzT3dZHAku`U$i72$NWjhv?RtR)q ztdWeeXxv7un%j!aaVuAV3KDAE(iPG|7~I>l4Ytpf)l!z;kT_k-n{VIVi^v%QS%#-JNOW^7$*#VwsSxPG zGb_Km80aPPYZPN^TG$p~R8Yu151!&WfyCGSK`{15?$#3@AbNd#Ok)ODEIfiNt>HLoaOi$ zcEJ|X*ciiNU2eEIG5jKJHl`Ox0$s0;4&;r;ts;HC>2HvOScvFgbBC_F=EYG#Vs%?r zJ}-9*={1)~Vx(!9nEB!|-7;maLZC}M@;NnvMS5o2OuU@*gjOqFQ^WS@@Ub&@+p?E*eds~)nB)xodw*f# z|DLAS%yLEriL@r2_?Msi$v;osWUc1E4iG!rzozlEzvd%>E<7eVlKJE-dfod<7rv>+ zQ9)wkTEgteH!?PU1`5)+3C|cDoD&sqkLq; z{iMn%J;p1v%@EQ3s0q81ct#=6rM7NJ{~%Gk(>PVj4 ze@{_CLXG%!`xGpWr3w;w?xsSZ>%*~FzF_bV?QQP_c^nxY!$kRoFUY#H_bDn!_;v{8 z&GSo;Zb#B3kyL%Su$|nH?tO7oA<%W-X$;?ySD*Z89Vdy!fgxh7i~OFj%{ht+5}zD` z`FUS!GUQmQB+Sjj#ks}Zsq^q{3W2V)9#OnPCLtfY=kzUcAzl*MW~0QhmRU6Z#W;mP*U9YR{OQ41(&O0(NgQk$A)H1`rvrH=MFokw z%!i*{GLDRT6D^4zheydHUqHKA_frUTUHKHuj~8Z;F2-o8!7n02o5&UP>z%P*jkp z+j9`#ykjBxa5F>_*6l`#B};bFQgg2oB+#{|ydU4TX#p9#Vvr=fEh2==pPXi&zD-a; zqI0H9;p(p*Q()H4^i;rtk!>61%|Qt7=e#>m;72mLO*f4jRncMV8&2ELXFd3 zzrss+25lmAXDNk17v5b4gI|G%aCW*%uDh0Fs30+My&OL*C`a4^^%$0E^L#}0tL8MU z;s=TZy72CjW6=n2aq4zMx^dM{iV6}}YzOlC*P4>jiF)+TthfH6dg)HIG`K%6WbVYbm7WFByKIp7c{-dPS@efOpbPIV8AHDzKs479 z=^LB#6cr@=g57yue>r3DB~6wQIypp)D>j+#yu4W<(1mxG!Ein>NVK~$i#i_IK~X^> zq?6grPo zF0aQ9u6rIP*Uxv*tm+{OfiAqeWZy1AM9i9eda~SbiV703GkWre{a2B1GD=g%CoT&U zUmcFo>lbZR0$g}^$+2jc5OKQndFr^qmZE~c`%df5lZtI3(U0`Lq;+hlNYA=N54^ua zkU*Du*XBM75@x&Z&@pGO6I750EbhV&)ZR(VSL!`nOK%_1qMd=&;|&RpcQ7&+$0!Cv zovGf!)T|`?*!q`-3KAGWD@XbbhKQ^|C0NM{4fBye7miV6w1|tBsQIW2v#dHN9~C4p zidn8Azw{DaTuZZkpZjqn(1oKKgJI$~58<+{JhL>5<)|Q`MtOg?k#Uwb<=A@v!wP{e zb+lBhS%0y@(Ucwj{;%?GfP@-De|l3t5%Z=Zd;i(I0DlWz`0gY7k{Z25|8`ZG-!WU| z9R~@_Ly&Vahq{Z!^=h)mce*PCy3|aIfOegQ>FD~blfQcbDoCgq3ZD~Qgw34Q+V)G0 z8D?r>j1TtO21Bw(N8#Gggrpy~VW=R1(L!=gKe2}pduNl+4eKiey0F)l&nRyfvEkSO z^2)yvLj?&n#w(^zU-8(iEUiq;6arn?Ysji(5z z6hoVYf2XJ*p~hLdKN%|4ESyYNUb?Oj=)zuG_M);c`DHbSuFAVjQ9%M@Rb|%Jdp|MG zXEnWaWWPe73wv$({qvnZVw2Mrnl$4eMFk0r{xuk`Z4VGu-Seqa!hD557xvn6q#x)f zVr);+>7672PXHv;=;+!N0!67I7irUoFoi%D_S$l9_1S*n%=X*#;n*OGib5#a1Ch-F z#D|oJG`yjOLSPiU`ZRbj*;lk${F>&RtV>ZrLd_nSk{&JgnC8;P)y=rupJBXJ_blT4 zkkLhJhVcp>v&lI5O*Ne3kfZPgF`{AYJbGop-}&f5I=@;dKa)3&lp3#(UjO|SD;{i^ zLLEz%<)|QWF(QJ`NSH_(x75Gkw$nUTtoUa(_3hf?021i>aD4<{eO`XEc&;8(w9GS3 z1a_HB-OMWHqk_cPoI(I^hn|~QjfoCWD+MPuFa+?)iY$~=l}P&(B<_qniqc+O4`rU zV+RWx$BR}n3f-sw5P}L4Lx(2v6AuRyr*eA4)|-KGqDzBubiva?g+Ld76UWz9?n^55 z)xSRUDCc z-&W5tDSbU&urI!JyWs~x1&NiV$8qh3Eh%?JKk@^UZan{zTZzP!&_`rZL2=@ePYZhUsHZ}ptMSaSy#Jlo z+Wv7-lIV3UUes$_mb9#urtGJU`va<3*#1$m!l}4FF}XC2qJo5)g+1|6yy)q^hx|G) zN+Hly?c*e#Rd&7RNA&me)gNO;xBP!eP|7%p3KHsZ6x2%)1+^Oef$e56EOChx54?*Lhu*s>=A2_@Io41{$~K4)_ihX% z>rIYPRFJ?qCmHJ;6(u(IIYX{=%Tow+VGZTCert^qJAQs6x16?9RFJ?qCxfBlz0o4O zsTIxmGE*VYh1Z*$)6a_(2`5|7>gSgz*A)^t=Op{Yz0sokA3bP(!?6m1F1!n5M(*h- zQUB^d>J*o)+#g8boRhqxJjRGlorcrQ9$pH8F1(xN&h@#Y#jD4$bWfcyfiCRFWG-^uXi;uOHobkziK2o8&N&$jvp0+p{p1(&mJcYV5a`0* z)nMr25G{UnpGW<^R-mXLfpbnWH+<+A;k$hSEp~9L(o>@gpArVcn8MMbM46S;r}ZI% z3KBSjBr~LsM+?LD74)xCOd-&PPdgc%U_M$DtF?hvi1Z|=Ac1pE2E&WbqecD7>*(~P z)*2G%!l$;p2Wv%%y9wLr#T6qpRFJ?qC;496K2i+ryoYXH=b(%L(4~$U&hHKvNpnup zX-+vBDoEh_u8gK~9xk3gljEz&;}im2xH=$nOn9)M74FfGTY?EHNZ^=A?o3g9m@u<> zMq_piR0wq8JGDF?Nq*wz?e{c!>M`YQ8wquMm2hyVh#&lmUaPTNA<%_y-txOkKfT1W zgc2>rt7IA7J%)>tCWSPsLqCN;7sffrXv1fzBE~sVD~vUvU%Eu|*j2B! zO+yZmg-u8E+DpG`Q}d6JS*J$vb9-x&mJd(MG6wfd6C>utYCEPqRTLy}pBXv63Q7}G zkM1Ccr%zW1bnR+Bf?I!SLzc!C$}%RLP8HY84b(fkAwdNRj21H({`@OJJUAIiua=mb zj|93tcOS+NC%BU{^4gQDGT);`J(Fd$k{qX@f`qz?+^f(-KkfVZxdOqe$V)uO$_Nr~6LZA!Rx#gIlt-m;L^_GgZ$2lrU;Q2Qg zzLp9Q6)rrdp%yO`0$u8nZ;Tuve14sxRUR+ms33t?rHp5&5GkS>?xGHFCn*HFu+`-k zJ!i*?cUd!Nv)G#Xs33uNmz-xTFLHZwh)6-t3ohwIhLXgz`RLohoWB4c1D(C`<9T z(1rJ=e5$3SiA&>4lPeD|DVbro_mY}})sV_8p$I>cP@_CW1qpluka=EjQ-odOHnMni zF@-=E=1R$Zzh$mW&kAQrVpt<3%M1y8127mGXQv2m`;i>?d!Xc!p$qek42CW3l0{(Y zvXtdjq^KZ)Zvb+a0vSX9t*|z=y11VpfiBE3lIP=0lE}YlLoe2NN>D*UeVgzYm@G0T zx1(uknF@g}%+oO#SeGO*DXlB5?Y*6#f&{)B%KZSACW$U)y{X&B1`2^L%*~ObzKw}O z6nImoI$;DAB=8+qW)Hkd6!Uuc(0@C$)sR3JX2ci_dut>LuY)6K!zx!bRFJ@Tbr}~P zlqh;m4WWJdkIzQ}U20a!d3m4DsTM;|)@gYV6(n%Z!C=^3Em4el8b(8?g_4zmF3cX0 z-_GopAdZlDn#KOjM+FI-JCW-KWfDb?@L)QnRzqG-RIiAw$l5;&J7&tR7XvEr!fw4w1XS92asP=0PEqi&YLZAz?BV=x0;jBq$M zi~7%9q!8%B908d}|2$IonQWnK$_gbH011pvlJB*RVny+-)94w?`3iw9jPf@a9GXXo zmjxT?^NL%PoCYK?LQH=B^iiz%+#-jTOUqUXh&IF6dKsPI7A1Bc+Cayq?c}K7?_%7V zJm)@fqP9yGZD1Cl5a`0OmdvQKkx|8;HqxwXn>Z>+VEmn2KhKR6m#%H0p665oT{vEm z-_Bg_Cn{vUp!NSXSE4_Wzz9K^B{bVZRGU+htsL4;A<%`9pfWaUNjLEzvRt>cva;gG;x;N%xQQ(BACyKPzT zM0H0wbm87~a!zJ;s%V^fmBhsDQnLhL-^t5$v-#PVwX}VQ?d6zyK%j$2dZ@8ccb)mB z+x9$QpC4&+p$WNo$Da4y=tsW!HX+R-J8`nel?<({6T{N&#Jp3Kece)wqk=?XNe7-^ z*O!>smzG5F)ed4{uEt)y=%kc^^qed9+_9QJIrPj<64A$73BP&mSkLD192F#R2SbCQ z?bBvrS#Aeb-fXKvpiAA`uv$WQvFdCC_Px$CQ6rT z#CFPfc2tnSh;R9H4(TMihBaX;wp%F#y6~9fjMpGdbWL|)o4QU>S{Dh7vo;uI~ z$wvhVjNg}0la9V3t>#bKDlkwX(B-rf46(rRBkG~ou ziIojG>{Wx};C5nB`!)VppZ3!w!V7`f5abFoHD%H=TQEMwG z1iG+AaV?@ip=h07pUDHrOLd_W2Ic&7J7qEeb^y;P%=)&_PXHxITETPs{wHj4T zl>8{ne9C*D#lIhNb1pyKSswWVyENfbDu8Q~fyGIC?F2yuiRZVn`I}N7oDQGV&&O=nbWyoWDjBoB33=?B z!xP7UaxNx&%fAlf@V!e882_#mpTjqd%yD{Ox`8APPD&S3PPHbFt~OO%A>VVj)-?J5 z58=H*=Jv&0*8UD`L-4ndm~Sze54~qF(sJyRnJyN+edheJf1E;~tMA?%?)BZ-Y4qM& zvR3Iw)5U}g6Rqn92Z9O`!&^+|l?I=7)Q?Z@Li;pLjBZqp94o$+V4GlDVQuC93^Jdy zg_ujGq=zcCLgGgE9Db+1iT1mUUJc}t(>cV&#!?~Bg{>}+V_t&rI5mcryS`GZY?r}L zESqQitwwV)xqGE_h@MSF7vjriF};Ee;wTUzcO~uiV<&b{eKEO>#(Yp_U~^2QBX0kTL}?N6pJ-; z8;FUDsECP$g@lACf(l9~Dt32^g#x1PwYG(=*nx`O-RLpi*_`Kj&v$+o=X%axUg!RP zm{ohNnS1V7%(u+mt)K-7{QZlX0~x`F*~wdZhepjM0#%!8#j0k{_5T^;q3LLYbJ45( zXeZZ0_&5?!vASN6VYW>wzuwVVB2XnC z)qxv*48NO*>Xd~NTz7~1snoJMGd^*N?Z>E{&sNC)H-5W>XJTJ}gZW5PTAz^UiWVgN zZNk<0=S=fyvF6MhY}obf8;|sfmk3nhIf)tah2e&GE1&Qt?{B!G1&NMFC#wFL-~Myv zC613Wl&gG=f0=hjB2a}_!5Bl|)lj`fWpdb6tJSAt-s+;Ojq{HeuL91AbUKS@Ps8ro z*3`mm=Rvd}fmcLCSyc8gus;=P#F#ui5~#u~D4i}Q!_yGqS%$WEZY#~E0(1^`|q#zA7-k-e93T@XHz5p?>-M2!)zY^{rkA{EtH*|W%i%* zKmsjDl$;a6&Q$sRpJ(^q2vpTfp2WuW`A`6X79>)iPh@{`{`>pDF_1tNUWI@3#%qNZ zBs_=3umdSs1soL;sQUM-i+8Hd#t-`A_b26FQM|MAQK1Eij!i!674N_4e>gIY9YhNfK3Qc|+laCMgFsdDan@?Np#cRDXh8yh&GLERRUC6`I&;~xHUA#qGyQ)E zc-oOjd=baiw4YVL9mKzds-j$e@2;VKnoIcIwr968GZ$ffds0=jD!6%FTpYJjkCaIzdq#2|9bo2 z(~g9BkL~*LAEy`alpuks>-D4ci=f> zuBATJBe8%nkU*8+6jOa%=a~f%_?z(FT3;P=)F)r{@4pYUAaOXOzFIf)Z~CA6XMDpU zfhzna$^=@F_|eZz?KP`?0q60ga6Oj#A0N_}^=;W-S$}_D2M$zNiTZzkspT=yf<(;Q zwya3Zf4|QEFjEakplV%~CkuCNUcgbI1&Jr30@%uZ&i{iz)tq1-R(o{)0tmDqvE`#T zd-CP)dDlN@VZ0wmpbEdiGJzH(dV7s#J98=(a8yX33cu9y7|4N5A%Uvq)2g#VQ%4p+paqG($;H?Yi{Sr3pvvCgoH-^H^c_SC5>r|i zW}jPy7cj=)+G9k`?(+E-oFOmWsmG};Hc1o1kN($ zJBS3T{{45379?=)E02K$s_-2n6L=4L`h8GpZuxt@^Y8ZqElAA#`ar3%IJ$sqg#@ZL zn_W|~noKKzKnoI~>yIiW-o_L_paqG#W%nzc&J{FoM+*`@m$xaa))(~UL;_VOGG{7Y zwF>&Gp>F{_6Q8!kt7G>UG%rC566iaT?;sMWQm)6ToBI_sBSQ-k=-rXWKmt{JZ%$X; z9kvuO_dyF1=oOL2Kmt{z^s#F6?z95NKnoJGXX2kxrW%ky)q;Q+b$-iZ1&o0fBxD}| zj)4TKULKvK&Ppt3<%Jd`(C6^a2*$4(5~zCeGeW(${d)oDffgjt6C#g+1gh|TEE8x! z0zEqaPM`|k+A@JNy~Q=}9{REK@0s4e&-&1U#E_$&hvqb%RlvIh2~_>;>TuAcZ9xQD zkhp2lFujl0{~}PeYFunueWf4*El7mdINGwc_x~bLHTA2T>%E!<5vUq=v8n4I*S}T& zPM`&eYEc(muOBXG7LEj}Iz--bowuwY0xd|K-d0<={;Z(20TQUXQpa9-o>mZn79>K( zwp8-^{VxJlQ%em|Qid0_Dnbhq|Ni|z0##1iCMfSW7xcwJ3ljLf5+3@eMR;>9hU!n&4VHMi3a{C^u`-UXv#0Zv{c1j4-$IPhPK;5% zLt}jxaa6CwQGIrE*4Gh7wJ!gtOiXX-GhdCTO~2M^D;}gCIx5a1R-A{HIx>Clh?^|t zc@_S<*NF5;c7|>ADk8>+d0E!rwXz*eKRHLk&U;v0%5RdXdg1kA=62$M*p>O%*uqda zz8)26XhLDdE2tgp^sMpoiBb<9xx2~@&BULQB;wHS^~;rI~11JxK_dRax5cYhUI z@!MFLB4v^#Sq8MDK580oTD=ZCWp<1`vJT{~CF?M|m}Bf!L;!!-q&)L7ImxzJ2MgkE zgq2pgWE9!n30Cn7fZr0+@Rs_x3o}`iy)nw7!raxG!7_xRCwi;s@jwrYb(#J8skSrN z!fka0(NnWB)V}CNM-mdHNRAKQ=IZ9u3GC=?2Ptwyr#t(=+;GUwhr+`Ls2CxF1bXyD zc1=KOgH2*jx?T6X9tl*T|3N%gDcPD==4cB0yu!|$%>=5f9e8`NnE#j=SielzeJwdT#h^alHr*n}R&dmd&QqF79sLQRq;s%Sw1 zzmKA-%8Vzis>MyAmP=&?WpU1Gzj9JMS1a^mR-$@$Ph6tvG?#bd{FLO+U5XK8Oqu@$^&YGgkZElA|ubYiuC4Q3tA)e%qP(nV!y zyH^jYQ}l}-2~?qXNAwdmFGY|1deVfV`&ALk#eTQ^yHD+{vra4`(U-OA)tKRUI^A#c zl5{`Hi%gC!lCCZiDOa7Cjgv34eQo@GJUL@Ur!_Ac^*l);P=!aR)4gk1j$)LKG@{24 zE#-S%mX{aKdb=gF-<2HM<_2MG(dQ)Q^T>?df0w|DmYpxg=yR$peV*Eh+QoQjXhGuj z9!GZSvOoLvbCMvE3`Hq8(~}Nw>n#zeS{GB8?Q@M~?KVUT!X(d{Dr9vbR=b6U79{)+ zI#}3BCbB2y#wyJX zhnFLMumhbs;3pBN!aFN^PS!G`^%-3#wE22%b0rgIk-C}H$iB}i{L-;3(VOSqV^eLO9AcpWz9 z{ycVm(|Iw*`bK4Ggk3xGVhbe#RroB3{~VhM;Fb1xed$wc8cjm*V%?MZJ6t#6D%gZ9yhOI%`DHKVVyr3YxYkG zC`IXRT}j{CM?(t|JLlQ31MiNp+=|9(p$#7wqaw3BDCK2{M4)O>ur*sBsIf1V$_v88 zsx&Qk>qL8#CTnOxV(w}i_G^fNjjLh3pn&P|5`n5yuWgv$nEh-+W4m$kd zwq1uar>y;RG_mgO|fW{=*r=XkWD($pIZGVRuf+}0ma(Sk(jPvU+AUtk}`wh?2r zuWLzJiM=VZ!V8H&6`qrbTMD+IdAGdj?zGqX2CHq^v2WRIQc`#RyNfM5n3K&CPjvb} ztGi2S7Ib-(H$C6sDV+xrc6Dr-efw+{lwXV0FWZ7XH}|1_!;4cHMh{PBNKh~58RN)m7@uFXf(^*R|+S<#UTRyO350!Il*z6&^ zPd_{MV)g~5if+A6_mpLG23=uheT|*7s`C=G|Ed?=IdhGn1&KOc?3i}(0$XTqtVUw* zS%Ug}@}iO_&qxHS@QR4%Dxetotm#5`Yb0=+bN1}RzAP4UbS$@@XwOcMImKc}j^ZUo zmSgQwFR=CFjrB{?4;G`HH$CWhmte_)L`GeEwq*1f7I0;_Ain=DMxXk3r+_=65(4}! zRH=D(EOO&nwr{nu8cFwFmQ?r_(Y6=Iq}3g+=yva{!!nwv?D61GLCm!N%^L?bru)|m zQ}LdrY~KrwmGYa+yS8;;nH4fv`Iw2kNU;iRnpn3F7wdM>8K{*74Z7Wcw&{LL79;{p z9N4Ia2gH*&K@g_`EofSeCUmXu2Z=z{{>(be<%piuJ!L$qzXleifhDcUvT_Yt(4#K< zvTze?`FSe0|LDLvol9ZCC8qGHcPg-3?RK#{7mWQ)p&nXDwk$P56U(qT)E?l9?wtI z(i>frQd$+I+W`*Jc_49jWL>6g+Q7N#3b8CaA_7O{=b8laf}^Srqs95DrI|4e?kiqv%8tIW(g~l6|arNnK$qFiMPH= zc8#GDfvWe8=J{iEE-_mWq0jE|qSc2e?VbGyEl7C%c%>MR%B}PqLEN8bN%mEqDP_cS zg-25Dw-ZYoGgoO>d?rU))LR;9NvqNevt!QQgcc-j{w1EPs!Npn<}<|@rN95;(=xlV zX)gy#1gh{#i|1;A1zlM^hD8teCbS@N{D~85{Pcm6aM^f2s#XwvATB1c{*f|)D)|mR zrI~zCv3SKlG+grUqEGisk1_ezYU&uHN7!ymGp%C9MT&MOl75tr(HpN~X(gGL|K1}1 z-@i8`^E0hl>JJDX^5c9Ta`mrew6Eh9DYLpo5n7N4KVp$j^C!kJde=_V4i=A7HZKj7 zeBtQ-UezrxpD3AOyyq?Ff70^G4^fKS4s78)<0>tYOY>h-ViqNMJW&u`3f~X=vzd!pbz12~^=#5S0)@iy8*|>}KKOU4mzh z=Y(CgMPz^NAKJ!AB0EzZDD~S$qJ33!m5Fz|d;YuKGq{MMW|g<>o;WJ}Td2a`+oJ12 z+rozK)!q5M%E z(1B<59Uu{?!Xp%Qwl|m?${sDn52y7Zv><`~y>+_xRf-sv6e+}GExaWHRq~l@xn>4- zs4p*7NIr8sC+s>e>NE8Jq#fB7%B`~cN?qBJ=(e=5`gmptE0e#EBY+HoQdJ($^+a!u>;}G81{#kcgdc=GBFITxQ{P<-;vOQ1a_L&>B>BMuYKLI zl^0F+ln7Me5sJ+Fxuyp8Vs`5IRU3zYuUtP>HHQbpvliRxYkO)-C zXMQ8e#1LBJ4c|7eB^}vfrrL@5XO5VEdK{~(4mh`hrHeY0bILlZ){_>pLide(USBtv z7L=ct7&dv7 zr_O6?(x0~uYX9>otXIh?+@V@s5ly$1{c1CnuQxYS8_nCpDi<{p_a2xSrfn`wEuY#F zT9EkST~~D+D|~V`###8np_YaZQ`*o58)B1vqo)}t`!pew!ON4 zNERCu;4j9Qxz^G!&${g`tF{n6i}T(C`PJTb z>b!^x>@VTVs6NL|y>Re6dv(F+%P{L+)UYt17iAWA;z*!MzE*d~7dL!=*n=9bY9*aH z5^`O&YZk=~OJlp!rJ{W#0#$gQLgfG)U_%g*EtZHe9H}s}vp}8trknk;LtM>eJf%*PuCx{X@ zB@L$%y=eKkndy0;sx)x%A$v0Ljq3S!|KD}#$g zFS5DQRz(XEODEf^R+TQYDvOOBy8kL?Y4A+&rgAxfdL&SVS6x&wkF_$K+187k=e9V2 z79?V4+p0f`Tx84l7%LC!{j3bn4)&svC-Yp9Ko#D9QJ=bHDZ{~u9`t>6NA2fK8@1^D zlWa@(hP>)x8`by2DW-ebn2)S#twx)(I$T==Q2 z^ZnHRpYCeQUieZ-PY;Pe)%*`P^v`pzv!;FOi!sb|N*Pi{ccu}6ff`n*U$w+W?K$l* z%lTC6|D1W>Eu{=kc^8_UJ3=}SB+k#XQQti|#@s7Ah%uDmr3{DTyV8*K-V%W-yy{}! z{-lJVNuoQY9$2m|{H;?viXEksVn-=5+gAPDX&dW5!Gyo)WUCIIoyr;(E+NKf{np%Y zZkh+(5%E5!+UnHpl*MvaSKxoWv{6s{?`QpHl;yw1TdR%4PQ!)#orZTeN*k7Wxzow8 zBn>S{U@d=f2WOZW8u@ggL&w)^b*h-CA$vBn!eY-0tC8T*ib~KgtPGK@+S7^+tEBTl z!t;r(T5;@Fwk^=OOV)Lgm0|GC_GFQ_QX)`=S3&Gl4=rnmtlN&1!3#8uZo-~=a->t` zjn)Q>cWuckc8P`-B#u0_SF=AZU@ifd#hzEkNkt4pY&(;mZjD5s3a^N$TyImxP$IW2 zotwQ%x>iWYm0K)+l`?z^Zbz@)ua*c@;dK*L9qq~)?wh(%Lh>vr#tY9W;huw}i419R9(BtZnuc_w z*B=LIXhFjKuexgB>2Ox2OR^Y)^)F{w`nChjVZ$W?Rq|1doK?hNvb7iGwQQt)H5J*5 zGo#qM89f>HoW!FQ`?Z&>4He3Er4zH7O6P$@JH4a2I?12;TsQ8YPjWA72s7zIVZ+-< z1gh|yL@m|}R)%_dvC@8!Bt=tU#T$%H5}u-*l7@!MdQyezsZtaY5^|NB3IhrorbYE7 z6YY&epbD>usK7tBw82oh2ZdM`lCBjJa(~XM{mK|-zU)RbeM?CMs_?pr75(5wTE&Br z^tDcqit%X}4~0=r!h3ErQcIZ-LAHhz6)i|$WR-~I*f~I>eiP_uW+@E`RP{4!sh`n* z4%_~!m$-v*uZn19B3^Wqh!@3ZOpLjdBQu?iO88 zt|lLl2vkj6;iB&wu$5^QRY9z&;iu;H3ZN=t474B->M}I_)#mN&;dCRh)%U6T$s&;A zf9#Y9R5`^o*Ka(&j9GPDD2NMd{L~rqgQ?Tc%^F&ec=O6Pz4P-G?A%-<@#^s-)pbEA zO{$V45vY>yVCV0?DwU3)d&|Q$v>>t8X>j^G?_{>NWp6RYwKuuy&xw<0^yMZJfhv4@ zg!iMwK=sCv$+YrRMd`Uh0we20HTH$G)v|q~DRpY5^z5Qaj_b=<7NJj%o6Ex&aA_*7j=%y`B^1V zH~9gp(yx*DI^V8aMEk}=>CyH?i9i)T`Jzhm;+yIqlL=&@giDdjNbH)JdT4ItM=bcX zag4_{K5ChU;dCx5Q6f-_^aq!~3Ln2@)NLr|MI7 zq%zCBkHi=iW)ITN<&2`up6L>SDtuRp_tp4Bt$S-f3RC=11K( zv8;_yrXPYGgRTx_@YA%=Fs12w!o;JJpQ8B(5l$)lIpjy?j5M?!LFu(1L{gbzb-Qh~|89B=uS2CK0H@ zXH2K-A9Po%Uu+27cJ`dr5ak0z?rPrF=>2UTfBY%{iwKI zB2b0Tn3%&k-PJZc=tIw6Y}L?$ggnzPdEcOwy*YsDKG`V|sKTdGd^zjf)V4GfGcv>!>5OE^Eh}hR~+5;To=AhXmc!FSR<$99~uAxIz~Gb~RV)IdTB~{1GRugpt5? zqE0ua-B&I1fj4zr5+)I-!j-O;2Ya67Ih?b7?~ zxW^vUYRSv!>6$j^ ztDXEcfo3cztX+84NMCZv6E>lct90glDmB*Ewtvn-j<*+McyEc*-VF&O&o}o~wBVWJ zH5BSB;MMmslHz3WmfK^F>cAT+covc>Or)r@;AwX#0$%`L*EwNWsYxx z1YuJ(M}I6gkT&<-%eSY5rJLnFW-d4VII5h7MWkPRdY4_TY0Q;*ImTOM0V60O;Q>br z5;&gdR&eC1zG|1jWNGz7B2d+@Wn_Bb$t%p^u(6lv)%z>dd+U49GZ7z!79{YBh>X`s z!aGP_^mBo|hF&i8c;XW()@ob+XwEPCQNU>{=}ANay`Lhch+ozM+(*){RX4r=Z<$C0`D92G4{?5w<7@3Qg{8yaHtKqj>jzt*$iboA$IJrbyrpOUjVq1yGK z5fnPDGD8az)wJpQw&73M+HhkeV4X*#HCi`G#5!+~2vkkTYpm}R{fuoG)n5?D$M@52 znogjTm#cELAd$*v=&$X4z;2WoA&7RNq(yfLr^>y$NCc|3Y;e|>i+#juS{XZlbv@cw z3)~V&Iim9$T99aWYli-4ncHl8&p<((>(8_Ycl>GSvTYK9s_5V*`c@n7up|HN-s)Z=V(E~Jw8sa`dwllJ{bF-Uq3NhYd)tdjaXNdDtz6m-`e6Bn_@eaqv}ne zz50g9*{slPK3fy`-ImSt-hDEd zc@<*>opaHSs)==FT2Qhpp#_Pzlc%OXFTJ1HOfeE}C(fw*E7d34C#@s`Rr1>>EZjqN zz1@r+?Q@pi)JOzYi%y@Pae|G_H13SHj_^?LtnEnKqN+;-s_@OH(2{{AQ_4yU`VqOyaY#J>QsPeUKsV^M*O_^3I zS)7Nve@}Jy?%ize{%ArA5>I2|)60bADV1W3#IWd#Y7L7#HuuD2i9pq#ycYUJnf5HF zzcG{b`oeDNp;@K*;4)E!79^_0$E6qXt;0Od7>PME&Z)^UjK{i*w;cQ}RNda&Lf@Y} z*_0#$xpTj(QR zPhyoX7-Q8uZo8}9zAxm5R)i8-khnfzdit_Ek!+F6Y(b=EXQ`(G_i@+B0TO{K>m$we z-`CD#i!K@C$o%zgYHY@FZc)^q(1OGuhuHKWr}-?jnK9Doe#~5L+pRcd+deUy$F30FCjI0vBbI&o_imn!{OUa3Z79`{+vFx;1?VhO0l9?MW5vVG9IYaL`;j`jq zFkW5H3O%*aO}4OZyCxD^kih3n+`)y@v_gAduxszaBm!0Dn=|yWCv4eEYvUN(*LM>+ zOU3xmjuC_wB=G4GUW3KaT4O^~-Yq*sB2d+KaEAU>Za3y&WxRuHPjuG0o$JA02Za$@ zkih3nJiAttv=U{e@t+xi5`n4)dFgt;+7ay9a^oF*)3k%OB5of4(>sXJf&@NqB1&&= zxHjR~F1~WU=YCc31GtDEhnEt`0R>u!%Ev><`cn|Q7!H`Pv-=s?zS zl?i95)p@+WlXjeiU!BV3x2QqstbJ?fLiab+m)?m;RDB<>cNv$?cC0o=Ub4#E5 zJC`Mk3JIbs`}dvN)4@S>wE6&s1gh|hD&{3+4{G+a{i$WCPtvy*iFNgJ^x@U|>m!Ko!m( zb-EQkx!UXrel(`i4+ZaYk8GX#VquQRF73_n-Uwgc*1K9>*a+HO?l?mW5?^{0QhWTm z!8TtVERJgT>Py=EEI&&7Qd0U`sKR?Aa^g(yXs56ElKa~}94$yJeO*Z1yz4S6{MTqP zM#Wv(+VJ|mG`CiqM4$@qjmRtVxTTHys}Btwu#=+&iIf#4>ZN{XShW?#7_VdN&uKpm zUi9Amj6|Rc?~T}xI&n=ii*+Z@86P=XkXYzts!kKRK#xZl^H@w@ozh}sT9e=6B7_90 z@NSAXT+7SCkJyBAOO+$EAhBeZsp=`RYewd0*GxElPz#B2q0h0EB?49QQ&QrQh2iVi zK4foxNX3{NjIzPiq*xo2DQqa6=|g#KHc4+EBrtwPcx(H9(bg6Br6Oe#Bm!0Vgo=Hf z;yT0Hl>;gL?iM{-kihsE(Ld_yXU+M%FS*PPm!5W1;d3l{TKxE}_3SW^CLf=}(1L^< zO;u^ZC#_A_!8EGobBRC|KF1VbuIY$c;a+Kco$!|4QtUJZr+%FNR!sl4ztF`{7O`gz}KA7L*Xh8xa z9Yy|NwO5*bIYzhk{*(w*;d3mWE0f>ag~<)6-Podp79`{oQ($%YI!HC)|dOLHcamIzecS?r)XjTZUz z9gM&8&sl4=KQXp+_=Pi_e6&yB+aZlj{t(Mw1nkp0>hvtJdJMn6D_8$4VK1v+))-sc zb6KW#s+|p;;|&NcNMJmym{~T<)<#-Yq^Z9|)*<{YRAH2^@F9D?*N&YjMe5@EQv5Cw za%}C|Z6*ef3l`LPr;|jW3Zs98*ZEzF)@)HZimSz>Gsh!LJ$O%lC1xEP)!G=jyuaZw zt!2}a^xj_~v>+j$M|bNBn*BI43hCQMB2a}9&0@DN{hiizwkdToZz07xBOymF+fFwz z6fX9iU*F^+5vamQX;JHCo{533KH}En6~ee_ti2>3Rr_1-w2a`pd|&hS(ili!gt_QP zU+;o8qwZ_Iz^}7JpbD>{m@RF~&^~*=}Y;YGl@VIKKa6b^FmIzc~_K3(zS(L8nZ!Kb#*9J(rGDzTBRCt{u&uRDPU1TfxXo)}-=4^<4gI9aC z9VK-UMnAp^*}SD$Kgj>8xJw)qe$QjQ4{xE9sv zqUxT|JkJL4UVOMjpbB#x#2#eLo!VQ=nS9`7KPjgH30#Yc6=do$ZGD-|+z>NRB2a}- zzE1b7Ns6|u{XuS$JV?sTKmymIqO0zS?b`Lf?($h4eIx=^_~eV7AGl#pKj{%upd0){UC`z z75XnlZuk~U3N6>3(r)gM>YQQTK4!>^sIW|PO3v#{EBmgJs-Yo)8TmS0cIbD0u#N`> zZAp~~RM{;zVZ8qt=952fw-GstXIHq8=foErv)?g4U(UQw8(NrFOm?MLf%m06dL-oY zSlHq#ACTrsR(4+{0#%sxFREV*dCk?!?dZdoCmbzE$mj83N(KR6Ut? zR~aVOgYELygMPwN^I70yUgwhMp4CgD$*pOUMXChlci%q-g8->3MC*~cs~ z`_SobUE0a3Z+D=m+fIZQB;+yr{&~tHZ`PnZR~sqwzCvL$<|(pv8i=eNIgfr%$WtD> zvo!Ur*GS5WM*_3g#T#zO2fpN*IXRVekqA^_4!_7)zxIPaqPKi&rXpqcBZ2w#VqQ|b zC^=tv&NIF>lL%B{1&KW!_9$({{>S$G{SVibJNU8KQPlKsltiGaM)_3bvDlT#%HNgwa%DdE?lg)9 zieD63kl1={hVn@4U>(cf!DyD=)fPb_ta~B0LU<;w=X)l?Vm|Uib_1yE_O?=G z6I7LbRfs(keun1xeum7!w|S8DAZj*d8b=EfW$NEn9tq!4Ejy!ciRGQ=`=<4!Yg6_~ z1gfg{xTExFcAg#2_Y|$QN$0Km^r7&H*Em{`nD{$YnJ9Mq9P@Ykx-8$!mz?ZO8=IIB z5~y17aj$Yl>>JJ%`-Wo0l9j}LkGT=MXH959VtlK3WvK9xP7^*-(Rs1+WZ@}oO3Q*A zB?47`uj3VW;TPSX?-$Mf+>yszb)x3Kn-N-&sOj8H876kgO62d7bzWDWPx)4n*01X* z5vXcbq`7ig?6;+h{WejrZ=o68{MC<+zMOCftJz=$BE0{`xbV;Xsqg_ZQX@&sRI_fAR78cS$F0&6OWc!o(C+A6zp?jMMiE+&z-k*h-L(3tyhy4Ouk7hB5vbbOKSL>guN!Ng zzq_=+{}kWg%=j1K<3$S+SaU?DYoqMqgLX{d7HdXH1gaK&PFIq|?$V?D-KF$FS^V&o zIR10kP(lk5Sj9zj+q|E`W4yNUs%M8t1gf@;N>_Zu?oyfj-KE8ikMSE1Gx&f`{Rk~c zU@aRldp)+D`~JAgmxwB6NT3SmU1Hy0#!+76(Hs8!SXXIAh6K)0M6^hc{d|a1G4kls zRw7V^voql%^UmfTgRSYuEf+!y5;)fqZw9|CUdFx-O@C@H5vY=9eII-;@eg+$sYZ_) zgcc;Qa+AnpZGM@5U(l_@6?sKR-$*!h|Dk*}Ftk9svIEzNh4kZU>}%rYf^r5@F_ zEGiMG!s=OKhxb+k-r9bVlHfd@+ac|=bnv><_R43Swp!Hati zO<>!f$^@!fS8b_O6!8p+`SA>YYQ^&O><#Sl%5Xvp68OdtyZU2#@R6tAvo}{FBmz~h z-?vcKi+F~I`SA=ps!Zc{O)Ypg?=V6O68Odtxn!wbd66qE_~@D85`n54+gm99BA#J! zemujv1yOuXPY+&a>v%#768Odt{`Mywd0od?9@|YOP&MAIg)&RTGt|zHXSnV#k#|p= z%loH~BeWoaZwyfl@lty}EOif8YmSu&R5d!#TrpoakFCs)XIP;N=at7AxJ~a7gcc<5 z_b+_N1KfDnsmFZ#-oX-qDtRXJs#+NTz2^%rQnoLl1qu0GQsewUJ|@A6I&|@n2vp&` zOGF{Mb8?mlRN?$ltkoW@=L_SUMNLavX`YA# zzA;2hkzXpOL2W6vNC}BR70zmfudm-3-grX?I+T(d)apsjmyb&X zs&GE9)Ac>_j(_gtMf+#0ljiM6pwB_%u?+voi!b!1RC8a6K$W~=St{OB{%gJHLm-pZ zA4te`2Tc|irxGSTsg$pcM4$?5H;Njj%PmP0)!5J7bk?w9C)P~GnxHyekF>(nMO4c= z(Wi}6`x6PQpQ_UpJNAVKFA-6!rMpQ4s_MV~qihwq;R*S<;a4jZqB$|WC}m5Ch885S zeyUD)GqVsqjOk8ayU0~&vA%4VHace2I*aMnR1j-}F5~WV2P+?PJFrwk3lcQ$rt(Te z;Jb+ke384f>M}1md@zNbi<1acg}l9?bh~$*^~}#dpVRLEcUta8>5IcOv>=f%b(dlq ze4Aa(k3Daeu!HLkjHOBrog@NPfr-16Z6enFFA?i5RulaTlVx;YiWC{3ST!3fWe1s< zvktSOm}y*3k-;;4^G%*p&5y#rK3CC#gj|z6!s0NG>m|I}KgwxHpz8Rl3`G~7z^;jW zEHU4`n#hM#3#D%DEH$(sfmPZ?OwqPMd|QKX+SkZQB2YE?R|{pk$mdMW&*zN%FoPEh z9!G=I6Ey7Lft@`XKZ{k`i~P6|B0o;#t5x*oF{{VZ{dZv+T96oVvyqZ1a^mXb=fo9H zRd^XSoJKTjFA=C(f4`B^Ttwqf7t#2lPebxemQgW`ERqv7>_mbcN@|Qvb=@d(;wI$h z#ObYkL_NR=I`lqFLkkiQ4P(-~t$xJP-Zm0r)ctr2vq$w+duu~{AX;= zdgD>8iSkixuSL@2a}71LAc0v0I$h9gA9d)`D5_etkVK&BQc^(rMa!3LXRx~%V?N7K z1D&JDto$VvEl6M5XHr-LHCq_}s&s2sMBrw8U z#6XrEs3v}lq-}TVaU@WMnF~5yLc$$&{L=_>TiQ#?X+Q!a%yqiFMH|&6p&`^acd106 z3iBIux)&XbYDanmkj`e8lq-P*Mwp9zwZ`V!%>Kja(xkf*fhvrX6BTn?5Gv&K}@uC}y4hy?ET>vS`o9oI^kQ>Dk?r*U?`)?4;u#{_XK8o^`!U)aMje{W*3g0kR;duNoSskF{E#4eY`R$@ zP!+$>MVT$CcpS^G;&I-}k44uAqLU80HMAgs)i#9ZF8Pt@t}u?WKJS+ZR9(?6 zYjCV}M~Ofc=059mhqGsBz8wSU-tKS>El9`}9S(e&ul0!>OAgNxBmz~KEiKmPcNS>9 zMR&)IqPrtnkid+5;d|Y`Q_I>vjHZZhEfT1bv#`qqp3<6%@A)F}Jx2=?a(4g0!24Qk z2_G6P{0vB-3Ulg3^(38%VdRHy)GBzXRP7B3xjtOw$;Ay0(>u}rO34y|Dy;k_x_R6! zO&8j`)BGJt8upLD4nDGnCFqkmoemWpb^gqeI?*73eiV^|W%7;tSM5W`Xof_f3cWj` zhR~E;zM#XHULJooJB2`HD_=TI_$UP8vn7C)Y^? zs&Eflr`z=S05@wBK+)OFrM@yq;Os-h+(n<@r$q*j65^!b-$E6}nuwlAUw87czCqN- zb^t>Q5;*(N>FVe1i1v)>}AQkdS9GM|@qmb(vu_$NH8;pbDc?M5gz+LTq5l za%J(ADTMt?u}djtoQnF1qf^)_eHnK3T{NKu3EV>xPoht6_U`5!=2B#eM4$>YPKAH> z?iE%eW*5`;L=jq$z&#}4(;w86<%RxW@AWc)D$F<)Pf6%S7P+PrZ&zV5p#=%tLlU|A zGrKXj$DH?W5GfI;!i-Z9QxtiQy=~ElzcQalXh8z^kVGxkz|JgVRvh2EQ+(4QD;8Cl zajMfzSbK_n>AH|}HH6TD1nwb;Ox7Fj%-1@Ncj_4^5vam=NRi`yJd6D)e4KxF9!qFJ z0{4)F*WiE~J8C;LoF!iT&hJ+ek(rQljs)%@iP}4#-B_^>rRYpm zFNr`E=85Zce&Hur-pNXoQl|@{1qnIIqT8Pi?DK&7WcA5aB2a~y!qe$WG6#<&sav*&LBQ^r*t!0kJdMw+Npo)&{9!ZGaXeaGyeWwjGLa$0p&_`L(>$ zfGXUx(CM13RJcdE@#LV$yBSE}?uqyscru?WDtn!w2`;frCwxW(#!X3V{|4`acsHH@p3il?( rzVj7x%D&p0tTJm!yOv1E9dC=zElowM^q^{@HZJ}xRN)@0PWS%+16tN9 diff --git a/data/kuka_iiwa/meshes/coarse/link_4.stl b/data/kuka_iiwa/meshes/coarse/link_4.stl deleted file mode 100644 index 35d19218129b1619d65c1b7cc5a83c906c738cc3..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 210984 zcmb@vWk6M1*Y~|l6uS@`6BP^)RM>0GDJa+hf?|Lmh#&|Gh%`tGcA#RS$Lh6IhUG5de;FQ%$w_%|UZ zcC{oWaq%CsQzuW#R^=@9fwe2jAH((=!gK#hkx$%TWC&{sq0$SLUL~+c5tciHOAw6nX%?-5<7yVuS;{y@@SkxRSCe-?+hSePSU&Md%VJMgX>_d&KYI$_U za+R7=HC&vYqVT_bAeEtZ7Zd+I9VotrcC8X>8L6#F4U2UAE9KaNQjXK{uUKK?UpZ|^ zlj={KS8D4ojtM6IdpeLxEpHj6+z?hvR_g;1YF_K&I2O5eW-Y{A5TPdO&A3g!C0d|=DJ2vm3PZhQ%kdL+3)jBQyk76^H-$xSjP#*>Ta2 z8b9z>V`V5g)lwWT`d+Cmx5&r3;}v<(8FyOF%vD3EWm2pv4*&7dr-3~`d$b)T+;TOx z6o*wG>f1r&e36gs!F_qcAyXRJ*hE8MRdM)_kI<4q{Iqc)d6RW)6}A+IRUg{7=%F4H zxZ~VeB(d@g4S`j~;Xgi1rzi4RZsWkBeegD8#KhKSfxHo#Ofbaarlo9 zk#Zv1pdsbhQXDQS5A};sX4hr4TmkoVfDF1xnAU>s00mf(PEYQEUYRH z|M5{&OQ>jr>RVK;8HO)Qaai?HRC|hi6xBq-*PvLXJ`1ag!+(4f)plwQ5$e}Kt%(L7 z#o<5s^FQA!Ng7+fD}OOCi0ph@m-eXGnH}~y22Wq+z?*&@na||{7&u@a?DBSGITubr z$-=21Nn7Q3ZngD1tGMA3)OnfC4t#7$&fV)PFZ}W+Y}>QDe0g9Biw-fxQw1VKI#GDVZwE5S*fBTGHxz>X}aD2S$a;riG^y&UY0 z9t}5~#xlRo&0&^_GwT(ShFfv5L-jz`2H6+V9f6l z1ji(a2eAp0tROPL5B?P^$2gv9d(@v@ zbTW$Nr9vM;$E(cB*O)>m)m8)>a%SuCF)yB+lwm0;yJg=IM zAYf4p-!|$Z94c!=umuwz%0#dLa!tNa*IN+XVqaLj1aXDL@ZX`U;l0$IU<)SBB}K7~qvpx`x(^n_x_L3Y zV?Y5|obRL|uxeaD1lzvgogDadkRakkteV>HhxJ2cf-RWPrlT~E;axA>fg@wuXb7z0 zog>(%*!Oanry8rNM`C!@{&%6)dP{;Wn85iaNjsxr_@$v7x}DPIRmy>A*5a*Ro?+2b zlW&sbujX!}y|B%U5S%}lu&NTrZnjw?pB>{UV%1cR;oXkRgGjet8Um|YRE=RYDoJi+ z>n4cv88Q4x=6dky-i2TbCYGFxV^i+u$+s$Y5yY3Q7@l%_Ep+qiLa@dAb{s3wH&1SU zfdYP#B=M;++;{yNkV3RRFrj$Hvyf(s<;CrZ@Nuk54EH&a0MnZG)5Hp^W)F^KJ+?T@ zEBg%)gxP`^o_cORtUu{Uumuyx55_agGP&}+BeEde2gLA4)%F?AaB1WvBdAYb(gl-!lEt-Y+L6l`Q>MKftxeq*>tu?ccWcT zL5z45&0q8xkU!GFi(pHG$?@#PtRp&kNl(B}k|fVJ(fsJ$nmXqho*EyR2)hx-j5e2$ zFK_NGe9WsF!_QY9DC^G;)eu;vO~(or&2O%lB2V)4CfI_BdXwW=Mfa-mt95Ftt$!?< z8<)Ez*E!>*A+QSPx+FE35X}pI^<=4m-UR0lPVL413GCA?UB0oXF`_08iQ!XTmSd)E z1`=$+#9fCJrcAzOKcqrKLA=e2=5wA!GNZtu8Um{_dL^)B_73@_^{S8kmm~S13TDc> z-owZn-x${4FHoQA(g9XAj$`*5%KE6G9f35R#Da}4<$Inq7sRk$6FGCOu8h(TC)k3C z6+`0Kpigb|>-u&Q#E@4LdGE7d+2#pe8Um|6Y>H23u09wlHKlcTkqHRvwWBbFh8pwdWW`+0Y6E+;T8pO2hRga zrPz)dADGzvF@U)meb<{0YAk$wJ2r;5Z?;o`8nTAKDjY*eYTI=vuYOJ9O@CA&Hnu}q z)0_s(hMPk9rK8!#DHU0Rgc2~&&z)7ZZO-C%mR!&1;)xsujtfjR%GqF^CC`-Kfg(q*7KK6AqvHIQ4kHwjn zXFWSN)WlHC!+rAM_s-r|y6VjcjtM4i6^>%Mn`Kz5x{ZVn>N|=btA1HIf74V$U==PW zNvhD(pIcoyqpWMwTvLLWSn1)rG!{&_KX71`8aS|O_EkizN)PG5 z?;NVnd-Q&!A+QRUjU*+O>CNkxtHUq6djr^liPL$#*i~Iew!B$&;Uh170MCC`m4}`w zK`?<;+A?q1p(C&K(wdt`&4BQSmTdGf4>sg}InB6jM?hD0-mVAho|YoUoV8n7@(TN8 z{(DIp)C;j>mYs*N7Kh7eXq?f2?ge^usmX&T*p5P;YGRl>Pw!lbyIkKbV*;x>-y6d!lr=5#v3Rj3w=E^{>opY_TQIS5S0wvt zQ>usvxHghQ$Ct{CM;!oLFtIZ}nsr$6PQUZmC=o0B41az|zO5XYenrLvRyFAr!)(@l z(*K!T8eDb^A7A^7V)@r~8Cx)Mt@$KYJK#bQ(X~Vf_js{S@oLo_umuyYo0Hj-_dE65 z9}W?*y7zM&uTyt}lKj^T853AF(K3Y%S(0Dmq9@%M;Qs4Zwj4haGv?Y!CnJy_J z*2hQk-}^I^LpCmeEts(QoX(;Lj?*99)>p)8AdBLQZO19QLO;luz^X+HGuRJ(T#*lF z(Wibr#!U&m^HIhYOzcm}WS7iG6cMk>$MMAnEtJ6h{Q+Arv1iI;*8IVPe7imlB3Ap- zdcDqKjl1R9{i?fNCrN!bByvv=BldkteZZD! zB%94B9p0(7cz59^Nz(3tiM+$b47Re_8yQ?Xt61W_GftAhH5?G~8 z`ODi0d{W=7`aPfa!I9pRS@oxtbQRbP`PA#l?0e8I`>lRKa+%~z_OK1hKhP;x8o`I+uRmDuJ(`PB?|7zNq1Y54X0Dsw$V-H$nrH|-lJ4j z^J!T*r&@WyV-ZPmn;6IEo;)V^+G$R(1ruw_r?JG&rR0!RYCmzn@Hp{`2)hQKOq%AKpl z@eUKqLeRo?nv~--Dfg4v>tvlge?S9~j-Cmz{BD&%IfM~{EttR~J<%hZ7R%?gvx88l z&Kd%%+IlB5X3u@xm&nc@n<|HN>;!ncE5@~##au@J zbm-Z~K{Kw!gauDx4}M0;>xZ`!J}xRTJS^7)a^LmR5Lks{C`l<@V>w;!0al^1W_*r` zlYx_1(4|rGPkk%l<7_}I@7%NpjE=C^5Ll&6d7h=HyQh{zL3v3t-@a$wD3)*L3MZUm zHM8|%tkx`^zw}!Mw zS`>!BXCrkEd3dFG{;2l?XuGZ~!4^zBKIO~ijr4|s+KGaw(kg-X4W15V@{a;0u*!MO zDE7g00@U?V=SBY-oxtyPNruf6@&Q{g;Zo`jDO#HZTvyv53Nm^;*%U<)R? zR2a#62ZezB*hzx;Jtu*0JLv;v&bt8DLd!F75+NU{wt-KNfy$GAx}iToB9qCGztz`MMhoax|+w zFLZwFjQt9zcC*jFR(^W7OXOvgbUE!}FA%d9elgQ)aO;}FOc+IMnX{tZlQ||!q6q|poU`-vB$YXw0V9U0I zYb=;Bb@OLuI&z3^*-`iy6q3lho!+4ze>h1?AQfHCekNc?82 zp(Sa{hy-3fKbuYNxm#nwgm$&>(kStD?sK2nbxN0UOt7k#O(@eZeg!w@l@YOWHA&#l z_IzfIJyT?C!317ilqBalar|J57Rvn8Fj>DdiIsg*gP0bG+23D@EcHq?Qffz*yz)mp z+h|vnG+TI3d=1RRnwPI%6Xo^ZNR0&(t-D6E`rnMm*Z94H`1UZ4hgmmNrdODxA+T!T zz9^Pi)rk0CVuH9iJC0j@ZLZuaovn!#UO#oQPi9R=nv&e1g9Y(sMI3)Nx|y`GS>#1hYVK4VR3#rJj; zU<)SjYOff1HHhbP=G0b_M(>m{fmQd$q_OxtjY-P(vcgCC$arq-QBiSu@oI{<^Edw?n(SI8h+aeDxZ{hhZ1=nx1g})%blg~x zYVa{2dXb1#w}!F2!MnLkKfE)+7EG*rnZ$nC)hBna91(<@Z8Ud$+M6xj>Zc*F%4gCa zA8TEg2%_+7Bo7{4gN=?!BiMq8oC8UQSZyvmCy1l&5!`jxEWKCie1a{QIDRmiIgGDI z-d+D8h>wNi_{~N$_a&X(s3EW_uKQ$X9Tcnjm*$(n z?J9wW@NK_(uy}R|`@Xs^DSOaVw8711ym^~RySei6FvGw8hm_6DJ6V-=rxunbhMT?RoJf~ zuu7Zq3kUl0-%eZM`BoD;xSX5eS>3jGh6mik5dN!T2dJ>jn>Dysha6h1&N`P=Z1@%n z3*u$jp6=>DfUPsDLzeyO0aasKGpEAZWO2oCST(CPyYkDFgq$BQh)PD3`#Rr*sCF&s z?X)h2=bmZZANn$oO1pYGZL^Cc}utTCeEA)kz;)D-D5Fw2=kdeyb5tPN};r_){DH z`BFpDcyD`(Ett@zJZ_2&pOWTFdV5$>kE<=&oMC0i_PJ?L)2oqKoW zxf2qJeTkM7KMSk6buwpmYac_w{n^5YlGTY{JC{T@gtVa8f(h(TlE%2U<8?=5lO5&T zXb7xIO>Mz;l(`HgF69azyZQ{}cbZs`<|BWSGToh-Q~5n`=IksuJJ5-lc)_NB3pFlW>36HS8^xE5 zEkkzk!EXyYHPfxR1l9iXH2Z?uY;r^o}d0dU><3n@x zKP^gWdX|{b?(te&A(BTXiXCAtSsDVXaQehJYJVvIwqJoKl{aeAfr$g-2QnAi74WK) z+6F7$8qJqg`UX=kp3x9kg>zlZu*Ao6r-+sE@RUjf_qOqFGwe^2YL1KI7vF`ztUaLw zTQITY{ZRHQW(F*`&J?jaaWR4?r_BZF@(c}uRZg1*vEz3Z!S2*-K^)!@#x2*Z1mlFo z1Y4Y<2C=A~i=kFtwr0#A^2#=hUwFC}6o+LRADF0?a|)@14+p zz-kSFRXE>7?v9D#4vQzlzV&0t>j_>=myiZ!9mLmQk0<*bmIY?I<^xhR1XkgE6Lt4!0=F=?g~n;y0FN#4 zm{U8t>$E}a@gjb(b4Xo+EtojEVFYWnItfaCRNp>5MNj|Bz=2}kwV{T#8 zx0+@`$)>)VbYLR)ycfGrF%^t&rwShrPDb&5=9#d?eYA$aDxB+LZQ|i@e$}Q1X;kM6 z`D8kjJsff!s_KHkrgndp{N)0iHckeA$Dzz>Z+YUMq3-<%R=RTc_vc~attJ%rUU1Jz z`>ky`s1NVC`v$bzUt9C##Dung)$BuW9(tr2ncyYfiKu^tRrs4IzO~g|c(0Gu$)Va+ zv^@aSZ_}n@l2spGSgI455>-P(U={veiEmUNSDs;OO}dq?K(PfAIN!vZ;e(j#YkQcP zMwt>k-+FRGDhu1>sBiVtin5P#FYN#2)rHOlJq*ui7)EXnEM~v0oZ~Gyb>?wme%#)lfN|JQIDr;2&}?uo}y=Y(4BV=HRekC zS-=)d;N2IJG=GH$uX465kK4IYLtqtN!IUIF@a4^xKUCh2e+<}y3GKd&4!1|~$lROC zolbi+1XkhoNJ(0hF_wG2+NHEJy#d&QiKgc#vG|1>_3mQ*TlCv6h4M3RH!4SL)@cZ= z!mEptbbQ7HZhs_08CJFcumuwhey6cidoO*D1a;--_rZzWaZH%freKqXz$&~}C`r8o zV|l`h=8B!&5x^Eq;FT@0=5;HMH}^17=IvOkA+QRs(20He8xr{2pA*@(pw*i7K}={@ z$)<_f+6On@=*O66X$Y*sYm<^>=RB6Ptt*wzw;T!HHHG(FY4=8jnvUZe*34C$!>DGb z6DDvA7Crs+P<|(CiINx4Mnhl~E`PCaiH+xP3uh~53ma>8?_dJIiNuU>i}8G4?qX%g zmvR~ct8n>?5zD6u+_!s_((GV)f-RW9?@F=8@^T^%^Y&7jxqJgmU==QZQ4^cS@^kUk z6p}29?QFSpUaLP?w}#C3eU-jJ;F04@?Isc>Q679M6d-D^QVkwFTYhJ zmW|X|HQ$s74tAyWQS;_$2&}?0VUqM@-&j5?t|5dx*K20HFmbTyXtsZF1+uoJweYc^ zZy=x9))m4UozoClg=h36=}e##e{409Sl=|&%o^Z+5FYP}lNP#uyyC20WZ&n?nsF^A zw7sRkokRHRu5HMTioXed7FKCTclIYo@+FHalH`l`HDfhQ;9jlR(KsuVH+ZuVMmFE9 zA+Sn2NM1+%35yid&}U$@<6RH3U}SwGc@< zH`A3bJ-q^QnpLHE))CLc;=ZpqmC|k)AKrNZ=x>*#*n$ad2`;c2#>>q)3kz14&=6RK zd$N)g(%YL4cyJixtM3T5U;@_|N&4BqhnGF`5>Cgz)DT#O^G(dw28`jp2@9cX?Gu{u z2PSYmmZXl~LU=v13}_g>LqlK{&S^>76gGi(3$T#;jGRfZ1rxYEij~pWDDIi?bnpDW zks1Q4v?X}Fw@#{w&c*iRc)sIbVlW_&lB@sps40E_k|9J(;VXp`H0kHr&a8?`lxP z>fgVt?<{T*C?cAx=jpKp6ZoXR=pl;}@pBghv{26~Vgjp>Z@na`C*rH*+-sqphr||4 zsHbs@?;?;S^+bHsaAR}z%q1qUN)4;&5GN~z5A{TRgQp$M)pMQLf(d*Vfh4IX;$80d zG*{1#Vgjqwu~ZbDGc@BSC!AC;hW|KmeFBU~ISY*E8%8K^N4u{GQ?@h9c# ziTLEAlw$&`)UfK~522oQF3w$S!Gy?lgO7hokQbLACa_8kt3Lh^>Y450T7oT@5VgnP zL!6-fQxkb{O~eFNsbST}A3{BQUR>L;1rwqb7<~M>lS8y9K|D3IC`@3L8diPOJRtvR zgDPQYwb+6QfHmFz$%o7 zf>2MyixOO|-fw^{m_X$(h@x7uTD?O76Ig}nf*{lr@uCf`Hr&(jKQ&H0XZ3GFm=x_D2RBd7rpQ= z2j$t*yYW(woAPl71D7vu^cCLhG+`k%l9wMER+8-TwPHq>6++k;=}P0Hm- z<9PWuo0gBQTZibzC9vv2`OEch%}9^$sch`H^SafO&B)k`RuE#a`7GHbi+aWobJBfiM>zWgNz ze3=N6dpQ836QW*y?CVR9^t?k3KCGn-Z!{ii&#DD?2jqfYdV?@dUvGULTbG8s zGZBVx3BS^CrrHE3*&{~~!=2BNQ#HoW9jor}_f<=P%ehVb!sm*qKe zNwB`dFhP_q>q5Tf#?U*~2lBglMaWC;WEfOA2ZqX_V>1omn;(YC9j9i(_4XCmENc~1UK z?*jX5`)mV|I^#p5IbHvRo%=jmY&$p`%AKhzh+*9-lbDovy1VaYjSu`>978eYyuXw< zS%p*D;BtP=lZRwGpJam%&;85g>@sPF@U&mc{aXoaqR=gXX3iXtDB>U_!f_^rwmLr!*yqOKt26D|jmpDk2u@TGJ_3l;*&O{9#tkFm+j1 zgC%3LH5^>yZV0cbXbpF52Em{Y-$bmQ^^s})kT&!~t?2wWi5?Ksu$@8G>b*0Je&uKg zUv+Z^&skj|xLrMaNt(2$CoQ+M0sWaLmVuw`BMIKnq$`D z0J?g?C9=t3njTv);rlBI2Ddve_bM@2w87j_6R69nndEQSpvy^1gTM-l4bSRcI}MIq zSYZfn2}uK8_!9YY&TK&#*NdR_bh)Hi-d{Rw!Nk{*DUg%Brzlp9K8~lmVKq6l_rg9* zV3jsjQ@@7LVe@wr@3z19VGAbeyiS5~OV1YhICm_FI)xk~Js&m9#{^d491%Aj-|4N zBS{-DQu8t2Wc$@0Wo*HOgIPA5X#BeK$(g+cG5B;Gjk#h*N+0MX zWA8Xt7E`i-JiA?V-;&M8c)F>}ZwNb>D`N{Luy4`#xt&1A?_m&mDO^Kf)w88pVBGtt zZj^ZEi*=m%L|ST41k|6qM#dIQXw#8%Gm*Z#@KKib57Q7>B~A=M@fjmY>gSe7&vmT= zA)6+_mBv{BwR7#A`nt$}1!O^8>TQ4Lu#Mbf^<*g9^qKB#jI;O-29HdnlM*Vz@pX}a zEttUNB-+Q(1e$)fHT*E$2}_4(g7@c2@-dz(XSz*>DiOxIpsO?Fi2;*A`cX=^LsGxB zVI~RGy0RObAoroLQU>@~uhzM=zbTizngO3DrRav;J|g2MiIpEYfp%%v3;HKt1FY)( zD+5|2MeCyfI`A)Ib#MYLJWgQBeK|2!er=jX^ot7^Nsv_ax&aCagyJJnTb9_ z&)``4d`o?DdB$D97EBxyUuorJfgC?cUE7YnA4@++K7_5ODicg#RmqXbFlbFr*>#_K z^2L(JQtSQCA*pFqf-RUB7dQ#JRrZ&YHmYY#QiI~?j9+J9SzjYfI+jdGg-YkE$s6uh z(xgfB0OrQgJ<4(TdrN789|QWF)7RC@*}>D;Y<>b*@1^1f9`53#;xwO@$@1 zr_0g54v6yb{TxSGlmfGAd;@I3#Hb%>&`f_-7qDDCyTo3_(G?fPneATJGz3<4%uR>7 zKRU=YOwS4;d1O4b;PG%fz7)Y0Oq6y>2YpI`ZfV(fg6K9go|ddL9-^lG0!&~PuG69y zo*YXXl>Z2He075J9hb*|0ZGu?%i24XsA71rzNq#DUHFJbChGDtzoVkEJi_mnEf* zt7{0Xs(vR9+IG*AAD&f-tF2;b#mi;L(5lr5wtO;)hrqCt zQd%FFIDar6c2v!k+bimQGUdCAcAj05G=8E@2UcmzUYA*0rGb_Ys=diXOoGSeoTfg`{k}t+8Oj>r@y#SXKgt z4jw9Ewftx-wfS9{)X09JA+QRM$i#hpPvdC6j%CP;F&iNCcMv@L(iWV@`oZ&2p|Ebe z3G^H6t%?0$u(6 z4Cu40_1J=mMi!&MO!TW8dD;uY`a=TETe1c0a&O3(z$&K~{;=$tIH9&dy&tYTNuZ}( zZ@{f{T{N)@Y7_`1Cij4|h1wX3nTg-=G_A}d@Glsti906N%nE|q`>mm7p6VlDLp*I& zU_`c=@0D@fu?p87v4`F|o{qFHNmf`b(Bv*AV0RE)im`$<(^VhSTE^4<2TGE%^A>6d ztip9cyxWH*((Hgj`R1t%R{4w%Y^k0D?w8xbfn9zu5z^u7Hc#-Z;tNwYXF|OL>WF?U zOQhR~Exb*ypvM+WIREg2zp5pJ#SHcQV9eG;YU$A(sx@4bk1aPusm&jo07ou+|I5e1 zMTvAqyblbhTiYJ{z{C?Xf7pIB1iHLcPc#sw>_UdDCHHl6pq* z*!@ImdwZo^P`F(~U==QZai>$|M0$#+u-|C`EPb#)xY}|sYtj+YbN!&wjg4?j=L9%M zB&k%tL~1tLg&k=*M3YyTxDe(CFH5h3xyI_3^FVMSt<}Vq4Qkd;LtquoH*t&L_;~8} z{1?ldmcdqub1DU`u7i8CdQjnQAf(t`hVY4v;DWIq*xon}>sd+R!{>55t#9?1RhXU1 zu5@^+{$64yO zL=AyeI1j~Xz`AktWo|R2W~U5RukCo~<@^Dj%im?Iwjtn}@eEo!8H4k@0C;@pKD--! zQuN3kh;LMxdv%o0f$0oeFyZD91Pwdi1poW${*qH-Ja}(?btUC^nufqCoQI;!`%I+K zErXTP?cXpw18K7(38G)rAdr(JX) z$s&e6YS&LG({-|jz^Z_AQP91H5xHrk2*RXuEbT?9vU7#Zy11l4$)Lt0(7e1n)FKV$ z|1cv%UssgpDygvZN@F5_Y9vO&%Nxbgk!>B6ymi2^1rzIQq(b4T2ITZ9_2lG?O;L1O zD=)=o=n)NpRX9f^$!mW!t+(AxS@d+KCa*BDA$$_lY-vK;9}N;d4lRwQ&RYj5gImwh z5LkutP3#=_oj|W8tYNM@O0gSaT)VGLM-pSUA-~${EExB$d<&(| zjOLo$#e_J|3F`gAf6jBhTNF!|_Ufcu8*QT@unN}&NvirOks57C(6`zz=}$OjgSsZP zutHkLpXS-{aELv*|E-#xr`?~wUnp}@%uF;mo=ErgPt`a3Rfk~9GY9RqkX#y_=oLhYMvz3BGBbNZp&~ zvi;2^O_^gAE`Lc%hd63&X3c)qYNhP$o(a1{JCe*!)t#atunNae^h?71XLatpecp$WFv(s0qt33pPAAcxw%YV=GCchmW8G){SMeMt#ww0~1a9L>g%Ki6xkr zRrB?wi^GH2w!zOd1XkfRiPOt>`qSwf&ai#WYVa8iJfOk+P9*B8B@4CiH$3;++4>B} zR?J3yaHFZy#<8Eyl{D$VM2X}80}XN=5v!di2GNoO$FVli#u@^vaGJz!Lt;zQ-Mv_S zM;qR?z|rum0oA*+*=L;$Vei7Oj6QIJ-p4x;WwV3u;nPq@-}W5A%v!YN*n$a*Om_oq zcg9)}iBr1JAM!Ew<$4PZfmJw1#ClX!XF4)3h#g96tjQ}(bZF&a@R8x(PWZ6u+nbI% z7R2t~t*arh3g?@+6`0kap>7$hzs~?(A-ta9S(mr^vv$3k8^Z3byxF|#b>Zp*YcgcQ zNZ}*IyAF-(mC33)_TkuqiPvx280gKZLj=KJ{UEnuec1{#FFr1y6jU+qKx_|=XZf#6 z8B{x-MzFO5DjULm149KdWY!t-n%lB+N+3^`FUcO>9muJy1h!ds*{};`if0n*f8m88 z{Cr@XAZk5bO1@V%X4%H!{CsAfY&*RJ+2fMRBG#@js9YPQF{hq;3}M@#6hSQC9!ip$ zpVF5<9mP}DdB|nAcOXwbWw75Ph8t9RaXZt%?aK|}_m*jbFi$=Uh4tp@rz}h0ipe!y zF2i%l4Q+Yq*&nI(wUcgjNZ(<%C|7ZSy9hM7%PzXkza#l2LB zSkrCX^5<7Oke10Ru_tK?%$rb#?Q#@1XCVtFux~ME*|a+3G|gZ`yK4!oIy3n6@_e^8 zB!{^?Y3v9GKLMjGQ!EKmJ!ZgjTf@dsg3w zx6h=y-qioYRAm4=pPY{5kLWFKf%qXkK5{7d*~Aors~cBLpMmX_m~z^c`o2f@$> zR;1=+bq9odNH6+4e!5cCwF1W$Or(u{mg;m;j`^#JXXky0!itA+UyB!m_oW%I!R4@AKQhUYdN-fR1 z9jml&(K?&D(8VWuC?}toY2JyLz~v-<*&_q#;@svw?5e}BPhA5GHquP}l8!D7CBSS)?eu7*;&-cJpIRfAroLya}< zh_P=|(LSR6gZGf7IThR9*jEv98e%&d;nzE~k}Z+xiU$?^SilxU6&f zQTBtut8^7IU|6n5N0V_L^x=?=%FOT!3btUv)iwZNT^(Y6e}N#zeDI>tVe6C=wf1TV ztkUjb37q0bb6zb~rgdJWU<)Re9~}=n7n_opOb6j(`ja5KID4*Ap-PH|z$$IZ+oq4D zg9c7lqC(>|J8Lkp!95ASuWm{b0V8EQXFLtquIJz{3tDUu#cv{1fY7_O-$n7|_d zak^iLp;p&RD|@Ae8Um}d?W1M2cv{wB7PGb}r(g>vw4;fLel52A(8c|y5xxCTF6wI%$lS)EjEQJ?Ld31A;wpPai`pAD>R52qSbBVPhai8r;& z(=Jqgcu=wISe|1GCI+4C30qC8l7eSyzkO>dM;dVUvf_C1w}J_*5-XN4?Q3aqs$`}h zc-@}#chqIYyX`XtTQITar3;K(SBlj9-9Zp$_j=N@ZEuO1cvnMURq3OBAocP)Sme@4 zwA$(pgDJanR0%14K*1JFwBOzF8|}Q%Ht}zucMNXo2DVK3hzP`_tqwQ(1x$3D~%kUDycu5 zpx)8~2zBW$SHC|PES~9M;m?!u^b{uu|F|7?otrD_?#S_@sL%YKO1=0(1zRxjeD7dr zo3s)-4*n{LUEANB^3FUTTQH&BtJbicBYiiv1$FA)kzoR>y6*9Sz^3hCZXFNN&Yg2) zn%>WXuK0P3VGAZ6M>@l}>)k+?*j*5N%(~LKwvFl0q&f;Fu&NJu!0%eN;L+=wAQndv z>M*G(z5c9+f-RV^Z|)2vv6uLLn@56ZH_w?K>|jb;=Xz)etctxq2tKx#Va{Eh$lY_D z9I4F;Q|cF#u3!r$%9M11LUAgwRl`<-I27EA8jYw#7kA6h5Lo51%MBJTbAqo%;etqP z;7rq(RG=Q0|5C686Z*Pcp~Z(`;Nqm-rC0M+Us^FhqMv>**AQ6ca?u51`nrJoz8Qj; zIiV-L+x!dpHR+IoEtn{i)djk*8x2GH#tCAUGJt0L+#{{x_G<{N`sC9O5*m+yvagp5 z;^_9?^t5!IRBrQ7!4^zR2?ucRI04MoWeeh27guV%WG`8haZf{F)#+Ki;K=t7(0QqM z-7oyvn@+!#N3743;@E~Kr%~R zWY~fU?SASytH#oeZhHtdQ8WZrd8CKK1HanvuI+OXt6QZ5MbGjesd1`>f-RV6R?`#S zlgrO?{V{am;7#PZx2u9Jm~eXN z0V^^*AV0HE_=vbLj+U=6pS;~*t|72$^X5SC+zL=Kt%C4zr+YBVF*w0VS&mAB|TA)5Ye)Nq|e9f-RU> z5jy}@luU#Y*RKj6qeH^z#fEld{>KarfmQmA-Z0-k2!5=oE_}Qh6C~C-OB3&xOu-gR z$XEM7$>)<{YZEmcPm;z{=UNw`;qW{SfmPkxctZ7clOW+qRpFygMgZMVr8c;_T~e?G z6V`Wo!k*|k@X1gfjeCdE(#>|uXJ+oy5LlI-HWUVKmy_Z{SZA^Okh=#_!=zETL4eP)LTz4n~$MGGmf#5*9sJD!36%oNm8r0 zXga2vCvm0|HM_#_`3Ag)O_KKBjik#@q>~}#uE^Me3EVcto>YjURl7uz*n;+&-ECNf zcW+5j*)0=jxf|0-tF(7}umuyirHMNrlA^?yGn@>)S{X2bRoZ<^pJO9w_3x9(rs;F_ z*n$b%HpTr{rqR@XP7pb}da8^GtkUj6Iyr43-Q6XL+?yveY{3L>o8s=z3NiGe>oD?c zPg6Z6uu6N)v|7bFmaaKRNw)}l4S`#*c1KG5#c1lWuOo@b zlN4;h1a6yR9Ay(nU)!0I?hcz7Ca?{(@V*mCYOy+s zF55tKC$hs8Y{3L>o8mONShZx^^!Yv4$r=Ky@O}+(U&gCQ+USB0`_Uj(!4^zt+xg7b z(X=3TDtlJmRYPEvc3;NAE8#T!wXrgIPPT$An85vONosT`p4yDa1IImAH9ME_Ze_eH zRNP7aDUR;@T$*%vyjrtg6cc`n(;;YUwCuM@?O%C3i>1eJG$oa`FVzrOh4;gX{p~xW zY4!fYNEs71%^MCAW=m7Rxy&|sZ?O7{IvuQ{=soj^#LcU%hQKQPwi7Fg*%5SKw|Qic zW1x&Jn3!-Z0n(a3mTfvj2_G*OhtW~qE6CZ5x%)7IRk%+ib`FG&rH!{L#C&-fO>YSk z+Wu8i!yxLASwLRd`)UZR!aXNR>h9!6BR||HtFPxXY{3NX&xv32NcW*%EY82mn80Tb#6FoLVn6k_ z`XqI5V-0~-VPd8F)go^>_@|vHk15ZhY4WY%WQgT98Cx)cPj-khH;bZ6tHu(#X`_a~ zs@$Wg5I$|CTxvuc;p1y=I9=(zm<+#etHTyd;L|FimUJ0US2?UFEy{Gt#{^cb4o!j? z3$Mx7PnroIk4gm5z57m(3RQROu>}+O{ExWHyJ-NO*W?P}H7YVpVAY$Q6CkKmS%{0M zDSY&)<4v1A`A7oNd>FQ10-y5}^X>V==_s8nzP^ z0@p1Y0=E@$?oJM-Ev_6UgNL5h<7Z(N&Ji)g@?kuE)@3!R zpD@`DTQGs!yg2XNAc8Kcl}j2_v63-?Rk&ouSpb_T8t)!O9(Jq%*n$cC?h@mud(pIQ ziD6{Z&xRTTt8kr`q;X^7D5=qi_>w5V7EIuGu$W=V66+u7zo64_ErC_qRy%rC0-Z1@ z3szNLqG^Me(4Ks;Y?eqjM%019CFg1gtitDX#7H=GnOx~XcYg6^BVNB*+vPV0-UZjT zTl6ntMlXM9`31_k)MTT&@6*xu@8RL}a!mX-$NfWcfpZ7G@UM=VQ@{A6Z@|K5dBb-e zh4Pu7^Tq9Z{0DSV9C>_`ru=U!oxIEKGMLB{^v!SR!fMFMtn-WmK>i4$LGY4wK4+l`=?;soN2)wBV1 zxZhA&YVOSODP>GJZ*2(E$FBsia}@8A?Y_}*K>RZADtIZH;)l(3! z%`4LQ9r?(GXabJG(VBpLhVaHMt^) zyk*sCgXNWZ>z8%-mV<2|eg7i}KKeV~!`T8nXJ3Gyl}7BvHAc+he5gtoyX?Hn-&CMBT;D!YX`YfwVOf0K5SMKPr6B;$M z5IX^_^EQI%8)JUug}a8pD(y`OHY2ZqRn&K-iKi#W7EHvJpD$nTz6rd}S&6#q1UI3p z-%Vv;@F)#|RiD4-$`{>N!-nLkg4p)7H#rotP-&AH!hLn8n6Nc+io0NFo8=`lK!^KhpD|g@K>E}H3U}SFOm2qGq(XS-CM_F-nG$uqcDN*wGeB< zVK?Q#0tY^~nYo6*s>H#qmfvx^4I}HU(o53IV;^+~cU9!8ueoy@r!9GXN{RbYrxfn% z+~~CKlK*x%H*KL^qnz1!hg)xfzSVL>O-%pwLLQs*PPvfd!?6Vu>rT4L-xsffu|aBi z^pDsipMU>Usr1BGLtxdtk~8vx+i!+Z%?=75XWMR))B2uQns@|qY{7)}g|T@gWi>qZ zR98lywk{!Gx|F1tADGDTeIkL5u6ecktbm$9sk-b(mvntUu7C&AQUr0^$U+Vq)D29x zYHuUKH;{Di@o8D-UvprQ+cZJ^AFj?jpvUh0;~%4BSCS}+j8v#3)P2rPc1Tv)L`I5= zlC%^J6|!d$k1c!mIp>%mME2&%-mA!n-}UMFK0Vj@{TJ8!^*Q%E_nGg@Dl-~JPaW3VO-m)MzI(Waow?`M@J|Zac6v43k83YpD|3?js<(s91on5qzbkvaB)#rW z3O9F9Q?5A(9Ki%WLa5<7Tp%a>Y}6yxszhLw!SP{=-I+8}+&Ku&qcJ%0Owa#AKUN+g za0C;wXU(y`mh{NBB6@1nNQuCzuu~h927kcI=I$COqyB?sO3RaO{A5O?^jzU*2|qC~ zw)DIuF~8fBhg_N^a0C+zEWDLEoz{_srdd!1DUKq_yPa(E${2~js+&88C^?5#kg(G` zfiU`+PkL$ButT4s1&&~%=+`=BV$3R%dHWO)W}#K-v~S(W8ef^fs>s7x%D2qLWS6A? z!qBBBt>T$QQq)-jM=&vN?ltAf-o+%&`wb9zwZo}*`e6DvYnnu0RcY1@We|AwUpsaK zh+V&0(3W$f)c6}tTI_6s9ZzH*mfNsiPyfLzweyr$3`a2W{>L!o;m2gs`&kA&yNzo3 z(de`wHA6p*V*;xjOg1VmlM=~2Vhl&+^Qi)9F*#H%^k2d8JAqw}1??D|5GqYYvSdSj+hZ}Vz0;}+yg)A|{htiw& zqg5lrLXIPtz|S$v6}7RX?o%hJ7iOK62&}?Ss77-ysxob`F)Ue^ zi1*rP^}S>_PnT{YhvVuiuV_=! zY|>JavN%vFu4+g;*JY6YjUAx3eWAoutypj>rw8*CID!fH5iQ8&DQV=$$6z3KB-B(_ z-z~^V?LSx|uqxoVF)=S)MtlY-K$xGkR1Gug(h+^S2^_)1IX_#HUn7C6dg~8Fog*e{ zcsEn}xu}msVAaS8b&2Pd1thc*1)|1{ChD5DOXxYT_5w#RQE1hQ^k7jW%5?}3eXl6$ zr}ZD{gKi}puMoj1ys87%k^N|=F5YyOTHLKGa0C;$Jb2m(Rhuk4PS5PFDG^wOS9NGK zzaKiQ_vfb4(@re}j$i^`H)ywiRMf}%iPWzhjC!G!Cs-w~7V&H3ppLs=jpomB5jcVg zeE*?Wbo?Ftc6h8h)%$)9c6h@+ZnE3kf$WF0*6a!D#$oPS9Ki&x^I<()*QfN(=CNwK zVttMYta_SQnbfTv4*6@X;A>EGL;+287_HW?nZj`d6Y}?CMBFVp^hh_g+LA94fmOB> zE0Zx?XclohEQE1@~)kn-S{7*6)?pUVC|IwP1lGn7}hRW%jon1A{hUod&GDBAtitsp?A1RY=;t&> zO*Re{ID!fH{gsF})IJMsKf-xvf9#@mUEk6d%lb}2l*B)nS@&QBjs-vsaF2RKS zTwQy7n8vNJRt*}rmI$oEZ4?-94?98AOI+2{JB4mff@HK#%e2D88QK2qtjr46>^no=XpyO;>XgoFxLQaC;tlMXzG0@7r*7?Ome9 z5lqP5hI7u1r{Uod>O;+$986#p_J@QwDzAoWb7`=e8E_>Bdst$pO6-iN(IjW z5lrBE3|xn9S5}|rc2O&(o{|Wx3axBG+)9GT5clIyM$hhFY0JqS)cd#pa2&w|eqvzn z>wt>t$I`~C`KY=A6Id1GY)(=KMUd_ls=zx~mwu#2G7Z&6CtC>|!32KtVYSHmit50_ zrS#FKwi1C=S5MU^-5SJ`?wzfn4AY`_&2BliEpup3|gj}OU*SuLWdP-sO7#ufg_l}H4&^&{Jx61XQ=Gk-RTm6Rd|FI)-z1@ zp|_9P@)xUTNMo;U9u}#DX!T-y!7uQjnHEPkAA{_=gFo@tCx+%@t)l!0;}+R0<4t1X|49%-&GB* zvOfnqonmiP+4Xcq?S^XqrXK3WgVtIc!32K)VO8@a^t*!c?u39<4L*28Z9mf$&;2HyV_t&*hpCl;iKJ(=gfmP!xIFU@q_?f)20LmDY zVWRqo_NwQt(;P=If!}|PW=Tv#wJ5!XdZOg9L}1mj8ji#&YXZ3tP!HayYS-$jE)y(O ze;a*)BbdN728^Dsv{DyUGgP--uPPB(RWz;*NqZbj9xT`OCfa_grxtgrs2<(WNZ<%2 zaE$>g2VR(|O0CXEAU$;4-VJ1Ap7i;C(8?Q&|}vY)^aOyC*=`UZ!d z(-E{fJ@U|3BCslXVyW_1!3y%Zs1B6TX6zn%;fX2x*fdz+2qxsZWa_moG%&=F_h=R* z5m*)Zs6;WolSy9XRfRIPpG>1)Z$xl=lc|tb_`e7y@ca&ZIUUy0F1r_SGb?|Iz^bom zkrLy$nPghN)qQbZ#nYQ9Is9VP@d8IMf#-KLn!o=nq`%hX@#QdjjtQ*NKKYs)3XMkz9Kn5D{7W$U5q^#S%A3nGqUAC$f&07Ak2;u3NBh9TGBCra-o6u(Pb5=ip`%dS=o(3Gj1nz}HpVQt+ZTPx|y2AJ^#{^d4ItJPdtvjfp zv+Jl)>A4(7FoE}*z}~)Tt<`$p8>t74Pe}w;;kpv~9}S$<4<6R)qbcj9IuR3i-wdn@ zYiOsMx;dy19nvKNt8kqUyO*Cjs9(1^sQE)iNOe0V@ctiIS<}i^4KP#GJ_D*r1XkfM z5wt81IH-LSI;d+e#7W;MOyGS?;4{(FL0!GBqk8m*p7b5WD(oY!(WFGXsFBHS)pwnf zB!_WKVDE5nR&CUbm|Ilhg}b5!&VqnF8RU!zn-8ub(S>>J&+lk~BbdPM4&a1P*Ocn5 z+sE?ND2c!->~R6RonF+UCk(Bbi$}ENet`+u%VM~GYucsNY3=H^Q4)bw*gHd`NicOF zXG`bvL5IQw&KQC7Lde-8Mt|5&dbbYbzgo={ID!d$Mc_Q_o71b$dh?P=;SzyW>s}2~ zzLd74ogeF5JOZuV>5DzTnD@vCfg_lZuhsUfIQlg078~j?Ln5#Wdyc@&k4GwPsvW^P z6o*M}B$$xBMPBz>MK>21uvGI$k*Ip@Hl}pc;Gx8ayAdsoSo!z zLOws($zR|ICh%2<@vGBzbi31GeyC-DL||3z*a6DTCRWtBLmXV)4E+Ig{pZ;{*K(S` z5lrB#4kKRi^JzlVaGrZTNFuPR^`}h5nzf|yTvtY@{z|&_xG`V8J4E0JCgl4uyxu{2 zVoYV8)?$i8U={Y6fnD+HeyYEE5sNSnk{oC-A^XY1-Vn6%J|}kGbc#e^751-zY@4Aj zG!<6vXewI^yy6e91ibcpiSnYb5}nb=9?m@7^}f>IuB-SpxT(OaDeziFc_oMKGD=3h z0-}Yy+7J`+ipD+Pvx#4JSK$=cL|Vy#Rrmt*5%GW<_B(Zt9~;0Pv8RPUrzxblls z%xVDV5dxWDPId1j2Bcd{1XjssJ~Pgcn4WGX9zAjwev{HSh*Jji{oB3_=dszo_JUib z#kJ`DWM3%53Rd`q^)?oxZTkxx!32H_G#cl?Mzs6nD&k`LV2Qx0-o#4@_A#YZ`i4Lm zdfUC|)xcZax9?biBbdN%0jzY|lur9a=kUPqGJ#bQmKjQNb|Y$BGXlzp2-!ewk0XNe9GD1R7W#CW2>5lqPM zhtY|rbXI*U{$aMSL|_&6dIBe%(S_6|_bB@s>?gTEVM6wFO0D~zeq20;89R@a2&}>$ zQm`k^$4LD<+LxcH-COde>M#Ma#VoL)dPj$_s(uxSwsK3_|BOGJIm@Y~er=k{Nq$d( zBbX=||3~S*#FFOwjR0avzlv%%bvfVCyq`p1)sw)>$~v1y)T&P)5X!=0TG#(Le^u%s za0C;(K3-H>A2y-uyAAdBAR2UDNY~Y@D+UL2kqE4s^r*M;!mB3rcGewL;kB{!f^$nz zH?6(E5ll?J*-fbzs7E*VcLm~gTMO#-&_S5Ka+V0J`et#)EvquPMQ3*dVqd^R@?1|5 z%VX>Wj$lI0YBg=<5HcplO^iL;N+Pi8z=8!EM%=1Gx2^MlGU|>xrA&Q7Mfyxzfg_l} zS+q2o)2rSo)dsr=%ha|Kfomdsv@q(tZ4R-o*G4QgaFvb<6S!8=Xn2b%^yN((u|1eb z1Xkgz4!$_MU1`)q6S4c7hjeu@fomn0QCyHff5aLHFFj9*z$*OofFFR{db+yBUH-Gr zQ0Xbb1g@1}ujPX?bp2Y+=jaWQ2&}?y0c438bCW)*w~)7T8Yw;Pn839XteX7tnWl}3 z<8|))NCZ~lw;9&&I)A4t414e`dc&l*787!P)w{lddZdxUk8B$#5m<%&@1S36T}9om zSI8`v`AD@7CS;$xbY4U4ZkfnjTMw29tirB*u;RCFOZ9J;-fY1IRiq|4mU-r_@$qKZ zweaOmN7C+Vd+N7&5IpVQhqh6Js~=&V>U9)2f(hBpYTtHSwO(=q{`sD(L||3Ry$+=1 z3MZOy!wbr|kmI24ZsNu*+O`!qf(h)N1s?Hct<=yn0X(9mOkmZ*!>!02eH;3&gRW-i z@usaBWtqrL`?nN0f(hAI&1AKsdi3CG9yy|gL}1mYzimmMb`9yC0nSiHqwS`u>)N$^ z!7?z}K;H}#2UAk?wjp)N>cw!a4f9bYwbdU5$NBu}iog*}tgZS>(LSm}Z+++vWiX;q z+dACgc2=Dw0;_PX4WkA-pVC*Jdg4)MSAip#cy;%ja_LJoy8ELWl(GH@qr=3&Dt^z!6NyEwTotA#`O^2l44}8;QUwTx)}e&|5d!X@Z-GDQ+Qf z1QWOg2s>Z$HB|4kDjLK$mk6xFwKl9aOgKy`8+8-)&o>r0f(hI%g_SjbJCZs3x{JjI zGJ#b%zoJHSBYeGL-?pa+o7qUpyod?BV+dALb*icwDAmNG`pt#WuR4VPF{TI3IkAYZ zhU8P00WIxi!VLd>RdOy=r86e9ggaOv^dr4hY9X#HZz6C66X7R5D)EmswDa96K5G*5}*4WZs>?m#~a0C;g5jRj68`4&kHtFpeXb2%0{Ota^5hyf<0_W5^TUPEpg- z61n4nxe|d@*s}`OuoRC{TVLMJvyL2*ys0qJcxg{!+~fh-(^t3Ju#3rH^>Wr3PPSZ- z2&}^1TQEm&)J@F}e!?e#Gaim$!p5@`v1?aMO1U{)tE^G(Y7nTeq`j30tim2*FoQL* zqk7u%D=%tTDtU!rBKku+lH#UMua7tjWf+!rRG-+r;?0g#68N{U3Ok#@ZrPcw)o|Ny z-1tHb$t4XF^WvM5%hRgRJ@>vt8PzlG)wEu3`H5w9Bm%3jLmP~X>PM@-aW~nUgMUkT z0r1XpeE*>?xi>>?sWImn%SLe=!Gyg3JkK*&Z51<=Pu5G72&}^QU!$QGzUnTUbRLv- zn&Sv2umctB=9n~Cy&1Bf*Ga!C5m<%qKdj#A-bJ;4c9WlZ@RQ>RCa(8U$jmu^lO)HJ z$6)k4o~U0=z2)!jewPTW!uKD>6CsJ>y~7p6BC|>YM=+6?;z&ZmOGuX|@o)#fIXbAF z3o44K*JJ{#@coBzxZEb{MdKRc{IKc*M=&ub!HOKs`bm8H9)vRX^tV!@+g2Bqs??SU ztin$Wv_+qOp(lULK)bz6(~b?qbqtK?cVCT%fo8qh+} zZfymQU;^*+gnD<4A3a^eUZikmiNLCj505DZKk`W4hUYmjgEb(U*8JQ+%--8s;0Pw< z9iUYl#?mF3W@7cKZW4i2sT!d;uh5d|l_$cptC+M^drxHi{ag#lqY<~;uqz+biFezp zo18cCwbvU;etnq0EkKxYH|(tbFx|v^PdAnbtis-Xu==xBS9P7uI<7P@6gYwj?Dq?E zEY13=p0MVw+C50egIrIs3j3MD*Wg$`_2IVl+%5PQ#}Q0m-(v7K%iA(U;=w1!;E`=pnCmY zFh6m8r9@yA_A`Z*fQ^IH>-{OOUwbXb5lqOr2WmD6Q)i4b;~n#(WCGCA9yKz$)Cc04IcH^XMB*dlA;PnZOZD;5Mp8v+T$iT6>5hY8y0_ z2&}>*_mJ5^Z!k^Wt%wR4O{Fn?OyK$$)((ELq^n;Oapq5RiNGp(On>#vrnKkZE~3xy z*3t+)CUAWWD+ikC)22y|;@qfq5`k5CFDZKNeAwwB5`k5CEd^v!&e=j! zmpjz1zEHHuhb89qnPM)BHTA$>WHbW!=tMG~o7*%Wenf}RN$_Kt5B<)bZguFL= zabgX%O|d0k;XXhjuu5L7Zo99A`t)HhZSI850!J``Jr&^lq1Qoex4a^){kgS7U=>~| z53bn*d#OuS_n{Bh)s@!JV*=-phk1iV{ng49lj!S=iV}fU*zFNUIgN*?#vWBwvhwH= zoY@-Zzs5PMp{4KDUtK;9vQ+%(nS&#kz}}{?BX>`KRlCzzJ>BYs786*7onkba&Tspu zljF_Q(0z#vM=*iCO(7@i^#N*q|^$W0ZyVZxptli}*yIX7ruv6kZq{$1>b3iE@JW7JBQ1l_N! zmI$oEZkVte@Yo3Tu-AS%c|;D!5lqPM$Cw4a>bSXU=%#f?B?7Ck8z!`t4v$cy;T`mj zc))Q46Zn0Eb>Y{>s6kVQ(cl*MBm%3j8z!`O69%fU?tLfI&(#n(f(h);0((Xayw%?) z)5$8sY7&7}*bNg#ioSMHoke}NE2OEw5lmoz7MSz;%S+wgu_KEwtRoRvh21b=-*&E> zdgf&#UVmsyfg_l}jxI1#RNq6*T5QH|1(`_%R$(_x$j^D+Sxqj873LL=%_J9Eg zGw&{H;{14CwT78QU=?LAVhU;@wY!07o=SpV1{g0J80DiK(PXSU$$yv1Do`fD&hU8k!w=Yg3 zOEsmI4PVt>Ca?<6(7{ORpoVJgz^lx`wWl-_hY2~?*8LSt)ES|@*k6OYNd#8mc|+JI z{1jYBAp28_W4dyyMk>?gs4}?_?grTl%l=*r*$bDyN@31-+S6}&A3DP7&yr~2nG~k| z6!3?n255IRO_vC)!bb@6IP1g3jT9qo;N>`qBbX?>lvq~AOW*lW#x$b{;g@Klb&m~{ z2&|INyxaUhk-hy`&hDe9q%+6o)TYC%vNEn06+;s+EZf{E{MBUr}! z_SCFS2@v*XThqTws*1F`vB zYjNL8PpMzkO|3!f%YOIh-I3&qTj#RBeH?m|v-8{;qywj&`+ERUxTu|2)cdWQeVDU~ zBbe}C(xr?ZxJ8#8_;i6HPK6sP!|&Ql1Xkgrh5R31JBb6?Yg`|@+DPYti9vRQ%F6KE z>jGu`tk*+Wcj@Cg{hgIWU=_ZGFmDjlTJ#JEAb0az)$pfw?1h~zb#FC}{HkZqR=swj zx2BK&e`j7i*Iq1hb|4K36v)5ypUTC|o_YLmqTV6@pZF7NFMjbh#PFsfojE2Hpzr*2 zqNYH@zPmJAF?Z>8rSu||2&}^Q3D&TQnISdJdT)?tQax z8}dL%1XlUCp3QW5U;lKv1q98TA!?qe&VH68(w0XOS@V1+`sr?x;u|-&Oto!5rh;kM zF=81i^qQX4cG|Iu;s_>|pZKSY-4_a=42P@1qUHw+?ToeA5`k6nQT2iK;CI&NGb7Ck z@_lbo*^!*AeZg%_Nn+XG?Rxc4KJ}l+R^>X;HNSMb0T-l2ix|HSMW?!=D}Tw^sh1FKHPo z9t|*HpYJRuID!fMorf8$v{;e(^pG}w?-+@|D%_UPXslIV@xu6y68rwM^qxPg?O*n8 zKlC$~-g$84YClp?o2iQ9d5wzSZA{2tgPL_lip@0_^{)ACQ>aUZ z^z;$G7V75=ORT2i2qy5?2b_(VgV2mVM_gjtt4Y`F*eR$pZay1Fa2@!Jx7-y6*1)Wz_cT zDsD~`wMcSpH^j;B?7DPR|0ZQzMCSJZ41;^&(}&{15Du78QhO9p<>^Dtv33?N{PTK zxu(uE4;Rnsp3}y*Ns#JYOyD-EMsvP@r05!H!xH*YiNGpc6T#Z3Z&9My#FpiCttWjy zFoEk8*hl|&j7W?OWl*}nEw%sc03C8hpI>?sss4HNRp&I7^RFWz_(tW_fn4`JtIg;D zz71NJ`N<^2^GpYD9`>@;8lG*(Q{F`CTvZzX>-`9xkd6EKWfJ#Q>2Bcflrv@X8WP%I z9n|f9o$PqJ>t23(V4whpQ0>2dsIcE%`>)d}>}u8i>un0T0Rz2xF(1PBj|s7X{0ggFeUL6s1KVS~oD9C%n!u_T=I*_R9854LusVhPn+FZno}cg$ z`nkn)O|J-D{wVfuE-Dy%W&h^Bf^lD#T)#E(ypROn^PL}R3bX34+9~)-PSpYR*o|BM zB*?hZvBb0HY#{8T*8L5;zS*Nw6G)%fGth&4JEn1TIoQFqCGg9>3^t0&CbnMAO|S>Fwm4%E2$6n+}*Xk zXuN9_J42kr7`0c~w`f>$C)Tx~TiM^qXUj5;v;Q)UKgn+@Ld-na*r+bzs#Ci%)w=kB zY+$Nm+21u`^)HMXu>V&4nv`h7g(yFEG<$^b8*EypN(-CJ(uymU{ax=@D1$Z0?B6`x z&`Ujdoj<$l!itto5_^XI((1+lD)yPlyn5a&``dQXYzF%@wEyPehL*nmF#fj3d2P*_ zv&8IKv&&Rh{S;nVL>* zWNlt9(FR(_>N0efM=&9mZEv=TuQsdB((R^+wMFO4%CJ5k$L!~CDEnLAD1pJAFYUki z#G!`!vy@jhG+>9$l$PN29mpY6mv47W4%Xjcb zq@_5x<|?CJJ#?cu<@XlfbNov%4tLs2*f}RN$HQe=*~`no#D2dGS@*4L`GE?aYX1QXLMjV+_+iY7qBJ@pU^^8(lle{+E& zJ;R2VslGGMn=KqX8eDl=h+uk(I zUGy9lz})XQlL)NB?(<-d1#YFU=`#IXQ}U9sKKE;AiCd}D%R(YW|i6= z(q#cJk6_}!(|^X!nwk~>F?v&g(BIjw6_Wbu#R5kPA&-><+{s!$`5p%$eB~yGsOC z9bx~J;r**05EUB7isGwlSnjn747Vn5I|1?xvtzAX=q#(9IZ#t8v7%seI$Qnbj}}KT zfqP4^n>;N_d|KwnOjbAMxO99}`RV_Rm(I6*2xa7XMT=J@i`eIl8jd5Fz-7a#m%}k4 z&%G}DdY>~)U{%4!f6CbGn+s)3wu=>>VkkQk6V7l16Y_bqxg0A3mYmkcEd8d%1XkhE zVOZT}5+mkS{m8n8)?$!doV{+*hAz7|BnS6QanBp-{L(1lLhJD+6PqyH+s3_O{7W!K z<{d2t=+)xplgyumU1KS{zQ-@G~xTBm%4O5yC2O*GMs5U*(CT6$Tm1*}+?l zsq(dv+b7!u*1yz>cC1`e`FnB#i$2nr&e^Z8fS31%2;ni?n{WKKgyFA#f7f_sJ=Tn_ z9_I7^S^(2dMu^<`gZRpaix_SjU}A5bx$ORhhP34>8z{r(TZFh+qd)gfUMLY*g^v(= zMZ;$a^KBk{LR2yvcx)z1HmpJ?++d1rmk4I@qYC{VeN=%AyR6o)s?>K=BPe5Ovsq%~ zdQbkxWgf#3OyCv{^v^9K#k#X@{OO~)x;(rre&kQm`uGCnu6+pWF{Fs3xB98zvf-^Y zh!V%Vn{z9NBo=KG!hCxbk&69)DzIjsJwH`QK25x+csK_!ZN@ute}!%gxnM?==(y9I zuh^K#a0C;bdIvB|=ljI{rWp`t++#%VcITPX)K~_qyji<@=gAIMk(dpdz%IK85@F*) z%;rvDN6b$UF~=E*pRHp=z1V#A$0Cm5Nc)%Y%}YK-oEkV0{7Wz^b1PajIP;7>TRB%M z0~2-b`Lj(IZ;+<18$lU~og&4%L`yy)?S({O6+S1JKmQOVo(-tYHE-wY@>G{!A53(< zF`4adewTc1U=C%t$x@LEHV<)y|3FlR1*$o(!zgdmJnL+|MXsf$Ow5f{8k# z{Mhuf;AkB-0?Ig37%S3!mMF{mp3>q7b@pRBRxTtz$k6{+MkJKM_Iz|ZdgZHB1}1vE z9>;S2UPTVg9|&b!yBZ@5_W#xz#2jV#sIUrO1!!5WfF4VOs%-tyjtoaI@y5-MU3T3_ zjPCb=GSUKLMTgeynAHeRiNGrP>fYWOE5hy!AftY{<#gXVo)wvekp`p25`3j0%OFeJ zolMM6w1YC{!$@jKhl9j0{i9+OIEj5f>qR1mk0+NhCbF4&LrLa<@dR=oGOLj@NTZRi zK&&u~6-J-765rAT3XWhRE@1+TJv512-Z2gc?iMRvtV<#rmRK`PV3mASU*luNuLF@} zvF~X&9Kl4P*#y@7!c_9Dimr@Li(-ZUw?I;%kGn)*6}}>{vL-J^jJ3%jJ?H2VeCGHF zN1dC*G-iFtw9(_CjNpwiqUzfM5>?zxizAqT%#tj?V>nDnDL@!m!PTAom@Me(MKFO? z!BLahpq*}{)ihlhTQ5b4^|SP8P}_Z^>Z~C4Zip!fs5pk)>o$e?b!bM$w-`qtLnhll zqZ7G)KzBbhhS9?KQziO3EK7=DVzvliVR4RR#w0%=HgAg-JB0R zuOaL*g*g_ztSVGb9GC6~CjM*;V#i2blA5cVR}0=6CF~bgp=0moNCZ~lXF;R+u`f~> zq*kY~hf1XDgRfhgnKPMr@;Rl(CtY1Kb9JP6S+xb7w|@`85llb^S!P#Qle9Wz2gGGJ zxK=-E&^b-3QcPf#{kEAbD?e8W^3|1L&?8bDOo07|Z;dD(RXKk$n%V2ER#u!*{@)18 zskV_KDZ4T)u4zp1*b653$Y?gTX@-*FK%tBl_L1Uksvg~EA`@6O=3x}8&^JqIc1;B$ zx<#Z2Z>mq*S2d97L!q*L)raU9X&s+m)tW>8sf{8gNB3Sc}S|#1C7nIRXjTCoY zR;OKWSCt5?lJAF$h!oe?za}1S3@KzeX8htgB|5GKX+0*MF*^^XU1no)(Las_+!(Kv zYFk1Xi=(4N$mL7qnZ7<<@oX+Ld8w}~H>yf@=FegKCR!^qs+#C>GP6!Mwkpf-e}I?o0xkxRTyDoIC$%iC5pfyH*Hq)gph1oIc=37QvSGCLT9jzrM4$Gm zyjLm%6Oe_GjrmqnIV)DfQQbC<5fg^2BySzgN(5HnD*~={(8_2tusJcQwUbS6x}RTn$%b$jgwnPOS0<0Uu$q1)U%-lwp} zU9&p=ZlKFDwp|-5a@$(KsPj1mM=(*jT`CLsSm3G~zlN-DFdiCiQC&HBdA>wo)dHHz z(koAIU$2aCITS4tNfo-*d9?!hWLf@}0m|ITnQlLvQkXK7|g!Uoypy8Uxh6a8X^<+^#qwL-W=U==<>aC_?%A(`A1{E?ef)=BnaRVIJJU zWi5lnqh5Pyt$Htx;Rq&LHGuUD_Iv(!R13#X6A{^e(c;#55`k6tioodLwNMeVY8kb< zvDFPnF!4J$fn|PP`@b@pwF(#a-4f`R;zJUFRrtEWnb+_Uwoj_5$7*^UgXI$jbHIUJ8)=_Ft}m(A@$3osyHY}# z%BJNJZU3M-|071O@aF6L%~CtGJ*jhJFQ3)>b8EQvd}4B$YS8I;ZR+Tx{}GR3Z1}pk zDAniTu^gah*sUGgBC|HfoB&rnv&2wX31kzW4&!Tn7}I7 z#F#UD>Az+4Y%)UZ`EiBqs-}@f=<(P)9>0bW$oeD1r$Q(0w69ni*~Uc3@98Ya(2*|8 z{-D)pQZvVj)TVv;oewu90;^z8BUV=NO9wW1HWN4 zUmC5&1U^ET+m4wf(s5m?p1dJgM*x(W3RNQcpLkI&&^h+R)^xW6IC5lrAK z4eK)AO%vCbhwy9Dy(I#xV2?8Uxy72sC>`LQpM4o3T6m1(AvQB~dy&f{n7~gA?A6bm zDKb(=@FIgV43GTc>x0LZAum8mnE1RZjAyK`&v673`1~}Q=?{a1M_vjq&GwZDtdif4 zK`~Rrmp$|Ohwig=`?ky998BQzE8FQUoc`PCT~1&Xew$&v=*<9eFL^G1wPUID)?z}w zRu9`v7CSnI^WyEBBm%2&tpxifdIgFGbs$W33*^~(RKf2wjOqk;JH*h zON#4xa8~WpPuQJt;?pL{^R<}ph?&3wqaA6~a6<+;KwW*rtjPY{XRt<^;l(Ok&qFWO z&s(hOIG3+o{*~hhCcuAywXD;e#x(v7@5iNsL&X}WblxHUi9}!(uIFKW`$2DEadJKP zE_lLm1QXz?z{YHDK!a0s^PKCh4imedZQzGL7DxnE;V%O`iNQm}v!U61;q+@dCxr4Z z3ns?9`mj-zYg4b`tD%hEp`*lMuWfw5Y^_9K6@G7Er09|&+8CT=sit<)Y7y{ND_KO1#F3iJYXNugK?@I&uGf$6_ArqMtityORu%X1 z5PhG=^R6pu2^_%$xKyyvbIs|=I%ZIYQMRWr@=WLKNM(t@DtvFihyGV@5ucL9t>07< zID!fA(O_2>nbVsIm7t8QTrcsBw2uT0~w zFM=`}xbzh!W3TevJ`W`VtG2%F&w{sCq9%XZ0@0{`SFv%~3qJGVD~=bWT&{5lp}iKK7sM(DFrH zg#OM#K7HgziNGrGFJk{WW^G#$C<=p@^KthhIG%$nun1sDTWiokPOEYp_V}@HcQo{5 zkuLZ0sxC9d@4rUz=pBX9JSV2{+$1|4#ocSBm2;3hWKXa#J%V+oeNZX z1QU3U4SHUMQ^oHw(fmqH7-|&`m9Ki&B|G`_m-x!h6 zV;^^4xm_Z#3O@_r57*2`v}<;TU+i>By62d{?>~&B&K)g!@6P72UH3}_R^ewF)>$4L zEM|BJ-n!al>Dk4ETr=!^HAcj@TE)+<;}U^Y_)UZ7>dP>3bapH+n)8ysKI+3-&)!5_ ze7-BNlbM;XJ4b^0_fTNxG@D+$pByS!25)VrwM0~DdX{fgYv^`Jmq#!G`;ytnCD%x4 z&Cy4}ZQ8JvC_Q=!5|j~T;$Jw3@`Z#WAwSV!tR zFeNcz7#p~AKB+OV2AO?i2+PP?MP5$Rt$^5|*Gn{eFup^&Ud_9lsZE^#MdzDquZrl&nU|tK|&inERCSXrJD+UktuXhrGxH4|Au)29k zsnesTL|_#-3$Tq9V@ZX(w}Ghtq`PQ(+AL>Y>&7|MR1n(6_g! zu~ADFW!IMotO73+7QQBhG!EC@^IesOi7$~qY2r9Hoij!Gnr6J#8GJNYi-%2##ms&{ zWUL${8ky*+f9mzs`DK(xFab^&tk^*zOCP%dvH7RB=#s0a7CkbR2&@7>5SG{4k{Hf0 z0K(ffP}p`@NyCjIdAsdXS(833iJwJ90`3kh%OHSkIdMY)Hwm^eX$Z+FyXW8c_=-gL z6gu1~SLYg09>D~7HLy3mW)uHW2ce9TdLxCG?NZu&@HL6RDsYfsXMRp4ZliVs;hZu< zByXEXyC%hH@mvu;!Xb&%*%QBdA|=aEt#!32H_V8-P41kp15Ds?KXED=~W zsU)0f1{)AkB@fC-Up-Y+bFQvk5q^~8S`F7-Jz9-q#@pja%nL)P;aW7CAoL2}Xk*wT zjw6`B^%%_8n!tF;nfau_{H+p!Rod(^Y~_Ri@@uQHt__m$!2*bTFSR=et5v!|2 z@fn>P3mm}&xE3;>pceGyBHij}yB6+Z!R<8uu}eLPz$)AegFendRUDeUjxRY~SKtUH zz@w4523pX9>lRSPj&|LI!HLa$`JfsSfmOH{26L&SJB!rxqdenOb)A1=dA|=6;6lqT zH8i3nu(v^@d1KH`tP4KLEyh-o2&}@rFc^o+RD@%Phy2Q+$^u6)0ZygtKX2UhlT>V+ z`i$p4{>3qYRk#-hUjt2B5miYeF6UL$x#^bo`!E46CG0l}N_ z39Q1sFsMcAz%J~SRm8#H`a1X4@_rvC!2N_J9)CsxbN@i^uAxO6@ojiT;de++BCrbg z+sd3<1afXE@AqK>w}W7B#`3nJIQiVLF4MklFn|7#H}cRIID!e> zI)m2IM{jXp^j5xf*aMx@ZF%1ktK@cK-z9$Hua}c}+^<}zuZ9WSegqF8&oFU)?*q0g zElDD<3a|Hry?q0s#Ddt1if;uwj@PQ;mL6Uq2BRO25hCFJGNtZqe~u%Vz_lyvuDKE= zrsQOhO+#x)1Xkg7S>Tf9G)wHOpG8(Hy*Q3w0@ueH&G?N`;%3hZw4qNv!vt2zE1i0b zpC!)bRi{_3TX7u01g?)^9l-ra;b?15y^LT*5L(5CRd_`byipe;M9;63igvFVj!1-5 zQ(wuQCH}JSL+j4Y*J1+K+IYnctmQm3Q`iJeptiGCFdV^zTvOLS9wB~SA45BiTj_=g ztitP=G@AU;qeahmSLomI^Q7-N{!-%>4mb#iNuo>I8R|CGN@~eqLjF28T{%_sX|tDh zUUZ+~-@+=~QiCk&*~6>dL5MxBUA z(K*kYz8m_8;0Pw<6+(&cBSq6Kh2*DWEot2nR^c^FFwZ$ZQuMm{nbfc~rg%jY-sgwQ zhLP=Nks>F;nr?jmSUM_9$anB@r3m5EB#^dQdqu&&g;lui3v)&D!iDmBHoeuY8N(4w z;3o!l@azc@*S4fm+f_vB8(Vy6=(*tit_IxK`Oc#erEGbw$e@jw6_W45F-g(Qwkgn-7#R^-XVa!rMTl zQHv!4t8kAMYHF{U!sSO8&9k&1ei?}@U~h!tw<}$7su0ia#GF>+MsH z2I|HDju(WA<4Mct=x^Pn2quQ)Ml%1<62-jaFCdbWrwQAK8)^QfW;yt`uqy0q3`=PC zTybtY6Nt&0sUjjZhnkMGWH^F}5sgAvy~TCOyXr zQiDWo9S6jVOjr+BYC*3b8BFjFVtf^*-A!We){apEOFIG)@D_IPY#U17x3wiWf(d+n zkpH~rOyPDXoIYs!Lcs)9t)OkmZPpxG>a%^l_LMJp&{^|?TCOYbDDFsw+6Bbbn{)!QEaqTcBOs{FQN zn7}IBr-m`IlmM}`@i{u?!4)lz;9fEQC2%k^4H2hW?4-+9zsSK6OyE^k@U8uOy7;we z4Q=5#(+v|?g|7(gS8Fm;ctu9i%pQ}ZtBVPFbz4Yjgs}NGjGnQ(ArV-G?<{1fcp4>k zG_;`KdKOFf920o;9_+7$HS{O4O32`*ZKUT4tMC&F`*FI%-ag-1Brl|`^z32+uXF_G zmWWu9XI+gn8#7uWunO<52S*^-&Ea2Mhosd^BY3wxUe_rfRpE&kv1(-!sbjHBDgzUE zjVE|)O^p`nv_B-iG)W?`3cp>jdZ!gQQ|z~*b80S<>MKm(6|EZ0R}M~W-G|XDCx%J{ zR^hq}?qF1em~1qXc2~m*j$i_}YG7ya(i!3fPo^=4ilv$pt8m=~o*a$BME%7}=)4-{ z3XWg`x6a@jwP~uj^87Gern)dpU=^YI^*q`9O-~ECTAMr?^pK3LzgY|W=(~EcqI4o!EU?pMaV?Kv0vzA9hX&mwrb-wP zkoQ%q%lrECpS-W-1Xe*t*CzJ|J|+WN?*U?7*hp>=-B`>zO$GR=YyZut0l7J}bGM%+ zl}lUZfS0@Wzib{mD=*}AZ(56eYI|L7j`9d5AbSWKQ+SC4FI@nm21D%~ z47kc`Gf!rd^CtUX9%tm{%iLhmN`4qTs&E7o;1SQBF5N^9$JJM04_1d=d|1MDK0#CF zDqsFvSOuQ++T(!-$%h4=P{#7(oPSwfz#Fw2EN}!9;4sf(_h*yNhdu+L*J(dLe)K25 zXwgR^u&TAa0o(P4k!{)4f#|!~RC`Tz5YIPv6hY@cH4Zp-j@(bHrk%9rRpSu{b4k_Y zZ#lt3&*Z47CrGOKrX1K6A7HAjlxQmszNG?3Fp)FhbmJMZjMVn^1>)h_WbLR+4Mkyc zFNwga4vq42ZcNxu3KpyZua|7I)7odR+KX=`j?x>2j}X5raOTUZu-dT>q7vySa0C;u}lSMuoQ(#fJn&#zV;elI0!2Q6^h`R1I}$-aw- z=hry5?OykCiaRePZHET|pwhoHnVVkJXla+!vK7jBC2^PCCRXiyQi;Lk z2Hlf>zjS8Hr+@i@9M39GP-FhvAkxJ z)H)8gIF4XK&6#6m@G^}|`&t{Wl_uze_Tq_lYI-AQkzJ2j1t+AF5wC;YOh3=FaJ~Pw}t4DJj!31814z0cclexjH zaP{_r*9;R_h1b@@d~MHg{$}D#^}aRH;s_?>HS|6usk}Lzp{DoBm)7ZH6<)IsPM$?c z+R(sO)Vgbw_}b94agy&U5?3w54L|vgo07F1cOQ;LjEkfmIGB8?`Qz63IPc3`E6}ecFEBCA8M1(E`8Q_^HI@!Fo93 zfo#$pE49Os?gB?JfuA>MCx$*@qr9owr2w)JqdEht@DakEI3IJ)r;k!i9X@d!!32JK zV8mXv|7ioP$IBOKJ!l^o~QdwQFF}FIF4WfKX0(k^6yPN?b8(1bE~sNU=`j; z0y95@cJj{EL)7H%U9>oY33Y8PgL=BWmZuE&@im|I)CIOZBm%2!Cst--vSP{pfqQ}Yv34vkSw4}axkZR^ zbFXQi>|IRayx+KCr#k(88CrY)^(6n9j@YoQEqA#vifb-~2^_%$_Pm2ke>a}6*iHxe ziz8Dc0;}Y2Z8vhCx%=Jc0|Unk9Ki&3<%3nMpLa8F+sb08^)QLRD%>&vhrfznc!_II z?Ql*p(=6PiS39UpG>_Hg$s6=agCzHI&s|xMJ%31mRn@uZT(Q$&n5lrAVDvT`+ zUCr6JEWUN5Okfq{UHU)D&O5A%UJLizF7|?`pa>`+O$8|mI}?f`f~bHM5k(L|6a^9K zAc&w?QL*>ldu7kWj=iARd+)v1n~k3DzWI(m=U)HfalOC2l1wI(vXW?e>24sEjgxul z-u^jR`L^(wQo!31v><`KTK+wsH(YT#`bAm&yoW%b3P%}y?apD0(ynbe)@6yGF#bRS zd$qhzy(L9)SXP%^>f1peP=#X=zPta)JSF*bO_s5%9YYHeVt@A?U9a5V-hgFvaTW+v z;aG(4o6xt^Bv)7{&vr~_c#2?X!oKR08p3i6SCm4MDoIE@d}|u<$cCW>32cvfR9Lkc%Fh;FRMoJ$K%j~mU(|%n8BLyf zHPHIV*{mG%96%>+UZkJ}32cvfPrpftvb^s=>M+MpAW((-3VB?g+f`+s-yj;f|SP~P-F&Mc zfvS6B%ggm@j^gJD8F3$>mv1SdgZogYd*c+eAc1v(&%N4}VS8c%sk>uEfk2gb>glxa z<=DAyedzTMP8zfzA?|%Wvr~up9Pde|`JE|50#$h8s`hMkE9F1;_TelJzr#<{z10D7 z`^v0Bv88_aR#)lxr2+eRwWHAPBC)9U42`4PcG9Go6(3EwZf>nSZc>SrRk{fTs_?tQ z*A3iUl^Rd(C}d!N;roHalf#W!ZsU zx1|{u)eJ3246`?o^SUJx&oY%bVH{JR{S2%^A6hgN2vp6eW-A-<^L~#<)#t=8X2@QT zF{Eo3e^AhZ#K1Ck@&emnk~`}xf99u&4Qrm#j1H)}OCV6?Z0adX>E5JImHV8~y=KdL z#8}aM-?0i>ka!U9DG$HWj<}?E;6!l*VPWOW=;@A50)Z-iBcB}Ev=y1ruoow~*}Ah^ zADhu9n-9roK?3)_^RM&%PAtZ=Ax)fPEfA=}9r=8;J=B-A-`{{fkb|{%9R9Oc9|>_E zeOM=d=JK^Roj1JM9wbnOJN^0BAZ~-E`0XR5`omDxq+puyLCa0Vw|0Ru&NJb-gtv*h zFEvq?hn3IIql6I)68P=n>*uw5$hmZyBJ-7A{4G@B=!LI_*Nc-Y?Qg0~k$8+0jD(QD zZx^3$54j=NZ+oO|T1uKgpbAGXd_M8Cq0%-YQnJvEXJ|nJzg>K$sA9Czeo3)px*$X# zP=(_ie!ggxe8nTV9&J6%ouLH@{1Wk*qFXza(KDOU%Em1O0#)KT>Qhd!67J7)@>9KWAU8rRjQw>^>z_Y{o$m@UsJ8AAiSEcPNL;_WK zj<`zopy*xUle6_%o5r0P&NSP%-(=jW+%8gm!tp&g56e%vDSBVHe@8X8@^W{E79{Y! zQK=f_JkmUWT80J02MGkKaAe8*S68j&vAk@v%d5hN1$-thT$qwR9`iET>6uxNom z6^@YkzM`40VgKvdLu2SG*>M96P9-vHvRR*m*IuAc1w7 zpBvTxmGZ>VfDY{1OdwDdSH6+#@@W|9<-V8u=p9v#IRraW-!ktNv><_Xn(ub%t;=GL z68faedVxSyZAX4`{q~-u%tGxAF1=PXV%|aR>7FO{3R;lBI?ZEPhFh|y=LoG=dyR|) zs>HMI3u{`kZ9OR6GfGE;79{X&eSQ)`{g%vQpEG^aZb~5%sKRsh`PaE`I@{3owmK+# zjEtv6Vyr7hxAO0YcQP~dDbe)X=qALyBJl+FX7Rm!vq!PQ0Zru}qcQ{nRTu-yXXwX7 zuwBJvBRP{+r9g?yylH05U9c(Tzn+F zttnHdj*?>?+A*{s!SBeHO(Uk0@%clz4~gHl5TR5dDHELp0#z7Cs8Tum*svKHyU3Ta zE(|S5xCfcbr-x1;yIu|FKK9FPS%St<`q|7}QeON9!0KHIO`CYG>3?AW(&Ig#4KoIM^%>)8f7&*e* z-RA);XI3>j{M}<2ElBVi$mQUp4M`ox!Q4kt-5`DhN*QX>o!>D6`vg%XMx?lU_hS(o zKTC6i8_H-wB5XvwoZ?XC_t{jJUWBq|WgknAWvW2}Rk#yPr7}F@D!(~hUcNG2yv+k| z@W2~5RI0?Lb>xDkIdWhJ@oo+zPWL=zQrOK#O8PjC@8DUneXg8#=a~HCN2+j}2dZW~ zJzsc<-+eeaB$pGRO-yBjM&*<{8&Vmndhb1Ia@^Na`uZqW7K!=YP37boPKwT&WQG6_!s*jBh6)rAcNs3>CJ?B?`o>RmDDqd<4&9~fdmbUwDB z`)e+k7)kbRMspvxODq+KSNyDupg4g*6~1YF?QUcjWu;vgrJUDD;f+FK;p1+ax8E%! zw_DlVNB1d)N~1<^Wd8=@TZ<~O_3_Rn%6>~(&WTSF+7cwh`-njhko67BOr3eJ7 z@Kz#zZ{Nl?iq-dn8r7a;;l3gy@O~t|nT|In6ho;hjNvqmp?0P=^y4%AMzd z^48E%3@u2YKklRQbmejO1NlPV5dwj#7Oxj*n#vYZrlNg<4{PTrx5`&lOcLW5T9CkU z5@N;I6W$z9(>s#86Y`{*=qiqgV$jM8xY5QY{c@cDBeaZ8le zGYgfqPx}c3sto(i)hy1fCoLSMy{|}T#zbZMs!NLgogju5B(NUy-crRGN-Lwv?8j^$ zfk4${r&*eAhSj95^L@CF!Ech3J3n<<%`{Jj79{X}I1s~8v-<8;u1WSQHRdn4&Z`(2AMpw{zNMK>B<8;>?x#g-;#TiD|6!Tm_?czcRR3i*P1Z2AR)%q zRxBAR7Y*;gj-L_reoosn!a67hrKvRYmBrukj?}A|8WLL$V zrJ9HYs?Ii;sPRjCN;Eko+{d^&7D}Vhl-C2R>r(3fD(@hv!kQlY^l_v9+N^-kWi4%oB8buRp z!M;0~3k0ejUpb;V`L>F*@s$fFEIXf9-XAq$FQ+tTXhEXZ&kvfy<2q7&xCJL_CSOr3 zI@e;M)f@x@RU2NN(6rd8D=liL{njSWeWUosm18N*oETb=n5Xkiqq$jEy7krC;I{C_MshdEc%HiEv&D}@~>9D@G59d><410YxQyJwDz|ew(PFNXPQ{F=II~2)@ z>{(BgjiZUuYI3kZph~>yZ`6~wio2B;Y&HI^I~cjQF=vgWMIevPv1p1DAv>Qt@f@^^llK`k@w z*$In%jM*TcGs>lI77Q&&)c#giR({rzwjHtK#QIjoY{bepig7_>fk4%`%x3cG*h(1Jwbhg$OM#g(P+9d)^nrLlF{3jNy5@r0g0peifdNZ!5p zE9vRGo%^sbzoInl+=NXqXwER^X3s)>xz>S8B*3Yt5M%aLs!=<>C=VAjX3wh_GPEEe z`gpCw*FQpxS#$>jfk2hG7hrlxC1&xUAP34g_a9<+c zyoq&;pJF~;hqW4UM{ZxShj8;E5?J&3D%trO%w70)Z;5WBknJZB^LZ=w3>+ zYgdLAB=8O9NZ-kzZa32ce@j`an4EUu@b zd^_hP5U9dB#@|6&gVlI@Ub*VihM@%sY*G0QF7<0L<2T9LJ_u2eRrP@j-w)VZLK%ffu>F~MN zR0qZJxeI%B+FaO=g9P?Cc#|Dsb~Y@ppshfl3gcOLTN1We-u2X+&3{K3T96Q9Irr@=kuBHhvl16?fj||; zv+$l}rz`Tao>f@=HQgCnkighc-in@UsywdzKq)92A`qy;cou%QY=DpAkhNZEFf@vx z1qr+9npbFzzct3IHd}Z+EEJA+7GPEEeu0gh{y<3^+OQh>>BLxCg7|+6Q`U_H&$rtBH zS2px#Xh8y38da(*M_wrTn;%Lp)7=FERT$60Z^+9k%Sw`UX}uLD3@u3DN+bU|ztv@} zJWT1b4&N0dP=)a<{NyjYMl9Ufp5E5oqo4%|TsPz=rMI+XOMbMbm)ndM2vlJ_3*Vy{ z-ikH$bEE-%briH9f$N66e>GXnN`_g}81G~m2~=S`3;#x$s9EM58!G7@6K;<{0`K?M zMxME{Y%!*ygDgAtTcAaRU z_lgA0yzo)c>qAOd{p!lIm`H&@752{gTwm2fW%p?lrRd~fp%;z>&b;v6(yMcdV@Zti zvqp$OpbAGB{O-(#hn1wNc}m*M5MeZd1kSwh`&jB-P^#>Zl_CD(_ybiqTH^as9ri0j zJ6%>($^OEq2nn2d;b*rkJ*2FeT9GxZ?Jf|g!ciYzaUZr`(J83Qq5~yibcY1ayr@*S zUaVH;Y&B*6Yg-Bgs&MqmcPL!TSISpx!Iqt{7DlN^;LM9kb=M?SnIGDg>7Q;U5U9dY zIFB!BFDU_sB+rIR!=-eU?x!BI3^zVh40WzL{$KwDTtk~CSJLRUY z)WXSlNZ?KCd<5C26?3a=tTbrmAP}g+Q}Xy~#$`)Zx7blxq}P_A1qmFB^4mPx+p**& zF^Wx=jXLN-ug7NW0uax6w?U}8CsCQ(JPNt z%dull@%I%Uo0LN zm1;L@y_y>4@X zKov%(@EGA^50rWDsxqDB_6#jZ;7%L9E2a8pCHT@;W!Kd<0)Z-wPT_ZY54oUh==Mgb zI?$7$1qs~m&PPS`trEB5kg{v2w?Lo@qf>a>zUi^@-erwavqJzw3lg{spYMHDmuC~J zq$w3o`UwQ8Fgk^=0=)XJyc-mtWIgT4(1HY>CcyWGx90NWhX8CsAKW9Z+1 zX~I0#dP~y-+ynwu7@fjbuq^5`+XHFRki2#bEl6ObJg@Cd+mLw-qE%h0!T0)k?*I&2wr@SEg-J(1HX;%JX-ywi|o0(SR1OO%(`K zVRQ<=>$gWc_I_7mI&QC%f)*q&Ql6jir|QhC@9NT1Ht%F4P=(Pc{Cv^te(dX-+BDd3 zjEoi}Fz%htUtJAkc`M4(IWtdakU$m2v+!Bxv_7oP-g2~j?EFq3-m5=9OC(Q*-4{jHYB`9)}keSxL`e*6VaBI*Rv+;EbXKU z8~Tw|=d8$q_syl9_e06`Y*(_M|9#4`3nz52KV(={GwmmHSqy-u$$oSL&Wo|6J`t(Sn5NV`vjITKVo=b)8-A0)eV(#JV(9 zyRY=+KKd2*ptpT07N+&DO0h%@_Jx(IiccB+t8_;e`O_P7$`u-PtWB}pkw`z#x0K$P zZ^?aFd32$7ZZvFr&|Oa;P_?;!PZIvrPU`p4juS1ucBEkmw$4Qz8&k9(;W@WgsgLC+ zT5;m8u?KB_P)B`Xv#CI!3d@b}P@t4XHoo98!pc&3f=IBtKBYda&0V>VDTmw8$S!wX z)?3>O1gh})t5h)tL#Sus>_X2QhlJXWHC$cxOvip$13ETIh=!nuxcI6;5+zynHSMDUCA1)MH7mE2 zFkT+aiM7v?>7c>uH05^KOK3r2W3BPT?1q!ns9Ob2bW2R7lgGqrc5kjB5U4Wq8DHwd z;pcZA2^gJ`M$Z~1X--$ZO3;FY$JAeh(fC`O*yxi^+fP2N8MbZ`K?@S!&GX2;-p$CKf29HdYF{?6!+f1`$^)2N&Xx$%SA1T9F^yg8m2Tyv7%ovX-q97fDcr{@xE zW!6_$AW(%VU9N#&MU|e&fjO!*o7c+o`p`-A!tT97b!_N&yp-S*`^CQnGE)yHj+M@QTc@_{OR zPCR<&emuRq;ghCp%vcH2j(M89FQfE3IQ;lo?qi5U9QCffM)TTvwuBZWI(E+_drR!3 zT5}F?!oGMot@5gorvJS40)eWC7QcLacfH67|6W6B+Pg+B?XL3!Z^42@&rb2BsVd1T z$J^c1;z&Bvql)v35oaW{ATc*Bfz-KfCxyQF#(kJO4y1w8r>IX}xGNB-S{EHx>SM<3 zirmMlq<-|(iYbMk3O`HO%fK%j(tK3p)R#^%k5*e8RZ+Ac@w#SYsSg%rzW1CV`^{Cvf^mjeBwjm->-?k%N8P$g@ z-YS02k@&)TmD1VOTJuy5IMtb+i9fG?D(eZ~b5vnT^N5tL0W{&e1NmB`me9*UA}DcS zsgIIbM%>56Gd=13y$#8dJ~{${DttEli!(Qj#)Z!+d=vFR!X7Ku82nQ6K7(}_4cYgg zFuL(02`xxqUEr;c)nK|f+DT({=9EC73cu8R-}dIAbabr{&3%<3p#=$iS9r_NJC4%H z1)6P9vjhTF_}x{hx_*qOL%h#xYFLbw(1HZE61-&yNv5r{%F74NNCJT>{C4rvdhVvs zLUSUosn9?|3li8?@-?q(Y1F0cD0ySE>B3hHRrp2K-UgLUf0SD;A957R5$gVYaNmP?aQf8bNIdgmaQOdte(vBjPx5)XkADxMs&ZmrNnsB0NZOTQAu&J4?O#NgHz5x0Af7Z8b9D zo;4X%)JyJtr!ps&`q-7cIFM}Y z)>w8q-GCD_mELp$kJPJvM@Jw~g(>7Kqf5Kf_|=u!=YpydT99ZO-kq#)G?l%!X!Eg` z1<=qFRawIGN&4xpQ=-BLQ6n+Q3_JUvVeC)RQ0Wt)^H+(+@0fz(`GqLlS) zD4_)j+cNRwhSv>EnD0kkuTD4&q7&O5S9C|23k0gZABiBfTYu9Ow>0KHy6+oIpL%as zW|dV-+kZrmP@S)u4LyxX`}7fnq@UFMJZnIjOdC$lR6eW8`)I}q_1+=$joxZyNq;v9 zEl5;9JDe=td|H!XYR-w>ZQ^KZ*AQhvepl(^!9;SmI7#!w!jAYDCz3}+*_vrpY{~Y( zG}7wyB+X(|T~1_88bL2cMl0#VJ4eC@yFj2y%=wjZ3DkGp z5qb8Pev;I5G#OH*q_FP^bCMm9MixGDEqt_>k_GcqNmpH^@Wnhe_mOjF6wTQCO?Dp; zETN@UR0;`uV56Dn??mvIc-{3KMGKzPR$d+s5_}*r$T@}N#5rr8B{^#IaV4I|G8ieF zrUeQFsy4q(BDyb!YUak+a-wn1kyLjNQ7kiqCA1)6J1mKe9vrFJ+fCbBy0bBkT4*{c zAGQSv1gfwu@EOQ`3AD#?deWivDsbrPWW0%pz z-sH&SRPxm9sLQau9m%WD86^GdPM4BR4xBiCKam#ob1j_f94w&)33+ZR`53*+Wm&6^ zoG@1ssYQOV=6XUufk2g*s)IC%cCpGJV;XdpKIo;A$k>HyTYXC2*G(cG4>Qz9I&>qA zLzBs|ou2AT{$05b&v%LR(}im;jhl%1z!Wx}nL^e^)>1#-*ohN!YbDVRsWIvoTLLAt zAR+b{S{5bJe47$=kCVXyfhsXo{#}!(Z`B^e_Hq{qEl6M=h3^=dnMCsbXbRTc=2!)vOZXb$UII(V967}eJncV5$N}M2t{HX=;92&-n`IS=WYu}4R z=WI=ZK-JavQKah(6Y_qR)<>_<6nf&wHDYB{PC^S3WM>p9NwOuYCTo3o+oaIE>!-=L z!F)y-ehXFN7^m0x6na0rgg7RZk$`8NhBpBoIJVgO&0nmlIMdW$kl^gi4;AM`}i_2 zmAVhxLw3qH1q%{5ZsTj)MJcq(;oYR_^zsr~kT`WRf<)bDOE#R)j_#@y@|;IA;@nUq zP=zJJ&pi8>LL1DSM<%&fma>fol4r-elUi;mq$E9@jMx!D6846YgrZQgDZD@FRX?5k zSW`BQR$g5|EOSo^79<`Tg_Es^qlxP)?R&m)T`CPB8_DFv^Fq$sKMf~~E{71Kbzua{ zP^C)ymP%_LTtYU~IV@O^K!5y9S?g3fMqWbl^;E+1K$YXvfuv)1e{ww_nWySg(^Tpe zu!!W{DkGr<2`mvl8`Un2CLJF~THe`5Fo##I29jAr)5xI<{e=?YtKp;5XoUueKk62G1v3J89=+tTv3I4&5h`_xgzv`j{#Ok)n_ZWN1CUrna~*2_2A2 zK9n2F3HKfe)b7qWa^PvSgqHP2!Q@KxSmK|SE%@fE;ky#(+!6ew!;KMw44)aOa>^z>TADd$7 z?V{zxZrXf-Ko#bR*ODFsY0UEqQrghVQt*e)WYYSzWXH(KL~i6y&W~A6-k+LCFtz;b zgnfhPx|3hX9(qQ|2NDIH0?0PIrDRRZi9A(4@sYHm{!5b6|ENHq3iHIHUR(p|1aB)T zIs3bmX55~1O5RO|*-Rs@R-VMN;x6*)NdCW4^?70t-Mhc3^kVA=!3Pq0#U07A`&&rt zps74nfzSHWEtd79qRWp20##Tdd-SB=t&;khD%S$=26SaBY~Dm|J; zq6T@A=Vf1#7nRaDaVg%38a>L8I%Swqv>@S_Wk%Ljyg)ok=5V5yM;n?{akTVtrl~-n zYT$V@vhQdKd38`rILr3b#M(+SvuQ;yOtU0wem0Qi-H0KzlP$@^v(*%Z>m3?a%w4=*sPX7pbGQE=axoBQu?DT z=^cGmI=VlRxWyRoIDl_zT!Y5c^7iUN7>#l?BbsUVB(xwQuJCR<-Jg~p?M+6{c`Fd8 z!aVU+neK7))Q)^jhcUCHHP150kG74ZTNe+halIZ>%g-q~KAg@npSmaN%z7aoNZ?95 z@9%mKr5haV)N`ut6$n&eo>Z#Me08bE=3;r<+7cmJ1fvr!1Z0t9Rby#D+lhSk+_!fM z9shK*96YnGgcc+)8iLQN875P=*E8fPL2U#ARaheYHV=nHn)Ap3jq|i^dO_ftua@9#?GRVjCwWVg$#;fhOWstR&{YB`MT+W;12ovb(&FxOQdm!)7_^8X-k$Hs6ZKcMr(Fzj z>i&)#X!w=;xU)Bfs!kg#<)V{>(p~;7m8@@DOKLWEzdGV<0_jk5l(`a?jyzJ z?f=z#ts9a~dmO4SFYu2MEJ*yg7fxcw9Uv2%Xrm_mFQiiES+z7r#*`O&uc#7NkvH0= z({DN9vW^latQ;dz^;IOvYI}i<7}bRPXv5dfp9M{jXEzNN2vp$;Hs9^!lumc=30DV= zm``xLbjCW29Cckvy8P($uhGQ3>~~&^;~-jSB<|66a#W$g}cm$c!r5zR#`LRO&ck zm-4Y%I}1LL7#=yAw5t)W&RB23eXKm5M4vvcNd~%k3k0fg)q(d*UM11hSJFvZ>%dFubx9f>{hz? zwYsJ*?>ClcvW~bctoT}8mABd_4UX*D+P^&a@x&~ZULR|$KJm4_gcc+Qe#<7!G?!c= zmT05ZU%gME%hdhU%GO2#fhzMmV@Rc_O6u$~I^4(d@@e#I!HvRi@4pkDA34M<<7*Fz#JTDwp zr`(=NQXZL7euPtf{AJzDX6><&z)*@NF}S|8352vlL7_#Q_AZ$|-EO0-+SP@i1qrKN_=BkchlEhUmqw{!Mf#A5UMI=P6x(bR}p( z!hd5XdH8m_X3M?aJXMOx2)ZeMp|Wbxb2SpEvhA8hoKF}2_L1-@ir)TmP|@@CB->LH zN$Ul#HQS2@s<%{2COYTdm8y{D5x>RJH0SJ2W&YO3YP29R_hu&frnm36kCE?UXx^L^ zihlMpfk2g*Dqo-e)a=-M<-lz_Qho4XGR&c#+_qzkn%o#lrkm82wNDLG%g-Hb5=QI3 zd#H4oU!q0}5;ZcDNd2oHey8eq(IEQu{Uzn~!b<{yD$Em)Ra5!XxqQ!B;~ovj#4f!^ z@X40)wSFn;pw_{p^-{~yRAFlQ-ldctw0KEXHg?)BHCm8pQ6q}%4y<2F^Lq6zkQ!%| zXU!fI3IwV!Pkely?MQznv}TP`g4HeBxsk9kol1Xe%3Kc;7}v4%Z;WB%J^glS+9=wF z^`AaajTR)@I&>qR!A`$Zb#uB0{i!l#Ud3+&0##Tdd~7h^i$=dUWD&~?)M!ECV^J@{ z#@qh(VVCbiFPj;#o~vgG1gfyy_^jGubDE#*#@r5MJKOqMlZpp||lBOoM*gk z|Mb+H?s0ZweXj?&;BTP{ON5`W(IJSY`c{_WPk)v6HyuRw_N*$cE^9}^-2;j3ZXGE+ z$D7#K??N&^og=5JXxBfkzW1XOpIAs0tgBH};p~@4w6E_=E$rN+*5S1&T96QDyaHW1 z(`xzN(w>hs1Oin!m&tc$esQJV=|iQ<1NfW_%yJ?j&L=MXKxh-)1nEdwBY{8_&dKt4 zxY=>k#x_uiuk0tpkzs@wMknz({SiFUX|9LTz^R=Og@lAY-@9}wtC8k>mukFp2frRg z{k}9%s^0Js2vlKw5nrQ^Aq;4df(Cva`4C^&8PNH`5V>z_DJe}F6k&r;uiFIR0>;`v@#itvbIPZ~6C&f2VK8*Z8(1HZ^234xc-BM`Wvm3HW z&GHfwsKP!fAF=RVLf=ze<^7gV2wIR3`-wkWrO|-~2AZ$xHv)kw>^bxJ_H}8r#?Mjm z{K%C;e;0jVuZE9U4yMqP1!a^lJsu$qeNiN^6!@HeMl$vCvQ+vMtQQDWVIPIB>R%m2 zTda*zw%j>F(1HX$O+I^`G?I4UCmesx*dP$7!rlj;@!Bw)8uwkU9O`z1palu6Z@gad zILkA(dz6(I_6h{5urI+^^`${{@w{_N%*3ZcZwU#En&tDm_d@83gU^(hi<<=kRoFA& zHE}~Aeb=ijdv1PF==&gnvBP}DWKRIKoKl0O&6_6>sKReBk8TU}q3d@vWM4*Vgq{o% z7>&(O?7iqtpG&5!{=rOvKo#~SRH}gX5>5MI!Dd`tAw;VqfidYS)xv~VLeux%X$lU=QZmKq6+<>v8; zUj|V}uOel2tc5_JN{kD)Y?w;Fc-B;Qehnr#zl*b~IJc-$6%0$EYepWDrNSx_T96Ru z!gZsP>Aoffa{bk|0)eVT$3(JsUJdEH{TKc<_{?LSXM9%4=l%H_Jy?(sR~jC&I9kr^ zcww<_fk2>Y)`S@H>`OJtx`}r8z~j`Rbll)~YQG#sLJJbOlEP<-W<}EQ=7UJ&$kPIW zD(u_w)~9uU`laPsk{0<^==C8Xt}Yb~>_gKw-yzjXR1|*;RoEL;sa7}jqf?5?O4~ox z6#9usi0f+QKl#uG{N!SvarFcORoG|b`weaqzK_0@boGg;u$GF1xWfB*tUayU*-v_L z(ncUqCBe!szyD)l6rJFEoNQmPPx{axknd~0LTb503DE*;3`5D$%eP2>BW={nZQ~L2 zK(8!fc4wZ17L0ljXPwJ#OQ666Eo%Kv{=Pm-AW(&?4m@U}t}pHLsH>FC_b6f%0>)@yf1dZ2;(OBaL+vH64P}LX zI}%vZe5d#J-t?u1jdZQrPYHhuRX8r;U(OQ)=z{sxq|EboB(xxbb%FQv?}pF{=_=`Q zt49KXDtvGFX;#Mv)2~golCIT@gm(}LtUdfTsOV_ANf|)0op%WYs<6dSsYY%XNk6vK zsFMdz7Fq@*urBa#RJ{ah9Mn!D_e~K9RAI}ur}U`c<=5jU#z%UjiY;ho1mjU?Zhhpj>%WWrF+sct3GsBU*B# zBU@cOL9igPY`7Jx)%_A~m*1I%`EAMxAtX~uRRw)b;Wfj||O8?Wv6^y#YIKFlHNm>SE+c$yVi*ELxF z^ekH~mQ{Ea13GP)4{O_HwO~PF&n7F<q-Uw;TilRpOjXa!4aeH+r)JnWn=0 z6%r-Z)+GDZuemH9n!cSo^@*?5U9f0FJ2S*zmWyWD|w_li-?aPeU3FC+S${n z9>d7SVKqwsUKg}keey&n^{=^bB-#bXsTbVLDOF8&oUD$TF}C#Y$okdP?_>A=f#|cq zSbl90E^B}56SIxNU#^%ceCGI^=Q`@h zW2VN*|6Q+!FU@MopHyjW$myTA`=@(esj6p-;f1ej|N2|>;W%%bW^}nRr7B)-8eaQK zX~&#Nn!?*-|KI~HNT6@g2hL67TsY5@`pG z`tDt#&a04JN?=_OQ-u~JbWa>mw++cGrTaS<$jg4NT82s|LcX8(|)xENQ(qokf7(U7WSF`r?vzMRACz<`ala3W2U@o zGTq}>%lCHzRoGUFM3DDW&Ad@5rB7<%oC})l9=~b^rdA}-f<$wRT^he(S$}xuNTBNP z&ja7{H9HS#-kr#lwQtw&Un+g)|Cp*$3lg`l+|cNC&M2k-PM`|gE|EYB67MzTs{Y<4;@5J+Ju7)>{a-x`{H4FA3W>n3*0TBU^{>AZsJb)6UbcPJ^AGvJ7J2w( z8;$4kaiyxix1wl4BIT*0W=hmAT1*uZsKORpBx;$yS8qO?T$&PtWqZ|8&9h4X=CwrI zFZpvV`Nx8U_3mxzagBa`S41E9Tc|SATcHm0%Kk%HA<<&+WtYW^$Nztn6%t3^`D{O- z{?m65%L-Na6&3S=Uou=P(yj20yN*m{zQi#-0|0|``N&p=ESeuW3ceNa0dODz4} z-?irtIY$c;c9!MI;?r?|NEH&O!Y{R$D(v0q_}7<9E=HFAE-!U$zx@xXLJJbk)oRF# z3Woh5RY;(Ur&ima`-2a(AYo!vUJgI`mz@9eTd2aXotSexy%kSvDp*=NxKDIO6#lDgz-dre53ULMFL0IhJE9So7Jxyvw!>kLv2S35;yry1K)#{ zqkGAhjs6)&{Xe{eNQgJMXuZHQ|L3<*g{_j9DzqShH^%&(KoySLMPgY=jy%_TWa*Ro zF+5vd@a9)r%j=tl&wl)&USWI1OZuNYiFd4Pz5FNVXhGudK9E3F%`X}9wT*wOSLGe@ z<;?X-8VjIra^3#*3Hw|3kk72@h76ywpUOwvVC@{4G>r%O?_O zL1OFL@}xNLPd$AkP=$R|(FexwVO-zu_eP^FLyw?BBBqpAc66B ze#lifE_tv%=nt(ZT9Eji z+W$eIsvtX?L{^>u2Lj)sFLvW)^?=Hys=vQcXhFhnWv+ZP_1E`G%sCRM!d6Kn%=QJ! z(RM9M-?cWk2g_9}HYoj@=SkZVY5u$J;urGq!ttbv&taE=yoO`Bi9XPR1jf4moj}#^ zUn>0XRG|e4jIIBpkJ8^l70zFa1b&4-56B_~dAmxVAU=PQKnoHb>SvRpb4&kFOOQa- z-|H2AWo-1v$os4}{eRReB${{3l)EoK_=i;S(*5V_g{r@QKd>$>-w`i=wlDWT>J`>F zBuu=MWcxM$iSpK#FSLpO)KOGjHXSY3k2t6K?^=SEQPx>4&g2cSJIr2BnfA$+-&hfWUwKpSIE-~--hg6~Eb%*hC zV$EOsG4PkfoTCMa-4n;lGYfA0k9?r&_b<8p_wzst68sI8|Fa9`kEtsCEmUEDMI>-8 z?9(_8d2jHq7<&GF)Q*JzP*!L`qW^R+`B`SW(t0fVKmt`*7eoRrNL)VHOCCS=KQZ)L z=1;X9RoH^_6-DFvZ0G#WY`~Z5YMevF*~lRit>mUI!E(75*?cW^_<2KCbij+v$UEhN zbBIVk?Q1P3*apiPzS{c@UKJRyKJGqj=ancmT96QZwC~@9?RWEHj=nnt0#$nbt>sFG zdDMNXcEvrgngN?M*N4^Va!idDBpi4?^qhm`He<9zfMXNZCD@BO_=^Opytt1zO<(!g z)Lc&7?5@w28Fpf!#t+nJL84Wbm0VpXSeEZB=ETtFO<2I54y@{%as&xf-3zsr=jrs7 zb)vK<_PROhv#GCqSnCm;2wITHHM5di>-Uk<#;SNM&NF_OP{yNnEWKomK%mMX+FG`5 z(_1#-8A*Gk^N;|}h{YYF!Sv8;hdPbKBlNXh(Tten?d zPqTk>f8y3OK|WJ2MiaI{O`e<|Dx3A*q1hMi$qD^!acl{n(=#bIU9uR_Pwsr;vbs-| zStNH~n0(K_3h8rc0_j^WQZDm-zq7}htNxO*D^Xrvl%&x&w~uTm{Kd!(7HU!1Fsn{1(>jBIG6a+LC6c;)G|z&)%7u z#GH37CF333q|nCU@)v$~n+ZR=%{n_oHhJ8dl>0P+?3y`HE;RBd$J%Sp3hR-S#M)Rc zCLLyaNN7P~oXJ4>)#2`>v1PKL@e2lOXLO3zhW&@X{q3zSzK|J-?BvSnM7Lj0fj||ekiX|P32b|n zDP+*9;XAmKN zv`_Jqb?(k2Pp{^a_8WT0M{mv}JICbxt6tsriDoPHj*-gEwn_NANGy08C_hh{LYCO& zavv*t#jqIPog^c1nLwaQOqH|MKxS~ag4EXRiqy!ei@bH(TJj=(GPxM*FSlvFoSc^@ z5=<>WopRkEmSOOP1g<|LBK@OWJ)R%Gs<^r$^SVY>Sbp~Ipo3-63}(#zle$#)U3r>zR#r3}W=+V!8Oy$&YH5s!15GmpLh|2XKO^Xkb9+%bfvh6|Se%5C0Bc!i4YqP7F zud*hOFYe&PyOy2VJjXAjU!tx+{2#{7GpveUYr`9* zh@yf83pPMHHdIiUOcWGFvCyT9fP(ZUMVbv!?1-q?8!9Rmtn5rwEZBQj^tJci75y^X z_ndEqQ?A3WeX*WFMyT&~r_Glqpxec|81_X@8kmw~ zi%Ma4^_e>TlDpyVbjkB6sO=M740|k)=&xZ)Hk>*xv@AZud>nJ|qNh%6Kp)%da0FDr z6tZ4lY`PI)z;C_G106(|t|)A7(^Nus2;fX%*={u_1;QNLa2n zBbhUj?LX~3%?R_?UNmIiWYVOx5l28(O|%(FxEt^A*;OvxfnR)R@hu(cLybEAYp*$p zYGtJ?X?GlD%r_^KVwx%6YF8t@o4rX~kG++vbSWcpclgkDuD{8E&YBonAaOx3CtEx0 zt8Cj+t|iYtjiL`$43_#A{uHayEJ%XRJY`krA(Y@_LEg2=Q%;CEjNBjElJYcr<^64P z?^W~RDB8EYpES?!mk2G8INZ~M^nWx#*Ey=_6NGs=`Jw-FTj&5ra>oT;>CdxNmO zScmx1q{s;ARrW^_S|9=Qr%(hM`O?HDi={S&_e9TCmLwnUwYEw|9Bt-HyXY>J^5gGv zJ|O*cy(M{k^PY10!wN8PP7KdJ%C+}{OHr7-O~27qZ|QM zFoo<(B#lwDdDtFl&xA7~v_PVNZ!0q2y*~L~B>R}waTMKgphB{qbe1EaiqE-Wf(QLl z`a=3qwm~$pwkAvO8Iw((i_v})YqII55qaNy35xL)NOk)rgglaaORj4@sFB`tDfn5b z2rZD%H?St}CL5CHBbPEFE8B-I@wz4@IdA0%sDfpvP`E^U(Pzmwq(^%zxUzyo$bKuL zySD|Yc(R81Xm00Cn_M|BebTDr2&jU0mVH;m&W>(#}V{%Zh8wt}N!-(qo zgJ@Cx)^u*7rwA>O2xs(5mbiCFZ0xsow2CW~WZ7<71V_ z5SsHzm&VSG<9t9OlF^+Q-9Js5i}xJi`L|3a|BeuQedr5%5XX_QInSG7KqRS z38Q>#vgBTO(!YsZR{D2F&`W{!s7})b9065)=@KVIcUGFyo-G@TCH1?I8;NdYWvwl$ zX1_K4-N^AQJ7lxEA8Fz&5SPRr%tw-qNc(%4(ahP+MQDM<$p&4B=bqu@>TY>=v31{V zX}iCeZ1A?V|wvJY92<4P`B>ma`$)@0ooFYD&x?J?Kvwvy-g!?3>ofM})@!I@R5fHaho} zvp^!mxWa3nglO<1aImHlXOPZMf8O`Xd*RKfhQsM-QVr_ZsV=M0~5Ifq2x07O3C zb|%x=sae7W5^q8?$cV5= zcO3Zv5(oLgi z-eyu}&J$4eaa$J2a4oMCTeHJO6_N4j^xc;=!i)HD(O^a<(ect1UTth~N4p0OJA@<=S|D-sUJ_aL;-JHeKJkn&ots8A+3uNr zcJl;O@v-oUtJ7&pvLABu3=q}Urjb5zMM9{$4>HxwAUG{o=*aeSg1*^_o^#V_{{F6L zt;T3BRgft3nMek2cNW$Um(O-Ol9f(%y1f>1azZ%*s$hw*FN+&x&`(QtqR%S_i!hGA zH9v{$kGm%n>xI;b>1VQtaN3=6M7ItRVGbejQ6rf|h&O~wZROI9E=;Em4f2rF17D7S zDn91{cUVODNj~bP=gH**5*KpQ$ky;;;lLpIETMZF(rJzzJCX8^A4fnHEOmB51&g<@ zI#q@ge*HukW54q=f|y44K{q4o#@qKrWYCgpJJHL|{Y5xS0*Pxcqe#$tBXn$8EK5}n zoIzWt?MF^JP8N&1^6;B zolc~iQN4P;oDWEBYZpy4>#3pQEP0Rk)&Z$BNoy)Z5k z5-=*l=Dd0Z(N-5MkV`?Y@Rz;q!BW&^i$AIVR9A3$z8qcj@E|ufjjN0> zT+4`EJECde=y@b|I~Ab?65(v-_4|fo2YOkaUD{(9O)oxZEA?N3KD?b#-vDZ%DVrbUWhEi~5xd<(gXf|XFSugId6tm_q zVohW;wcOH2S{$&IBcQ6Zi!Zr0bGGtIg-o376-&!bc9CZH+8{y;B!bt4ks|9W4BbOZzR#y=?bWHjk4WLBC8?N&$Oa#k|e&Brxf`Qcv3q z!I{5XCq@&8J@1qqABs>l_Io20@ek#D{$ag`k-T$)KsyL zBcQ6=$e|=+%W>t4XGP4%^u!1{^?QHX!Tc+j^pGO zu1`IG8hF}OdOPDI7gdANFBqj_XJJ1GqC-5pNCzjp%8@%qhtbq_;&1YK^=lDYAOTB( z?HhGAkgh&fOWLpd!Vypfqn~VCYwgEYakQ28^i*(hQAqF+$dMgJ(N3FNO8eB+IRdI+ zOqPueP7R~t-sZGmUvqAh3dhm>bFT5zgC5mxK$AY(a!)NJ7MQw`3GZ8ws`m2PPPaM- zQMFA^q=pOKIRdI+tHk0ykzw>)y~9$2$rHKO2NLS-0?FZ5$CSZM)0vOmr^nLp=fD4ni{OBkZ!Hm$i?~~0oxchNB_#7#@;?JeQ{jD5l{u=LG0Yu@E}@H zds1pqTg=6MAi=jj4dPiO_46y~^_D!2fGQX}V`~jcGHBb58&IF?m|HCZ*P6g}Ana|h zHjV!JU4nAIj}@T>60jf4-n9=C>3P?D6x((MM?e+d_X*NSplct6Aa*jj2rZC+tCQG_ zdqDzSoLsAPuh}R*8xcV=FJE!6J6V8Wf2UJ^D7o`xs<7l{A*;Iev%gWR&eizE9l*+kIP^k4?eh^mnHOLj3;{p#>7Kb!D@b6UNXVl>^Al ziLW>Us$N7mlG;8O96A~8V?NqE4WhXhHOaHAqf!1|_8 z*u^DL>4ZAcp1+(Upo*{Ud1~>rffid&cXS80N)HmSzOm7rZw!s>Yk-#2NE`uG@JUlB z&d-dbzw?TP%~=Rw-t4(3dfz3PL zOQ-u+Z$e`)3=^RR5->`|PL@keqeI_~LSGida|Beu=byD#`%>xrB}GE~m0Yf6fCMac zcE(|w33TFm4dSLgizA>4wn}USIX;E%cvVhTJ)Ft4SCHWEhuZf4F=sDXcx+{O9`%&EQl{D%>st7HRfW0$?qT9+bbm5gM z>EPt)9066ZN6vPYe?OMyC9ILImKTZ80tq-`Wl_$uDC+qrPg+n?$PrKl>jK*|vr#O) zzAPv8dS}V=pg~e zRBUIw`{8uxcT;H$zQ7Ss1xNQRl6o(M-b(V9TIO99p#>6fbqYImVOB7G^gK}VnsApR zpo))vxcU3j#{09S!9AaFu?$G?D{D55^rhQAO_Z8Ud&3b>1y>HSH|O0{dLg0+1)fjl zR(Zqq=5YNsduo>@(L>=Ykg>~RZk;|P#%yvYFP~bXcg^IUzR8(b8fLN$9c7~lcrB=c ztNd9nJiwRk3^5T09Z_Jo>K3k)=2tXcNeiMs8@3d?8oU>w1rq#vYMTLmv}cbN;_I0T zZVe<7Z>g#@fIZ0tNTi5Bghi_&#VI0CBRn40x6wx!W6 zN0y;Oo%zu=B=|2aLftZ`cf;lA?xsQ9Xd9~duQ}chHK+Br%oDp^w!u@Unvx2Qt4NKV z0_?QFgh-pOBBWM=2H2UAzMCGS>ihE8IVQn~;#mvC{F8PVS|H)v-i+kden6*p$T9ux zkId+Z`Lo1h>b*Dus=gmFBb{!3K$;;kp;l=|vwqGLe`WN-&;p4Of0+@ttk1}7ki1T& zVSq7Rb9a_FQNIs{s)|Wwq)FlrG*i#kzlON0NS2;nNn$Hx>)7hha;e>MPCaN$WA=YS|AhGV$A64n@Qr!b9NY7Akk>31=+;TOUCtO zV)kA`T5#t+T0VXNzNlkG4*fJ2AIu0t(=S<(s!!(P)kmSIXRReE_-!Vh7#z-s>90)b zr(0i;#!`%-1rou%tVr(bPU6B}k&Jlo%a|6WrHZ9R_86w*-f?qs=!v%Y-g`3QQ|15L zn5O=U66Z~Jz|aB-mqNBGv}tp(^W8M&BRAEIUXSt3S`IE4{e z?~JKqs+-t;D#FkL3CjZ(#Qj_gF=Y7!Mx5AcO22m;ES4Q~;0UPF&9Ec`*(uk{b&?pd z{-Y6XpXe;IL*X#AK;pEzC2`YgBj&m!GNN*hDZTYw5c3xb9064u7Fd#Nzgmm27ZVuK z%FmeY^0X5_RA3A(kWllmBpONW#f1muXzl&sW^|%pA-d`#j({rM(TeQ4(@~Vp$Sddy zO^m6sk+Ha6qd$fgNK8t$Bxig&iZ17(7@&% zKZX`abe>~Le7|%Oe-+88DsV8O``_z`hIbt~0;*sQRVYe+nNrJ#mr=8x{n**8|6jvl z%}-@}_dT()6dk*SG9U5#I#ILQz3B0)ff!mK;S*y;7ADw;@tx%L3>m#U(<6@aSQLky z84s=nRXpm^iGg{EURcw<2Od2ctaNqEs%JZXhrta+K5N%$v&1F8PWKCqtV-C z133b!1m@$$4;xWm<-@8^d%CjJ9Hkz1!O#MUnqyYP!Nx(lXLP|SQHG@jwht^<@ zfGQniP3FH6#Qiq|88LEYTdH>Du!FXyD~1+GD9^Js!i>=DD*O2Jmy6}^s(V_DLb7GL zS2tpn@1^?P_nZxpcSw`}FMrp~6B_dmD`iX9n#rhv)^64Bbw8&dd9Mul|LnVN_SG-+ z0STz8p88oueAJe|wS>f>$QPCJwG5`tMCVJl@0Wl7V7r9Mdj!b8*;n&*d_W5%-jCF* zkckuh4@f{2`@h3~^zly%BvQ@`s{f~&{2L$tB%rF^@J@p4W6WLoJ7JhASfY>S zZBmtw>6@wlrF3D5Lc&)gTt&Bwl-D6cACQ15SRyi_k$W)hx&7DzOkajR0!-=&zk1boinvmIwO7Rkho^X=;RfcFF5gYypkRXO+RKD17~ zf_H77Q45voz|ENdvF<|R#A$UEo$*8Nm;Cwr(_X=pK-GV4OXOX-$Bk`+m&1X zy`a%F+iN<1ez!Q4%FZ8zKHwdMcg<>DmWm$R`f;5*ICAh+l@H5^Tmn+4T=wyV>i@P@TTW7EhcNY3rB$T(8@s=n%X#nWUtg@XKl)>7BW z2ed$9#HAN1;<-m=9UqW@s&a>`Dq>b(ZXH5el%qit=g5UTt}Gm-`t5SMJCb)hk^j%$YIO)`frO`(r-~lF z!xr)P0}@aL?q(ey&;p6bLMN3EkJ7<)d_V%K{_`^kYxV11Gga5!`LxynJ_UR}pal|* zm(5VoJAPRIOFsVpiGnKdtkfZ(1riO5rvE8j_ssu7KoxBB`Fy~(_ItZOZv)>oYyV5T z3sR+oMA_s&^s>>*mAnr~Kvm)7d{sWu9RunR7j1g0EGs8_kO3D4s($Amcar;8|EP&| z2xx)CXzZe*{qp~KW zHLAXk{rs6^p7NIJw`bu@IaUAY6V=H%v_OKbt(+l0wGmDQ|C%art^ZfS)c)t3!|Oi$ z+Nx6avApZQ@u9NFJ2gSoe}31(Hqm3(8bQA92kUA7W6mM*J2*f^D_Q;emwfy)=THSp zohM$u?SkZ#luz{~-G-W|etTJr{vY24kZ6=-prWtt7+WV*Fy~MO-$Z<>oaWC|U8~c~ zdk*aFtomKT-p;I5Qstb@yl&tLXn{mv-#_#vjnjYcHOXQisxi)!o6}X-eRnEZ`Ez!j z>i4jMxpK>(^1(XFJs)V4t&Fp9~`3&C4G@$!|`j{QKX&Isa*a1ZtC_qOV@lsN(}( z3#ve?B>YQ0R6gV~fke#f@hTq%*Y)f8fY*X5_}1oq!1i??`P0^V{~Yl@w(XEOJMYgs zadwBAO5O*^xe}`2`;jN01rit5{_(LPd3_&Nma-3@fvC&;z0chr>su`Pi_@}{*a+P!_< z-YaZNpbEB+d_G|OqVW7cB&TZhDb>4H<>Oyt8Q>XILc*!qQALkzHmFX{Apun|wS20e z1ri0*d#HSr_;}ax0STyrEjaH3wrX0*(^S_rcUk^lS~%GDL1MJeWEH)n-H|$NA|#;d z>#JN9@wVfI|3Xaf6s=N4?`ZyCVoR`eA)z)oLPaB?O`WoW1XTU!aV>mLXw3QZ_Azuk zRteuLeCa|9B;NJ;Lo2px)yX*|pbC~D?*m#Op}#R-m2-nzBkK5o1XRJd9q$8O0$L#9 z(kDaZW8(Wyby5WhsDfi^-bc4@6{;LAc%zEYs(#B6+AGP^RlnEum%kGF^Y`ZtLJMe# zRC`FvE$Y9Z<#p?IX{5K?07+2AckfGkh7|?SCBIL1J)X7gQzHAEP3sQlmNqY>_>8q^r{2wd(W#_%?uqk?RB%?Ukxl#|Nm1N~nUZHlGhz zieumZDbXd46A&zQo`4oegm!JON|l~tM4kHq38-R`Nfq(0^B>T{BAzOhJg)+;^q*4& z36rLMRP?zs9{(j(Pz75I-UqZmqDhjI%Ez#&bt6TPfGRkW;eEjR6FxA4$aPG&Wt;!8 z?n0tkk)WbY7dNU?OJLoFDpq?`b^2dNUeE%GpY{_}J~R^kO-=mgwV>)hM{8lfwnd47 z>bm&#*#EIl4T)W09aZ#*@US{LXZ1&wDmlgqRj@?(`vEPG@F?h^^3nKT`iYQ$Dj0K8 zD5~~#!s))1NaL@8_@j;$lGigFVe1(-Ua~^+dWOAhJ;TC8E3}c#rCx0&&vTl`cgDX> z7oqpVoG`RNLS5e)ZLzcwHMYrfsU+SA$LB_%eI5fj0;)c@wnlT=?Car~GLg2pEp9Z# z*}+vuHEW6F+9yAE@OhkZ&I&nK3*w}1@~q_%*N(WT(K^B2Yp^`e`A-6>eli~>KW)S; zm53};+h>tKvj=6W+?C5 z2c%IduPHiy(+q!KJWEV$+zUesBs5Q%q46~zkmGonnCNeeN1UE5PJd>{5l|IA)C|S# z|AGRV$*Yh)A2Y+(9?cM4*Z0EE0ttOxbM)5iJDPG@o=Y7aYmA3S7l=1q`)~wQJy~Lg ze$T2!_BZ5JNSRAb@n4UoiHp;1F|%FfYU~}TjCV4c%(f?K$YHJ zb2QOkTYPp@ULmx172Cm6Ocz(N)l|>|iCK0QD4wlC`aEAIs(u^eGrv;BgEQr!O8lMYz!6ZjXn_TK z#8wE6e=M&M(n&SL`Z<1L*Q&l4S|CyCY>CSIwG_QJ$TM*@uZ{5weK%2SHsT1VI(g6n zjW=#7o^z0UOZN&)@%Gz;MEeI07+N5qH_;M3VJn2Xwv<;0MP4+*3)(r0p9IViP?e-% ziEe7P5$E=kR|vg`GsSVOk$8WrfT0BvR|_rC=HIQwWi|2&p$b1^ywJl=%wa2pAOTgA zJuFdCVteuMetCt^Js&eXe72eBV~Q}eK%&Oh3OPLMBo^I|WJKQ{#yDi1p?I`Oe~y5v z8wr*u+p?qR@g<586W<$Q14TRW_U!%`S|H&%#}ch#>wV@gmDl@>9AbtCFKQ{SHxeh-dT7O6=-xpwnIF~oi|+(+aC=5 zV}Gzs&->?uk^#i2)p$hM?_aA2kk&sUQ8#sr z%I&+6n$BYw@hEN}9@EHx?pZxpgce8~V7_ZghLXFp-5K%AW)NP9+ftkI-W&l{zPbI- zq!@viXUY4jwbjLVg2I%xEN&x03nUgXAIS-Bq)D#4*S&@v!dp(7(`c>69065DjCeK6 zjg%>5!bWQZb~vd{2dU2yeWzNZuG_m4qL_`6%B_*u%Z@bInTICXAr$9iKrAfebuzEY zhT#b%4e0Cs(?w{3#N8v-XjX^=SvyW1LFVopf%PV6(LFiY9066Z4B7bxx-K~LP;+|u zOBh#Hkl6IX8hw1{NZzlHV?H(p48oqSt!TS&AC7=3cxM#~pEwWPs{DoYee(t}$JiPT zxoAYbt1n?Yr?cI2j~SDyA&b#2I{^(E+=MiGyMXzqs&U7if4-4)0@jMq0*RGg*67Jf z3)1bHT-&wvys+bjm(uL*%Qyn6U>UOS4N6DijOyRgPhk;PR*;CBWR1dbck(hu?lYL( z9)a_M>(P--7H|Yq!8@x^+_d$^yRMy=>S~XC zEgg`-uwP2sT6rhWqes1P;EF3!<%+!`v_N9S3oE2)V?Ycq$@_lnTI-F&l&7SvWfJED z(vMi5I^tj>QsT6c5i<|_V)y&|rL%hui_ijz-7W0V$UV1|1C8Z9Of`@A;G{JNq@jCG zas*UmbhAS49qW^36Xm@u3Sao);k7HI{3(}3-S2(So`$=XwRYRk*9Vqp*z@R4}z&>J%IMU*rn5A$$aTOE*~7R#1f5Z zc~@zqE$^2R_GT0go4-O5&fVq+U7&(_V!O9G`r@rpnB8#pL`5PA2cw+}|) zp1Dqv^@UoF;8d;_=tae3<&PJ#kIh4Uv2WKDX|>NgE>(*kTc8+4xpKpBK80)zJtI24 zPLnQ&ycJ6 zNX#&@L?c6~a^VFz=Ou%E@x}AArM1f+a|Beuy1>5eyD~*nO4Zohb9+ztjiko%>2UWoTk(frL)v#gdRePsXn}-ZZwpk@I#oG+Q5ExX^yVnM zHwsHedw+?L;8a|_dYI%j0 zAzpY!pT1;q>&D#ufJDe}GnC(=)Ztv!8J4Q>m0q}Gz-Y2MScfB^YD}ydil~WqIO{DF z7c9K7A0n z%*Th_-nh!~0I5mh38;cKMxhuR=Z<5umJ2z%^l&^fMJFoDgslzFqK!LDQSm{4Az=Ag z1j~@^ltZ5l{t7n!R!M zx#5xJi&2+(de~YrL5^+;)bz?JG}p)!Z8fbFrk_27PW2MeSjR8IHD~!5oL)8(`(4_H z?6R711XRIZCL0w+569_kKBD!*T5x?)*#C@)H9Y~)1DPW@ZPRQ;?@qWFtkA8zLyD_m*<4i&KzNc zP0CQL?cG)^outnZP?aBGf;tBXD0k;kMy$wj#&7OAiJx@aa=mca^EMl7f=ZpIq7{ea zvO0ZI#Jxr)h$qWB;xDXpz1nO>#bgWmxzhwqY_Sok&EJaH01$QmvI`j$E@8y5_842y zIPr39M+_~HFkEGVbf2t42kvZR#Dckl*d6o~3!GbV1XRHkvR!CTIpTT4{l%}R+F@vc zgb}+R1py1tl$G*(@Z_5TSSN3|m}6tW5m3eFymU}++{PqNoX6rn>{Jr;k5fr{E;L1` z!C7>t;R>{LkS%I?r5a_s7Be5qAKPJd*U92=YJ#B!60i)}j@B0hJok2*nD1i95m2@3 zogF$BcN`s8onx}cy+1Y^5+fS_XosN%60p=+S=kT5C-p~*-OKek0;;6@n4O12kw%$( zj!FGnBk-_!gGJ>r9o)~#8Ch!XLvO1Wplri|$aUg=6xXG&&OO)g8-|PLj}WV>n{sy$ z60s-xA+r_|nh+`b`0{KBzGdSrHd)q;BcO^;)eq;kI668aZi(7H!EQR2Ay%*T#Acic*&zvvUA%@I%qOPxKn55{B7>krV~ z)G85A@wdR(ISIcbw=B+9+9~1rq`^Fp5)335{q0tP=(D}w7J`CmZ}D6$)#>&uae$hZtVY2I>V-eaIR zty4I9dCCjvvh&W5mUb4QBM0*SA` zLXdlGEHa3e$DD_zrenMN3(>V{qc{Spo<)VAQ6Cb~Jxw_}_-RfCUifW2n)AG$n3+2k zJ-;yotz@UACAA-mcCd5M8nbiI7W#&;R@(-hO_a+@b7}@YpSu=K^>7rS1roON!;y=Z zJG$c`f59_2CIjzyzY2}rI)Edf3YG|4f7vqw?=IPg91I4CQ5~XDi}8lY(Ipn$`V@sm z78#*Wi(`@3qA<1_v^J84%Bflwlz}6L?L;41I*QN&i5H4U1W(Zwde1>FfbjF>et1N(kCgoY$y5n3Se`)M2+;MV|^&K}1I|I!TXo>7GsowMTz zs7h0hL80jeX#e(TMmU6| zzRnTpc=p9v!dbhq-2H%rad9Rpi_{gKmAf(@zbB+)-;0lh;1*#V0afioC!&*korUY} z@=nm3XQbnLfmY~S;b;+BJ~hukPET@$>Or1$QZ;5-I&SpV8=ZX;!1;j0nXPHa02c`+ zYVw}T6WIMY({LQB&hzI8sDd?y?dsSf4ZBa$BW4B}V&knzh>qXmaO7${a$1{?j!!y& zAYzjzA|+YqOYA;}b=_T>aa1XT5i%RrOHM=B3`_GE-Xmna-IVw-fr zZkV|HR|E>x{-NCFV~9Ey#-sBME+`AWn4*5uVh}qJN%^bPnGvCSF?fdd8foQhcM)13 z(fC3FEm(j({p3>qIpC+!5uVrRI#7XB3QGcDt^bh&1TP2-_y17|pyT1zhPSLd%n^vB)}Eopj0USjWf6U!l0z%!l5CFq~I&R%-BUAV)ye`P|Xy@~!vE;%4%5zGJH!?hx99RyEQU+uk06 zI=t>p+SoNi7SBA;s|9AnRaYO~9O;1uh8q*>lk%GF1=l=rPA_fx-b7!77DyP6^+FqL zO~~M#@>=JqYJG58S~qGF@|ug#!>BwTryhLE9=qGjVH=T)<>fDS| z$r#60o6_L)dLksC3P#o080V5BHWQ7h-H#6lS|C9h^+#7M9ZAI7CM+L~`whVUQHFHr zlCK;ARhu95N5$;Ck*q#V8L=*V7;d`VO8h*z88;q;BR$whWsz+kKOD0{Pkg;t!SzKU z0sC6=h<-Hg{Jx=>h+c60U8sURXV!Z)j>eC7Uq|aLC9c;82{;SH&dsP7i>sELN0Ykl z<_M^QGeQc5cpw#*ubq#~D^o={?*#jXaGr{dw)-aG7mc^0wEQL93>G9{3fUu!#KD$|~BsMgyDNt;*7HL?B}d~5DU6jSh2gceA^l4ko~g#}=>q<5&%*jkQ& zDi{w?D6DHoV%_K3VxwbCF|B^QP6eJRe4 zcSpL8mgrjOS}x*ou-8!J{`07i)o44*d0Lwwe2>kjPm*dyXo1m>iElAl-l#~3cqhjI z#uC&*ZyhAf z`@L9%7D${53PTOFJ1cXhO=rZe?cR8gwk9n))<%RaGJM0q7M%57z5TKAf$vi21QV`p zhXj1vDHN*$1Ms1+_tGv$%n?xa;?+o0IIJac5qw#yib_N9lxx?e)*rk?Xn_R0PYT8N zULjcD=Daj2Jd-1!D$#T}%3q-%^E2ep-TH~)ct+Z8X_=TWLJK6|ePXlWHevW(ZMpQ; zp_n6}YD=jr%DnbiNlRuiAL_Q_aF^#LQq_y4BD6pP-Y5ACg|WE*!fDbtiwg04`=KZ> zvRZjsZ4v75Y828qFh_aq#vC+ljte^dWxewA6nS2)FeC!kyb715CGHlX1rkTzd!z0z zMk#$N7BRwT*jQ}1Em&H={um-@=G%JH}z>m(8VdXHJXI0*QOA zJy6RB@s;&Qu4RN~k8rHx+E9uLyulGr_3Xz0bZ_Fu$`=#lNa}zSV{v2u8)WC%t0J^O zf^SQQG*mkiUXh;w) zUcFIzdAO3BONI9z&NM0%9hZdQQmrD%YKz3pC_)0(1va}hIT-)kHCLL{@ia$36+eTu z=4A-J-#bHctUSZbM?nJC1-2*ol3@JYEk-JHyu}ev1?SroitFn`aBT4qDQDp=Ze9%% zur9FOLfZu6P(wj_bN(quKoy+dVdp#F8;wIpwUc76KjCJ6AOY(F+jXdO5O#U3BjLP{ z9065u_DrFeaUd91McgCa3GYQ{fds4ztYx?vfHSTiBwNCNaRgNHvrFmTLHNt3+2r$( zA0o6sg0EL!-uhv;rPd_XUY(oyfhvAhrd^Fc-gCuVxw%b!ZjJ>K@J-En$YZ>5;FTRh z;c0%B465La5bGf)_+Ud#d-URjHaAxU3E1Oc>wPNS@w?qIXv|_=j)1Bu7N$teXOEEg z?hJbd&F8t}nP1b9a99^Z3nbty5ZleF#~>V@*Piu$dVvIdKe9K@uXw!WZ445PH*;~(_bWWnzDeH%`*Z713n3UiyM0ZNA{NW- zZkHImEvz+)mZ%6Vkoaq}4?2H)h2S|%et%2}jKwuqUODJi9N-A3S|0049iV)i{ThEtaB@%_C6tm@^KA`m+#E9O#&UHx*VY1B=Ttu!|;k-fZQRC(-xO_kY#(mjZ=e5bW zAB!C+Qwli(s$l$@#a^@0@czZCP}Tkj?tVamj|e+W&%hnLx1d%g{Wt=uU{sy0ZYxj2 zbDO&<6Dtx$7^i{}PZ-ftDDoDi;SEy??YFN;=3;%2;NzlY^HOncyL%4P*lZlU7E~?& z5QCanj}`peO=0(=SI;y|Tw9>*R%s%%Kmx|ES?tvz6_>U*MgfDSa0FCoT#G=jGY<;$ zG~^Z7u9j(dTfa}INd_J>|EMqnv*yJs$go_c`Q$o@y_0z(7VHhTs|NHYbD#OxLyj@b1N6B zfAa)X!BS_lOM1!p-lc1m7gLsUr3(r8bg}hUt5R^+?{hfT!T2@n@4ijO={>EbWo*SSv_JwzaTSUV zvs3WxjXk7Eo5DB(s>a!8qUp)@%9k0oELD2!4i+LTHP;Lkp#>6reAjVG94;6)Pnw_Y zE5aBnj6lOtu|jcbZUTPqFj30b5XwbsAp!ldXzl8FY}+eY3jLPO5l{t3#R|ou^@+G# zV}P_bYqAI}kbvdJTAzUlczlQ6(oHm%>gceA^`_J-Wm4NMX z6;h7lN{)c43z}n))pc6AphEt}BsVk>fAA?M*(X+r&;kiqkJ%^e6-;%RPMHii`+p1 z&Mvb!gGCb7>9GY}?Xi?2po))KK3tH7+f)^yVI3p62qYx3H0wIp~r@07pO- zT=CELq2HW_pPX8WlCFkx^XJe9|323^l8Ci7uR(vgE$80OkbtGYR(Z$8;;yY0pb>}n za0FDrzLr9POUL2YNztg|vuh%>Kmx`YSqyo81in_Ji`4pD;RvXLy)%X4q0uZ-Fa zP2;u*Es%h5Mz)vt%<;J2;(^MVc4s&Os$fq|p-730#D)EA$bmK&xE>iK;OL&sZFi5x z^BSd)MQy4$0;>4uBkRa`99z1bSbH4jdX|uYQ3@7;)QG`RI+f(q`R?nW+>3JDl(Q7DGQgyYxEOQgHs)^h|@@nf7Zt48CdE4N7Fc5LIK zgOGr0-C1wRDG*z|IVkDO*~}48#gDw!UiQHQ7G08B_t?&jydc4^(@)p;#P^&YOYQD% z<_M^QUq`SNDLV% zGuZwN>)I`nHoi-umDMXy{cG!##(zyFw>NzgoF`N$wWmxXmplCs;to|PN6ei&tOZTsa#JzMh(LSb$x=*npjkSXa zxxbpF>Sm@cmDadZ-);Gv1rqtDR-|WJf0CW2U_KmXvGIS6J8d_43xXC%EMhxzXYKVP z@qrB(vC6U;ebCH}7G{-k1XRs!VMVr$@*@u?$V67#U(&bBfi!%WFP{&PcD}5v&uCNU zr9L!t(oX?eU~YTQwj%oWL8Q;rJeG6Y*V?q#EFZer@Bv3aRWu`v9fC;x*V7o`zH6s6 zrhOdMbt*ydKJTr#t#tW5k(_w^OMrKlon-bvlESOlDa7ZNaQ7S%{u}Np&4x@QMgxB{ z9|r9Ek`DUg>3grm9067E{5DLXX1;Rm$~>}-}zS2a0^pal~7PmWi%9-L1y@5(*~gsV%<_Gi*=PLv~{iZ5N0o@_kJ zP8xeNd@I_uqe57fKAF(5SA|xqD}<+OCy}eQ-vwCe>~zO|W5iFh)9BpWO0IMv5tKMl zFbkVTw7$r-WR7h&aZa0wRNGJD2&jU0lg+EOS}G>oPo&CrM^Q7766mA*v)w}W>`CNt z%OA{#YxGjlyj~JbDcysh1rjiS>>R9%8^oobXN^y_>s`YtO4#+aAu^_PBp(+ovjTiJEC+>45YiuGNQx=lWNI5ST{xM#*hr&b#yC zOxH-77ahbAP~~*{u3*pF{IjghXJ6`V)WIVrdQq3Z*jlayR;Xln5IH_2PbiyUg@)`8 zB-b=|2=Gm$P>cxF!JiAg==zXo1XU9ftWd9_Kr+U3ZyiF%T?cn6_M-V+;<>jPB-X`S zq5E?KiL=%|ma4M6MtJ-=FY1xBh$EnCHrvxMfwk>PsGZ znx5Q`D=Sz&hJ{vW%g7+|^`+cWk1AEew}Jzx*kCAv7Dzzf?9@=bhB!CNhmx4X0wkd7 zz;-Lt@pTXxXk){C%y=$d>Ib{w1dH=&h%S=6~2K?fBQ0a_rz*F@tZRO~w{hMs6Y zgd?EJVBJ9>%6!V-K0a^WA|^hMrzcX*3D5!wjYAcJ-1mu8^?gP}trEYrOrqvb{Wt=u ztoK(4Gulo4+ef|7KvC;@I{no6p^)<3RxrMlPpqrv2s?iU2xaT?RVqlcb~kpaxX3A$ zp7ae6pal}9`Wpnl!PEZs(X?!_xWqG=KJDYr5m3daYSaBS2ReSup-1epgz2LT_Wx!( zi_7)(#K)n#PYZv3hkf#@XtQJ{*&Z~P)so>&YK4c_bLj2gQ1B%O5xbs$hvI6ayo)#aE?SbU;e|6K-D4><^Ug|+fGRl3V6j*IjndG-1bXP#c&;xB`=8La zLUH)!R_WZXc&ZhBjvJXkV)Nc3%8#cf|6NN~Enh7;JV>PD@Az>9RKXHqd)Bx&qe>k% znpo6C_)4uv{NF8^{|ZC$&SI?Ux_qDdW@ZCgIe!#&>fKm?7D$xXYLlt+lmAZD*9Hn2 zx+;)rw_C{(Pz6T-tiS8_OcHN}(i+zHgceAAQmT__8~?n0*ls-&Zb~DP#?h5a2uDB_ zEI0PXNk1!jqw)0AITvmW0ExeD)+qId=l-3KVPg+S4w12Rq23UVfGSwhY_;LODslbs zD7xBx34%Qf*x!L|Fw4iCU1EWD91Ytx3qcDcV9$x2Q5C#Vw2w-lq|$S4c?en{!S_WMO>+~qyJyfJV?sCrs`wTzz5PWLte#CR66YdlfduT&v-7#&1XRJ6kFA+V zx0AjlO{8y87=ji^z*d5dycFJ2Hp-yd*3Y>%5vpK&%p$_Arb!OgsdU?u2(G2(2+)ox z6fWzUQ$@iDI-|o`1jpfUeEzC|C3&&bo4B)Yk`;=;J%+TYTakGCo*n+x!G!3ozl^4+ zFGK8GLh_Gq32zf)5?#9wZN4k7Xj~p)MITnp5=+*0$It?a$;5=18f-?F56P>k($kFT zq1bt%tE(MHK-Fn0WAb>)W>mdfUYVKnr5!EqvP52igtHt>NWi_TsJLkfcWxg{Et{2@ zZbaSEi^Me@`Fy~0```(HEcW`%jBeO4U+n+JhRZor!91}Dt=QqA@kEnI(>`*M}pZ zYTFVcqNlwK#mw5ph~ZDW(H4o5#65vsF|jBb%S2*_9`t!>s(97BD@Q;TpYvWfjcMN1Y2ukreK52@A}QR6)W5w5RjiTA>O*d4 zn*B9TEVt$fsDh==Mt47Y(#LEz@igheu`2{}A27Hzm7Az11PMfBQUly>kE6=S<_ z_X85q{Y*&csxfH&frBhnE1q_yX;TA4H?}JmycSfI+p^U_Y}9n+yZlYH-oxH>ZCg=% zaJUPG7D!xS_aiFb2^n9MzuRtKX+jk~&Z6~hfg_+Q)y9zgnl}J7Ja~)|j_SSbE+&1q#?S%@m?wpzdb>HD)h0&imDdkn*knk~4(lxJ{B<5_uQnvd_jDKR z^e>>fuS`k)025)A_gUs6@qjti>m(?}N&PUiK%!!~A=w?%TQKc-fe|& z6-PkTk`z{iTyCNK;pn?Lt?e6Ncev6JR^Ln5ncJo9CgaH z;s~gkXlF{Ett}I_X~;edSDVxCRi0?FSw9RdknkH}NCF}^2qqh3ALBL(wEXxubTrPI zBcSS}fhkG0s1$Zr%PZ)tuCbFBeWs&;x&1J-KqAu7klcP;DXeKJ`?%Xfpyw78pyp-P z9067RHB8BdQ^$pt#j+2r8)kIY^POn;Z;YV@63sdrk`9Aj3x6G!bAHgqfp)Apil*PT z<_M_r+{E4t-Lz4OvAmZ>&TKR4_xv+z(HvuFfkaUULsD3wg)Vu?sro+Co_=ij2^p-i z<_M^Q&y7OSGRlnZ^=K&S&k?yN3KCrn{*SG*4$Gox|NaG%wqQ5iAc&%J%?zPniwYtN z0u~|$b{AlGcNZ#PfXVKTqGBiFZDHJYCw9DZ`SbDl&U3u~aUAFO!|d+0J3D*M88+(i z?-fYkkh5Zpp6?xbN^NVZ%$5mM;nO8zKT0tE?nIh0q=&0?C+f>OsaLtVJ}LA(!KXk( zlKV3L`q&2LgM+K|d?0aA(7`Rt_5U_AT;13e&OB~;9rbyf{6wLu?Q0v=-7U?3Zd1c= z-hLS4`wur$r;Kx9XhGt3KPPq2on-%ytqoVVWNsi&GwQ9qb*jbk>bt0c4~HujGmetG z9(Jm6+2P8PU-@MBU1xP)>t;$~UBm1%zNQP`Zai8`&>AqbAkq7Qts0ZrNO4X-C5Rek zLHu4)Gc9vw9f?5Iz5UK=QWZC4Wz7?Uu%a$}!2K@Tj9QHtT9DWxYDQoGT1}b${j?xn zjSJ-OM11?~fi@C>s?qbE)k*!WlsA?q1u-($nY&xJ)v_iwW@tg;m};x8=~GoHE@QZN zr+5YO0h1lIbGfz>fvQV-XEn3-f!ykq3`aH5&xOCe<)LNQ@@Hs4Vwrf?S`??{7OgS- z9-n&!^04M5v^8VxB?46^YdfnQR?N;lyuvVsQIrdBaHE{IV6mQ|1&PreZB?a3aPB`2 zhWqNo)d221iB0Twa#L%+$X_?Gq)&o=1I0@+M98Np#_P0ZEV%z6Rx?L z;f66T4-DX+nq5}!9(R-oRJm?;QpZjoD$+&`&tL-+7yeE=qfT2y8CsBt{$isZI~e7k zT+VQ}8wCaMf67f$2Y5J31ghk_J@LIW-{reNZ9JSYv> zq}i%phD@LepEObJEyJ1jc1zd(VIJ)LX*<>D)NX~hK1@~&vs0~|7b_i2j*+7yUDQFP z=P5^f91&xLo_FS5ZC7c{pLsE~AQ2mFr;gb@OIcUT@OI9B7RZOyOVvsrs3sAp8WicG zzO6Pz8Q$Mel`DOKGfyeCR67#q&Cr6xod`QMEo_F86K@zJ>RKRg_F$}b;B0k?Ko!my zV$W-+GvC~FzE*Xvk2IGck*K#*b&Dq|^%D(qNz`;_-hbIF&AV@Xi9i+3D>|KWBalZg z->6M4sKAbva8*A?>{EU;RLF<>c51ZyA>~s8PBOoX9@5=&l+@9NT47JDoq3*>qNQzd zW@teIePJGut)A8n6mVHGSS0#(%}yQ*;k*OW`KhPs@k zCpz)RMgMA{|JGz^L4x+NS3}<3QI4NAWCOZw59IE*4`_>)mXZim;qN4T88e;v&^nj2 zHP>yVUl56~n)d3x;M2d5OCl;ly{%o$pca1&mU zz|od!NM5EO)|Ct3P79xEZOn=(5~vDn;HJ*+P(uB>*f2)Xct_sN+l>3Gr5Rd~=u^o- zeP7j7Et|hn5aYcAc$now&9Ue+MFLe`wj#>nf=<1@%WzZ)_D)>Y8*z)dq1s9m3BBoU~>8AJH=xf8EB^R4#YyoxlJAkj44UVU=sjdE+5 zVJ;cj*@^Ey@LVf-q?$ya3g;E!buO>xlb@91wNvt>yZxYpySnYWt@_S-Il(7Q)LgzS zz74jP=ldETk)A;$9NgX26?g5_ZQ+KDkz6Nx?(@KrPxHSZ5vWSHa8id=_g0t380x(m zFKEKMcvj)TgLhN3AklxkyPDS0OU*nyM-ZD^+VNYxJ@~z?xe|dYD}N_7A=FoW{nHj#Z)WEW{#Td>7w*2`@Z=UfnLn2U>bIwUUmP*v=)h7$W zH^7e{-)PHUcUwf!f<)qJceUG5K8HoC#g*H4#eBtf&PNfT1JFC4zo2!p&CXvyp z&T3rEP}ODPK+<0jCj~Kkgn@YV(S}!wZOo$<&!T8S;*6=YS}-a=-SN#3r@!_^13r1C zBVXV!T_R8=AC<>e8~*-ZKb|^mF+~d!TZ*03wQHH$*3FPvT%(o^PoL(;r_NX|5val| zBK9U;*XJ>(+_=-aLDEt6dgHEsThUZ?sMMF>6%p_AXWrbmoEINIvxju8keDmz=bM_U z@m~_fQR(CB@^_Jx#||AR5vb~r=d32aXracv?kR{-b$$5OVP1UMwXPH`NKE*B zQJwns62!3ub$QAg#?M`eln7LXw{}riRtr;i<+c%obGR43l;O)?E@({Ag2ZVH4>f#W zTlMPRW`g+8p*C;1wkcn1=PD7XnsL-c)wc>)TMqIQ#M8$v{LE85ZGI88-E=NO{XVY_kv;UejokV0jK)0jKqZR*_oSfBy0%wOjPoP%7&;p_{@KW% z=aeZ&(SihyEqs+j$ z$L4%TJ~1YM(~zsu*^0X7>VN8<%S4YBcKqnlV16+>U%Dnp)EMBdx;Kha9gi6zQhLp+ z!TF&UJYe=|i9i+Zi-;-(ZS^#5ls8d&jA7UZ3p-q`ukWX?RLzGjxiv$KaoD{&4NlCU zGvD=R&k}U{=t)M@>cJLraAke{+ATU-dEgdeWZyvl{YQEFtnx^`ds#B zOZ**3Z?T)PLhNQ>FA(h6A+r1DR$>AB7t^X21Eszh*b$>bt?2`#p$zvSZQi1KuUr8@736}bQAW^q_Euv1mNshKQ)Y-PJU!Co2x{Q9>KqLZH zczz-dIr9XKkKIPU{OHO$U)iOPbo@-3eBDU4-8rlu@TQo=ci%|-E*p`U&0k4$b3ESk=8UEjn5s&qn{xx~Ec>Vv3 z;r`?WU0-=KbxY{T@c$w)-phz|8Tyobu~;X@m@(9x^)9`Nw#scO5vao7M&$6?n6pZy z*3jv5TS{F?kXR$eXf4Jl{yj#AL`$|NWHq&LZy^z=!rw;hu{`Nd7rsfSJDT)mXW;I; zIy6#0ri_ky*4jeeUEib6OsqgZE;HoH9J8H4wY;sg_)G#r3lbF{F40#%_>E+}Hmr9a z4GPnj3e2LWdy?6mrtaT;vw<<)8@!d+_qX@YXk<*gH8boF7L-4! zK5x90+HOx~_3axdKmI%iMIX$Sa(#{H>B21p|C6Y*y)HpLYoA4F8+i;Q(&qc;ZuT*z z7XuArtT@+SsVk1E?Jk)>6&|738TDJIz3|yWr%mk1HiTp;+a`S`F;<&MhZQRnr_gVt z>%~pP=*Au;OI)i@zpqul7qhf0^S9Cti3toXNGv!XulQ#CBH_O)Q>^zMq?x*Ipm!T4 zNd&6!iU{xd!$w+-n>(mSWBFkdgm=)R*S zk8)f}&lUKykXlaa#2@d;+1+!b9bVk|74f@)6?yGzb7n#(g z!lM=b635DX)#v5ZbaH^SQ~ml>IW;N&U$Qb_4UvhmO-k_%&THrsEmS&lBtkumRELD8 zWU#qm_F3<2&NpvbO}~rU%lN-gh36-#Y=#wUGk;6$A-~7i-tdi9 zW$PxIF}s6AGzFFX3;Ld@$nRcBp#M~F&Rh?ttBHl1|pV*5}4_Zk^U_(ok3R zTx1>E;zANJ>gcMP4yi>K9qvyG-y;~4kFb!?hilGIGvnH-;d-G~^ zVvE6oIQ*_WuYa`!HR%_|E|+#w4gJ;bPwz?U|8P}jiY_{*n)f0eV@%Ydu}*YM{&+!* zPOrdEzNtVPcWTGbf`t7XS2arX`T4oHuOKR0l;zjk%pem*=Hc7HZt6bKvFx~UoT!-W zrj8VS+h$qEkvRq8`@gRb?VLJN5ML{o<ae zS9>GkGruQ0nfCE__qq?3W5}tqCaR%3+vsn@{%4Ff+dgQse*DtESK_2GkT_sl@i%?w zMt?De)4VeL-q3K;>RDq2PKqV@n1sKW7dx@W7WYs){> zA^qZpGqfP_aNf4xV>rGxJRk1mR%^5E>yVy9he!mf zKTaZ0h1X4|`yM@v)HiKJOq)+&*mZW;MZLe_|Bi5&X;@|aJzB9^Iv%TcedI^Z?w=r? z2NLhX%yJC$sQ|;~X!in!OU z6wCm$W2(M86*-P=!}PP}m-u%k?%O1`?2lB`(0iZ*mX)wa^r#p{MW>O|z(E;F_& zw*g)8BwXrVhlF^el7Gd!cJuFd?U5*J_K7v2FRQke2vlLOJ&{WmV!;~pPM}?{hq0rr zN|5JbZLmtL4Y0Ey(jsr$z9Q>f+>UPdZE1L){~a9(>;NdfarRgbV!hC5b~UG1Jg>o_!* z2vp%YiRu@&<#=H7E@EG;Bf~d6u2JxPC47BxCOq-#TXJ38?Px&)*DIo$RnS%KXUI#E zyt21MpbFnB!cYB5)gC%jqXXCXmEIpnWG3e*3u=j{_O{`zHj7Ntrj#sA{X&LH1gh{Y zA^h!5(OQt1C;j9zTzVTIVXrh)4%~O7P8$tg=i)ZE)V+>XY4KM1U5hIDZ7{ZZH#Os{ zAMH70jPy2;iT-;+E;`Z{i{^5rSG)muBA&W`RU5vclZ+EBTEvjz>QWAGZd>$_|7(-zTEaRV4ykdVJ??-%^5vIFz! z=VL=80#(00?cQT@xCYI4Fw}t@_@Ret6tIG>+%<%u1qs<};8)y(*b8Fu{}8B>{cz9C zXOU{-w$hiOgBV(nkbN1~T#ATu*-W}Ja-c+@3Vnbg5AwklZH-kHolp=jeQl%90l%Zg zx+G|;=DBV&?Ht*Ip#=%N(!#4|dQ{sHzn)r5=_V1V`k(K?Peoc>>xFdQnl94U9TIrQ zh`8607CiFhOuG7OYl%P=euay?qN0lYMz@L7)FwpwK1V|Sx*K|T3yrqUqUEo|v-2cN zzfSmM4hWwN`uBR@-K7r}UWzTkOCe&v5OX40kib=@h&3RhmXnxw8;f}t2~=%K&e6{oGxhM_ zGj)HbX!^p`lYSLrpaqH2N<+P2-gW#v?^3{ z#z6}b+gjoq$NI}1@@rut9houWe~AC8@G6K1A=|IivivW-e-lxe)Uy^be9Ke_>O=6$ z0@tWwzxGlAeLQV4i5}5MTD>BHcaKh2CFm-R5^ILRV$Fd63styg6y0uKskDb!GYk=H z2DBi7caO+Q(chq(M6~*{E!`yoRk#`ySr8saXlJ_^T6bn|X`P4!-aVr0v`-P;BHpzV z|LWCe7agSszbvKBW#S|PRXC4{J|=h8(gd$9 zG-X~-X}&^2_R#CH*3gHdYRi1j9uk2noLxmEM;|Lb>r7o5Si3DlKNWh|a6PBf1!tP^ zp+g$bv#-J>j~5d1+NY)dh88Fu;YH#X#Q%jVT+fN@evc#C1@Q~k5x*c>kiZp=PWNN| z3~jBLeYlu?kU$l#=Y+TRNURnkW}hu$_CX60xWW;BpU-zx&qaxJgm?y#K$ZN|_Bb4` zzRsCQSH+DGE6e{rsYu`oM?^;-i6@W#KLo1e=X}_ee@T>BU%eCSE3_biD;&dqZFl-c ztl_@L4v+{`;XNjzaSwE-|1RA?Z&>z|_KJ|eJx@{7X?J%T7P^fdztvYFP=)(cBJ*XT zADeit9*r(?XV^Uedjpo#+mL__!KCYTL)2vQ=lZPPq$s-du!q#40=spO-e5y&XAUC+ zdUHYKzOKopid?b|-u?`CTydvzq=y4JcD;~1oVZdD#u1)uz^f^=`x8%wz51{>;0ilC z(r)H<^5bNtASx7luonBK(grqO3@u1t?>kZN^}HR6x;u}4deTrLP&KZvJ!w(;1o8RT zuw#a{jVR4LiIdqngzg znR@1_-V7~BV3$D=u{GS5Ri3e!+PL{i1ghk#d+DtcJ0v>?$i)sbYFT_wSV zhW&H@(Y9>LxW)8>tDi)m3V&I#Q{BXl?fEvF{`}!5UENpLY)M~>P2|VKT?Btw@qIqn zj@dt(Nn^bmNxwM~7E5f&Mv)tNE!7aK=25#IYh^o$)@Uf-C8)x_jUwM5(Vk^TOrb|( z8!@yXv9EG0kVlWMcqo8>+lLMuG*kO)-C{UANM+Oz!A6R79B#tbb;T)1vS z(nm}t$G_)_F=l$zXUW|}h0Wa_5`ijwx`gkwkps(lF_@ma(^%@yiA3##HsnU^c=Aza z$Oi0L(t%C29YCG?HIWEZ$xp5N*_Rz$)q$3w@^g+V>^UmFox3`)&7-=}o1Og`T9B9$ zWkdFFjw0cYj*6q|(6%AdnFr7j-X0QxDx8UgAMUOL>vXIoB`x#}El30t8**@FQ(}F{ zFkjX2ab%4r2GcuZWCB(443{&g5%c}zOic&Kb0Vtb?kZKRoS4tnhO|Y6r5{s{(Oqd0G%AzE14JyP7oMA0qXZMdD{o z8={H4qK=~tISoNBO<0pXKS|alcZon1R^JqNqQ4V6sVhkr#!R@f_Im*p-IsKRc$I$fhfPHc1wW9qz-N?mo4=v&){v{KAT z$zFyrUfbzehm)ts?xSuJfhxIvd-hgm7MXB_45+{uT9D}9#D=`McvR0U44D>Im7Lju zr%TCYkwu3Dsy+wU5dJz>U(?Azhz1+1|2Px9a?F)s*J12goIK2i+?+N_KcluGe=xR- z3rk*Fs87Ge7+R3H7-vHgmM_+asD?3G2U6xRw>$|d?Z(i8gj`R*LY_0bH@ZJr`I1Ql zs^s(d^hnP(rH&<~%ephPAc0l$#qLtJo>d=}MofKW0#$eo#d%D0VYZvA9k_o@KJ$_r z#cXh>o<88!MS|B*RFrEeh>J-q|mh-BDIwsFWB2b0hx`h`NQIji9i+h`WBVaySuQomrv#SM_EAVQ4|3Z@4W<*&UR-tkijNRNXQHm`U%4>Z$5t#)b~&sKTz} zVrIA!z}|~ovMYNW7+R2!dy`if=)xAAD5q^o(KA%->19hEyiUt4zw8{5376(B%(7V> zt@>?$h883;=83B?xG49?NW;AQ#Ve56T2$5MueOs2ROy#Glfpe#ilx2bZP2^OncXrD z)}GXD!q9@m*~7M^S5`G;%}vAGU|Uiki=61K-92a{5vVfS=uG05R96-~Fl03jP77pj z&onCeOuyuzLC;m*C`?s+Iweq zb6KKRJ;0Bl1&Jo#Y{|jGHcH7yhBMDo0@=Qi5n8Y1wIu>oT|}LX+f_#>Q1#UkYNST^>!d@kv2?IQff$qq-yO#p68?}-=60Q!s>Y- z`>=MDR<2|XrUMHSl{>qTb#7CXC1VT(UE<90_AJp%+Illol^kYABHJ!ju2(!pWTNd5 zXEycLYOUb57efmY?Z()VX}gyy@r8yn@AxT@9T+%ETeiH4M4;-(4Ht5A~ zEuC5Fmn^OJD>sG~Bofcqkru0VE4LdT7DVF*foyEtYVFu)Yl%SBvPUkYziy|prLAF% zm>u@)`Pk(!zqUz~>Hxjd=qPp?M1|kz%J5aW3iZLI!tcaoo3H=T?68zOl z{dmoA9v0;t+46L2NW$xJRIys`W!B$ zt_(I1gI7AT+M#9ml(D7^2~@FG4y1P7QtF<^hD@a3{ft#Be5JV^-sN$cHrlqdTQS&ctp0@r(clph3P;(A6+AEI1Izp4`pSX74G>(1OHt zTUQd+gDZOxNR$x#x= z8qWODzkw_`bgj1Oi%g(Op5fNjv13N}Jb8`X`{+J@C(^sMuj(PPvpNMkku#TkRc-Vf zGH{YR>B;J;FZ$0GV;m}F$F`cf^V|tXBmz~Bw>gr|5h91UlOg+T*|x?kW>ghk=$}K; zg2dVgck+0x$N~9hp&(9$+p)fD9eH@hWr;u)&cULZRULoUb*B}NI;m2$ATh($ojlFA zQ;)VZ9F^{(KPyNt&j~vs5vamBSnO?=vSGVi8uAg1)=_)0h6|X?)D8A2!(`mnIecIYi(G|sy_Ve zkew2ND*SCko>!qCYxAWx-+g@@MGF#9Y3{^xS3Ok~`*vdXx!8!+5jk-w)|({)RruS8 zcdc1ncE3o^n~qPRd8?gCzuL{!tg=aD+jDpF;cbxmZu3CWu7NX2a|l-V^%^6_xNYOh z%2sjZzltYPv><_3LHMc9*|4W`8}TU<=1T;s4wyNU`y&HXqpuUi7|}az*!Nq0d}zvI ziWVgBcM@52DX#1t_vewU6rE}6K^nH~s208Ul)5VC<++d<&f)5YBtu5kgSu|4o3TG1 zW?qh>1-mLQ5&voEp!RCni3Xx%Xf4JcHRB6&Z6pF!$?-1amKLTu9cn3vR8iyQK8Z8eFBX7$d%$51Z7*lSfVMEfJ`~ zdrYh{PFu5tlkNDNq5FtB!j-iB5v4w!TTZG%ELR?Ge4qwfR@{Owy|IU&C1-#;S>+d{ zwh`H2_@BfoyuTf5eI=Ox{GKIQkPvxg<`^wAg)3uf+~j4CUdyj3^SQ>R!^7r0(dXl7=o~jKG*$ zO!q2;ubWnqq6GE3%&HIVRlX0#y=LsI*SZiW1+8Vdn1{Rj=rkb zYKG_w-rgZ=JTmoTv)uJV_uVJm7G>%O&1~r3BmG}NWNTNIdS7Gc(#xZmQS+U-tNvWw z4n=3O&3n`(Uu!)iH%{%#o)#8M7HusO#O;0+c+kd0^oCtCslp#tk?U91O5N|XoOE7l zSeJZgq2rHDn(`aT=cT-D%*ft3yM(H*7OIkNhTQN5tu|>(Q~LRWVqaWNJyz1NB0Fnr!OE>VsP!{# zD(avA_e&AKAT5_xBtzV`Ds9Csmbg}9N-_`64fOQTP&OsgnhaccnLHT1k>D=S)LuHW zKm8&(AG2K$eHxc%bC<29eeVV{v><`|cp|DezYP06c^%z3qM1aX3iB1k4whR5mi}=e zwI14x^(|{f{&U@NR|a>1L}erMifnm_Rdfgsly;YJR}Rll%!xfJv0W`!Q=dTr(wQTH z`)%SGd|HW_o35q~Rb&EHcooDqP9sa^*}Wf~eXkwE-38p6=oRuqe_A|?b($F}8#&Im zWL1Jk(;MsCGF0J?iA?M+v}9KwPofp~w_#{O0{3)8KF&u==G8fkDnuqwh5JUL2DV#S zwsm0>$`7<-==sN;hNMXqNZ3$4DdTAH(5HozVRf?d$y>{C$%l;I^B0*F$h|GU^oQ#e z2qJV^8CL4UYx2maBSQ-k=&jf3CLJro-20cN0RbH(0#&$&AiOwZL_BrMM3s^#hW^&o z$A0Q#oG<$KxqgG7k5qi!o%upLT5@%YS2u`*Ts26yP2`-ZO^L- z<2y?Ps?c95=ERq#Y+t))>Ia|Bk|z}j^pOg0?JiNXe~A$>Js2VR^q0F>kvR*}^k2Re z65LM^k;^4Zutjd`^#9!ID(y5N5$W<%zw~QQy;;ofH;#)r^M1D9|KEfti9i+l-bFs= z<*(GVbha|AMl3@M5_sKox}k5)#B*V!_U#oV5vW4nyNISbZpJ38^;9p%MKQD>fxoQy zDq3&K4w;nJGN(o|yoz{r(eJC%-D>rjHZS(lR;6{7JiDrGktr_|$(Jz|))0)(`j8Pi78lI?`tu2|7oT63! z(T1S~3G~T|yFFRQlKYRU7r+n6MH(VzdiqIx@5%fgWg475J+OJMJE; ztuc;}2vo^uUS^aDYpKi9a!a;g_%6bC6rP{xJ+Re+jXt zY@v2Pw3S4l3a`5GW%PMVU$uFud6W-e1G9|C%2ThEML&-a^ioWAG9sR@4k8ti7uYq*tNT5GRM5LTFV%v|t)w-{2BoU~> ztDw_OZmwh7vb^}#k7f+LwXd>`NnKIZ*mg|@K~J&xHefI4_kN9dquC}5El8L-mmsIM z`l+u!8LBNS}3livI73;*dFKM%2N8Yr3b%{U~{<5N))ixbldZ`xob*Ul!f=Hl;RYXl5)G^1J z)p$r=9f?2{`b$OL#Bm+-?bnf<6cI4TxEE zgAogz+m1izutf3{;nkIi7yK1X8`6o_pFLml8X$pRdZMeCBNpUyX(L*ExRe0S* zWxOe7Y@K~)zUatR$!mZe3uRx%xrM)I|C!PJY-dgKOdx^%k%U)mVM%u7TLdpX_>e@P z3VS|@HFe#4w6#r7&f^~v?3RUN+?`=Uj($i|T^D(XIdOf|M_S*r8&7!uouCB?^l^w4 zS%8k^ZSBH$6qlt)pek=pRT4iVUL7lXV~M%sQ%QEcZ8&eg+MJ>V3G|8xk5}k*8e!a< zoA-Pqod=GG9XLe(VDqzdpnD(wWn@W;79^$)yrVb1J5+S6G1NkGns$Uvv`ONFtG|-E zd7ujWbcpQ!7qN8QwGrI(@E78fl%se0^Bvw%^fmGR(^C(-vx)AG*}LgB-vRueSFZ{F zFB}8=uIY4P9XHWhhX(SywJT7xAc13xU6~ro>G)2Ad2Y*(Qb#saVK+FPuDt(rnw&M1 z+bN%EnzhsX3K= z2wpd_`|2Y4(AOEo-}I_Z(Sk&iEe-XDtW(vZmplZ*KOBH1gfwvp{ObQ zwc5+T0({r7cDQ=OCRi!rXvpH6y2jpIQNj3fe8*u7AAqrSbHxYdAg{yOD@RQU@# zpU6b|7E4~>*opgT{}8kwft^rwI-jquszs)K)q-Oq__YD4 zbb*VBdf<=u6s!7ms##V2&wF0P=^r%bWoEVGgZ;)+v><_1`9$}K0v%uM+mde`oh{X9 z#9D(B?w3&G|9Wd{8yWGTn_Kg06Shh<8nIHLOeocj`2L7CJS%@AMGF#G8BxT^6u;C= ze}?mg)mKUcs_=@4s=$g7Z<`?WkogJ*Jk|U@b_9~8(((Ew~`u7Zz<;PoM4q^ ztnsYVd7UxigEoEFnllaUq>7B=RM5$lL?*@ zfhs&Fo$f`n88^Lb$xobgW@teI>*R{K@IY}Mk4p1y?HnZnRr0lZHM0cYSN*zH@RYLB zODn2_|LhN7y>R)=%SV{=^Z(q|mdw^Usce_?mcb#;;N% zwL@YQLkkjeca=-)&G^%#2z5w!l+;}Xdo$pF5_fxBGw%Itp*qP)9s>#N@*rvm9sHv0 zufWw#zTKpwLY4W%UyA47y@@@xX8e1n^XjJ5&I~O`L`yv_+Fv#0yJmk?Z9hj!1gfwj zhS-BFS%#a9i6>n>A{ch+!OlRdT&&dp>{EzUcw`wqtK3r3a%H$gpbGo(=yd0rl;!75 zT&eZ^FoqqVuqV!|%nIs%cbDScm*F(J3N_iZ^?FUsGyGeFoF~xI41RQ!_HtLd*E7GexgTrYJ0S`)H4jbf%TtM zLH+N(+WQG*d6l8zw9@M~3@u1tpD&#*<3@SD+;IW@W*Q>(qQh=!^4|8U9p(A{1M}$c zq!5M{B(OW1PS?t>JfGq+iyogBDiNr{o^fI?^;t!3aeoyxeh|Q>Wm>EM*>}bcg14j| zhlQqTJl$?{RIwFDf8pYc=t{h(=cB+FWG-YT(0>>7a7M)FatHh1;dPFOUKo!<& z6uW(6ero%#Z>GyCwq3y<~^fhw%F{9GX=sAJsojyH%J?*P16Xv|#mC{7)iR zrYKc=_0Jxm?DW!gJE;-p${vnLXY~P4~w$v>@>j zYP1SZYQGGvThvY(GCfWrP$gfheM7?Zm)Gp0r|bqYtWy)>`rnGZcghUR{)e6+!?__+ zHe2nllv%rvTG$R`Xh8xi>*{n4OB2)*llM_KZGc3eO0Gg1zkdS>XZz^Om;vn3#ohk8 z-e<^;`YOTdIe4@p-Y35cz4$4c8b>BFtYv_;ibI*V{^y^2L9E+f)u#uJ<|(`R-y@Cg>~iJinJt3GOcu zsKTotBF~CUnDv&8H0E7PhOsJG{TZWSbh?@*pJ`n57P|gTJ1Ob~39KV6B7WCAq-ASv zrwM(-B?47Wi>~QoO)rovvP;}0YjZDA`f>+dXcxs^eag~L{qsDJhf3L4L0i~f!^NRP-h#5U30#)@Ir|B!L zK1=T1G{h~1)?Q9Wx$UOr={*=)kidFEV%7I@6dgnM(ww>p5`ikbdxXEe+)TP{$R7G_ zOE2lZLPD;|5x*ma_IkR9o;}@LB2a}-frxbuj#3wP&!l`@GFyzCD}dIU6z*?*H>mo4R2$-TkU9Lkkl478PH@YmIrV?ON*6 zqK!nL3fC(-T|J|+yhiv+>KZApWRQ?o8FK@yxa;tx^vd^OX(fXy>>4bhsjmN{HXXf{ zM)#3_bNp>myLl;of1)(SwMvZCCfMzu5%rQ7T9Cl2F0ug^OxE@u+e8oi>LU@T+F3PI zNw2(sWN3ysvPRDiYHzA-p-+~_GPEFpS6%Fk(#zU|F>C3HxULd`swKLgid)hWa<%Od zF~-9sAGLU=RkU?@2Zk0TM;4BtUXFuUM#mK8pvbb{u>CG6ao1Cs{3imp z(#i~F%+Lgqm~4pmSzG75_Q1ObwKnY{t-^nn`k{2M-hfmYTtJ3|{80WI*LNfRrdE4R zJZ&5l$Iybrwd6wOeSs$lyl_p7(JuC=Hn83Zdb4j&i9nTnREPU+*Dg1Ur?1t%3@u13 zADp4EbQe(|W#k_+l)5Q)-|@pbD>u_$nG&mT#`!fi|htR_Z5=Ut#!NBH}Ew zEctEYMzmg02kBZNfnQ|eZP4kbRwAn*T|Y2NB2b0bO=P9KdZ!hAszz5>c4KHk;-5}G zlrx^M_0wt@qV%4xxT$T=_okoUc9#fL;dK+MzN;6sjTf!xsd5PnEl7A~6)LfH@98_b z+!kZ#n(o&&*?Z9Xm6Id_Rd}VvTdmR#?NWSc>U3ZLLkkk$H)JS_XBO%U+8JVqIz;AW2 zdM)`=`x35_NL`FXpbD>>_%_IYr(IncL2mtwV`xF5uggzm<=^Zv6e!)r?{!xD|`bD119m~*yMD0hON|7#KKk$wr zB0gw}xwhn~p4g8XClRQslI*3J|B0s;yOvFewq(U(|K&@@Fti}i;ZBP3`A;;ysJ3ur zkoK_RFtvA!krIKbHH$Kpd4Hqs4;ye0mqIm2`)NpR7y#AAQA@=A)zo-e_hVccZ(p}ii9i+3c4GIn#4)Xw(KqE~ zOh1MeByM_SDrtXmb3}E@=R36iSC8u5$_cXK6ElA88k)ouJ zKdbke{ZPz_mtLo7jbEG5u}@?IRq}gqZN~_$+8zgb`qgl0)rZ9TeV$6@pL{Igrw(YM zc{;?>by%y!Zv9jCf}|d+oASl;m$m0(UmV z47cyK_AFd1kR4(q0#%9bI@R`Xw0f-57p*8ES=-k)lA#3&+;0&zwvN8k+6Cr(_%KaV`xDF_rFAJZMWyzyyC;!jhk&G0#);zj8yl( z5!eUEebCyjy`|kVY0A)oguH7R!=GsPyME9trvyj@s>Wm)smuRFe~Wmya__X`v(348 zm@h*M61XcXYA3Kqnth=a9}?;%5vWS_HCFBZW^H+1{;aJ!UX>3XX2;Ni1n!axk8tmo z+Lf|)yz};25`ik*?bqqfchT{E9`<}+Rz)ce01516tJ4Me>$qcqGe0%HoJ61sV-Up5 zkg!hOlr(}KTrq-SejPp&xT+C#wkMiuipYa>5qXekK?0vHQAgO%OdH1RXxVY2B?48r zsuBL(RsLGnEMq!$`Y47LB=DIRnR<4SS_z|$qW+XjpbFPPI$ep|leO%g;rgXkBN$qc zz`0AT;R+ULE_t2R4R?l01ghlq)#Sqcn%CwrYH;EJh884n4i**o&+gZvVqU3rtolm? zs*aS;QXaKim;0sBUBg;5;(}Jv-9&Ral)%t}ggjp@d%91v>=~xbj82pYR83izrNsAa zrSuKDCC13Ca$c)&Iz}tl)q|l037nNgm4a@2wSX7PwEnlcO9ZOS0(UA08?9IFZoMkT zIML*+)+KMP)<=tGXh8yJB@svFk*)O%KC3x=?JN5gidhb)PHE$G z1=`Kl9T-}Wz*$M;W{lgVO?mT6E1S?tB2ZFesNR{CP7_0s3-5p8#VJsz1`i=hPxdA`bw-KIqj59FtI zmzM}sHC(bsv7Z#8?s>mKjB#xAVQo;H$nO7U&d`DcMkk40*b~#Wvvy(J?m;m{0#&bT zW-BvGcT#JVUM$8q_?2tbKDOiKcRrwKK?38wbh>%#(zQNSyYe>m&q@TUmd?pmj{eQ5 z?hvozC5)T#7a~Ievx%_}Gt#0L#OxPZ=HNCwpy?5c79=nhPgK|#cUWurPZWQCAy*<$ zB_Gwcq$Aq)E#3I=^O-)6&|5ZrA6eW+^)Tp;f4fer3vr3|3`Xo=OOKW?bZ^3D$K_dyJYr1=(ttqwV2Ay zq)a^|{r8TqlbN)W(ZRlZo`duf!;`K?279=oxNT=&R zES;v3aNc6{V~If3y~TUyqRir>V355p8exP7Ezb;1evOar@=a%3j;F^$u|ofvUiDS^B_3yC#bk4&H+M6c*Bmz}(6_0n(7wF9VvucfPeHdDhz^rf4Z=&ikQ86Mx9VV*d zBY`TcAR>BgoxDkB3-3p`@P42L3Cvy>nXEnBXcyf;?&7zBVkH%W}~ zf%BNiCeI3_4F<;W8ed;Z1gb&{eD!yxwNr;3-6Y0HEgD2Oee1+6T7RWzK>}wb5dqO% zoX4Cn?h#s=A%UucjeYg@encH^yhn^tId}+dakx1@b=Zob1qqzT#CJK#JlX^Qdv><`=n5go9Hk5`RcjH=JKZ!uqj5|Jh z)}y@IzRW2xM&RVpG^LykAACp8(1HZcVH1b|1If-aw_Sv z7{fne0^PLSf*<*}Ekg?uIFE^=y4j9i?OCi{SkgrzP?b8-Ti@|Rw(`~Sh8UyQ=Sg(B zO_BC%P7Ff}5;%{E9QXDeX}!LOwf7+j5`n4-ckAg(%}G{#y$#=-1Fxjgv`Oh&=|z1Q zT9CkbOwD(1HZcVJ|_}# zMsArtAE;Z^XddvUu|%K>Gc`q&x5s1ZQ7?wKtbkk z6=qS2O3<~A(ZgqZ@+`}N6fH>Lno;D+9LS_&nSQvvFVRUNP=z^>B2K2k2->G?GH-uo0!0fF_%0C<*xy2FR4^uuhq{6Av~gm!d}T*0J3s0#%q3DZbBV6sY^>jO77)jilW^%$CHRM$z9n zB~qJQJLFCl)aDIAa8HNO^$QS#ZWkCUI&Thjh<3#LHGR>kL zw_jY5p#=$CeTdAL=%ys_SX2I>jh#fG>XK3?C#8X#TJxh}l~H7wPg3U*zBtI0p#=$C zeF$%q8cM!=sK@OWG?EBZEt^n1XY&MWHSC>Xm2v;kDe`cfGk3IR3@u3D>O)ktwrWi_ z+^ohU8?=@PR80u1lw+CmPAN0QP?c+K?0MqeuRK>yw`XWU0#_e8-J9)UqvRl6pc=Ip(#Q_7h? z5@QTrbB)w;P1RO>9>&mu1g<{BzS`(0(rQB{MvzqAD@UZdY-*b zo{X{A2KkO*Xh8y3A39xB-bO;UUr`U99w!l~3jDRx|HLOF{TB0QVvM4y7Igad#p-Fx zaSSa;V7*2W_2RUH>MWMf8DYKH)T){Kt$*SWpRCBxkNy)iw~1cWPbsyC46^tg_j=(d z?Ynk*2YvXSLk&g9v&y*^Z`REPxjc@o)~m&&u)ar3E{dx%7! z3hNw-dit?tS@k+?Xt%L#8CKlGUP5y9y=r62vX@ml(2=6kI9iavdW0e#&enu=H*ZgO zybYHKRJ|(oLm&Sqx>3{?ar{BgckfBJRET6~K?1L|s1%ZZlRAkQ$d)1o5(!itNG{aB z`x^sUI`$|XB4Qw)iWo?=Ac1#`=%d(oJG~@gAis$iNF-2|FgQa`|HeRWw4P6MMGWK@ z5d(=9BzkvD(I5B|6)L)hF0H^WWi6&7E;VIXg%Z2W$#+SQC1qHfMl0yP8}e_Cgj}6+ zaUEk8U2i3A*0rs4m!JyoX;Cxt+E*I1XFXMn!=!r`2{}U{@A(}%B4;ga^)gZ-P=(K? zPPcboA?^BL3!Uv4B|U>k$QcR~n;xQXA~(`fmT?k+Dx5LI4)2XJZ2pb%)Xt~_!|IJ# zcM|JEirA=rqJ~hc1MT%wt{jO3J_S16y^%ku|B34Knbt+B9Eqy@PCxXg{>F=Tb$UeHp4M4;-}h7A3Jzwx4F?h60zELXZ{N`HnHB=9K^(Nq`b)B79DY4=h? zBmz~zBU1F6|Hk5EZAzmNuN`Upz99@PNXSpr;wuq!ed7{zq0dN(KvmpBPyLO*F_2rX zUnO2GZ0YcbF$}9FV>RV0fWC;mw)rcvCq)e^_qiCleT2kf>s`EBEx@ckM%M zqiS?;h1z=Xc!@w&!c{Nj-@o;cd#2pi9?k5*C){~Ju(AnOalxG?v45_=qOI)Rn`ar7 zq-a3`WASvlGq;XwEf4kPS`hu~DC!Y3CL<<}I0v6bFDr*#-5L{J*}}f)%4Q=e5p!rGG<-Ko!P0 z=yW^xw$N;S?fKV>M2crXV$NM3h5YrsrpJxf29~P8SKG9Z2vlLbhVXLUYNP4Cmf}6E z!lbwiB<^_lD4+lOUPsTJq`7{6rLB9@St3w{aVI+6R;9gGxxxdjM4ebEz66Qklm1^< z=O5Jb9mny{F?1bb+qJk`H$OU!5pCACzMuD3WHl*9KkQ3WC`!Kl)Q_ViqT$GB!Xa#` zxm6eATYA4gQCzu>7JY>ncgF5Qp=^F-uifq3^R>U<&qqJ*`~CcQzn-t>>piJv_M6&k z)s}Ute|)tH{3wbMsKWjkN(r3}R>!84tMZ+(tWO4snA;O;`n{>Wo_f4qEqJy;`CO)5 z5p?OG3j2U40V+e)499d8ur`VH`yk;wXJU=^ruKT_RIWN3GhWsEB{Kq5`&lP>pP$3j zy#g1tEF_KfEg`}0iFpUYRMqq`s01kE_z0 zy{Y=y<}60wof`Z1DOWVkB44FU)E%SOus(ex@X0{=^WL_atkW;`i%)oGKdLZQK$9tc zx0_yPj}Z5d^Sl8P_=KY*tFoIs{+o`EKMPgZy+=Fx=pubT_4QT%udfdYep*3GT#-Ji zBVP>Absx*Y(xDm7;qoPe`MRr%dfX3=m0Gr6Qej z+qi-R|3CK9Ay9o}g_xhl6Vj-{Oe|gJDoj)amWXL(%USjniQnLi2y&OIH;VA^GEx38 znh~htso%-M(U@15C?YQfvB?ye?czzjZ(sB(*FmXbZ(s;Z>LG#2H*zz)x|NG%vpCg%vhUyH#ivu1~j#_vTp5xPk<}4N$*Nv{l$BxBUs_wvj*;RuCx9IpquC zMhTu|O7P$c5?D>3a`-{+#nkcPZWyTdGu>L@OeFLxR zb!C(FK|xuJKo$R%JQ{D&gL5KI?KrfCRp^nx`U9nF+OL^b94eBBT{(d&^b@FR;B1j4 z4t9COJB#@SNZ{MDre%(`$QhpQs$k4&MxY9P5&ElIuS)k4U-jAP4Ca3zfp7ivRNMZI zj1S0Feod*2Ko$BsG(owvP0HMzsyH*5`8Y`6?uG86&0*5j{j^FkH+ZPY_w-y-97^eVs23z)Bl1nwruSF4&W zU*r!p(k9Gd1gg+CBoA`=1sPQ9V(hsP!2CfZa96Bp4~ET@Yqor7L`8BB5>@DbQrBcx zqkMJ8!@jc8} z&i!+iQQXcwVN{{JtZ9}db+Ym;nhG4jeP<-F+CusBB~zt$Ww>$j2KTm6g}%C`)p?zf z$7~VC{l(lrM*^!xG;8v;kBszQX54zm&K!4CVSj+8UCKElJpy8l3F{hI9{>_q{i1U% z9qMJ&qN@=ecRxKSFxZJOBUy diff --git a/data/kuka_iiwa/meshes/coarse/link_5.stl b/data/kuka_iiwa/meshes/coarse/link_5.stl deleted file mode 100644 index 35aa1245de49a6b5e22b28a57b786caee063ab8c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 253284 zcmb@P1$5O)7w-ox4n>LVkF~z_<@UdSXU|L~lbK2O&d|XF`t~S1pzommUAzkafB1Ji2O+M* zawr#SH#biE_g@*Yxd?SS-A(I!?k}nO?!5G{Umt!vV1EhP^mrF-{f%i7A-%P%igcx= zv9(wKm8c+5JTMoH{?Sj{z==V7b1IiRH!}`Q~+_bY19rqqeuIs(?;^BLueQsm;P0L*;!J}Sd+VNb zA8fRE9HFfqyu(7EmGyjto!sF0d4*AtkZ_~>Uv6}AS8;BmPq@+4b;U8BSwj9qpw*}m zu5|su9=2YB1S&}Uxl~A?71oK6z6S!8y2m4F(f#XX{9UYvx~BwnZ)Cqd>Z}P=T=qrM zmHrzn1X|&BL&%)KKqcM6NIEHMql^j?uU8kLZJLW~laP#U0+n);BI*15n=Axc;nhsY zqYaUsan3&G`B1PgVIQls(UsoF+>`e)D}f3UfA)a{T44zZVQpoww$jYD!YlRFz7pDu z{^Cl-D~-36!P-hQ+X@vVm=BG$6~BUcTN$jaG_$RcKr6id332pRHzF;kAuc zw-a2o@5OrBd?0}e66lY>zi^|Z+kSP<`pi;>tHspQd$y`6Qa9zt-n)*gtv=6AF#iq! zyQ1QbER;5Vn5deHYpS_YndLG37-=h!HC~res5!V**-F7`-A^mHk66EY>Yz2-`LUH4 z+VD<7w`zwukvmT=wd8)CAOG10DoE_T*jnAWX)~v-K9E4GoR5dA^G~lxhNyIYlbW|e zTgj|BYXz0H0zbz3S$&{_#K|w?)Lec`IQ?e=t+3s!1h(SL_G#53BM$rzr9z_hxH}1% zn;iaslnSl-jtNh=SLg3>^?{=S>$?)`;rw^;m#hRT zNU%OFv612bQ7W{$m8ptUz}TG(feP#G61zVBhf*QI`m_)0?aBDSdZ5+kgDyVJE1XJ( zK&8vcfOhyBvE7 z_UfGPqoko_=1Zm(_A#puRFDWbIY)9G62s{~6KFN-;4&%u;jm;3tgTem zy8lC|kYK$>WxXevaTiO4R(Rc5YmQeAYf+Vr=e#HWnLq`J_2o{e%e&6uwABX^XoYh- zLZTbGDZ`y=7$&=IY(@Gbb6c&iR#>{z%ah6-TWcdbq?hVP)uv@K`|)E!{_5zejCoO? z6KliWX|75BTDwBkBwT;s`ihVZ1xqVAvidssz~7xPuRKjK+VNi^C#H``&bXb_b%}3grxs`G;O&kcc!j&Z<{j<6#9r`ro1S&|_ zdyl9`_m^3fHM?3m5NL%fWI`IbWl-u)Y|9B$kho-Ipa=beZ1wmt$4NO;+~0vfE8J}% zBzVkEc}LOCf`FYHBs%@|T^f5NMC(^Iik**&HBu-?zI1dT&@-H5ZtWFwgu`8~^Y=1p!3zVaId*vm zx@gUw_vOcgw8)*&`1q`i1A$i7J+iC+zS1xE@5YIWbDXp{nTJwyfy z6VmPZd%gF$uAD#x2`nukhnKw2N2lrTK%mu$&fnEzK_PTRQ?sq6Pf2Oqs@#zis33v6 z350z6p4m8`sx>EY*C6%a+}g%EeW}@Bt;Cor>5TjP+i?OFBn~BH(3WHj;xr*{3y3kL zeJ2M3t+2Fgzhqo7W8b&hoWMO9HZo}JzQkJ;cUuSjePOVxDO=I3R|6!5h-&R zduBD~1S&|}Sm~;y? znUAYOqx5fggE`T+Zj8EUN+hi@OOp09iBXHQZ2?Z=)db4GosDv*?Rp8f}E0a z!`FF|{rKqi!P2q!9n_-zqxs(nS-zg?X=jY$1S&{;S>><#bcv=WO~{KC?e)WXLLCUS z!X87&>}mb=c11^W0u>~%_Ym^#L%5#H5IqqIw8C~HWaP~lJ;8Q9P(cFw8zIlbGwG#g zg<0Clybof{C+*sw&^0F3)=Q8;1qu7H+3JME%8#_-J;rb!$q}a2r3?ELqE^P*#>8_G zne^{7MX6B1-+j5evf83b49&`}O*YH;1A$g{TJ+t>&p~qf{Udm(y3;{Y&C5}=_u1ak z>0V1E7w-uAGeu45SEk<5gEXAU_cp0_*EV! zf86azpw+;N^Q0sDBWMq`BqQbo2Fqtgic)o~5h&$47DeB@IU#x0TrM?piQvaaa|B9D z??=(64?`Hy;d+#u{-U@BQ9;6fJW=k&h|w2^%aId=kK_o`3R{Hr_Bv5=@h8FuD)_su z)t5=N%0$q_^evc=S34r*>fam*w8C~HKIGR}em)wu*%t4TE{@lBSjSO5&9B7r z<7OYW#mhzGsHn%VJwK#rcLjk8655MUpY?BIZEdx0?m?exKOG6Q3a+#|K5hCqx}^$x{7~f`Kdsl9?OG(>{rD7YVe=G0s;ikTHgC z`nw(@@_N*hdu0`4J1R)@&Du)Jzc`w9?w^_w3%-<*o%)FT2NGyC;!xsM` zAvt!@HoqJRw7MRb;1fJ8mIicdz-qpGZ5$oiTl6bbkXU=f&4+%7r7=z!7_q0s1UhD< zBY{?U6|i~Y*+MkmSwWzJ#Oyl7y;rf`el<;A=HqVQRjKt;M*^+zS|OxQwXBLdAioU7d*>=adcKC)|XIO7O`b@t<=+;`nw44u>-q%Z%hQ@}{ zuPI%n<@qj4$7_Yt!}-m=yZq8Ixx@DUoInMMH)Re>_X>@t1>MRsqD;dxa-oQRoInK$ zpZZTEzmoPf=a>Tf&F>s62;o}6`-MRSFXY$WrvF0psmQd9rm`*;oRq8tZ zt5mb`2tH%=3n8>d=U|$a-#I;Y+?S8V^yEHJLE`nx$5Ke@FnZH#0jq~`;g($gQ!fVs zt>OZnNU5HUwzY12+jH_NXHj!hkSNGncYV!px*^t_^*vgx%T?zN%_ZhrD7ya6yA1%b@?F+n0QMa+3ZLNz0 zDoEJ-n3yNJFZ)N%aa6Pw_7ZGe>~Dm;c6}~)=qt`3DoEg&Wt$}BKgcySu`_`LTD{nq znLe5}*fx9ZxbeF@V{K>Nx~L$b(#$mc!eHAB`Q7@|%7-^%PX-CJvex`)F(+l_0DtZS zmE;I9PrOkstCGH&^?aDEXs1mpY;{8PSvi$@BgFa~6(p?J`Nz}S`BDjnwM)k(iGWT8#W+YB2YK1X@{3 zRW{W$xy1V6oInMMnI~6E)vrzDbt0ry-{o?yw?iBVixsp8A#6P;v-Kb+*a}Nx>p{)7 z9+cRsQ8TY1wjz_*nv)+B^6>8%*?F?42euW~$x1x_K3Bdsd>HqE3KAzD?U6paOwj7r zG)IOto!7}-=L9(rXoaO^>+{y0@)(!VoM3AJiLD1UvoEo=fy7o2nr%HOvGpMTJ0X9s zrm`|)6erkvFiAn;(|Uht&&X&_6H;qld)Ys4r~`pkc>W2gqg``W4;mk-clzo`pcS?oA-TT$OO?Kk<)vb)J8!nS)6DWtJ+;l-uV@^v`NCIM zy;|fF$Lzhnj_I}HHw7X6h)9S#8>77X*(b5SJzdGeiH;LNLcI9p?E%R*58f< zS`8>NDq+)`Sl$YRY<^luOMg}nJ5x_hD0C!NTTr&Wv|wmz@3L9qwBfbfC2SEwK81Br zpL`JnDoAu3+S0pprZ_G7do|Wpu}e#+YrZ=YXoc;@p8OPW)^1%9#FIRzKm)qEB^ zNyR7oCWO3<)uz=PW515J8}VM1^$=6JG9#)qWK*_ZhukCYZnB83KB;vMyn0aM{4dj&Gq@LUY+!7iQNw1TbF^y8y>?_u}af@Ss4UgCa^1X^{i03A8G? zO-qQK9IGu&W3JDeYhqxk*yoInMMm-{noMd}T<&H4@< z|E`Z;+S!3Xs~RteHhy5R*5k!ib_VDExTR-&*^3iwU8}M+GH>08E05K~>BIQ(?Y%_H zmN!`QWb02tPW^LVuQ|3SCs09xtqoPSy0@=C@;=x5_7hLskwB}(I?=MY1ZxKtn?8!B z-KQ7aF^KzMYh;z}C-9PZxF1&66dJFsaxX8TKSFL!IjmRfHh>eTATcc8W%YcmaBUyo zFWFuDvi>}wj{|{LSVA@f@YnSjYX)+nPR}js%IspDQN{m>I<-U?@2>}QUskn-;o2s? zYw*42Rb7#V4^)uo6i2kz%YwC?Yt82dCtFW(M_D_7=Y&n@i`+yS7SQGn+f)Z2rjN0$Qm#_%XhDNJxQd zgO!Xec5?z1B>YP4myYes%xOXfUJX==PT%A}pcTFq%65vL4OfQLnZgNFkXXF6GZX7aNK8mO<<0tZibb>+qFlO`+krr1S&|d)>T>Sa+;8G!J`dny_*ApR`^ab zoAu2dV+@&cMKislf`s}0Cq>m;VypSS3gwmY z3w$_%3KIAhGa-2@^CGmq!yE~;qESl|a^5>`^O5D*1MOL#F}&ueAc1i@gyh`R zT5s7Y)PX>&zAQFtV70?GACK8;V%r6AK2SjdBZdg6w|Ai)aAzp@fdpDrE}Ba%r|UK! zSwFARKeijf2~?24I3_}B7C*1khobKyfmYvcwN`Jh-)!^oEB2AT@lp@&0~I7N(u$DQ zuhJV%>)SdIX!ZTkaCOG%6*eD-?`1P~WD(anDo9x4ylN~fWW*M$$9*7yR>eL?sn<)+ zxA~~ps;Ke$ogXJqK?38-2+1(p)0i=!ssn*miAR>HlM=#gKIY!`Hfnz<&k0nJz-Tx2 z&i36#hUeJ44g^}=W^eXiywJwxqw~}j#_R>ooInK$jDliu+e11UO-iP8AkgaU^qp$I zTD~?PO~X4GdHe|{P(cFU_-D@t)Alxo%)G^C07#%!I{lz}Z`u#roT293{zmM#qntnm z3F~|M595a$3Dc%J5NMTxMQ2w0Jlp1@@Zu51mrBDpfeI2B7r@>%XgAvE7*NiEK&!ep zPO7W>1lWA6XLsk3OWZht3KAHtKuC^xV~pT-SExDOA%RxbyK}~=V~vP_Ku)0YU*dNp z(xmvYM)wGb&j64xkL^}CGhlDs?;CCmm_JoFONH|ijOM@@4%?Y1IM8_gZ9gYaK?0*k z2)Qu3rx7szz5{_)Y&NK}d9Z4hgRQp1IvFvYh+!V1f&|95u(|Vr_D20LsT~Nk3S;rA zqbjtu`EZ%i!U$aC%n4MGVDm?n%`9!i{eK!6e~-`02~?0^vrLHKd3W90sP?nG1A$g- z7NxTJmCZ-FX`V)tpsJie1qqB8B4lf`qQ=>eehvg$jb>5Cqd%>%`3PH5$aq`49w$&i z0%Mv8d3Gn8@g-|ZM*?Dl*-TAkb2yui=x6DTkd19QfeQXEn`=QV@;_r9>ASD?a3Ii% z&7xE`zq0wbmHWK@>v3OBpn?RO2dVaGX|~JxdX?U<-`-w=P6`OY@usNK~N1uhQb-&JHuMZU@*jx*u8Vl@vpl$3c zcD#^4D>jR&&gNG(AJe-F}fvEqCn zfmUozB(eFG&Bw>c>GF?2@k|&MBrpz^koXY?)sVtw&2XUPv zfmUo5C9(OH%|~?Qyvoo#jkyn0kibZ0Lef<#uLREZaUjsD5sQ7zHYCR8W6Z9~N}X0- zoInK$jI}0Yl8>)4`FSY^0>A$^tk zg)eXd6(lewmfc{x1S-!n?f=+$fmmI%LYj~}RR$@!J4Vn^5qouv=kwe9UHV>Sgw}_}^I;4g zA>%d-RGhO!(7+Z6`tC`I(vRbz+UmrX62{tL3?3mrzOeW0*qiS@`}gViTj;||JY&SC z>JfAaBTzviX}Prrn?zLG z<3ky=$74l|8b+d72~;qO3V+E;pn?R(WBr*xtEJb9X(?#{6>p^cX2K0rkiaOh-}YwB zkwB}(2LEqIy5A1P}cdHCCSZ~)t zS#L)L2|Tmxnefm-#-p$Z?O}sG76PrX$5>id!3a>SM~VK4s>jAqD&BPZ&4eqcAc1Yj z_FijL^Kf>lTEQGm$!d44knYc8-@Ys=uLb`Sac~&B_GbdEK3^-YZ5r3r7Db0X& zy8#ktWsNw*euY*T;b_)CP87^YP6td@q&Il`5&gZ}FKnIiTLbbfET)4!&H3KG^B#es)PD)07q)9`z~76PrTrAn8+ zlyWzX5A|K`YoLMz#>BE5jTuTSSxQRu>){#}0~6*0YpRudq9e?F(pn}Bk@gZv7X;E}y=GCm1)E`pP$lb|Xizrpo zLZB5!H50<_9}2sF&{yH9x7){X^Bk~uwv%FNTVJZIUhij*uSEhCB<#N=-qH>L z5-r{d$viDp?@aO>SB%U@xvs$5Br^S z!{S%lFoqL-U};5LO=WH6J3gDor6PgSk{==>7o&4Aik8hqXZG|A(iEPzHrjK!RHuoE z+qFl_ns0o+zZxP{)Wk1Y2~?0ke}5*>3QNoDVX%5=?|W7DwEwR82Dbg!ES0^q;!Se1 zt?UFU$q^>aa-?)i)Or?mQa@B4qbw^HBDFsiMLX(gC5(f_xJwo@>NnQd`0o_WW!+PY zcgby;RIOVCO`V}dQVB(=dR-r56yG>S``Tv$wU@+HkiaNoLSEJwZIq}sS$ns%kc!0&Ge;UT_r_@tKDCokL85D$rIPcI2>R-)`5dys&;dr(E)%tl0}ogTw8E%wLJqa* zVsy_Is+Fz(Sw;nkI}Fls7Yr#4kzYoja#TH#gjd)!^ArSrgX3CAmpWGAHZ$4Q=z3U1|N344o`N3xnD^}&jz zX!pY+des`?W*^~P{#xXLR_smLq)0{wg5M1iw;lDc`!Hwp?7i2dILH=za?uL6MNH)H zdYA+%NZ5Z#%w8LIdFt_{V@Zl6;lfeI2B2g}Bi z;~vW5EOlv#V^xi|;a{b%M@76VdxJ75_BGSmMCs0>P?~FII6H$oCRJ2YZt|n~KUXtQ zK?0*T32A(}tWvmV4O%OJ8dwsn6UO$kjB>ZiDU~Mq(zSyn0~I7*WV|e08y!xg@|lsv znIE_-C%4t4^GEww2(+@6>hl}+7RTLMbm3TU0~I9Zy?QJy2nnP0YMN1vi*Hv@T%OgY zBbQXS5NL%hLWuL~Qp&uYK6JXPZ_*hwd!oG+%;T7hho!6S$J2M+%-L(`*3!z)I}%M< zsfL0I5*VG!BJbnfluzkp`m2s&A<*iT(`9MUm~eV5W*ze}<5U@CzK=qywU8B5kiaNo zLh`F+mFM+p(CQUUK zntr2?g+MFpp)96)|8@`ew*2}qFnSr=%HCtlmi{w=Rv0;LB~U>^zw}t@9TsMrg=49Z zK&!jWo=Euv>_mJOFXQ>623pC0$_7UIVq|f?p@g2EZ;wAu?OEAKaj?F2yO)=N3KAHX zPDqu-m5d(w>uWE+S_!oJJ~&aDzCDy~_ubFh>eg;gBQ$S4&F^*<0~I8&euVTq=V3H= zsjG$TuWBLC%35>#4B5ZSIS-6QWVivY4%ejUKP6 zXfN4H7!@Qi%9xOl@kNbI@4Ylnwh~4HtuT_AuTrGl5oYC7jgidr%H8O3W4!U>NgN z{)3iq_&}_d>2rNH`fRS0LH5(~NkOZ_3{;T7Xf8tLO`IXW&a_I3p~Ec%T8&z=Az{I_ zSnX6@Gjg(bN>x5I?t;`M?H~gcB&?BP^B$&9)(m#0t@?Jf5NNf0_rip}FJiU)Y0Owl zDRp+GQdluMEo}<}6(leQlf9R*-$S{SrY=2twyK3dt9PfTB;5HDtNrcXp7|);*jJf5 zs2z=ISjs>J35>yH*$_9kRkno%QRf`#Ed*Kxor_3NQpIWMZ*^fl*01fNeC`)Yj}-f) zqk;rR(GpT^WT5iT(nwmO?M4fMRznw$ODOFWr_FzE#v+G52~jQ_kEQ4C4%g8N6(p=Zu|v_Z%J)lC=uP5jAb_URxME!Dv8N&Go+D9O(FbOHZR?!hX~jaBrD_?+D5xNTk+W>xzD<_r zjBhP{7(2>Bpw-^zA?kYOqc-=kw=T=#v1`86X;!d;3KIQ`M5_T#QQB}GS=?mecKOcT zW7475Peu=FZgY5`alA$ zFe2MZpn`$6vQuc2|8&o6V9 z(KaB=Saf}|c4yo#iV70ej1I*=4>!Vh#As_b#mGpYRk|mwy=T;j(>A>`vqpHaY(U`| zBee<{w#%p>ff*!NUgzBb#-Y8VwYc!t76PsE&dlN+R5MNsN?V@!X!cioBjUm^ZCj1h z3Mxogb0>Ux+0aPSx`$RePd*EQR?hVkw=eRI(*oO+U_QoY^ftCMX{P1rTtPtv3Cz{N zc5$|rG>WYB)}|-=S_rgSvb}WtQr1=;S@Sa=!F64X)U`@${k}C(P(ec392{SU5oepY zFyd7}cEj~?G40#o<_aoEV9p8FR@)!z>q@53?)2oV#*G@0~*AO*Rxljv%R>3JcCp69(r)3Bj1B@UaJTXzdu|HHB*qwlvL|emjPA+tuX4Fkd@^tD^>OSl=ky7P(fnRLZW@j5~8gcVaA_7 z_o}RPJzAfB?q(&>3ZuSRzpCz~oc*@}jpfUTp}?)I!!>K5O1 zMgpzu{=^Oo5~v_yFRgV?#@q`>0pP* zn`O^sajkz9C3THP^lQmV76Pp>V+A1-Zg?pT7B{3`36&I7kmx!xQJoMUs>L>TWxc(~ z+saDb`3-2}HI*#{TCrWcq|6&EA3(aw%B-37Y1L_73Mxpjy*`!ga@zV8dp5D{WyhN4 zipAUuSJ~4HuCU$Oq}&siHA>qn|dPJuyKA3C!rha#LL{YuxEs zL;I^Me`1oV(K@tSK-^U2S_Ev1c$cO-2!d-8(>T46>P%M97r)W0OX+_npkZy2>OGc9#( zFh9n~9xH(g5*Tk}C06^sP4Eqj<-d!OXw8PC-4{_Sj{n_Cpn?QOrCAA#+s63ns`(pg zx8}+etLbZY&64l?f;wap> z4e{Bnn{?K;o+-skf+a*M+&~41gVFxl<`DN}>VX7W{ki5CQ$6(FXsuq@Q`V0NVbMbn z>HWK0;RY&5^f<(>rg4d!{%vozE)r;kEn+25LE_hkLE4qvS(B+b5@?0(X7zy)xnzXD zwr-HSW?Eouua&SUKzDD$;c8v415~v_iV_iS#TrtsZesf2Lt*~CkH9K^BGN}z(ofejJb^?Hkv8AXvm zE6j^z^??c!2WCZSyC;Vv^O)UN zk}}Pi|84&lZlHq1&Qqau^7Q0p07#$}=A*O!zWM**1}aD_SvsDsakFR4`psAgv|=L$ zVxA}`WBmeEeY+Y24P#AqUaA9?{Hjk|YT49DAq{0nUkl52JR@=V% zlMh-8A4s4T<`zOK+_21EeE(HTmI>2Li$Bj~P-zat=~0R52`!Y96=qwp5~v^% zF+Pjt)>Nzw|4g72W{t5Ds338mCd+`kyK^%2Kmx7s{%G}q3KH*zxocG;k{d;lKr6h9 zT7BT^H|?-Q>FO?V4*t9nMg@sk?H)^;=8N-h^??Lh;jGq5pn}AgE1RXv-pS3Wkw7b) z`&xalwo1zPSZ`CePmtpZg>!NaXF~ zPgmtDpNtRuEwsXW*KZHzSb_=?H&uVyepPbob0p9T@4;3dnBnglo2}NLB}PuXcUcKk zka&3AS3OoNxv?Dyw8A@_)d!npB<22V(J@hdIVY62DC<3tcknk8ZlHohw^|p~D!0Ou zIUh)%6}HH459awm1&Qxp7pNHyMxW^<_&@@!@cdhS z;N3F%eUzs43*vLpKi@e~L85a)l(zMP`JG1VziZ)8rR64Kk+xiuiB)nRcM9R=5PD|UbRRp ziwdVJhhI_A+B~*i=V*mjFjCn2H z|0V3JVipB)^RB-Bhxon$KHJ2nq4+$Kf1z7uU+Cr;O*yfL_@XDq3F6l_aU5gMnoblpPFJq0m~DXhT`->vX7OP$ zCht-!IgW@ghBVpkO82?+)L6a-sqyWMwDjUYe%y7I6HT9WsMd5qdUm~Z?B}YSyH}sr z9QVR-k8EwYJIyu8pVRD%2y4nJ4PR1DpcU@JVGc3&orbH0mCbH-Ie|IP@OLqr8T;Pd zgu+Udfr3B<3G~gfn13yzl%{pK42+eLX7*9c4~BWeSUl&Ghw`K!A{Q$vn2!v9iN#c}e<8O_DZZP53KE!ajXe$bPovC< z6z3cXv^xElJI!{;pO==9^k=Im&8k-7HOI4tyS3Ju2gE7LKUdv2feI41pG?S=@m|Wl z$jS}`TK$?`f!=)4))rTE(??R8k8|e)DoC(8P*xXPJ(h1TuPiStGGHQsRy?n~AOAUFckU%T@l_ugKFZa%-RPH8nf1-i}o*P1(W(<(? zHsp7FuDHAR#r1o|f+)>BoJbf&{h#A#GOWQEpBUIc0I=wD(H$ z&VXY+d&jGEX647U*4zgwNLcS5yWG+#&yKfqAkYf;09kxg{`c}fP9pyAc0oa@4l9v=wAYsil>CrNcu|BrF1A$gpCsvQa zS&T`0T5$puBrsDcBR=FZ+K+1LK%kYit zXLmJDpu+A^JR6>QN5)^`cQu{e)f{{v!R|hg`HS7vbaq#BAkYe1o!`}Tc30yBDoC)A zn&-I_bB3VG*Yw(1`Zy41g?)j&jTIKJXX-bI6PQsB3Cz&OzJt|$oj!YZkOP5MnE#ID zFJVNajX(tn%+SVKH~l>Q<Tm83bs*3R+l^%;UAbAmvs(DT-^IL)NE0&FZLwZ_mGFTI6839F z)VvXypht&_YtTYKMoP?7$>N>sr7{W}?ZE4SnN=~HDrUfC-@6-I*jO9rxDv+IFOIG( z^H*X4KzxRbY|1A$if41tY4V_)gpqPlSc6(p?JM|8j=J=-1ejVdJ2%KB{L z-IGgt$-l*Tg$fdQJra^wqK@9$Z4@sR=3lkv=riL=FlQfZiH{4J`0^gZo-x+;7LAx3v2+YijS-_BH z`wS1uY4eT<0u>~zxxxxRr3vxB1o0_$!S;Qb<7lpd#U(6BWcK{=XW8EuSFFHh`jacB z)E?Xx1S&|NZ$hq4&acIvcO=j%xYFwQwCUsMlG^6?K~KIaqdh$;2vm@;*5hY=Pd!!c z(foYa&zfyVP%YX&nwrO$gOaU;uh-Fo3yWTY3TC~;Sq+qG?w< zYg4a?)3;M}Tt2h#9#lAo;v9Fm^@ip_;>9*4+PNL>7i`?>A6B^4)bv-V@CwN*c4d~WD z`uK69PpWINyoBs)q}i9ya7hrTATjvG0-ybRW2v&GIV)9g|G}Pt^<&>L=@?J*z7cJO3KH1I2npDjQ695U^h6}k3R|7+ z^*!;GTXz<{1QjH#*;^kS_m(H@bR^IUdnKDwS86R^W?v>TSKFu{(VY&GYF>__z0dY$ zZFM8Gg}gl4kw7c#$1Ic1w-xfE&0Ai-8k z=B~PJEUC8Us_b7u%rcNbD{IcPF2S*~Q?OXwVJ=R43C(!|=FenzoTv!-M=>#bMFk1W zpGim=|Ecn?gW}t==mYbMB2CDH`ZML7?t(xC3Cw^>NCWpZa^d3E)-}tHR+vkXkm-}w z$t|ad)g8+~!E^kY8DTJgB4&$a`z53H$z2zT^MMKyRv#M%u9V{!ic%qgR+uf8#h*7^ zF6a0p2vm^3Iq=p zh;xn#687^X?zMF)PnNr97ySwew6eFl$UGb>t&~%&5;aE!3CuysqBEZ^k^6TLD=#F_ z%KmqedH8kWW_i|JvARPA32R$TKE6+GKUth}B+v@aKOw0rUyzFq66;!2kic`pt|+%- z@}w(bwT;g?@!2NkPi4E#T~*m7qbL_z3_$2OwIFCkR?GZO0`XQFaIAvgWgOYVG zN|l~D5@>~Q$FtSlE`Qo_r65p2qVS>JJ}I`byL124%*Up{-E`?_iV-<@A<%uF9m8%)jBuRTApc|83Jp<8PO({etPwUtXyD&_5_4xB&* z36@6z@*(H?1A$g{T3jE?S34{FqFQht_~sG5w`3(k=mU99Z?R8}?=WBq@d_rSRl^Um zva2iifeI2C-%+BIcb$&hx|EVw=ze4 zoMm9%YIZ*_l|}J*BKE>jL4xg(n@`+rGnsO`@+4`4 zOw3`6r6pwf9-<7aFZvZKNMJr&cAcmBAa_45&Ib}`g>@n%)yMm?-$-%JQ9%Op*%FfG z%MJN;@7}!TNT8K<4i{Ctj@;XAlwr@TNvW~i2jXp>Y0tt}SG`)~inC?-yYI4q%5?;R3KB;$q_1wq z>WgPZ^J)!{_vaqTec;nDEFnHUBgC^;Q+eOEP)?wNgtZQec z9hRibv-WmN+LMvlo(!)!Do9|DVP8e`C?c~x83zKb>~#`8CXcvBmj#XC1S&{ipJw?i zUreBnLPX7xKr6QUm6R2leOKmoIlAbGAW%U9^HlNuM9TIPd8v>0yBhS)?3U@OUTg5t@Q)l#TjJlWp(NO zD4uhdt%Oy!Ue?U@a?UjV>iT)nnz?JlX0M}L=u@HvfeI3A?X0q$B2DZR`Bd=IzkCq= zimm&TvXG)bEG>H~lexU!sgCF+s33v93Hi3QknVolkw7bJp41?%ww}>PlnNCjto2A+ z#7{3%#gRZOw&SI;9WPDncrCq>M*sVa7)!7ocn+{d2=V##NmE^Iy&c*L3C#V=-e~lE zt&LP13ADmYzASg!%X?bNKtZrwoTNOYR0ESMF#>!>dY{kq56?l^C=_tK*02_L8+f%h&#-ek(F zNf#Umw8~xeLkYIOYx5DCs*Lv!+bD_(64v|R@;N8;Q7y!~QEUcazPG@C3p3a~__jxV zGh~9z$NIXv^d0@gTQ8^}Va?Xlzws=6cG}^5^g#lxunh^hKPgtfH6)l5m?0K3xw2JX zQYI~yU2NP`y{smDpcUq2wG!jI%+!aM5d8*K1Y6PbT*c<@Kn&!H!c3)XzB_84-e}PvPN0H>)rS(aQZKwvlnM#7!mO@@WNo=z zKk-2js33uLV!MNpm-Sa0#rs$IZZ^KNjrpC}dT`HOt-&zIs}_4ZUXO%is^_LR2o+-@ zDo9v+$%~Nz>^nbV4u=F(jG|o`?im+0U%l zTWVHsrJj0)XkAp0z|2-`zWeVIJ+{M8OD{2h3$5(GB=(k?ByQHX%?-2=rh~9l6B1W9qyBM;xH}_(R+tfrMR1fUrC*&UMjup=z#Pwnq|4q$f78~s zx`TXFXoXh++x@uPPFFkxfeI3srJa5M{MJuV3u|^ z`b0+P*^3JwNT3zogIV;zbz)5P>cp=o%-)IFLNVheA+D`b8Gc3wPN0H>{aCC&zGwcR ze?8LmkA!K388=xL+Rr!ie0{`Q#dxKnmG!FaTltNiEoV3G0~I8!r7AS=hkhimvjc%v zm=A)Da1S#X{j}DcKm`fR7R&O`H_L7`b#CE6pcUqWASCaW{6_C;4LN}d5||Hy?K)S= zVhp;|O4LKVL(6A(m>U;ogKYF!k=EFv`f~ymB-k#MmTPf8TQtYIyiUeHLj+-0Y(p@O-CF{dzFb2dn2ygw}Z6%uG=_bt}vuV#JG8$@>D z^*{v)%#BRQoEPu)oaaPOL;|g_Ma-|I-PbdZO^QTHno}czIiA`3q8V=LXS$2Ni@$|d zIKO6J5;!&1xOB4^kHEuNJB-@HxOCR9l(EK=Pm4H#3KGlP$7-*d{PYofWW_6m8O|AV z%jRAm5@?0d>+IdZd83SBu9Op~AYrbQ*nCS8J_@k)O;F9en(3n%TPtOb{gPlR7)yvb zatOH@6l$ntTInW%S<7s{tC}?CCL?4n`=V!#ndLcw3KHm>kn(P048Ketc&U&;E6n@D zzS_f9k9iA@ zf2ysRXAs}z#5@!D20kGtj+Ha2JeD|t3KE#(g6$4=_b^J$s^&nT6~;QSulDq(#w)LK zoInK$%udSA`Db6_Wwufd1X^K41Y6Nhsc-bZ(=k6(yf(ZG1YNi4&+Gfw@N6{_djA#@CDA`58n4t+0o(?=)2CZjAr&oD--Zff-O) ztfkW1IKASg1A$i9j|rKd%S&nWzA~=|K8eAcHJBrZtbs*5n zTJvGKMk&#I>T&{Wj&;JU2rQ<$z!+sijnDjkjtUayo1eW3JS!p2dH$JWl~!p7I1p%s zSrOQC&aRt@qg4D&6;iN`sB61A$hUZG)}0!y76mo8>pmdSK)==EAXEkG9>~ zLaAFRTSjK(1S&{iRvmV)?b$);`81USfmT>T7Vo^GhZ5Q9F|P+INLVw4jGWg;DSzj( z1A$i7ns3{g-*Bxg);PGX!S#oAjgxk(tI=;meO?b#kYMAX89!)itHuY58?9c~av;#k znoH03wWl#7XH`z1f`s||=6{Q8@Y4fo?B80}fj}!u4qGCpuVYm7F3Jg1kibmfECy?P zLt|i8(MwQ40<(0pCnmev814FHX-0H5{%ZMypFt$h3iEoiH_3a9 zFiIQ_;RMdxF}pFlR?M}5&4&|&hLELfVste)o$l4obT>*LRkhcz57+kYu*$$tMKP(dQ}(rI<{ z$!Rp*#*Y6N0ih7Irm^o+Ye|(^V#EibV6Y{c_-sBeiAHr_6I8$xeer`(0^<+EIy?m|z z5U3zwKTl>~u+{?!w6d2r?10~Y2vm^3^JMjb1X|hK@bQ3#|M7te681AI&iUl04dfv& zLX|fcr&XUgsJ(QzK_nf0#FeUl1xdsAN6;z9Txs*PL!|9bBWS-GW)2~#Zz*NyMqj1t zt3lo?v-#0Rr~PQt&#rWP9zR-_9hV4lqKk8T(tw24G&a$d5wklNQqH%nr^F8H?u`l( zqei*WK1DjxhP_Q63C_8dQ5%~m-iz8=2(%h2yV2Q~I?!&fOdn@_vMJu-EtSL@jlEGp z!sV}gbj1ChwER<(hoc>jS3Q3GvuY0fAyjZ{xyB1@0U?&zN?K=`)eHwfmYU<@Bh1lTrORx z(*EJ1>Uf^BtZY1PN-s37rj@L}orqHvn=vgu>*ngn@Qg+WTW z=V>ghi&l7M*?xP6>{9n1W0iwBTT~t2IK2Ax>(R6$%k5M#OJ<+1ucK*+U9R+L^n~ht zeneAGwll?g`-o!n#Hq1LnR$Jyp@KxS-gkVKyGPSc31+GOzJ7|v#g9?S#5h++0@w{Xrfi_iEp3HF!>I+NnF&$!lVSQO@Wew7$Uj=S{V~i!pcP)tESJTv271fq zp~}JY)Ap_0)K@LWa+MZe>`L3uX`#OE9!b5Hy3*=r`l|o_8(~{>7Wz(g_bH>4z^JHw zs31{o4pnP?h@`oeo25GY_Lo-iXP7c8aY2Q2N)sHX2 z=z>YEbjrEMYTbn+Z8a~sMAP4$8mRQH?-Y*;5*ITbQ>Ua1rvs<(n!B#lORXEC#P0uh z9};MV=ZTODuVeIk(ZNc=zYkl^2NGJJ8S3pa6X~tFrjKRiyX(i7j8q0>UtuB83VRQW zEcVT2^d8+(`FNvo{Ie#dv=NUxP>-Rm^yJz++R|G+>B*6<^jCkDXS+a0Tg@l8%xFA2 z)JDm2p-wz1Nc3OlqRp+^n{Ev?OXYQp82&XnDU}abwGe29EyDJYr~j*;&elVTdR@ZO zx=5@!@l73aY#3cJ(e$x>;zd1u(Y}i7GZzbiR(NLFeqtjR1J+l|U=os#p?N zEfT08QLFqZsm}d{KF&@5>jMe2GWP~pWVCJf1AU-^#Qa-lrH|eBSKsI00|~UU`L?ZC z&<83=RF_UmfmJ3Z_&WGN0b$Zb}XOe<9hytI@II8ZG{RF z=8oF`A?!TEsz{!;e+(!F%$N{GQ3(nvq7qJZA<=+<2nZ;sfJ#s>kOUPBm=$x*sDL1f zSvfNY)_`KfoO4#pS<$y=U7xMq-T(D|1*)W_r4-dw6{5-{*r8)HVBaZM8J1 zP?O#5pE0OH31wtZd1Lx_40@;b_)*E$nD5}JxB{+?v;V9uQ4j6-<4z(N-Bzwn}Yb zJzc%Y^`8V)D8b)x$+##zgOs4IuG=T6tJ$tsf9U?t7*wGIfBz@z4QLEXP?s%pQ&(=b zTfJQU&lpsp#9y`h*L6-~P=dPNZLh4}nD~b}yX!w=P=ykIoz4G)7 zT%;|rApJ$bim2aNle8R^pe~wC`L|zr-cp4U)160ZLitYJ|89wtpe|mf|I6_dV^D<> z`PTWG`PY7DP5#ZKA|qo zO7qSR{Erxvpe|*!OBp%(ckNPz5*KItNZE(2{yzkDDZj7$+P`B^g%Ufu#Y+cmRR14> zx|DmBQpSJBpb8}()tM$$H%LA_zwW625rZm}xZ}24UFSzn%{ShE5Mxk+ zy8gPO{`VPF?%{tbl!!jPPJKUTvc|{lpE2lfQ5XLeHGd4zxam3ty3s7vg(|IMT#RVblc<4T+R_ccff>Z1MY zzauC|MHNaYty5`p|BgWk>Y_bzF$PsAL3c*{-vo6xtf$K;ol{v1a&Q586ugFH~J5PDwLpE3xAhFIUkguu2gx96uPI%f5e~) zC3p)_o(AfFmxB`2)&FaX^mxmq{~)MB37XX-mV*-1b*)~Sbi3c0|A;{qO8oU)`Tr2q zb#y*oP1W7`KM1N&g64aP<)8$0xs8}5WmR4FSLWH@Oe#`^5;Sk^Z@+TRDM4NT`>941 zO3*AcF$N{5i#}2LDhL}(ZOw)DIC@>;LHbrrui*X5oTTY4F5nohylp?O(@E=n-v*cG zjXy{gO3-VQ&!3;`tew%NE9QBm3IufxY3VE-3qC>-EtSG-^&FyeNl)HdY#btkqw6AkGG==CFs~YKPpE{w4P~? z&37jX1a;A|e!l)Acdy;rk1IRB<~i>4eSp5>dRa}kUCdWI{TfN71XU2SD7y2gHXRiHhm@mps@Y;~K0 z@$>#kP=yk71VM~J3F<0ZITM0{oz<1*{xb$uC_zU;#2A#Iu8=B|V8-rC>Ic*Q8G|a6 zpd&hB3`$Vf>YOmJnrs9SnDoRk7(|L2y zJ2_A~{O9~2Ju0eDg7(P87?hx{TbunrrL~fVC;YSRQiT%q%|eVp3F->=N`&@SDk*Zx zKVwjZ67&s8j6n(NqW3Y8pb91Eo8JE>sEgk1M1r;@I?nXJ+Z9zPLEnAE7?hwcI$I+W zRG|bNzx>|>bw>}WbbpkWU533X?Og6-kj?OZ5u^5R6y zdsB4Thj=C`PNE7W_Pnxz13k9Enml(-Oc>l63yQnrphcghF>BkyJ;OX$8fMQn#dU-$ z{O|dz9M~&WXK2}E8*GVp;KcmkR_Iv68IL4fm8e3A1Ld9J45y8TEBOqgkF~^!r=79d zo?`+*U7>;2(6v?`OnapelBqea?aFXS+w~GXURn;3m^s4@UwRs1h09+gs!+o8i#0^1 z=fH4(r5xQ;5X)AyMV-z%G9{>smXCi);E_2#pJ|7>bDGJA!5rqc%Z1P1I5s z$kx#1SuR`%?7)dcf)Ig+sRa+ zgcxJu9!CrZBm6k6qf8Y_1n0Ga_qDU(!P~Yx##N0q`mE}J?tQHVg1Tt=c+SL~2y9we z%T8`@BQNl54R0=Pfp@h`*tL_!(7R6-7=3QbXgrlFYWDzKUh;`Ot=B=QT}s65Yy}p2 z+3@Mlqnb9*7p;3$L7R7-1cJKg5vo*kYK%tP4lCGQ-{!(m(Ia8rt-=Jx^aCsH^F@*3fLwX3(}#Vhm|A z9>=bk3q?bXWvWnOTv2;y*eVOgd{Sb3+cF+?JDrjAC#eL2y2`t^hI7fAz{5_75$2GL zM?N%_=hb{8QH2t<>|4XVQJbK*y+Vw+n}oS_Ysg728pu?k#G57U!MsT(y#1*hmHw(Y zH0v@=ws*fMQG&YaPcw$G{W8GNSBc?oJr;lX&Xk=N8Ow16?I5J~7C1kpGwU<59b~`W z44(};GfH#9XB3{d*dX6?t1VN764Il#(A{hkL^ZbHF#`L=;5@cXp8DpxL<#B=kIJ!K z817#AP#!RGrbHD=MB225aRwPMY=#++(SG${thwU7eEwAzfe>5|TS2(*MrbrbDfzM; zNqDh92Pz$Pm)$eEKve&BZ!%%gGR8t%b%omJvVl1(_p55}lTbBwfTq@s zo-$P^F)Xzsw5yT{8cXHwGyO*#MvoiD-qvX&f8T-7zfKk`v~Xvi!Vu0i%z`zCd$S?m z8QjmvhH1{q)4+UtJT9Bz%e)-h$yA|4uPbUu^2mbO*n<;oN5|n~{b4LyZ6y%YMUR&6 z{{3PcZYetole)MH<)DP~kghPfLKXz8m6Equl7ydwtzmD5yFgGEtwVnIu^oke8#c1R z$u(rFQBKe_G!xA9yqULucYqg}pcC&QJVjNii@Tz6&bVD{a@HO+WAS6waL6HvDwLp4AAX%T@J9c{x)>3bC=k>o_5ePVFpM)W zN1L+25>+Tcdj>pnAh9+6Fn7j+0bdFzL0z=>p;A?>orrZ(+p?QWnN06E^sLcqo<9c% zCu54Lvi-;0?lM&x z*(COH)KY~KzcYbgS(L=NCueu$Z;42W+rC#4v^MS|si%8tcG^^)#J0CV$OBG7| z&S?IXPkkmPkS*?G+b!K7Ng$}}-rzm4V&6*(c4$^`(0(?xkp{LW$p**-Cai z-`jAnp?veW&b~Tt#|s2?l{L6y|BA=>MLcpTmM_-G-j{whN=p?={LbH2vhkIDAXVB+ z!>{gZzb;51sB6>lcy-8z#6R=*RVuT_R@#XT8tuREu$z`Dl=z*${VTJ7|7Tcw(&iq)o-YbE5#*=@h5qjEGX2V- z|6THrJue9ab^Wf9U&Qa)y&J^Wb^cY0ib9Fs=SIo$7tWwSP}lD>`->p01gS!a-)&4; zRiILlmM9R^^}B`sB1mgTs!-zhweo9)0=c3Dg1UZRX}^e4e$_7db=4wODDnH6|FuHF z|L;44Kv383JH{`9+7d z@Ymm-MKLVO-x;!FQsDEs7~V>z@vnv0oJS9lked3Wdw7x~{I9--`~ znHTiqzhvST%86OeCSV`aV#zolOCYGraKx`)+AAxogl4TCiOnw_l^oyh6Qa|j8sEkR za(TS9qm`p7OBjhkZQSHdy)qb8D6!qJH+1JmwfkcPC)^EVF~3Q%WbkHzKu}l4lU`8B zV|Z><2vw)CXwU2FTuKt73MEbs=nalMhGn)wIP@5Yw&ulB{7!Fype|Z(eD9r63D~y1 zoBY_golv8cXz;=lym^dzpOo7D@jVf9`BAk$Tu~sXi`F!MD|+dIvs)BPPh*Tw*VY0C z@De^RN@B$;452Om+sh<{t&j~Nb7LZ$?wG=3w7ceq_gWT9*WT)4z0Ec-nY&&Oj$<3f zSinI3_ul*@=3>(xu5v=PG>H?BeEQ;{%SWZN4t0?#l%TQsF8{OKvBoo3IVWEvsLQR2 zDU|RSC)LK)EeIL-(9jLfzk5u zogz{P;Fp)K^69Vd1ced-XKbJnKOc>UDLsI2kD*whZL!qW=$1fGmv}|3O9;d4W^Qud z=(9p=r$mD|gr+>kx^825jE;WcX#2`l{<%UH20MS{9g&G)H`d5rYO3h}M` zeRk*3QE5iaFr*44p55N3cH=SRuL{wtZz&s8!Ae=EXL4drYykFgXUPLWw!oBh(j1rhrqrLNqp>&+eAF z%3ab&2?TX*lOxoAJVuu(3URM{Eu34&O^$fwA)JrOLGRQS{H&!Nn8N6p<><18n`& zRkrNWOE~A02=w}mPQ_v=@Q|B8P*<&-8t|0Y?!qR@el5jLEzp29O+lk>je%~E$ zk5r+=KHXX{hQ~O#QX$^>b;b_{#nQX4)&fCY^lry@8roxx@eSN$ryxtD3MDMmjbRCo zVG@zbW89YQu>6IqZ1>PaAgD{c`&_NJ9y-{&$=y7Yw6m&b+h5`D0A^!M*&21a%>w@S zZ3|PDb?lCPG;bwCkD2lq(-x>9VynJf{$;$DDwKGTmu?eYo(z}Dm61DdjXii(?IB$q zks=V(wc<#+O&uO%Z<#_gJn{#dkytF1#zbjd3`VFgb4AD5oaL15SNG)Spz2r)HnROr zwaiv zi&Fb@+GmhCk0FQ5Uju8(x0Q8N5?R09XB~FcdV8wlvvfl zT-}n#IO(hqOVrM+ce7&YN981epe|bLyq7V`km*!$lXEL23bjj#^$+jZzvgH2!d~SJ zo*exNM!a>E4|EwP5Y$E60$*#{sX0Dq;wCrKanf!Z`BUx4TbxnF&di|ZcXa_jA7@Wl zu?_QTK`j4&TGy^TMwxvZJfl}E-F?$tOBG5;1~uV1r|&`+PRzX44m;oCwQHaj2UhhA9ke{!5GCjv%J>-fV{MdKPUp?eOH+*@F%*;5n zZRaK%pqEUQ8}oaE6MyOtIp@jfFY%Hmjm4_G*Egp^ybyyD%jf>04Nfa7y@SWZ;%DC4 zOLwLV1a;jCbb)RB%w|;U#fhC?M&c7w-WT;)FH?mQlBF}4^CQgv+>;aaD@Wsx3r8jS z@*aVpuKV+xVJnZ(CQBjg{UdP;FGu;5-7-}uVNvw!T_pFQLR{GsfirpSYF?EH1a*Z! zw}B}=s zE$DDMt+ov;s4WoGMXyJ`=h-4pGd3CCC-M8$vpdR6wRTq(jQZ>< z?|#)!OBG6tYJW{#k;iCUrVwY}{ABY#9+eLC9Vigg<+S9mI*7-pTfveOpXa<|r}@1^ zy>@_>DwKFG9ai7sPaIEog{bTMlr`jipOuqC1cJKgbC*9qX5VE8c|S2>@L(-fC{ZzS zzxp_j(PM`4be?N}jpguO-yVw)fuJt>)aGAI@81#Pd7t5PYznS0xnVzoKU4emn!zS{ zt=V6T|822n1~aX(X8$nW%P`zFgU872lFT+YbdzVb8jG}-N_(#-{EgI&`B9B(q7a9> zjArT8ilr5E5|ApCusYO3eSpX7{!Z!dKA){-Rry;{;+A-UpswxhZrH!%&)R5DCC2Q_ z=IleeVkyKj8L2`ET0Xu?bK^buSkABWspABKy58PSvOmIOcuiJf$R)F&+H!q)Mb>zv z3MIt4D%he?r!Pp5U->2q1a(2w>iy|FMw2B<42?Dk(^|X9D{A=zeRJ=1t}poWJ5J7m zU?z^2Ol_KsCj6@1e5H??DwNot^^5MPRYq8LFP(_-{4P39Hj*eoT^-|ojmdNj_2a~r zIZ61XxtlyAeVRlSN{n;u3x50vkBm|>gr>PqK(8A|r4BYX1cJKgGf|~-T{jLF^BzF; z!0QrKC?Wg&dU7u5q8wFdn{oL0j;rh?eG>@kqEA$QRM#J|n0bS-etk0*ZfXsMI=OJ} z#!%KbrUew9-w9)qLfGmX_29;tU65WOoX4;asibw@?1Qsf2C?#3we-p+3ufhovj{7D z=^38~{$3ctEQVM~C*^FoldJ3_H}t?;xnYhMW+rT9gXguAMnBvP29B|8{%&)r)A`Nd zy*ieSTx}**`Mw$UT#n_$-D-L4&N>g=+4>XX-DUN+%#Dz5I+?B5R}tnz2HYq}W!?SD z)K?udVVa5Z{?WDD5jOjd7bX|pV7lLRp=^2v46c&O8r`oCKTJ2lmQUl^tdA98gTYo9 zYMji8R=2LPvh&`U@>FJ*e;5GUz6mCUC9xUxTfsNu&G58MBHQa%8y;24g$1{jv5du! zDq*A7z8Ih9$ll$zgHM&Rpu>X*R&EE-E-edA1`ikNkbf&>mJYIl0BpH>CY=810I9lL zVOa4X_R!SjB{*F8^TrEVSJ&d4pW`PgWdd7>+P^vDG7$dRl@O;cF*ITxOEP}-G#{U7YYN?-I} z8z(4~aQ$in0V^}1@SQ?buBO7OZ+tP!HC!O5i=J6NiqrEs%Wvs}OS3ZA$K`FIIB7HF zC&jaH$pRW#Zh`8R$FiC`44^+hs^jUSc#OHtUNK1W!HI2G3koF~6j;J%*DatsQyIT{ zG5QkQ5$lZ~;*JO{k+wdogN-4T=lgiCP}**bTrG1+@j~sldqQicE&R2uE*u!20cTsL za^jrDCUy)wuv3kn!WBiYqQ)iH)p4O4!SswWGV%4rQWj+5jwOeyU|*Aq>W-5#Ac*fu z8*g`7y~|`H_za%HF8N+nZ}#5^(N7gZFLVLB`?@zCTcL~8Md_j#;KRK*#H$w(^#O}3iYU{4KUs`jji^WtKQpUGi+?35Yu>8jafr? zEYPisRH1~`>s9KX>FKs}yw#lHHy8rx5@NPmH`|14NzUuzQ9}f@$pZjHLzVHm-*fU4=O80Mf8Z?kII^id3P5Mds~- zV{JCWuHni#*Kf91N*&!B4SI?Mb(JsrQgEtZJuE+=)KwSjoznP8y)kxo6Ql|yt{tqd zx%kI=2tKF~x;DK*) zBBidj_41HgnfJvY_v%O$N=&-7QggaiHnek5+Lg)I7NnArRD+T|HkjIG@Lk zRbpfw{PB*AtHF$ADA~wA}z_i^U`4Pn;#@@*SN%*w>*x(j%e7(X~mMwMH8t z?V?hK3?>iA>&wY)W4>}3zbf2(lU7;XF@8g;CMw-;P%s@-uQRP zlBUZ&&UxUEQ&o^El(1V>ta(v&BMjQ0+!LGk9WP&>;(@IvR}%>863@pApZ#)+C!Tm* z|2Z?&sUj^2&VWyWsq9r$1!;_N2I#&>WySTrYR>p&!wl02${8HEM}DdCME5Ucfnp?0Z@)*Js4%?nvBvG>BwiyjCir=_j!Q(NkJDFZSiC-N96 z(MRMVY2Ikl?GmF3CFbYUm)r{@=$F;a)CJimx3_aifv%h=G_l11An-?bb*(3CXDbYB;xir3X6Es|^ z9M$@ZcjdPO`(ka71cJKg5%O=c249nhtn$JsUyd=VP~vFCrqa8qo8U?A#bMPx@fR+KUB(x@>(cq_8GipsRzjpJls4Rkd4O`s3v% zH^8B7cd5t3tPoXmC|V6;_T?7nf}46&?DI7_GWi)s}ntVU@VLf0LS9b-B|Z8ryL zG2ij7TU-F!65t>ucgTTdM+4a7A)Tckm-66SSLGe2?&=EKB7!c8ng1vrJyVpiYgY<~Mi4 zF4Yj0IIEd7wf1hf5HOhC-_}HWldv0%mMOJs(D;_@cRLJw415Swp@d_z=90&eU9ikh zd1EFC*p+HcVSaQwmQn{(;aIE&U0;46TWqMXpRa*669~i}l@)(`J70a6rhvW19^%+$t zaieNwY4EFk;J0EZC-}C5vR8a0K29(Y2#SF>!YJ? zfxP5fB%1GNE)diumVEiEd2*e(qcDD2FQMeLv~LXZHCJCtU_M0|VS(e*>z=lE{mC)HGbhTBtBJQOetz5UpWwqy)wtM zo=trzhXIA4T@uNT*pJhc4%R>qeI?KG+Oqa?wGpv6=6sT%P-4{1 ziJBE}wV-3K?1vl`)l(kgHwFVVlLdmh=n?XM;$c6z$AqzXv0gZ%3ME!wT&_ucE`uDP zw2~J$!{sUR7+j?nDiG8qmVE87a;bgm1T<(6#Y()Grs=Uluzw%PI&5{+j9ya+@A&+5y#?~}Jp~UMNH441H6~WwcCC2IYKQ!CB#$zYX*#bdb^a%ME zp`B6cv@ZeEUQS?Cp+xb+83m@tiy-8j62oiyRO#TX1ROSTyg*QwSn?$f-{7ZhJl>d; z#G+Cgsg1wN5OgSpojB&Ko>0JR^i3ptajc6v=u;uc#!8GlPis*7C*rUXv8dFRLdB3MFW4eoxF>5A$m! z;N5R20zqA?dfc{8o>c@k8rs^jRgK3@ixY*?QsM{; zR$uom1nX7G6&2xFpG`;~iwh!VGpbM``*Xayrdt8Dxuvv{n8&SIVYgVUH*JzYP*-vB z5Vh=92(IZ$j8An3vKHgVVzE&ud){QT`edjK`R~Ko*5t+NCGE7Jw=RNxTf9`gC`f{J zO_jS(R?#rly3SbC9vCDL)V1p2R<%)c8Qcyicb}sj;@SMjQRv~D%&0<%C4-Nsqtf@o zDl27FtxRVst2ufU4r>rD5Y*+|N~3=4A;CgjC5H8&BDU2&0%b5`nRYr*%Vs}JEe&NC zyZ%)7YIgu^mWBOeWP5pz#HN=<;K`~Mf=ai>G=U@#>tQv{WOf3b1 zy4a>K>dG??fbIi@cwYRFRj(6@57}*4SY!%0!}4LKUod;%(+p5&H!K)ASQvZfUm9O_ zlXa59(5~4Bpri7XIJl@0T-VtHo_0!4#>C<(bJ-t;MgtoOzeQc*nEw2M7nswxq4=|Q z1ECz0xa+PDQtBQET&=`dzT*VTm^K^}-Wv)8b)W-+ng&gs!)Q?S@3+gPoLR?w?Wv@>NZes_Uin zuktf1;Q6dT+oVt~58S8YWKW=$4TNtON zggD-QMtzkz*#_g%uTunqx~^2M0xS7k(T63=#j-3RVcCR%N6y4%mV1MMd`izRbI~0 z9Aa?k_8tO3UHe0hsaF?h;LEJxoS2bylDYKgiwoT@2=iQYu7J)6s8k_~OPH#LFRJe! z6=uUIL1!KKOx)5vtiEah+F2C|1a-w9xT1b>X$QQRpU97D|HmEdyzwA}*ZGVpl*o;G ztG-aW6E-zb-ksNvU&6W@g<c-&OPxBd7C_$fB{C>5x8;j?CQD^lufuJt& zS=+!tuoNvjRa~Q@6LXk6phHnl)FBYVEl-@FIK!$|DOIRVeXnZjt@d(*^Ly zRHe0>O6%1ALq}rU0a}5euKdFT3r^b|gf<@&IB_YxiF#EA|LVfpJVq5th;I|BF|Jad zO`|aDQLaEx*UsF=8rQQ0@RHBh^VZ%ZMmiWi7MB&SVpO37eP>XqFttn?IARRO#jFqr z>Jr~M)A#WdlU=d+$A{^{8zd#@TNwZ5ut z>W5Vu)e;EmqVr!oBc*f^xRm%~lZRE1DwH^Pal3uQi#%AfYZ5<$?{AG#&&>|t-A<99 zuKk_j3(oe;g&+5o5&FktW9&~^24jr(4@MPA%v@}Ia7g4%DDJ6TwH1tmBzMDLEU#TI z5Y% zvzG;ex@yhN*A(900ln@k*SUFMAKBS@7`~}p%&0<%sk4@88Z_Alwrk=!5j16rJS;F2 zznLEr2JG4Ls@#3PuACvyX)+9TYV2fGp+sd>v1aMEy|DGq_rYnUo8;I2 zA(-#CO(3Ytxl2_ksPlI4Gyd~BUzshZuMES>6<0H=P(uI9d(Cv$J<#i`GWy}x=!pFC z^B{CeUMdjOMaSWJ?e0D<$L$@0_1;Vs#@i`z{Z$<)?)FYN{YdFw^|gN>r`r$24Zafu zg1W>kq^cvI$S)IvaN*!UVcvie;>h;Jci-iT9{zaxQeT0fE}8+wvx=8i&>pGbk1n^m z2)R*|pd;!0UUK6$tJ=OF`p51QGLLAk3GF%Y_m3wxSmmdFc+?OH$EkRTX;edyRanHRLJ8V)=3mu)m&sIz z;im^Sj(#O%o6&3<+N)8iMpWF#+V%Fvvef%RP8ub|UbxZu4CdUwKaTEvTOg>5_G zYWVZ~*)uR2G8&t-SkI_J2|8ZJ$J;kV!hi>3Fh*~kKu{O$)$s4vPIH7!IdM4d@mygf zl@fGpk?#mpGf#cuO+04Im?jX^MaO;lTFcBjuz5rx9$pnIj0jVLj(+l;zX}Gj2Ho7z z*`f~8{3MzWMe~dJ&PLmYun8evcx7=lA=8Nxv_H>BQtL3bXp;{HgjEp;>Y_ak-Y*%@ znYqsmz&bO2Fse|3_UBcqmc?(u_wfJ>s`yhNsEhVE`0VS&8!$e8Fm8DMicy6Uv_H>R z>P_%~r#FZ25n+*_F52VZvzAAVp_6JDR=jtcQH2t;Kd(}Ci&~%=G-??7UAQF>)J1z7 zDpmREN1CX%k@z|BG@}Y7Xn$U%>S4A+nz%j!`)xWY5Y$C`9DJ{^H;1J*cSoSfnF2-? zO3?m1&xi9glvjmCp`F74fuJth@beozpF8T&Q~ z1a;9K2XBd~Q8Ma8M?5m=;~ z%&0;MIxDAA4ZOEgu4EjJi`R@62RLkk6hx@ay1e;PcftlelIh%>Dx2w4`Cpjia` z-Jna`f|eycanKAg6OiT$(i}fNroY@$?Qp6O*0yhqRG|cYzf!3t9p0pQ+Q18|RMQs- z>Y^EGd@O@!W~r+BVmnDs%seA`kM#XY`QG+k=|Y$f>em+u>Y|x-D%ByA(^APte{_z} z5i;l~LEo?VE(PCP${5`r_t{q#2eoV&5+inlU!N(s6d1REJ?^pckT(CqoTo8b5pr8(E`gvfaovPb{B`-tUVn60yFthbqlEb8ReSCWxldakJXatR)J4~9 z@OJ~>mvVg@AIv$hR#?qJ2{AWHJtGaJvTH@WG6E#$!gx^I+ z0Ozf+G+8P6zN)oQeai=jZoaRkt3)!fJEWFvg$Z*5gk6aFT{N&h_Q1YqWqC|Z_a~-= zr+atk^mHqHoukBXWTrUitpirwwAG#x)J2bw-`hj1@%xr8Slv!ONEJ%>oOT3Dx2^E# z&vMvovd1T_EYS@f3VRz;msoNy)=Hb9a>aSgx~f0gJ4g;LIZ)a^fO*$*kp2kBfeJ7D z*}gH(QjT{vtk|ins7jd@t8KM-0Si5nC4GGADy>f50y`h~XSYn_VT=rSgoX^hPr6&ip0bLt+aQayWq=P z5A3NziM%%`U5dzoiOZB2uSd4h2HbSPlM#giL0u--QL>25fzF`{@$9Ca*5Zo~J~enO zob&!Ix=R6kZvtwB3>$dfJhk82|Q(nktl_S%`f8<5;XV*mnV2 zet)4v&-0VvZjz_t7I;-HfYEcqXEXFhYcVdH#b->As6vUV5w6mc0hv&#xpGvACquRU z0-rGbYuyEcx@fKQ^#*kVwZ7+ca7)K(5>+Vi;JmXm*&rKUffD2TcMomiw1zm=u0TVT z6Wq0yyWVgY{UzS(YvG}tv$qk}JGEOl=ak4=?=0nZ&W2zICB_mrTkWeY9Wm5(O#%Ha z>Y~>sZ|x^6wN|?JnAxkqo+^~kEO(ULOt(Uf03}A>F$UU%{=Ko=%(cQfr!IOnRjM6Z zsx#vi6EJDjGIgg`C++K&ABPFg`moktdZ}Bc9E0F-ec0ZXj_O87j={r3W!?6-8cW&K zKVmWEME=2RRhOx4s~m-Wk~^E@SggLd{0~@D(3=f7A*+WR{sYPjffMh?++|a?48<-v zjii1hAJl`xrV37vD*hU+tTv zE?=ACH zhQQi)kTq2f{Q;l017j8TX%18_g54&{e&JVMJIED>CS(0Wz15$JmTKDS9EGks+?i>7 zFU`D($H0G7AC~;iK{N62F>oBElzeEy4Nd8#6zus{qn>MWqQH&URp&>2*pU2$ZaNc6 zz^Jwd+mohm)AmFO81h{zRH}N9_RH}@hGA!xB;VgPLvyQi2V8np4k^jJ)x6Awr=5R7 ztBX4{S+Tp|nqCb~+*BFLC3_R`(L)D^3gqU($yH9h5=Gy`eGtj$n3r3q`W*g)#Lc{8jpYQi!TRFXxv?cg2M zm=nW$>uDSB@xjYQ^QAaVXQ^?sJb0jXVRc(sOABk{!JsoP%(_}zsmZ;aVBFe`6D^mI zk*mtF=wH2)kON7x|0cw()hz6P2wdk3;Dn}h9(1jkgtq=(LXH>B-n!Y~lD${eVpx@~ zWQ*7uR>P6){PFUgmKwTCFWtZY?vD2Geo;P*O7rH#56f$?J9r|VwQ4BQ?|9R%fDd5z z><_2Rggu8{__u3bt{B~I>bVrOTGUvg-=n7AscwFFlx=L=S#UL5A?oIuXpKC&qhnT? zCh`wQsmWqDu>08)=+}r3-F1|t=5Db6fI=K^W1_u%vpbesMQW%*3Hq%hl`8$zPx)L< z5N>F6Ohdn(OuxMx;od}wj2{jQ%H4R3HtVZuE9eH`s*cArRG|d@IyBE0T~kwA^`b8} zog@;}MZZSPzYCDCUw)etjRs{ZiGKf@es4Ro)_G00J1KB&jVnK@tQ$pg$f*%Hw{``I zDwGhv2(7>0Mt-*;8TG5zm*^MF=@-*&kNIjM=1qrH*Ol5WJMJPMt(c6C2K6PXP(u9P zw&R9W2q>9|Z8tBIXltOYL_FuF-;ANw+7zr4%5&REYoG-EnmuprCH2+!&ZOX%sUksL zw7u~=+=iNL-mnQ6&{}M}^a#c8(T|8UVvWtlV?Tq%5>+UX+9yceG<`aRS5(eN@^Kf| zq;fKr-mW7M)TPN9t&S^9gL%cucd*)AAI6-ICE~`2xe`?U9W-DnEDu#;c)G>2 z(|(BL2EOq+ZsgO~k#IU?k#EzdC!B+x)(X3zoOl|5u4z67{gzCi?)Uz&3 zfDe}q!LRg^y5ap4IQLYEF>S_P)?6Y_)eQmye^&UBq(ahIL0L={Th*}6g9%W4W-KCQ$U!dG1OJsOX_hl&Jsi6!s4 zx+ZSB;)`iz1)3CQ21_msfRLAl&@ihhB;FeemQM|#mxTe0P8trIqk8Zdkp)$8>lc3v z($i?DLW$bdo501N!(inT<){wYd|>JBgV9eFEK!2GXpQiEhA;QnSihmzxUX2dlyKSj zU43&-9Mrw7#5gkV6l?DriEBMYg1YFLm-hcf5MRM?=4gwx*F43@Px1S#J#C zo8%0w9o-<~qjHDK8)J&YH#wl|oqHOpP~uaTGZf8qgXMF2al-w53kY;ZRCw6}xI6GP$3fF0#G_A2zGj}wS>0=(9$6Dwv|0#V%`S1G)7uVcRLL5%rrXI>p~QeOonV{e1gLoXBqxsl zu*AV1yWp3zX0p1Y73{K2hB1jHux+gk%K=s2p2C>H9n|!|h{jaQmY^GF2!cKQ#t-s|Apl`N?yj=?)(rR(y;h?7YzSJ3OUk?xn>Y_)>-v<}8LEG#0c8`xv-15}JiUmGs88=s=3MJ^5x_IrnRmQr91M#f8pFmI-eaGcldS`SoC8s}j zzcE{)3MJ_G!}wh45f$R}fq26sT_C87)&k!n#kU6E1KSrPrj|-np#=R-2j5R-Xic8L6l{p7i7FREgTm;TtO#Yubmc1Pdn#P6{f zMLuHceW7@&a0BFFBN&7GKY{5M_^izI56pPjU_5`!L|D^630gir^E2rc zi&;MeKOUYg5Y$CiVDOgs?gh)U4MD##>B8C!N{Ds!+T#|>jUS5VcI*SX+JzEyg$kbq zD7nB+RtQJKKh^+MD6u761#MesVBrO2L^wL^3_Ch290&h#K_IA$u4&=DrLH+_=+%^$W8?$SYGuylPI#Wd=#nxa(^TMiolXHAZ~Tfuel&FgY48U%CO5 zpe}lZe6?(ph7G?Lg=xcn0#zs>uE+VLIm-4JMPknOCjvoTV#yx`#jpi;Vli~I727^+ zt$L6DAxKy`Kv?rdS99?%(by!hsRLuN+eJ%Z)fUagqQAt)EUQgrRruF|3T(`U7?cn* zwj9f6vp(0x;OuaB@sk*-S=N4yN&pF(^4ad@Gq7o!R#=t@og zmOAwZWX2_7{YW!`pe}lZ{8?MS36t#;ads_NMiolX)sB3QzLF7(uF8q6&H_PQV#&`R zsH~Zrl7!lFZ$?+I($%t2?QibwGO-wTol?g7+O4ajZapapcVG5qRH1~Ju{EH19q9cn z8DBQ)BoNd^>rkcY2R)&(OA@}D&{wD{N{BgLgAa{>>gGx4)j=evOI-Up1wTs9n~meU z%Jmf1JBLlYRIrtgY_i!wLf$)n*6yz)XAexmFi%rKp@fxB zi8%9?vp`T6T_?`7UXn~?IGuncZykj-=aitUzWFHU`peRn5#unVw6{lPWA)gqX zx>I_s9fyyjJQ!6dA+ANPy|}-$?Lso1|K33$sEf7*zN16)_EMMNBwT6VS2*XCplhF1 zs@8>vG<6e_uxpUmuBeN)P?gGJhL3zVJ^}w&(uC0wY&x<{>rJKFWYI?+G$9^c2H7&I zP=csvOmj;c+=t?>QL0$Ab@l{*-bL3dQ zGAy8}v2X?{L3hRA>!a#Vk&BOw#S0eZ0zqALZwQsDYVapH^z|T2p4tff*0h(j3-V#> zFmFb82XV7*Bt^qMI0VW*+jZK!lb0PCjGs5g0#ztM_Zi_i!bhIUPrrv?#;zqm6}o>3 z{Ux5sG4!rH^kNuB#cva0P=fBT!bgNVT$XFj8jjCrED;FmqUWEF0jST*8!in;>)OYG zDwLo*q41fw;m73(c@em9@g0GnF0oyOW$I|>HwnaLRayg`&!)5CwBC3I_Q`76aohW2 z%9AackTW*Y4gMYHp>y4tUT=G8{M}qQ+|rBD^Q2Ps>{LyAtQpVP+T^OC3MH<;w3n_N zN_2p;KWlCkOLwO+f9GtGE1a*l=b>Mjw?Z?CbbVxa(rV1s*Ir{lp9c?52#*&oQ z0w_UUv_|*}g{eB)_hx~3Da0IT{m}Vg`b#_yAWBC&qe~!~-M18CP=e0(^I7En6}4ZV z4#4+Y0tAA(=-xuSmvN9ERn+aNWs{6XT}pYA5i$sjh@y6A0=WJEetm zLEZ_{aeGc&+EG_);pBxq?!K3(LWxqx_EL&v9#nHxi0Ht2TK!LbFll>hp{{6|>ISxu z^zUqi=_PGB;UZVpHvi_0uSc88RH1~EQ$=aaw_Q+Tt&DiRyP>b`(XAKut!OV0)HP;D zb7{2CRtPsyM!b&QucJMt?t}MFILmZKn$A>HntzS9q_KAWTsJ(j!%?ORCDHg?! z7?Glk+-0w8s4bY-6SdhO5Y#0eRnaO#ZKvms*x;2oe@>6^=^O)Tkmp8Nezrc3QT$L} zJ7seZ^m^A%rV1tYA6H4GCfRVUP#LYA(4eLEp1Gf)|I4xD15O*XSb zvmrh*RVcA-zoAsaZzXg(pp4dj%rMY?Jm!SWg98PEy66$|+SO~VZDtEN$iqjb3MD?6 zHIr(-UJH#Ql~L#W#;vrjhZqJN@f8T_5=%biOb6}x*PU_C7LbdkSxRFMr9zL_r4Zh- zy<}@V73{8Fg(V$pNbW`pVc@5WeDqxZuBEn1yfw~>a+0Y+i9=;=r3LY`VTI0fPUNm^ zsa<1<=;z`m5Y$EMkdH0BZm0cH+7%yv>?zb0C3-(?#rHN`0M&acWBTUD%(R+WVRBcjlhjsjw64DNc-mxeYnKhL8`?-^eC~fy_3cozVOOcV(@2>9 zavzWJ^HeKsx_zX(wAiIL$l)Wv@VbN4dD;6i#gOG}F#*3YewVk$uci%6#b!2dB(}yJ{xg+2jjzPNV~^5&r$b z_hwpsKQ-U#+d!4b? zt^{dMTSuwp^`3CE>mZ<+BQ&>#zjMBAq8-@F9gWOeN>rhQm@U%Ls)hE`s2*q^nIh!L zP#4XB;qRO=QzWn3+TcGkJJxHx8BjqEm23|3(5qT|diL7eud{0YA4YbK8^7o5(x)K3+vxgXPgn zeKhXT^Wj39bf8DrZK9v%V1wCE8^>^>SL@1hhXzTwY`LXO6-v;f%bNCg4|wTIhMdxI zC{`KpSRkm&q276opUV{Jb9*d5s*FamykcZ1&g?!*ezmMnGpEg37_{RY(DVOC_DM}@ zqjc!9U<)S(Rm+j3XT!0tZJJCKO3=2zS6aM1AbYwF!{hmh0zqAqE}hk+Pn`kL1LpG> zA6{&c%|}Eb1Pzv{LJ8Uy_?ozmdt@|^#5JXE0zqA3$va1Hly5AEL2q|MnJSc^ZGq<$ z_1hso=@E@9?tYahL0#e*>~641_8c}AyF{i5=YtYrEAe#NB3J)08eiO02?TY~Ts*!r z-dAJos6$TJ@MXGiZ>LWB|foK?0L8b(C z(Hh}d-lyKky5T{%-PKa4T}tfoR7v(nCquU$3-~!d*x-`<;Uxc1A7?|*yT z*ZI4zo!QyhiECz9Z0&1HIlpESHL4ISW0WsO|LWU0X-!zHbKWmK)~3F9u8MqNcOu>0 zCt5}e67_%VF7gQ2P1>b=XLoh;wXJNR#L-43nH+(tIVP^!Fcw>FuJeNtD<9~~v*xGM zn*HVq7!i$e&wO-rWRrDLnMDTs8mufr3le;E^pl^Dr5zQ=((ZA+B_vRl5$LY1{QVf2 z)LLrnSzK(1L`c%?P*jpDcd6o=V&h%cS?y(&(3f7aV~qKAw6*`*`Va zk93+iMn^^q68?J@xvgDyl$;)=_BkK*E0nqqPo*8rY&Zf{_-xpTI&XeyPwz>k-7dRw zQQkZ`z9d^D(N4(|IRaIq4Jx{KyuX{Y?xvQjE=Q}ApN!}cIZ;Ln5&7YROw{&ifYEPRcj z!+Q&N!S%` zs8XXP1vhtbjb_4%@@1=*|(S!m%25zH{(B zS$9f*+IxO4ZcGLVEcvYVc~n8!*(8`6CWLbYs`&Ae`lFx8hb;QgpbDe7(GMhW6%3o( zzFkwXw(d@y`#qF!G!sXGarBc#4&17y7z@EP%5WDqE{X(>Cu=m%9V#hRi+fRr2J1Ki zRXB>vX7#;3%ZFq8(>>D%aU~InfR8n$vhVxIy}vrJxAw1Y59QbQ2h)%7aU6jvES0Pc zS9)0v-7uVfu&d0iT|(k@{0D7>z}8I-?8JObHkD@|L(5 z+TF2_7A;78|8Pt@Z2lo~b$w^%qsTN*-l4?Pl1RfMBv8e_wbQeB(xxbF>Gv~BHcsc;x7^O=!vx)fvUYP_6i@W93=JJ)E2;w zg?B{Z`e2%Fc~?RU5*T^N+M+j4ia!nxr)4^NG7_lj<-Jq*uv;PvJF7Kyohr}7od*Zd ztqsg%v><`;mu%J6&tlR1;b2;{%84UTHGKGXVYcah;{8GW;xx*9D^7OpL(9V3$!I|W z<5Srd5c#)7$GZdQo`ZoLfvSCTb_mB4c9K1&>gqF{3O~fmQ=# z1PQn<5mz7bYZMpTjSP$607X zf#r?G!`&Ju-g_HMKMxA#2vqT_GxhRTh?iX>sZLRU87)X)d1GVY&F72fFGSL~?eQFe zDqI=L#`@aq7gvT4rMKIR;ns{If#r?0WRC06(p{nSVA4V@t}@(R=0^6j8Rdd4T||u1 zWV5d+y0mxQp7iy#GA&w=z}R87m-n#m;>W^%blTp0men(IO|F8tz`q5van5Jyyfboh)w4 zPozt12N1L%f$uyUv$PEr4V#al)t*TlfhvrXW37zFqImyp3N?G2L(qZ*)=I4JJX}|_ z=$%H3R$k@^RPnKDH^$v0%}=G%Nv4YlT9Cli*{ocx>`A)TA4_95-Qx&U@zGS<=C=^< zvoU~CcPGfWjvD)C_-?Y^#K|+{=J73aCC(~)Sq(uZRNZ_~@D~YdkWv`xT^xdsX9Dyo~_hWHnIilR| zbqc+4aSA~T5_}8UVt%On7duDVdZ(5nP{l{LJ>5H5&YPb|k2mj2(1HZE$l3Q}!fd&D zRy<8GT*MKm!dN^ui~MYpJm5qOE!|q1palu+CulT@=l05*v!ZFch<+S_DvTCmbxF)c zdD@&2G=5oM0WC;ie@CNPL2k+R?5kFL-(!wI6(0{5diR~|&Ayyb8~ba~f&}*4*jpR@ zUEZ{>A00Z(uLucLVeA*%J7Gvw#jRf$U0BUtLJJbOj{@5zt#viUcXCCbq=B5C~f`LbQ(+1iz3R*>nFFOp3!ytN8j2RCf{1tP}5h>Pjs>Cea!JX&iy7n(qg=FF7!cygwYv zh*?wgNjF9ecTJPgf<*4oyPiJmu39`+edxZ=BFFC~)2~&Aas;a4`aba7$!3=uy-|G_ zdsh|T7$nk9E0SciAmM4+TX@H2ervg_^PF3IG#4AYCDOjF2XF+c?q&8BhStp`Wkb|i z%fd;KqRE|Dy5(z>j20wp&Mg-f8BZe(4yittv-5)ey2jF}yMs9bRsM@t3Ik4OkyCGt4$iYTij+hlDeMv;|Nq)%)Kfc_sb-n zE#evB8+cV5eSQ$#+@p((79@6*RUm&IpFsL1s`EGxA|HyH=L6`83r-w?Dq&V7(%w0h z6lWwbqR#9Jw54$vJzB$AMhg~L9k%G5f$r86z<|F5IQ#yQLJ36i4 zh=dkg-HrdmdS1gDP%*3veSf)#^MM4e6K87_-&dwTSBKFpC2u(bRhWltZ;=@#;)N{( z>CP_KCA1*H?+36b;evRv{xE7Y+K|g#RAE_QvCi?^#MYgosp-ql5?YYJJr!6jx?qK9 zJ9iW{9b&?j5>#QCX7e}~$BT7)CeVW&b-1#N1nyG7+6>i(ie1VQ=!{y;I09ApZn6=U zjaKY5s}ySKZNR;QNZ@W8tUs7pSrqH0&@$JS9DypVW7s%Dt%>9Si+Zv4FyiVGBru+Z z)znEk6psNT-}ZY#(}V!x`CZsdG=^}p-nDFpbEcTY%aAhR@Tdmrla~!`JU9zyM_&g8zeNR&Zj1RH@ATGIy~ov7|r z7a8|2z#R*4zXKL~Zev9!yb|gB{(js}2uSez8oc~uNX3XQ^kMy>9Dyp!pfaJ&mIdTh zh&t~aIA4dpz0jRrY&k+k3lfeIKZR|*r;u;Y)!FdvHC~ImkA%@5TgPz(sv?XJ3s?bZK{kGB-TYP5gx9eL;R1bZJ(+)ri!iSjilt`T#i6h`%fK& zfs0p@dWSDCVnuv{xT{_ionk&uMhg-{(?SHx?|Gzl1J%dANC&a-;V3%VaS=zL%5uXQ zPoME?$t+LR$6$K{@k?qfy|i$lj20vY-o5ErTa!=3EozJG;jZb#SQ$-~RZBPmRW&MG zx*xV$M>x@k`5_xw2xhZj20v;Qro#FZO$imvs52>XAGnVP2y;R$5M_!)y>>P zMO9cjBuCXpc!`1RStpi8ylWCGZJF!sj}xiUBT$7cK(?dYdjqnV5oJd6WV9fGxxm(WP0l5;to0f*d^$&<3R{5e{a8{>+;L_! z%^5#iMhg=7G}#!LY$pz#Gn%gal*19I!WJMqO>od?(PC0GouNBTMhg;HD%q%W8xMhg=7cCmOkQYe;n7)t%uC2<6*um#9QYq#GL zQ;gXD)NA5ov><`C1Zz{LJr|u$_Mydh2XF+cum#9gHJ-0bwK_rc$j2}lEl6N($J(NX z)o8a?-Ragvz8rxnYyq-8$+wx)=tOV&pNmI{M=Ll5cE0%^rkg7(A1ejX)}woI1gbDjitWr@*-&{lxGTLjYoLr4 zB=~6cf&^W~XjK5+c_Wr1P=%3Itc5(nP)T*~Lf5-S%VKaH=gpVpWzOL&8aJ0CP{p@PvU+TiOWcN0-9Fh|y95c0 zfMK&Trc>q7%_FGeuUQ;{Dy+fTsfamoa^peKG%tP{SGOa9F*34SK--TAv> z!G=CGJ~ophP=&2pwo~EO@8a|dA=KkY0@r#)f}cf}ryJ5x(uGc17ReE);@j;#cQ>X+ zH`zw!$)Q{;90`6OuUf(O)OCq7E%5EY5vao5(=?hOPeEB?(2OQ$dvYtoc6>9H#@|>* zo>Z(O;;ybN8rRoTS<|vPwLj*;?e~fVu8(88!#s~s?tfk)76t3czCSIbO+l+kvxAo6 z%e@v-O!gX5xYklcn$42+8?3Bte^Z<}+E_-FPH-9l*-YBd zYCV}dUiC3$h_&KgL7)K*I&cK4aAhEC=?9KgZlAj(1s?U4RvfjEo)@nmcHb<;8v`w+ zs>@fBCXX#e=Y{5yw)+wy_pZZyl=)^T)B2te`rVu*p#_OM6)dGUKC4OGA@!~rb`DW) zxK>q8+Ex@l=$J|#$Meb8A9X}Wb5qGGVlf$a(OBGY-AsD0eGxI+ulmT|9je@|qpMsG zzD>}A#PkGHY0s<0*{T&s-YOVi}qK*n$xSGY2RQ&VP_Eh?6~$KvkZ7V`<{PWn_OFHBM&z&LCyn zq+jw7qcpakorPp=H=C@PSw$RQY%bMWFq4E{tRfz9F_$i8%p%#=>Ker^{z1wQ>k3N0 zvINc&w%trJIWn8vYoW*e6Kf%V2~?b)R8r0)4&p3Gl$M%E-3{gwTCpbcQFBbVGU)qF z+5ayajzAUWIvaZp3sUsQS5;!DE%&65SoX<8+TUma$$D+Xd=x$kQj!l;RSL#6;s{h> zSzuqa3jLK@7U$$EpJs?hW;K@eW9v>M1J-C*I_@TgC@n{Pl2_YJ;0RRV(`38#xQdCypUZ zedox@>vmGLSK~-l@g0KcV?CC3Bb53>SISM3Cvho9Vy>H=WV~`biN17?rF@F_U}dTA zemSXQE=QmW^Nsa!Hl-@959CO_%vy@?hdW6o2jfV@ijySbyo2QHkVGb*IY;nrS!B(S z6s6~tQ__i%o?JSRxK-Ujinx?aReGI~@?QjR@oB1hg0=Z)zrUY6tk_HM0b5ZPoourWaZnJWX@eh z4pi}wjy?=0K}WWdXJ6c<4pRpc?dq-UuDlk;D+Y)2#Jh0|1+*X$>FzE)cs_(YX|eB;7+VD>H7?Yqw&wW~T9B|5snmXC5UEvRCL@|R4p652 zs!cojPUi?z-DuucT45bXx)iH(ESeh~m3e+9be{b}2`xy>_|jH#Z5u!qtjc0Uwk=f- z7~9aiE=#2-?{-o@woWwYW(IktZ6^gy=}PW>$sjy&w`&{aFEeMl(<@p!(b`-3W!-^X zv?Lhnb7=rI`~gF3ptCg2c;?Ueekroyn4= z>g-a&7Z+t=eMh=^_#BQv72Yj-qu#qK$#+`Pa%DHq*bsIld!BD8RXnU7SX*oP3YDI>B4CuM593#GZOB=nBY2Je==QL7x4siiKo zEVvVw4kYk7vGMkUtreqUH#&8eJ4c`jcY+OybT9CkXw=BwgcS~h- z1y4FY_AIxnJnkgVr(>D6m7+BEpk@207A;6%9>sMdmbO-+bH|J+R%Y#ws4~#xTcyfyItQnDS9Ps=&Nt5xRQtju3cj% zdiu6e63(}wE$`0d2vlKCv)uJ{P=cSj(t8fs+#7`iuAJ6r!opiCr61ksje_AEfhzt9 z?rG6ZDc)jDw+>q?VV!}s51;Z*(Vj}sMLW9T)_yJ>NZ=R{+h5eyS$W>uiI(0f>*@U+*WSS0bEnhBG1nHE9CMi+G#;2cRj!nsKR_> z@8D?FSXIr51poalHZgoq_=+RuF2|489<`|bFdvSi#sTDHZ`P;TxxIxsxaT!EWkmc+-l#Ho~b2p{d3&21pB)zCiNRt z+-_RZooC&-ek~HX`w5GHIMqYhG^;u_SX+xDP=z_db{J3fR+b+zr z6{idvvP=x8(*-0@g>7y2JZ_{aA4WG7hfG^a(1HZt-Yq?mt|Si#Ad8DXaRjQc4bR%U z9nzK0<2;Ju&(`7kAK2$W-)z67;1s3%nTwL;F%Pb9fCS%<+GLWfT=A$cN8Rnn5vam` zqDFIR;|QgicBQ<{cmmghM1t>gp6xVHxu$0lCM{};fWR`aO8!pKetIyx?cB{yJhd?(@#l zoxc_nv>+k(wv@Vs&n2hqs<0Yv#>^CD@E3jgbVpOJCyXjScb9e=t6bl{LAV*nb_It1 zITB)+jkKjCn+)`L$y%>D8`G5rqo)hwwpQhG7gc;ISwvEmC;G19QHvQ|NkpRfii7lH zO$ymw7Ta{#` zB0Ed?&fPEp2~=Ueu@NuVXvODVp|~&Uofa)f;FpNyZp%2O%bTU*rXFuRkw6vZG@F}P zI#fAR>o3uyovVZvB={CU@aG|leT94CTk9qqfhzt98dV8Y4wM+u&ASh9Z8#+Oc1h6u z4occc6S}zc2}huc-*2hokk<6lFE{$vlm6UUDR>IXizFZ7Ys-4VW7VE;OvMBmJ7lhW zS~tzJWr`(va(e|?SKmtf+24|QZC^p^nplZP7MYXekVWKs8+BaNZAdg7*P~E&xw%9@ z3leP?Sdf8(my=?mjzH>J44{$9dwJ;6nFI+`IhdJ|UGEl?163O_!q6d@mbEib*3EJy zXhGty6OGA&!eyjKchyHgKne}{Ma7~UinPtdlAOG}hO9VXDej(WNxpPlO}gB(6rYAS zCT+_KNY*uVM>&^e>2&v-J0v4(jf55?D$cef3p%bQYZ=YXknWs8FMECv{A=fO1geHq zu_DiotRzh}>Rp}v)SGsZzKC9TOy%8|%t-R+Wu$$2ZE@_u#>7flOSbQ{6yqyekWO>f z64O1ZkIt-TH+8BVJvXNvccujrcmfBTU2^S0kF~8s7uecyCv6~szS(ZTXar|H+36rPF*@$%VC%(-G!s_ zNpyAsOawnOg z3eQAiar#Z1=;B>2G|KUZ7FEvqzNCo#@8jn_M3jBW9yY4_D#(NRcqz4_Q5GJw+E8=u zd^Mz(F7PF_JNc4TU(}IQqo)qkt%@7n^($YC79@Bd3tXM3e9DCmdsLYtP?c)IQhnTq zeE+KYs5{n)>Up`)=K~u{c<<SzfWTyh>)Yrn9Ea zkP*9aJukZRM^j3QXGv&LO4teJ)BMS! zWs?c1=tC;6>r6gbtLr~fj(O4pP3`H7!YLeqD!f~Ex=JM%N;*2xxc%d~bRcnRvk#Hl zbtEyh!kLfIF3xnZNgF!hc??IOiqGA=OMU6Fvp>XI?1Vh5^@{?XNO$uTa%AOM!q+|# zS0kur)#IYo$l+SFATedSCzo!Sia| z>$!+O~H&pd>D z4pC>Y&b1GDB^Mr{Ufhv6dY=^(W0d&~z+BDQJo2##oFe+$AE~E#NSJl-yuTwoc z(Qf-1(F<4Ra0IHb^st>HH>c1cO?GCC6O;w?GKtJr_y^pW=eUx9YnMsQF^Hj2`r2wubQ4>#GFU*wEgb6;sggtusrWU z#+?{KYA5X^HpQM~Nn|)VylgAMXQR=W*N>-})fb9!-}42uAdz{^ll1BrPS#FVpLy)J zQPj(OhnQC3ga;C+!Y9k3EQ&*@o%aX1-_uNy*jW%4=b7Z?&?@4F$yTIY)oJAV35~eq zgeAFiW)?ARqW0*gKkh|4jd&y<^UvZeNPL@QO-_8zCK2a8u)8`mY$VllUL*UQ7|ju= z3LR@pOh2&sdQY`SFS~`)){kV_D>Fw#3lh7Go0H}}vdCqfH;m|G)1UfoJR^6iH%ml| zW3CO^b9xf_x#lIA_Q8f6cAiXHjaPlRbsj?Ftar)3gj^9VNE8mRC*$Su#Hs3iM(B(l zO{)(cA}8iVa0IHbEUGCGmD~U)nd0;bUYk40?vvbUqf zPQm8|v>;)z$Cg~0nN9Z1Q+F62>m5m7pFSeao4rqq1gfxK!e%WO#nS4Y>%~vAFMFZ| z3H&Cqo^Vnhs()5PH)hS@`Z%bu-1a*!r(vE~R=xvz5~OKg*gm!bNN z+HaXo-%UDHRJOcGb9JV&R9iK1ZOc;DHN?c*SB^!qga+0l8!8(U7Ck zpbhR4j-=qo6qYd-zxykdp1SWO2kq=GpalsWb7EslHW@TtoFJKf>q3w~6_zpf{pc`; z#uWO<%cU;_ElBV+!&c9+^m64x+VgEoI098z#@Jc$A5-X_diSLv&zp&8L4tqgkHXSv z<%mE>$pNM2^yhI&CzjK8Rs(O8ZRdnC9xg&_U%Ut65HEs*Ur3|Dg7qy)s3CMRb8`9 z2~Sjsy&-!a8Kyk7YgC99B>XL2YWFNnmF{GzclBz@S9wpn{>si%jvRri`umzo(=YV- z&t3Inv7*wfFlE*yuR^pSvADjm)G&Cc)IU}AA>`Iq;sU!VOFD)XqNUn_-~W3ufweX` zAC5^DO5i#_rN`)@oDU>?YPw4mY`aRIMyWoIq_tA&hI=S?<5M^SRabI@r1eJ}|C5f` zv!TkRJ$g#i&-}t^_amhh9So(EzNTcGYob)>rukb{uUUxHW>{+}Z;0xng%F_JdsauW zT`;#0ElBV_zW(K-oLyz5>`a}?5vV#cCrH}B?#gf_J?LGd=RSE|gLT!9Fd>r-_}`JbkF5Ou8dyPg+%o_l|_NWUQ33_>#6-sCri+ z`q9dvaIM_#_Ii#$)svc&CH>|zw7=hv0-t!LzFWS$yX%%hRNbiaTh+aXDdCA#?EQOM zW4t`|*tSBnAaP{qWNFR*$=dpiX1i0q7^6f#>?@B8-oX*5inN^~b#iU?pSvoVk)}A) zW^#txu0pgRk&rS)YOv^P(PMwrht-9#%DqoVq_LNFa|Eh(F3pkB$GH{#PI>>F4CR<- zg488!Pa&$-tjv)zn97L#FHgLBlA%O(dZ6`PxTg>;NH`tJk!nXq?D^JBy{q9rGL(?g z8iM-7?}YjQl(0v4_VhRjQsO zpHJ@Q2vi-LnJsm0=Og^~v1oI;(rba9xV+NtLR9Uan=N%>swn}cgeL}XO;v6?dy291 zcNU@riKfT1q@lHY2`1gulrOn3M(I=7U)YIQ@ORG-Y>@AO@>Gf}6xDb02OL&5bs31gb*6W=K!hT>X!a@S9OeRIns^?OR`n z79<*1822}^E=2WFBW<|Szt>eU`Qd7gK-D;Tv=qKuhy2c6(`SPfd-7O3AH1>Ex}e=yxS(d)Xz|iw|w7+79@`9>$y+z&i$KaF{yJq zOPZ}2iV!i2BTzNoKGS_JBYN*pQ(k(#ZsE^g8Om|D5xdcXM1W(~--P4eEt!#V9m)1> z8On(TGu)6sm4jh3p*L$2JvyNJXrK0lJg+}ix$@S*9W6-Q+>;>Wy~~ocZPnJ2)Wc6S zZ;Z0m$;v{C5G&}^pz>8 zXw``5bss8)K39nqHdX1H6Jd&NH!qGr)rVW9LQ>B(sco=&R~E-!i|tDXDzT?pc%aJL z{k1S_ajJCvwkhF>Zs|9~fd_{vPwX0bpaqEsr+@nx!Du$_6SGGQa~!3V*i_^QRADZ# z_ha-@v952NGC%X7J6e#K^mv6(oHJ1}IIsF}X`dt}Mm!Tx+sx9REJwvHaguc>ieLhE^>dtC5 zi=jA5!;;k8eeK+peynb++=!g*fvV~bVPwX@)>7kNri3TDJn*3lms%;?Qm1;L1&PZA zzkSU7sir*lo-3VW>Zr_g%H#-CVd-JzYJ4ji)6YY>5ud`95+r^!^du%tyGqJ?)kj>K z1vOaZr*s`Xlp|1urIO9#97v}nJ$2=gM!P*yO|r-l;~84dTwRj3A(zDKyA`EP*Com6 zIfM?pT6D3Fn!E4srqK6yI?Dqq?esuPz{o5zdE;d5(pqK&|A|FlOG&i2;&?gd*f!1w z5{V6d`yRq*wr=8UEd61&R(`d96Gxy5%L0oFuO3YuL$xx!y`FpKNW2&`j?|rTNxRWN z^|5Q#P&#+a-|a+>KoyoTHgE7NgZ8tmRP=V^9*?3ex#VaqQ%}2kX5`M1T=Fv@%H>U6 zGcMm)blcMm>K}Vw>%DM~2j(aeNo#UR0?X;ujAkRLIc$H%^YK!*FrGja<~o~$+?+}q z_VX0K=k4@}x}8l*GkXbB*^|w^oYkiPwVgi6!Y(*7}n?VTt$7ftMU zd7uS}+&(#^m&Qy;`}?l0KORfJT#(4u2fH}}RhT~36W+wm@=EST_Qde%K*BO3m)w5d z-?KK$LzcUrGw2F!tngzEPoN5OoyA{`jiU7}6|sHtdJpWyZ>*e2KJ+{!9I9EqM_*zz zimoxBt3D8u&K7{BRnOAHqQ=~=~$;P?ZZ84U}hd5JY?^$U62I0F)sq9aJfk@d)lziZJe9s1Jg`!rN}TEG#g z!aQW7=fQ($2T~>)Ojyq46%x~0B$9&3l}J=IHRUD=L+RVHJECXYDvm%Ej@7W$18u|0^bS5Y;lTg za>Sqf^dCn$&khuQ%)5}!?7HDef3dx(ANf@~mwY^_`VdaW)2#VZNbh^IWV9ghc5X-V zp3yN)yE5YW+R^k?>lq}f#ZrzyRVDxSob>-_{0*EGH90{Kg zEaDxy#Q2l+A5+N2=jzGUgSL*LfjyUy#`^+gv><_Z%ih7~V`yGUF&P%%%@L?N7T=9j zu$xI%wFqH8%-bc?N;mq8zO(O0(_i@!_pxh8%W7dF=CossH)$BYme?5dV8p0X$+Yx^ zAi9{>lhJ|%|2$d@Or{1_F5>ad%{c;9J;K@%@^USylGu&;7`cLdar#sjrN~|~T9EK} z@*&;Z%_Glus!y=wWfJvzQCGZ_)Quxh^?e&9p*7c$+4fx+L6;}fpGOBtSG}U-V}8zL z+l-~;lW|+I%Svam>GN7r8bC##fi7f1g>|H#pq`7InvzWOI%P{9CnIH4AuSs?lf7@& zk~#B5M$C90Pt)ynaU>mDW3y~x*p?$ul~B}z463n)T*_3>cYZQ2g4Un0O{T+%j20xiMztX8 zU#}*g8>z&-cY|npjcc;OGCvtDNVMwIn3zNtko^XeAk%trDG&2GNyU43sVv`$}j*;+>-< z8FOhlX}6{sBlJUiQlk$#%8<5oID%6>wj{%YSCIOVDv{L1iDt*xDC19O%l@4jkU*Px zWKgK1_^eJ1vZ!yfYTW{|bJ)N)m=k~>Wbe=b+oR8f#X)yFh5Qg$zw zRIH=EgURD9=#naB^1;<+O5>juNZht8a@5XI{7|zJIlO)fIdjpW++8(wv82tnRaQK7 zYjZx3*mI&XF&&soc6m84AGeNMQQf!I6^jmf9Dyp#5!P4h${)LlV$*K)^SE$;RU4vx#P9`a*of+}K){^#mJwg8d&O<>95)myckm-(-$>dno z$HUS=^m5#Ia^t`Y`PyT5a+9TS+$V3*XSFkV-hinbyhQh=ZOJ3{`|%fkj2KmQ1TB3$ ziA?HpQAP_A_}yhQ?kA$?l6Ltd?bv>fK-K5&KBR>C@Y~dp`8csThDP3+LspO9Afp8d zzLhb&AenyeT~9naw5^P7D*X2G?W^d)NwoTzU!-HRp)y*Kz^^DsFz}bxvhGwC(>8W*cMA&VP zKvjs9B{}klwK6PR8R0(Mf=2nSlP6VbqhR^LcOJ_dtJ^o((yL^T?7ONNR}zuHI)?3y zyUv|XzcyMPJEkc|pbFnjwi@tiJ349gSUGoDL+<@Rg0HXEp9!E-Yrc@)I2v&Ts^*(H zlLm#kgy?y(l)t+=k~&Xc?D_QkX&IjysxYV7_-|_3?nZ(Qu<5wUj0Qz3ldmsv$N>lc+*=eKg*|_uX6;d_-8(MMH||F zTSFyaf+V8_3H=ZHWc!DiB#x@zkFy6w>e#TRQq5#9N1zJ7!R(}sk9M?zeRE|(w~gG_ z8Hoj-^hx%onWR8eeXQKtidt8;QG(hn<_J{bx1B{U*YTm3k3|SSbDAjWBbtystd@DY z!c#na*Nkjt*H0RHl&h%^M7N`-b%F%Dbo51yMsP2SZM+YhTRV?XoD(5__d z@;PMBsPcVIb18-1|DrE$I?+JJUJ4R?&uiALWNH=hhBR64&k?A?H;t`iZJb1B8=WH& z%M!VF5DEM;u-L&3(X@7PAEINqmm^Sx?;~qp{TfQ22G=K}AKa4Bf&}I|J2iAnD0S?- zQ9IRKUqJ#@e0}9@)q`fd`|0_?u@+ZKkl>$3RijQcaQHOglBp?2pbE=0TYZ-2N>`*b zQnqPW(HFDy%Wss+4Oz z>E*hQf3A5yhK3a7l3AtQIRaHU=EQc=S=Ez9c>NLw2HVU1 zwpfz)HP(|yZ>_o2dAOpE?K#l11D%!IfcA`XlhHEW!;GAdTTf;$vJ~;3G#Z0r&a~oH zd;0aP$oW8GyRSK!6S9FE_ioB+pH>51X!Sw%^mt=|BT!YrvN4;V+CV-(v1Y{Wg2vQh zZ9BTBC6UpBM9>R!68vBT(L7a&mTc6(K6H+Fw5XPhYacOQ^yV2W(z)w8()hDVB!3t{ zYpi`No~+r7i%G@QBF$zq$N;+G)l;$FGaDH#NF?mAB=!dD$tRZUY)t0N5c=lmMe&Ze zHAkR|zbnu0Npw?csF?gnhf4>laHS?2RdY+C+DrY#T^TiGv>-9dzX^GBWes^}sP>&b ztBj@DjU!0^0rw>&P=#@eY{kg9NSfC5u-wO>l7uT{YqN;>xWJXfG`N|Ft6JIaNu3AL z3O`@TUtZkOq6G;J*Q1vn^`xr@>L_F4dlw>sDt@)>fz|0$pG+b{ZoifA-o+kGh}XF_ zB%($$kxz%5I+k_|Yoq-h_ZJtLiA2NVCd8!wYN9k%^J>S`G}^yr9eLN?#TMGLBL-kQ*W)jW2moB^KL~#VFFxS~!(XS+G9S|qq zy*rD09!MB^HX#pUR*}x0s*k{jakTQ-1u{)d<_J`A&qia_qNf|%xkh0l)|y4FYz2$u z$>fZWjo73#LI`8mLH%vT(mMA%%a$dRg6clZ2NJ(*0!ZM>WYVmCxLD_=rYP<*YegQg>sNcI=x4k|*vE*9j{fC{gYrqO$I@i7 zcX>-O*KM!1C%e{W+l#_77wrdjoqo`_9I-j-m*B(891&N;L-AE-yHyE1mF9fP?G;BlOv0Rw9CaD~OPY|D4r{eA;jQQ9&t6w=H#_pz2 zk^NVL(pKW|HLrxG?7Ca3!@uM%<~tJ4`g|7zM(;0F$1?DFAb~1;vOIxLtw5OJHj6#A zyY~O~1o7D-k)yxf^E#t#MmH~aS4g1hzrP=7L1NkCd!DbEkIQ??`#=I!_-^tkUlm~| zwO_*CiQS_3@sp{P%&vQzc!+QM&)3diCGkn5I@5r;`^QIo=LB)HJVFRz?}T$^mUud> zvCx2B#~5dqBk+HPrI6u}6`spScKp#ho4 zYRhIL#)*5Y8j{iMx^Ut6f9l;5`TFUwo+lg{uGl9mLklU1xVvh28t48b1Gg&;Nf*=1=XTT9CLAeD zx_RaDEg2+G^(TG*p1VlcAN*Y>ZYoqq=a+L1ewuVtMc_O5~%v`H8r*@|Ge{RYqEJHnrGI0D z_7wXXtm&@KT4G*di*;a^&>`29fQ^gSX~XWx&l?flC5Kmt|x_2KWT z;-&!U47-!o*@HySIo+j`?0V_j{^Hz2%o!H_uU)G_R(bj+jqi<|FITDqC#31=_aEWE*f4g<$vxeZJ}aYlE{zi{tWBh`>{|b5#y_Rqwj`>Y zk3VHswIK1>$4p9MbdyFI|3aWDCa#6li4j-6rj#RYbvUhcWu`jx6J?12NFexDoU3bJ?3ut z9t++TsxS}v=YbX^5;G0ijzq~MWBT}VDMtcT_+)t>HOEJ4Pp}*fo|GjHuwJU2z^-d9 zoBThf9Ek@$`?O(x?N!6+T)1uJB7g&UUYGoPG6YJe~BvI^f@sdA1i+>->Kq7Z}b*(X@16<0FOyGZ^3QH(|S7NrP63lg|agGK3mNc=nH+QXAL0#*DItaYm| z_1dOStndHio*+IOj4xtqOg8kQT{`Cokp@*1v>?&+ggxoY@+$DCI=@2Dxz7QB0luLr7*(TE0^pMT|CPku^`u>G~!)!m+#UIRaHuqw1uD{nLG- z#t7@qw5ASv`ecxcmx2}~Fz#8S*|^@0UaFlVSbh*V0#(ITYLNHLM@1vGuh#ZtE4uNG z9=ZP1T|o;Hd^}wBp)Rz!M~-lPjuS_q3iFMXD|3NvRP@Q+;r0qzkihsmcJ^6jTPm~K zXXT{k9DyqSd9*F4L5tet2uJS)Dy_wv!g!X#7x!9;7kj-F(%JLa|D&~t&xx&fHmpNO zx#|(e1tYpN28Wi zT_T={*C!jp;y40T`25+4&|#irt5J^7U`K|Me{_ahO_stvrOm_|`)0T;VY$1!tXa9- zExWvp)N7_siXV^V@(PLc4d*@YGg=#}K95GB6~)2t^+^2DbdEq3K3VpDI9(I6mgti! zhcjsXz=C}R?7!T0WsBnj3icVYJG9@OE$+OO?ODivw@XypyBn9!Bu!Fsg&RFGC|Z!n zZ+6==lF{8esYK|DNuts(S2$BWi8>zcAna$BcJH#pskcT5SJ<`pj4bhH(}BVd=40M+ zwY@vaE?I1tr%xuhCR4PW+2OF!RyI$9DviRceUZFj!edMod zPxw){VzJS7eR5kILD7Oltw-|(Ge!%?)L!bqUi-vl`*Q`;Q_&oODttC<-NeVmqAm0B za$+1s3lb@NM+g;|k1bQwC)n%6RIvw3`K7N39Dyo)vTW^Z;sY^Y5hJ39a4E+$S$vcQ z%6zyUS5uy7{8a28!&;U@22->ku_5QM(3|BI-K7$q@7{~qTlC486$3Z|RYz=Z2qDZz zhXd-ofptX<{i}M8aBFQ}iWVe%#T&vn=A+|Lm6*6uhn`)oPk!X| zsl@m~13Eh|S6JO7n4$%VnXXhP*0fIpE3$*#?~00J#Zq<>iMozqYTFF)c)lsIX06wNW@-^Zv9KOTpvtS09XZ5&9AB&w zZk>D3{*7~lg)faLT98;i`gf0I&vun~HzJVMW_8Iqr|0yDYs-~UX$#v$#cC<-@=g+v8$PUvKi9S<2*5;=m_f?ZKycaG8e#B#S;5(Sk&a#U6jJ!Ms!w&+e+B(I6Vd%C5uGGLAqM|2(QMNu>|={2y0m z9+y+l{{LH95=BJOUL?sE}vqc-+2L#0n->dDwuEBFp)!S#i#oz%D+ztGc96!|KKGJi}SU zE}X{jfBsOTN{6Rylzg-pFo!;>Tnz8~G?Z{|adh!6CG50<$V8ewW;{t;w@1XggW!Ee zoTAwtDIUd;(p5=g^M@qrvQD2QYgCK)%Q^fF-kHKdU|75soXr)&-Ybdzv+hisC!G?p zf(e{9`|^dAp!KE2@OZ!;5$6`?iO;!IHiv3jZiB#>+agvl!RLI}@Hy0a>r41qwx1)g z3tuhUrzj(tezmKIekX5p`M?DJ&QGOEHcqCK3w6mF-&&5qE*wL)+XBp{v)lWS7RmWs zdEheOuj*ahEc!8T2nlyc=hDE$%*oy`y-M)MnMOy{SiwYkx*vqL`Y+8| z;aPKNe2FG`vfGKfD(u1~%XZE7olA#XynxZpN7Y!tM53KP6uw;gfB87BmqO2W*aqud zcmlidlg7?>&WR)%`uD^%$#{g1XC8`9%rw~{q(zO?1d zyF&S}Y^dJ1fIJ@aNKj44hP;If$hf`tg{vKMK^3g@CVn3Q8kJf^@(bG1fH%glZ_-xS zTbWEEOD!Nqy%ql2CXo{t&0uP3KB#{vt-cd$r_j~M4w3LSfg-+_@SQld)&opUOQBhW zawpy&7C|+JeI(uW$3SABCk!bofhJeO$>{mskaE2c#vKeNJmJw}D*fK=AgMT5EMNr_ z_zqR62ECg?Yk^(WwAX4(U>Ckx_MDFzPxqfJCjlglZ2Q>{yqXn&Pum#M@S+=(+ZDi+ z3DM-qMhfY-i@-rYhULSxK{Rb*yPNFkI*C&-(V)L4Y`s$e`)`b6giBp0by-{x)ha?@}MUifnB&{RjNbbHnj45K6!Py8$D&+ z9L$3A;Lxa4vhR`(EXvFQw&gTw^hy_uN^&4!q|$eOd$}WhI{iK|bu#A&?7|UY`@PQS zMRSf8lKC|jT&yrLEU6v5b=V5MUn~9E;I7W}mu?Xm&Gz}lzlB}+t)x=fbZ$ZunrtOr z>{KZHR%>hWMi4Tx;jrcZzTsQ~b!bL#E;)PElj3(DCi2(+6=J?*LxF`dmSONwho)rR zAxl>G;Rx))F=YEEUNNJy2Idp*vwgT&VZzg*DU^=PfjcHjZSd!PM>?osKG7L$&k@*# z%ZBZA`{^qA{PzYKdVCO#JDVk(blM6dvKA7x<`KdEQWn@WUHCumcBeIO$*M^?B>rR| zmk&(*_No*Xz0QI!$CdhH_?X{hbBnFSHN>AIunX5KY~1HSKDq9kMgCqHN2?F673{*Z zV28;fg0FD!{!zkKoh%5dQ^qWv2QDCOVy=;cbTq{ZCZ4%=5%LOhU|@4)1k&1KKPexc zMK&xN!=-U_L8ed@lLhq}e0nOCuY8z9xnz-xSrJ^UFySHQ2v_H1fmMxCpZ|+LP0F;g z$@KIvj=(M)H#RdGX-CYSY$k49rqSGQe_c$^Z-Mx=i-~)*u5jww7PynRnDF_yo=QpV zkIkfvPNi7E#9`D*P} z^a}HDIQK8x02zaOvt-`FNHx0Ltob+k*bSq9tiB(uoPB=bcq#R?|Yf8AJdZT}V+d`2PCH!l?(jcdvMQ4=@*v04k*XUenT)`GH zZ)g;)o|CTb;hhCPhAtxCW-L(e@0A7G3l@>C)l1YwV=Ig?R-TWHHXEhIzqgREYvUmixno$zS^YTKQ#-^yj9ZZA(cvD8Cm3a(pZkbE?lzgPW)ypZ+?_Zx-WO4x2HA~ z_kPZWG@p5-cf-b_d(RwbIdvYf>Y*X-ZkPj~pDDG$&cRLP+CjHTM!YjeU>A-En*})A zR5m`bm2{uv!{rMW(DA9+b7yVT?mY0e;yz%Ja&V0*XK3vy8RB9c&K zK#OHF@!6`aQ1>K>oNR3-rZ3tG4-At@^m!A}gY9kjtu%?HQSaMVPTXBciegPDRxt5( zp}weok^`2(%9#F`V;$JGxcA7sO%@!1T{wm+)$3WEWvh+(r0jfGE>@T*4A&DA#T@9T ztF&Y$PPUT2e9j{~3VLz`cHy#NYjF~W%Ia_1NZrR*T>ngJ-(9ran+pML68@*J7PE7( z?09<{Y0&38r(igP$kJ4Swz-Yd1~iVucAq>L!kD#d?sH${6yl z{bl#n+B6L z9zNpp)kVez5HJjt* z>1QsOz^nGOU z+74f0f(ec~8^sx=D;v!jLJMMkz?q@0;*{J{Xj>3Lx=nBu-yJB08+{@O{w1~}=>lE3 z;>!@KZ*qf60~4;+{Y0O++rh^xl*Q`7vet5as6Tx=cRfd77rsKaj%=2${CZp?q#s?v{D|rpetJ(3Z##GKM0t>t`^>|;yPLej`0ey@l#Xz_?yAB+uO0E zINU{)XO}>CIfmRZb{5xOEdleLF(lf-MSRV6g8p+%c|LYe)|MBT`qR}Op`23B-cj%S zZiDpl3EVHS`N4!{vUtRw>Q(u03MOnPQ1Q26DZCswmZjk}N>4uDbr2ocvl~ZX7hfKq z-s;Hho3Rm)tGZlCVS?0CvA1U_449&f;b`{6AD~3L)>bg-es&SNHx% zS>65Uimf|H*N2_OamS0G|CbqL)qY#izNQFF5?tTgsq8@)st8svv9XbnxRLFFExIVR^B&9RQhk$wbbrECj=-+d8tui;X@zi8 zS0T<0KQ2w`(4U6i{l$$m+cat{t`94K?`-6TA9bGlxk}Ps)Ssq=ec=>Lv$T@7G7IO{)VKg!8#AFuvJ=oKI|I0OAniS(ftS7Q>aK-q zgWfDp1xn609SM?lg?Z6+vkf@{yKoFuDvee)Qi7Qmty^czT@_BRzmbL7>{2cq%29g4 zZ31?g{o!LEdPLZY`P zJ#A=3v4RP!>=NfQj9y}?5H-WpF7|PrwEmqX#foFotfLLGbK!u&|E3X@xI}%F5tWZD zxim0wX~~9)tNFQbPD@E+PfRcIeO*8Lvcj4punR|l&9OYq6~jY4>8J}96f2mhU;DG- zVnr@wo>yYEu2K?jEc2w}^>_li_~*#E>egs%K}OE zbT4{DGNgD;uta~Bu%TlfXjK32{NNv%63YQzbj`N*EcgF^<`5I#hJ*-{8nBZDY?L%A zl6w$wwHuuuZO#$cg|Cq9>iDE33BBh@w+5L~tYD(jXpj*5Js0}ADrtl)Y)Hyac~WgF zGmgM6KIisVv&q~lZ`#kR8NEL2mQWOw4^v*TGkKgZ3Hv(bLtyv}Y){#)&&XDdfz*CO4Y~2x2*|ENm^XGdaX4xSscc`yA)As&RlPB6 z4J?F(E0j6mR$7n9=DGoNr|(Tp!Gyt+*6`P+5Q@JmUmPy;en?_Wy{SXxbB@3+E+VRn zvoDhapZZhh)o;1zVnXYW7St^+fbhmjdDyo;NBT|ePh(zv;t1@*CCg^8Zm8&lrG7MQ zLjlpR=mtN$ia~4XbTUEg3I^SZLAzlbd3K~b#J($nhxy9PsQO|(aqr_ttxU=|1ry&g zt)Xgm5$u_rz=-}y^`t<%KmFz}aRhep(H%7L9f^BAklu?q#l;E}OIlmPZ>u7B)lr#) zOq=$K+)N!vOY1Ih1a{$)W#ghRno`@U!F0*Q@#OOpXZWtU4Z1&#CSJe#Lh$AiIQDrW zSz;@|vK=MR;EU4p@;a(T$(F%X-Zq0%Fi~>84}2R`0z+byzJc`-ZK|mrNKXt)=LqcL zqkBJ6lg@D(L3iry^Nqv864=!A=1IRd-*=>FKyj24{mr^!dWxL9GL-Wj0F!fkLN zY&=Wj>KSeNjP>Xr-5kad*o8}0rMkRSmp*e0q}IPiKnd*!sdd|7&Wd32%*z!l-O6C$ z#$a;kpDUzlZHK6;(JT$01+A&M;7^6>e2%~_K2}pxbgAz1A+$Q`4qycn%dWb@^^c|C z?4(3j-&L0$`!%&RhF)yoO3jU3;flXI6xVKpvA4oW;3YTc=Di)B zCk2zizWu=d)pq!`Tp4G0de}yuH-b`0yNnz03hnGJ1{G{$d$#@W2+Nuy)^eYp4F!8`lQ#3Kjhs74k{KvUlPb9k* z0&Q%f$r0Fv`*3U*bDzsnyXu~_@%=VjUkwv_v(Kq5>T}`!bETEh*ZF{C;OtDjlG<_v zcHw>-8c_SKeNsu;hi z2kltcmut6UqQlB^=k{!VCoEb?W2b46`q?T+x@nXHM_?CjU$d{B{?3NQEDfu&zFcnt z6Dg}Z3%@RG1=kx&TlBoo8CWYjQop1g9D!Z9RjX1R80ta>ceJOQsvNl1D<&Sn7QrGi zm#rjM%Hwj+V6r5kFMagSh9j_xZ&^lVWs;sw4z#FSC$61{iNd*eh2Dem;FFzlUrh)t zATM`2(Q($s9D!YY8*W6vCDQp^Pnzx0mTQq=!jG+NUOYb^{yHix8IK9Iq&mWd`iJsu zIPBtEORg<`k@X9D(*Q>eu4RddsNSYV)rW~k?d+l4qX@E3D6J*WsOD6TptRpbnQNC|7vBQdnrKXe9i3_G{ad;E z920IO0Ck!ruuW5W?=DC0KSnXVEPQ!G(=;~eDxLOSpd>yrYj3GVh>PNfx7|9XXg==lr_UYkI z``p*3;`x2ts>xus8nX{ujj6*{W8yW1D%Fne{?zki}Ctw8=LmBP-e>5ADN%NxV zaTfIIho2mQUBj=r0eEbO4XoZ}-^z$CvRjoMZ8eOYlZa-Q@QewrMOi-Hxy!v@m{P4? z-3V4N!OyEb9N;KtG_$2ize6|zyKpVa`cbQ#&xV8TbgvM z1;q*``1$k7tcG&-2uoV^xfMrX7p_HF3pw|bH1Ul-^?=S4E12L{Cj=b7D(T0X)2s-d zz%E>ivh$PX63P_s0)9}S>b!318t#a81kdj&Q3O=vb76~+X1;aZgK6tXacZ0*sC z&b&K-Vg(a;#UA_q{B1I+++s?NM8Xl+g=|4|!nG*tbDsK0#7FwH&$`YOE12Nda@tP&PNwErP;)mUj=(Nli?TI$>8mnv19dM_7ppLus3UgpYI}FKi5Glw%Q5%SN9;^dpd}k?RLV+$R1?SrOu*` z-3}OZuO}nA-03P0kL^P<{`8cvOK+r^*yiDOSbWahOXK02KzYxZ#%L1RmC1Unh%?tci|6i4}LTsOKT&_JqovlCOg zl|xf67w$?XA8`0jo=S(ivNV1^?<_ZY=0ZoGZp{%E^SX$mdX&Q*cV~`f-!v?UlfC?W+>2yxK1E#1>98>T@TKz%Cqh)`r{XCAX+GrBSBOMV%eJ zMB6oGVAI!?92yH^53@2j+0U1Zx!hO0>$4Natx(RXURr7)|GViyXAHd{>RI*@*EB1K z(U(0*yt=1oXj~3Y1y91~{424PJGAkju}1eqtY9L(OAqm3hjMt3q{Ir2S;^a6-RQaT zzj*?=aMam}o~c%Hlv#0n;K2D*sJk9NRG3x9T1v#V|7I~UkA z=lo=jz%IT73s%I-Rx_rMV4;K5t(u7Ax0OPTr7zK1L`CB!>^$;jz9hZSRh(8|0!LE( zSQ^gbN69NMs_4`Cn?#&Le1#wCJVoPmB@p*lITyhFPmJs}^aMFF;em)1Oc)Px7Yl+* zVDD?CJoaSGkTqYfAdi+^;t1^e_R34lN-BoEFO)P?<7dmOJ)A-R%3w)*Xm4@g^%7X- zKuJ)$K4QfC5(qYSC9ALZ7BAf>1<6XeuR0pfmJgb&ftFYNB&=X!eQ94Y%5598vUF#J z-=qXto$p5seVjQ0yKoFyOTTEQ++>CesTtdoi!LS(_NL<1rrUrNC?~iqyAm%8S>s8B zx)VoW7cLt%S5!M&ZrbE^MafoQF6TH;pG|s*#a&C_ysi^VqsAji&YxE1GUKtkgcVGj z9%d(ob!KadZYb}PBIjB1&8ZEgGk07$0=vT5INW865}1|Smk|lRGvpuEY0_T5_R_Ui z)?(<|Liq5iD;e6pi@4!z5qzn4Aed&~4+bU3!4)H=8;N!jRxr`zK^HMeqZlIJDpyr* znka9ovy&ReJ8}ee@mFothsMbne>O__`f4s8m>6}yN}Lo^ z2$G4CM#mK~a!BD>DcE=;M_?DOwN}e&o7`6?D-B!|g z(z=K2sN0vme0M>_Z!%o_;JS;gV(m)hpa<6Ufk_hyE11AF5gV;N8!DGpe;{EWx^M(` z;VWeOGyEGaNB+~Kn`*jBSiuBteXuc^W0A7fh#TZ~n?4+YU3|{tEkoqZBYqO0++M;8 zM{was|BTke`OKiT1_zuUiV2S`H-%=ROirE!U`tvv&m|l14(j2-7)a& zqdiAp7mf&wWuiImZNk6R{O^np5O#n*wtFxxf+Fg-e#Lt$i{{wja8a zbiL4xD?v=~Z|Y^|BjiK7pONmnT5|+;;rfbwi(D~LZhhhixi!9(gcVHiHD^m`mIiTEV86eguul2yG;#qHfoVck4St!C1lyCh&8kQoYzUUUpx8mTYX$kt48+zp5v@ zM$0PeSLE^aZW2~7!S@Y(j|R&-y8R`&Z|r#jJ*j+j?~Y59PmJ~@<32RwuFCVTg}5WI z2s$0NB)BGGV;RenAK9pLT%{5#+k`oC^MebaZ^d5`{}y)P z`iixX*UXi5cD_*G{&88v3MOtvSc+PC1<>J{lE$^rWVy<;rPMOEf+MgC*H>(g#bUNB zmHA1H(^rXD!9@Nk3-Q&}e6ahiq;bqOQ4V=HS#r6zi6gKJ*KjJ8sq0Mni|#z>)Qp)T zRxshT$3pylC?9nGDrqE_Pm>2V+ac++9?ucj#n+rh&ST}Y11}^^b%7cynAp(OTufst zwvP0&VrlgD50Y=))slDin!pj*h5ONLr0DbxDXK|<6k0Wg7FXR=N53|xh&HH%yfZ3s z$lV3b>u(=}7mh8(J#HP(ut4ZNS^;0V7P;Po-C%Yf8OemykW4 zJwWU1R4{5?0|jPw5FI-Pk_TRclUluDQ|eF%9aF`K!Ar-}LzcJ6&!u~Xte^9tQ@AXw z&hv(Oj`1+{RwF3%a);M;v9Kt#IrQlg#R&Jc33TB$18M!Sab$f&PxyHu0m83eg1PM5 zfF`>Vp>%0A;IvumRr@H!tr;b|mj5F`V~@DJkDmfN9a@rg6$f1WVy3{M9xVyUJmj+K zXf(8P&}DbY%ANh>eIfetD%e3ks5V-ayouoPEsUk+ciROFCTCo$Y-G3=@S0JkO>i=Dr-ohrY4V)=MK z9ppP2cGS4zC-tHA?qa(gUJza0ALdoNi%$1EA+5>@GU7tTYC9Vs4GANRuTGU0jN2=% zD{BC^^cRWRHW})GAts=HGgq9QRikb;!UV<{%n>Kaz*td7{kGF@- zG(kMtS0!4FG=UY5CW-kzy5j6m6EN5qEv~R`EvD^Ih@^`Sa>?mF@~oNt;pEytar;RJ z(K^ZmJX$)54Q&0y?^8`6c403uD$-vJI_a$BgXqakLWaoOi$+1SV>aT-E2G4-@g|UE z&`xYWEJ_@mWCCY`^u@L?K}-i1MjXv5l{z(xmH*yNgj@SwsW*;F7X6l(z_klG>c`8{ z#M1R9(B?#@+ICo)cvB@XVu6;O6n#5MCVHumF?O;#^2=heI*So^Ox4etEETU7n800A zL-oTcOT>Dj5L0Y!kl&Za%ig17;qm!8VPVt{Lz8V9O5p&Q~R?swQWK7!YHxsoe9*pcLC#$exm%v1R|39KyH}7c*|2EPVSgM zzg?=8e*I|%fj)^~=b#eTYMa9AS*g$_qefk(V+tRevE7Kb-cyGjQKI`|9y_zRex5W~ z_qmW@xEM~h%TSMNWeWZ=i(ygOBK21GcX8Sxc+x*ZUHPLgBld+4q)xMp=!n%@DuP2t z!z>3Ic#uy(t5Z1S>085FO;gZmG!lF^b%UA)ri@S-1k=kqn$V5Enz-PnXyKHJpb^s+ z&NMNF`9sITN*{9wZln-nx=p2?DF;cjb%$Ka8ZLmZ!IeT~OH;UWJr!O~xGwm%V0oIq z02Vb-3$~qlGGbXx4E4Kzo=n+wzy&LqxY#uTv@9D!?VTQsh)Is3QuTe3IWyN8E0}1| zc{beB{3%p5SFWnX=`l2Dbsag~Dw`v)Yekm?$X=uglbb0-(99&-a|I<){@n$2%u-lt z=pj7QH-*V}mq6Wuk-~EJw_by#@cHU6p@n5{Myz0aA=w`sL0$~+E?@-{Aqk6NPQp@Q zM{6Yw(@`_&@3IA?)rokHz%CpSl`5w&j-E2hChF9~T&ythD0u-`j8F@DdP*8Qc1@$E zuD|8tw z|J>JQkkp5z(e7yqt;snpod1y~U{^)?GC0-B#Ko@d{}SX_3ibWciS2HgCg9(~gk{Py zxch3fOKV26ouIGIr8#;c9I2}22<*a9XXgUEoI?XUXpkQ_`SQTTvQgz}Zf#7E z|D8yJeH-G14WAc_&#Fvd;j?_TebJ+yKc4rCJfoWp1zRKID{n}FUN-I`=Ta?Tx zn80r(c2!&ZgMnR&?5Q^&?u<@yT6A%#csx{qd0iJct#e-{hU_%~d)-b#2z%Q-J!Znv zu)Cik@2`I+3?Ds8SQ42o8l?1fvHZ~+3_GNYjc13sOd4zgJuB12){`b4{5?n^+HXmb zyZsIn6J2rytP~fdvn^QqR_HO}V)|0?Bxu# zBO>2z)rD@BdW&azxQqX+eW2QMIQTsoDc+LpASfdgMm={EBT0X#4H(UcA`Nf((qnUa zZQ5-$Rxq)1-*EAmeoyeJNMb}#x~m)>WJ9|hfLiKaLdM3%(os2 zzE?8CkP92vIOl16Y6&+puA+vBXyQ(o317yd0##DcsmWY1~yKtV^ zc!}N=`NYl&a^veup~YD@QSIsrQ-*8k47CD2Olqje<0@LY79inpk<> z>SD5Rb9c^#>0^zY#ZylrA@JlbMm&?_<+9F;$n0n504ta{%VskgbQuA<&IcLM`#_>B z*N!D2i`m|6=(n(Il9QA8_|-Ug-hCe>$7qI} zSYj#lY_@=41rrl5+l!v|Ghxw%ON^+}A1xmnc1)VLD32T-Y$H18E`qWVb+E3lo!G8m z9!#lu2+-V0>=Y3T<%LfeVL5)R+-=u(>9R%^!3rku)v|BmF1pBzcUs8D5>iQBov|38 zvk|C9OA^GsmNY)O1|D{4N_sqOE&7aD0ne^9W$kuVpdeQ@Hj@qA(>VnbC;OO*)hVlC ziFFf3*e&fRdwlL7yLEUARi^sl#K#*!+uw++j5iSvzRQBUZ`%_GGZWEjViu%Uw`0W6 zE>3b;rkz|+Wk@iAT}#APqCtzbuy$H2M$B(ZWK%f)z}BZEPYsS8ak{_4mHXXTJYtjyi$CZwLc1bBE-GpzZ(La;Z0T$+S{=xR@Sau#_k`ot zn~BkEh3U#?7L2$nTFaGwu5$E@JFw??3vt1|4R9yll*?1ESq(+~+|^Lj&X^G{)h6;< zJ#V?RQ$1h>M`8SGP4S}RYFPfvh!Nfv4)U0#edNOM-CP>$-nJGm8gGLBm1bOe?6d+6 zM|sFodpUa#+ldgB2PP6vwh^y&-3$}^nX@z+4+VL3fvr64w9FCMg-cVVn)#ls3VUEB zH(s^`u!4yrzm3GS)7fD9PKnhlGElC0)?QXMi{}XJ;-gzXVUWDV*+A~;@l(JGCJHpo z#V?t;klINZ%lNw~Kps=uN?!4}mLsqWmn_>O<)V??F40Gx)kKrvxZ}9pUfqDrrLKZC z)0OfVUe{69y+!0REzAg3FoEw-m8vA&KrZ>yU)~gD!x7juceG0Mdzt}5oRu`Dk8LYk zRQSkgpL_{cFwyv7y}B-M8MynkW`sv#19@?~5we}L4@Y3vQom81CQt5b+vaX5@4 zu#1n?p)`=*oC=j!t*9ffuJlkh+CB-MKhh!VNH?|J#W)CRr$;85`KUj|B6Ztx50Fo$7`sXTpS?%^6V}mn@AH zM#`Tw-*Rc--{pzMQx{0byNAl|$M12!g^84T;cDa0Ga>qha#f>$WJucm!sPss)f|Cc z+|{ab45w72c#V?3Ox2(!bYuc__R%GI?`!+EUNQ+>AG9EvU!Na&v3wF-XMeN% zs$5rG)+$6!vu?-{*tP%c?uu_mqCuydGPdOCKS#`%IZ6(&Za}fi@k@5a$>vjln6xB3 zvF)cMx)hI+cXa>9DVR8S^<0HLnF=HPTe395jWi|U&PZ8*pNit&!Y*90tetqIt#sn- zDEaG$?_7Cc;@h*f>Q@h9p~Z0}jW5HxNpplyd0q4;j=(N_$FMc@(`SO`pb+_1CrygS z+weFXjyjuh2OU_koyBT)11`FlXwiC^v-ZYG(Dt!X9^sQVxSaMGC2yI?mmqfG(qyYY zP3+08!J)EE{zqcx(o1kGn*{e?>5zpP_QHe1aqz%ck1RQ3Eo?hA9ol_Raz59#Es;Dz z6noX z@K`2W-|oWNx*fvh&0P+W#NoSyga!*>*&Th-@lKggxO6^@%hxAM$LeB9fmA z=1rGDaJ3I~5sH%4|WW9OqF1rxj0UJ-`O zS_~cQ+p?=l+}(^$eGnk8ylPJZzG#9bT@9J_M&$fw6-0Lx5!l7&BcQ^C-fPxXe%F0HUNpT zpR)-D&D8&&=nj2H=@GdjJ7KIjr(nYTjR}O8Wr10YQiAih_M_8lI>YbGcc}N1Mj_?l18WW!83RTguPLEML`c;=#du| za+|6-oPr6vb!_gSOD4S3R-W2p;l1gKbX)m%+!T($E*ufI+Hj)_Jv_@=Uf|%z#R?Pe zQ%vA+L?-NwRMP11&xN*HX)TX!=fx4&h2zG)P|zMqTdk>+F8wJY4$C^j!Sf5@Z}D5$ z-_8bXhAf8K#veg*jtPwTodT|QpIM)?=f%Oa=JR*SvttRt3MPIpw1zW(mcYbIUm3As zlPAq<*i;^|YZpgg*91pHxLCIcOgAcXMXQs&=;DCpvd-3Af)z|`Ut|USv{t~)Gb%=m zyyQ%0|1py9-N@kx?BYw%vkRq<*R_*>YOLkT0~26p0eyO}g11qPSQ?o(1!|dLA`9(T zas+nayN8V@j-E-sg=kBuk>T7-9G-nUxv(dgrY3+vgfa$@FV3WYA`-|U>rJrWh6{`g zi-eLzyP)$`7s#0u2`6%QLD5KnW<5qg_#9<~<>QJ(+Pgf8%+g_BStA7#mY1C&^~^YE zJyRKBX%(MDe>QDLF6zGI2<*y!+y^GUW8)=3%6Q4&k{B8^`T}{FzFTX^% z+gqu>2fXw21;@;7aJ0KCoIf`Lz7N~X2)+36w8HcjAz8yX1rtvq2EzWWZm{uyLNw_X zPOBZile0!2kK*6Lt}>B*0d6)NehlBhh_e?$=wU}q8j)+H#tJ6%virf6IYZ%H^Hq%4 zt22_q??%)$)3;Bjyil%BE!8@n(@TwF=$!j-o4 zu&cND{xGdoBqRRy@usH5=Cu9Yi)u_@mvd|o^laY~#tlnmgn5-K?b^&W^}wKbk3O}PEiFj!q4G0F={wUzPDi&@jcuUf;vTt zhC_om7eB-MHTnb;olKVJ%xpmLT*~pEX2K{ob6hi0;O1V~X=w-d!=&#C@(iuH1kcJ~ zqR(7Ip~@{y{BcdWDzdT*l#GazZ!XW~2<);tJk6;`>O#@ul|tw~%Ljv><7HuQEx`&V z22(x3+cru3;v3J1s0D`bV8|FbFYO&iU{}!LD5v}5SWk0`LYzIj3iOf!<=Oc<6f2nU z2W{cn*=W(!N_ozUlN!UBuYU5kO9mW)T@x}wof6Ma6fZd`#PeWwUS$rI`?K$zv4V-l ziJHROh+$&FkTs0xd!tUsYwskR@9M!3*rhXYnA6?vBg6xf6~emZIG8-Ii##h0C{{3G zaQ~-^%~>MeanE9e!KzweeSAmR$iR+pHoVVs~9;(A%ds)KvaglTx#S`v4RN~ z^G7ZnX6uM&UhH7RN{t6_^y^!xwoe2dzQtSkvZPG?{m2o(E;2Dpxai(g?3=6*&To%H zhHg`N)t%uKE11CPv5~uTD$?RuEBU6^V2;49`-c*QZx@}!){nNZG#oS^K_}e~^6*qQ ziWN-YxUreI;8w(Ea%XwfSb-z3Yv`_dLg16ZV%3k;ERAEfzrkU;qikB$oni$OxcpVB z8+WY8p7tQm-P(yGu zjJR3yh|Is-yfY^7n@^=0wr?b9v1yik?`RT7U>BbAW-A(dT_AxM`pJQF8dCgr#&7N6 z(;9(#@c=RO=t7qBOVO_gIowOuIjK#tf(gl~0|=Uq;^seTjJQ_$n#^N;gFP*bI0Cy8 zWD{^bY%QLy&R|4HxCX8GXvp?SF{N0+#L(+bp!>FkXm)KSBO1PFKp&ellbbtq;Rx)? zN^*e4`t|D637L%8aaV`>xB4Zm&ak6c!G!mSf#5Xwth$5EMn=S4)S|j>H>E|BT{r@} z{BJk`xj9Gu-m!!c-ebe)naq09<@6?Jyt)Oi-ofi<*dEx^!|2kedQ#%p#04vu!0Uim z39{DfiKDkkaQCYmfnEF>7VrI&=**f*a-scV0V|lmtM}LpuS+~VF?tPgth&Gv*u}5? z2-}!Q``w#H%=0^Qt8_3C$VOT!wL^rH;|H=>2}9V~fbW|Ttvuie?7}NmSS!42HeL19 zPuf`hT)=Ct66d4?jksP>%~lBU>#r;llBuqdrL-r^hf^?7l$H*^jK5UuQz z)K+%Vv~4m+V3*sVrI7aEL&fP2?1V|xg0^#MM8Im%#^pR<1rt{D(&64cPZyFhh!KN# z&!H|4E~z80H71zAu0tA2p=D;O%a{ja8R5@jwNADEuc3MS@TE`|^NqlMDca7J|U zO``oxG{_gV9>D~5{T#dyCS92;+;vpmq60i;((pACiT|?CfE7&GO-==0a#^^zb21}b zo21aVX*)MzC~U>A-8 ztJUVtrOnB9$ZWL|u!0GEkFhT;P9@V$ryG%$yKofPS1D16bXVPEGI!EazzQbt zozGescV^Ht&Z|hppDi4LU3_#amQA9MnpKkV>cM~&Oz>-K-JHhLb|-I=VYaI{0=u%k zV&GCj8|cz%0V~0&m!{GeL3^dlQO&t^k9c(>URlM~ur!Wit5LG0CuBCaIuaB7GZ<|d zOV_{6mAouIaRhc5+)0CWM^>sUZw_Hs^=8aWYTPeUnqt$4U1-x*=+jw=LQ)1O(0mo1b))k8sX$b`YA<43QUG@1a@_LHXo$-%Y{v@ z|0%(H@ib0rBALF+f?x#``0iottADZdQ?Crt=xG;@z^*lCXTttB&xPwdmA*l^*+klJ z%rUa2Sv_C{6a0O(P%oOsyUN78aUX&S&Q%!;*N1%()(lr#082iOr3oolN$k~LM1>Sg zq|XV5vxm)~;+WEU?R;Y#y=r-w+%}!h5!e-QGzP9%H-KI%lrfq4kH^x|aGBH`NG4dp z#L^vspnKRB1}1G~MD6ZJ zwEW{Po_Ze3(io@Gpq*=a$yIaya0GVYb`aa6@kI-|skycMDnyfF1ru$nTw%*$Q_;JF z(jwclss)`j%1}NZ)S4r(3%7&Vmy_L%>8qDo@}O;PC{{4hvfWTv`SzuH-~JUWjqz{W z)12eqB+EXQ9D!Z9<;2GN%B*R2!|T#2drOKHOgzpHhex%`)d73gvox~f+fgy+m^A!u zFOI-2zD2f4I!bc8?~wGp!l>x`PUyG%f?#x_7UJSB3)(9W3S(|wgN9u+VDNx6=d)VJ zSsLdwiwSwMO)~j0hGGR1+m_xD+NcdGh7)B3(%U1KJULe)ZSOgjBe1K<;jhB=G2_&4 z^pr0~_NJ{Qz5Vt}36*0hRxsiF;gpd2ZkbxU^I=B330Y2-B%hOFqQf}?yN=ztE1Zjc zr+)HwJ0pS*#gjor_ocD+VH7Kv=-0Pc==!aJc<6E&Bl2?NiS54z^6M)@IRd->wLUDY zbF>$I+?8Icb&V&nkq=AV*GAK}?{*6wt@0~uJWoJr&_bc*md6!G+Mk4By6c6G`*PIH zbdNA1(ASns-*8-dW))3MTec8v!sZKJMK?KOnf407d*XT_D&qzt#taxjHZD0NXUw#HwAj;;;(KY(jS)~g zC0PAdHwXCp%1*Zx)%m+s(wyo>v4V-tR)fIJzO}k^Z4pZ&v%41k*JP~}_jVvhVAuFS zC$N2);nZjAUPf4L*P}BdCQEOA^`}_DL_(PlbTGQ<@+xOHBYd~%(T<1wqy`;*IRd-- zruBlz@C4ztrJ517>8A9VNe9X1qzA8hY79T0PN~Bd}|K zTNBuHvn5=KyTXW}GrQAit%9_kJFy~+{vP{{{JnJ>Fo9ioq?pZMnS{}`BYu#i zI}ZRWn85WFYb^~5qQ#+FwDAg0j=(NFe$7@>xsRe>v@~eTc{YF*OyKq$yW5u!qZVCt z=sB%i7ffIm9#3XH$h9G~RhA}Q_hY*YRxpA4hHN+XJ%RLWtS)V*)tMX9$1Xgc%=YrW zHH^ZM=5)!TS=^T|nBc!-nV2((9=9@}`(AA32<*b&&8So@E&XU>ht~3-@14nP%c1b~ zW=}Elnlp4U*WDEReAPxMa&4Zy^tSXLOUBZY#52w-wcT2>+H+B-NVB)xO z8r&=W;4)-{GS;_r_hcH}?Sp!GhR6}v<+nc-hL@NKS6V2oKA%a`XyoP%u;P3f!3rke zL<-QkS;D9T%NTJqJ%+kQZ(;4TvmAk4>4Rs%AA4^>)KW%qQX9t5%zq6?hUF=O6-=~E zPlWR+JB7r>YZ>9!E1dRo%mtl$pE&}%-q%fq&QIe6bzlx77IzA#x3)AO1!eCDRxlA~ zIt|XvmxXz!l^MkgKZEJ%Sx@1*ohHQucIEU5h3n^@36H)iV@sJuqv`HcLP8y%6RcpO z>eWbad(Z-se-tpn|9b>Y_yXi(+j|^=T^pMC!t(a!@cpn-f5bJ4rp=0C$juGA305%C zcuao?ppI~cJF<8L_{{_$MJpr`7ubw=OmU9Gl;U}1VA7wY1wrc!C>il*+_cp);->-eX zB7)9(_FU@4)CsMLQ?2Z9w$;NB}+fn7S0hP)|~*7=U+2<*a7 zFk88tH=R1%pD5)$jUZUT1n#}E^*+JV>5E-1lIOO?9D!Z<31)j{)+Epq>Qb?-_B?_W zOyJ%t`$Bq1Jnin&K%75yHAi3` zI0C!y6U^3S)W*`kYof{F#8`qAOyIsKTZc@i&`va({6DVVJT9l_|Np-VNm(jsL1bS_ zRF=}2IfRlV36&z13Rx-?Eo3SCzGMs8_cd$RnXzY&>}1Q!zVAD~xjx@Nevf(o=jQRa zUvqV?Gv~}aXXg3bnYTb9(1kr%>~+4GtTtJjLl1?v zmI!p=E)tPD`c1N0WW9o>Z7h&>iy(n}LPVsf^BA?N|6Ce(GEE}Tg?n3cy836`)c42Q z@_?iu=`=Au?c|fiiLst)@5?T{Y}-lc%rO%9VxqtIhu&i=?O^fg>E9uHaB7b=U+e9{o61BGBb2X4{*um}@2GBSjn0 ziv!gs-T$z-YHKJeNZ<%ZoWf2FRENHM!Va*b5`nJ66GxKpi%0c2l?{0f_7#PxS-+03 zP4kaYRFJ?CjyUtPJ5+5`kk9^Q-IWM*8QYH|*Cut+XIz*e+K5SwQkxx)V^93AQ&f<^ z5spr0H$75qHqn)R_Ix1`=xRD4gY*n_^$b2`h(hda75fk~CY# z>M9cGI`MG`>1KY_D@@H7ZH#EqOa0!pqyAc5D-{(aaJ(XVl((N+Tb-t#-MEfKpzHqc ze&q9mEsE(tL!9Bl+937&)RAOubCF396eMtjqtjLB9<0vJo=fTvttJuZnm@;%+#OSq zwCz|R+L%|`UrqY^li05QMo~cmM>rxk)%s{Ps^lE0zv8(>pvx?blEwX8$yRSov~lsq zP&LH78C{!pn4*FNKKVox=i~_Wrnv*{-(ZtOpv(S>co}^cXJ3C9X4@?{k5UikcBS{V zB#H_W@-y+&`Bb&K<4a=xeUL<;OWW9%basd#&z77NZB!R0??aq6ku!&#DJn?Fd+wIH zXQ)quS`_v@+)^UY_2z185`1J7dE4lmXk)^(w=}CN!}m*=)$@u;A}!x^Q$DA6y(maqkeiFb*qv?OAiR z(rABvYS&b07ZMU(a$Awx`tDj_PKanDv2#_`t40U@FW{g=pbO)$I-PlC2h}RF6+gG` z6h#GzK0SO%LfhtA@A-+M4Uw@!?Y*l3uNU=NBG83#Sh3@Ga&vXSJ1aip$tQ{m5)WMa zk-^MJ8`r|HZg6->Gqvu83jDvQN-7fQ!Z@s0KVRNP-CglHTi(h{MFojAIfF^ZR$KI| zV+{KfA3t$d?eQr_>~_5d5`iv^$%*yBl6LB}b2;qF+lDGCNDLS=nA|eiQ~1xtu&3zGpGGP%p2ZfH zwUG#PVN6cMcb7I*7etI?uWPqcQ99dq1ZAga<7V%ss^gV%thf@D2y|ggPNy6Gpp7~) zZKK9MyQ!!kv2}_s`5IlS1Oyo(+i%x;s=aitwR}-y9SL;Fu|C(_{W>~Pyq)g`(DS^D>h5;5f}!TA38Mm5OIzw5o0t>uFF z^QnmTOv__u9S5kWAc3)d5ij|Dj9%ZloOOE_DG}(Jwat?FxHr;oIKN-CF~w>ZJ=uFR zo83Q3MFk0r^@}}so;&ILFpX{P)n6je)uB!$QXF?h-=%bmXv3^=9?iU8!W=e+tEeD> zv3`-czH|+(cIg|tYaJvJ=z3h?vodXGLv6trLuBGi@myN7tr>4p-(N)q33(Nuhxc4+ z`=A!@VnQVXUE`dODd)%eXbD3Mqb2L3wY0&hcUYrd@v57(nZA3(B&BfaEpo3zUC&iR z$11apZ<9I2Hl8&X-B1?l{u6|<(vmz&xx?;<#;d3xf$Irk1Wrn=ayUNT92; zpH6AA?yfR-?_<$Mn_L@OQtKw`PGVJ5kiZoPoo?6yN~aAdW5ZVuln8V=kIhixtY0Zn zr^`ee%^IiDRu)%S{(vYI6(r=fi4}w9)ANOQnAy>Ai9pwX`wlC=^v0yBzajJ2ot-b} zM5_a=?S-CF|9Eigozin)4N}_Wfz($-?l$ME^k1{{?856HX_X8Kxs4Iqk5G2(1RE3{ zCK2eu6*IB7cHep$f&~6eVl~`qIqlzgKYPDFS|ZSeD`q0zel&;v7rcjE zoD`>`f&{JtiGKbji@ut@hh=n+mk4y>ikZmIU>8YK+iQ%{coh{S(68NkXSp>_MQ$IbP%f4L;ln8VsJ2objvg#^($}`bM+pIVAnfV;%6dj_X zf&@NYMZCoB8BMaB&h#(CBm!M0wZ`=Atls3YAK`ZB2-k6z^AKN`RPzX zYk%IxoQ%UH0$u-d>XR71?Rvlb&7zGV<&M!)O;50~HA7WYkie&_*c&zG46WkxjJdZD zkO*`ITG^7t_o{0*vJ7)In;M5{?+WF3`ea`f6(sQKDk7pvI_o41iIuAz-+f(>Y8_TL zYV+Gwc(oL&y>{Ko`!V z#ZJKB0CiKReQcZdjiQ1C#!Gd&^<(_iig%W>7@vwN66nHtv{=W{^-*U|3}c=x%c-a! zf$>tYk8F*;E$0}s#mr42(1r78o$jTWm)9IJOv`@U zTtx*5jF;+krdF!j#-XORxTZ{?3+K@yQ^-$$^~TH;t&qn<^o_c!`!0q?$2{48|gSVHV>b4^fJ z{>=`N%=#tNE z2OQzl%sGauJEv33S>b(MJDyKdIT@P@eQ5h+-xU%mE_jDt!JT#?-Bo8mJX-dvgc3mjpAA*cnwIpLWbAmThZGSusT3j|C2@sjDyl)>|hj zNMP<1v0_rWi8}uc;T=om%qHlPGgG8Q*r}_B`SLQ$Zc?5JB;?=x*S`Adg)i;-xVBjm zfi5{egVASOwfRYvKUuv*%C>+6{<0#|?W`v1=L8oXUA##m(1qC~bh>g^9o4}HT=;*! zT*?}O1pcz(t(NPq1_s)5-KkR&fiBF7A$IAVY^nOyuE7Tt-IuaoAR+(e{Z2dcsdaML zRZ+3I+@)IDm}?f~r`Kh&b$%6X$YE!aHl~#Dvkf)V?)6Aes9`VXjGOIwpWT_PL#+lX zDoE69&`3)^tC0D#46%&ptA5<;yE~ix+D0PKRkgrLOKs~$p1B$#!oyzo;??%OWoy2y zmvXjarb;<~`^Ia*JTv|QYy72vqJjiwtrRClestzuXTPwrgEu7tT{dmZwNTID#Ob)9 zf5dJL;!#bPvMm9>q%51?jp}L#n)(u}IwHzh*IN6b3nweSJrzW4`*wUzm(y(5dutUH zBu1tgXErHvhB=LL=acu^ zsi+{a?bHnYbCIi~>r_Mjk|WzY@lh8n_>QbqQl5Uy#xLjWuT< z{&{7XiV6}KBNzLY^1SKKA*OtfZLmb3>v!82WzXqa9ladPxdsWw~7i9 z7=af1OPp3w%U$L8qVwG)0$o||o0Qj9jfs)XThT_Nv1jRm8?V`%Xnz$IBrpyuR$psA zp!eH-XTR!uO9Z;U{Jy0$h-*!%bbT$_XzyUE_StfiO|n;1RFJ@^k;tID&Pq)RD`R^L zT1f=Dyz-0*5B4Fae;J-7cfYhySJXekUW>I!bz);76@M4;ZN0C6+hPDmK)Yv3a?}4Fz ztnr9c4=L zUFEbJ`i?QJMdo+Iy}P05Lv}>@&emS-sG@?z-*4;n1s07-*!MSrco+Ki|MY+MQ)} z10qzc)Z-AkU4N>{dZo(d8~;_@XnbkYLJRf9|ECg2eCP_X~sbYmlJkh9~vP zrw;65Xifexx~oK>YgmVKg|P?QkDoEU{y;M1u(wQ`G zWVqWmt`Iwxi`wxWN%bWHU3A+lW#L6ME76@7|FDw?bd?M`q;xtNOD0`5jQYwcAL-tt#(b@-or($)Z%2Gk`hSZc z34;w|(Z%ByGWWCXxI3vY^(Y)0Vs92}Eb)4lZ|=;GOl&CiS|o6ksnb;%c8i&BvgJ({ zwUh{S;ZsS}&G0M7w{0-x9*)k^(+3G0EsNQmLv{WsvW(5`E@nmW>_ZnmUB%hHco$BZ zA7Lvt)|Z~5NZ_bn)OPBj@@utbF~9P)Bm!MHLlPNDclG7XI}T!-(*9CZkihK!BI;}x z!$;&gv!UfnB?4V*oLg$E-t;5q%Nu5QE`Jia%}^`0EOjMC1qr#5K(~>peCqllt?QR$ zi9pxq!R}h^W1~pI+Ovkc{g1*oEp*^hJBX+nWb?<`UUFT4jdeVEN~OBI=Hlg2T>vEH z*~EhrP56jJ7he70Mu|Yz7eAfmekz+>yk&^ujIyf7cN}ry-qDPrf&|VPM4b9&CH^Wy z<*Rp`mI!p+iMy$vSUZbEUpBB-##7D>Mc5}2i3>}P0b$Gy&|{L$&f5`ixHPFzr0pV#@>p3hl1Ub?T4z)bmK zy*987UliP&yB8!$1iG*~hIn30^5U^XMnd+HFFgeBrswjevi^y>}^GF zKB?SaiUhjk9yRFoL8hzNg=aX5RWit%j|9H2#3;ja0Xymz$iGIGlL&Ol8Q=e|OlC`r z{dnV4D-{(aaEvNO`c6$*(A^+DbWCN5Ko@447r#e?D(tSaKOeEjR?0(blWxJz^ot4Rd9%|< zpHH7pFSiQh#*4~H1iEl-N~gQh<{({Cz6<{lRZ&F+2^=}=bc0-PQJV_h{C(bEDW5*N zaD_&k!XEmI{;1}{rw%b!Q9(i;h1VEmt@ci;%bSfdkqC6js{nV(hH{U2=V=}DYKo&# zmiBDp4P|p*2lCxyl2+J@D>2V}$QIowt>!&r(mmWkjNxWy$MdM+cj(ox4hkwr)a^M+ zbGcf93|Zb!fEA7MY@2jk?Du1>R6(r=E ztj_s8__R7A=fJf8Bm!MnmrnHa^Cd^3gU$vwZMWS=q;sq3PrP zX#VZe8@gZb);>0YXnM17GSX%Z!3uDfE{gT_<=&*naKkR|?pGps-7q7y zn^@Z}8NiQ+ex=5Dt`j8Ch4qU?4Ed_4X1>Nm9k_k9RM{8_tb-@^2H6j$Owun_24=S`psP{QR4uN0Kc#k% zp^Z7?#`5>|Qt0xHehMl`{GK*RyZ)n4X+6wM5HG%s=HA;E(eJ0cy^uiH`QH<@>H7;6 z+Q-mF@9<0>cHNwY^milp-6teW)e7GBQyy>VMzB3`0Bg-y?t3DUww_lT_@~Py`dQYMrK*}(6%((Bh(^Uu;PdBX>syYPCS5Be?#`XAElB9%)#FHjxVi;1 z$MdJATgkt8nLrm_H?iCBMh4%wtpat}vWK98gpWs#_OZnfCFiK2u4S#!V|o77;dJH0 z$r6Dsyl!Ic?$v01yTv>@WXclh>5K$ESH$nJc^Hp&IZnF{sV5QW!Y8U&|454G+n(K~ z&wkb=s33vQG11R6!};Q4<`B>5XY&c#vsn&`Q^6b( zZ!=zNlC)Cs?>CdY?KoLWOMdSa_`{I5wnL54e1W5mHcXpEQ9)v}=_IXE*(_!B<4J<3 z_Bw^rn~TWG7ZW7{T?hYVYpu)g@%nOqtRQNx9m`+F>S$3|AVmd<$HS&*{srTePHBeB z^>!80`K*&m$iSxUB?4U;_R}=i$SkjUwGFvHhpvd@*^BeE3m5LtpSRMq*xSuL6BFhW zybAB_CTd}(4GaBJ44GS8J`LxYuixuUR6Run3A`d=*Q7%tZ&+osRx)Y3M4;ul?Qy-qFo7^AQ9+#Ixk22eBesqou%=j zjhHQI{B-*t`ZYTPC@M(E*J?^mI?tT2R`Va}ED`AP?>|lRv-?muqeV~A#^>-pJZMQ6 ztGm=#{kmtQc5;-Z{@C(`1h4d#_*CuN%1-(RqYS6X1Mfs~r(9PS^5+>v1qrb$9J^-X;fMFk1G>Y~!dss#S0!Em`MFk1G>LTCLnPh(UTLN=-iIfO*`MjL0 z-8nr+|DaYc(Z<{#sl19)I~JPLilTyq{Chkfo64W}i($RujU@tIc{8%LZy|H_6Ffac z8w;XT{?2C;%Qm%EC+H%z)Q7Y5(b0cqwapz(hp_ z3H)V6eum8f{9V94R(ttZiUhj09Urd!y?sta0JgdV-7U#E~qJjkevf}jFtr(uPUSoS5 zrbz_4x|EI8p3E!Nr)>%rZS*Nl;0M2LV4t=|P*jk>Usj9&?hfUr-yUK0t?Nq!x?*iJ zwS?{W^fu)^MH?&HB=M#{*0Aj-UlUZ2kbm=cRY&o>S9$Exh>;S3uG`i*npxAi`k?=- zQ$59f1TVj^BX!xahQ>eh)&6+4Bkoz-$*=j{w8k|Y$7g_AH8Y(JCV80Q0KYp~~n=GEQ6}u`)1iI#r3e}pO zG}1miFua}pi@o_w_fj@+-*<`%64=v3Md-(!_?W$4n6-9SBGC1#WPmpDrn%N`*a*?a zmpy@e`p+k$bmO zPX|w?s33toO{cr}Ih5C^^_P9W)IlQ9Wt%%ho87p&Hf6h^M{Qgm#XUbfWi6&vqo^Q( zJx%0d-5bU4J%7s%KAA_5K-Y3LMLXi5(;DRa-!!H|2?9%SqWuNN$h;AE*Z^yn`rR*?$-Q#(J zsA^k}yR@6iR@C)UQ9+`@%LuJt<<%phJq_pRpB`wzFI-G#CtA5m1iI4i#cAu??kV&x zT_K2eo7?d{uUoQ}*PT^VkVuXhti|0a@v8fJjUcL2?94lTv}E>k93=u>FKM!NVs4<< z!kNniQGRlFzGU`LjditGQ9&X+e1ul}{3s>zpW!cG(Jq9~tvpNrdXAYypsV5DRBg1K zukv%3A-nOpdlCHonU&=A<9`$tB=%1op>*1+$FF-S!rvp)$9|eMW#EDzM>AYOv__VWch`yh(f%X%s)NTe2(>4U4MYghj-t4fp3Ul>mfTAfI z@aXP(c4~NC9x|(~M4-#`+tQY4<|NP6N~ZnB|Z1{Mf_ZDk@0q>>sKpT`Fno z2X7aIL$o8iSmy=1JYb+ipzH4aj{5mCx9Jl$8%AUUS3l71b-T}wycndSg2c^YR`}@W zUVU1vBZ7FwPH1Yc@nTMxMXukiqkmFyx>mBzflO>M*>h2+nOgW>2U1$cPXAEU5BozE zLF~4r+Scuvymtp9iV6}~OH7=jf4yHb{+`00h-#Zipey{lg}zfKF@G)$6Ky1IbJ5<5 zDr51Pc@z~Su$GvJ0aV|ht^E%Cg#2R=2G2y}H>{-f|@bRVsv?*h@rvp>J}=S7vV-CJ6zs33v0#6-O!Ww>@! zR2i$6MkE4VYyQ42{3xo7{qa~S+PIngM6Zb|W3FvGsi+`r9Ac6J6#HsjgE~KR5dlp+7B@yV_+WDN< z!XJC}w4vc{FJEChaXs>YE%1(2Q9%MLoQb(X>+{5};u+RTWCun9U1rDJl)@<$^~(+$ za)oV}JB;7&dxCCV%9Kb=(VqQ_AXDnDC%EcR?X0(^@6er$=w-;Z5V~my-`}U0rYA)b zRFJ^+1hH2wZ3yo%{1gqguSStTS6-c9ZSdaaWKT;&ord0n2k{QWZqgd%no?Adkk=-1 z=Ew4{KlalKe{v)OT{EM?v{ARKkxg3-Bg?WogZR#e+iB<0B@`7TaEv0dQ~E@6o24VE zOK7n~psUBeaLt}SQ9L(o5^XHfMe)g%g6SkuN>M=q$6BI(lu-zeK6#V;3^Y}dK-b#L zFs<*kElP7M!;|`Qb9zBhCRvwRdN5$MY9+DJR$v$N3J&XDosj+-%mw|WJ$Z{I^j1qqxj z>2xW-AF{Fc*0C=4`$`15p0%^k_INkazsWV^rrJ6^m=C&BjW=moi_CsBOk3Nvs+QK@ zf!H+ZtF?}Ar7ejS)u5#rWKlpjo;tD?SEg){6eK=62Wjc|-L*uuy=bG062LDstIqrE zY9h@!(S`F}Q7e9lH{W-=HeZ_CUz*n<@ok2`c6+X?mS%1kA-{Opi7%L9#n+r)A`$4q zdApb!JZi@iUfPSIt^1_;ITC{>bkSCLHP_CSOB8M7-D}6~?^od-BX3Fsx-kAA;?y^q z^Dm#Q_`DAvr8ol;Lo2D;Zmo`X`N3q-#@o-$c>3iEyuu4p6+a7I7)KHF!6mi%{@13w zyQdssL85z85AE&yYMR}`Iiiioh+6#UnXjznnR-%$1zl|+x+5~(_O8mW+x=vRnmbEz zA0&3&ZKWv=fAm$GEfsB?)QoxHnTPCwLL>rReg8RXkAk-AXU7}f2IZq~v$Izpuwx=m z5h_TO2yT}U)ae* zS*&)85b1e^#MUDXwXq}WDqGHKq7BoE<~%QyF~8K&qMjv{nO~DQA?!p z6%rVS7pGEc4d;#Ltf#H-`$+`4a5N}R>SOpKlV~am zZb}5Y&c5~1jGRJ9)%J#GNf-SXe(*{$nR-5(qJo4RJ#XD{EblmT0-3NQNg~kIDX@(; z#x90@>SK5^Omw};O0LB7kOjk}$j$A2FZ8()8Ct+J2ZFH^F?a5#vGlS8zTf(@q##k_ z#8Q3pK2x+?I>Ws7%Yy=T@o_xAG8=;f?_{lWZf@e+y(6762i*PG7B z($abw=CxZgHn3)I!udqk^AdqBjGc)63^iu4i0NTG|Iky43KA!jnfh%bMr+&hM~gNb z9xY;B8u{}9w@g(e(1o!RaWd?D8vEGXm*>{DR#8FX>47PF+XFFL6K06wMXx$~@?7Ah)8wBDPcFZU!+d;7=`#i`e71Pe@S#CgT`5`iv^ zo#=GzU01gDg(GjYwS$TZ62U%+`WeNZTHo`AC{CfiJ&Ve<;G0Z)NCdhtb|T(t<^F0D zJDc)BQGHcZkRX+=7nY_~(TwjKqBxu09o9T*y=9dXqa*@da!h7rzK8ZpeZ!_$8(Z#B^7Oiiromw_mv{A3WF~96+&d*+N zE)nR$F{3zLYY_60H5eMGqJl)fE4THtQs3&?sjZ?7tK$pVzIiv;ou~+jKo^b~MTWmFNi6Ty zW!C#jl!^)xsV)ojRtHz<_kS{sUYmvVV4a(B*7-`jM4(F^iyr;29vktikd@m!R7C}e zdtF=T2T!l4f3n5!j%sVYU!TA192;CILB-zbvd_h{{}DU=MbA?Nd$Ug0Z)vI)mwAlM znlw!6=SawHn1o)|Mwp&qH`@%A2y|iGS44!bSh5vEQq$`Gvin5`ivUPY}EG{#<2UOGVznWvmp)xX~`=#KBF=JURYCF|3Cu!yy%0CU$WT3)_iKBnM9xqS8K$| zPak8x`$lUK$@wL%{2+nPE|F=<+=w6O;LR;sUX=)R;X0Mr{h3vj|F-MEmrXh#tw$k& z&tQ@7^|LwOn(EJoKhKc}bm8imPUrg7j{Bzg@P;Kp(z+TF_%0FI*lq23jbwlRbicx+96(l-acxpz?1GH}=4aD&DXjPqhg!#T$ zB;_1%o7s#UIG;`aZhTEJ-+_qlY9VT!%6C}l(#=v{10>|EL+pBAHTP;UJJ9{GM4$`v zHi%vKyF07T*%ual`IeNQ0SWnpLSRZqb$|L(_GJ1ei9i=-lMvTxK~weB1QR~zVVDL{YXbCUj`C*T3YO4EiqOz*P8OU zOlOHe7v=*I(Wr4Zsj}Xd*L&1b%KL!?p86J9Xa}99Lv~p3qEYQ70$rHbL}csHub{oS z1K;-3Q_5e01fE_O=RZQH)4xk?_)h;$5`iwv&te#nb)+GG>hUWc9i%)gNZ=`aadnT> zqK`sq@*Cs3N(8zv&y3h}cXk;u5m^e7hjfzi$smE*1jGoS(2g`Ps?ERfZW4hm%$Fn9 zgs0Tg`U&FKp>9%M93(I+f_UT9UZr)sV8&;<$(eM}g?WF(&Kh2uCA%5%-V?*5{60uv zb_cP7Rk0&GGO&zw%N!^X=)!D7;wKNqLHpaDcoPV#e|$hc#<|nDu@; zNFva+vFMh5$V=P8A-2cG(`V1KY_@t?3Xd-uORis7r7xQ~MccC2fy^B=Tp#m!s&-|i z1Ht*HILGoRgqbU2`S_4Ol7a-T%8Kfz_hZ=hgGt$-f%Erl=r+tFodV%Sli6+b4+c zdS|X8fi9eXinWQ-sw}w7pSN3QqoRTYuH%Y)WE&f?L$wHZn$$!h(1r6)vBvW5ul72* z9pALOrHTp?xQ;6#6H(Tz#)xKoXg5V7(1r6)@$_l;L@TP=kT)OZt)hYiuH%Xo_c1p$ z@A1{SeO91EpbO`p;(3)Hq&ZYFEHX`XE@P*{7O;cc!z2P-7=hO5yiDG(DQp>AIH8Y< z3KDomS)8?us=#ml%4C+Jx(X8L!U(h&Q&%?UslBGML*=`xs33v4mvp*!i)--?qq;Gp zC!Hk%T^NBD6{mXC;}0VSu)%k!iV6~#yHR9r`QgUHjZIn7U3ZB<7e=5(9+p@SejuYB z`}oFLMFk1W_9#wa5A4d@uic{QpF2ndx^Ne>SQ-7=ogba^R`VWhqoRU@oCnhVOc>89 zS*eY5tRNBS!hO%;G>2aZ|B++P22?dsQ9%N8r-+;b_Az|?k8@i6OHU~h=)zd9_{&em zamPAk+RdOF6cr>ecZyD@|2&FY{Aa6`R9r3*=#pc|gKwqsNte58ExpnyDoDs#RaS*% z@R2W`A93yGED`8hrEjCXK01O7t7~{W-)OJVe-9FP+g4vm+4(n0YFLIgq*SikHemNk zrE%{mnz@G|>O5mf0Ui4&o>xyxq^MwZw$Y95Da}@m)<)S0C)P5!r=xT9mj&gO_Xzk}! zL)5u%(?!&~fj=KprILyY5|}AptRj1kqaB+0a@EgTBGC1v#WW?bAVzC&!w_}0tv`kC z^Yh?GJ~dQPK?3V^h?O6s0kqFvcV1&>3yDBi@UDqU@5g~!(RV}CxwFeKYBH`7zvkLr zMFk10+N9ID-|?YSpF8r+7duD8jlTSBuHixp*shie*QWZyTKQT3+AyxS&71iIvR zZStE6RJ$xfg-a4tRFJ^xQ##$qR=LErKW906hDijv@I5b9+~X~Y$-&d?{;>pU1b_rq z(GoQd+tk-AOpmg`cEcqCT^L~#r!xnx)Esu7V#E6;sHh-;*-6EIpUI|de2JcI8ZQ&* z!pNkUvD|fL2bLaVT}6#@RFIHoEI)4dW+5{VvhKeJO9Z-b?Ou!kXa?(BV;?gbB&s&U zdOs34CKBg4ug_wkUw5!JG)^MWg?kXhiNlQ>*uR(CSg+J*X|DkixIaLwvDDJD$hHUB zfs^49fiB!jAx<1dm9h?x3)rQ#y`?=9NZ@WEQ3Ld=5l?Me#0oBSmI!poyG80|Tl1YA zkFa@j+e>>tkiat=VuhDB;@1ZjvJtDCBm!M{Vo1!qTv~CDMoU>zVl(M%9};+GL)`6F zgtwkIi{-C%kO*|)IX`g3GAxn6wC-3IJkq`5?(3r~ZJ zRpdqe`2C+VHQU7S zMgq@li24Qt#W`WB6C0ijBm!M{T3S>ZA3cJfZajqk@S9IjK?2Wghzx(aWS*Zkgnm6Y zLL$(Gr=@i|kGjcxdegbISLssY;PR7oIZK>0S@c?_uH)0L-4pbO8zidBFn<9R~PeC^tTQv?+xFk^wpx$K+Hk2*WEX;w!h0$q5DQq(tS zna1m%3TB!GA*dj6GA>8kcsNII`+sLGt7oV3D&Kr0SrlaPKi{f$aznMn1rHutJefVWu0~e8Sx8Esw4h7BnUQJV=8-(wl8)_b zMlAgnlDFraL>mXMS*wXNJM!2s%NV-MzL=3cU*?ffYD?N<>^tSf-r2I zQ6@(PiF%VuyvhXa5@sMiHTg^Uf)M?Ve=>ot%&o;B)4r$n&zU>g8c+Z?n!aFn*M8C2rG@{)jZP6-`F$5GO+CAv0 z^bxelA_K9$TLx7QKhy?HPLT+7;S~{eWiI`soo6I!+V%mwCb_H37M~Tqza?GT>$I{~ z{M)9X3;h>#TFHMunK*oCA=;Q0`+<(ClBoUhj^d~wVSf3fvQE%-E4m26p|Xvd5&1*! z-6fEx=loH|3Z=_*H~PB%MFic&I`(WMzD^a($18>%L3&Y-tgy~&V zl94=@%zW2Uv|(0UL9HL>%k_zSBm!OdZN=41uu@NsbK@@E?=e)6aI-NX-FMC+t~U%< z*Jy}^n!U-17w`Wn5$M9JAf7(X?&@`sL3wzmQ`)&mJ5sIL3c@0q(uhtrWUa$8GIEv^ z_3U4X9QRs89=~fM+IaW8rCMkzc1~KAXQ&|YGQyf{Jd#U7oSX%*>3JjdZMe#ZDm5em zUGg)rdShpG*C(;FrfC<33KE;LEy&-mi-^;3L$8hd+(cb{%Y*+c87L9x!soG0mp{9U z8aKQi&)u^{^XpQZe43C)DlKV7ciYt@Cts`}rT)z+UJ-E?InG;EFEr#q7mi8S3W@g_ zcBGrOoD3*2JgHAEQPtC#P56dq_ay>dc-=(C-muQ1wVI5-RbLPjL;Tg**|oUNeX18KNHkn!L&_#DC(C{r zzLjoNXLaR|2E4!WPC)`)rTaMs37rmunpPiww%}v za1_M1mOp8$X%ReSc@=v8la5?Ann&tH)S?cJUMbD0&mq-+)|F~L86p!e=(Y9(xpSVQ zq#%KHp2XFyTTY#m8OFC68A)wmEg_^u#;hhL>V#V%++oUBf(jB??MUo4jIO9IToS?) zKHQWDbcJ6uA#dw1B+;MiioZOlp`F^NQFne~>ve((5?GH(j71+dQj0vixnrXl5`iwf z(xU1@HCJ_MM-QGqX$(OHiOOl#k=tO&?bS5ga)V;FW+M6SW=$L2-KMOcK8eJxwWc|7 zi0tiUXQiYdfmO}KX^uMcX+!g2B95FR5$M8iC{FMUUr(n$ z8_dau9Eu7OSe;GOP^hz;riBmYE4rsh1iIwEJmyL;Eq8MW-!N()JwK|u(jp{_q^!23 z#dpRiHQ6|_%ELgX<^$}@r13ct*>hc$ z2Zu(H2emE5w=&7EN?Ux0;~VX+NCdj@iind)X|1Wg^B_Jx{kn9mkoe~Augv{5h76f% zXyZW3u5^nomT$OpQ6kWV*G=plOvv*Z_+%g-m-|_o3FW`L=23mxFw)_HI3HPkW_z>T zVZ^4anrP!zY(>(0-yrUi_(USmCC{VY&Cep&c17_GIq#&u9EnAR`@I5&jvxnHS%@~q zW$z=oS`_D<-be(xaJHn=%?hZd?l||1UD@u+ajb@8I8yLI37$BWXc>l)%<3=Y)QTO; z@!F?aa#WCL+P74B+-54-z0xoWXEWc@!@ETO_SO~>fi9f&iAd_dD(axbpZbVJ|9qoS`g82n z0bh;^5{>9-C2(yvv7T%g`z#y#m2SLX%pV4|l?Zgo$gLNKG2G@4C3NFAFCJLWOd`-FU){`Bg|yN7KyGp3g*4kn!uHlFC2iw0axup+ z6CS>28zsh3+;rUzi9i?5)x})x_jWq*Kq9X+zL|FC)(OSxrg*!JZ9sRmeXArLnnRv- zZ}LAgdUEzGwS6?0huWDioa-Zj<9U(8^yN_+8WqRW*g%Oum;9GMp8JSy%kRTGCU24c z4kU0quhUu2|48#q6kf0ByF{Q1dx6MQSl3K_|E~^D&ass4b|mCE&ZX{F>O@;3ezvfY zM4$`%rpO#w_cg7uF;T0&DVpPqx1{l5WxJSvZi#5|KXd2Sxwoj#+^#GxJzAPOBjK_t zSGl2|Osv}*e)I1c*XV@8Q>^RbUJ`*Wyeq|Ss*#6jR-Q4Rx!0GYg2c}ixk`V(Y|>dX zjKba9GU`1}kBhPgqbJ4H0R@@_3}%TSJYA4aC|juAUj0@l;*KAG&1`B07u5*Vct zyIxM^(%_b#8M_)R5$M7@MyI=YU>uFSS(6{I^ya7_5z;q6@%=i5BpfpQ=HGnA(~4CT z?!Bp=M4$`r7_q;^rz@>3s}6 zM|ytZIDTzz1BwK?>V%PD z<@)eeAyp&-T|W{pdmWsSO-c(5cVcShVP){&7+yU0IYU>EMvFWu4G?{zTVpB{6`vO< z0~aK7^N#BnDoCtITIAuMo=s>=LmOt3t%#$`IR5r|yhNZYbJu0B-t}_Go63y@G2~*j z5|uiE_Z4}3Q9( zWmjhmlOps;;N2tE?mBwXp%ImNY=t0+Ko>r{#3|D%mFTO#PTYQcdyWbcc=w2XmKIiY zVQ?V#-D)Wj=)z~0=pTnKkrJ;czV^}^h6)mRFX(jReXf$nSCaYjUdto`UHI%0XR0sG zB>PsU^MST487fHNFDrI5wp~hYnM~mN#_csE(1p(~k@IX;IO#Qh0?*oDLQp{h?**~T zVr(*DDH;6fV0rxvUAW#R#tc<{D)Wug`HG`H(n=f>@_lt^=2GRYTMFOtXQo7;tDW^8 z50B3i$^LeRD9#xB>gs-9Uw$`wqO?keV`_{Pi}N_8Mrx)0q5N!`vlJ0V0!RH~N6Lq) zYQ@IAcv|om4L=KA81WXnkP<7ad)D;fdwvFMs31|kwJGV+U=hjsV(5cub(*MU3p?`o zTb>euE;;I)`(=sJ!Ds}}>Z7N4O>mV|{yp5@Qxcz*z+Hliq^paB90PC)-bF5@Ci0b* zTO|Tr_=XcX=sJHRhvG)?0p)i~E3Qb$@scY^b*OW>(cHr%8lu=LpXsgK1+8FU~`)ogYepn~%hiGH{az8;Fa!umx`W9)) z?&~E2T|?e=(*_9o`2Ijaj5AH-N2o8$o3N0f%eg@}txSAw{^%Z5Cc0lr=HLGKu#3&I z7%E8o_VCvp2%79Mw6Vl@9Jh}w(o**Jk_dF+brbp9om2S*@vVHUT^TA!WJCpOS411J zBYKNA8k`x+Q*^$}N^dF==)x;4-kfi`@F{*p+Vhc){G!@IJ0Y$~qa~EiTH~O77ymxm zsy+Ss%|RQxYAgw_-Cnd&^-5R%*UOhZIcCFAS)bsn`3jeQKc)Cd;!L$?5B})84=ePq zCbfaYh|&L#wmeKl8>Dv-Z(P1eyWGK2BG45#u7!47e8YYl4aA$JJ^AVizU*(YIY$MF z%zAEGYw-=+J?tQeVqF-oMT)e)lPX9Ax^8Xr&{m2z>V4}Zi1g$A_##VRwtx9ohOV#I zJv0aLxg$PyqB3!ycO;Lh=*w2Dd%{pb;`~FRRTlKFjy|G|Q0sWUzEhDlW&I6_Ko{Qm zqMEr=Jbzx*m#u7ilA(gc;OgGmUvZZh<#!crGzl5P-`9a~b9TS4k+P#OBP zq&<5is0HwM#AYpu6IZsK_f9Tmi(^A20;?ikA5?EZc}qrXvDe{?3i(POct74w6j)V0 zELTm2-`!BI6_tsNy)NYplQ)Ow4sVs162NP1DNQ-03m@_NR!YRg(#e_W=T1Fi});U2O_wTwJ8xk2j0T2@AL%uNx1N2&|ItVD|?##MkCNe8`2K0$ZL3 z{#2jB^BS?a9mUTAe8=KaU!3^j&0`aMrKbcFoi_Yc?*rY|$Qf#N`n`q7vMgpv);z<HxFvlL0}6eS`Dhr)<7AFMje2t|Hwu7w=ZUyq0SP4Rk%lm z*`2GKc+kLy$82sXumuw@yqd6BC}a2Ij!;J6cD-l_z37{Rb`pVAxIcziU*`qt$hau} zGcZ~q!K(@~*F+QZ>@?cEYHq>!-?600_B6WNrgdR3{J-72G$^BvU8dS7xGoQOi&wA( z6SI5g7MM;+Ag%Xn!~w@B_S(&de_1<2BCx8W-NVARP)03(jhNzjfX(k;%$6LBSFi;W zSO1h0?t&iUx{pR&-dBtNf@jw%Dq142YVO)?8)j$pa&#t z#NmGP`L6fgeD(J*iNLB(gZ?A(|0SjxI`d5fefaW0kqWLaz7Cm)4-VwXgNxbh_0bBp zVB%9VKXnXT$Kf|xt)`4h<8A*IvDldr5`k6t`e2o8sHF&M>chipbyf`OQpZ5MS$QSV$Rty?9sZxNU^bM|#lueAaw=ve?>!Z4!9=1>HRb|zgX)Pul-zO< z8{r*{ZKRh7tXf*F25SjKYQ9#+j95SM62`$>{mqpNF@O`x-~{~Psxt(!r^ z!W~$5sMWO}Gk`dJtg|q6^x->aSt!_2+SP(ZfvRbv1d4x2r&~8qFNS>g=5_AbNo8Qd zx>;j36KInY2~fuJdL2cGdod#o93=v)$n#1XkfzhZU3X>7qiPVzzxlCUvRf_pe{uU}g|4ndHar!>B(zF^J}m z@?uk=4X5-9g);uaPV&R>)&`8vl`NQ;mEpxc06i)u1c*m-L&O5(Vs^x6uS8(grtGe4 zI+RhiQ!4|C7yV(3+P-%;#THCl*wBT2gEC5&YlP$eAYneJn6bB~B?7BjfB4TM`=&$y zaem<#5!c>_Kkj{%V%3UfgqcE%zKIH_GSQok5H{s~`01aek_8jRwjEhxpvQS>Wjt#; zO#J9o%wk&W6#QFQRd&8LI|5hE7Hdyp{Kf&|rIQa&eOE!j7EILfXv;c48U9zIfyhbh zCv3q3IBRMu5m<$vd^qT z^wgaXXhg!hzkFY4nM z8F@W5LOd1e8Sh1^WifKMo426CLVPyPy?Whum@ThwwEvS z0abmt>8mjkfmL|Cg595eotRxUU-oT!f;c|>Zs8snCqj=kr^`=dy48d+{J?8_`ea9@ z+eGjNuK(6z`eU79xqlNMo?#O%u&<7N_~zkOY84o3+uCXS!mXUA@_>59Z27z>fi0Nu zz3;1zgR(QH{=1VrMbE2P`|xN(q(orVq>* zrQT8%TQFg?_CLD)zwr{2oS9Y>pIf-RURzpXbr3)ke7rj@a%T)Y?r^(YIjRNZWkq8xR^d?;PMT^mPziBVXot5I zl#^cV$h=BxN&J%Ow5Dwfa?f)O`IZn(PuaF6MQyXlb^93Y$_reTFJn8>%AMON17gj| zt9Gl2>&tjr>4hn2v@wrF4w*&!zpF)-0k5?rN7uvjbKjqQrhkD(_T(UMf ziPpS%SHELGF1fTfiEe&dq8|Z-r@7WAo~^jj~XOJ7tkQ$2HF~?DQPIa-k!&>K(3(wsKLQ!#?e)o~hKa(?nHgzKSe7 zl|nk{b*IQ}CYk1l_ulJ{xdHwW@yZW-Hi#Cu-+aQzOw4Ur~QWmKUe;?=uy_3@h z(tk@J5CK+kqRKZX`UMDV!9;dePjAMPr@3ZhWd>vVzqRII#T#vBO*Rc6^m4F8kvzI5m?ng>CDE~&L{hh1_4p=@L;jMOLMx5 z|D`XhIkG4yed&~FTIE_xCIZ)x&PStYY+Oe+4*q}Ud^iw~=MI6quax%u{Y|o9f;V(z zHhb2PK6N93sA?G~-c;#ChqE$?z$))~&g@UqwdBlEt&DAzd_?e84;oUrp<)o0ki~H| zdHpz+?(Aj50t;4?W({L$O1=%72etA$7Y9W24o9)*eh2y{%tdjnXvDfW=aHJBv+4Sg zwOBOEBc7(S=%opD*m@w$rfBbZ!W>sI^u8NCH>-_;EtvS6T!*QT^N7u0ZN^frfnFFN zwWAO7n@a>%$+dcK=P5Sza;KX^tQBm*#BnoAmXWfWJZPX@$G1W+K?iuyZu=TZ1Xke| zff@aYhGK31ru2THkJ9SYQ}r%fVeh+1)Yhpy+f^}-d@P+!y%tqu0{%bHQ=37aJ!T{R zS(oiX7EIta)ag<)jl{J`XF8|x0Hy5hd9`}|Tw>K_4vjc;TkYYQOT>*Nipz$b znafPX^{37>GOn*wD@<(3eWdmopG!hxH1BoDP&4szge(0yyoW?!6|N!Vwfy>lkGar} zhTI*d>=|)X{Rvli%PpB&R21s(d#gyxt8*x>EqvX7B%4S7b)-`-g(d|4Uq~T)@K)I?-V#CMnp0iBm6@tNTJ%k&~}9?=?03JRiQ@nyQ84B?7B(i@>wH z{szAr-IiuPA0xFDCS3D(tHwK^6?$o9960urAFkDowznH85m<#=8a|b|l)^+#8`^SL ztdjkCY2mefD~bQfR9czk7skWYCRwD>CtV*L3f-}iG{2>dYMJ4U+3PV@bcZ2M!4^y; z=RH1@3v@nB1EL^vxJUEJZD^^dOkmahlY86`Ze2yu8$jViz|6(i3LuM%0f{8;*YU=L+-SXe- z2))#TzPQ_lIzwy;6Ij(H$W(vg+DdXKS}P;>!&17rx;4FKHC4G$DMxP!-h@Sb3iaPN zOuxGNDiZKIh4vT|sQ&|H?DErywkzW3mHCeJZ>#AFwqT-wwALRhTS>~mmw*-CYK(fA zw58{d1Swrvp8j(DDq?#jnf{ZsOkX@{75QC0h2pXy?h{);k6&=2QQP6%T2w1cTsn}Y zZ#8li+15mR+P(U2q`OBt(E(4UNCZ~l8p1y0X1A$*aa&s8H%3`*uj&=J^7@mLsaoNX zzU}!{q`7f2#kJMxe9o0qwz%8URW}0^?0I324F3|$2RDDEag&_s`Q)Ke8JPI#eN>MDyXc<~^s2N4BHEh7l5hRk(&QSG(z?B=m8kC0@=7_9pk9uTD~y zk!_SkH#^WrdtDXmb7I2F+L&w}l1J_|(IR)PbS;!;&zjPPmpmi_tFrEtBXQ7%(^Iv+ z-RPmUGNPzGb@|mv!4^!c%l@OE^eLC*TWf@VQhnuCSldZDPX(xg0GW`SrJ^Mw;*QGHI;h^|=LYoPAxgV4~vU zPUIQT1FmVl=m@h3N>|aDUfOX&BCzV!X%Et%);i+QN+Wt_PEl;zI8d|HEfiZY@xalC ze1I}m|Is{4%d6pvxCAr1;~}(MH!rgK4tS6^#?gxBI+Go(@=3_VASx5a=F^mm1AXW| z-(*R(>ANTKu9{DL>rMI}V#4C7N}rG3bbwR3WWhwhC{NPv<2tf9ORJTrAF9N}c+q91 zDE#@bFgD(kLx#8b3MkM-> zgzJ!P?tnHcx_&rTi7+_Pqj}>9Ca?;Z4cUPg#wf!l^q_-RpC;IXi8-b|Brsq-xzj_N z(bs$xqpbeghMM-TB3&U?d7bbhKj6w|HXRQ{QPxp?^%bRr_MWNK@0VMU3%h*X_N7T9 zCmwg<>w(A`Wbr^N`f^8{f-QLD#A7g=fax(;-(+GNddp2Fuu2}!KLn4W-B*^9oi(GC zvjy(@*HEjXYH8AFiN{^Y%~5eU?Q`9Ve%>FcU<)2a<&kr+(9`|R9I0bbltf^aJf06t z9Y!i;7)VaB+*W(9qRta6s<{-{x#;sCgL^ zTR)_&q7B6K+gORfs)?=zdUqhcnP^0(!%yf_xQ-Wf#wyri{e|llP<1FyrgE)(4t<~w zTMT4%*hr}iOdM}{OFs~3-@}^EFe6i^{3tFZg|lTZ1FPhb({Dr-WlWBNOfw9U#z9OB zO?|8ngfjXDXk{Gmucg#rrR2ex-V%XTc$|lQ$g}Gy-M1Nt0dl2a3nm)>_^A(vGAfSI zMrUXDCdxf{b}N4Jl?bewKC%Ld1LDaS&1ZP=b{0JrV<7xNr1TEnwi~7Y4bM{c+EnR% zglwDn8T3W6fwW%`A$hNum~k*jUk=LHk*;~K{_R)L?V^Fw6ml3#*j zi`e4;@6}hYd>GJ--W%Io!4^zlZxHUsP@=@1C?);ww~z>|dTn7rw!n4F>!d{{YWWXV z=s^Sdw!f0n%EFNpgQa$S47Katk=%s8TTYAkpSWmho#Bez`BDOwG}3IUTsSD1HC^B&Ir>TdEZ@eRpE^qX)Y01h5b2* zm&Exi5&I2f^UOL5wqT-j_f~L5(JWHDN?RY?`=Osgmm6T=)Kns{3g0K#N0tz(thioE z^5eEr?1hC5??PU{@4n@sl7|DigvzEV8OID{Z-Z5m1rw#k-N+}Pm$nRsT3Nq{Prs=%Af-lrnaifgE`rPqF3g+MbZ76|Q#DMCq5{42XkK%JZG2 zWXIGAk_8j8m%%4QDtjE;P|`C%BCra3oG_|Qk5aC0?@l9DHIsZ%Okl4DzMFVCO1TbK zUcc>Y>78&`u)@jESRWUj*=3f;}&avyYuq#%GQ0Q zWWj~&5`k6t&cZ3?#gmj~(7NI0i=}&xiBV5Gljl&zOS3R2gLq9*Dy%e+%&mnIfmQha z!w!h~mdbM&ITIWED7X&~t5cC^r!q|`Nu+p`fOw)`Qzdnyf&7FV(%6EDk4;QTCeS-q zYqQjk(^@KBPnD7}*YpyBRk-ic>HbV=t5jNHAk9Z~kmj|RP_xa*GAQHIJ1tt<^LYnl z%mxG5c-KiHunPAW5dAnjLmVDvAbIEXbf}R(qdjMl!U^MO%J!bD6a1Y%ZX(4i0y6Lt3xW08TQfzc@dh$^st>^yOnh+f!`y)`ovqD3 zs=<0jy_8Zi+x@CUV3pifUcT|7Nt%Id+V+KD3norf>&^5~##bwC{?V{qoN$|FATIA4 zN^ONz_&&i(!{%VoGu=QgtvE(amUUr$;kUM~45jlLQZ^L+K9?3Qt)xIy?ZN~RkzPus zreBgQn2=X9E-oG?DzO$cxW;9Pz$&~V1oQLRBgM4RPBeeOBWbM&6Y^??N&ViU%j#0{ zu5WGSTYf7R19gv&pCPSa;I$Ws@9yg%8ra#>mha3IY{6>?cr66hKOXlMp$!QAp|2(p zScO+;;A@UMW5v?m213?7lv?!TOg#&P8uC`trPUf34F-%6DPs)e;=yN<1rtem9ocB0 z&H8HleI{fFin+^5$;ZB5Bm%4O^}(4n&xZ(K7|*loRFJL%6HATSvZ+wU0Iu!#dAebM zSQBO->*A|Q1XkfzhjjzkU6DH6K&k{pNxi{#vmUGq{BC|mkhFRRE29OGV$xs(nP`zH zSuio+dw1pq^!)x>WMXRHaIs;2DRBv2A`w_6uPBa=o+>=!48-Z)dg)2T#FU0zSsy54 z3e}=G_G3fDqlpI6_r-pRz$*OSz^U2yTZlpHn^Kc%9?~iqUjM=?Lf}~*XeH9~OG)_? z?$TNjCXOyLW!s=uXBKOt!Rq{GVh3EuTsKdNz^dabjo2X|o-Wd66TDYBk$A#}Zfr4F zT3x~`O7d!kjdKOD7G{t}?*~h36PPgVcw2n}Wi0!5-;$rrH$F1eKx{q-N(5F_u5d#A z0z{X2+WN<|d)6W=0A>@!OTqP>wWR{%pmKVb_&@7v%hy_nzLO24%`G44$}v&<&o8wY z=zsui<~4bK1MwQ(kJ*d-Bm%4OH9>6YaV;?{+(66+^pRG{FfnZI3-tz+;n`T5K{ope zxj*2I>h*hoL|_$e1voFfc`v?cf`ODgiBX!K(W^aSM(1b@(Sgra>R|YLkxknF>}MF) z-B0TzH-(Q{SW4apMoDXTn2@ed$BQQM z1xKuC!?Fm8z$(1M17^b6-T9lwj&yGQC~5BpCh*P?*i)puzE~gVCu$}b$Ytw>(&)Uuf*nhS zx5zv-UK*)kH6zMPj1Do75jpazJ|;fSvtSE>9&V@2&!>-3#59Pc>X+C{tNK`ldsK)B z8@US_0cEU{cPC(?L&JJ(HIy-7t>z)`&2<*lXBfy5H&pZo#3r?=+ym9vafx}Gj2 zkrOIQ1XkhrHSDvz7_XRur#~t8q7>Q2#Qn3qiLUo7QfHhNq1W}Fsf3jjk@=${Bm%2& ztRGge`XnelPo$Cvs~^%T045%l_9Yddj9jjLIawzxK?yRXlEmKcI^y5LsxEK-BQ%d3 zb`{U4$sgqz$onO63hp`QcYjzI0?+H}UTMPJ! zFM_ma?c2|DnLotB^H0hIR^d22e2?>?3G;aEEl@xEFaN2|;b3pVzlo$e<|1Xkg_ zc#wObX1uU#w~G9oU5U>O>cxy&E+i#J1L@zg-pm8u)W*XH(C3Z%{QI{pe9x=XEwoP% zyr+Sjp7i0+?YDiI8>swY?p z{*DY=Fd>)WxGql2`c<7?u-PIJScO{w)+QRpi#sRGsQsU23|laPcOF8V;ZCf0me-Ch zv$dB9tdd)|O~hcKyE&T#H8K)&o3#FS9%Z+Z(kT~R*(7K;3)9YY_b6AEP%nk7s?`}< zcknYSQOA1|Ul!>i#w3a5Ifd*R){c(0t-;oINg)gOxN7&qV}$Vj z{GJzYE6-1eX6(?+^~7R(Yx>x$8GG4zJ$dx2743f6l69S&ODc771ftHv5n^GjxBRQK zkwjqCwHM9U@T~RZ-3#rj#uYvzM61Wo`H)_299uB)_@8FXXLTMaVJ<-E;PlJCLC5)s z$TkvzRs9+|u$)sH$fw`h+0p6K!o`g^M}Fx_67TrOh4q@hn&^Kh^kWkzW@x>UoH6Z4 z8$4>wQhKi@zJ1(*sP-XTTny>U=L{apu>}(&4?D68)*DI88aE&+f1Dy3Rb0TEevOt0 ztim;foy#XfM7nM{ubAG8V+$rKKX72NGVuu8sidJ1wV zhJ8{`hlcX(&2DUb=S`%xO&1zq-kyzmyO9iT+==2AfgSPFqD8aNF|0rzCbbnNO!~Pp zzv~;x+;$4o>TF(=$QpHr?O7Ns5m<%W4Q8o*qeZ2z&NMH-6~8aKv1Lh1$k#u;Y2#j9 zSpMLRWY5b!G-G`y7WR81Ih4>7$_R{&7T?_K(K7cgyh@6~8duFX>-54bAqvhgND z^I;e5Jx{j$c^xgXW$7$*=_zxSxkzNMobLu_i<5D8FYCfmL{1 zf&J7|!^CO>?5@7CmG7AF-yFGnVmErg%!l=Wo?$7p&#F&eY-p{yQmA9aZwdYLY@E+%ko;f-n%Eyi>xBR9=PNCZ~lJ|EU= zf5GnPy$8sBWs3BaU_!o*;NVyhq+3fidN@i1R^bs2X7qb3#i!E;)aQSF#FlY?)f3Q) zk9N1Cs*^E02!GdI zy0o>(&njfYcDV~|!NiFkO;{mGA?IdkU;Qo??L@25`#lbMb`aQtiJU_CIumL*;iEPh zw5{zfivHHouRiZ65m>crZzHx8h~j!$8DVd%M3H#K*O^&~cWrAib2gWZyzfHWjV#X+ z`=ygb7u!-i62X^x!cGKjG84Cq|MEA6%B=3C1%%geqODd{VhwlCBT0vyDE=iFaVFS` z@Hf@OYi=x+feFK)ifsIdxx~&v%L~v%wH9T|Du}HqbtD3-a1CKy&9S*~xZFT2I9evv z3fJVmr7`RBB9ok2rj3KuXh#um{(~>w`kiA7ChWIbvJ%ThB*9!8KZd6|i~0kv#F?WQ&Z@w7w{*kChY#Fg=DOaBb{}`n(cp-O-@wmK&#%V z&t}?Z6LX?HCG#7(3%4RW(dJPQ-*lobi|e?Yv<-8h{^qsV*6Z0M;(M$AA%4{yCN7$n z7xl^yVkLuYSZ6q`-nW-MZM4Cf6~fu`)za-HZva*SRu2*@FI5pe|H)+7Pr!u#(MIe$ z?1u}C*1pOO-4ZlbPR$*@d&e_iP6D?{q5V4oPF>Jv^rBriP^}|Zy;L;Mx z$nf(O@#`Cj->pnICa`M$vihuO?h10?x<n=^VE^CRS&fvLhd}NaG8d@3S$&QS_+VLX2vbD-l?Q?<}mJpN|qd z%9+v67y3%QC>|4W{|I|nJfcLC1%FBHj}tkzU_u@_Er&&l9!u;=$g*^az$)2ixH>&r zJeW3{lr|2LJOE7Kky@u?qhdtj*NUXv+p!XXRoGvF81nbw;*pX>{(1Y0V;{H14L3Fp zdYrDFUH-@4J(e{>ysnx=MtOYY*b~OYgNGg27@%LD>jL-V-L&x{YgQ_mH~OwbU=PELJaFNqi3#N#h_U`tJE}wI=e1FO=c_2EKPbn?nwi?Ue|u!lO1sokx!nUvpdY z$Rm$9?hP(3c3}+qk4G7vbjczYmf1Xq7>qrkj6w@nVO!WpoNp=j47mTmy#$=6pVd_q zKKQ}w`ds1If(cwUL{cvd6fI9};$+@EiNLBMQykbz=Nz)*vj^0wlJ5v%ZW_dmcHiUJ zf(iLLQe0b#61M}~$)dS5W5Kf&+@tDrOVZrMmpY4i!B|VFZ^y&}D+_k({#-Koo7V5H z^y(@Ci#PL!YBh<#DqKUz+Vi8oDDv;Yy)!BbY{A6U+b(R!!MP;#g?2w0-wYIf*J|=t zBi>7Q5UcRrgiNtQ5#1*G>W5^v5O_?r2x-EW!1LO2bw`RvZ8&Y=YbWu(OFz9|+vd{f zjEP1|EZAb8Pk+}&=Ru8nh$&*V$EBo(5`k6ty@9jz9{G!PBc>CZ+&ThVFi{Wgc^s6n z?Ja>a(#QbuAQjHS5Y;3CtMKeqryH==TJ#*4#4QGU2s|^zUJbsRFq`0x!uEg*|C;3@ zumuxxTkX3=#h;t5eBAV=5`k6tZbHux;V&u;En>r7nF(yc1a1*H`Ro2*QR{vto7KLO zL|_%Z|F8#g_ju8(QhhSL`8|#;n2>v)i=IIuNc*4hR<0AJ*c7E)_}y zR^c84A`@^DY2PoM`MmR+rM?6cc-{`a&&5$9WyDgxptw*XunPBl5JUDJE&7r@{KoUu zQV)j-Ja31XW$S)oSfet&{n#dnz$)w+z^>v}{e<^1omgIHj^qJg0{bfvPc-!wQ$N=i zJD!Y|2&}@s9lTK?USeXDg*aWif#mgJLiT;Gr`w2(g+2$vQ&c>I(mBI8m^(Piu%HQ6PVY)EfIr#3sG2EIxmTW&&Z z$?Jq#ZEZ4nI92nOR`=b`H{|bR6&{6(#=~M%SBT0E@7|I=?wO-n!ryLj4)j7!j(Vps ziQH=C0K~r8W&He_FlKUbw0KspK&=2O*IupZ!X_uwZ_q~-*|edPhn`RezfB@fA82Jv zGOj7c?{pAm312y$58&BE_ky=-gUGq$`ZTE9T_MLpX$+>BXq3ilT6ary%A0C zS*m*f$smLGH=t8WUZ~4!FCbS+ErB?2U=OeAG*JW%oJx(eud1s?r;%FY>eKZHm>N_u znKU|BmnO|Vtp2%~Myf_N20|HArhbJyiXF^vN%=qU*`F(SoheLf5KAif)dQl&ljrQ0 z+i2ks`<#9$t*5?tFqPCeQj?y(e7dkL4JCtm*Q7ELv7&%&IzCEFeECYUV4}mP+`{A4 zLI`c5Weln5IF@z1Iac)8|5zfh3TJxM>B?^ZQ2iW7iTzbRO4osj3ZI`IdNyw|xei%S z;2Xt)X@&a7BgNV^a;_At!g*65zk%w{TW$*y0kikhYCp5obzSC=23yT(!t9Z1k_fEAcNS)l zn-_8lSuko|UrEhQZda@SO(fsX)S*3kZc!I5NF?Q#*O6KTp51~Re&=VfsAD}_dgAbt zh}#h2B~4dx_g52zwdq3Xw=iMejj2AL=8&2@>%w)^yPd-~y`Lyvg=b3yR^i&h{`U15 z+ySydJaN?Gqh23zoUx%}4NntO_eZXPFmM)s6i7ZXML7Rbb~jEF$wt8$lUSy^Y12NrS}lXLAVd!!a%QS3^`IF-R96PAA@w%D}%X6K6YA z6gNKvh)$D#!k)_i>-#Wqdr>*Iwa-Gbc$!wL_8-a#YClBew=OTWE>_{*74kH!YbD&1 z^}@S*pfpA;d1c1VHC|4-9krCkE9euG?S;$IPU6K7_@WezWSH1}qy|gcn?vrbvw&JT zWHu6;PIVLYsuoKGR^gV0{czO=iZ>&x2~VSuDvo&I*hx-nD>kQK4LRhZjhwS{yNh1q z8jGP%SLj!^uwu6R*N~CUwlu$j75lVo4Vh(cOYs;CxrAJO#Pw}fqO)G;vFgyzMr=+| zF0pt6r?sO|8`jV56tUK{rSRxxDzz0RqL0^Q*IKV2!JgXaeDR)}sQZtT7*NSoBCra# z8_Wl353y#Zxfot+HgmsTpFM33IVU?er#L2qTLe}!`n3@SMIFR(hdNS(1$!?pm#Z*G z$Wl4>rajbZ@g5g(Ol>Cyy!phi1rxF-6EV?M#G5*coSs}FunN}}7MG@V76D6|ij(6` zOV@!395sTcq{vIusbwt=*4`-*ScO{wcKoKewzHnl}UI&U} zK(On@yQw&L#!Xb&Hiu&iCgezw)t-vN=S&yz>)|nuJr?ZAjGy{OE!jPv%-OC*yq-L) zDXO&b5dRn*9U(6WquFQ_G49{lBBt?eZOtK_Kj_lR~!FMCjY#2qIfn5`{ByW#Qwe++@*z=6mQ2wZp-&-3)?wlp|=)w4)AIq z=8pH}9hUn@1Xkf#KV;`hYaoV^i|p<@KWP;J6Wf>kw}UPxLW}Rd?$t>2f3;D~3zG?~ z!YdH){m1<(BHa6jn%yoywElKgEd#H3rkx|r54x>Bg};qgI8t05eDjlQDi*o_P*cPE z3v9tew@>fX%Rq06)2`ehwyrpM_PcsyyT3$W6|N!drs`S3lMBL_%erxr-;RCt_eGo4 z8sN`w7^`J6OL#e!-`-xrQrB!@!b!yE%j7-vJ9-(4`Ih)MXh-WOxTH z>b$)$k+&%+VVhn=2yDT`sq(?92hhX*%?72EQNAbSA&Y(;Bb9;amtpq`LxETk(;Uh; zVr$QTr?um8OQQw0VB*5GGll#9nN6JiG$O3z4_jh1Or7^DULvq+!OPQy;ZR1S@fzXe zev_4(Hb^Z$Z>GQ&OqBGAD@+1nKwXXS{5^*`e_h8yHq34qK_{Dmh|f@5m@zWQI0y!HntOd4U0>7KEE3EB& zzU}xxamwu-#{^d08=j+1$WJAU6SQ7*Po)*y=E7icGy5*b7EIu`8L~A$n7|9e!i2Bo z9ErfHOU-iBv(9P6|3xz>V_f}IZk<0xShh>y*n$c9Nz}0=EVgfgD1SHH13wLyf1N4J zg`82N`q|PHYd>}K(G+rikXFX!xXJ8CT7uYqWuA&HnCSQYOrZ|4S`DjW2gC)JqwM0v z81ZUuH;xIc+R@ri4SJePQom?^`zduRn>IQ^c!ba8*n)|_C1(mpXCxE9gIcXB?y15L zZyqj2-})jESmn{&PtE&0hfLn7-4D}eWlU$(U#R1&32ec{nv-V=2SHx4Bhgx|&hK;N zvlcZMSC@K71XkgZ8onz!SeLJFU0Zmb>m~UNm^iflOkpL+$acB1R;w<=l9%`0!$USs zmI$oE<1WNxo~&jMjW+Ts4pRlTU;<}ngR|~0TC=UUhx2j=V1a`)kglCUv2dI z3+iXcuQp}FB7%PltMF3^=TmnHR3jjVn`xWb3|laP^SMFJ$+Q}*E98mmRdFK61Xkgv z66S+9x2fTfi*9hYe2y)czSp$Xnq^bg2 zFo84YK^ax%vO8^B3-XVLL|_$uDuI~UfO(bH7JH}m5!iwWob?a(Q%|YKD*r9v;@CKe zz$*M4LpG14W}-?HPtifFk@m^pm1;avL*#Bn9Wi^6r^r39LYk#wLY_M(b*w0Az3wL> znvRqRtg6-cwYu`)0y5Q2>q~|&s4X^``iasN{W-Q^0?*ZQScdzduQo*q@#JDr;@LZ%o=@m);d6*D-KBV-q!l^Y@!zG~(Ez9Ea<U_y>3j*ajZo71gDkB@JpC?{6QQMJlb z+lngjZep_0bQN1Lfuqr|>!qQ+XtdB%^v(8^qH0)$-vZbp>{?A+Z#__qF*em>3nu=j ztw#LekLw4Di=zuwOkfp$H=%XE74bV)gT?mxOZC`-34CwBFZpzuue}o_nuQfg?>Sb< z{nh;XyLh**q2gXB)6h&2 z6L^*Zv5XFb`Q^RQ;^&c@5`k6NM}_Zkew%XRxOm}`@wpINFoC@fXsfezx&6{u(ZTl_ z!vt1gUmNyJ1pQ)@+~UONVILW`U;_K7@HP3B4m>_BRJf+El)P}P!ZQG!&d|06UuzmH zEC&`ya|29ZuNLwTT88rbwmrnEFjHy%fmL|!1N)Zt4dELCx{9)=4W&5_Ca_lvqruUI ze9n=&V#tcl5`k5C4hN^!jh@5L{4Ot24)>AfYM7AyUB}#|yqQBhALBS#BCrat#KZo? z;CVdzaS1D1JY8C&$AlbJtLJVZHXSe~Mm4)hyQ6UiD7+^bzO-m%D~>Er*E_WL64-(X zoWTk1Icp&vY%(UDrYaJFRd^S(PFHNxN-Un8uD1�$VVFGdMxSYkNB}PZ*QuRvjb) ztME=P*wNUwqxi5oU4MPIleEVR6F7qt?54Uz#fqvXWN%nYiNGqn-wUE27Nf+OWzf0~ zA35HWi1$F^{BbaMo;yNhR5l??VUCV1n85ol;e2XksMs+fL!Vs_R{c<3JFLQ)^K`nK zPX-8w#wNsLTs0{}9wz>0SD0U4VIG>UU-7DzL|~Pi8!%yPA8~4xF*#vmCT04=1m1-P zeaRizRh*lyZ*{t%L|_$eY1mbK*Gt$PGbWzxZ3MPp0`HB}=|)xUBwS2P$Z^va5`k6n z9rQXsPK-EVOd>v&NOusoG~PQ3Phz`CV*Ao`eWmR499uAf^ZCK~a1}$u?rdX{b*NAx zuu9&O`p@1FQ8+qX|K&n~^oK&Pvz6$!W=OP7C}sAkIGur=EVD zDY~3BCL0HDk@AdU0)L4J`%AvXi#bEn^?7ywN(5HnES%6&?}!&hi;c z4}hv0~-O41MAX zIOiAT&A=+0vje`C4UQLkDwvR8XR1lrJTQUJ;ei-{=}a*l?qGKCcPV2CR^eVDZzc)d;gSe&fnJh57qY>iZs0{tym5V91 zU_#CrR@7{oIFM;Vs_;W}zbLuQ6er4^V8ugnZV^l+Pie2J}}}u?MBo zlQ4mEiRpAN>rEEf+l|SA4ksi6tMExmkUO)^L{V*Fx_SNTmzqd<;_zt;IBOU946Xb{7+goGO+6_)7bfHrfjaH& zE6z+w*N-1qOCqoeXCH$%Dz?8^3!_@|WI4+iCh!SF+WPrmF=k?h{#REcDK8mT;Z}hB zgT;a3oVf`}U;k6euZ9VHE|N}X{Bg7hg%KyF>nn-CD!FwV6g3i|n~h16Z{4MwVfZ{5 ze0~k=rb=!p8bGbyaw?sRgU^=0+4*2Kyjoi^t)2<--{&S};ll(zr9!7`kk>(!g=Oe> z_HQQ;gry1D zaHq3$<@jplw%YT@UhIJPW21$qf-RW9c^hG$We;m{CMR7#5Y~P$fmJvgoKDxhRy|SB z#Dx5D^H=a)!zz5%56q)_*AOk@GW2We^jEM26F9dU?0fBAMfijFIzKHyBCtw6L+ICO zomkt{gj6&eu3!r$@L4uctFhnsmBDtzJ% zeD6G`l)r;{RMoR%6>PzToLTONSqY!D)0kLR8ZQx8g-^WE>8@?Q#@{-?lNdWu!4^#5 z^J`#jqO6cdp2^TxZxEtj3nt_|qb=&L<#~He$n=}jBm%4Oi8ngkvN4{#@zxA|!=bSX z&UlJXCc$}4A*TP&2!6e_37NblMv*M&OecIU5_~0;J(D{fOxGWL6(tc^g=+|FUQQ|e zN|7<)Pa~zgub7Ze>#>Yj$T!%SkOk8sBm%4CEAM)9dg05qF!Q>dAe~~4&o7xR<>6ga zt`4jznvlgi6BKO01U@eXb~+iYVPR)8^zGWn1Xf9{u5<4HgY|JTA-cEm(*3{$KKBLA zb-vt~pKEVIY_G*hgrq|EMyI>gOpBJ8Q5C@6iDtE@}~fd&rpV?GYixOK^+?=R4HtLh7aQmMvk# z$&Zw>nPUR)VS<$g=h?h0HA5e?JxU_53gO!nqwx}fRdVZ2E6L;M zJD89yuHjPa;ugg_BjCzI5AsgX`$T;Wk@ier0_S&!@9yl+@*HOqVzg?KL|_%(KLPsy z4*urzAntRnH$+z|ai6>&Y<^ zfmOJMI$g`sC%iF?=Sf%PeDs*W-_Stc{?9Gm;-E1pmjUODzCNhlfGnp=Mz^L|C13g7 zB6D#B;&4fEJ)~G4-u;K8co56@R8Kh9Hz7N+dP#ZQF@g6H>U85e))cE?JkN~mClOeM tTOB;)4#wiGoe3H8LC#>03B0=z&hnmILA(T?dROvL=?-EQzBfAE{{w?SD@p(W diff --git a/data/kuka_iiwa/meshes/coarse/link_6.stl b/data/kuka_iiwa/meshes/coarse/link_6.stl deleted file mode 100644 index bce349eb2ea1be41398d418f74eb7cbd4f9d4f1c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 164284 zcmb@vbzBxp|Np->SSX03wAf%^aqa9VAxJ3(V7G{f-HqLy*xlV+J3DrFcXzkv9P2mB zea`)Pjpz3J*Ux|42d~$2-?O{3yR$RznX5;aPAP4@I;C_@ZBfPR|A&7U^DD}cDcOwT z{VLJxt19vM^ZD43*$L!iopPkI*lzeRfw;^qM=GZ0W7nT1kfiD5h@uRR-OA?eEJqvd z3g(VYo!PE&QDpWMUy{__iCvo-MGB1eB@sPbS>E0eg#Yvs#D&M{%x`XK8W^DQuq7UB zrB5hP1{5Q{V*A<1P-1_y7%3a-!E8o^k}AiG3F36!k!r`v9`sbz+Puj96!zv~hT1vL zK=tjt6t+I!0`&#QH9T+Hx0@rQGU#(apPwjI_Q*W+bpL32WcM87WKUaSld}=Aiw`6lyV{bEUy{fl zwF60A#g^pn*ofGy3KYcRhOIR_Yc1N=+ld$V%uD)DP9keR29VUhY)RO(BogvDfY^Mo zCHXcck$DA7;taX0W^*n1gTX`++&kB+wc^i@?j%7*962fKMkPLAy`wOw|w!+c_-RXt(QT)e+ zLZn)c`o#8FX_DH&o;0x3BN<0ak%nTs%dmKoUcHov@gq4uE4t5(7WpfRqk=@aN)9Ar zR6NNZWD@%W>syZOcBT72MDr8(Q%K?Zf9Z?r8+yqHDP+flk9yb7d-U_8Qpv8VANAgE z_vngp)AA)VkB2i2dJ@aSzXy_DJqY{U$ByO8UXu7`3uSx8Ij~AON)Qhvlsy~oz(g%+ z>0!O$?o9s>1S&}Q3u5rrPvFh&9CrTgR_)r5-<{`Lb=PY-gA#`z}%TuPN+ujgNW(wnwk_ zErr<){!4f7V~FGUw09@j+}VK+x2en5cXwqKJ4BPS0e<9!*nTGNl}+Ma2~pixlbKPZ z^>ANtuJ)!MU@cz+(Cc-pbG(c2?y41Dlyy56O@@vzYvPG-GnltthK9XSd5DueyX9V& zgxi)RTN>Ik?PeXa<6;T&N4X+w>)ARa+rtuqNG(x-Oe^n3eLF<+7D^%Z=cD?hpKlpb zRBU%>RG<9COOrBd3bCYC^~s){r3I0%p}lc2xH4T|xB|x~06rP2AIZ!1EKMX80|Er` zsZ?pc>n)*gJ8UC&>}=VUMvX}B`GKULi!IaYHX?au1d`8gwk%O>Tg0|_mJBY%uMMKK zNHszAYRe3IsW$b0@zp>DiIMwk zS=8zz;%Z|OyGyS$@~(=eH@|1+NTAF5-j>Z;l|*jYn#9z+(+y9%aGLS9Fh>Q6wKemy zDkYOh@&dD7%{$)OP{)PPgzoMVfv$Cen39r2vRyF=+gX7|mz*k1axKYGL867IyTg4YjRt_!2Q9(k!2k&&tW~AE( z(J^+FBm!M>sXmvy$Xp(kr{R88IVwotJ+CM=LaVXF_N8d#Y$_4x8XuUSr9Vm_=jND4 z-tog)=57~2+Yb%qs33u@4@L34*OFa3REkz{q7s3wQn&N7*ro|2zN8uBz?>uO@z(%) zIj68py4u{I$MNR2LK1hJ`uC)pR~N)Hx@;rRB#w^}9f zeq=T4ktfH^c1a)atL(jJd76BtD#x{(a?vcIDl zBk->Ry7PT+>K<21BG85Jc}0mhK88gvC{2BwG^quEM9o(PSwNfm#DAOF0-%#`>iKW^ z(L;MeB?4V|rp3Fq-5Pd{mZK|cSvV?4P|@O;UaKBib;7(JSC(h!eUJIl`kTWf0$uVI zJQ|j!yR7%2=azV zN=AFqcT`c@Yib-v1&KTXMcB{uqhn6Bp zD~eilKFj#44DG&1<)|QmZ97F7vcX2*zs{Sk=wC}B&?T2@Q@J3 z7vlc@dL;0w6IC|FN?)l+uqMvzdxKa~d|z=Zq6sml2|XA zIxB*sg2d%^1HR0XR~9ie62TC2G`=~YUdfquH3Cayn5IXnW!-*BzVy~ zFFLPC1V;slKUxJd)#^(w=E^BzRGe_Z^4`{q);%Q?=(1ZuShDU*?&dTJ?-$>ymz(WH z=QoSss337FKAepy;7abb`$P0hJfC>7dhbzQ)FCy3qk=@h;1FgV=R&s4{33`Jv&!rl z+uMsi>LU~AN==Joc7+_tj<#U|=DqpNV|NS0o-5P8<|sVWn1=sL?` zQA^SaMRHV-SoAQK4Qi8zIQ70RVyv6#7<}H{i@xL$5`nJf@9MJaf^g0v3J-0swr=Y| z7dzJG*uR7QJ{J>Ovwe^EstFA`7ok7blDrF&5n%Wtm&plh&RQ z$x%T9uZ^O3O=xKyG~AQ^SzRX3WgF6o)z7^^Jv+|qxeMxd#WM4%2Tj@=$x%T9`v4W? zYic8_cT-QA&`2iGHREJ&c08tzI$AF+V)T7G!}9FB2R(c!lB0q|i>f`@s1~v6k+P)( zp?11vO-S*i-D70}U6mU3VF$e;)nvQkg6Nqm+VbqK2Q6id?54b>7j#e-)58p%;X;+^LZHs?xzOCh^f zf+*^9%$jSR2c7d!CeSt8YdG6D%h;V(*E$|Fv7AhxYfHo7Y}W&OYlZTg1<`u#=-?T}Jt(PDo1=on@EpU~z-BJi zGg~tSakkDr>x`ep=-O17Kvy595iC!q?0VuY!>TB?cWtTOdRH;JdPQxH3KG}%4`b)& z=hWA=+%Jf(_xD*>(qeQ;wkU}}SF+o1_US|m-PNO{t|(KsT-x)hP%+xEL=;B_iQz^% z+qbr*e*LmZB)wi~owwYb*6%M9=*m%G7~64fsQzcI5J5CpJ0Q3LbElRLQ5+Q{E^Hpk zCY%|nC&ih>g);-K^cfMR z#Bn?n$AJX8Ij)E+P3RgU5$JN6n#ekNIkAQt9|y3*UXdA~-LE=jeS2mNy zuuB_FqHPXe^+a748u2qmBGBa=P=YnzRD;z$Rag*e?<1Dho1JO9ez6=CB>D;BS?5sJ z;+i>*V;$w97C+%avo9BC7xsm&lEVU7;=N!NIKF@&+=|Y(%zNQXU&O|8RFGJIyb`-I zBA6W({c)nT^gW0A;I<2OofRVy=*nB6Dr+7d#Fi|z5k%c?lPzDvUFhPxu^bg7+TRam z!688`_ezr(nEjjObvajhqH&Bwplj+NF?zMR6bm?_2;z39;+9)|U8uvO7>)`O-DX9w zyZK77Np(!(Nbdudk#VB7hsp%H{$;&M&II`(#7LFTq1o}KbF$JMqvw^L8va;ARq zu^bg7#uTw-$(!R@jiM&8dwN6Fa?^?aStw2-(3Nl~7pwoF0h`mwOAsUOPg3j5bD}Yp zI6ma=-Lu2%ihoM^YCIF1Su zn*<_r&6zsQi(yLJQ}s-8(wbEluM%DoDH^ zwMy@4)0X`?-XwZ-U8pu{>P)|{iIoU+z1VS7pEXP9^gVZ>V3KDa6 z9@Ud3v|#>oN(f^3nVIU870xuOSFA*!>tnk!dh(&B?AX%cg2)#)Ono-TiTctwjtUYj zI=#?G+-S@eruzxv>(Vjm%mvPL#GqJ-kX)jc96wW!ExK;jt3Q{tS67}C*W4|RE1)1D z*Q-}CL)Ahro$0`^ScyQ_y?r*U*ZFu>EWnJBICPNu>5emH;(3J%5?GHFW!IoFdj0?x z`nGT^$I)pVwSJxYUiD5+WOliIM2yWN+Uet0iECaZj-!HvL-)68-+YbP@Q=QNn0#cs z-gLL9S1GX)fv(~8j;ec7nlbxa<~4U7JWPMQ-idZBAIDKaBA+1qSG8dM)|uCQ;m)~w zDs!e+TE|KRx_sMgRa=g4$(&qE3S#2@iF(EEPIO(PIF1SuwHIwtue-Kk=RTGaM7!pT z^@2T|>G3(S5`nJV{YR=UZ`!gP$IRM3;KY1=<7g*ZAtH{Wg2eQGBh~#L$*gBv^Bz3= zb%TCvxHFwUHdZ3g)w^XAwQfi(|uR#b)%ft{(3fTJHbs$a;M-i8gncKHkoWM$d`ks35_UCtEUVrLpQW0tL~b z-FUsacqV=l&qO59wa0G8+8z5+*+B8ERFwG{4tlJ;6Fspyj-!Ia;193M4tT7kZ>vEVs3BA{Ruf$WFA1;&@S#E?P?$MQcgU{m9-UMBjhc ziJmVQ$5BC|Ua5jaHR9RwispS@e{@Uzbunjp;7+VWpbPIu(aOlT*y``+LU;Ja@>2_f zNtISXET?Y6Fau_=$YHs1p$6;x)NEg^`hMIRRLq6Ol#J!5Ac5I1;+xYbuNTSTO851R zkqC6HY2;1(9KxAl>nLJ;pL5aLC5H=bVTt9aAR%Yg9DMGtcbMx!w;YX;2z23D7h}TV z2dv($o$1JJ^7TMsMh;hUUbIDRHkobFV^=;{m!EN>&phI!D~K+JDZS)1qw3t>lHyXc={mtLtR(8 zHY7$O(6yvjGWp&y8(Vtzpdj{)a_)3?j^?N!F>PH3a(41ZU3qVQ38&rq61?P) zE3N%pCeVdhZ;JBd#gNQFUT(C`3OOGR3CxWXBR?NkSzk?Yqp5Mx92F$miEO&^SKsQY z=PpsInSXT8bS&*gm4z~aE;;9}d1VLdt#~&&Xo&cthip6~at%u*mma^+%QxR9V%QkI zmM^w$RNW~P=yK@Oi)7z%PS4kDks!|6)y-@@$&Gf3kLIW#QA6oVwi%iFyW?h`%=*&9 zEQLn7(b9=Bfv!Q-hmaY)m+Oi3`w1df=+f%M*`02F62(zLVqN*6WY+oddT^`yf+)0a zvZYHocRKU3OrR^L!!WYhFI_Kr-0bm+{?dN;vFYwKWlR)D1&P@0L&<6Hbp6yBlX$my zoaO2`cRFK|OrR_0iD9I`+BCiS?TUg3pX3)j`m#IS(?AfQAn~!uFp}Aw=nDoG5X7Z1 zTP&|_MDJi(nLwAn?Fi!LT2#L|^Oop={9JT+u+qC2-Ey@yM+FJ*4a102wL{jZN)rXq z%xi;X_VHr0?@XCMSNr+H$qC11)~$`~1uic_n_IROrWd1?Ql~0`Qyxc*9QvX_Ul}k6)YaKwk8NrkmwhlP8!_4xa-Zf zGu0Kvv*i-Yn9&}zY&MxdmsittvQMdLai3brBEBYEiv;^+c+i0#A~`BZv_3n4yhyrZ z`SF|yA}oEqB~NZontg#xpliT}ex$KpPTl2QNEMlY0~0c{?Z>Ox zU$qu7reEl88PdU%wyq-+=z1V>t1BK`qb_?mRuD(qx3g{)J^AV;fjQCFXwEQs04 zf@*t3E!ih(2@>eSY<%&An;2{PIogxL7Wr>Do9{G7GFiz=2(l1*#lMA%LKaQ*#la1!Qgx=z37s7xh58Q8caqk@+G@p zjoR$rFyy>Fs^8JBC?1kzgSG+j6S2h<>l!h0kS!c$1(NeQz0$uJ;tC9ls z%aB>Vc?GfW(8l2G`MhavMT{bYf<(rXs>Hr!39{!yZb9_febeeEYI~alGJ&pDH-pH7 zI)S7>lLCU^kNa94j`OD0*|j(-NSr?vK)N3gc^S>kyo_c&S6RpQ^`Zg2A|wJ`juR@9 ze1|I#nS}vmI=WssN0+^?4{7(1l4X}%iA)q;-$fmA+?S5q5ynwL;_5XIGBG%m zG@WG5mC;kf^f$LWX^oc=5`nJLH$2FeowZ1d=4MV&3u_y-)jnUE(+K0JAmLWgjjVfH zi!_;O5;bB5=o7?<`vP&FBZ01gi#>?br&^@&RFj~+C#m&n`q7zjVH_1C8n1UH1Nue~ zpPb%;aILdizmV)fr`Xn(2y`WEbR~64M3YN@n)4>wpSr2XRVhXTU)JWRAmQumN^Flr zlX)ViOpHO^?x6h7nkmvk#oPAWE+_M;cv$wWHpeyHAXHrFEp-mQ9Xd=_; z(;hw7h+?$G?%Es`BubBQBDb=~5n9(@5L&HV`um%nH2Q4>M+FI-l_dH_9Ya|zPZzrJ zM2tkBtBsh)RPbsX8S~SO(ZAs_>tBVvXkL*`g$fcl3rgfIrDdu+7yHpRpF$-9T`l76 zNyCqI$i_EjUfZ65-C1`47O^HC4T&nVyz62*4-ZZ9jEshEj^4uleDNS#A z%7cdQkCX^>;W-rJQCIV6$14ZXrJXDCHlJ-t`L0PM_(p&B;>hdIajtNW8aseKb~t6fv&Q33y|t!UfGEvWkrl?d*7+&V*F`~0U;a}Byc90 zqSTtwjT{OtP1j{;5`iwPJtDJTIjx=_Q=CpL8!FW+Byi@N=tEYPT6UE2p@oaok_dER z9TV-V)w$@8tFiRvjHw3B;q&fhONta}MDDf>Bsk|!j2q;9qWzd0PrrQJADU(WeH*WP>9q2+(-5`iw9ODOso?(fxd)vHUtX52SWK|-ECxUBLZY;T|y%s7Mg#4DTzQA-Yeq!yqE*I)y|#v>K!Fz z6=NnbX67o2&*ne%!7cr%O@|PU3KH^6*1bL3sj+K4X{ zI4VfU8NY=;EmS9^d(eO{krIKfRf|2ClWhcfveK04s$~}Do9|4v1peZ zJ*e)^?m_3*t1S`evis`I!bgXa7l+MO#)8C5{liZ`s;vm+s33uJd&L)IeP{Jnuotbe zT;#pNzR-mk&0>aI(q%m{rZ^qfEL6&MMq>IpZ|3`*l2b3t_Eo~xHhN%tUwX_oTq4kg zdC!V+FYP1C&nwW|8!PkYwnf+x=QuK`oj(Z|+5G+=V#)nl{-l!F&hHvW^0qbKoKp+D zWmhItpxT$p92F$wyzsn}MzWE+O4H*unna-MnaGGgn?H_p>}AFn*D{CNEY6b_XdTH> zK?3v86{VBsYT^=SPqXKW=cw#y;l#4J#gSoc{0Z(!QLZ0fLGE?2r>8#Fm0}*3YFvY&a<2_lmm6(n$8fXI_+J)KQ$TZS5;L?Y0I*Gc3j zZkf%(kCma@uB*}&L;~l*DoU?eUrQ*;P+ooIWDQmm<=>&h7Km`et`kVeG#xKNwU1m&^Fv}pvfPJZO z94Zjv`y7uP6(sPC{GLEp<5W9;vsC8aWC9f=ptQdn2NLKKrOi6KW=Z83s30M>vk3EV zG69Nio=LOp=3Zb=zmy6UB*Zag(f_{YNT6%%ssjIZiNE*szf1LB0$qP!oBt656(s&H)&Gcr1iJn{ z^8X#~jI=x)+ z%Ap4mF`{$-DJ&WcaKe`isKD$p?pq z;_ZwvP(k8YM@_H0XaxE3F7X!v6(j;4x$2SM#At&@gZ~GCF56t?^{;nEkk!4!ngCL% zE*)REYGujcq*YWR$zE6S?>>1HsWho6nZBu+wQ}Ha^7vfBF9a$`+<4Ee=@FyI`uHaQ z4+33SLb+6^AmMpEyMAr$NV3bm@h>ruK-ce&{CXK(@A|quD_OG~yRNL)AI<8(vPT9m z%zBecg$fdXwC$<)+?vMpZWY+?33Orho=l*E#JWcb`lw5tSxV80zr;WSU3lNfF;GFG z@vT6;@U*Yf&^yo{hmNq$D@DfgPfZ)*2K&s!+Q`F zBrtpL_XN89s(#bk&S}O%a{n4bQXnf3v-ji}NT4f6X?K?NI-Y%dYGw%GaiD^PoC)|l z0$rFjE62du6*!yY;Iom;V?!r>bc0HwU4k*nd5>nL?Dtr=IE=F9Z8e&`Ed0oNYvyVz z&Nq<>RFF85do**L>8o$I{UpYOF$NOo!V<~^DoC{4If^|FucPOj=KjlZAc3ymA35gc zM`bi;tMfavjmMwpQx7&~#jm+D8{0R(#K3u?IODXEZxy!XOjY83-GTga9Pnnzn`5p1 z&2KQ-m?w_ln@A>5LE_7Z^?Kx#LFDq7*k58Gfv&GjZ|mjicO=i&lV1o_kht;Ss{T2$ z2Z=ry_6vdM3eOMDR*;Va6(stTM0RGj7yGgD<1c3y33Oo=yBq@*BtB)-W}bxuSxP`I z_Im}P5W%X`Pn9mJ;(66nI`u}qx3G@O00Waw3IchrZ@8qTJ-TA&B*?xN$oGMPXHiRJ0T zS&r0&dZ+kqztnal(1r8LSiRZ1a;6IAkh0$uJ!ZP=^^jmgdS<$obiL89`Gyi9A;l2rZ~^#35x zg=?Y7r9uS>T>nfa@O_SNGORr^feI2Av=MAuj+wgW`PRSG5+u-tcYz!O+YI<_-`R8& zt9|EiX0s+OM8+1@5>$}DnX|tq(1r7PWdds=*1nn*qgc=G9^|303~aGP4Xety zLlrWohdsd-j!d9}#G5_U+2`;|WnZ~v%(`s1qmGg`aOXzc^n60V9Nr}TZ{a| zSxJXumcd8Y{L;!m1qocGLM{~&=vopwlvUnTQZ?@6Rb>JdByhEj-xKJH`P`3n&eu=< zJUZ%^7^onDtA@xikU-bC-96dorL)w5Ha&ldfnTP$-V#3ZTk2~==RK#VODs33u> z7XF?<7p{^h6Syj{v|8wITgcePMFQ6|m17`*E?hrVCa}FT?tLm7)o8yuZtr~c_iZ0k zkeGBTjU9L0quxoL`O6)J1iEm|D!EjsAo2UV7729WnniL9RFJ@@giPR_ia8Tldt?F? zBrr$g_XN6d{X3b!8i#9`Vr-c}1qoa~_4fq2u)fIzDoEgpw7)0Nh4+n2V6DdWkTJGQ zpn?Rh*!+6}UAT_4OrU}*T4QXPKm`e0bNlxMx_=Af`mCBf;jm$_{o$A1XZ`8l+8Ns~kc33C+r?|cRk!z|6u=+-68(jkE^bK8tzmO-rY zFOK-=orIF+89)VzbAFhSVxHBpsnI3Pvy23~&iVQJn=#BYZpO%|l|58Ci$Dblu_yii zjzg46D=^(Lt5is!%iR9I;}A!#*(4k*VIDauNQg6%6~jC;iXzS~4SGJcgn4$6K$p4w zf7e4eX}v2w{LSlv3KHV1X2lSD6fs0;Xna_wmF9Ip0$t{|8RI{MxDM1S=hRi^bwLFQ zaaOZp{3lOFTn8F5@TeeiN(8#hZ8JurwtwFrbbVFF)#i0U1qq0!XWbvPWUtbK7$Fhp zg3=1YJaTb=tTwL;DoDV26NGto#r?6`ye>$f3(lb+OsBX%R+}U$NWk?MgjpJKf2=l3 zhXlIJ?Z4}lAj~5c_s44Ux}buD(h9SX%(E))kJaXNK|*r1^8V-k$cmBE5cfwGp`Zf$ z6?;^*Aer`DRd*zg}ASUMF3?GV9ZIg#oPWGF9COxXO{^Mmn|5B`tk+T=_D=1PyD?BlyF>aDT`^%4#v*t~J|)M6D%i6f7H)t%?LUdu3M4>mry z4q}&A%+=3VyP!91l+OAtT%_krT&5rWoX*;}4AVdDIx2|w2V;1R%kK>PY0SXUx1co* zSg{+9Y)8$43`fiq<{qwPG|Z4h*Vcr+$?$~davrpLnbaK`p~0V_@@wN)`ldHb!yq@ z@T_fz*oErhkVqCeb`-hP#O$q|U2y>Kzq$+YbyW@5A@NzRZl|2|W0t?Shq~)cXEtEP zAC4!nlM0LDc#+tRzcU(lVu5%nH7(dQPfm9?GdHBX-s9LXNJO(ee4<_qG< z&c?ile+pSka`Hi5)w5joap(17wn16jGnU@h?>r4+$8Ss`N!6YS!al4wx9uCGWvp*# ztj~yJwTF4DQx^AS-;c(z%dgzBw(YLQv$PX7s(;Mt@eW0KRkph8}soRKeih`2UcPYioMeZoKI%A zr~-hmS=)1Amvwvv@;(Cfj`@Bzm1hpbO84Sf%-Becp`yFhZt}l+G0rY1b;S z`PMss$M{Q$KYiv|gF-As*RHJyt69b@*ye*D$M z7kaUtt&NLi8ZwXXJ2PLgG*--^9y@m=VYgXJyd3MX(2EIHb6ez|x9rIm?c2*Dc1@88 zbYVP2aU9T_7j9~66!7V4pn}Bh_`1xy`TM_Pe7x9`59Ae%MfbW$1iIwo$aA?DAGq`y z*<5&pfp-qxQFwf!?mp_vZxqZRrLW3Ij)YRU9^3i0vE@HUzJ6Ih-a1E1^-hXRpbO8N zSXJd#SH7#$Ol`1Zd1L*iC^ocD8`a!bw^7mTePY9`?d^VHta$ufwQ7KQc8@M@!#mBn ztfhRj7?&;tG53u(RJ+gJS=Vhf+2cFQ{|6EBA%&mntZTN@0u9_368pD@ve4dhvuH6Z z{$Ls(UUIc&Jd_D^VQCem@UZ%vHnyS09~NUr*Rt%ypm$mOsvcL7wXAw4Ya2@|&aP)7 zpF1x*%~&WO2NJ_FDzklWFaBLB*EP-f`ns>RxZ^T`E<7f&R(`nn8Fm97KkxVY>%TYn1Tvg93nl>_XKWrmaK4^Xd z@qSZQBG6^-$$S${2{U6C> z^+J7EyFr%Ha9O&=+V4Nxp)*3Ox4E6fPK+H#20XbKtSD<+4&j}yjwj{HwbfBUqWQxA z&{zH{FW$A&rVr*zlnF#Fw47iJq}R}TS+RqCbE~37c5fixGn5e<4@E--i4~&7@nGv1 zGBPSu5E~El=VNT<6S`HC2z2#dQ8z2b^vOPga1HIsom*TcC(>4H_}<3%Inv@ccpCQP zZ(7YK4Yy6#P(h+ubWBzZ-veDlj6B2p^2Z+Y$xELUi9nZJs*@u_c(vheAeu zZMZ**w9M~HHbuI#`@P4I($Ox&cR&z36gh&Fj{8f*7+o`jUysVIeTes^s37tEoEyuw zZWbw>UW6!0&ekD3wCyQ!c8;G!pv!!7n)PZ@nEA^N!SibKst?zYk`3J{Dy83+&2sH- z_J@kG#T#c;J?=Jc4f*=aPKtrVA9G^|(=sS1%r*C0N`jDo9{FvF?X= z4SxSy4efggv3>&V3tiX~Ce{mYTZd;~8>dZunxEn*`;rCKS&d6o#EfM-f+ORKQY1$b zUpzTNJDg3Ss31{gXC2nRP)*Wi*eP*#UF)^rfyHZTOF%&AEOX4HYD?w_f}P zXycyTrAuXP-;7=ofi4_F5G$*$9KaoSza-sq*lPu2N3snK9$2E3hE^O!#xYiLc5e>k z%iA9zE$;qF(1kRPD2q1S(Lp?}C?}d5Bd8z|v~m=4dz#ZSqwjq2Z13YUnCERikqn7A zE)nRGN2+hV8Nw6i#OnQ@%~bJQ4ZqJY`&Y~+H@b25Zm{vPUQ+|}GVm)EGcH8i=Z~(u zwM$PU<7iI<6(sO`SFEd6zccUXFxJ>rWw1n`3o|Z6yM16PUteQ}kxb`Fn>Z(#s{_HdDj|- zUHjPvWpezK|3wBWNG!5XVdbokbe@_+v@$+! zY|3v(9x=QtuapRM$vG2^PBiAF=bbdNZCzuaf&}IZE6U?T3EW>hV|-LI4eVRMK8F&i zZCLc!qk0+5Qu!ePW=3L=*8#O(mO$vatc~qExr;`}1$P-1w@^&m;m}m;)V4dkTiE za$}Lh9N6TPPQUa4gzPQD(=IsiRnH$tU-U?{Sm(xq?VQBL-wjk8w!5+IQ9jIOY$NvaWhwSaDZv8n))d5| zcD{VmbVu%7SK+82G2x6Gvu_%}Zaj$+#0|xlp9w0;|8$TEbX9uj#+G)j%4$BPg2+9p zDWAOYs5ZLA3PYRFh-qn4)XmA1HTSN`65AbDt$CZUVyEh`V>{-klkFP_;zgH6yt3y5 z?MIhs1}aEU-|FmC?~7{gyyo|LVcTZhcm73f^ahzg*U6n>jMQ4EMi=fNhy!aHanB*I zwMjMu3{;Sizq|_9ZOQvTyr8waI8Y+cRjx<`TkJhe{pQt8#3<_3mMej$wb^A83{;T7 zFH6zm^(u|;e>zor?ABEx(1l;&;@6;Ni(a*I!?krm3DWmD68KfDDD`}L@!T2FTGbs5 zB?4X8ccv&i#qVsl>Xes$oi^3z@hO7Q{YTWuK2a?1(~9iR+~3sByBaXNUV&`kmOs_e z!_1o4ZHvmA4lYJ#RGMr&60PlHaYc!q*qoW$eit2ye`E`Z7QaiDDTt;Xw1e+>1NV!B zx&3oX5%OfH86#y~P2O*w3w={^sO7iB~9nL))=wxm4TnykR{SzX9r9mzPS( zPU|+CVxWQqmR310j|+Q6 z#0oSw2Jt?AXV}jw%Nh2VAhrycWEpFi+3Lfd z599-!&yhD}UP}bJCSDlE?k}sZj;g&%5dH4==PAQHwA<%?GE|Uwk!={etMyXb*~}5d zx|03))7+(v@11=N9FM?J2YGCwOu+%Xt4B_w$(W)BDoEftRFp$L1Nk4t#<4NPS0d2m zUT-A3yEDIa>&KO%RF>6)_~^&M`l&s(1}aG4IaHKJxd!qLzP-uqZzUxHT{d@zvBCj4 z)xY*yMU2wd`}3X+Uy|n={S8!*z;h^`SB-n|=OZjyzTzz<0$m$=_ha?W%}{NZTo*AK z$MoW_9@f`tG>9@#K|;PBiwbn(7uOEa3e`!L2z2!d@5KiEII6Bo+b?1SCy6Wg%vM`9 zDp(rF!Lb|pt0@2Semw6OAFXB;4-FM0aP&;9f8{lRKb!BY{gvY}U)g(TXdCkAkv zisdx>PeTbRNXR2`%hLw&8aH!m>o?bv2z22$mFP8in8thmF;?yLUN`boXvA3Ajg}ha zTCkVpIgiB{Wv}k`ex!)cG6(q(S?Zalol+dKGI*=+sVZ<9ozYeAjf?B&)N%bmi`f~ZuZ8*j4biCT5-S_2g%lFkia zCv(PG7Hv0UEW6d2FQ0se%G<39JZwWw_ujMx-vU*F&lZC8Nn8=t;4jQ7uEg|=B)S^=cBm$(T^H&-EW|R#O{%? z?8w?vYP%KH1+i^H1Kz5^8Et{%L5VmWf?p46J({V-L_HdL1gbe(SAi3R^Gt=711{*K9(JMDP?{Qb4&eXRy6 zNR-N!%svzhRO1$z>rD9X?Z`_9_-genGJ&p3qPM} zpn}ABhbC-6g%~yCNQ@w|`=|0g2}QI%@w!By>q+)DEPUxH%h;CTg2+`Qg%|d3u62mo zZlEF&w_@3_qUmZK+jfE&F}ow*XVlfYw%;rfPr%i2c>{L%aar-ZmaPS$xVPoiW~|pv zFP~?4&uq$e-wq;NS*~ZqG-tP}7bb@XJ<|0;otfpw4>f$3xkmi_GA;S0k(;%(-Wv>5 zkcbXz%Z7INq~7gp&ieIrYtNIeuF!V)&6Wss$MJ#y&`ky^Nc6sy%(mq_ zu6C?p&dBvTn#?VUGqr0U7f1xU@J%FgaVm7+U2~7qHmq79y>XD(zM&ucUSWXhSMQ}b z4&JXDFT1#|X0MHs2z22aRs2fjhMqhvkB4@&{7~u5iNs;iE_oKa-ST7FB@tufn0`F7 z)nYO~FhL^Fg)IX`86)0mJ$CI?e++FUw*X+jg}M%Be{An>-I8X`uKA-|e?ItR9p=3) zRwB@aEgaFO@7R|+_CCf&?@X3jGDyhTA_Y(O;pKJ}Gpad9O9Z+wCq&ftlf8KI3C-Y% z4W(=mB(N7x{IWy0-u&2#dd5ocAc;U1&YTrvkdu4zV|qJduv55!3KH1Qs3^tyR^@Mp zKhW}L*k)z#e1BMhggmokeXG45T9Q1!7|M1yRbiitc#~6x`Se-hT%9*@ex`lMo{OVm zemng`JnU1I^?%_&RA&C#&4nNPR|VT3#Gv7xU&o% zj&$yWh5w524}o9d;`dVbNARKdbJ2m*Hc14!@C~OZrN+eaZj^}E*QTuE+)j$Oa?4=UK<`n+iQXXQZ6}xN#|_`w+JH_U2omVRuNOthJGCz_*0+mhmmVi&8zS*| zeQ&nwz@KXA;2h$O^JR5k-sy5Tt?0%(D((win5!sO3*Fe2cP><3yD@K;hO>5T5<0TV z^`5C4zE4)=QL-~ldh#P*sn(%snuZDzE`M}oY5QzR?I8=r*j92<>G|h(w?Z z&zs2W8{C(>C$!Z5oOqm|f`ngGS7upSgbX`!LY&>+efsidYujs)i5n#XU3lIU#W>Z6 zJ9itZt*m0FqJqR!y%XCz-II*7%_h#SQ`tWJr8ZLQ_2h{a33TC^7SF`l1Nh)#MYUWh zkJ+K6t=NexV#VkCkrvEJyb#-zT~2I4-t@~OVpQzZhesE7*Cq|AZ=iz2!Kei0ccu+# zKE~|D*_7FXpRd?SyS67*BG6?CY|q}dFHKfPv=_v}PD6N`(>>VnUf*==fx@^bO zoF9j9`)-r<@?B3`Q9%Mn7sVAkGK6=SpM#8eaal(KUD#_R@^?j#*ZBt9NaPu-jtUZ+ z`;TO~%jQ!vZq^XTQGD<~ezlmRwl8xbLjqmcuOWV?`b|F`Q>T_zch@0?3KBEt4Q00v z%vJAQpCDr73hK#oP8pyDbSZBjfi7%0ivc&$(65>g8pi94GZQ}KKi9i>A0f=AiY14&!yqT}v$X7*b=_4Uu^WM&>eD;WCTBFuoBm!Od zT_UohlRNXBmWf*Az8=yS3ldnz#1~{(BEO$HPKzz@*1#NU%&qP?iM5_;6Ir?Rwf+GE4lT z9L5&EOd3>&ce(zVjP-SpN`-`cJw`Te$tP1MZRhsq2JQ=8^0_+V(uyC=*Hx<%cF{lu z3B3Lyzr8x;XJ+@(tjvR(nNH1qG$-9s{2104^Y0&v_aaXp786I_H!_+}>C{>~^tMnI z@sEN8#uK?}=R}53LPah6S5JvRml@;d?0&>`mN~-f(j$~ROfII~oaU89{G%X&=S_^O zP1g84&oSEEv+mMynDY%hRwa>!?j@vS62HBis`2v51Z}&QJIAskVQvq)o=DPqn7too z?ZbKE=S5n=fP()b{&C4O6oyn&`5n7uTHdlQ92MNJxxG4XEmGdb{3<%}*1}Jm*{-$k zUF2WHKQ5E_XFi3<9C%Wj-`o_hJ#AM+%5=i)EzDsO^NPgpw=X)RYS$wjC@M%`E|wsM zH00}y%G%z2xg-Kzn2{t#W$L!zt=D;I>pH#CP(eb@Zridim7lp*QhRfHyF{Q1bC?t* z;8b^RJG_Y2EozE}3KE#Ns3>!0_2W0{`e<|adP)Skuw|eq<*y9n9Xr`->szcKs33t^ znqpMu;UGSK&M@`18N^%W?@Hpk*cnKm z3uj=6Ux{fngs++SLmiPgoZu`G%vHj7yZD78We7iLbR>&9j3uZbA@|Tf%Qb{I9kYSl z?z~P#0$uoS7xP$F4C1YG=G8KKP!$yy$ zZmE?M_b@6*$gS}F$9r=dGED2>vQQ$>h3|IpD>0*c^L|CgXpQSsW~d+`w?&8RJ$TNR z)3xV)E=UBr@ZBzYqeM&p$EvBCHh(8W1qp2XDoXVWJ-Ox3aP0;!U?71mY}G2t!|Z)| z`qJ*2HQP*v3KG~N7o(Q#`tw(B>uQsoN=O8{@V-%$r|0_dp0kp)#m}2dcN7x%Wg)(6 z+xO#p9BXR9o4!i~y72xNUtUvt@sCYvYOz6y(tVBuej$l@6ZN|BqaQ13S7uI?2z1F= zldZdU;hEbjXvudMXs958-*DoWl;b<|oG%8c^Ur2VBUpV_H(`TUg;n!QXey0nDT-aa zG;Y{bU`uxx298=G@zu8}Tl8_AwZC}Yi2n9$op|@LTiJ=)`y>Kg#{=82&z|=B;mj~W z+Cq*aoNYL6PFsHI@HXRZwJB1bC1zt{ z2BpX~*wmhnNndFMoSSB#f&|7^lu@i5uef=ck$=@Zi9i=-P>OHoK5hAuatjO^y2d~S z3Hdm7Uv0)$-q>wiX|Y)%&?RSPwr!fktEHSa-fr1upn?QuX)22KMFZ}5G*jylaoND} zp&aMqSd*6pNx_K1499fDF9W63;p3C{YoRk98mJ&qyJtMBU*W477~v-B?$_c8+%{#m zW=*{y5$M7(9g(+mIf3suyj^oVaKS(Y3AIcIHgUpEbqEnPW%R88A(W4c733rB$zrHW$@ z9%z?K3n($oKn00>5OBm!MHrX%JXwCv5p9X{`A zYd_vV1&LQLhqAC5Q>}0Mz7jERj_J)E+RS3vca4w;bm5qe7!!8y$>$He&z!nVHc&z0 zpvz#Urm6bmJ?3$2tI?hR_)ykZ#_4{Cq6&DhcURDOrQ(zE=36udEp6Vn;CVNu9BW5NbD`#k(D_fp{Euwzj3~$ zr10~}?Tk=$vqYc^pG1n%c1}ERR`HP5KhJdo>no1^V;xhJlO>b*SiVcEzwU&A3KEz_ zAZq*5*1Smh>6+VxJraQ~tYczKcuO*mupgkcdAY?v1qsY;5WmnJ(uL_8)!jZ`ApON&OSm!M@P(cE7G{giR+n)UYW9+QsvRK}~zls5NVPSwtTBr!@%%CV1 z0%8&dAff_-U^fN^c3@!~^_bX++`DUccVm0(R_tf?miv1?g9o4AAHLX^*XMm-GqW?Z zvoo`E4O?kOQcf%o2vlJmqEh1nxEAYmgt~v;(ormF89{0)Z;5 zV|>>6TdbC6^mS#{qZKMzkib1Nd|VP3qkUXfP4&F{mq4Hj>llw}RkW|>w6Bo*e8ol; zElA)fil=HplveG&rD~YFT_8|}wUU1eFey?CeEm#myIoV!f&`ADBHe1Yn@`W==Wu5=&_Y5T9Cl`IlepLL6la>WdI!>pDYll5@&>~ zFALYcJ()o>GByY^!bpg7eRiX|X(wx@Qr9cn1p-w#Ug2xoK^-)girZ<7%XMKSg9OfN z@wJH^KAQJ&l{T#TR3K1=qZ&zS+_{PNC~_}7Q^;IH3ljQ_m+90H{#45=YxOQ3ro)C7 z5eQW2*MXV!iDO&+{o|9Py*A3Jr1rt%z3>$Tj;Zk!2L2}OSx3vYu8?-m|E=()1rj*w z=WBO^8)*j@<}Uwdy%Aj)qS+ml`pBEYF!lw zRN;vQJg%j6fOdNJ8r66BMd5q~B=9YauRHsNYN;J3s6Jf}2?VO}WC2Nfy1SQ_+rde- z|FB<03ljJ?$#-mx?5lMPJFN5z*d`FD5>F6F42{v=|8>>i`)0dv5&{zVR?Np&=5gAl zS>D9&;!1%)mALM_y=JUdZjgaIe!oum3IYk-c`8YjzxLIf%T%C+YpfCoRNGwajz;LGc*g(zUJ9Oo9sU*?94_S2UN6wP;x^835JO5K!M6J9(3%jY1z#g1$v;07{4ll3JZy(Jx{4G@BZZST$k%AkLJg7F8RG-zUs zMfmHh6#aBD6M+^a^wYZZU-}h)@H9UuOFuR1uuH==NTAAe{mX}b8kc@D*O*~d^;8*u zOShP=v!d`pEIR$fFa7kdi7A!>p`Yo+{~1$ay8h)uKUIuVTFZ|QSEI#rt^444_+RwG zUnk1xri7$6iSl?iL77BiVc{RDo%LT#NR@d>H3!s{meG~p75O4 zM2qPf?njo7tkPw?bOj=-bd4(0^)DY;caTj;v9v{t>00-Zb^o(`WYrSJYl%Rh%5?q9 zM^;T_eOw#bqQ!Kr`@k5NzfO+SOE|EsyFj4IbZzpHM{iLqh!bcrU1#M(Z)sWi&})c( zPxMroRQhl6RQ*q7y8h)uuZ8+O(Q}R#({kk;=J^R^*~j1!ZpK5T*NwOu1U!hDz(P-8fM%B{ypr z@1RwzT0kqd&5GQJv{8a*1S(!MquF=PceqU*molctd<$@Yo zkcho$MINL(D;K-zD?eXdGN_Z6tM=rzxwd;nrhNKK7v;5QO~tNg1yZqgD<#9hPTBmb zBzY0nK}iX<;e_9**Hj6wuXUEpHMAgMZeM|f@YsN6PxRP;OBGAjyFoLp_{Rh_d}OBF zW=k!_=3=DsG*6~HeTJR!Ts?G zFYh1sr+HF(YOYCX>XdKm<$)JkDP~=}Dn&AC%irdAQhfjJqRgFLTi!gYO;$d>%-Kbo zZSSew3>czjc#W1@jcj4GOt`ULKKqIpuOIVY3YMEH6QlGm)@vu9prztNwYh%{QPF}# zcXg}0Z7$97(fj;edT~QX&3eZQfj||O0^c>c;0KLv*IujHWsGn?keGe_fqZg9oh%=p zzZPN_C$`o~Sc?Rz@NV)o;i}~gj|vRZ*4QVipKhpo@8!!nfn|3qsA7j0M3g2b`gwGBUb9rNLJjL+|OXsAw_9jA@BH9;Uy^-8O4 z=(fvL6Z5s(tA2mdLwgW5L_Pd%y&;^}xXHZ69bCQMFh%`U6ZcO`HYCnznw9efyDYU^ zuFbS#yw!gHo?qFL`m1$LHp?_DpZ=@Wwiuad2;{A~DsRn_$BunahnH`w4L-X4UYkTcySbXMbWT;OQRx9mlPr78>QEZSTt0AmM~i zB(Ovz$zWDVd%4^}+k5=HK%ffG0Fk6O(dD)6kL)$iz8NZ7kiauQ`2BcaNJ}Yir=_pS zt>MWXcm_z*5t#-D{={i%eBxa1R$QyS*H-J-o zV+2|LG-!W89T_ESh9COVX6$>&USKL0Zw7xwJm-YRh`LoAYwNek{Ly%cY-^r?sUP``3wUmqksj^z=$CT9D|xKT&pE8l{vyTZflb zTGIeJVpV&s;Sn=|Koynd~d16TjdvWj(O_b;Dy|=V0Xo1vn}^=-g5`t5Z+8HGd#bB z79?;SEJ>p-9iWvSd1$Tfn+pW0a2(82)$R^GvC>8Bm0Ca;AtND-#>1+J)^H2T4?WgUs2J5ggCP7xTP>VJH5VUfB2q2pbFo8c&b)cU|U@s zw8fRK3U5V7;2QvcItLci0?XIe>OFm;;I@G&Ah{%R6iA6J4XNYVF)l+n8GISEiFHAeI(+>~Q%X2%8~)Ctp#=$SD|`n;uk-YnRa32E(eFYnL6unB zPsVPc!w0p}QY+=s1Pi?V3T<90Q)U94L_qb;Qfhrus^PL>`y~xqd-L=kq4gf7k;B$q~g-`0O94Z>7HC*#l zAW(&MfuEpU`>K+6dsnUds*ge~K?0wmeD6oeuIdZ>Anmj5Yk@!&)@ezKIy*+~u%W$n zs?K+z?jnI>34S6_E`!=^S}U!3moEZ=Dr{-|G^_Q;)ppmKXbBU|G_)XrV=YN~8TwW2 zTisb3cQKDZpbE#qd}Y*+*YZRMEzrM!FhWKGXLO8Flw|v96}9ebTe5sZ$IInj^-#=? z*((FP2g!a-B9xo;9Tj{giUeAaz-OXJ`T0j(w5J@JHEwAb~1ze1)lc?$}E1)pi{5=+=pRDbrM*oIio= zXyH$y>&%v?+a~a10o!IPE3_cdboNYn*rZ{kVo&dE#QHj;N%Hw5gIh>D!{x2x$lC4G z3;~t_hBn(rlhZZ{hEr#n@O^!lDzqSxl0Kdco)%~5ddKAt1ghQ#jUjvDh+*;Y!r6$I zk#A+2h)zn;d{q=2@4T3smkj*dUwOVupSibAlm66ujeV_#i z3-dDM!t2&b(V|%~@Bdd5@ebM*ts{?mK8{qG)LFQjVyf`2A>lWsf;_+bcv87nK(;%G z1gdgwQD{Np&DT8gnRVPpk-%&|kU$l-W-%Yw`(VFPHEgTgJ*m4=ro28v#yf}>B=9{U zX987Y{g29Ny}KwS^6KY)pbxYlfp0Q76R5%(DiUZx0^a~~CQya-SR_W>8c)m%MYvk8 z$mcesSpsQ)`{J%w+s?SQ>X=B*u6eTO#Hq=@BESEyCZYw2~-%HuDyR@=4z=l*S*-TL_ER~BEl?Yqm zr_hfTv(-ejAdz!lf&{9>)eOuBT9ClLOU#GkJ9AR^?+~)pq9O6N{32Vh-o&$;Ocu|5 zA$!~jC!OB9X6qTyf<#>WLwVQ57?S5^<3A9n;venGbNu5-YHZVN1X_@2l%~n?2}8() zg022QpepC*AX<JvcBSJ%##DkM;~G1h{-|J0dew#-gg`@4|(&l`|79ZQgiS2akQO$)N#%7#qX zSBn@xs4B|p4Id4&k~)zcjjffH)%DZGuqL7f ziL!fJkbB>1D;+cRv%-)-3lb4=Er`pwYRdkTpR@Tu0#(bFd6Dgh>nfk><$QNYCyA2~=UPB&G^2NQ^YANv>S*Q2PF($F9MAAb~3EyF>!(Pjvm7q;RYoiR)RK zV0{w_v>;Qc@X zRiS5xk!PJV+&TA%-; z4wA&2(|N!CHZ2=r zRnLm7f9*wr=30}h*D8^zZk{A~T1DYmBIX>QGDwuDT7`r^U}VLm^4VGx5~#vHM)ZMc zZ`L!C{Cz#I@}j{>L(cg?3lho8V#vZ*KMdYu_0x^94I+W6@cX?s$@?`!=ZM}0_yeY7BTVmlMJ8@00ez)>HnFtuXoq6LYUvkQ{e zCp+@!Q%>1@Ab~2pPofWeX7n8}nk2+jmv^)`TKt$ zP}OK*3le;*DA`!#pKJtLkm!EjkGvgIii|(_@(%>6O8w(T#x1Q%c0V)A*3Qv_M9$+~ zBv94nf-5;&t2(*sm^Ygbv><`wYq6bU|609qDe~r98&aY}jsIicj>PSerAfrj*5vV! zYS~hSJshfV^dY7SEl32WmM6moHz!r{*ktp81gdZpB}pywl+@}JA+(i~H*2t?fI`E% zlLkNQlXeBZ7~VMdCWkx9q@VR?LqKpM+2-4T`zTe;Up@HBiH7YR$d2`)2EV1_$d5Oj zh(+EyhOZgp$eID2$*Yoe3>CMHCr>(d=0taAceUIMCwl4WAchtsDqqiSxW;FMca_j* zgs)EPM9seLA)_6JuqmgQF~)jIj4z33R@-=esUfe0CF{ul`q=L>xM{pT%1EDaPTjL(H_43d#iln&HI#fmo{W0k zinw)MZ_x8mKdA|6?XlZ~m{7P2@#c3hWZFpf(C4GOp7wj| z{K=bFJ>B%{N_W~5T+`!U(XC2zU$tNl33xe@p#_QaEy_03>5@Czb04`{TPigj^3qAG zM+gL}ZoJjf6PhQI)V4vKICN{SvXH0h3K_}Jf`oVP^mN_F;goiqSRVLQ@#>bB{=79z zAW$XNUBk+9szaZ2^1*C4LkkjJmsBy9Rgv$0+((Ap(IaY&VkB^L%S{ z|K~lV^RXd9i$Y>)t=dK(;r6 zh89UQ`mish&x^L2t*8sH?t36nIB#Ev5Lgu#5 zORL`h^bJuj@)kY*xh5ZWO-DW+G?&+3J*1HT8dLQg@zU-YX>$N0s zLvx<JzWeFMENyXXz z3@u1}JagYjM`Sp2AB7(Oq(5fnqJ;y41Oinvnxx969z&8A-+Do9ilmYHV?!8PkSH_z zkkLo~1v2+x_2V+_aBMeOSvx`?P_?AVdLz*`z6mEwefkyUcu5yKHf?P)8aB$6;X4jKsqfFNKti7+ z5UG?Nxp#(xBU5fV)6)eSF|?%clj^4ijU}JESY>Fn>d=*3-q8Lm6ydIZ)tNouxOp)Z{3((TK83-t;KT-o4zSQb8_9%+trZd`YP zKozEtpR@hoIdynim(HKkRj5};;Cc&>?KEFv?(gc;U7I=!1ggZG4}ZU(dhOj!3M5A| zYzNpIh&i{tzKj-HnTLKk5G&*Z3G7$+nNHKDQ1^;XbXNN~fj||Ox+J-*=t#W_*P@e0 z4;1bP61c+8&;InM)Q>-LG`}GX`#$Uwk>=lR^C-#-eVk}nI+&pa30&dlU##b8MpNcG z(F3uA1OioJs*073QvFZYqP}E+FtWsF-`M1M!?WUJ$-9#J?wvDHbJS*YoM_!D{TN!1 z5T9ztJ-4Yx+SQ@cc0>vUstTB`GkmKyl5EWH!+m@@T|l$E)`&hS>CbRf?2_=%aPn*n z*>kmVwh^-D&pg`cW(}$Pn-0Qg35gr`uNpqKh$pQN>T8g-l0T|vGHcQBLgI)FRhU9a zYCigkdi#2P8hf3L1X@iRq0)Z+q=QVja=;>Ft zlXgGaFdW_Ch!w|=l2q-wjrQ}+XOeNtQ^+|IIQEsKDz$7h+v&CGfNzZj0#*24B1z#d z9JLI)x^(YI7vYTs35<)*qZM4S)5aI_qJLSq3IwXei0K28zt-gOd)c+kvMr9=aGZFq zTGbl*^MijO%HM>M7-8*d9MPBXId8zzzxD4tbwdA|QY3l?ryEDeA5+>X^PVTB>8j!T z+AC6sjmbwgLjMh2#eY-AF%^!rL?4(BOgoMlMMD2(RQJLE%J?RPcT*&Is*Ga;J*STc ztTA3sxA9cQ6-+c~mA2s^YT041=v*jn~!qofUoH{lI&GB`p$YK?29u zITNVL`3~Zp!WOKTk?GEgKG1>$zUk#mpbASwB+!BczJKOSpbBfgNHqJO2y7oho5-=9W1B$YQzd(24Rsuqy?r2os+?OCwu8b)-Wz{+MY_}fu|*+qyZjX+ z{X%icmUC=_sKOEv?+03th$6dS753U9@t|dUV|qKRNN``v{EgRcRrAUE zc?WvUm!$qRL;_Vq|MoKyv!_@21A)JVM3>gyM!M>Om~1&m0##UsVye)Bgk$SwMjs{H zEXn2r2~=T^A^O1f3?*$Sd-lGutb#N22$EP6(Sii8p+-VaL(T-M`Y$+SB#zFLv-!Yr z!l8hOJ^EcMbLUTE2J9J-xES=&IODZ?ogQBe^MM4aFohz479>6g)-&c~dhzW26%wfO zyTOda*}lHnQiYcFM`jyUl~S7<&$ZA?;rG%-A4uG2lxn1B$xX8PKmt`c-wz&dfauxL;~N0aE2a7wIYEQB*gh$EGr~Xg((z$palt>oc})FMFLfLpF|&ML88{%dPW~V>>g%I6%wf8 z<9Q>Yzv+oS(9--v6QjzPzZ>E&i3D1ZXguIo-)_@$aW)@FpbG1l=mTemFv=YNrT;^V zLIO{07JcAvp^DcxqmSQ5`e;D{&y*H@Ab~0|?h>{rv|ywr{H2_IAdx=g*PD#z98cGr z2~^>`k0iweeW69qx1*I_ch-W{_i|kQG30BHhRUqX@8$PO6tN4DmFZL0$UE;3BRj*r z`ABA*{8rv~Z4j$Dex&-3`D*w5gWD4Q{51a+6Vf!^Bk0$ueG}8RNARx~8ujDElj7yH zA)d2H*AQR(kgF)dH!xuoX2 zj+}73;6*PKjU=gChidq)k8=R~TG-25gXWM$)AfR#;m7Mz)A`qxTe|$B(v&39W z&mw!ZU=1xu;JgN3sSYc|{<=4lY;4^@AW$XdW2xhKdbz+1V#_0L;Jw9rj``yeDqbz1 z>WJ|qeQvyv4xo+Fzn_?C(^Uom0h)RtGG$l}`rHMAgsZ^)ALu|$B{DX;^kQfgB8Mz-waPF7{f)>RL1` zpPPmjB=l=jG*L- zVaw?I0`8hw)l7qJ-VUTe+onds6rU4+Ns{I$wpw>Kjm~&j?>8SNLicBiASy`*7ujm6 z&lozQ`R}PRsW62+g5-KTZ9}oo^rxY?_K^S9%h9&v=|xXts!ZozuW6NONQv_xA&uJd zva+dQuO&^&%^a^66bMx5zqH)FCTadyKP_}&Ejz7Wu4mLHcUcY3)7Gy|krt5VW32pk z+Lcpx==HBw8d{Lhum6qgux_@MmV50r8nN5qH^QXCQs>c{JJ@Oo)6?nENw&Y;4-=vL z_%~kam*%!wJB#h~(=z+t2$M=DO!tQO)cGB?edTSLpZ6wJFOzmJ%acvbJ1DlvnTFI{ zb%{r6n4|6L!xyT(x0U+^bM9LeGIp5S0$}c>k6z@ zyKlb{CKcW%J*J+$7PiKmrB%)=+zuL|i)Ma^Icp7t_@UjF^gCmq;)y$QQ>DI=P(UP6WV<>E-IZ^tV+G<8ec6DE}+TeDoVN{_eq@-i4GJZv>VMrn~s;~@s9Ft<1 zYV@{_?9QH%LRld(==~AHOAps9A5Ra~)u!yN%{Ci?g?#9_{kf$Sc|1Bq$P*uhKd!5d zv#G_Nob9V(+L6$&|E(qay428;WOp`dbGzRNlgegzreRVqyR1}AyKSv)-s#GkADXVB z1%Fq}`OCkHY5j(@WM%#yArPqQTl%44^pZMRKF;LIuZ86EV`imBs%Sw%EUWKNr>c3* z^KS^k@+BVcVwIXHUIsfJvqOKI!2878;I7r`8`nq{*eXQ0gGlVzlx$FE zG|fuYjw1)vu`|M1&#m1B0#$f7d2OF)rk3^{$XZt$s9uZNyJut6ulJf+h4UDWKK3>K zE~ZwJ+&eT@)noC@XY2qWA4u%DUe7RTdYi0NEz2FO=IPFNm&S?&sxVJH63wP4`q951 z`!ZsnYJYT;oNGo4<8M72W-kxF^XqpPZnT$om+~WXKkMz|K*J_<=hk?3jSf`Ng2d06 zrRDOKe&vZr=1>jP!Y--@#ma8?e18PHb~n6C+`=WG9jql_UdgdvT&rl}c>yb;=4? z87-79mK)NN z&Lw-0C|@6T=s{@>X9q?_B&KCn2q5|D_fc9ev6tr^X-`~7_vSu&her@6#hUfo?WLgw ziHLy2wCO<+F)e24AacERFed`;T_&eC&ZR>-#tQ_h7DwC5b#BFzvb*&-yuO|XNSodLSZ@BV zgDnS30ox{z*8C%rw2$n{S}7ldR*M9dh$MZ98BV)i@nvjSehq&MRTCbsku8#&lh#2I zJXIHR^{1ZGYchGGi-r~?utfNYau4QFN2NFmYuQvFP*r8u8o7jjNAk)gko$OAtp~l| z{xBVpCtO1d5@K1|WX_`R61LNEW<3M~Rn807$jAHlB5v39(QAR~$#i;nZ&sk)Y@tuY zQV`quz6Q(bwd6pyGWLSd&XK?p;rm5{@6xl6TCplct_lRIu&wa-+6uSnuF_6yQ~$CW zT9CjJ;Sq1YexpSK%CWaTHUfdFzwW)4pDb=n%5K+lF5kXH+lM};qmQ=K(1L_mR_78v z(V@~g8b!SX0#&Jd-pikhbR^9SHsd~erPO48aa-xlZ4SmcGK(@Th{sPS;~ZI#86}&N z>MJ5qDyb$be?FZ?c-U!Z(R%|Epe^(oqS&lWna*f_E@AMmCQepmhJGZrE zpYuPYBf_kNeBkfu*P+MjlF}peodea^*|Lf4-_z=MO8rKdR5~$cy(9U2R^M4uF25bC zp8qGce^}I*bCX3^84lQz9}}A@Vydcz*s-9sX3Tq2!QXtC2%U~URf9ZwtdEcz)~m<{ z6)DFqJU07{FsZQi@O{X69N4Fm0iLbs6Ebv%$R(8%F;}geZ(N%U&%8^CGIx1qS`ZRT5Nse}`zQe}f ze3%HG_P$-3q?+mdZbv@{*08)Ib1k#{H^QXSiGQCs*UH&5oBQQx`(EzG`|;%CMDl4t z8DmWxQ*0<9%PJ~3f6Y&I9OuBEbbdk>pZGmL>lEn1c^NbE3$;{RYSzs|jAW((#ev&k_ayPPO z>?5+|`v_r{6N$1kF>Q36aU^!A{u~VNF++KGVgq>^Gg2T>g)@45uCMC|wM1r3c4$mP z&GBMA!>7*eiC5p=N()1(;jrpO8aIkiVt3XvJlGXV?7Z}PRdid5sON|sp#_P5 zCh>jY2_4AbdwQy(TSTktq@%P~i5>!hDs^c+L&p*Eq{%>?7_obvI>K%z?e{oTLkkiG z_*`cB^a!#%K<}wl$2fI&=m2`Ha6f@S)%$7n3@3+=Aw^&4ZLp~KBK7T+2+H0^X=p*B zW4BbprB=hp$%Cyqv3>SZb(3mOTMpsT5#hH`HK=>4A$t1+5|g(DCtkI@tD5bqP3>2O zXlOwK=gxQ>#mc$0qMeG+s96C5fhwHE<1xK^R?^PiEJGWQY$nWEBEef1%)^E8`5u?6 zd1>>&CO=i&U1{!lOW??C4ybrR;`kib%qq^39c zJjwDYG^&0(fk2fw8x?x@x;mQ7rzNKb3Ufdtxp(EXKpj6j&vLjr3hfB(2DX#=~KV=H=B76??~ySgL|etb`TRMLrU-%?sb3liA6 z_)|@Kq#o$nihZqmNtiD|mH0+q;KoYz;ZbkqygZkN79_C!^Jtqp6V>%y16jJv6hy**99$1UUUU2*MJkNS&=zV+ZZUe}$GnKMEKm2>!vGwb{=zuU+VPzBv{d)1Z zu4K@hYP?1HSX;4%7rN5YcRhb2Oe$Pg<)<54*)oeK!|9L6h8kM%clGOpWu3{^!Zo>% ziC=26D$U1G@7oQ2BTOotIJ>A5sX0t1N*1?ei*`<-UoScvb8fQeD${rlee>_OuasjI z{#rs;FOh%qVIpvBCrSBzGik`dB-(IGdx1a|K7Dwf=yaJ@GM`5eJ`2*&f&`9Bc{^X6 zOn;UOrw=ot1p-z0^pPa{lD%n#DRH#$iGCVdkia(!-iv13A!SQB)9J&83IwX~dBvlK zR%%P87HB~o_YBq0f&{)B@-Ow~`x;t(9K=p|j8t*W9Os$vO^>e$hb&Vz*~c-nihrqS zK|-wU?|fz|^Nw|4%PV{r2vp&Fv?QfE=2O@2YQqx$D#ha#|NBmk1hy{z<>c*gis8OB zllyuJ1gh{on#X)u_FhSK&&PUP?4+Ru34CfxlGo=*<-*JjbbeT@K%h!2-Lii@R)*|N zrrTb|X=p(LpW2diB_d84o2Mn+GJU8(pbGCSUukIeR{3_kK7Cw6yyr;ZGnnVRdmeS$ z(N|<-$>BmRL6tc6sa$-lYL)(x^q4$AShYj~pW6Hjw-u|^OW#kB#L2M&fhuv;a!#Yi z>gihlkm1upg*8Yd#OL|>iIUd1{{~X4eXu~F3Rg_|>^Uo@O>>(?3T*Qi)>4tceIUG@ zdweRYe|g5gK+`aC67R1RQxrD7%Sw;iXpGe=5;$XuGpYLSJbj1KuSkFB17{#{_DkQ% zrT_b#KnoIjk7}CH6H|pP727<`4>8S5*?b`uG-Ac0YX zb0$!QvGzp5Z9`@9(aA#5YjswAHC|`c>Hla^W#fFv=-$@GcEI;FTbs=TEqS@C1he-LOv;$RC#tWR$G4+8U1r=u_Vva`5Rg((!v z3N1)%TF{o9pOE7Id(VIbs-9H!Ctl4Ox&BUIpD}T&BkASv#+WMXW5iUU1&P9>E+N|8 z|HwHKsKRm+eV_%2%@f>+h5dp5@PP!Xa=stfli}(Twtq2IXh8y3vvMX-g*~50@O&6! z`s#Noc3WfRQN~JRZpSQapzM2n@jr5|uREL8mw8DW;|c5Zj#x+K#E4&aQ}lrrB+z%x z1gczp>M7k_GX5h~Xh9<9e7GmMDF@0OFz9LDdAzamvhPacbrx;B7E^_hLNPL_-o|z6 z_u7sYBrsl;=mQB<_TO>-ttm2=;YBLG~3 z%ql}U$NOQlAc1S1Vyf`BP=$SrNT3A?T)WMgKoySEL;~9&?w`QcB@$>s0(VB_OrVOF zNDd=Qv><^yBSarapbAGgB9Xe#M`=06#&`$&CAL=HcIsff#x^e!_|$iRc*|M$$?$tE zK?@RMtX~{iB7v%`+VdYi(1HZU78dh?1gfxC5(!==`uM}>eMJ7I3P%d`|o!UEl6O@ zI5Aa7ph}F9i}xJII5FM*$#{!5d-RlGov%f8+xRROMV&*d|gpwNge8 z3X}Cz>E*=pXuK9vg%%|CZ}(I@2QK*k5U9fOgXjZm+|K&-NRy=*#@u3!5ec*)k@&ba z>DBzPkE zMMAIu@%^Zea`}bT|L1<73j0dY2ab0>EcH~Tef-rkWcmJ&oTCMa;(J>u)e}SiKLo0T z5)o!U(1OIxNFSwfnTr460|`{!ZtJJmbbXutd(VItYfFE{^I}J%3V%r~E3_a{v82Cp z?nuYozxzN!P{G|4eeh@0|K@t)H`h=mT>4e}czw%Z-Uls6+@9sA*jc^#kFr7nRd{E` zRG|fl=xcSAl=NRMIA;P?IMx;k>|Zf9IrhgQffgh%7JAMEs<1>v0xd{jO!u4#RN;&s zKMk>^%<}qIVjnk5HSRSqt@rC=6w^L{#rx`zSvC@B*+5^Zp0i{Ka~#;0pNbu%;y35` zjr(K2_T>GKB=TxYX#ZfM+e$}7Ve_fvzoDfCv#BV%dJg&%4(n?iibLTZYn#a%ygP3=7E84P@ zKgF}o@oe>_%@fFn`Yq&U^H*}h>&jpjva$#z3mQ|jAc5z)^Yf64jpVz7X7Ok?CkaMA z!H8qGwkMLlhx5B{Ka!fx&#k>an4KL#)djsus2EWLBW<)z9ZPccT4?CsAfA`iz^*;m z%5U4$#XV-K7@J|XeP41T`Lm(zhYJRbryxnnQG3?qMHy}Nq(>^o$H6!@j_(}Eg?b)J z=4fkv2d`PyU>jVmv=7nGRJ0(0F}V2Yt$qDisqXo-AC*U{_*}y0plw5E@@mmj!`r4& z+=r#qpPhf`tA5-QuHyI##|eif`H}uk4u&h%F`Q^-*O*1$v0>5~ac8Dp6HR+Aakho; zv!t!q=5$Mz&`?&clRL?>W{BgdI$|BgUfx?zmv8b^ z(Siidw()N*8}wo?%kQPrCx`^9#Cad{kwe%i$7#xa>p&I9Z8+-d7Sf)$2hlx`y6XF0 zyI2op%fk8^yypg}Xh8x;oIJj>G?=Xl3MR2n2MGkK(vJC&W6ev-{S*6fA8uQRuw~n} zljyHLDq4`hSv-DHVZOnvfOko{zQ0JI3TFx>X^%rJYpo=zqx^abH4$qczGd(ozxlmc z%=+koW7z^bR%w-`_U7~}Ayr6V#B1Ja?Ht+b31u`g=)ORp3QJm&f;(1a4Rcl0 zR))M(u_wbgf!Om&()$KgS>8?+v~h!83wVyoIeNzs<1>P$+mt~ z)^uqZEv5N4p{$U=*!28t^(s}_=AD*W+;B<5-$E7MCrP?t)|_=~`(52|^RS9>;xGbS z^RV`0m0L-r$BW|p4qmU|$-Yj^t$DbgRMCP2MuX$~uY4G@_RXUuUAZI>s48aTMrypb zS8T6V=RT@*3uAi^Y*r_EE>iJHhEKRHyLyp5mUj)4Hs#|)!;Rfp>+5?|%aTil=O9Kq z5{b%3g4y$c!>afBRVrGLz{pU1H`U0lY-G|7_2`t%0)eV--$IETbii;UrV3A0{z8E) zt;#XA*w`&9T9Cj9SCW+bW+yiK)p1q&kR}kQ!cyla2(p|ig>^xa^7QG=hJ8#?-#<%IF{%+pQPPITlZkEj@kmWC`M6}y{8(1t z@CeoWbgYU|joz&vPL!u}4TCCN6XKxpFDJ+MV->=q)EE%x3DjKIK##Q(^2gkr+^DFnjo-xjLwim5LT5 zFzy=vj{e&Kma9)!em-t(fj|}JkMBadJCY4MIbRtR+Ec-ptQc*zG>-|8vZ{i?uiOxx z^KH*Zuq7*xDP1P6RM3Ki7?bs#<#1Mb^?hY$XA2bxR4s2kj@)o@F}z*4lKW^;brf6i zPfz9L^LW9>`OXtaqIM;{+M9X?Of7HcFGjJBY^kBb_ilm(i7$O8kVjrM)4PR!=HuPA zZ$`0wfmVif`4`FfTd2a=x%}Iu+5_2@3$-g~EA=0_dWUH;|Bn7?4BKK~msYQ|h@u4v zjE}^>l}YH&D*JoT((C#N1ghFu_ao68EXc0wbKLnC($|`?MuXc@|D)v?Mv1|wnCFkW zlGKe2iPTAtgxT~dft0KTj9?;wLcne#~py8A$7h883+asmH7%Fu-E9#f7!+93Ks z8e;@V((VSWnR#$tTB3AWh884nHbIiU9r9#1%Df|ctg8qFsxW2)|290f|Tx7 zm7xU*jM>1yW0~KIm8FB&t~{E6hFR}Fzcl|CZZPf7a~3nI_i zJ}jlnO7i015sK$H;VDq!e97s(Jz2rwD@m7I*C<+$z!Rt>>DJ|Ltl;?rWaON80)Z;b z6F*yB3t)COlgXQeyuvIF5_lFCpZ&Pkj*TxhnWQf(A`qy;QsCpOjJ~YZ%$3A#*ft^O zm?!Zxt3r9>S<3!PM7cDNq6LX1C)$%1=O&V&9v-~5=UzRSO+UGaoIKJ~AW(&8tVz-o zZ3Ii3VIZG3?|>5IJ_c5 zFID+%N4)9#DD=&rAM5#f19s!cq4rKjBCF3(Fi(14VmdvGr>d40Td-*wnP1GtNSG{0 zh(1a_@?`tX_mH|Zs|p0FbRVX#xp?U=^<*CBPZH-UzX+2hJ7LNbe;S-7Y=U_*EjOvW z(T8bIyZ*bT-SK<-FkUlMI_w1S2fB=l?34t)MqV-d=B{hUA> z#aH}|FsXFH^j&}?IfuD3v%Utp=4c7+*y|Q#bMY#~_G&@nE>++m0tme+rtCwbLCT}&)(Bt=frY{4Xyq(GNf6R#4=$4!qS%MR@i?chy`&6{( zX*Uu2wdw0aN!q+ZW}UqXu%zl|eDx|8>T}A4`5%2l zM?cA}WhYE3oiLTUByAyt-EU~aN<{V-)<3$>aw3EGe3uvR3^m@tf4`$2RlPYo`P!1r zE7aRam@G&foa;g|W?q%II_Y!aE7wG_;H%e_86kVs_QAc$^UN*ju0>sytKq%LnB~M! z?qFTzMrp6lNXP`2suPTFJ04YJ#Qa1JXys23M^kj zXMsSKer+m4P7IA=J`JqsB+KpUF{{qx!>$AFyBdTj<@>ZFGdx`6fQ&Gu+0_v8_~#w> zH+}T7ikJE@^PkOWwXZu=v>;J!X8_r;se^nk#fK9ecl2WA2DYM)FQ*Fxs_5V0Bu}nJ za?p1D3+doBJ=m1Flj)gjyHvCwVR+by^m#T%F43wnCqDKJXWx&HrR{9e1Oiq6m_-tg z>CSSe!gib(Y#GXm4qHH%XuDOkAW_Rcn4EhuN1pS#At%C=aJFU2XzFB069`l-ycI*1 zWHyvZa0O1V0-xB0 zeg;JT@4hVAGC!;TXoNtZ3Tr4|G3nfyl{bG$ooY-FY9bO|vL}hZv`Ie0zi{Q>V9oBv z3JkwYSB@Gf5U3K{p#R2!?7LNcy0f;Aifa(K3WTd1yceZ$EWU3)dTULnu>OIB=wr^H zD3&>K3cYuAqClW3d9*jN{yAPwSk{y0qjLRl)}+;Tx@c9BiWVd=PkhvOKZO00wu=tB zv`8ROHN)M9JojHLZ`rDUE$ezBh_$o3Lf3aoR?&h4mNY*@s6!_fvFJW^+pt(5P*py^ z7pYh0r2JP6{lu&jrG40_Yi8``u4EN0NMMcOPn-qKnf*!&HlzJYfj|{LANe^GWf`00 zUxqaukRm(>kZ&SQkifZ2{^k90emd-&@~UNupFp50b4LOxyMh>kgHH1ia^U&_ z?A>wX$LRjbgl(9NyZOjr4U>Pu*Usq6LYB zDFaEa9TN?sYvtj@7|Uq(y>}J0LgP&Wfhv4bOVZgo(X7}DQ-jinv{8i-01_u&_aslF+}x%U51y(f7o%C~{j~-UTSXvHb>M7& z@+D8h^l=?3a-vg_zU+tf8@a)bbQLW~6nBUr`8rN^-?dVI;w;)3!yf%}#=ZK6Z32NR zXSZQwAdOFVi!R8CJu_mM`O9kLn(sChEl5~289?5CiFO~=zdR=v=Z<4trE2MyU#=1e zRCSm!np8eFCcVzlx4f3PJ?Y09{#}BMOjxC&1&PeFL&??DDEHBI^;8WlGJt&|8pCy*WFUbn_mjq6LX_^ApI6D9v5jbDb04OAKS< z%XB2WQarK||Ej)MNF+nj!rjd7PUXb7YJJ)F2R+G>m1!#0B^){7{pW8J@1j`7Kk1}w zK7)!DBybcZNu#Dmu@k;)$bM^0AW(((pRb00>%)eBD@ljeQ&hAdfukrMZ8JKGeNiOZ zdU%>ZpbGCl&&TCHZ2lZO>KmMgf2^B<{{R`Q03MWzDoUWLuxB@}Tz4$}ER4GE`Y27p3}&d&zU1*flqmN|leOXhEXD zh;Y*W+FJRJTUkzwDH6)QR+>lmoZTZ3s5(+$5c!@rSUx`9j1zHA5v*Z@M0%2JRMCP& z!1TeSfyZdMdF3~}-wh9lWlyKKq*s^D5C~LRP8>tJFEE!+?A*(Vx(oWVI15+0|5;xZ zEl3oeJcg8ROyuOZ>p3xZ=1{iiggMPyy0So^YM^5xX&XD+JuG(=C!z-pXJ$1E(6O@* zDriBXZtwA=UDd*JY|oaQpyNlf5Wj20a^ZLb5~vb)G>*+TlI`<)OM0Z0A!tDYS2HE) z=hhKyLHuEI?v_CyP=&iGc}?6qoLvY!O=|Y}D(tgFLR{xO<>|-HemY7oY`CE|D(p)Z z=e;Kv_I6M#;(W4#h@rlPWXCLdoVrpX?a^|#bM@g3N?e7otosh3r>AW^<^Pts`R zNqOS%{G50*CWOV!TujfG-z^ZR^5{31R46@9zU7|5OZVPFcUH3Q391Y)EX)q-?*pd! zM4b2I=c@TNW{Dm5(YtjlG_)XrGm{dpCT-ZTAeG*Ud8s0Sssj%~NmAq|*>jyfl8Ii{ zjwPJmO6k>M8Rc!*(k?3)cavqfk0JQ*l6;`YLRS{cP1yy zd-r19bi z*h(D6EOQa+*x`_j79?6)jwa=%Y?Tu_T5=!zZVqMprZl0EWd{)?P=)(7_>Pp4L)hDU z;q+RgZo*CuBuc#>LbfS4MiEjoOI zl(C*B5UBcctpoX)8Ab;8?Zs1dvf>~%+r0wyGY?SFf`pilv~>g6!ZBg=?(8}OfhzY| zQKXkznRwL5&wcpqrmR`30rYD3%Esr1X{Abk8kkPZ!nH7deqwYhwmu+)+Q}t;Tk|pz zXD7RmMREN|s`Y#Bqn|@Z{ysQ~zH)!B;%}kqSzcfAzA7UHoGx?XS%EIh#xj~(4}7Si z1&Q@zJjvesQRGJA2~KRU7s_swm_c7I*8~DpB-Q z(Sk&y0^&3%==(nT6>bU zv2;!4qnEDfJWI?Ik9q&K4cj)k5N-Ofq=ptGaLtqNX#5z&d=`|V!L`1sNT3Sy#Me@_ zFm`_4C6c!MzKRwkuuk(Q&dlCyZ?Q7;?3e=rfhsHo{_cFSFUwuG938cBwTc!buuk(a z!_*kI`eqCb`I0CQs1i$eV5xXk@9=n9EWNIZ79_;lUOLj9y&brX7M@^fydS1jR=sph z>%%xk;p;ejzfb3owfz0O@Net2CIag;-`%#!m-!ssOdrj8qvCI&3dbmX7i;s5EN%Z9 zYO^RqMGF$x3iwkkrWbtt2JD%q6GK?3g+-}f38&n`yHp-*ewRggf{z?lO{Y=bXy z@M#O)qP7(4&#G;jMUOe|SI~llc+Ztx1KEXZ6X=l}j}1tms+w=?|6}aD!>ZW1w!f_i z7Q`+J0$ZgQMG;|Vf(U}52#SckH$V_UiU@)t9K~L-_uhM9G7)?4z4z|19eew--|zX( zcZcipx!!+S_m9kE&t#I7wN^;;P1Q)}OP|HJHsyQ@t?Zek*p*n!(1HYxsN!6JHY4fx z_u)#!d>@HG)wq>?$cdMo$e6CpM0{d;_9*(jhK+J%V@HM-B=CDB_SIZQQCG!MS=wkl zK>}5B%-x4iBk9QdCd#?F)fKcLfssQZGwfIbox7;MvXf1h2vo_jgWY=#rTf3tR4$rq zks<++z&I%}1Gw3PR_gAlL^ORP5vaoWOHo~HW@kEmM+32|UrLIzL;@rBbUNp)!L)va zLD_e*rbM6$qe8{+Q7eEJUGPzUowAbRMUjxB4d>p7rT3S3DQD8xD;W2PF|gR{Vg?YA zK+g^KR95w!CiN~77!NCaWS3KDtxipqfuovA1gh{^5Sf!lQ)%g&Efw>CiV9kgz}cCo zZFnw?Zrj&I`Shrr^jx6|-vXWPT4E|qX*^Wfne-Py3lccX6sw}56#8;hmNMel3Ih_T z!go_VCAU-P!Xu-V@kiPl(1HZcmUX)K;v|p#=Hr!qqr#+-0aZB0h^vZCrTS;XmGWzw zOQR1GIO`XC^t)5&i1Ndg#y56I1gdbIsMCF{kw&9yM=CQcjxn?#f$JS{BHPSFT2LcX zN$un#tvOMJ>s_7hi}x^kIXhbk^-Pe~wMa;-FkJ(`fi%v0p3>5JnM9xpSK-2o^Qbqi zwqS|UbIcxTeU1crDRjEMEh1=|{T{{3?xsYb3cU#;*D^JfT9_PAPIr1H`5BNv--(FJ z@NP*LI9yY1zW*i>sKOW>o$le)06JybT_v#28!6rg30!%LnZA7s`u6fW#jWjgi9i)b zC+T!^VuR?AtiP3`kFQ8kNJyY>KxBqJYe|lW0Lg&YbM`xf>nddZG3_{=9bXYj-ljuv9Je%fKwAw z8nI(6k`xS0QLD8u=FwO2jihrgZPCuAUDwcp#LcWW#JGS!R?6>Y?>7)(bWoTo*E&yWaI$=R|4 zzx1W&N1fEdgNAEpK?19-i0J5u5p+n)rrMen12oJB$Gl{`TAi-(KS?wz=rb$TF;BWG zBrr!=M0qbCO0AAm)wYk`ED@-}UKhDbBZg9oO6OU&$sVb9k%;Tmjg+#ORoM4kH_=zq z+76^%pZv4|JLKO3Rro9je~D=XeK1GIQ+zTt%$>*n!Dm|RRNsuG2SXoeW-S*>&n^mRqKCS8Hk}oy8Ar~bARrqd-ad%%^y5h+dt--OI(mRL*J~1LXp#r68CZDyH$6iPT zs&I@EeummX^mflDT4R1s8cUGCCtsY1U=u`t(YM;#@>e7RRdVL!jqROihw(*P^DlBH zD-!bWvEzL=ns#oZ)~w7SDRUB4nCB^WGfMTNiwgeIEJ%@*&xyn`!ysbcaGIJvU~y&Mt{S73Qmov3=@5dg$9E?P=TfQeG+&a&~6;&H=R6(xuv?uL~stRhV}x za*?A4(Qd<*X)BLUmojpZz-&;FD^q$P4fWWhH7zw+B2Xn)rYJo)jz0OBr>*NeTFM#4 zj8lxu5pPtTSUPygcrD3ovW6BU@CrrE{{69Z;pI5Z_U>GXKov&v=yWx|4xv$%himN~ ztkKYd1opJZSL+{5ue-F;CXU!45vam_b#Z!K;y~)Ur@Q9IiliNPB=Ct5yOy;E)47Hw znihFTB2a~~MmpVQry+EGg__#9=)+PJ5)wEPiIJhnPqew&rfs|pi zaAA&mByO`5UxEaVk0N5Lasn-k@E|*$u9FB!Wj}h+ib+sL47B z@$^Dn2c=xf5{W<+M*oWV#F|6t!t=rpUUQy?79=n>QdGal985n9%T|2Ou9FBl;egtQ{I!kidDV$Obg&LeC^0Q2LHz5`ij= z7Z%^ay-{?RMUgVG!+s4dNZ@Y2h{dVgms&KPt;`rxC=sZ_2pF+Pe{vwba6enQmbzU- z3lg~7FS34p;_3Z8O_eTX7D)uEfjkk5^Z%o?kigx35d*2FQF`t$ zxlY?i1gbE8LR797xnz}YF;d-7K|>1?xOXo++jU3N<8DL9%7|2k1ghk?jO>1+sbj(< z(!{f_4_c7G-F}^}?#$8jtAjPM-0Mn^K$V>7J*tezCO<<-V3|1tEl6M`C7n+17s7M0 z-Idavs#D+Zo@~{RiH43_2#ISPz^dO{WZ0`VASsR8uu{aK@aa~OE3A9CrZ0E8dR6nB z6|B8;i)U4z*J5AwBh}h<2CxF&j3qv7qy|45#2iK$*k29{MHcps(v5h+J{LZ@evV?3 zZp#i?%wik!El5y-EqhvjChKsy1_{!;Gv}U@*`~Bgq7Ae04fv>BGtJK3kJcQaXU#o4 z+4arQq%cj-mR56PzhYy^ng|aTG_fH&RHu(1hPo+y!|hPzN^d>2tzpf2CAK4nCOeYA zuU4$9KAilR;6Rpac45_WT9B64>j+}~mt;PuL^Wkza37`Z>{0CNif#tSg`S2ZSy`;o zKX!&Xg=Gzut+Lsk+hq-LM@UTbiRS(~* zHnX0juKtUoS=CwOR1enjeGhj2(H+so zx^1@n!LfSWWcW+%+{gN?>hTcvuB|2e=~$O#e+y^FuUWI59qO{hgS)YG4`Vfw12KC3 zlw`|x`LWu&1K6Ru@6_ta9a$OI0LB+B5^Z#E62NJN zirins0iXqm#w`L_SEV=OFO2aFM;Er{7iv`ETGjCqfvU3cty!fbiR`b4(&B0V?A)HW zIQU6B{%O5-Hntmkv|OD2{PUIibx0_q8BVOux)KcA7TE(^+VD1Qb=>>xHmMCHj$UiW zD*bk1+ssOeJHHa$hR-d~@$;_RB?490BO=1IW;ecM=w?j7#a=9Yf;~I?*FM$% z`#{#QNd@+K`DN9kRByIuPz~1K>an=DR+|?Bd^tqS9S=3 z+>YfhjudEB?#63>l}}|oL+`7T_pVpl-AZQO?LMgb6-!j7otezva7=ACvp^8hGl%k# zSLbO1m-W=pg2d>Qk!(T0HwU2f(!ATk!kT~={o4q`~QT^ecBigt?llYLSiQ2GkJ`#Z{ z99P6X=ekTj?A=NBd;U&?^@VZFZb6n>&8wPE?8#iVza~}n6U^1!>EqaQleuc0=C0yN zjLXdAP1!Y8_+6DONF1M?%bNF#RI@kPimO^0o54+Wm9&DmClY}w>~)a^Q6_^gzE@Gx zW@Jgf2NJ#Zj$=FDC90z)dW$x?B&YMjGLG7VzjsOms_?fFGku!L7Y;d8*!jiZEPY&%8kZ3wc9)K{9nFVc&Q#OB%phn%Vs5`Y zmXh(gaJK6%(N~G@Gx@o43JdAGSRzn`y)OK_V@LDJoqX7rYmNjhNMyFiW3#WAsqZ$Q z7Hw?kGnzli%wsMSH%h-Cs_?hb>FOkn;`%Rb$f??P%Hy$P+2)?5_g1uc@7pmwmj!pZ zwr^2U(mw1Fo$mG34F2k6ZQ^s;x=k>zpbn6OTtJ__dtin9YuvRxwQ6_}*9ka#k1bAZb%ZiQO5ZpaqG5?PHn6 zm8HHLr{;@a@N!rhKfUb{F&WfGB2a}rBBDh`jN}pZ&l2}5-cny7@oGR0Ytf;zZ#S)l zXyg4e@g$a7Map)NdlyyMZ{jzHFHBZk?fmKb!pDSpHFj&?Pb%BL4AXhGuWw|Lgkshr{QeJ+S9-Qzf4X`=)! zTq6;vnp!xJx!${KNV47}h$i`cc=HLq%IxsF%F~k}%+8`NSylJDVd9J~?85Xi#H`X) zgWb#?Y<<)b!@I?g1o7eI06w^fmr`r+83ip!G#KBVIcqwyq5WAw^mt?73#xTeCUmGT z&987y^)#&>`}UzOsaw=c%&-2UP57PkC?z1@mHH*xGH$!Y5dAWQm^ZRz39bhW{z0t? z&NxM;g?(Ed5z|)rTx3D(k2bK3d+y}ugo@H!wDmP__Ih3uGOe41XyeS5Af7!dMA`kI zCPfR*Ugb8L1hnJ}t-_T~)vP1}Rd`Qg$9;(p_i5Kj+48a>MGF#mPvXnD*qblk*;Vn_ z;UE#HlKX1RrusbmWJM+WkjU%w(X)c=hlNKo2a#EBdbY)`sIX|!KoVWbjWuukqOj7B z9^%d`o@vM<7S&a}n<^A7NCa-SV_AQ#_WcrXB=`$AzL_^t!lpKr2vm7I7Bh@pIfg3L zS_>lG&WS7QS}9xidQ-F@v9iA%``f9ip>(@0g0Kp4;h|eXl?o1C5+SKx*s{jG(hZZd zItap~o*hqGl0hDf3Z!dt_3Xov&1%m0IFc|<&*uJEuda%VBSRXyv$%09)QC3y1yR)3 zj{n_mGI?bgNYR2scOv-J<8_3X-08{g)1*?Tg(6s>-qJx4Q$nn zmeN%rVK46QSY{2@{Yso@V;|LXC!Z0_ac+P_pbC4$=z(;6kOpazB z>PC@8=6d#h&mb1nsS9b5>cQ%#^<IQx+2=MPY-*12 z7j)k5$<=fpt#30Ai9i+hy6|i-X~_4dd1wi(i1d3PQFXYUwHo8a9yN&;ZLB%efR|rX zRr8oaB?48rrWQ}4vj_JpdZKlmVnM_FJ($at6c$pIl7n09*n+>an6@^U+&pN>^A)96!Dcb1S z*p;_^xJ_IBzJWxb3ZDfLA=H}ivyZ=O_lLb!7N2ux{tI(iOj}3tBgu|EtC`1kl~V}b zpNJ7oZp8D3eA8^knMn76M4vf!Y|zB9ETCb4xT+gBJa~ihZ?ujbD@p{au-}9q?yCpy z5$nts{hXkn$0K>EEo*mU23tS6Rx$6#n5m7p<&Fk??Tw`h`bCh)scFZ&+DvBe#<_^A zGJj&=XRWLA(ELpjfhz0~oi4X~WA0p7ohL89B=r>%mzvtKqJQ$)HqXYQjjMGU^A-Cl z@qzcAN(8E~-$ccev)(+jlq>J(SWD>_Uu1#EMdHwL^vo$lf< zcfLvAgnvBMOu7#wwl%h8ZF#mR5p4{#ape(feE9wES0n;e*l*&k?eD-7JNof9d%H8dbG*U^YwEE_9&=fnq8QP} zyL2~R`B!splfR9j1&JoDUD%WL(^;7mKS8XV*??EQ`pTLmj+(_{N3QZU|7gvgAD+clc}N z7C6YDPJdy=mfX*0RU<7_ygzZ0z)n4%-?KSi;h!Vj2NG_*tl5DQ(^$#zR)r!fWvHI> zDF*)ebbpCJ752KA0bH=<)4ZJc!+j?;^w1@jwqmwxMzO!|?@`eQC@M{@v*i)XoO$OV zMu_}fvmhnG%cdL%o=U%2Re0WNsM4$?LMC_||w&T^_H{uWaZIt>7iP$4n z>`t2rEX}R4Dr!L7v*nN6n(|NWmP!Pwu-|mLXGzgKf`sgEKleU{ ze{kHPO=)j05vV$IB7>C<{h_9Qw-SBjqL1bo?GI^Qd8IV8An`mSn)y?O-F>>+N7TP+ zHjGztTC2qdo)iA=|Np;GHLhD0+hzAftuSStcoIKciQ~^iz2%hnB!(6wDj$kv?Y#}G z-tfQ0TU#kUiT~4ej%NSntBM4wwvWqZ8)9CmYbNP->vUrqCh`)`7i&$=PdA_iiMSbY ztjdI@Ec$kYcxyZJ6#jHphL%^(K#)Myr@%3+^U`aonZ4075ondnw-k=mj#NBG(1JwF zzIgWiiX-bZY^G?VC^n5(eb`b94ErDvsCqGN42wR()Od59Ad;J=@E)aGYxY5I3R;ku zYCnu67u9BS{B{fCS5g|!-Cs@{|HWG(Q1xWQ7}oyjLiN!DS3%6)k<2Same(q`h*8jj zM9kZG7B;UeyQ;e&h{xSi`PMT_*@ErS5`n7fWyi2?H%6#GU$+;;9x7mb>EX- zQzZgb2S;SFcU2D-u5Ohoh`NypJgU2=!D7cc1uaOt5l`Z>GZWOl?Y{}aL6^uE&Kyj_ z;ulE-s=`-}V(ZIw@}0PDtRR{ljpO%P}m4R!tHs#1yMqa<>ph) zkUBRDB?47r_yBgoVuo+UR^J72V{aml(A86pe$17;QE{_JvQFpX4PMJzN}eeZXX%*4 zZBLe04%Qs6pa%*Gyjt;fK9Il%ohqT!?>%24P=%f;QE{=L+KH@MGJ^g zN_W%Xwa|Dz&bMiUc}6o&<&sA=0ypgzQPZ{VgaOXyI%vOuK^PBK2F(*>HN`IU+w6~zYX}mP=((v zu^YZ6otxh9(H8HsQ_+HiypPlSRVw#t9ivt7bz(@M3ctZ(wzM^sk8~NJS>9YCeb14= z{Wh_e8aRRnOvuv)R=+0^sKU8~*cmM`f}4%Z)=oFEkme;w$UAYCu?c)Fo34#{;35&I z!daB4s$!YI<5MSU&#t$UW=lxOyZYMHc;2MhG)?InDG{i`-AtXX_Dg?GSDBE$S_3+3 zuP;kY5cO6Yc9uPx)Q5c?Fk5Zr+gYq@tvC7b4>4Pb-62=10}FaQWuK)|mGT`O?vTqh z93%o&WS}?OxUjG=GcH`T!K0h=)Ry&>>`%@VEl8l>SFF!#IP$W~>++tb?r0d1fN=-7 zUoY|?bM5*5yEgn@_*D%pNXV;+nWJ6!`f+-`!bt?`L8Jq!`t0yze0@4=XVF0wdqob; zJnoPKKkTqYLkkk}Y9ceHG2hkAk+0b?Ng_}+c7qrD(CaU@d4-vn^}Vmwh_~zJ#&6vi zp`ir{d960{oi~rOa^{*#Q;9%TP&IG%H7}nX2(Kr;IFnj<@!h%ZeE)zt8d{LRm8DqM z7Abtda|gcu;t_@fs$LIj&ib61$o9A!&mQ}_C0WwV%@ zla*-WR{eH-&HYk*-lq8qT9A;vYMT~!k2!1i{ zZ|#}3NQw|bLXKN{yEcNmhJDi#JNzXPs7hNH#at~S#R~93p|J*C7(ZoJjz1k2ub~AA zIhyKKR5&kHu>wDC*-Ro(Rj*eFQx~MMU+Y(ikvd!F&cpSQ%8-(tR0n&FxCbqN)e0MV zanq~_W%gNTY1a}7-0c;0Ijso4RH>QLut!6QKox#bbvoB!LA>cjOC|PT9qC((gdAu2 z?nrBXw)QnLshLbjDwr9F@#;$$e-yQmR0*mg%>a;?d#f#b)iq8%=I1NksKT^Rp7XIh z=~$ztM4$@a0ucwGMDn~wB@GwqR*;@{Bu3k`XC|$0t9@Jhh&Gpu*8r`1;oN<{N+bYik4V zD`>(0d&@JN)nz{H@z4gM4a@31_{Pv&?R3H|i9i*8CB!+SkNWcLbrZCtPWz>=0TL}* zhqKO|!r6!D8lsKogM0F$*SBjow{4RMRN>c7r~BHmAAeP6m$tF_Ea|I;#PXM6>_dnC zY)^Vg(MElT9=z$Udzz0~hD4wWzuLklQ?(C2wDzvH=7_)abw*;Mc^KPbF`ONvm&7dN z!|fTWrSKo!nDL^M^k?)-Cw5`0zDwbCpDiQfl9S@!WX_IT<-(Z?eAESfFN z$WVoIJ8_1>tWbXSKsCOt_BCnNhlD&PdLIqo`(Ik~%FnH&nI)=lRx3Wvoq~CX9kqDS zWG`v;1NMM|;h@i9c;zO5M z@wNjtN(8EK%^=?M%FX%CK{a?O_kGf80tt-%6~6EaUOcjLHGXgHDTzRp9EWUZK>5`P zraa)>F%2z9$kDh<_J;EXKZ2F#Z%m~~Cyd_07$z~6H0sL#Q50oh$8QQ+kU-Crh+7Jc z;$|BfD1Ea_QY27?Uk33;&Fsw|pQxxD34N)c1qt-9iItagcmCYvB3XC!w?v={zYJm} zJggtTvVI$JEPSG%1qt+cifTP=dh?y@+(_V!j}n0@{4$7NFk}#SUwXulQR}9H79`LQ zE4-Zk{kiS9y=wcMrxJlG{4(ft_ne~n*f~$sZ~f0GXh8z~$>ORi4dT;h%wcz&u1f@} z@XH`7{H==Rd3Tnu+!|a#3liuT7x8e~5Wc9nsdmxxutcB=zYHR#=ye>AZC61X{(7x~ z79`MfFLq3B#_;l=L$&sm*GUAb@XH`hCe0kiEuz|M5e1VJv><`I4x%2}=2)(_oTNoe z&6NmL;g><2Ubk`>cki38Jxc4KpalusJrQ%bxEOBMW4re9P*aIO6@D2+HsH=U?i;*G zD|qmkpalus1rlrLU4!`MF_*O!Icp^XRrqBP9^s|Y{7QpUT8&#ef)*rjH%r9H)bGm& zKYOFyZ)UF|fhznm=yaw02k^4Z9%x$*L@~4=fxB{|%I2GHJpGb5uQ*zh2vp&hL8rUF zx)-+`|5i(%TS7w%61cl4YI%?A!hf~W@yF#IBmz~qX3*(g6!qY#dtPZZU$>Cf21sC5 zlBl=j*p<6J|69A+Z@5IDN?sLhtJRA;SG=L!uaYLMage~BSdq8w-;0lYepWksG+!c6 zg;^KEt9H8&*G)L2eN4;O(1HYJ42j*0gewN8$yT)Y+SdF;YK?~PvUADV>D|fY6N^@_ zau`ecwCPOdHmkksAMyA7;_otn79?hD?ors(eJpu$-WY#{ZMZ$QRD*wHlOpQ~GQ_Kj zIxJ@#QO|ZEenMzbYh9g;y(IRj*B()oG_kkj61Vr1b9f>e}rY zWI<6ovNbAOwXTy%-fajib{}X#!n8@6TJ6#pQnM)HzYwUx9+9sKEl4zc=dP+Ohm`3W zRjdspP=);_xADFE9o4mCGQG7)Qsh{?!wl5(o5NA5iV6(c$qMkA|gm+0y7^{YUVJL*ph1J+ghQV1%Xc@ zT96o2XDs`8vX^RU?V!qSq`BF%=W#7ruj^IW=Teqz7Hi8cZ<6!lWCAnikWhII=9L-B zHoU7->^_h{)t~SDRsSq@yxV+rRcMTg*)F9jj$u2`XQ^LX`4_tnv><_bGxB{PfvP|E z6qNF>q9?m+b!GRIXG2+qQSQaA3N1*C;I(!sf}SgA`Oc9*)#U{f3rmL#Wj3>l zw}BQUrutV@J#7+Ll2h?EkU-VifI#)3Pc+L`+=^WlT9Bx6*IixyD4vbWX#8IYRBgUL zPW3S##0*`HXNKYLffgjPttP5Y;&i-PNgn@&K-K%))oN0?{_JbMv8oETffgk6BA##m zn87T}y7-+VfvSRC$JD5ay;#En`(kaN1&MCM&#R7&`m^#qo&O7gs$Q`#)tsAM*`n@hkZJ-4S{65OPiv+6P7FA+(R)(|F zdh23spaqFPe{t|zi#dw;6_u|FEl9}OfcTUkfvT;Y#+kp_Tg0_fhxQES*+#YEZ=H>4-h*INIVZoVbhwQP{%Bv zE9E$2Ou(NBR7GWsWLYEjspI}Ko<4+a;8=^9-hUo<(SihKmdkA*fvVcmI4~UyGTuUhV@}$E*7d^P4X) z$OKxDzzD%V6R4{DsTb?}{<5LKd}FaT(1HX;2+D0BfvS76JF(k0e;bBoo+;J_T9A;V z4Y7BTKo#cm%2$P>8sixg{J&^cR zXv!8}h$0PLi}x=69;hmOZ^~w`jv}{BixX&B-@=Sd9TG)KTy>LXXL4U*8%XpzYR1Os zqR5>rw_bq23nB#^ZW`4 zRAC(+xec@+f%7?;z^9>Tf;sEwA3^-$o&T3lA`-oHmD$(F9Z8zr`M*4gsB&IgnML*K zNcQd$ClE=`?oGSu%`EJjR2o;iSQSBh zKX8OYqFrqlR{Om-adW9&?5dDJ6|TtS`#=j4R|a@6lf)*Zb&jzv4qg=!sKRxdOkn@) z?NyVNs1r)Y^lSKE`U<}vNU(0TL_U2x(xAu~-G*0%1gda0C=>YGde*GML?I{g^n~O8 z^0`8y#FHvaSsYH*1v(bHDjauFg;y(I6Uo7RfA zO`einlt|Pz^9($2q~X?%6ykrSwPF8=v4-)fBT4j+c!THhmSXg2@XAsFPVT-+}l{s7K0tsY~XZX-3xWa3N*qv>2Y@s|4_^SM#)rEAJTZU|@b=5HIV+dJrsSX)Z_|4GXBY-Tw zy~yCa-}of;yY@eM4$@qPt>N`9!yO4-VbjVc)7}?M z6?fkhC3AEZnOIqG$UR@y5VSgj_@%WsH2vgg__%TuQS3YU9$8_`mVJFAgT7vS*SAj1 z(#nM0<4AsDkowIt#P{QlT+;WbZDE~-XZG3Aab#Gta%#Q7D}?Vg%OZnjhjk;LQ!6WI zLBf1g4q33Wv+vPI#%gcp6VqwA2Dzl8MH7iYl_6&=@m{Uld+EhHL7dzoP6xhooV@XG zs-Oi4>);&XR%fKIV$wqp&nKr*VttpqX&59CsOn*rO)_7UHRSFv)|CC{c`E&qQc`i6 z60D#FiIMtj(z1LN!=7#LMH{PMWzs=o*0C~TB&acJ9C7(opw=7ZTG*;{9*HP0Q=Pk< zF3h|zjucMMQuTGJid=p3oY8bqVJnunz>=T^iLrh1h_kbaTB7u^LUI1b*G#%%PzamQ zxj-UNg};-?^o|-$y@$_JSCpSb(1OH;3VB4=b!#E%pDEgKydcg+?sC=l#+`!_fhznp zMcqN0blN$fiRQ6sHH+#ymiV;WrDnHwQ+Hn(M>^yus%-+j)vz@=WSHlAwJNbbL9KGhw#Nfh{a#m9L^?Ijpu?T2YIicqNd&5}*G0}~SSDRQ=^?v% z<*|wuBntQDl6Rq0I%c!^~7T-;c)V&GzRYW#2&dqhM6#--99_uFbNjm$K(Ao0~9hv-aZs&{Vm7FTsR zY9!rmXsXRv{7~v$RAImAbnzb&=%X6rweEYxKrOy3+mvtWT^_F{p3fq2Z}zBr&QDbF zYDE=~z$E%?NTT+K?N6@Zq`)f^2TqOckcuykVV9ZdO zzF@94z^R`$yKE|{((%5!U0ttka>^hn2hOOorY}_SYQ=e8`gr==Y=-vhdz5q^NUTsZ z$$^?j)t8%%b)Dyr8%9^LN!sy&p%Q^AyeCn^wEJM%x9?i*t06}#dozi!!>`nRsXNqX zx5VjwK_ArCtCy$?%f*xDk9Ev?>><&{3+qADF>r@=|NJNoEl9L*k0<4x)ne`qM+%~} zIM^_6 z>s6q6caDxd$73 z|BkqGFMl_>b9RaV8=JKxuc;4iEZ(9$wYlWRwb{jxT>k^ zZRx{&TW+!LiA10ZXU^iS-DOK@6=#0l;cNSvqSur56fqK$|Lwsf9%Q(n<> zsfHFLG7npk1|27`@z;zsu&=zarPm{x@DEp3NCc{WueKsnp8dtn#)b&u!eBiO9j@@l z?7`pDUyL`i&Iuq+*Q`n1iV^yxSK6*OUL*ZV#LN&A? zvFoWd$xE8Wa<>{Y^)ANf>554PKIcb&i9i+hh=?Q~-+&ff^5c`{d}1z(>XB0xb6Ky7 z{S9v?)gv)S3YZz~Z0Od~h1A_VomCoVtVh;zTm!0Z_v3pDeloNmQIubg1gQn=@i=20 zFZ&h^DGzDEU*_+T+CbX5z76SBZ64!ED+ST&iyO^o;=^an9mUXs#KzXHB<^X2s&cM-H85wqQfyw07=md6|S4c`3p zq^s68mBL3O_ay1wKAXuiR!*KWdF~(%;JAmECVh%(7925{5sQA zBv2*a`LsE%^k&`WeA>aX3f?*1(oGg5NuB7h?chYc4F54V#^fQ>OZA=G@w&HgS3l+2=v2BelnLl|3 zi#%Uj5S5Ay^zV6=-0#Oci9i)zp{ODB(}RAqbLPpNCMsw_!lb~K_|%-qHk~wP1L`U? zqD!~C@T#^s5`ilD&S%zYOk1Rz^Xe6!NOz9+bS}n@41ScyI{i-s#E$laR!RS^X`5au zXhEWu!Glb^nZmBtqT;F+&uBz<{`js{T2YoFfvV|q>_|}FSazpwfFR19cA<@`Z`Kle z+S5A2J;WL3J=v7t_M~ZLJu&PU#KwyH#35z%OhV8c_cb;al-4P+8jSG>!H1x+2Ev19G zM4$@qNmN4c^q{>KKh@s4T2Qngk+s#1c)!bHL$?MS+qmOFQ_8&24u(~f2vo^^W&Xv1 zCX|fR-0pkPcS#t6I+uPluR z*-HefB)L>1dqa#TxSV?IOsgu3wXW_i5`ilGHARle ziUzdQNHcAFO+U&)JxJ)(hHQzg_+M#y(#YJ6Rqqo+f)e#)Sba}6DcM*X*TmM7?%8dn zU7y`pB2a}rBEC3_?8RB}&9&U?zS5l|v3Q`Koa(EvL-EE+&<`6r(4r2JT7}`wB?490 z)1ppM2@g8la~50j(VJc~@gVOjn6bIj`jc~$^kiUAH5R%cj!5^X+kHw@VK>v*=p=vX zK9Ja&rziJI+A^EMq2j6nSr!Wv|i)edbP^RII?NHo(!G0S?zWy zj{J0SCmr)wsO7`@i>vB#+m<$2oInm01yZyifo%(4Uu8YL?lDQN*fx;jl{}xLCr2jz zQknU%VpsL^mmR%sV#OXg1WLV&#Kz$RWw>_w1z70vK{@D;dy9L?(!IsQem~Pmhbs%@{IT2-hj=`?Bv9|h9y(^ve zDO?G#Zc5RDglT;{(xPrRLumO`uRq^_ z#`LJ6?CB$>z2C(*YFyQQTmR}yW;^JKeO^)Fr|^NK$1hhhv)7Bl86|oOqESJ88gsb3 z(&&vJMGF#F#9Mo7w~5-Kgz;&=FiuZL&DJTaJNioms$TZfld}&ysQE2o1krM2G|hRw zR9jyuLs|*rS{>K8qVC7X82ZU~sdoPEAPp@@$SZp7#}In&)+Vh%lim`6DqQ30bfKLF zQhl96TGi%}8d{LJY&n2*-QSE2yWdC^b+&8uqER9vU3EfTn5)#(noMbM3+CWp`AMG}E3T!oAGL)V^8ar~_9_uL?@&ykSVoECQzXwPy> zNY^LJlsd^-q<+bRg`a&=B@gY5%pv4_+R;L{@y1GpD?+2`mld~&)BYn0ddyLU{%eu@ zdMS=ht9yy;n7T#sQzIdJgby7^pk`-EC`)_Hmk3m$A70Fs@{(x7;bzLt3%Qbq9tre7 z>vSj1C(*B2b(AIhM@s~%ixvgqYTFRpk8bA>N_ekmnl?r_P! ziv(VwsGZO&g_=0tApx&~G#p~U|Ai{_UyHMy?vJEfR)lCrV(<8(1qt)q zY_fj9D|PP4hN3oZ`zL91zIA79+lii%XB$=MDHi^cn<+G@C`EgnF-GzTBXOr&7Fk#K zi(0V6SmSqC_hediVVc&w!zYPAmFyAzR4s{Coh&kCZA(l3T_n;@W{{G>Kh&5~)~cxQ z6PrMP@13qadF&z)sKQZOoVw88m9nwt4A+_)q?ruPUU2pyRud}>^rqF{2J@#b(!2zT z2R=SzZOm+Sx}R}1p_@c$&*;s>G1@^QP!-wNn{?k&Shz6JSbfi_OLKbIva2%sAA5@X zr#OGWJx{UwTHl+xTSqEi<~UNcAc1oUaq^<8H?^?vR!VYbi9i*8=YdO1ICA46g+%7~3 z%c()pf&})6PSO48A`ASa-67p=xhCZ3MK&1C;PFkIv$c{EMRuOz*=SMd< zIP#=^6{Y`$D)hF9=!9uObjHtme9dnM$+v{Wivl0=VP!t6a?4mnaQoR-vSe>VdeVw%Om+>J4iRqnT={m(tt-j6sc5vanIzD{>`WJg+Z z_;GE;)H4cNka%^#KpN)6Fo#aYDuP3Iw51+Lw`d0^ewPST$?Nm|`@`w}E3>s>XTB?F zLE^_%1F^U4$QIWzRuQzB*P0&BOxF^2RF>A~sFK&tAF@K}k^$|t*ZNA*N*IYfYYgP_ zByV=|ow16bdM=R8>u#etrdde@s^pb$*s(TrW5ieHWmQ{R*CKJcrGfmYVZ{b-G*%H* z9sKFQek<9lDGek7RXENIpS~f8F5TOeg*e+t>p>)1?(`*Zl1i{VXXDpkn^yp>wDjCQ z`=RwE0#*2B5OEm>dusKfDZhJioU{vo{(bbS>vVTr-RO^XuKeP=Ns{**iNr0Q#A$0f zn_^wIQ}OX?h}&jdnJkmwG<2E%j9^@^TXrG_)WQwIGUY zs2a&C=#5nbe=qDz$7Yw{HhUF`KvjungUBm!0&(T~#uJDiOpK@Iw+!S(ne7U$IhGuX zC3$Bjs4v348E_^m#*)Ycx_ywRVfprT(y9oF;kI$)dB5H2jSyoU`V9+4(Eio0?Caih zszjg)XR@Le>w`pbGG24$A!^;D1&Nv7@nnJFp}H#gv1p_6*%bQhKr(xqkR}nR!kMht z)#oGV-5rNn_^Mn5ElAXP8&95!D*ppY8ms)Tc1xoXW>4AWZfzw3RXCH?>1vctq4)Y& zX?;w(DriB%&wd!GeV{h8@i(4UuyA>r*!gkQ0;*S$2vp%rR#dsMOrhV;bkjPos->U> ziMspZ$@;5~>|%oP)CI4FsnoXPV9gLen;?NIoXLu4kzpg~?wJ!clTot?T9B}r5l2pm z(chdb@tq^uwU8Q81OyWDJGe+2K+6=I()2y#Xc1JQCqz_eD(XRR z?0uyzeAPlj3ljLw3!ml7NP5rvoA%T!Q6f-l^Z<=bA*I3irHqx=|VRsrP6%e!tmvX>S_| zc^A3wP+Pj&(T#uh;}U@?+=&FUFocaX6H<|>o!bnE8V+QUlS6eLiEb4KC)aOg{GlsK$X70wyO?rU^ETJOP1ZCSx81uaOdZxv1|bqQw`;*EQd zUpDoiTUXA|vc1kr1gdb(DB?0&^rb)6j?j88KdqnziI7I&Wa@rVmwdP};wiYmistG7+G8)fH81gdbhEZ*~Wv2=RZ{@UA= zB??-Qz!6n^Ij;_*c8=-VhJtvBKo!oGb-Dv{Vrk%*0!?=!NkIz|_+`-P+Oc@LEoiA` z`PfP#P=&K)oo;YJG`&<-)B5DsR?vb3e&NJ9)dOQ`zxhSl1S-~JYiUg`~wk+azyY!~fZ$4_vl0u zbZJAg%GBbe@~x!xITARx6P}6n{`6I88-9Fn6Nx|-`X7W3pr;Q#R)`w?Rvy}WLNXW5+Ug!1HLYx|EbHGC)P=(Qy z|C39m{=Z6|0W+o<(#NM0tATCFx0(Tl2`1TOXK)8XSGF?T>y|?Aq@1Xl0F zI-r&jhkb9{7(?p4H%1O1ffgjDJ~`^U#XXnoA>IB9fhxR0xec@+k?_gg(En%-u@D*4 ze>aAI~r3@a-1(ENggJUIP(8Ae@ z#@13c;MQ4XNY$Sa?8cKQ&;WZ-bDgcVD)lY#7!zIg8%JB?MD!1uXg@C?JeTG?dn`f!3HpG=?yi7vf27zQ@VAZ5F>BY!4P6&%71Gdm0? z8-^Lm^a+72g$^KnoHxOIeZ&qP}do&BlyeYy$~YVXlKrpaqGB zrR+)OwwCN{g=)pxKmt{mvmv*E79`4-bRhZ?E!o})Rg1NO1gbFiL~a8uNCf_LCnFLG z`;=l{tPLbkg?T!18)!k|^gc4Lk5~#v#9=Q#)ATeNcAc?Q(%&uK2 zQS3gDKo#cy$Zenni4wzu$?^yGtkvyb#oj0+P$kEB;gg6KB$fqsCN&P!WbIZxDb@zQ z+nCk(=l2{fNXYqvcvVQCs&v&cWJ~>Q)#1c{>LLI83!()H%vY3q7YS5lG#^c7Ca+LC zcT6jG=V(Df&N#&TxR4t|c2E09O@6yq%I7=zU4-t(XLJd+ z?A)PZ1jbD4j1D3XOV%U{vp*Ox8bZEvv>?&!1R;|b>B;a{#@%qdk5NmkNzIR~h{ZG; z61mBew6_l-m%r)>)(Maav>>6cWl2nrhLHK9rq`bdRF&RVi+G8OU{gdzFqw#ns6rxq zJCJ$D9LcYXm5Fy^M`C*1iPWi8oh+bHWM%*VRMPqPDZw7aoWVc$E?SVl>_hpgkU-V% zrJczl|C-G2@qcP&{(DtuK>~9k+kJi{fvN1gdbvkgp2g1I)<9_eLhr zf`ptci&upNs;Z`pASHL6SIhTUTQ)XT6BWy32+-*ESd~uIo%L`+qUy z#vC)C4^Sr1f&}{gWCATnOnMteI{2HA_bqN1{!E|>-+!4v3ljI{1rx1&b<&{Qe`?VE z`y?WPDjX%`Hn0~lLmGQsCeVTe#&7?bKoyRzGJzH(FxUFe1gdbvkO`aa;sgv`3*Wla zJblwQrjf3yt6{foWdlY6%LI-ATo6#)>ES zejtG=teqkgXhEX-#Kxrjkw&CkH}hg`Ab~2Z0VB78s%uT`N$h1pV(e=dt0#l^f&UAM zE&&b5kjIqtzx1E_aQ{BLNT3S8MDkUk1qr8{)@19hR-{+Y|5V2Nw+$pvh2KZH4SX7~ ziU&SDGJzH(u+GSz2~-U<9ZQ3LE%)Ac3lZ3&xU@)q50f z>rzET)<^_ckid!_e)pbE1q{!E|+3Cz=wuL=oN;ixSWXh8z=H2zGW3g3U3Xi(3LjGPih*8Sr~ z%6&E^UZr+-}senrvszxUfwL86s&O*K79)G2FkTvLtr z3JG-Km_a5mIuv=S(2($VwAyfcFZF+q6rqBIx~tT%HX=-2Sl_sM8P5s{bgf(Y($M+d zSkwj|5l3`Rw2FGN;t(~XcFX_A=nkJb61GlN)Vni>s7t2) zry}WpuN(<<;Tg(TjtUYhs{Eq9tL>w%C}{PsCx`^P@b|AMo?|q%bWSZ&XgX6npKX`7 ze@mue$j1cr=n4D0H_J2Jm6Al2bn9R+Tb|QGmZqvw;SIT=EJpBJ#`+`c@@ z--6?=Ex1dJ-JD%|<6*O@`7aiNcyPgv`Ofj-%R|jM?pK5RJtk!d8 z&Q!9B58#JW%5jXCV}#x>W|!fWI7Uh(<1yB%4@k~0op^+c1;_XSl;fx%amDqsA!%|19s19e&uBwQ#-Xm<*2PjH(1mj$Vx3ooY_f8jC;xiKf}?^2 z&TNQ0WKoqRce5X_*1(M8K1evnW)j-QFj?HIHUHeJt!{4W=H-6;ij5gZ7tWZ;goRs< zx@g02UVEGwM+FIarooMVQ`dAG#@)8d1iEmZLacm=dd6;cb>sGm1;;(Z@Etoa(3Wlp z@uRVAs*5LB_h~V^@RRVI`sFw(NXTzu_t|&Y>d_iMwOo-1ba^ear577apkohx)D@*T zd%wL?O~V4f7N@;TSZs3yp_M~xgFhDvWV6kT3ru2VMp)uUPxnF8)r-!x4F#L zI}YMeuZkoBUGrLf(S4N#^zM=!g0QIYgc-y>(l33_Gjx5lv7vPPEqpwO1iDOiYKgaByd-EXgR}z6PybEH5!iRh8ZFo1nw&`nz z3KH*%ZE5AV)2K&zWA&sS9qzJIBR%-|Q6D7&UGm*sck2(k9RSR)cSP(f!}4`NHZV*EzD)H+IZtD4)`BDnkW{3NP&G)VP&2 zY=*H;(aR1cY`fENp6Hk=5$M7vE2^HRe`F2J2J_TkQl%$|MC+0E^r%THHC?WYh9munxxZ7H!=-9 zPJY)n6yE!QFJIWMqx8&?P`=yK#TKjR5wm0B3A!)%!Fp}=;loXbNCdj@`HNae zbIf@9c3=M3yBaaPtWW2yUPE^edu{NzQlC2hTtf%Gd~9&r@>8F)K7-o*{4TCz^d>XD zvDq-5yU>K7f6+i(|BoFyqs9`SA+nPv;|nE`0uq!X7Jp%T_O*^!qLnmElOeZ!D)f z6Y8p-YaHp5Ml0yR%U0^jJ_>cext6}JVO-%>qM7hDKlNCdj@jwp&lzA3leIGFEW5GdVUBy!t1(%vIh(|{0jag5hp%y_Jy z4_}-0t3;p+pRD*^#r;pyYeG$hbf?9zZ1zFS0dosHwcFH`O?pRAU=_W8OR zDoDiFH=*@Kudm>fvDbI=!fRIPWdj~@-&P{f^=(=M`m|0m%_~og*YWrU+mZ5y?GdYH zvEO#Hr~%#cawa`jrO&_ma5lf*W05ON`LQHb!`>YdMSB|1wXbGTw!>JbXjSJwSwVJr zexyH<2z22YioEbwkJ;0}nmlf0YYi17Mz3x_gHz_xZcfHoeTVSpZ2iu9eB`|*5`ixH z%9}(LGy5gine}^bsrQQ4w7zOX`t?vS^&K)y9OKcSjG5Ou#d4z^kF0!_ykali+BjS*_^lz$@UBJ2JfEmG5r3bGx1#=6CaPPnnb3Os?Ww4pEQrP# zI(ydTIUV?Gn1%`x`7z=@)oM+Dgc+;Dyxfz`whXajf36Id2z22YD$0z0j8#71!isu~ z*HA&CPGm#cv5hmmzT0>m0nZtm{Y_&nHit+Ay5uW=xjmmfPS{4f^pLL{uW9d6G4{Dy zjsC1)97hc*m(9AiNTMHyPu5UDV)Y#p+SKibe(_?QAWjUR?AhtR^)ebR5$H0kX-GGC zJlCx)CktXsaW1>p=d>aC>?AEvWFOE+Okck{PR&eeNZ)SUttT#+s3NT>n_>&t_Ua1_ zA+5tTRFF6?j`8WoBYnBG@fcTIGIlLybbh7XGJ!7ntjac@V=XS{t8L@PYt*A5?UiJy zH`YSbYBL+sN{^Q5DF?z;JX`TQH#@;nER)pI*ih*@kcgPqkfwdxsc)NTtkCo{{unEI zG+sUMMkdgO*Q6*zH(zI2`)iZ*>>%yZDieBQiHW|a%XD>R>xOhsgTnm6_2bloof^_L zvmfN2j1Lya7@J+f;%%KshRGNWT}XG|-GI)Tzuo=QqyRw-cyN_@bZbR?DhFw(AThn7 z3H=mQ>c0L(m>?cJDPt#Yd68j>eiDJMtw9awtL8Ng=Awd~hyl2KVKv_lCUMVvHB^vL zo;%WZBV!FqW(^cXarxKm@zcSCSM=9VK_a!0LY2aUh6m$D3W6^w$I~l^kRyu+N(8z( zPj#f+agSlb-(G^)o?4zaH47u>hx8XKTK`8uqH0@58qw;g!Nb#7|7yrSQ=VlSOg@GT z)=)v>*q!fs@ql`&OPl_Jn9#Qd58FA3(~M^5!tk1a9A6L-F?!8e@rClfpN)=)u0j()s+;K*l%4dc{`!Zjb(CXq%oIDoEhY72@4(?!c#N zL&*o%E)sz*`K+28C}MkS5MoM$HQeDHcYbfaBU|rjJw)yM)R$nQV8 zk`` zRqQv>y@ob=qBpTP>?INC!YH@s0Sq(IvQGGtvgSjz6Rm5i)+fpt%z6f@ShEJ}>WR_a z87D2Z^=NY9PDg346g(@e;v-@i-|V#Zp26hs`_58*A0+UOh+cSzwKmXpDlsqhkO*{P ztshaZFQbN*Fn1Ce>(EQ8JBS2U6jYRPQ~o4VHeXYF=!;Un$r6FCSvO2n_f9|bhQ-Fd zsLKVNI9k=A`NzUFRFJ^>nPTv+22$;mKw)6t-Tq!yw8R8_8cz}=)y{_Vy)%;Q)F(* zdNz~?Xjpj`>((mkOw^IH{pq$|#?jsJCnt#S`Bm)N+>sh8NXYeGMrhZlKeYKs23KCdNSy9rw{vhkiTk`fylL&O-8H#$A z&NoTlWo697thlQNCJUAs^QO2^YRe1iJ9aDoX8N%{22A zKOUaqEbY30XNY@5i1p5augTZ+(R_OI#nR3WNDScL4eNJrqT8w(XH058HPN;t4(IN^ zZzKX;xRZqV?v8p+Ru34-$=P4o*N5K>k1B1X4*ksxxat#WQ8==_iB{*_FrI8;#ZW;4 z*N=*-5tmK03KNI(r`JDGB+we6sEbxu565Z_XVg5$MAECi=UD=ZV{`{`~jS3+!;?FNT383+TGV zJ9Ml%gLg#qcW*r-?az4g?KO*}dxZqnuMzR9Iq`8l(P((^z9ch?cW zkBcQ_cwA3@X5u}GKo>q6u`|%5mFlScFgpD~y!PjKSA%!!tNQh$$?AjC4teJW+|cV( zT%h_*b2Z$o(vnsQnkQPEjW*TQX74XhpPBI*DoCs;cF2oA-HLvRPZEUMCRHt4(}r!I z6DtwuTIla;*m=c^&I*|$h+}=Lt7EtHW1|yiXs95OT;PxwvB{f0pJL4SIi9v$y;gHR zYi%7R5$M|ZtE(a4_5`}>P^=&d57ky@97<;nH>PT+AWgV(pH z&8L|0p$CRb1iA(%cQ8D-ol4(L2@u4WN6l3)(`r0$%peUFB=(kf$m{-O8T~cF7_+oL zwO8$BXvX)RArgVEQ5GExWcfN;$K6v9G2U+KG}{im%VK8@6(mg4?DK36tfwA5jWJ8_ z#Z)bx?9JCcw2}yP9SwIe@ZYyl!z|)S)EuTSPv$Lu1gAd!`1mzRD&o1R}( zO%N%{akW-J4BxP0fJC5cpHq9o$Bw(jO!aNi4!*e2Rh>{8$9?Nq5mb=a^2s*uUcnyP z+^0kk&glgz)8qL{FB26BbQLdfHvHasH*J!&RuE=$Rn=ur0*`f0(NRIdX0mOb|J^orO!66n%Cv@@KnolUp9b`(VIQ7&rHgE&5WVO@p_5@D}x^4yN) z(DSo93nHz~UbR_fG>XljpTf*5>yt(xaCiXS}tRwB@axnCmoT4t~Q2pz#a^1d-tkZ{bcm$xr* zK5clyxW2aDU3+y-ksmL5A!?XFP8zx}hfPt|)U8S9r2BC1c-`*HgW5pSL7uWrU~d$aG=i9>P$9jL}> zs33vuir8<$#+iJt>cpn4jg|;>o$RyE;Ju&+op>`|97FF=jkMU;lVyvYJyAgd+Z8cC z*rEfmu});6)>9<{U8n8$8Il9WQZLgeaf~`|Ym!EWH7xS?2n`h^uw7ACtWSuF$&}yheplf?% zuHn|7OK73)BaZR@QWJ73t}0JD-%mpY32avs9+tY=&{n1)O1qp0d#1}3xl-wNU#m_#fDiP@V>A%;IT(XJ2n`+FVzpHd6 z_M3+Cv1Vo(Do9`}A!-PnokqOV#`5<`j39xo*du!k1w%5$UO?r=F)sRbCx~B%=eNuh$YN!wYJHcGa3r9lELk@azgbZ5pyZUN=xHNBo zb0Ih*Al}4V>qxn6JJmxgrf8@jvBYwpVMU&eu8c6YIKPZeB8!=ey1pn%BG83xm&lC@ z=tYj_hO33Y&5&9(BnDM-H5|IrLNDH79OGzhY{|l7hYbBn<0JxI*ushG-*+<9rFETE zn|Jca3yDXO4tZmTwAC**nlFy=aCSY_@1~dG{<#EctcETeg^4FvkVr-z>Bsw8S#ZqF z$DDS2vf{mpTuGdgy!qVP<)mkh1dew_-ShP+Hc6SNMs}jH~*1akb=)&Ko7~M_FBumcw^MmJ(NxwlPDVBUKiIcc`j#Mp@gPOX*|v_{Oq;-K{yj$`(1qVhu{Zg&gJQp> zVD1q-LHZ^lAxDbp?cGcQ-%aEeg-#NIF8qRv47$aXtQ-}}^;}Da3KAGQ6V)kCW|Flb z5#0TFC#f|+7q&!V2TAv%=6*-QVeOfFL=)#_XxK|lRNz+dO{P689Ql9|{j9-f@ zZ@ry-HVowVQeR61y0A|q#^-DD$^I`rcy6hw)b~LGX9UEr_Q5*x-QJn!d~GBV=)%68 z_$HR_CQZvZ@$8aTQXdWpoC^^%Cf%2j6vrz3=?71VKo|B=#cy!OCUT%e;a0icQePAa zoDmXh$(AOQ^W878Gxj4T0$teG79$pIH930t2s>AKjMS$_0%zq!74x?VBg zK~ptUkifZHQD3xqEcrbtoqB~&mk4ypt=i)EOGx(2mh|0r$aCAQxR5xEuAmM&6DASplJfx0&pE5^>e7fD z85b+92E-MB>&#pXgGOc6YGZ28Y)Qm_RKYWP>;KpBpM0#D>F$G zueK!6e40d{YgqNYhI_HQ4av141aYY#lejxLlS6aDHB^uYv@lUUMwYs#yfS7q7F0Y* zJW4!C@SJfHfv)8Giu#ZrG&C7+jNGMv(@CcJ0P@B*L_-Dhz3|u~bD(H32@CNeDcO^y zV<3UKUm~9&*N;5!(V09M87UFy!h5JFfu|p+>-uydTTjMF_X-I)E3E1aA5}GXBln_X zB?4Wz&Qr8FYs|Dk=L1Op=)oFh8)3$dob|H$p@rr-Z4_DPI#9}CK>~As#9j~`&9sGC zBgow?gCzo8C$4-qOc8mOS?!E@mizSzT1K_exY`vZSnH=%%NgCgi33OrBo1(<;o=+lv>qzeRouXl; z9A*N_XEp!xS`uQ}gPdO_=iDKI@0f@Ic%3H^cYVmFMS;?FpbPJz$W_~Zn^bZ4Cta;a zN%sl~{1qt5fz&tTN*+{;-=#t-(-X`?+Ko^chL_G1_esz)4Q?;`1Obrzza7DI=$y92t zZku~V{W~vSBG84S7xBHScbP4y(1lnX4Ad~67S~r})~urJKJ=QUCiEtiqy05hkibk} zv4`}jt884$fuxz^7>PhvgP7g=aFIcKlLm_4`H2ZHSw_(?a<;Xby`_M=V1YwYB~p``K2(Hbg9V8*wi3{2h2JdP0JH8@lv z&^2*DuKujcare1%jjdW-Tp{~D)}2)H3DHnN0(0HP3Z94SSk1mQ$kwBiB?4Vp)%NL~ z_uJ?}0mjkxwbGsJdZY5hzrgfDY8=cphduW>(O=gD5Y_vL|izcD1x zW#^c!-yM}o7nvHPI7?>Qv8ks6_*Kuh3>73+JGIq&h#9) z1iDJ!X6w%`uBTOp8lzELq8hQ}av|K`?i51>iD@S7^lR@n)BZWe`H$~^3}MfMLwV4Y zEQvr@y-7Lx1KTa48mlp?)?-sk7PNX2-{H5Op@PKcgm(H;F^{w9gmE6{QQ$~6scr;s z{&S8*pez1;j_z%fNi7;1qk~?n+q1{RB6;Syu?!U?dR1`NL&bcQeFx)w6u%ZCRw706 zT8|th0$n?jcI%U-WzkhLj8RVA)xeJ4jp5xty`-oh@oKHJ-bKu-4cuXzSL^g@G8?!f znrBq0BoXNP&2f*uVSg4qHqRKX?d0#l%6i4}1gl*JRFJsSvAw=Y%nvs1Zk!+7^&*mu z{Vj@b2>GNUfv(7+J$f?{bv`rB79(!d$}N- z1!fN6caQ#*2y}h@zE`&pvj8psnFXkIwG-PC+K0cmQA0xo30ALz{&U$ny1kQe-g(s0 zk*u!Xo@+5JB?4WC<8$>eF`Mx|-#D8wuXk%^o!yi-Ug55xf<$3@2YrW_KTrN={(O9; ze(c8AD%|&tw?v?8eMzofJaRTI_s^`%<{(E_dexLS>+7qbf<*N94*Eus2atKem~mdgQnjw&XToAtj^v|na9>fPSa39qVi-{-CN{kc>a@@ zaiNCBG4tb20vY_*paVZ^v2UT4HYB?&2-f_w7RM<6S*y74l<-WJ6ryR zq0A~)BG83xm)NOkOCy#sVTjsvK%CS@A@QfZtDbzjg+Aw>h;X65KkHcGmTD0fEfMI# zHdy4aqN7ce>EhA&(kCVUD%fp-^4rp zn3L$e@-IQP-H+TVoG20K!oHn|4)&SF!qPm*Zqun!9}Wqu+#}Z44qnEBT67}! zZ%>v8bjfS5X1Be@Mx3oq(prtxaJ?h0)WklDShe+AA=?&qLA6;NDy^JELSD~V`+XX# zRXjp%Q#e&3(1q``=mG3XWlayxalbhsQhIlh!1bzPe(*sYJLcJk-lNkc0$upq6tkA^ zQ<(43J@kofr1Tp^0$1mXsKKP^Y=wJ0)-6IN(1qU^5jA)rc8@&LmQAicMf#Q?foqgS zTe~Qh9V{QuJReSy2z24MQmp?lPi5v?eq&!w$X`(;aMib>wBI(D)ic$Z$CV)ID~c}s z=8MS0{51CL=Xo|U-(UK+BZ2GPMJ{LK#Vjw-gtr+mKqAnEZI_~C?b^yFcB#yBPjr*o zC?s&zzsT#;*RX|OoOpx4b`pUuY=cE?=~XU!SEU{Ac%Z)2)*^v*6huzZ_|5EGgJv%A3uU6^!W56B<8~`V2^5JqWQ+T$3#J+u+f>Zd|rRpbPs%igJS#u{9$D z`O7YIrM?dma=nbmpF7#o2jM(sqMbyb3wvrJ58z@ETf8)sf9tcb&{6+}d~h)EV3 z78AkMz0vvjztDw!R7H99pn#p;6~=3phDm)Kv zEhKu#kJ4Cj#bDn3#X5;V7mj_zzDv(@*pfk``Qm+<(ijH`x$01Ix#g^z_b5Kd`GiEE z3&(I`7rxtD*-_77eEqk}(pU`%tPZ6p8}t32-tKphstdfV3TahEY?-^|~K_h0TW2Du~NMK7XcAV-mnffo$2q`bG`bC!<5nfXI zfW8~kk$iWWAc>k2y5xvg!OQ(LS7+*(l9?JRNMH|8R4MRlP9I!vuDUEqkO*|ic>u4! zXVCH6CK~p(NYGG00(-I|3#p_Y4T+yh3j$;UU6_q6V#teE(stMXpdRM&8Y)O&k6iSY zT2!Yk-n3=)#oa{$U6_q6_UG)KO7DO6X3uSAXs958BMb2xTvnYnSva5N{1zn<=)!Dl zMQOKhIlWOiozTHeolL&NSHnylo_Ie8qzFL)6DH^Duf&`9OMYhO*7SwfkGj5ur zNd&qu8(ZW?UEfRRmAdfMgY7g_kie0*$n4K>qfH9E`TCMN5`iwv#unKkX_Ov!^5qk( zEj3h-zzBkv;oaatzkM3ds|@>-Ab~E-#uoDiF~{h~wv%~$^DKf25*P^)6`Bk^Xh!`R zyyb|&5`iwv#uhz*YRBo5mT`QSR)e5|1V(hkT7a`%>C2@F{LTkU6$x}T)hrX|;Co+$s7lMFL%zjV-cq6Asgs=5hSEvo%8n35>9b?{16> zJroqfD{LMk5$M8fY*FE_&0hL7Gm1Op%x0({fssP-EqULPW~)>AeW&#jfiBF(7CGCc znY2dOWL_sfi=l!9Mm!ZIxj|#PqHieAPCF$L=)!DlMLG0l15Ld;j(^O(&QL)DBe#mu z<$yIE{dp8Wo$^*9(1qF9;!V7_mPY&;z%AE(W2hj35onQhUm=aUnECPL&CECw=#sO% Xn>xLt!>0}7u4!f*6(q1)tfKrMj&LW) diff --git a/data/kuka_iiwa/meshes/coarse/link_7.stl b/data/kuka_iiwa/meshes/coarse/link_7.stl deleted file mode 100644 index 2d5d6ecfb47c05e3bc2bc88ac6a465d0b5486fe9..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 569184 zcmb@v2iO(W)&4yyVz1aMf}mJY#P*yyg9<95QNS7tiefC-yP#q((O9C+`zaH=AeO_g;JLvi90-&O!T)-*dO#LsyFM-=yTTt2b=QAEtcu^K)JQ-Fk!Oh3C&()Aa2ZZP;h`t5(%kjYrlnVtzfaxsrHWEfLdLOw z8{B;I+e?jIE)^L>J#g#_&9~oryg~>qu zoU=YltbO$S?-pkwKK88~X2d9ZQ@$fAjYX z^)!i;uBoL|6xrpvqJ#{wr=g{6*FgqRolE6*#F|(0k}n&_e6ob4X@_*MAQEaEO4jDBK?Twn3_^pQaU!*H6*HI(=)FiBF z)?rzP=W7fd57Of;P2FV%C1g-{X9iK?QyS_i+UtrEGCJEK-ngN@Q1g-*t)ZSx(--7v zv#DGvN)Fw2^TyQ=C5B>7WdDTL4=pchAnRyyIpR`*}2^nmsa;eB5ian;x zn0NM**1hGT4XwP3%=<>y)LVvHNfvwhvaWe99adonC1hyq5Nf)tgAAfPU7xwljk$_Lwq*b=7;DdiU&`wbxsj!TOnwQP|X(K|6%q zCHg8Xr-TgFVOfXt#F~r`t5LQA+osH*M0$Ho#)p-JIh7fdkRkoJCgY>R4l;<+$V|qE zmA0&d5;CN>*MfiS%pl6s6*@Fp5x;8^qR1}m5Fb_3_&~?A_^4W#^)-T$xurq}^Aayw z(?~%6LYdAg=)+E=!N5;8QF(^9sViVULIPGub|mG)JQ2&OM# zCBw9np(9yimiAJy>_lkbvCh!#bwvhIp03a# zI}`CbPcI#IKZ<;1k0X}dkE!iCD4`D7{fK4v!}c}GbwwSrml4bEhwYJ&U1m^HV$3}> zmfepEJIIjTj{@a?uV64=EuoaaYGJYCN5((>?&OMH9JT>_$&U+e8h8B{%X(E4xe>R z>-l8{C1fxrDl<4fG(OQ@GyPa8GdL#5kh#3r73s_%>a?|PZ*2NrTrr}&u1vx>k-n>} zgAy`2$3A2b)p>l-4|2Y8Us>T3DIufttVRY=90g^|DItS%S7!!MoQcW|t}_R%ynL<>rPgis-tqp5`9oT*SnInF zjdp+Jd|s&-wUm&-y_&KPGKgaIQD$(a=iU+{gEE5> zGPwKInL$)%-%be`-ghhNiVUJSuary0kt)%0akklc)KWr*#K9d-Ey*Bi`<*vxp0V_a z6`p|-GIV~@*{I#O%a|x`3&@OIoPa-g_~y-PU+-ySvuwGS$|TbBi&JFxV-*Za$k5qF z_ZQnsMTzv?;{233l}kkl8Pbo7v)j%LqB^gGKgYaTGqkw%yI4>qhbsa zCF|PaW=&@XC1kkwsn9_NQS>ooJ18MTV{46a+Utr8qUedrI=E_-`J*^L@4SMfgbek$ zQp&i!RAdn4EnC6xeq|DR1|J0#3?Jtv;i(+sxw7SykRko5!`U4fMENXQQ7T5S>isqT z(fVOrS}qkOWbj<1GlM9u^veuN$lxhZX9iK+4=6LvUu{%zOHbD4#mzj9%`$@$GGyi5 z;g%j5L~))k>tJ6J|5)52=-jU;A%ph=$~wp(iaoT@ji%g3tA>+qW zhc_2J<0LQDn5V~Q^S(bdz2oNT7(jVs;3I0u`S;3x+VGL|Z>LO)DPg{M{eFYy?5AGi zI%eEqx9l&=yp?`1xXd8xorP=7Ne4aXjAfr4lO1yX7wIEQOp7V$KVn|V(>?a^8`_FpSx zyZoulAc{MBQS{O82W8v-eU0qmWv0bM{i$!S=7*~+YWbEKFRi&!_UGffvXxhv7E?mT z#CvCL-uOcwFV*|+E|X20Ff=>$)G~u8?qx>N6<2+cE-I}!?yza`L*J&2N0zQzUfk1N z;+YQ`AKtT?>saMaGi67AyIuDFMblzR$SCXhYVLWmTPKgoW?87rAgbpyis+U%b0%Hf&>Qb4bXbO;I%aU9YA0tTry2Rdmpf!L@%hzL;T1n@v&l#>0=NtB>3> z+emb<>||_l%Gr$rKHA7j_5I#|PkSG4{_z#Wh?M-8|-> zjbn~GI!k2??(@tsmo0SfmX?=CHCFb8E_kr}sVzpkj&E*0vAOT;M`!!V7^H-ZvW_(; ze9=7Q(TUlzG6u;YYTSZPcK@k=(6P+6h(WUd19Q*d35$4@rh&* z_2m7tc1>9?ufr%BbKT3evBw^rJtjVp5;9opQFPJLTi3sS|L{y_1KJ_h)>?GetSsv7nyM=Aw&9Gt<`srJO6_EU*A43(^-uSqPS}qML&%Hd;Kp5@0%?yGbd3y zKlqp08jnk~FLP~~G5(Nh>LSEjQwC1l9htOXwvMN8iKT7A8N<1&o^$RLV4tWk8s zuV2?c{a~kTujOo<7kPcY+jF(;K3mI5Rc2g%`bnJM~8AS0sI*N`RuvoJA#haMrM0Fq5GrsqxWvx_Y#(&>iCYj-=p_#@dl#n4FE^hhu z+Mtz^$4}_879@ix?s!Mhp9idwoc8ZQ)=P+z*(VM&S((xQ@mlh}%xc;bDIsI|S(lE- zzc;7Z6h-rIvr)3$j!R`4mykgePY0rCj{8O=TgvRLaS0`4$gCZ=B7g<18=V|HVXjQ$ z5;BOo=8uEohvs?PV}@sb-Zr^v#hJ55WeidxQAQl%66O>|pI<&Ed4KCKQ;ka~Aw%Mz zxD_oOw!?18)J5J(H7+58DBh)rqSbrtl{_;1kyL#mQD5D-L4197m6g5B`1eEmBq#rT zN2+lNC1gm<7>6h`iXI<%VDj9`7o{4PkUZMjtA5;BP5*?koCnRIk=;zuvnc9Xb7 zBK=s_0A1>Fc>d*o_qD<6ryZTFv)LsLjY}vYqpah*{~nc0xa-`e#tan^7UC$aTc3gJmbfb=2}$)N8k{wMzz3 zUhB0yF7XzuYYP(PEok|c8Qx3k)=Tocb(U9&k@rL|mG{KD_C)68eaukaL%mc!2J1Qo zecTz!N0*^|+_(-OgLNH)l#o%@;bX9lG1yiTA6>4)$6#H@ASKL~Hbv3Z!!}6f*s*V- zafy4iSX;{dqwV#$?{Xc-i%-0L$|8xzC6tgso1(~lVxm5g45HlgxeoV<34EeS$Y8BU zk58sgba^^yi^`7B^oV}L6k>PUaGzGh%C{Fj3|%DEZ;KYr#$LQH0q;-437rA zR32F-8d;J-lt-Lisu6kgYQ2Ogk6ta`GULKLLbjer2^k(ad#MI}uweborzRvCmykh} zN910r(+rQfqH6;(i1HPHGkk53U~OQMORhh1imbvc&76w0 zTB2(;O2`m>x>j=?zE(?gtwsh>zNT`^eXW*Yt!8=oD$LSlhOgBUU8_+-hO~{YQoU5O z=d092X9F^b^3|)C%Gc+KuFri+?kCK}yJ=O~uYcq7eY?knyOyEp0Xxdoqdc$*}BXh>y`d884OZ$s`*4kU^C1 zop|kjDSI-1pFGM+MU?NhSiWV3@5v;(CqoGt;*WJV%1hWM}D#WDv#M7sZ}s;&F-YY}(AplUSL9b_Ck9bwn;ule@M_S*Q7y2d3EUlkHEXj2sV9&%md5;BPLonqI~Pj(*2p1?Kix_P|T@Z zDoV)k8mZ7h22m_wSqDq?=Zzk&UHxIBOKX?<$_z@#c=CxSYKl~LX9iJT+Rk>Egbdf$ z-L8Xq5#{z(=wQEcn`)Xbdra95O2}ZXcV-av>lgp+uCM+;MX4wuqjSGvAN~5kdm4K# zJg4Q$QBW=wC1h;6*W-=%)~Hw1E*V65+Imb`2PLkmmo~HXghw{0b)WFN__V`U zmQwv;_1o*OeEn!$86)3ZH11w$K0}TBahCYPx%*i9!SS=kcb(VA8GqSmmgKJH{VHQ zoN@F0lhVuP|0Gq$KF9p0abPwuN4?!_>^5g?=_8L#8#7!NJL9Ow&q!}O{k^&}2IQz% zbvWD7L)ZJD@y}7KxgD$i^}^;}fBq;w_q3z3dCz;lvGH63<4smuy+0ZE^ldht-K-YB zvdG%~qv*En=Sn}Hc5r>_oQGzVkU`y1bk~5Ro9oT~v*{p%s4M%P)i`{{4dXNRi$#Ys znp!GnG%uQVQ9oyxz zdh2@eX|vCqYN@2WH7RfN-QHA>O4l;;(_O|=GKH6kt^YN)Sh>n@JnXBIT$4oUX)gC*Hil@#xv}=#PEA(ei z^uKra-=MFx;2CxGL0T$G$Y7r?bTpvD@*=9=37f}n?J$3%|6)ssj^}3lM|{QyFIt;R zEyhxd@omFL^yi3LW7wkcxXJUz3tq9YFnY|ie*Nnyn_0i2gba?&DBAv;C*ymzxX*Nu zLDbygRdmi{o- zHXpR#$atMQd)2hfIa|Io)5!R^y?fR2d9c^5eUrIng#J zgQz!;c%Z9$sZnnEK4XT)9}oVcc{obQ;4BeEw;pwTZP?%DG~Z4JQ9e7zW1krzmY@F7 zqRpE=8kh9=-J7Xc-W@D|W|Ik1Hob03tA!o^dB~Iz@s@76=x78T-`v0dlpF3G6~DOi z@cxo-x6JzSw9aY z3)Yvi_Mn6e_pWZo=Knk{-T%7b*5+goWso zZPZdihR;`CS27!uP7lyd`u(wm?+v{rx~;EySGW6 zjRut%L~+Mk{MFiXXG`6^WioBaFB_DQ!CmesdhmsnvrQgd$XZa=eN9>SnQwph=Ea)l zd^Vr8+J!qW)_m~F`P}l$w;q$t`O5e8bH0BgtOspJkUN`ut+aM?)9aqIoWx&^+$vjn zSkL4+v4avas5^>QTdAJiao!A8S7Z?NYrH~p;Dn!j#(DRUepz~Y4{Hxf$SB*f+Jx`Z zo$s7hS5Hj_Q4*In!^$#>Ug`aIGhX=G5WO}v68>?*pC*BGCE_WQ-H?@~g>(7|gpKRo?eXS}q^d+C+C{>j$0WDqseKi6uGh@W%If9W%S z_StUd*EO=FgpAwYTE97^_chKq>+B@ke##wnozKZ2%2)K>g2O-AI@{v#E9&YKDIsII z?h(xozB|Ynv#;}YbK7&zu)3nP=TBU-dBdI0)c!bmq5dqPtXQs`n9lLQ&o-Y^LdLzx z`ppl|z1r())#blVcidx~)fE{;v4m07{B+T*|66-lT~R{D)KMdvuS__|>uSNLH_lf7 zpITKAd36&QFPU+6SM0E ztXzL&-l$0l8Qgof*e4CK&k?T;Z@$$yp!QTcOMi)Xnz9D0y*w`JFELTG6knx?uL=nn z5^FVOAI0`gqG-)0duE4BN@CrUVO~T@1lVltuuMH`*=*R8Gu3nqQc}U_&LhinzZ{(% zxa{PH_FXbOZ7APc>dyC;-v55LY|_%m>8`aR*hYU{}iY1I9iK#P*shg-Pvz82roSPDbH}blY zxIL4&y@|Rq22o|ppSW-5?8d(iOLd%6LWcKHud5U0IyhT&!HKE%T{4LBvnkstjG{xg zKRDax>+{nC*ZNO`k`e=NL89pP%VtS`*t?IdSiC(N58VAiKkvtl1Fm_z-~HEa(mdhT z0~`6;VAS&`q_^&RZ&TL>l#tUSw2 z!@a9BZmV}?Ltc3()%GBRD4*@Tb`Rcs{cQWce3NS5rGyNh;hf=fl+~4c&c^Ov{-dA! z;Kokp-_+0N6}SB1bGA);OdV`%XG+NMdC*s>w~c=+edUJRtggr)%4gAL-V;B0<(+ii zKYwI(MF|xd;Ytt&E!@|~AvK59pfpELVni#0RtyOfaOagZ})H>xSS zQC3&9R(7UzZg0MD=hgjKLfi35Wyj0viV`w>AI0lR_Ni0Zr%rvJTB8Y*5XBNkk*pw7 zSwY&a0VQPku94T3tWr~1rCME)K~&lDTQB}7y<_aKY$mBIO33gS)$8hnjlN8uxqpXD z$2l29`K^v-ewKRCI{!}3J$YRAg2bYfkii!!Q50XjN;=0EyJXtiedT4^XI*({N1Iw~om)7Uc_tLvPzoZy{Mp-q~xkuG`#>Prh8V`PLf~GL1zkA%nW* z-Nd4&Hvc+toYfT>M9J#4TUNqeDp@)I74!CH;I&)r_~lte>wFoiXQe$2X2#>J00HdSa-~&I; zTYqTCuA!F{5;CO6)IyJuyPR{+Gho|u=d!w@wI{7NT-WN&k@c(kv4l}1byW*>MF|;F zBf2x;bv5bPG@0sa1Cxa-KP~QCP`dplh?-SZwcT%iQ$dLBeGcT{Jk5}toU+Ue> zL%%8*M3pVy=d>g0y^q_`d?F=e$hy52c5$QVpuv;t+4uX|_#lHQzv<}Xe490HtsghX z{@J4vi&8=c-_1nPqGNj|^FFn1@YJ#Fo?F|BU(p>lOZ!fkTmHu%x{{%nt(+YoF#}&$ z_-$M(iL6*-S+ROAIdAg7WWtMs%wJJLhRhO$?kGBOz~afvUktEPkwKJrS3ObmQpqVm zBBubs?-mj=%67;pKwVA&tj(DhQNBOt{mM^FY>x8Xy5{(CZ}s!jljdwce4=wy9OjiM zlKH$I=5tEOkXbvHRjNk-mo4&KeL(+fY(6K0C|M!LvfB1YW~&`$O;*|LE}PFOAwy!6 zSXQadm^O7#a{JqFTI@pxQ4-mg30gbaxW<5pz3`yNpef4YLz z6&XayN-vfbq+5RG)k`OXo>|)JiV`v;zSiAyXN=u$^W?1u23lQ_L6pSWx)1MlwbWv} zB?n&oWz*yKLPCbDePTIr_f?U^)b$Wk(^`p;V_6$E2Hv|sf0i(c)<6B!`m}M!g_ydi z6Eb{P-D`Kiq#nu5o4(pqpUAw3VhN+@+BN$o9}K$I);N@qA*&)iqxbdT%e_V?|2pRq zTjP*HRN3-P7uh{||Ev8Qz8);_G=4?b=zrzo2C*-pt`gFmeMKAesX} zB^%8)x$bM6LPAE_jxpOVp1d$_JKKk2UPO8CspYFXALp^gKHmFkk6gcI80WR)mam0z z?hM&ms)xNLAGId&o^K4yY{bOyjp6ls894wbT%X-+eq=XFj^Ip5_{P(r`Gha`(x*~%pmQZf7KJ-id!#_L~ z_Fi>nu{t3`R()}6*ZHqQmriq|d6(n{qKl4+M!k)9}9+E0Gt ze4O8S{4Vt$E<7U9*oQAT_+rE(HMisScTcL{`(tO(!pv+ykh~JpgMDO2{bNA@>04at|P!u@rd`<>%3HKF+6}H!*$nm&20PUU<2| z7YclpAf?r{pJL{+a-t4eoc_AUgS7FYO)kG?*2|Hyxj7)M?}}kiY1(q>D?hao#g3anc=HDJ87VV z3}3^A+WmB$rmR@(M3D@lXrHZEnzCYPvx5v@v3gy}iY1j5OIuwL#afRdS+S(DVhKI5 zXhAZhkLkS=Z^5sIotYl~^8rb(r&iS7UNDGa?}?&)5BWBI;`1@d+rpdME5c%A%ibsqUh^MPo^Vw+C8~4U8Qt(M-)pKMQ5#@rr({hPx8(-Up6QqgD-pJ z8$yd+kv=`{z+}C5UM?|+DqAl1;q=yv^(&sA`b`(R%f~a%;%1HYD@w?aQLDEby8`kT`F%uS#xHx z=CpoA2^r$GiAXQ`X6v{bfMzv0Q-(t?zb!M8xgexlVb z?^*fYqSdJH`+4myyKI)8ad~F7O9>giU+Q%=^XsptUF&{fb1fM}`L3Ze`h2xOcHgTD zS?y9nhRlz}`LL~>Gg&)Z?UF$hYaxn8-LrCb->hrdsHKDqzI>AR74I&eEwuiSB$3`u z22thO?cHm1w)zG0CQryX=UFq~G4XsjiUvfRWyzw8Cfjc_OOp~Z_(Dlm+r5TnqYqvx zS)RI*T8xr8AM5>hBJEEHOOSwz#?Qy z$dEV~XWO!CkjburMaX0j<>w+EA?eb$vgNY!N@a(|`jxB) zij#ab#zM7C7mP~e7tY48ql&lSLMlU-o zne4DwzoLW;*&EQ4QD1q<4ofCGEY`2cAj(fOy#-~5C6gVN7$>79AwyR8c+>Fg&qrkI zPwG+cF>+uy88rq`SuaJDp#){2^xkij<;#mT6(2W!;NIqig>wP3qAsqErd zdr(3K&+f%1PU?}#E>7&bI7Lel#aggkoJ@9c!tKwZ-pTN@?XG-{BfB`6?BduBQ|3h! zYeBvnwaD(7?BdjX7pJKA3Wo1^t-H&_?4d-lQHWdPzf9?nJSK@>R#Ymo&AP zP(p_H5`Wd`?{S*?9)}E~%9i^Li12!#xb@)o8M+7F{Z6<6;rAKjHm=?lvE4!5NFc-8 zzmc!*9%H-4MA0bzL&<$a-%_maCO_s-UNY@SqaKu|)4k7j3F(tES4*U+s~-8CSC zDBe4;eYi~a;cVBL5;ELZT00eL`+_MIcu_8@~O)`EN=ZrjB(*}1d!po9$GbBLm|PaKxX?x3{? z8AP!bqDXciGueT(8xWL`;q$z=htKD!&gWzh#dmB`cB16*RXAPJc(|xM>yVhWp^->-9f7>O33i2#u>5$ znaK{Moiva^lJhSyBGy6?w`ad^#qCz_WOxkkWANUGH_zU_ zWo|nkWL`wE$3)RWW46uCI&IeMNtq2OA;VW0uETH2rn*B<22tgn=(i@@>dIp+yUD{^ zm;1Z<4bxQPD@w@l_}W`gc574Ft!-;_qS$+Ew>FjCS{vt-kl|~?X6~tFw>FdA+RS%r zbq!#BlqimZD3aaUOm=JA#s?X`>hm$^E67aueV7+f9L?fId-cd>?7e-a^Eq#%_#Tjr zb6@GZ4!=*G={XK1WcW(o*u}0vhFt^8izt>*BAI;GAk$p~O33hat?TfWa5kj15;h$~ zl`WUIefrMJ`jxNf>~@o{4ehlg?-vzs$*f;dLWZ1F7cX4pw)!a-rt*%(`V|>O`EHB% zk~fyQCjDaKTz1om5;A;u#~F8B_;}jpN-o%8Yk>eDAE8M@#ZTI+YjFcE5xYGJKEJ z>+02;hNd^nv!vB78ASQZ1!sJ9>&_CzY-+Vj2^qe_>UAaO2C1AISnZNQ6l+1gK$Gv* z+Nh<34BxZ#y1GktIiDJLV5a*%WDr%Z-8Cm%+i2~mD-;Qgx4FY7d)SRua^MhO|b`z7a56FzGk`9^*#j0~c97tda8#qw&)dLkuc zNIMm`#U$$cYGiy*G%?dSkqn}Er!b0+Kjzf>fCCQA^xQytT=7j}X^-OT#?nr;*3Gk< z^0T|_Aldh!gbY8^^ESV9&$a9K&UJY9pzQmQK@>|EMNj_^{!-8S6(wXyf77o!c)yYt zZn3;@GY>}wQR0bkA5LDl)#Zho-KL_13_qLno+vNe>hi+PJRBKBiI2g3ICs5E%bPg6TT2E}tc56AcbA{)U1$G3(_I`&$l&*|)32R+5I4csB-NtIQvS;!((EbKVqCx#8i}ytNu0dVCYhXQ*45D~9QeK9={(47cE5;Ye8OTPWZkqFDI=%C?P}EiMTKN&LRC0d7WwPK?YH*1$zOS z$O}+w4@$_8H8t*w&UVx2Wb%%)*?dk0QT*aj6n(MHp~>-oJ1y0HAAa#$_Iiu&kjoyR z-oNuUKkt-%lfQm&xxIFxgbdkp!ktukIhn}I$*`YT;eouVvfXoGA7ldo7#D zYgyY*q=XFF#l>A`c`cjBYuUEGOBBbAoVD~ElgMk?w(&tm`L6S3yB?Cf^32|;?)xw= zqBxqPX#78qNw!&MazpohbIu*iOkE>hVojsGrcI1SHFq8`i*hR+azRo9oF(aeQ&`S zEocm)rn|G9w_sgckPu#;rsC{WhPE6u(0`7HK%lCccR3?#AnYy3K zXnUB13?D1C;*>0rQ?k0&F7qNv&cgJ)fivWkERj>Px}TC25;A>5s1u{GubcV-?iQo4r z-ZT)!_Y_g|*_?x9<+Y~WBl8tqtmE0&hL-jfK%Dy$eXq8`Wh*DT??VY0z5+0|eC;h? zO(eSSLk3YSVX>M>bl-;(GJG}R{Yt<6Iq9fgiSGN5K~&jtkKwFed1PTP20Wg#Z}fRQ z=e@*VpVigFQ9_2V6XM*%$!qeuye7APMFvs6W{7hSC$Gut@|xWG6(wZ&s?Qnnnmm!$ zSRcFRkJb~( zAj)@Dyd#^k2f6UiXTch$WGYgeyQmv0V)_aC}5D279AO22thTmGPJN*021mz+S#g_d-Qa8r;LlR|;zKl>+-E~ZI_1H^d{Z^5Gt=_(&9=>%if9@aB`M2(!A-5uZ%rX{lcaH8l~%D#sbP?{G}A)V{E;?aYWRfb$-3`#;;^9|qA&vlIXZhW%KKkjW~ z5Eat7jyVTypIj05$b=tJ64IKlfA?O0ML_KMrM^WHy}LjggQ$?sbqsra&7{w|gN#8* zNNc{~R}69;7mipy`QZH_Z49D9I@fXUDYGVvow2PkC<$rJH~a!auA|Q%KdGN|!q_$j zQ6Zh{c;VSA>jw=w&={12wC3wyoA+56V-OY6 zxsJuRzAIhs`F)K+Nl0tH;rAPI9ZP=xYTEO&-P;&Mg>lpdZW3rnMUD|viB_RzRUAYctnBNU3&CAn<3h7*jm#QxOh?0=j zeBCDf^%L<|Zh0GnsF2QeXzl*~iD!*LNl0tH-ZrkoTd<8mR7mGKyq6@BS42rjs}ApD zuETp`8-u8j&UJWiHwGmktvYgKwv@wVZ>0F0< zA7fAw(yGIKm+Np3*Tx_!q;nnaMU6p8NUIL_!LGwSbsK}Ikj{1ZY+wvZLRxkBT;e)> z#%W^^71Fs5pVf>(Nl2>>pA%h&&zx-xqCz^?;j^NbK}krf4v$e>hetAP45C6h*WuBUjao`VT6K7=<^D<|vXzHi)W#qxq;nk}^%;Yb zkX9Wb8q~D>U-920{cR5WEfM)sX%umE6>v#R(p^sbZmBZ-_PEs#{bQLy2^sWuWrpvC zHdKe)T(@rsY1(b-)^wRc2^n6~mQ$HQ9b|{|mUbPKkm0pE<$p7XlD9ef+ancrggpSw zi@iOp?%Q=xLI%g9u!{dC>954tFKWo2O5Q;Fg8oj6&Xv>EE+x#Dex*<#iAfo~T3AhL zzMUDAkRkUW^;cplN<{`yEN!_|?CpNf((w}96@8ZyGCW>s zw3mtuqC5_&&_M|qlDB@QR> z7QXJ(z8{Uet1Vw;chpfxsIRjQ=0%jIcR2IDic(QR#_TWj?bcXGM?tx+1l1KR)KazT zs&7{{L-HylWU$uDI>;bOb$7I*kdVQ8Gadf_CMDWe!|2ri4SiR~ertTRIFk}e$WXM( zin=OvkU^B{YV}>}(7%R~sD}t8RCe$ZExh_GGKiwSGJ_H_RF~>(w}T9#I@?hyyLdOv zLGz`)_EH54^?w6HbE>W@=0%jEtL@P7x9o{0Ualq4@qWTXcUxNfu=bR8%eA-ZxKN4q zZXFkz))5f?Ube#-U5e6i9rAUy{k_bfgbbFpGlM8ERfP^p$mnc2QC_O4Y7^_NTq;V) zU>$a55ap#ZePsqEWOQy1_ZbZ>yL$sme=*z0DPp6g%Q^(5e%B=0#-isp7|e?d_o5X# zv{X_Yleo9@w0YDDhL&BdZ)4EDHaiLiQDYxCd5W}Eg$_!{pnYW>WDuow7)o1aP*P^t zj8jo6GFYQhLY-?X7&|QZ@5WUZKCtfFS1umMC)}y&shZw)o!cAl{_ccjHC-;%`a8ed zxM0^wCULegm{XZS2^l9Z^ipHu&=tDdbxUP?98P|T^b4l?FH{+QGL)(RZr7oI4JDyIWmK1n5;CZ}Tq-h%(%R5}x0i|%GCJ24EmXFa zO!FnXTq;V)P#x8EMFvq?PpZFVM~@vou(g_?bf!0n=+Fqs(t_3~s)9ku^o)>GZb#6e zC@q<4SA8L0=2T`-LWVFko~tMoC8A4XpZ^Ct$k3cbe}xW~iYV4$yB(oUcNV^m^b!HHy>~dY@yh+({|K3Q)ao?wgzSvbeeQ134#QAEP{!G5BKIV|)*41>5 z4Gc=inD+99@#qaM?`mgI$35$86z}=*vE9?_E9+psWL%pJi(lAhhDN&%GKliOS1{6- z)`cCmwEw*`!z5&EwfP3|Jqxd3?6Muqi>T}8tHmGhd2)pgO33*8 z=R@K@yt_pOgAy`WBjr+&K~(3unz-3=@r?JqY!(i=V%7MwX{n|4?=#%@az&{qA!FQ= zYsO3b<1%BHOGO4zmmRfYywxsGR_I_0vZl!{>!5^;&(|9iZ}8SF6*|Zus&lEdp2U`> z_ED)DO~;yEI(faeR{#F?_j0KyA!End*R_GKE@|w}45IGrF-yGjZoMiPl)QV!{PE5o z&+`9JDl*nwe93so3g1?=AnhPZtd3RIK5DhBQZlO(Es^N4bY})7WN3**r?Ja*MFvqU zZJD7h7J55-C37k>C?P{zPui!VUy(r+Yox40M~(DGvrzq(^k1gq_S%(EQ`3GreNSW$ zE$i@njUnTqrafNS)Lmv!LI!nrW)P)5MLb2b-405~=xm32WATNSm(FP7*(`mgq+^-o z+I3L!$~#-sy2alriaC|-poENT_B^?Em#AsiK?YGe^T>Q+B`oWpgbcP*X9iL1F=fV~ z2OT%{Lz(ThyeC}x@9woy_i%>#fXS{Y=LwZ0gLQ z9m4JweHE5dLI&%wtV4QYLt_Q4ceVlBrp%y3dV530hn0jml^K+fA^o@^wEkwKKFD|Cp5YiJap+KD2&tV4WML;S8;sL_$k2$mLqrRfSC z%uC}C@w>*L?y?R_$e`}d45GxlHZ($OuU$&W=xhfiv|Q%ehR%5HIw&DSXHA(Gtrp65 zkU^Bj5i)yLFeuRoL*fQQF{jQt$j}HwVu*_QoOux?RyS4FZn>6KqcW9fi8RL2bY})7 zWN3*r-fGuD22m_+*>dfx+KQT&rZpb@zn6*(Z9R=m|97c~VvTezmBt9#Gp8?MJ0p~x z42__4?6jAPWhY8Uvh@B6JJiGI$kn_&Z78zKrJ{rk9q$@FwU>$vqW*8C(x^f`-t;9b zmx?7JLnA2l$?c^ggD6?OHf3E~VFx8-$Xc{1>)HwiC1hwUr*l?&smLJ8(-k^oXQHWf zp?Q%ZdmK&K{g~RWgAy`i_oFGhAGWViu3hSoy^N;pe%Kxf*<}VLWXQfoQ+7Wp>>z_E z|9d+l`S07k8#CQAyr%nb=M3JevCxk5S$ePY4sEQn^aT}XUXHTeC}&%`U(Xq8Zyzzn z(j_~R4UXQU_T5KsSYDS5h--VCuqt(Qw{{?N-lW8}n}iJ4VeGOFN(SCMu50FVC;UI? zAmfx_lczp#qTQYupFFkSea4`KjEnmp+UPm;eAn^HcLygu zt~s}jK~%X^e_nZTGUC-WGPQ$!bd#T!Z_GCH239JTHj28&ZkUXEav5V#LdGR0ZP}Rk z;Jn6;qQ{@#GWl%1x!V{-(I)wx%x$07zq@f4V{jC`vD>unGp6ok`LeX~J+c?(PKF<_ zWt$yj^jN)jWA*Dd_EKH``##B4pA2hb5Jj7!=;VDiuJ1PI1Y^(}?Emik-S6yujOEMH z%9mTdJFkB7g9o?SLB?rQy1RQ{v#*!x?tAX9e|!4)HU?3&DT=na{Nd(%59e?7={ZG5 zS11)r8%6UhJfQ25U-P&6luXYE>?j(3-NW&du7eCs2NZ3RU*Vg2f4b(May#4`)YPj< z*}Fmuvb0h3&VheU|G3;CW;rEfJT-LJt`ko@!s}|0LpM&po+ED$GKiv0^4;2P`ea9Z zp0_z?GHK^p=@uzY;b%gC6h1<%0JM$yM-4$EG8vX7OD5;8X5q^q{zyDNLC79Kn}yZ^a-oRdKm zZIUl+e0y+q+l{#|p|=$OQ43y;rIp{0+G>1u^WzVg_o0N0KFjT1OCNpB{nd#d?vg$F zMD7#GAc{7rmzrc&Yl{9{d~i+wre2h#6|Z*p(boay?hn@?TEGLRKNnJ?4 zx?tGci88#+Z5H+#ZD^@jTKT2eygl0NAj8|nOXY3e#vqC|MbYZ{7_?IP_^?uW@3T^| zv{B@Jx6KYRydN7|zT+k1Nnd>>$I( zyq9We@g>)1wQDukDoCPDKqiE55j%s80jAIPiRKyI%U`#D#*Or3qm!*v&k4xI@Aj4x6FO|nWZ49DlQxS{W zsAcRdV?tw5%a^4sVz@Rt$nbd1OI6F`#5M*|v?+?_eCg=qq6P0WPc1&9h@C@xt^O*c z^Hr)d%qLP3(#r6h++TUzZk7j>=0y~1L?X*Prf#b%GCaO^9Uiy0F^FQl$+x@yFf_S% z^<^{l)OsUC@2+U6^qz^{UHNF_+C@6I{KkXFCFjigcB+hknx65-*;5*auXnz&qiEb! zha}A<&T3;2<+qbecNA%fq-0hqy(6O~Q5|~sMoXxr3hBI5XZ>_@`uXnr8-tRNR)*gD z(c3(lj-s=ES~Y!V;KVitQ6Zh{xOx9KMGF|)KclqpisMdGe}WdZ<@|6_x3Ob zB_XX0Z72D+TdpP2lBte>(!7WY>0F1lp0uL%T}nb)b?6N=DY5I&){|CjV-OY6xejeT zX+<07l!UbE*lg*E<-VJRz8g@Q7g1V5sco+-ZM`r)D5+woJ{yBtSJviagtVfx4nxn6 zBC#V0c2tcbWt2yh)KwDdijt64hW3(H3rc$kBX5s@Qp<@7>AZH`msp!q64I(ed!^Xr zE$Dr>jX_jM=Q@0R7=x0KRvkK4q_$m$kHIzuQ5*$Pur0L_zi69OCeoim=~oaq_uwh&bIeNZ^1SOQ6Zh{@D|K;)KU`Cs>AP#w>(4P zeF7@Cqx8;8Z>xKIXrBt6I^;DygKvzicI&}YlR;ES=XTJyQxei{hu+_JJ2-y?l$WYN ziEc~hI@~8(T~QL!-X6tkuJSk!D9uaitw4ozuETwzwIC%So!ilR|0S!t+$Xj%q?h28 zSf0*xIHRs@9#AR?>0pQUP)$dXm#U4Sr3$E!&UJ7$pd_SoJ6do4iU`0)R6ymWYN50a z^(9QM!&}f8l!UbE;48uMs0}F1i>QzeI#$)5XgVkfX}6T896(u39CDEBcJh!(Xy-z@CUPOg-u7j~CB_XXkbS4nb?K&8X29)MSl+5#bpStDY zida-F)$%Gs|2J43(s`+L_D2k7sOcG6qEeighB%RV5ye`!IjV_Rv}lhiM&9N+`v)(| zyh2)0q1JN-N3E7h>r3rWs}-rJkj^cqXP_jcm7zUHb>=$geF94JA}XYF9gN{932Dt& zYqr$pMGO~Enio;3TW!pBFovU~ijmvlb!EMsjF47TXxW^>7_O@KDXQEP)$@cHj*^g8 zhPF{?8}rmf3>Q#pAyFZnTkd1fdx? z(#8mEMQM*w8*>K7hej(p3#f(q8Z_JSsmm3`m!ahdfD$r1r*(53j55d|Dx~w;WpAe> zq%~g&AoLAySFVH6Qb1{5M1^#&!{_r%Tac2F)_lX;-dqQxzJSuahzjYTqvaDR32Dt& zBbt^SoCgC+^CBvwa~+%qDG6!S;qQ69J$wwBZ2s2RY!PnoY$56 zk~RiWA)V`>_n{=DVaL>52cwLDf*pqP68c+YdLK$cTJ!Z9>CSb~`vjEgAS$GDJLr8V z32DvOTh?{Z`vjEcMN~)!9k#b*`h;U3O|+`^9@ZG>yI`D zQ6Zh{pueIdr1MhQYQlBUUj>xrCH_~}9EJ+%TnGIXB_XXk!i((O4*IKr(!7WY>7b+K zuP6y=w?kI|ZU_BUK)D?SN_1N~*Fk?pNl2>>sS#a&xDNWOfYQ8(3h7)2{S_r4o!gPW zSkLQ<{wknyJ6b5|G5S@NR=+BuB}zg%*da~ocFiTnGIXB_XZ(hVKOAI_R$gN_7ww(zzYp6U{SF64Gvm?tZlTmF~B< zF+^X13h7)2{S_r4tvaMe%wyzs&|d|V=0#LU=Q`-GC<*D@4%_{3JGMId%=FLAJnCC! z`3Lm`$viS&_iLXDUlWj90EhoO-Qa>e>Z@X?4zkO88I**yGQt-G+AR+#{el2dA)S8- zftFJe(wc90-Jk1lziXa4pfoR{LORz$PfbZk!w!#Ryj13?0}6H+%60o!3h1dR32D{g zHPV&aK~Eh}s)MMI&h4P5rX-{_UvG2QK~Eh}nio+a9dxujH6Of-ay#g$14{EE zDx`BA^wgAuwB{SW?vU%Crw%C1i>Q#!b?6w^`qC(zl91MX!`D4>9rV-zrFjt*(zy<2 zSWl!Rq+y3gGG3}ShU+s_Nas4}sVNC*)!{Yb5g9#oKxtk?g>G1h%5+$3(~Ki)3&9 zBDVp13{L(wZui>OA1q+r@}t*wuT9!1PnYkoTyx%B*?C{SUZ4BU{?%l#o%r!}9nIuctTeH+RxCq|6}d z{-@@xo&MZ7FV!y56X^jfEtu>#dT>Gs8N4$SML)cIQ~Ji1OC_fbC^LwF#NdPyGRn7J7WjPc^rWFHB%eNdHQ76G2pFQdfxo2 zBtvc(oDjvEHD$)sYrbku*>3gZ%>@T1l#o%r^^*0Ny}9(ygRE3!5G8-_Zk6iT_s_2F zKYWd3-dhJJMDb=#nep+%H^v)XHz>JwUMp3R7a8SSFC(W8s6W$t)#Nj&E9OO%)OvTT zJsJ;=sb4#O#pLOKSgDFzLA+U0W*of#S@l`I?w9N}r?p3s7a8SSFLT|0MSaPidM67E zDl>?Z{?=&q#HYH_`lUxMnjCh7^{YZc25;F!QRB^*>py%oPjdYlWd>0)ZW^sIxWP^z z)JKn*Jy~Y9!3j~k8&hT+vhxhdi5vY`-&ITijo(WPS(2fs`|ZBDoV)U zotY@A&Awdn&Q2%S|NLZ`LDaZwj&IC#`DC9z9zA&Fq|ZW|*Y})xa6$wAeWA%m#JemD{H$DuM}4}Rpu`28t^6H3U~bgfexUp%u}pL{kLH+E36_{FEh z>PsjgLvJUob?SP3^bV8U-pLuw=@~?MX+2tc>EnT-W7bp|M7fSG&9}_(x=K-3mKPab zZ^ka#Bh~g`UPO7z)^f|e%~Q0wNyzZ_ujQ6|ze;r;WL`vh-*p|{cT@CTlaS&4*mZ1_ zkB?Nx2lFDzN1E%0Amp4-p6%h;!D2&YM$(d zmM>{zxW{lE>aQ+4a?uR_${0ks7j+#&m%XKa#KB8uZ~U$BK9-kzI7^oq?sqfzUCWCM z_rYGOyT!L(H-5!TeLM3a%4Z2L)z*hES-)+Wfmzp?gA<~B{;+(@44Z1R&8|h($c{K>a6**mC|+8W89tw9n9oD03Wm?^UMi0n zGL0FS7g17&8p(L6ZoK{I^qpUq&o14+h)YaDhO|xb>LQ9{9!zB(%zPd!@*>LPF4y7l zRfhP=BxHExX9TegwUoZ9B2`(02+o126TzPgZ~I>`G~9sSA}M0p=; z zUoEMYIM>0QqJYx8hzjXkhu=2LbccnKkk)+VL|Jb%x{m2@6{~j5izqo!Hp_Dzyj5I< zQXORm_m(ILX=TVsbd+g%Ub}un$o7`VAWC(sjkylLg=CB>RH&;KgS%18E2Nd7 zX#IC?Id`K1O0^Re(s`+-zbUJ%=^1LZmN?fj{Y}}xAWD0s)=I8}H)X3(ns1rGlLksc zS{XWST9*45w3CK_Qtd>AbY3bS=fOmijmvF9eOfCI#{kXku&IbrCs%AmbIz=RFo@DIsFvqCd<@*Pza1#HDm8p9@6sGv{Xa;KGrz@ z)pIPZ{aJf|-X1M2R=b6S4CxCRy;d+NA){-(cN&`w8SxtoqO_;0*Jv*lC1ea<@Z%1( zO9oNe9_sztbx<-rqq+sj&~!ja&FUJbLWlPslSnCwwh?qu>#f$%Uc$VnL&rvST~R^? zdu3S%8AM6`9on1{GRk|eEiIE0GKligRZ&-3D)m6xQp#43r)g!#SgByBwQml2&{3_| zt9@TNqH)_UFIF%p(VA8dq&ld(Wrel}8ASPLuFydV8J+Fm=oAlE^b(Hda;YdGL&s*Q zx6TZrZe8{2#+x_ZU10|$Wavl>?Nru522pIMGJ}%o8S3k+M{Q_xWd{^nv#dkwL;92D zB@B&H zb4tk2o?cy7WDv#vR@TAtYF#N(tyTM~Jsc%uh>xjBEKy-OC1j`#)uWaSqQvvnI(pGU zLWcI^;8Dw#GcTgFy~AiOGbov!5ypIHhOz@nyi%>BhbtsxXuDL`74srW`@;8Y-dfQf zl#rqMhxRYqK?YI!cP(Z6_@IOgt%2WW5XGKfE>*aHrP{-NFHQeA@mt-a_Wkx2XHr55 z8GT>*zVXo0o5=5<>Dr+6pU$-{2^qZU*23qrbBjULuH(LHG#>j`SGx{M$Z&mrGqa^- zQbGn%j2T;aEtTHojG_~kRqay$Mg4^Pm+hsZgbYnr`zz{jw%zL^yId+t$nYDR6)i{x zQRVw^EiIE0){plXYlF^pMF|;x|E{71$snq8T~R_txU1UU9%K;3c52zJZ7ypydvmOL ziPtV7R!vK86{D6CGQ?|lh~dZ}iYtq9sW{^ZyO?D(-LX`KgbZJQR@+f9i1O8I1%nd3 zxvnphyxxkO%6724WXSH2{jP0$3z9*U{Jqi9a!6YFiave+QDF!3B8q*XYzHO&h9X#A z^q4Y3b%fY}49!ViT68E?U=WpkxlfI#-E>)qODD4ZOM%rq(kdPs@pf4>dbTBWX*z?Oe#9tLLr|f0a!XAmv z+SR_D5;A1Br51K{$~wp(ijhG(Ba8zwWM$c53^FgG^zYTNkG7JwySB5|ruHpOOJq=- z_P3WRL=)nv?H6yA5#AMQy3C*s=39Pu*Wye{C?P|l54q1UN&Lz5I>;c(byvg;l#n5@ zM6Eh5A%iHdw~Bd?5;EA|T6XIkMFvq`(-k@>A%p#`tb+`qyag+Cux-`Ph90Br&=<-& zC?P{%(TbgZho!~IS9c*VqFBNfUh9eyGF)Fpo0CCQXUjPz*xT7F%cY`(4Aw|z22tK) zY&@13l#t=}HQL9=^bGN8hVmX$!Jvfsy0@!fC`$g%B$L0trAWIcs$lq<(0 zLr!JO6%{08_^Pi$2N^`Mv}GNXOwSN6TA_msO$QWfp{&E_D9g)N_mzhccrEKww6%0z$ z4)LUh`oEQm42d%BH`d$zRXMK~O8)+T7$3}6^y%uQ!Vcy|l-O6C>6L3&d`VHenhyS| zT-p{#&x%?tMTU%8J^!dKRiT3@8S};2WJ`n2gPO1G5LsU0aSAp|+s+7WPKJ0pJ!z;Y z74ssBHnr;rrIKAVJ&$NBVVS{_kfBWdcY7}(gD5|HsbEk-hL%)qY1cspQGTvk!Jvc; z*}2mb#ou5M<>#su3`)pQn`FQDHyA|8Jg@s#6%0zq(6-RMjrO`CgD9=pY8^ad;caYT zbXa*&LI!V5m-`hNMCso{#93zWrG<`QMXI%$?s&#hNJ@FAghi=B3Cnh{BxLY)#Q$UzFE}Kp4r@+Im~Z)|MN5nM#3C=EG^gs?73+!}TD}s~ z_h0fm6BX-0GKkW@SFh+PAwznMzKN??6_G&{@13;lR!{9Hi|CzgqsSSSE;A@0!%z4t z7(4}#wMbEKd|zGGK?xbMX3!n_iuDH>M9F%`zBAF@cPSx*9-~|;GKlKDvrP#Zthcfb zGKkW2wP&D&47O}p2N^`MAD0=^drsXu)*7Y0GJ_IL2Zqiz>RZ~|gAAfN_bW=s(AlPX zHXws2ziU!aDoV(3pZFULqSW)X-XgbZE04&6q{PTQb%hS*<(}G5`gg6z_S$t%W)k;s zfuWwS10zVtaF6;M45I#LsfzNFA!(gUs&$Z2prnMwoAFlNs)v&r)iYDe%TG2etu+$t zD>Eo5G4k69)uk%(^1B9wj?l90I)a1@Ev@#m|J{N_`R$7e1|?+3D9}izfa}&P(5{0FqV(@!4Og~9@~J6O^O8~&<56trFrp|SL(|pcV|qqFNiBC6AKVL* zve!cWsE-NhvK^F^8NA=#;^fh5$VtJtC-ySSye=9R6nVum!E82q$O$U^uJ9q|4re_3pTd9h?lpRp?d}RhD zWH53nGqerVVjTyPzxG#4dk?jAnL!B|ny#L4re_3{{yn7Ibp#3Xb$u1>!Muoa-5nTV zM3JHC>baJA5#@F0I*#qTM)u8`!{fIO8JzrMkDnUPPM&689g$yQYtH!9s&k25F>i83 zQJ=~4CAEcLsE?Iz*0?vYdiQZ|>38pcsN|_yUf$8C*Q33sOgY=?0B>ZJM0ZOSCF(Riq?B%P&WUrXEpo( zUccPZvX%_4aii$em*tlom%6#J;$me6QRTWitM{VWn|o!cmWt)29le?#Ha7n6NVlW^ zK}%<{0jn=a8Kdtk0IgDCDmN70Q#PEIe_Z@Em{>Ys-r} z=K2+%w~u(kb!@!-CFzHo^f3k{WN`02il%<}XgcxE1=|=zv4l}{=10@goYe;yyS@)eA74ssB z?JvI?y5TqV+pg}B4WE6mMN8pSSK2`DBwPJR%hpgeqSgD9zyqW9Q{s$)bI z5;CN&^nSbdl53Og>jy~fewx>A!61r#EQ(e>WVU3|w*O7f-^;wH&MY=M8H<){_oBmQ zO1|p#U3%*#Ha?2FB13#k5no5qD&u~vzq0m>SzW$!$GnKr88x(Q6p0s2;6-&NGcPJW zv52F^gV$QV{kBh+OMV%DQhHDS!3iZ~lp|!B4HC=-MP5XSe=KT5?nd@rG{KBhNXYP+ z+S|kDbDL|K7g4OYC_1+98Zw{fF@t#hV&2xfQI8M*hkbpG^SsTR31-eB0w6f8$rpHROwOl#t=2bsaLRC79KU79@&oQ`BzV=X0%H zEwjGPEbj7o%i7;%9?VI4x}MsbiKZ9NL!1f`UOPM+Udv4{o`(>qg(ItJ{TqjgKU!Wk zr+?^Yecp_bt@YN2XJh-}L}FaBC+1Rm(-cY&;jJ{UuRJd*z>CVVP|Nd=o(+oU?0tk6 z&)JvAvOHfRwLG8b*`RpN9!?@qf(Xxdc{V7Xn-tIEAy5lz81mG@i|6cpq;*7iKG?HC z@tmW9@Zxz0fm;5Sdr?hz@jR$n?!_ost`}?RE!WJDDV|#t&xIGyIdVz~BD|RB)yj*` zvgKG7YI$+qv*9rSg@{x(5J7q744w^&=LW^|cOgPrUc~W6&|@;H<)Jaha=rNB*`RoC zQal%4JP#pI3&%gi$kYf1)dE zs}KUUJoe$)@Yt(Fpac=r4nF(gwVYzDO|e#Zu{JbIPz%Rj##)DBt?9+upz?4O0hq(f za%r}QdW615|5$S#rhRFiZ5iUCvc8C*xyz?Tyjl_WVfHFK?h`5twXokpyF0mq#2ps- zDE{3sl0B!lFY$b$w_{NrE(rU~5Q4m2P(4AA@tk)>%8P~&s6`%}_iEmFP&{`io||4g z4@nR~J{a!Nd%HX3+d~M{BL5ibbs2GZ2dN@XNP-B8C82i%$o)C*o#p-<%R((28`=qf z7A-3M&ocY=t!OuCQQFA6e@BL?A+Z&1SjmWPvy_35CMg#m~B&_=Ia}( zR)J62UMIw$w%tY4^y$GG71zmjjN18ZZt3L9q}KHrEhCovZpnPpJb!LJzQ7^Gwhqyv zz~okTy02GDM6<2K0%M&`vR2;*D+Gr8w(2d!k-X93`K3JeiB7-U+$X9mZj(ZA{>rZ> zHn;Ayl5EueK3Z(nS6HtT?Td#{T8vP&rCO!yDo*VhY=1lSCm+J=pTN|i?%1f>YFhI# z9Yy{3m)U6+O!2kjZA6iN^8)LeZ=+f@{G**1yJwT#PMhjOa7~mJ=V>kkcrIvK=Hu-| zx3SagIx!nemZWYoGO+Vs&ES0Q6ypNd%ewZ)RkVY0`$0yp2#RSknsaY$tyCd5Kx>vjsi`m#efmPqQbIXOE_Z(;BQ@V~IIB zQ-7N!%KLCTl*i$}hwm62*`#`a`f6^1j-t@$9%l5aZ4xoFeAUQIVQZxSpt%%z`+7jF z;7DG3z_1s_`iDvVyTb z&(w$qR}WIl>pvYJvd%82-%8!hhd?d1p?syLO>90`R4x0F)j6Vo&%+^t^Z6F7*?i#4 zUu0v%w!UJ)+Di7Xbz8(kC@pVRO8=;7x%c%Ie_!rvpKOv|wwxl1lwi4BD~eHpBYTdJ zjk^b9M5B63?dKzE`w*zbJ+1tsrrjPHEov3oW#`fp%MnzPw-FQ{0~{Y|1Zzc$n=SU5 zMSGvIxGWW4Ij^E9qg799TK8_<#qnZmO|4%x3ngzO-o)Ao$zw&|!JW(^<=grYUae$A z#-7%+oNWe+?%Ru+7mZ0eO5R3LPe*hbcA46-a>Fojz1Tzj_LBE4M0mX`wYW=BWPZ2{;2O&vXP5w)opuGn`#w&8=wcMtb8z^BkBB*yg&X8tCcd@+A zTD#-TJ)020d8Os`v^RpAjzx=udG^`Oe*a#^J~g&)BNRuWZz4qyXGpZqJXUhIL@0*D zWqec~aM79-Tyggl&09!|Dg zNw8dQ(;JrYx=dH`EZZWx;O7l|2-Na=S~5<0=UI_XB4W%+dugX{O_aQiP&`P}zFZ{4 z(TVSg-iLOY6DB7z?hd`J7oD8MSlBqR;XJ;nJBJb*gPSHY(iV88XS@7@W_!uqX~nwY zmBoMqd+Z5w9_vFBzSi%yU#2&xdP|QAPi&O?VwKL?jLI>6C&`S-fwg+_Z_n!^Ql>Bxd~fO38{E<-efXYHYr!5ubpCUx`TIZJ#K@hA>~&$M z^kRReG{!dBsprUgLhrvLmC?|LP5vKGlC4$dNO;YGtu-dJ6F<*Gb#@ zJE8I2!#n!MXDjrldIDqW@h5tvVQX~NhvzCYr+%KLipW+tmDs&tvyBo&{JJoy@#i=9 z^*Kd-vWU|I+V#k-{jk|D2xr$Dr;pQ9p>*c~~ADFOwRjUO&}O&i_}>w>zn^W6fPX-++Wh&Q8pb!^*xd4t^Uhl59C+q685&`oto{N)+A9@OL`O!fi0=3jiYj7|jA(od(Cd_u##nfG^Oq3vkXCcp^sb!x~I|fXh zW7fXVOKj~nB8V&JlTyd@wwqHM?a!WmYYlcEzS!K*zNdI~_fy&bYIP!F#Ilq6ju$D7 zFD~698#7~fn*U25Bij7Bz=uFBUI9G1k1Adv#80`lm4xG_Bu+LL$0jLGgKDhm8_Mpzoqz6piwt z#gBQ!<5F{d2-HH4LHpX%6@*@^h`2QD3!i5|M4((kqtR5&sJLrC_3rD+^~Clw=|tAL z1$_wA!nLVs&tBCP$1Y?Nr@KwIP=bgqLy{Vw{`gdni#|&>j`nIJzO4Aze0=dz01>E# zD_GNVylyEj=`Tz(-3kLGh~Q|$QRl|SJ7gp7XtWs6V3*k-#RDG#wQ$XATH<;g#b>8> zn=Sh_Fj0aC<*#z>dPz3UX^BOq8`Z==Su7i)rJ5NW6S1f1tU>X_;%c{gV$YH(HcAlT zkDNzG=MWbcR~5-mf96A=7WTBJB}|_~Ec^Qt(d60{3nhr)vEaVz^za0=Ln~52%pO=) z6nkR$5U7Pct!Z;e`*q<8j4)7w2%b}H|JAe`WMe7Sh-=pP+7%xHwXml(ja$vFrl+_M{s&gEX2Sq_i(AyCUdf+hCV7J&mV&ARJXnJ7U7GAB)IpDE7VQmdVqS*eGO zd`I~bW;NK;nznArUNh_J&Z5ewY&J>|feeRQPBT3x&3Gf-3JVdag*{EIk5&_}Dq2yI zC_w~zSK?Q+VtM7B>NZ)fOf?%&3wv7Ac92(K??9fxLJx zud}~h*i8(5G@ZFskQoKD36+oNa9I!6uLW<_2{UFbW}kTMQ8Q;~<#T4(?kP6$X^TAq z`;WYp!mOQT&+0SlZq=!Li|pu|SM4Iizu$Cq%1jEFt1Fzhh)-KQpLq6lOO)Cw^~-U+ zZSBK4m2Z(9{l|5@&d1j5;gst4o7v&jPJ?)}#Vmli^U>+4tX4fv=wI)@t}kky(kege zyk7gzEkewB_^C7g#RGFtfn~m0VNGh5Pht(Id_&JNay21_cPQt4dmxRtbN#fvreXqX zLAeL|hY>6E+eZ^wix%A1Cw;w+cNjrtQoPI1w8pQ(onNZu5N*%yuu*~t`|!))0xf~j zxPV27WLH0M?&K*VuI4@DL!j0)=Rq*yzGggcu!0c#DrazNeOp27`*fd;5=78WDabR$ zW%|>yq;qC;`cRy%zSu?yB2GNJ8_d!znUVkIcCzu&#h3QZ;EPm*VMcVi9fU}B?Qi?rb8SWD$Bldl)WRBSTCvGT?Ix>QiAKf0 zwo!rzwF-FmLSI;|c*TBbG!~QE&hjBp%ir>4c@jB?HX7nwsN(3o&@8lQ4(MkqF$0)ymvVmlHLExidB}%At+j-h zH}`=aTZ(P8>TNhB$7d8(7A!GQf(V*Z7WKTIzSkqN(f5xU&fJ3u#fTvreF)T29>d)m zl&;#`$vy9iS@g!&CQ17qQ9|EaLvW@Cl)MYUF_D=5)^^UpQ~S(yJ-)Ot_Nke{5e|D= z(~OVWJDs3nhr4 zv9PG`^u!A;P&>YPT+zw0ytHU+mGL7$3wv7ANZTP4BMg*axiqJOWZy_*@$b%5BZq3n zwelfQ3wxUO26a<9)Ov2Yff7Xcnaq#3kJ}4(b`&p~-0&e#OO34iykvOPZu{WHj^gOc znkGsRfy{}X6gBJaoL{=ue0Dgah3o}63idR4(FI+doR_zn#YBXG5=5XU(lnasPVKbM z%z>>(_zF=Rwwq^4*3y`r5#8*|&2TWsSe+g7#KtpgmrIKO1<{LN#FB;{XH ztde~eY@W7|pHnaRE!z2Yz(+=sEpZYtaGJ51<2ECnJ((X7r-cv^F5-t|(N5ap&y6p} z%HLA0)!oA)ncXSGk5Mc5lm**}_;mw6*)IN~i<2aFg|&K79RIFnu?=Ras#f{KLWs>S zV#cS@&h(ZC?62<*vRJFeut1>my}u-4;mqv;=GScF=AAx)ymj~&#e+?|JBb&rlix8x z38UXeWJu4?$SURQ=xlrTy}f+GN?9xJE8ZJ0qV)Vefy03f{2R2i(e)aiFL^w>qqG0W zJo|8=pZOQXkOUE&|Gm|WK+auT2$3sMSLc*5-`>`;RXl{!!rIb4s%o?|vGXRoNJLE= zC0H)!`(;`YV6RQ=mHKK>?p=1?=kLWsC@n^)KGd|SBch!#WvZCTCU2H4S0l*w)Tl8c zLBl?g^Q-fF`?i13$$6c4tNF!{4iYi@#mvYb_H0r86UqIo9`ntTwP#9%k{|-xr)dT5baZ-@A7OU- zRG!6=vw_P(Ek^U~ai0PFP$}A3H?W=kS!sDrCggp%7nH|g1h1~rpK+~TM|X5SKEKgk zk!F;v6|adbKR#3QDxi9r=dsIPV~HWp2wP?sTU1*jl*Fr*M0mX(aK{|hhYx{TTq|B5 z`@8a(gZGhsP)XiKD8J(K48C??Yq5r!mhyRwQ@2%&-S_0LYF>p}tNI7~P5v_KjJzCU ze-qo$hd?c?p*;KHyv$m}K6L{tC5JU%7slehrs4uKeA}=S2~r+T_NM zp&MhIGd0`UQ>M)KAyA9QM)`bS%)hvY#`YbE z2p2&oIT&G;Ta}DYa)c0GUTUeoyCdi!3_|c}5s6^QI}i~rf@{U?pjz4QLa>(VD|ZCF zmK)S^IZL>&SfXqI!ebfSyT#q!^&wQt8Lh^~eMSb{M~=DTC2u2`2QjPBG~hmR%oRi8 za+M!cXm`v@J&AGtOkBlmxo^1|K{;xOK#wXwknsZWgOCrnj3MLg9F=hS<9;lSuViw--t1H1|UEZ_YF)#ej0sDIGD2G`%N)VCso3p`$slzOn zh5tJDxE=AZjq^LPa73UM)|Q^V{;|`3Hl&loEF2|>pkD@p{4~U6;S~y6cEvU^4zqAX zpceKaongsT!>N`pk;5z;M-WG?a{1)ePnG`(x-5LllTOa#$3Z)WSorWVVO9!pHpncT z`-a=a{X@TrSp0mzW#PLTb#n6LkF%MDqXZE=dR$|71dsgwr8D;Odiw&ga73V%`n$`* z|97K{v+3$z_I6_7C_#kEyJH@Au$xnVXW0Dqs8v9gT%t=*DH&6@65u{ zh8jVag%27V<*fSpfXyr%C5XWG5zDAn-`Np&&F)Mr91*CcW{=Cl`)+w=@4H{esZT6i zttj?BYHhRsP;13y;WyT8wfFzf-eDH5W;nBOwN|*N)jW1t`1$#N+0SCzJIumSf(W$= z+%bps;X|O7S|2V82k&E`1QF<0G>tvOHP&SYJeO;k=PyeTq4I7#pO+!Ab9G=7hd6`JU!j(2pX+yXT~Fim zTvOY*N-P{Dh)`{EN%5%g(CvB)C^^xPfrcrL{48cKm^7sdW!QVs+mf{ z@l{1Qj-m?fM$Q743OLVq7k7Rl7LF1`C?D)1vZgEQ%+6K8$xSRA5vZkl!5zUFgDN>0 zx)pa45(`HOB6z%6<|0zfvkp}*1q9Brjjs2 zLO-a`?g(c8^Al&{)x=H|v2c_i0zE379i*9_lV&`#a73V%>IHWMc{TB>Vit}PL||Oe zG+wd1a$67!M+9oAzq=#IUV*&>vv8CkLgii0z@CRa5VP=iAy`Yb&mBSbZtUg85DP~M zmaE$2dWKow*LSKddu}reM+9oA*yS=Ah=Vpt5TRlsGaS0}^Cs5%5U8bMu*<@UfeZF0 z%)*I*8|-N~4iW>GOq{(0)mC~3ca{(X7mH~&G7BdLuJb%)|3M5~@@k%Avw5 zf@dSMaAM$muGwN1t`N+^6~gUZV&H;(7PD|=gV%wo6|-uNDc#cxvNG8txLkwIp zSeJzp12>t8GYdxvA}F3q2J4O>F>sUlD6?=xpqBc(%fg9)o6N+Sg`)%!D({XtF>sTa zIJ59~Ay`ZO-Q~N)z)fc2%)(XOnH#EJU>5GTK@8kvCeADzC5TWqTow*3=NT>g1Z%=t z3gOm@7`Vyafmt{)aJ~azF$+fw z7ETOYFcW7Mu2vL#AGNmGf2g(MvT$PHf|)q8a5cl3g{!r~J+0=k%fg9)3ufZX!cl?< zwF=xZhxOq@pq5%6E(-_mW1s{P=vOq27`XBbzII@1v4(``Utcg2XBLhUL}0(s?d4pJ z1ji_5;fO#jtRel*`LwR^;vnw_rMKihK?KD|$-UfoPO(;av6lCPAp~lvzq_lJ; z&MX`yh){Vqo)c#f9%u0RE7Vf$bNw#y62VNISvX1%q1xoe4`SegnK-j>M4*V6Mn493_ZQKG;PN7Zn~C^&wD8^@2Ns z#CL_qcbSoe#ugF8gC%2j5yYv5$Elf-g%GHv{_c(-X$z0HGb57-mLNjqT?ExgczXk8 zWbqKJrFz62L29+|_8-izBx7L-maE$2BA|DD2-H$N?Xqy@KFq|Kg`)%!$ZF`f?Kj-V zR1#)L=m!YXBLhK)KY(UN07XN@b>2xN)Vy)u4f?6BfMt-yz`Q^;<8Xnwa*UkrW<$s?A8R5OHCCKkT zYMuQ_@X*Tl<=^SdL|7l^^Z7F*0wst*dvwq1?*UGSUOnO=P-~m>BKS$-qq4Si9xir} zvud4?2$UcK+ehzCC>8Bosr6U9b`)QDE!aOzi+F9)vrIXXD=<5OO(3Z6*o+|JN2 z9s;$z_eOcWo3Yh0`xq}b(Jd|a5?{|_~FOJm=HX3@%vyph}KD$`oFC+pb zi16EJcJP+nWL>*>2-IqSe0cCk-m{(!ZC?VX#G)vPKnWtSO`4W;^;Em@lRojhiN=W{Gp1;~`LsW@YG2rSzu4jQK^O;U7yx zz2?jGUhPBvir=dzdv|+*X?o!^2R$3@o@5lk*iR(_CA8*42)~Wlxs!=P-J8Wjpw_o* zhwCLDp7Cr9*!I-CzNNK9pac=vCc5L^yM!q4i5{;VcD6No@*SIGxmZI@tJ|%TI5@7f zM4$u_gUvtn`s;u3YSnk-N1|tsg7FZjMIM#kbLsi3#B=J3upwC_0wstz-tmB*qPz0c zr`~TSM*J^XJOpY{BnrLTlukNTY9-E>eWjvWNP>u?$0}%Pjnew%-jFOUf6L2$Ucq z*$TP=`oBzGtuCG(N_SYcNPdL~)Z(|dwrDUhulwdm&xXmX)+;yCV`QN>hk9uFce-ie z+901zH=kVV@eqC+Q*I6uYkKm1IzIxnIRDL{M)}-m;30yHKnWtSO`+b6*AB0z9c%C6% zo9LI(wjYa~mGesk)*TU^@A7I@uRw%oY?q3MKrPSndA;j-QHekaBD^T!*(fwGr-)rw zGadr9Jg@E9So1Wa*gfD=i9iV=ytv}o@Zv{21ZsIv!b5oRLn2V(#SE#1w&}f`l~0A zf(UFAIa_y+6R#cKz9wFq=(_;fQ#;M>d@d1KcSLx5L$6lHUuJXGJGJ8>P>Z}$=nc4` zU8+Q&1QFgY+_TaCgG$b?CrigepcZ-8(3@lF{zqHWnNgsaM4$u_-oD+l;qA}kAyCWP zg?oq%?*3dNP~z>$r54)Ow6x*PovK%o#Iu12@41F&owl)R0gcMVK%xsQjC%n}it zS6cojUd(yif5S!Y!xgRJ_eRk>qBrWF#O1XzmH$rWdpE8e$}4UD|8Rj4M9lmwzqNG0 zOo{$)1Zt)4S=gGsVct6sC^?c27i;& z`EHUf8f=^XgU!|Q(-ywWsFW2L=*3iEW=&S0?rCmq)JRjRV8w?a9zguo# zS!iQO)%0K^VroUp7%)JLi|A#d1QEq%r?;Zx;-qbQ??-~H=94M|#m8B*_zijQp0a3qEYJn0&)To}$+TZ)2 zemun-YWaY=E9@P6ii=ZI3;7VJwWw%%tLNqe`p?^E6QWo_P28Vkihb2Cm{|AmqcVhQ zHDhW9OZ)SHUa1fFZsn#wnCa*(f?uD^Y+?%$T_|$~81sbsIrHy2EyV6$zBN&T2)~W} zzvmEH(tIK&U43XE0<|ix&k&k#^eb|)s^;+MGv>{xw&L!V^j4$ZhxBndXX_{aO>d2O zaZtZsYqsuh`TBCL3j&(!ttlKI_}O8Z2PK$+2qV1!RsTk+g}tRf7P+4(`}?x+vJd*r!dc} zvt17bKXVS5uPQ_flpq3YsA=}K82fC|^QKKZVnm?U2jkL(Mw8yM88OQqdNHv`o}i9E z2_kUj(;N6F=??i5=}X901!)uw_E+Rnf;1)u`xWvdL0X@N>q}_GI<#`-sznJRX!QnZ zO&Yv{sU5{zIph~j_KD;JgEWc;`$4ov{xC@1PukWrTH_9_b$6XZS!jdSc#zs+xa*wO zxI=5*-!QcoD}I;VbeN<_>uxvvm`TC`4r)Q<+Q6-^^A?U1)N*;8YE$ukGZ ztIE1#`{>kUgMkkDUX%SUN)W+$nn7O6$>%!cdkyxxZzGfz`P?AQYdJQ=6r#`AwAO82 z=Wo}YR<5i&t^FX)GlSPZ&BUVTZJJwhUSSInP4hNLbIx$*ZhhyFeX;8y{WZ;9lpw-y zgVu&kYeeVufe6&1H6vTj>qgVa=Q`wj9rnBATZ81;4EC=)muT(Dx#Vv-tyqUvuFb0! zC5YgWrB&?B67p3J`7G(LaQ0zO7 zXB_l2&uNM+-b|$UhnY z-bSdI?`LGhX@kTS4d&FuB!k5KWS+QnkQkcG`w^@~d`(IiO`J~ViT4JH5xxUKTrgyV zxMxUb`#>EF>;C_x0a z$zLl(pcePxyW7G07}bkZLtSZ6N&35M#R%0}-ruNkX0)0y{#u~~5or6r5vawrdiPA^ zJ&me6wLH`&-ruMi`fa>ju4?Un+dv8S58C$IKm=-W{@s0r5=8uWI}m|d+zV=)=)G!} zs*3~XvWdR2WlZu{ytk1)gZBlBS&)z6y_Dxms*9##^#6{TOYBALeL@mMkYCaFUv^oI zrhO98*zC0`i&3`FK*9Wty$r`9X38pBGE;uT0Md-QV9sf?RFC<(qd*BF$RFzsq7=(8 z24oQH7cMkcJrF(wYGDoOWDV`Qc=zQo06p=g^pY)+f0Q+3cIIyf@49&R#a8A^2kX(eKkNzgs@~(?_Umhb1Nf3d( zplQrpiILeJBMTu=i+lY|RQvkoDf9PC?d=OETFc&55=7wGNG>XPkIr0_=aq_s+*%d; zD7J@sU9vvGdvs=fC_x1G?whE_J8j-^d#o>17HZ+x(5-}RABmcYN1Kb1XAw9XupKx~ zl4S^D85Xk)lpq3oS~3~YB2`VhB{3O9pcb}|-kC`|JKo{(?hYl0z&_NpKMt3sH@#(W zRvkNKay!&4;k~lrbBLys%asftf0N6a!sqWn(oQITTR))+HQ!wg2#vIq1rgXYSySBSko zXE1&Z9MDI9$vgTwuMgNaaz~3D;a~Y|V7VWp%wWVWP|sw<-XHCTaot6SUZ#l>MEu-| zR`Sd^y?zI_ktszkdvfAIqVA}t1|m?4J<_5^%EqmzImV>8K4M{s@AwHzNP-A!aXLdJ zIH3P_pLbr1Q}#6f*P*W%P%Xa?fm$a9rh|5zdG46e^bL^vm-Cn?L4@`Nc~Gy{>D{>P zZ<-0KG!P&CxYR@mBG_Z|d~o-JpTEu~PXAe5RP0^Ghd?d%_iAi3tz*hG&gIshiahtq zn>fxmn%L8twkjsh&i=ZgSl()8 zSq38N{hr>K-tCayCMmaLbmcFMM(vN7*Uc^hC5XTpYTCCEdF)kLemAGk*J2QXT2Tkn z8$%i#(mzSfHhwHyz@BqBjreNarvfF2z@FB${XN#&V`Gxi`**AR5U4e`W(MP4+k^VF zdu-#%!83M&TxG?s>-ffsXy>o9_5%E0gsfh^GdObaZQE}@5eS0-t=QS$k zbZT`eCuUw*XQBiVe(&>!lMNTlx|lKX9)}qpGc@lvgi!vCKL2jOd{b#5g4rfBTSosk z0=1ZDGwY0xKnb%|X378WwL%0lzIWTecAysb$h+IYwPF^@HQ{!seq(#gG~>4eC5XU& z^Y;}ZP>XA*Z2J)?K?II0eedpG0+BLvlykgO7o&TV(niuu4d_i`kjax&)ji)tl zN$ZIABMwcE6&r^R2;P3#&K&Ylxbab&eSc%5%Qc*J;A{HQfNe2C~c z(bf9l<*$0`5@jTUSwH9JwZ0zt!xMfQ)ibQ0p6GE;=RnvZlO>-y4oR$xYNQ9CgVq3e?MvJIBk-IduG3&de=IV@joekBi`VgqaHXfzE z9r@cp9&_vLB{Sk!eyhax4gzOJOb2)TIm-BFN%^ipbL9B^)?aa73X~uMXAkWSx=uDn z?yYQZJJZ95K&_OwOB)Sx-}Gi;RCq@7LH$8?;^ut?N)W;Acrz2XjmvLLGS}PX5_R_> zP>b`=!)`=Yf6a5ZdpceGSf;u?u75%C?X7TQ;p!W*7w>)*ZtUxLRgPNsCGNT@CdWMa z+-T8n;4CZesC_1`J6w;5*0l8LI*Yh3hgu@b2@@rVSpJD?!;OPKb#E*RR2gOsy^%s7 z0=4|L3dCCath_0nflpq5Aqo#dTzP0)F!!Ay<>1%xm)Iz^Pzmk0)FrOWXa-L3JZK4Db z7!x%uX5vP3)xeLP$aTpCB2Wu^TGJNYd1YD!Bc0gew@s8F0;4Exv(tx(LMt;mr}S(B z5vYYdP3L{m77|}f%;2;+_`*a9A~5c1TCE!qqVn>+cJfN8eVzfeaBb4BGMnm%D!WhG zIj$Y`t#d@+x}jf}8n+W4EQ_^krv1~0KrQq!w3~R{MPxST*(rLA@p&Ia_}Absd1A%W z#<}cUu_b*7)bewN^OyRG@Je6VDSjMfpacYCo10xOl&$^|9MVn<8a_wU_cnhsHlH77~^`` zW~EVG1xk3fD+K4s#{^v8UcJ;NV`auh=A{O)@eoRj5yXiC?(b@1*JyL%XV=WHRy6Y= z3KlMHj2Lq(koC4(LseVyS7~~feM;vPTkllywF41P_m(!+wz(H5T$rQtgb#-qBXSoP zZT`}I2-Mn8jJC~8=yZtcm+j2KgOfA4njd;m}!Q$DN`^KUgyA5xo0z6W6J`Ok1Cc7c? zEloLsfx(2P?=;NqB_<5$YJOd;t%(vuq-z&$blY-W+NNh@eY=SV$u1fxx~%dcP|J&O z0XGgVtKLZ5Dn8s;u`;F5mWLZpx?GjLcx}8}lQGmKd!`NKfT+X&jRcN$3F9M@y8}g5P^M2zkjqVC~76UY5uf4n{Sq&7S3r+doVwt zXq~96_>4}6p#%}whjakD>uU4kgO$aSgPDB@)Ix8kX?fd~HGB7MCB{FzX`%!X+=p*G zT=UVxjq|S>i`Va^5Qso6&cE@ZZ=Oxa6Q=y6CWZrv@BJ*$by)&sHg!g<#YI)CO z-huF*a!3gxyr&}XK%fK>-m{bc3j(#gXEpCYpac>B-E!}Vmn_SBMke!I68{?i?q^F% zf(W$d?_DelwYW#<8QD8*pac=|$0JX=9oD6|p$^BvystCQE1g_^Z^9V0^VwXLzw+ye z&8<7}7l=#VTtDycrbV3%S%gFH@->=m9TphtY|@wiTt>e^9O`p&-u>DK>@FvxB|=Hqopns|Gkn%$mCLTg*v5lGKf}2bCk>6KKdq3ahn5Fir$~|SRlopq(wET#lO5e@5 zzF{?cdD%hIhSEX==f9hs$+Pjnf`|Dw#wEA9pBxqsp|m_35pJyxZMmOs(u73j?Q=t9 zt(2B$Lu&aE%~#*a_tTCM=978-l?|zd2+nt@eKKP4J^n&o^CrjhMLpYZjw<*?JcQC> z8`RU0?wIFVsOMW#JWS*|-B==&1k2@oopr+^a~0yRVBB{$=Bs?NurR-3+FQ zh${KQ^A#Q1Sv;L_Lar#K#pNn3KVox<@O+8smUN-z6V>{VWg&v|zYek@+djWQHrg$U z$$KF8P*JJ>6S>Y+xv0f9X#Gca{)oTG*5&)|a|`bsCJy$=&tHiNmBo3b*qbAw+IxX zw+OtAP+I(ViVTr%jJnW2YF^TVX~c~`8ah}O=Vz9$8ks3V)C>T^IDaDXg*8O zR@zWyA%gSj@ATC9^K=EZ|dc$=Gbb3+;%{8RtUC{ zy>Z5f#U+LrI)Xy4XSqBIs?K@~xYU*0fO_3p$jkjneerfoGKZ2lxVDH7fm#O||D)T{Ne%bi zZDFr3*_6y5KB?}Y7QOvc=eNAcw|e>z#cOW1DVYmLws5d4MBsP0HEmeo(KaQs{?0Fb z2-I4B>7hQW+Dq?iv^huSuqm0_?#DW)MQ>Q;@778!KVsGWViqN%%lKgqN)UnHbf<4f z&zNjbvg)rK>O-JbuC)n`wA*g#?$>BH{8q-KWG~1#z(FnR?}Wy85AWz3pRLgShf(UvCtb7NWYa?#*T9cB^ya5rYHEjHQM%{F0b@z=~*V3FaDcN0W)OJvU zh=NJpGo0xc^{J;e(M${^E-xrKKg_EYIe@;2%6BhfdO^wQJtmW{R)~1LIi-=RzhgQ0;Tu;cP7m>E%6%hghL}=z_H-X7eL+FVxwn3=4}n^$NBB*p^v%iK zSp+4g-L@10C5TWx?II#u{bN$H$EB<8L!g$LZ|)mOJLK7HQnE)+X(3Pxzr^lG^r!&-hswPAT2N}_(vD<(=1F=E+C zeaDNG#uu0F(cHb*r?^8&Oq)5=hd?ciqMFw4MHz>Zm>HhcLTA$LISHsO6m_3%cj}_@)!zc;a)fe2$FHxXQBlM6t@FJ^BVH-4@|nBYX~-Pv6p+ zT8ZGZvUL%PKL_m)5QwyNAO)7zLVqKoD7wP2tFCj z_jBC)YJA^^@BQ$dA1n*C{4L*4w|Dp!58vSN&Opk(!hYj3wtRQWy_d?jclZ_$-{3(B zBK$V^{uSTD;yYM~KrKGgOJ_N~G3WbNd=HE7V4(yN*d}>T*yejbd|DmH8D|WlX_nA^ zIKCIhC*o0p2>-mIJEO*s!%+_38ASwYVXxEKsLta}x|izky;PJS0@n?lnoKp#T)a4s z^TW=Hz7a$%oNx4uEb5uLH%|`db&3ysGZ7K~6~(s=`PLzyJ;znVw;t45!5Y&3gYH>6 zbl@pVK$5)Vkw&Oy0qp?T1@c6fe$ivlnm7=tH0u)=<+ZmJ5pMGM=LZ5&m|#Pa62Y z!v&wwrC%E?{++|SA1CwPjWL;jqpuM3tBI6&x9CD>`aR?w2rgGi5P`P+HV}bYTr2uL z>sr4ZwDe!i}R{S{0NjF;=kL02-MbP)suhXf&&v|u-v;#9a~m*B9`Y7H||XE zA&gcBg1^w4$>r@M_nx@N07mXC;Y5zfB*v9HuWt8C2_nc7@lAiv!?oY}fwQvRdm`<} zY57iENP-CF)5I>lcpkANk5fPURx^3G5*$B55=87waxnOEM0(4;kCWrrbGz6lznRU4 z)$<`xi@Y}9qxZN^uAMy{Bh3PH_=vA015-?fA{pOnkJoQ><}UR>r+eoc#)G_-P3%!b zR9zAmj69sq;#+C--M))GoGNXynH!4F^dV5oKOXbDb#S^?*{#R?aoI!(BKnp;5ImeU zz2)9^s#0jbeR*N5d4+B~VGFV4yq}_7l4OH4OR8+Q`_xEg?5^FFqgqIU2)ex!oV6~U z<=)^aP^g0aSFvQlu~!HA5UAz7146P)`n|SgIw!o*0(;nz4+YkjZtMh`8tE)PJ2p1q zq2T-p>8vBo_)O8b=5?H99g>T?M<@AaBK87~Kb_?){kikYl+os2fB$Qu1QBSP?!Io( zowH{vnt3-C6o^1A>;+$5teubi=djjJV4f(U;*l21KiuZ$~g4{y`Khd?dtH~Lom zn%0h3{@Bc>jrPq%oMX6}>7CTIhdQYSe5JQqeogMK)qLfdNP8(ccX7thJ7rT2a?ak# zXSZE-*+2;*IRA$A-R;xMDSl_VT_;(5gwi6;$nSdbc;fReg`LA)|FSO`c?6C#_SL+{ z2ZF1TrL)!?=97S}8r5_1KAmk(?Vt&iAOdSkw*ePbai)Kk(CK#Zh=~Z)q8nSm7dO*d z?kT+yZK9kRKVGy0vxk@{L4>~@M~>ET0?|2~K|7QB5U9oD@rEbz`r~!TYmj{s&lL7c z>}_~W@@|XQAFnp|%`H4bc&6|y;WfasgVzC~dHwNBao1o!TCu!xdDWr>5q=xIVtM8A zszn59@oeFh>z**>70WA^S1s0xS1gYxuUhszJU*`X;qm5i=P^eKB6z%ctlTl@p5-1M zOufrJ$UVt>PM$~H!<^^Q_3|T08{Wqx00X{&*eo z8pN_ti&xeg8@&E_9r7AP2_mo;=m`tOa*pX7&pG<5-lb`#F6!5W!4|^kEkCqY;m9|EK6IMYL}zvT;;H2_kTu=m}3p;4Q3gW z1uPNcG`qFiL$Gfm&EYO=DKc?2?%!N)X|12XiatSj?|* zMKRA(>m1SaSes%X$3l*SC_#kZ#v6_-Z_8TD#Cc!K{GE9<=Xoc=j5+?fKHilm1oL;5 zXa3F%JwAdZs$4`cXMeX1lpq3azi9>Uwh@6^yi;PfAHP;8LBxNzoF%+};w8B;@@)kL;{_Du=p1gKEu#0 zQEIEyFUR$^wGR`^7__qx#qvTRBT6C7d;@`vE^9)%=+_pJs)2leBMQ0f-{-uny{D_IC zw%DBhUD(t?2_kBiPht(Id_&JNay8Y;?mfZg^yk7D9|E=LEJKigRdm0W)-3E}n^U}*1w}TS;B3qDuf#q_s zB)Tm-eTK;?|KQF(8;JOH&z0brn@NoycB~^CrwZ;fInBAI9#_{0F#Ho$pui|t+qH@hrg46M3!)%lwg3f9L z`6PjBqfvA@!D-OyMHV7ZOa0wFo$&9xa)MLpm{EN0BUF~kM|8Lxs+EiQc|f?}bS`TL z6U#z`%Daf+a|;SiZ4>|TP6TVIK6FnfOf8#3aH`iPfxxn6W<49MR4vT-z2vjE5FgD5 z6PzYI$t$odM5xj9oq#a;1Oy^bOU+&PbV8pkTTD(v)-)9;K}7x{H-f#5Bu1}$d{TC3 ziwP#D^ebWnO4MxUa$J2ax5$>~hN-aZ?Mh|BsQn5$X>qumoeYmlw~MT67GLxX(? z)Kcr;Ju{L1X`=wAy03=`)Kcr5wfu-YrB7I#PGuM(P=biHS^{g{+y{DWDL$8x>Qqac z)88w5`w*z5ysLWx;&OupHmB!Kdw~)}C?D)1ZpS>gIaN4c$%jBK6<6Hz4CQ}I?QmK) zHK#xcB1E>7*7)wH^>yZBTIbiM<#IT!I{DZ{iHcENE|#Qe726eXI87~lz(ffmj!sWy zwd!#~|9by*vN4|C7{Mv;*pWU2YGK@^Hz=1X=WyEFf4hMaM9^1tEk4uWo;J+Bw4B2! z>7Ah#B2WvXHr)pNuvftkM#ef7^LOM^tX98FD*_zDIlpk`_5hblrzWi$!vX>Rp17v1 z$kx8#h-6-Bg=Mk;)^v;?^4GXUC6y-FINXREMLt2R7{O_%11l+HHum0XB zn9TXuNxdguJcQEXlB%_C9dH@I&LYJNw)m&GQ*f`&r&vQ}alZ8YJ^}tVxgQZRA$`HP zWSN~UYwAfGsw_lsUj3b-LHqp$&J;LhfAc}-cnGD%HU>^JHoMWee9{R8>NWVqp7={| zSu3T*~L0bp6E#eZMj zJuK2?07;7{SO0aey#7;W@nubSJl>_nHvT9wCDLU8ll~~R zaLt?wVn~OwvUgQkT&~jcBT{uT7B;*6u_*MtJFk=$A~-+$#mq?eTc#s^YPc}P@F>wU zjXQS{p|sdWwtwtMH#)EVsl&n=zjYJmDs7VMLuqljO3ROUu%+9=8k1v1niL)68dO?{ zPNjw`0!Dya6?w8+TCdNZ3Ew;fk)a49=X||7{*{-GPAZw+xxLl>>NAQX&NGodN z;NH@P(n191d8P69lId%kv}*ght2Q1&X|WCV3@!txd~HR(`8U!8V_y!FwNhGKuF~=& z*!whdy^pk^v=G60_FeqtZhGV58xI!`p|scrdphcnDP!wxRMA&+{HBkht7+d&z?K z5}_nmuD|6F)qL$>E!7UJp&L1eyOC3_D5Zr6&U38Y-}N%h_Bvj4u9UxHJcQC>8!A$3 zTJ_X}3J&Qv%=vBlD84Hbl3=-I#Kjqf1SQECP(n`(g3Op0jU{Q?g=5(TCCM33f{3KwoDC*S9cHpeF`F=JBDY20``I01>D~PYf*HwYZ$2_ot^VN(OTVlpvyF>I4>j<2~qd zhQ>2n+mzVDIVhng1{UvgxLhoWo*@sJZ&Q+-0VRm2Tt2x)Um*{=oFPkxqc$b88*v6i zpcXwbuz2U^a)wj+5;&A3XFx4_VqozOkG1@W&#QzvlsMw>orX|Zh!|cb%%ZQG2VKsv z=X!RBlH?4CKrMP=AouPrXQ;cautQ052GpWGzr{Oa*775&#D+VRBxgVgB2?bx48`Y{ zb0|s9@Gb;vslU7Nd_hb(hmt5qoB_*HdFBj$1k{S}G{_cmS%^@1*9JW?aMV+ScOh6y z^`XldRPXjmlaTK;$njtamaF>EXCDH!FjCXa7kV;CNpc31AcCGT1oZ6uI`#6K(=M2Ob3~mcYec}rSm%!x`UoaTu;|zkIGoXa{g2An4G?o*vA=y-Y*Ry>!?M1 zLB@0+XRw$vpac=b7j*VBKF(k>XFv(@1)aSdmy0EZID^g48Bl@<;tM)^SRZGwnKK{) zwTLgsh~VQ44nJo=E#eD0M+DaLBfN;?FlRssB8V^O9F2UO!Qtl&h(IlR4lm=ak25&@ zoB_3nFUVNPT7HBVogIG8fD%NgypJSQfMsFmj947_T62-H#@!^asSnKPi4 zTIa0gM}YU?-wmWMVJ$=`Pvqka?BRR})Kb3E#~B1aXHcG+IfL@^97UB6_HhPLfu1v< z1QC84;M;u&)KdP~#~Dn1&VUj`V4HkV&DRbU)wms4!w_fS$jQGn$XLr-h)@yL#~C;} z`w*ywkvhZ~1V3j$2_lFu7|aNKoPiPi+e9epqn1Lu3}Bhj(YaLkFY{QxVkUlj7r)|r zVAu6vlH5`H*G+TM)2O4Z8acs0Y&5a{XRdDB zM%q9LA{OQTQvctK%O0ZGhowZm#RWt&s@3wyefpu;SyHn7=^DMk(# zW;eb~l*s7QHLJ{zubaRa89`QNePd8$OlZ`qDS zGGc7UgvQ;^uFAaEzDO6*wntO5*Q-H#bg6-2V)rCQ^o`U~%V?OyDDi#{nfH3ZLpaDQW4q{~YnrEH{sRsA+w=L|e7CG__Ojj1|sDRf1c8dM3;LJV&zN^N0iz zef&z|;HXlsJR4ef+b;0I8ZLa$DYf zYeTzJ>K<0D!~?~}@`hjUXbTcE1j; zK9^OZH7)pTgPnO=3cEv_u08~6;rP>UsoCq<`^#>y#;lJOC_%&)^Ko#{k@}vEo6YLm zGxBb;7WVfeP%CW9z2Ko=+j)o-EkCkrw0~&L9uzB3(k;*B;J|v{NUgp(PX^zA@}1Ya z3+jGk=Vr6& ze_#8N4pI=2Kl>YQ$s;F}jEs}7c-uSI_Zz1{AXl%~$GcPCJf{%;rj6dl!Y%z#lSev8 z8AM~X!BVfI=0uTJbE24o4Wk~-qMdqm@Oc(R3L@0(D$s^8I%7#|>1N+A)Tw`HZpZlw z=Xt}}^Lw22$*op??#81Wq#)wM>+2&${&+~q_{WL2E|u=+KXGAX2!ULuANeM7;{}a~ z`)#VV;e1O!>2i49#kn?&_-xk>tCahU|Ic#zK45kpU#^?k?t^QhKaSNNWFGkVtm=;+ zf8TFi>Cx0b-*=>g6hypV~`U#_nn9 z?5-1R|L(w%4sy*s|CTvz$T5*`7%}clCi})o%RkbHVv|E&h-lULJ@Z)HFRE0XH;%Dq z^herYZ%>8VovoxiBP@x8Ksxo2tY0tFF+)~z;wsQJB;@#=yScD=hv z{x)-@gOolszBXSdF6R%-i6UCxPq6DOe$3xX2&5pQPnR9$-QJ%o8Tp=m)6RN*tiPMS z^AG~Kj$KPJm%g)D)#LFi)$C=%9`=vb9qC|RuiHPF*^4X{`GyglN>#VlUCQadO9-SO zqTFkAE4S->RjSEPeQ0O>yQP1CN`(mI+EV0{IeG4QRjN*%THC9aF8B7#9_ftgf7|S{ z%@%o0?{U*ywlN~OW^KA;Ce|6OWPEyHwcUDhf`6W5AO#U&85bUIY&UOz%p2BiWC(#= z1NWRU|6MXs$+#HT$S(E8NiTQzkq%N2fps#BZa=oR)2DA|R(c`4Tf!ZZ+C_=I1ixd_ z!M?n(q4&fuBb}bB{xP$UEH7&=cVvPKcbw5ZoX2}Oq^LcdK&ZW)k}>$WYo{#i<~g+Y zK?HK)PL^UoJlWp};*}=YZxNiu7TeUa3;8HyhYPuPw2Ep;BR9$fed`RjMY>9I(c{(!_qZ z-$)0!)G8|S4I|WgZo_&m@>nT8~$2 zYqwuYI~lpN5P7K`he(GJ|Hu=h%_m5tAVQriRjJmD`^LJkZj=28&2Wf7F17DcC*h}0 zeB#!r*xIg7Gc}%_@w}|gq88696rcLYV^+~GI@p6RM)y}jy4q6-uCNTXhqGZ1C!`}n z?dOz?XNEj(UHZ)nln@`)A z7jlJbesFkmZ)=s-_Jl`AIjCDu`)iS}I&G^yKX|p9*Rxdz`{K7F9i$*aoz+#T{I_m< ztqy)|TVwl$5XhxY07}L~V?XxZDb(Dq_1#DZxzu?;^i3GSr-}L(TiS4%5P2a&oh;P2 zDqFa+Kjfp&>`2~z`urgf$fZt8s#M$hp7M77ubw?=8qEyyTqE*Q=N*v_BlsM(qjP;5 z&QT&SM5r^BDpk6yz5FG|me@b->Z{Lc0)brW)Tc@{XXC?urR1vi#Lgof z9fzt%|H`%e-i^}PzmfI>xs+x?q)OFfWHaCYV7v9=h^XF2P!OTCJ4(hSsVTBRQzQ_`rL;y0(QIuye`A5kR^cyb zCnL2^f}*rhBCT|ps#HoxW`T}OP!OT?WlF|N^E&uHo0+YH=|?$8Q98K@Xz`Q=^7p?x z_@y7aZ;nql%2E0~K|zGl0SYv!{G@i!WbGg#kSnYmtnak(2mWxoMowBkkb;QxZbpyw ziE{l=h|Osc$c36oy7zi&v%kU4A#}*7lR=#|YIi91r+v}Sn=wA<@k6}+23_6>BO!oJbdJ-f~dLKm>B3 z){r7vuP+{)DR#+!f$IU9MnotZi;}VEa#6pQRY#O++0pLFcYilLwkS*~`;hDXc1Li9 zHNw0`^=Q?>=QRrT#;7$4BL+uic!!dc{fab7kb(%*AQ?u})!%uEE2I?w5y*w5rRd*J zJnpqWQ$MC2i0CtUevNByr4#itj1AxHvJY)78}y{MQWhRjThz~-{$rlm;`ooMty<^& z+TMLcjw_@f0`(~L3i#sNHpK`Pr9uR9p|!>^P8B+857>5B^f^)xff@^nL02G;)3|qL zAp;S}g;pT)8GSOH^Wo6LLIzS0f%*rE_GTwK9eW=0`TIZwa_uR0+-#IGMzz(DSr0oY zQ$7=LET`~`Lxc=O zAQ#%(NVl}Csg);dk^}ZAu}@TE$>MJXcbxQQScY8`*}I;@;|eK=P!=px+V0A2&S%f- znkZx-0=aN^ZW!$+x3vo%bR6yvq#y#VnG~h@k0Ex=szrqiL?9QQOAI6P-H&YdZdHfp z5~Ls^Y#A+bVY!{OK97)r2;{;O8NH9=9Iyx1OcM1#3L?~ZquMItA3xY@b7T}U5P@8H zdNqt@|DKnfz%ccWxf?S0*zl6cnUK1T#{;kn%~7R)Z-JliY1s0UIIp}rd> zV@0>D&Z27DgbYL=7wS0Zz0{kJIk(Fmw7Jibf(Z59C>cdd6mZ@w@ve}82;@TT4!v3Y zO;u<6oh3H+IZ_azz8fXun-B8`ZlU*t4BSVdg&+4_hVfpOa>3nw--&u41rgzU0NK1O z!M2CC3mJ$&F5Gb%#+o^WgI~A*Eo2}C5o%3T^_XzpM5wi0$*59%uRrH&Id&0&T;VfLp(e-uK9@@h8Aw5d+M_5LU*22lFN)+9-v=U) zD}1`!RO&N-^~y>@22v1F`KQLNzwDBd@vA?;Z@y5@C5S*SwQ8%~>%`G7`$gtjLIzS0 zp>`Zf#-;A{gY2c>vUs%jtZR7j8RkcLw!~d#ffeb*K2gr1Z}dnC$}B!;)}^l&DTu%w zCykP$^@GyqD|svf5y+)vtJ?{sW!EJe_8XYM1*D3s~!mk zq@N~Ag?S+t-ld?8e)*C?v*(ihw6`n}fps#B6(4#2-Hpq=-%f;W^vH$x1L%vA=MR_9 zA4ow&c&9)8y)}NZ>NWih|Mm@8+;Q)V)_%j-Uov-aWa(N_52PR>yhHxHRrz2-K2Nk2 zB9IH)kY>?*&4TPt+!D8Ukb;PkPaSfvbbC|uCixF;?-JC0@}fWU*RuL3L@NR_qpGu5ZjMAMjd>2;{=^r(w*^ zwBIk%rbEED!jOW9yN4UOZN^?yHIKV~!Jl-XOORnN^@qGcC!`}6-u|C-X!5TA z(5fCm`Aw^Aq#&YJuHx?X-8WRtbC>$cZ}Mc{py9%@Ap~+^E0DV3$)VPq3ltgejk5OT z^6et&Z`>Dojov-4Mv*H9#rrI7g-?(jK7Yo2qr>Q6*MYJ&QV@~yO}pg()stw$_#~yD zSN4lRL9Opsg%HRUKG#ke{EL_A{HP#-?hYaa5nI0NmVDpQGN%2J-)~xDK+v8>2_ldS z+l}VkZcY871&0Sb`yd4oUrbN$*8JqQYTd8jneG?*c}Vd3M2j6;t+}7N{{5hzgLhTbNl(mI>SXCj3-6GEHSNr=%dZwGh(OtN zf*fVqKTNMB^d*QuF02#1iFENb+q(5)@Y#-4Hc}7~uE#U;de{Z_zY<*du51W_T;aCz zY8SHK*uRl(S?6KGL?9RTzhNwY{As7`jB)~jH+$9H zW05cFgA8L)`X`*CTdM_&N0klT5k|zb9aoz}UeG&$r6-FxEt9GRkNV+T#mI$vEt;vl zN1ZlZ8w6+8m$i|Ch;K{HGn0PbuWJ5!+(S;#zp-d5L?9Qon_*OJliqo@X#3#FZDnnw zAmWWL#+y&x_+7~u)#Z{M8PO$pb$l3sT-efvk@4O@C#Cozu_MD<*Ux9XYR-J_X^}5# zkVyBMzK@eGkLRD9Sk^`gB7RLeZ?^2(LX~P&!A{PN_jmbMXjMZ5a-k-Sq7+>3>U^>J zj6dUpvNlo>aWL~Sv+TUlN=CkSn>ag~-S_!kI3kb>HG1^o?at;-$?tLo^LLlk_uIwn zgNR>x?lZFu)cdPKEgCrks}%|oMuri{g(H;oSFe*rH2Iomr1h;1pU`PMi&pf(Xu+=GEM!CUG{;|)OdWu#~q#z<(4^?vyYA(*<$c3XP>SVHyQl{u!u3#Jl*L~Z=7n51V(87uUdeU`|2M1X z2Xtc#{1{O0hjlWHL2HUTx8G_fbYw_DL|8jm=`+V!vADg^!yy8>uuc^5{eBOp$W!xe z@O%+9M}(SDO*z_^S0C!!{%DHLyI0H$xv>8YW97$GstSqDn}k459W_UZd{L`Pdj>hf zIWWVStgS(Wn(b7nzPerCIaDu;b14XW2_YA1RSl!k(Y8+CE*YFwUq$D3Ap;R=4puT& z&S>YHXn0t(73PIp*lva~;A9Wy{r7&h&uopZQ9=eH)LNoss8!8|RZSp}3tQSS64#~J zyB_N0aDSi|m0Dj#zG~GLIT?mpogG-61qBgmrBGY)CD^d`l z_CZR9+L1Z1BNL@UE*zm`!OAqv?we((Gvmjwhnw0n3bfiGD;e3cbh3y1uaEF>Lkc3) z?p&awCl-fKEQmlZb;eOL)TzkfQxQ@Sq0U#rVirAZJ8;?-c_EiNM_ckcS0`ZyPQoHD zbxIXn>Qt-{>I7-?2@-E+sk5Q53v-^*4l>%b*5JJnA>)gTl=vFLbHu| zAs5z(yrf76Q0|LCPR&#ufXE9G;d*qIdIksd3<7~%;kMfJ-gNKeGrs*<*8ZWJXQ+F} zI?rBZEm`P^Z@(Xkhtzuc%cDh8pnQA$R)gCF}7^LH0tE#`$> z*lzT?eBLE~Li&NuZ(E`|86g7^N++XaY?fLa2edc>fn3%+f~|A zk+0Ips+!Lw-Rt@xxtwQGb+3Yg2&IQrrOG?BX3(}noKrA)mDcYH1ahH`%`iG0sui4i zzl5{>W9mVvLykcx?XZ&3=UUm|r2=I{>mmZV(8gvM8Rk9_^r}?N>AxeYJr^<%p|spe zhSIk??M8Zg?RUs7lLk)#W8-{i0E4Qmiyzne5&SKp6L@bo|9~^qP-~Q zg%(X7dR_s2%_l#J(Y4h(+HzQtob10s+MZLEfIE8FOxO=44z_lZbB z1fBGRg;&;N@~J^ViH9m%ECUh9g?&Rliq&5Y-hXt9#WIkB2qjPTpsKkIH5ca(n=Hz;!lGh@*5h>DdiOK0{Ew4pZjr_>`drw90i|4OKl9Ko}sO2AR z@``6U>F3YhLm=XtUy2l*yjUQPRKFN`v;AUo(MJ_2#^Kq>i0u4k*fZBh2e+qQ^FD5{ zOGJ*W{rss2zuMEJZUrxQ=JO)`oL#}=zmHzSFS7l-WJoY`L_dFW*={yc5E0kCf;V8x zxyY67j7Yg(Gnm+ZtT%YzV@~VMGB17y>Ff-do=WvF)>QCry>v#^V|D#D!Nqdpy|wFd zI7mUnnuZcBUpN|myKIouXq&x;|#-`Sc=zQuc@AVq>;jn_=u| zJ=WWMyk>BG)?)&pDQOY<>oSauw~l-JRu2qnZ2r{FI-#OhZqs!!syW}1mu^H>(l^0r z{cY0gL)|O;Ltp6<%(!vEMheQnoXGCnZ-ZZVfA!$g{RJJQAOc%~c4W)a2VEbk9JHWU zp%H;x#}8KUmd0I)jIP7qU|jdoLF3F9`~_#Hy%p8Bs>vd~%&^qIH z7PszO-`o^)6!u4z5f#1WD{hFtlTLqFKfmGXA;I3)pSO{M2y8>cxI6qyzg5-#!Q;Q( zv=D(@U-YWzrM#|XRQ=O1)ssWBG%O-b5QIhzPa1ajyMyL4nb?{q0llScpI_uR#SbZnm7~DP9KEnrqKB zM+zcvo;Qr|@74%rH!10~Og~DODw)gs##4RH6Iyra# znXF4C5JOs4q%Z1va-Ez@%|$O(^hWf*A^uLbiCwvZ4P%=*H!@VSs~4;2b!c);&uzTKe3;h3oxM&cze6iorIKRB zNnYY}e{49t&0l!6uk+!(*DNeAmTLa+iaax@QXMEb*zw%|R(Q}Bt^^&A<0@!*s==V{oZHQ zD7n0~a**!cO6#4>RUM=t!a5^mm|yT(yUa@r7Hyhn_uTw+2!UMK(sU}?n1vS5ED5Xi+no7#gky9FbDNgp%Az4%N8@4y@9#h2Q$Qw1-f>IE^|83xTG z0nH~i&m~AfM7dfO#JG~H!RKR}1#5QY5_2NXwK%I`PIQyJ@EUjEBO{y<6JFK(67l75 z+4YQr-=<*{XqeeRfcTp55XPiIp_ioOCzTbxs$c1wZ?K0~9;8)Ak z+SxH=r;QXu;H*trwfBDWUp`vNiQg9&`p%IHM-OS8*Tn^=MwD?He|_6V3Lk03dIt^MS^cSGMfBEo$>eBAKhv1Unj)7}k32;>T{YLC4-EEw|0WINy6^DLww zB0Lh0M8*a^7G1Vl4Nn(ZA(4yUB;fBuj@@G4^bIP%zSCz0s!cjG*tF#dflyzOpdjL>EfqXx&y~o(=d+TG z39}0a)0#dLgFr6a4H`y|0{Mewg_{cmQV{X}?-ji6_pV0vEMpmec0TXNb$B5Lfn2yp zrFX;QPy1EY^$-Z8AfnvFir%>c*CThH$U-vWvkvkz|2`rHfm}RG=)E@S6Wa~+H=dCQ zq#)uj$vAT8dSqZZma+AJmps4bSRn%u$ff_@bp^jMQs&<-fj8!^=yU8_><=6ZWTStw zd(iC1%Q2$_5jYkMqjs16!SO9Y3<9}ugwn~Yz`)?M`(FwKQV$z~s#inJpk)qQqL%mX~WH2|Q zbX&1>&I`G8TFRil@VR7+K#ESY4E3(9lEJm++NVVzmriRLe7B8S_HYmOA1W*O?eTqT2Q zO$a$kG#BTETskdfD1`VvkfPJN9`sVMlA%f!gJ5}@OQ)p_RdYwzgSnWZxpaTf>%dBe zYTXzFx0~kDX(@xhaV{ClK#ESY4DMNasJG%x-W#Zw=0!SF?L6MPUMXg) zOT0SU9gceQUl}V9Nap{6FkyLAk?enLb^`#K0&=~u1YokP#$Odh86;W6hs(<^Lh^z+h-Q&pP5QkVb6U# z-?rxj0x2~b<@Ht`O)(q%kvWZw>1|Ki+e`F}k%5RSh4Xr=_oSGARp-6Wik-=JjWPpb z5Xhz8cUSdrn=iH}#Saw-q#)wRwmjaEB`Iddb1dVn6BX<|rR6t>2;{E7-~H*Qm$RU&Dz85!`COET&H&4(ua%_Ex0 zez+qH%lv+fgA_z?Y3bi;zIxJs*QcNDY=1E%1JM)i?swx~kF%~dW*NiZ_}HhP z{lClI9i$+FxILno5@F9z@#$x`bX$ZF$o0d}{ceN$an>){SP%E^jx#>}>__v|b&!Gx z;`WGUO2qtS*#i1G=N2S}5Xe>J!ajFE`Z#OrZkAEy*?a;0oNK%CI7mSRaeG8FCF0KT z_<(-SXIC%Sh(NAz4_-Z9GN7OHN55Zeq#%O&+asDO`#kr?CjNL1 zJDY#EI=}3^m^I#OobjT$xbR~0%9cD{o1s6NuNPfxRy|wXyZ6CG^RM%~dp#9ou=!Vh z<*N=-5D^|FKOY-n@h|C-aUle9&Dm4j8&K|&S!fH(=rp&D$-m!jjB}8JhTG`>>w_UDUOyu`$u==6KEl*7MF|9)>H1rakQ<%K>^_$ATd-^8gug%HT~YwLLLT-$SI z;YO@`ojJLX!@tjuW_6H)h|g>0g|S;>)FTf626>r72;@4_G2YuS<(#?wG>_ea*GX4G zzfJY~g!+8mlkwipRu{~*EyMk97<~qiCl&pQzuL{genv#2%JJUM2^Y*cWB5DI)Am!F zf3;495y*AqpFHrLk57Nl=3k!C&pJp!ME*MQUcIsB&F^z^Jyv{i#^&GFB6ULumc({r)@743} z!aDKR63Xi~rQf1-OG@*sMDo>qHGIpb9{&zLHP*qomcBoiTHE4pkVd*oBVNqfbk|_r z<39gN?;7DC1rb*sy6C>2E#4Ygko#l$i8DU`&Kq)0)Y7q3JReibtC{-lb9;RL_1M!& z%)6R`hPdh@@XGxOwx% zTb&YE#+E{_`TU!(ct8k&T;ZC3M*4RCZ5wsf;?Wwa1^ipS{reCCxp-ZnnL@2m^LE4s{QJG$d9mVX z3L-kKKj)t45N{P)&!fGmlQ-bs*gx}$RZSz1D?E04p35EZuUhX%#LB716(VZwKj(IB z8*h!6&oZ1cSpxno`79}fKrZ}l3}f)AhQYN}#R5J@{ctJ89i1ny#kw%vo4k9~X*stC z%{vCy)@S@r1anoUoDRk1wWQ|mn=u`Ob}vZ;=2duqic9-nF-pRSFB=R9HkC^jCt;)@ zqWj1cm-diyj2UlP!-Ms^D5gIBhX~}N>yGZkm-ARsXIZT3*kH}2s~#hef(TC2x~OCn ztkplr-eQY533vBX+}3^KEY=9`oSouMpA~1ZM)=ncQryh1#aU7#{K?8eLDx6e3ItLR zasRCpcj||6medIEyEG<9_&uGJLDK1jC#2^Xmg2V0l*eL?aJW>J_Kpi$Iwff5OJ4X; zUPScimEtz3o5zwG;Y@#w3+9}cH_H%#T-YLpv2Omb;LzmhqEuL3l!5gljrpWyxShlX8VWdAlFvz`VLkt4Bu+;!6SxFm#PQP&+Qsq?0h>0 zfn4ua-RHh^Ker{doc$X&3${L8K%8-qf(Rbd`kX+PpWJ4!eVx<}A_BQ|TAmni?suE=6C7rFVduabV=8!)~M(EJQM8fUsxcJLYfGH=JSV6OFaW?yI5z! zqXa2B%?Q$!xTM=qGFYR=I+L^r75 z8d7wcWpKNZu1U#I8Wu5MX)fKmnoA?345h^p2&CvV%P3HFmPd)w^W_%d?@`K7ts8?tE}fS3P(3IRNYQD|mwT3U{HfzAso^d|CL$&1Oh1!LP)C&*;fLx zv&0}Ynz?Wuqu05}>Z41=Rv%qnss~$t^!&)WQA^6e)}?%-lm{VXTd~y#N)<(DG;^`l zCw1OstB;Upx<4LN57p<4pMZQWpKOcwZt%R#nD`x7jo&eltE)RY9&L8 zPO}W|*$1yUnv3&7E}hmgLMx8QD=mV@acVu(7ZvcFhfM;vhw*xgPv|=$4Mo zyF!NM;=GVcr=<*Bagd_ZEQ59&;c*pRaWog_g9b{tEKCA{6hyFPi7Y{uv@Wq_i7ZSG z_aGvWi`y-Ar_YupvM>n*QV_wGC9)k^(z?W!C9*KZAdpMvB+mwH^&#tz&!xhiVyh3? zaxAv|V9!#Ylhuc;KLUXiM6lI|tTdLi{IJ!BtUoab_XF*%k%9=eWTe_Z zDjv(`@Q-IxL?9P)^S`D2W5B;<9RBf)jTA)aaV51lLt0gG_{S$aL?9QBbpE$Q{6iK1 z`UN}43cy-_t>0q~Jrl8IfVB4(TLu;AXY2LkQ$z zeLiXLEveHlcsS9aUy$+5pX?9?^5s_0+BUSPxE`ZcFOIpU!{Krk~$+$g`~9HMK^Vwf>}~ zw^;L!Xu~M?#U-15e#enDS=SepjtJK0lm6Y3I(?;~_gO=a2;>TvO4*8BwiU5GNNdU2 znnboEi!Dm{t95&pCbac*kBDq)^z+%S zh7?4wt&MDM7TenlBj=B^Z2I|a7Yki@G%w`BRwqv+Yne?yzgJ?9P=6qT?KxznvDl_V zc7t=SO+UYW_l_Y1a$(;XMv2QSJ^ESI$#;TVR$JU~UU`;g(02#?Xg;5bWhncH!}brh zeUL8KWcvr(KFD@pvi)NTtqNDW?KkBe`pbWu^yz26-m$)e6hyFs&YfQ@@O?mgc;*B{z{p?Dudpk%$1X~%%j$lel!>5_1`t-A3oZ3Hx zK(27j|2#d>r=MMZ?EnWUh+vBh*(XeCm04W>ai4y6(H}>I5XgnCZWz12tsKzL+0^oi z#WR|o`*^0)cFsME@>(Az?=z?L=NayaCY1yFIlr9BVIu_*Y{?+Ig(*Zp_% zTGh7hGo@eZ)!K;x{hYd`57|gT1Y0u5@?c79#>*QD2J~|VugmTr0=aO!(OVGGn&GfD z11X4LO9t60%#bz1VQU5=kPE*8@|+~SE9qaw{t8zwo#s6i>vl;mYfAkt+djw!A`oo* zARCCu_7C0vyr%1+jYd&wzkb$;x_+xDQ>x(b8=6hyGSf;8wR z+brmI!rv+O<%_*z5Xg08RGc+(xt76JAF}=k#Dm(3+lQ?_WPdTG<>#kq8H2OEB?2kf zqIZhqg?ha9>07jczNp$dF|w27z4RKF{VqVee`rONA6f zg!`lDq`7wIL$cFPW$Q}dFKu(h`|0Q&lj?Hk=;ww0};rDUxCnHMRk^Z z+U4^spM+V@!zW|jQ|q)mZKK8uDLTyv));V3oDOTeG#BTETskdfpvDU+I?egA=7Ue% zQU+?gG#BTETskdfpvDU+I?egA28VSiQU+?gG#BTETskdfpvDU+I<4!$Iw2`Tl}env zG?%W2=3?2LmNHP|g%q9Ue7QwfwQU+?gkfPI^FZV3#=%fs^v1l&N z3%PV!%ShFDAw{P-Uml^U^+1i6=Hk4NOQ)p_)OaC9r&$JTaCA$DHC~#F^Fl72mNHP| zg%q7;8LSfzjjO1}OLK8v$feU#2J5J`hXPV`nq{yKo^{xq7QPvd_RY{-oELJjZ2qF8 z47M4N?ZD>q`GdGvj~_;`b{>2)qIqd9MzD6Cb@8%Ptew}s8JdfwBNw;2o|O!P?Wkl= z6*C-C9)yrG)F_ETXf$*2=+U#CVfg1pIKNaKD851RII}pa2CtUw>Q}HnxOFZPPxqV2 z^Ti_XGvzDO^@&l=h@=hzffPi1UA2OhocUbjcX4xh%gdnNJ&-5CFENd@ci@>e20Y3{JJhB0DUS7&|F?U;HXqEFWf*0gRH zB9DoC;ls=IcQ$>wB?f_9SSQk+FU;gD*xEsq>dy)ltsgF5i&Q$Bh5g_x9cN&`n2Odb zeQ!i+iJQxVyg-1SxQx;iN- zf5+5=d|xf{mK9vxp$!e=rxwpRCubIpXgT-UEIlWzJWj>1rgYW6s2InW$SNitU!<_o29+wbei|O;hHDDR>96tR{G;01rdi2 zR+?GASKtw6|Ec9Z${qwC36}X3x|DZcd0v6AVM+#F==8& zYyG4fky*kUut<%y_W4cHuLu#yg=4`mzMk|GmCZ1weKeMR-1%D*zU(S3;?(qfv!eJ0 z=l;tx+>#Xo?40@LE^BjrL$QVMm$Ng*H=wEdC zOMSa=M4%`I5#(9Ue~(Cy^`Ad^)ag*7^YR8plMn*Ac#LryNBk&}qMWL&RZ%lU5F{N?Mw*f!4AZ`UlZQa5J^fm{@SK**3M;nrE6ceZ@``SL?sZrMnA03sq0Z?7Ea zyfPvEipTGK9zrOz;G*a-LWYb@_0YX>PVF_Nm;bNB{fM5Cd6rS>WKNS;Gb180ibwMN zvCgfMpDbT9g6pv zd}<>F5m+aR^)mXCWq%$0$!ohjWx=?Lo+8Le|7f1G(AFYD9a@z;!gReXb*f{45M>sh%C_A>hA^xH;%7~k)aWcPL1ibylj=_p9cei(%U!1AT(FO>UFLECEbWf?Ro1z*DcTb zLbssF?rSzuFkepZA9yuVLVQuPS|%-@)U#7?=3$`q{eHqHWhBQhQ!v;DY7j zCN~UtIVMOX{WGE)0I&kK{6P55iCKeMZdkrJgK;>!NIR^0lF5vkuTG^)Vz zFBV?*_nY0txYBtc7t5f?Es>QJ%Z6UT_;SUvZ!2aE$|tlJ2u(r6jcs+U!fh`_U4)vxWcEKj#PDPSuAQV?;C+UorHD-mf0*t9M4@|icP1Z)LB z1agI2m%QRF@``tO^(0Sti~Qx2Sx3fbj_JdD2A!6>rFFHtIdy7Zw;4fR@fJlqNM^kl z`M6sY*C3g-T;wNiQS3f3+X-KNn|$^EQwHZte)|^114xd>1F$I`fIuJxOG1$aEQ+zE zWKhfjn_>>cAdrjV4_Fk}AUPV>z^1qc0)Z4nP=o}FVr(fH6g$D8*aWarE^KKLXTqt}DX%CMQV>D00W6BK zrDRO**u!~y;Gd!g5rJIc9z69+Z^v!9Par7bg+(zkl36c`{ZFw7EQ+I%EH#iPmi2Qk zHIe5*q#zBNPpn{3l!D}FlmdsM6bJ-T5P_?xVNjF;hoTgSy&@uz zOQ+>I>iG64iE3Xhz9`-m@!H2Dk!A@IV@a)cDtc0vT~iVV4jyE?heqgiFb1)U=C0P) z&m~K1M(rz;66;^zWN-g+fP)m2(cw~E>+nbClckO2gJK0r-5jysPFm30K?))`P0=2c zIpU^a3^}qQF;Dta_RYU~#2_?RyWeRpxo{y_+KOH{Qo7XNcMPX;!gCH%Fkenn{KRCA z@M##A(tnb;W<@?{T;Jv~2+cKu=Bt9QUrAi2u(r6(Mxr#6`OA+OUqCHooh?={%eF&Vdwy{1JDTMVi~Ei z!shp{T58$mQO?+}pS6*zd(OJnx7lwdv#ltM_-aX&QW=N8?98}1U&zpTA)+kpWIEKn zkt}URcaN_vRpnYQ=bS3M3z#yt~PO=CR-6w5YeY+U90DzYsu19 z6yH8esrhf!6t*HnAXm80QFEs>MJ{WKloltH4(WXYUez=gQ*@fqO7A1kQC)Zp0=aZr z%SerWffSu)8La&z{Z&*(>fJ%j#d#r@PD>f6twoAXvkcbalIBjyK#j2G;=GVcr=<+k zIwM7=S%%U^D;cQS)?Azya_O{`f!cGV=(Mf}>0Xr#)X-}#T@TI0vN*M5Jx7X8vkaw; zP90a`mJ@%qnv3&7E}fP#ScjaGd~(u$=Sm|iMh54U`h6%pwLl={K?r$UJ*`e(=cUoi zrAx(iit5{aE)`M`p|t91>?)nUmllCsIwx84Mp<8V)~sqMWTaG2u$FF~?k;#Er)B3# zu)e7?!!1!Er#1Ro3F|p?hLT}*8EsE~bcCpR-4W%iGiwJ5icas%p2<4iGRgYs_R9)! za`05!IW|lnkb;O#d&*jiiw<%(9pe~VZ%kQjKa+WI3<9}+NGW6W+&0Ah{RYRGxRIpHfkb;QHtrM)w z;?+0S4$l2{fOBrurWgcrtzDjAwW|59Yp!N(?JpC?I7?>c60M6Z`t#KiR^Ib7-O)F4 zq-ou6a*uPqKCsr~dSJUFV(jh`RvGdd`SYV3B;(Dcp1ppMQq1;Zh-@Q0@fl&e}O{{^$6v z!Oh8Io$o*SUkn1du-(Yxu=8-|p<}O!)A zovDBRPxK%nkPG{X{8%0t=#V;t$@;4G%WfC4F5&l2 zZv#Gg-pW*InoHF~^ix;{QZQdmpZ)o(NZk9E($pg@LUZxob^pi8 z&~3t8)SJoN&nljD(_T(!wvU;Y&~>8Bcd&#j~{=d>go+?M+r;U2;@?K-^^p|fieUI5nS5! zuXay9Oe@2GBarLAYmO8|d`vQ?zSb*w5$&~NW$0E!F3yR2R`y{39G#ujKc*LRqT0Qf zyx-Aj-Uq1_Rs7vBG8KHmd8yL{vEm>F5qGMVw0doL&s^1mcT2;@H@6Ec9YwR8VW@qZ z$@%Iu%lr9I8LQ#^A!cW>zk2PVrS_aPLj(dTh)^@QD%B)A#jakkPYeRNnm$>^y4rH6 zxo<7+uS&+(aYlVrN+8rsE%I9Md7?FR<9PG4%Q>tv6G~Y}tuf}8vv^heY-Uv_<<%+z zfs~!=N?Y?1N18WxWY;UFD%Ft#k3082v14Q);+-;&SubZ9VQzSy*N-9NNEcoQckDc2H>xM2y&(d*!fjRmk5SI#i_eJN zlG%q&JYNsq@&$S)gPvqDQ`v3 z2CA(JUK;33enUodKpBYmvSUdr^3)_VE1?bJ$9^w4s}~)NDHU>I&l*Pg?rofO19Qf- zE+XtoiPqkX6U|r3vW)4kHgPs(d^84uTsUG3^G_a>)B zAlEcHe>_4r8gnh-FRI_7an7zUyHSd)??AanXO4~Wv&@bwqGudcs?)|eXYiCS1OiKi zh{-ogSl{oNX}W*2j7~$wI4A4mw$qjhxo{j)tl|t+DF%I2(dYUuIPXh}eUaYE{mljQ zX!UjGxEWckrg49m1?Ri8av}n`5WVK)4fBI~|C(1`;N21;kb(&IDBypy?Egj}*S@x= zOuu&~>z(8;(jYXY<^J^6!Do+{$rrO*Yck#7sD(m?Tn(^PNI}H9RtL>z&*!uXm;Wt| z3`8K8{(Edakb(#;Z+g2O{~?3(LM~mu*qUQcW$BaCinKjs?(e%_)SBhTmJ0g-5jx%D z+L<(^dJuxS^xtD!7b%#pE^V=$|Ne&z&I`E)ug_!^*m=@ySc&H=>_Ma;LXXhL-^rK; zp+{oLe=}JHbKExX6uE6yq8-wIBaniKoU<}nzhymT&J}wfEEOV<3ricWhaM$d^A<~w zo1M31wx;LLY3V-aF&#!A1rfv7pEON3lU1a2+O|Rja$$>vWgrC+TRYq`&6GRlo3t-IDk85rJG+cE4-p`6j^{+M9PvJCk0rN4AkMe(#N&YBrslV69!A z)2d0U|LODz)(tZ!>-kKclckJCaRuyt<`_{Aq#&YiyP4*RVU0v zU9(>`f4D|^nMOIRshh@|$3953E@#Ne`X-ZiGqQDS7JAf~-M@)IAlIlJ6U-%viPqqT zX%Tb2&F}R4KzRv4UWoYR_yqHGkwnXB%>7ZuI%794EpI@ebmYP|q_+XPZL`-bma$%t zf{0JgO)>9z3D%Q~SVq}*-nFMbCB0G*fm}G=41@H?4(pM5JtzIK$!7v?6P@O7h4jZJ z?`&mT9o#d_c|Yegfj|l(YLy;jX5CWOs&|=BcPGvda(WhD6N5mm?c0Z#-;*ABsL&z* zoBt)JN#4T(ft0)bUN&>iPqJR9ku6QBzIpluXYMcOV`L!WuY#|br`jc1^ZW9+%J)iB z=jly_M4w|lkPG|CFpeZNa55i_7YL*vqEeR;W&_e;?d{CpN12_~okJxm#2}ChM<~7Y zw`x?d?QkSPY)x9=e8(X{9kciZoBzUp;(g1f48qL{C!McmXcs@?QL z!KwL8b&hrNw*|mN9XV6O{R@OpFXf zjQnS~TaM0za=!ZKl?K7t5z!uumI}GB73dz>+~Dq5*m z&@IDJJrbksj$Gl^?f2_cZ|Oie@6Pq!rrMSe^HrYRGu?Y!H8|LjKT;f54MG z!yWyt|4&ajUm*qa9k6AJ>+R6HbGBLfi} zuZH5wxX~98Y>HbGgFr5hS3@ycL}}@6CB>_uxHSTS6hv^m8j3IDMqfm5C~i#*0=d+= zM9JWIH59i-AdrFxj#onwY24_G2oA-qi9sNj&Pkq%I7Si0DiR3g=_{n`G~XBH7)7Zy z=NLs4t4JV_f(VXLL=kY@=!*zG#l{f`q;O0eige?u7ZE@P$Hbx7I59F1!7*_thK(D2 z5y7X}I57z1;+Qykj2Q;U#G%+Y0)Z4na7-MEVdF+$MDQs#P7DIMa2(SRrSRTdba5=3a)41{_0TmaAqnL#d z$fY9QcoL!F;`kgF2Pue9k!f5R<%VP8(2wJPh7ic5BHnnRxHtiO>>&jadhANAfr^Vm zi1Hx>a;ej+ClMSIN5{ocaUVjXow+zB4n@Fmqj7Npij5=U;vhwjc1Cba9FA%&qh@nV z932-25y-_caVP?g8;y$-=(spYK?KLdp;l3?%Q10uTpUCo7ste*cs6b{E>581;vfYP z9219P&A9R{2#WR|@Q>r-AOg8KCJsfRaiei@d>t2uW8%*f=6C4kC~%Tq=r-qj7P3dJ96t#X$seaZDVJ?aoo`MO++T$HhSkA~+@v#jtUsadCVd z7Y7l@g{>~);`ll)4pI=oF>xsBjT?=NYit^8q zZafv`pZndD#Sl_697XuI`KO}%b4({eK?KL$p*T5SG|InCQT}ZeaCN5gZfeZu59A8s*=iDF2R%@*hPYmx}47)(?vC@9x_9J z7k)S7S)6&WGkfZ4pLfVvK29;;UKr6^ zL<;S7IFh44aCAZ1r^@~}MqKXY47&cSkbwx~n!YQ=yxB6&J6(-s6dFN(QJ-cJ`x2xe zBD~ga{II@ra6*X~1aj%L+=~|J+R+)kFr&jY=X_~*DayO@9>v;uIInjpQM`2!9n*$U z^gu&r(UxKY!FlP?{vZVJWT|!cjBpCn9vsuUNkdZ1rdjfMFUy$y(RMS8ws*!j^M@J& zfh~%Nl@v>62+dwyU5;=l9EC-)_MlOsdtzrNB4O+mzZk};YP z*ZyW1f0B&vvTUGKG=8GU3%OVZ?QE5dmwSzMet!346rm}I`1|D))9#(eYq5l7T>omg zv%cH}Tg%W0?kw72?5g+|S5lM6A^=3ZK+H>pumz=@755ypl3wu+% zwi%6=!I2^8#Z)yhG-k=ytYRaq#A{=Hk4NOQ)p_ zx_d5SK(Y*^=rqgV=o)m(T*<&2*qV#;LN1+_GBB0}QgoVSsMx9lvZtp9txU^^Fl72mNFE=XBkM*XGPq~y{(0)S^11e0bIrwhA(u`| z87j8AKp;h@S%!+au4JgF@-YbH;xWxNmohkB4aKbyhzD`;J^e63MU@u_r06swRP1!DD@5otbLm-0B5;&Y**8qFT&g5dE{%{f@QXrd$!y!edIbRybuAVD}FByLy4u2n-i}OM* zoz^l^XKJMAG|Qkb4eCLqiu(L$F3tAaqA*Qr*%E_$QSc&^o!D5x*nQ~Wpi4} zP&F4{EmCw^_lN${#7hFvSEn@>=f&-&xpZ2}P(3JQAVsHH2KOw_yPOXDC~7Xw3%PV! z%3$9p@{!WBPqc9kDU?Bazq(hz!l=Abi! z%W1g_-kX%pp)141^HAosBg!h)fD+!8d5M{+6VKiR!YX1vwedt zdv}PjiwNW@O?HVI^kTELP2{LLILJ6f-cLjdB50@Y>XV*f^q)5}=(_a9XD7DWWJ|M4mpf4jjH18IC@UV=Rft2HarnvPA zkowtq#$C}DtebL$m8`B?>oQXj1I1@eKH1tT%4003x+Xj_}JjpeSc6J$R5-b zL|hm|uL<^{Gv`u1L5@5(F4%c(Kh0cW1ajesF^u|`lRf_JJ}`!3_VXLdLR-uK=YR9J z{lUgKk0M&TGAdX7%MqV{Icf}dkb(&2W|~C&^ZNpye;FTsDTF|-Wi#Wv>FIxT4|HH{ z?Yhe=eEvnsyx<@O5zNgri5UA_iqF4ehg*aY$kpD8^CodoBOaI#Ee*QDZ1L)a3U%A*eKtFuO)wCO_Y%=&!Nzk4B_ zzIfjmDTu%^Msp&?(%0`hBLcbD;=nICN8fj5+k|-E87YWR@7k($P+71X^|AxM+$vTU zJ;QPPu=R>8PhQA^CEj;N3L?~-tV$!SELe_u*&#JA`Esk^V(S%Ip1hC+%TX^oq*4IE z)+?=(6)!um1-U|p&)MF=FE+Ey z1A9}v@9gXMosohFwq%hF#EZV~?CbZP5rJH62h;WhIxnX`=vX;n0K z@ul+W%qw>4S4%O;9e$DazYsijDUP_uZ^FvBQS=h6!!Ob@0`uY(pV!4$1ieIS^NX~M zz`PK_t0u2(axS5lXl;IxHZ20VDDt?+udK>QQ}hz8#V^t_0x5{#wJKExz2Iu`ORi}V z$VIWrJ$}_yMw+6S_V*`b zk@sW}fm{^#-s4wf<%_qMODyuo{2=d4AO#T=Vcg?4b2*+At(@Pl@z;MZV}BwA5xhIr zy-E7^ufFr2m?&@7AOg84qPfTK%gWeP^h&JHuf=lBk%9<{t?%&*uQJjUy%HPnYq5+# z3L?TQ4!sf^@N2PY5y+*}(wY(f!KW7eyjj)6iyQiSGuLul5L#& zHFKmOg4ZgZXQUN5Alo4Qe6|lF0=d|l$ghG+i{ie`b8Y(h@8;|6AO#UTSMfX}?|%GJ zb*W81|J#W@LI~tyt0-A9U1=Frwp8(AI#Lk9R#<*PUB-=KTdjVT9Vv+5d7Wn_X+>t6 zGyTNt@`yk#wng&`+A?mGvW$xN&v7o{6_jk9Vm6=~7hdX34z`Nw_s@}n2)2syOXnfW zsCfSzDQp!bTc^vGQOqf785QrJBLxv`6(uXC8?uaw_sjub?&Rg_;h4_QXV`{#&2u5b^s9)sUs=5LTS zHLSg3eFEz)SaZN>)@iV&Lh1lm@5=8lGXg0Z&0IRIH7uzSnvkN?j9{H8YbT`))9mxgbbSJW6rJXLStrWvCS{<; zOLK8v$feU#hSK#3Jp)p7n)79yDC=dU4Ak6dF3tESu9(25LExqSKr&w+L(Xqzu%gYA((TxpZ2}Ky58jbei+!o@MQ%l!3N8&Bb{k zmriRLskS?$=rrfc<2bb*N^|G%*wtK|7jo&el!4lFr06uu;O|klw1^ueZUO4=gQas` z$feU#23i4-qSGvcb)unhMb->y;niH67jo&el)<`0)+utSkfPHpgSC&WU*xoi=@hWu zGA#nRShk*t41;Y^{Qfc{kn$je)TB~us(|&cX%QODTsV&j54V8*`xrsKryhIKu}2`xf=QH+)f z5y*ul49h?YBFI0{We>!tk786t2mxIGU2|+jT|)N4)h+UW_Xi@h?5Kxyv{aZEaw!dq z6)OWNh|oRDKHTB9LIiS=m$%E_vr$j)XsM7wUd1l^@v>(z=Jek(5TVmi&*G>I%nP~n z-($Zhq##0J}dG;aC8jpQm*`r3MdFCWfS&zM3rME13$_DH)%Lt?(f_!m2@>ntDyi1<4 zK^%F^rbQqZdCGcM$zxV}pN(oWGWeQ2W*I@Avfh32m}PHS@|5-1|CPOE$v4U)?-wP5 zJY|ChWpdhFRMz0b%~Heiq0v@mv-^33$u=aombPV=`yewH423aYkx zFXuG>5P8fp0x5_fPg#$BVWqchkK${5_LxnJKrZr>_1G^~dY?7Qd)U869c=C&Gcz}#3LUS?tyE3yQatDwWp()Ju=qW$KJAnW9 zQXzuVatDxB2Gu-TD$S*3$Q{6g5KPgf;(R&HrIkB?{|lkHC~lZX(ZwRs=wi{aixkY4 z)7)-y2ar|<_W|#tDN366$MH8da`d(T8=><;1jRq|D6U#08doh^D$EPHu(Yw?p#GvL zKA^XC#Moqx9LPE8Z!;F5DTrWs6pt{O;}QNh0=Za*Zjo4orXYeM*m-eP-uaqi-u*WM zxv<>~W9#8&KKtu4R?X)k(ydPO%0Pbl-t*+IFLz7ir|+}BJ|mEV2sKl?a<{bj;XQs2 z^4Cv`K(0c=%6L=AUtjK)$WK2wOaA(dAU}PN{ik`iM1J}nd*AbJNzKPf#oWo=fA1^p)gym>-YsEHbZ7UkGQni>*H0@05#*=u zv0uI1Eu9$=AF#iES_E=oE6^L#Rg8fB^%;Q_M3A4p$Da6dx70qvQNK9(>!(E^SGaY_ zPe15I{`!m{KYfqAp*gk)`RRM?iO;(wwfj)5OMd!6S@PFs1ags|zQ^A8?5iI}ke_}q zjr{c)ffPiLpT5U_^>VjFe)<9X>!(E^SGYgOPd{LPeMTS!5#*=uu_wOVEs>vo@D%y$ zr$rzajyJlul%sRN{`!ni=K;|sI?cN!wX0QaMSl7L`|C3TDTp9HeUClyqSaID_+}+)Mk;Ua^?x2fP+}(C@D-O$- z%+0;~4=vxmJkR^QcYDrnPLhe7oMe&){CoW$3Dn}>>6_xKe3!SxztgwM@$dBoffD|m zzA3)G7v2)u)-?W|zO{~jum7VBB=~pwrueSj=uO*B;2W0 zVoQn*@hsHhaV1kkk(AhyO`rq`tUc=cKmxURT*(wsBqg?F+dv5t>ighvB`V@eqQ8=7 zub5&4aQ_zm4v#A_5k>Nx#Ab;2k|0omgggmF?xx}=u^A%1^do^M7GYMSMxvkms$~5*~^25InBLL=?&8EqOi6 zZ;JSmAW*{3RbwJrBu`=k8!P_lMMQk*M;l1+xDpd_AkRr`M8ubVBv1=W!9I!25b-5J zpacmXS7IV^v&xsYCX&kl=A8CgMPzlh~XhzVsu3TKHz| zlh~Xhz9a~gAi?8GOhk@c-cpX~^PD2S^do^v${f&`B%F%da(c}owT_OROW_|lIAYVo)d6Hz3Wx5VR0Rz)6P5(G*|#Ab>3(vJjc;hVKjVzWeiNf0POg2$DZ zh#a}RB_3C@M11K-0=2M)+9$Em1AK-j2odKKb2RY|+`mPC#m`%_XLzpuiqGt*nBfTm zB}jD|plCe1<28YMDpt!s8bG6`$GZ>-h{% z^j9KM`)`Y?H!eMW#AkSdKnW7T{|wc|JkHf$O)FV|I`|Av5Gdj2s_FbBHoL#VCu!QS z9{i(tKEwOb1`>Q`r;C}G=Oi}DPhyKjpca;beG(fLGdy7fB}nj@oi65XuKp@Zkq)#a zpW*#Tpq5&?$8U@w%lQmX5Yx%f5m5Zx|q9({z|Me{5u-dY@Xbhz-M@ZK&@X| zOw`4EP4rhPv3_ZG<1aqL69h_-;4?d2%*0&%Ri%i)%++7b_nS6%#BY|32Lv0_93J+Egd}b%k^JQ}9fHpcb?>GxSiVn-v$zVW~YmJgJ*W~!J(dS-VX8%UrQpV^7C&rQ$l&O^AhmizCqTNFx=aHrNYyNhK* zJPWnNdE{bN=9%4j2$Ud!wMTs)NT8NDU0lrLJhMBG4U{0EzK^hU{m8lUNu2FMB5B>m zJ@ov(Da{sj(~}!rN9tuZC%1n``S;bQB~DgjhSq%JvGmUF3jZm{bbYr z&70u>al52niC~}1Hc`9C+A_&YxPE6_xuDF6fjqT#s^*X}?Cp@W z&bpi^_iTlu-454t>pUIos5v~qrb}cFcl0~&CyD9nQ<=>_rgFyT#G&ay?C>sEKFE!f zY)1SHHgW%BA~tGHGD!sFZ)u*pk<_`lU?k1kwFjFO=qjsP+1s%5$5PqEopQCAdBIx} zHy+L~yH-iytj~$#X&13UDH7XSYeMF*sMkLB?>>J`V7IG%XRdqJG#@?783PjRG z)hza=_9rIZ$A^V`**`qWC4OJtw1LHI@kA1(3SThKuDoK-;>4%Yx7Z|l%ho!){Tlm_ z{hs~1Y3t)`aQU;6i12-B_IK}%)kl9+Hk zp0nTRdFKB7k<>3Rv3aoQB3mmw4oY9nEk~EDGqOKkN3K31Vpe)_TLmZ|vV{ZU2;Sfv(^0V}2VFMNdTJ*9-so z)z-=%nMFU|_q+XDt?l)96x5x&BF!$Gc$DElXiVGqrm(T(?UvAh+pgbgZJ*VnF8lC) zuuTM>3wNZrp1>v!C-~@SnJ%9FTdj#1zieP5@Aovna2xdkyxHe6UbdE1zAW26_miC} zwI-fB_l(^d($?(6bKc|PudMODceYlC@k7~|$xrOxYE8VI-rxL~w6?j46KQ-WuW9C8OJRG3TZ| z$?9;zci(GvZb=(kYoGC+4d$s7<)+q>>?8V{U;2(`H+asQ9sAC<-pOEV&G@33U+N~a zf2*}*N2w??Wu~O894GD_U~-v{mi$;7C2nBq{-n1=9I#| z=IbBwfoVVS_gOaj;40f5-+yD3GySz(X4;`qw9M;0tY(FMwxsC6KiS;0TkYR!i#nHn zy5s2Dq2|NLD0=PtmgFCCLm$_2j{SRs*DJlw{*^LS zSG(0FlLn%IXiq>WtHMw3^i>X}nAs03=sb}ntS+gFz4oR`}?&TXIs z3E4|X8~(d{k@`dX+NFyGYGJAKZ@Z!jkg+dA%?$jVqXY@rD@hyPiF1>lrOKJnJXH$e z>bq<$d^ddc?YEBP3%SXD<;2w8FZAFFJ#DQSkG;r}>Lcvj4(j$v?|jgZHgYUlOo}y6 zV4hDOMNxvpg`qx#d^KcQb^g|qeEH*d7Qk&Ffm-c<|El{AEF^9Ga;^^<-E$$k&RY~p zkQmoK9(h&!Z@YDA+RmeqB#lS&Vxc_SivI2^ZeJeNI&OjY!*8l+;c3?wmcgD62l zws~pe8t;9k3`$L)_pzUaTCyjSL^pme|FBM#$w8hE**a~BY{51y`$tJ^{Zx%qYdfBd z;QbX!kdVEryL4UsE)iob5~wBnU1?+g)P!W$fhJ@MCs2Zf^l&7xxcw=8K*=to1Sh1w zV@ssJLqsi+9*!igW_znIKD(4`pgWqc=*CT325r0ldpURdAyP1;)0f0S>~D_#n-UFbscp4SqTAR#?VS=-N@i*N4f(Ujcd zHl#OcKTCR<_HUKQa^W*OJfU5&kX`sD-K3v_Aan&UTHe z5I^3R{JL{JTbBKl{VeI@+G&@*owPCPNNY1-)^NMOLJ1Ob<|T8U`D8J3P3_|Lj0FkQ zl0KufaqDt*vtvLeyT6h?r!A4*r2Sm!YfIwNp-J4!FGqUw-UlT}NKaO#O8V^t{C4|U zs3m=PX=6p%mS((cU-d{{x+pQwYj_b*Dt1?krUFpwy+R2R($kmu2y)F0beJ31&q6IZPmngw-xz3Co6}dH&RY~pkdSi*IXYLZI@B~y zT?!TLT+SeDiJU>$BXT^J&=k>JSAR9O(FU`2=J}ywR6_|8^CzdY375~%==o5y!2UOT zg$*Q73uiBU#Wmdq^T4S~4q*c&NT_q1E@58ITGuNv_9Bv^1c}|xGMRVul@1Ye;8!S& zO6%;qdMRtk=jTYE7JZn>%)fVyB%Ww#oLin=XY+aV10^`S$0uo8u6JL}wNsw3j4xFi zNT{>B)tT0rBg&3o2Y3&M&q6Jn^@%$`2b$IA^kw3mqXY?@O=?J*5 z*lM=s`9KL0YOHVgz(})J>&|vQkU%YrSn&1pcgxtbRFohg$4BPs;Vzv$YJMJl z&rA~%Niph(@k^vNZ9tI~X2!wC%ym2;C_zGvEiEt8+zih~$cZ8h2qpXu$K$n$}bW{g=Qt!dB0Yn#>l zo}2k!^O^|pXe88lqV)Pq;q@VbS{P^KeF^t0C!XtW3eOTHNLUcRJz-T1D*?M$Z7WqD{GoWxJ#dQ^2p+TD83-C_{N7_MN&htDU zC_zG9$2mLx!`^DsH`x6Z5~zjoQr-q#b2U@U)lh=L1)i zaBT`{ejjA3E_$mKnls)T?w7#26B24nU(7l4o&Vhwb50~sOHGxW*V^v`B}m{J0-v$` z{Z@aU#oyVE=L6T$a8(Xzo{v#q^)Knam<4z~P=bWInsL={zTWQK8uJ6s2NI}-s~r5! zd)JKK6f=61Ac3nV{O+0(RY>9^$(_S_K5!Kg*CUbUdy0Bda&h!4vmVa}N{~?3ajv;y z8K#J3Ac0!AzN2X(Uedp07gNMbP=W-m8)@2t!DGpd=ZT#2c|LIcbl3NV`fqRfnjrV1 zk=C@Q6(Y$a>#jL~=L023U>si4N*v8jj=!007Utsz5~zhMTbj1d6)7^O@O+>I2{oo4 zHheJ&exNxQ^8N}_GONlu-FG%$2j=-eTGMvFTTl9Q`($q9IY$W+6@x7OVM^C(rlw7* zy?{(e6m8DtIY$DuFh*w>2R%gkc$5+kyMItF`W%_@_Xz3bv&K#p5~zjiBAT|V!87u?1~a$tRG|ck#wkAOG=pm$m-lc_-jOxA|1fj$ z_kofWo4v?h->r5^@JakWma*3fNie}q6-to6H3aU%C7VeSJSbpR<24Zp)WQ`ZO-sQe z!ciliG7%9*2@<%O7KaVHoEUe@+en&J5?w_0@p$`Ep_A7BzW^5ED!JD zkU%YURVFQ8%~+GNHiOj+hwx;Oz||T}E8a1sQ9EIjr{iB^jQYT*hEzoTek8pFTA@9a8H6-tmu zwICBoeRqYl5jrES5#ig6E#;{~0<{*u2_Tg+=9WYYzjQ|Kn4^xZoIr{At!Zb1M4yOH z;-_jf^)f^h=*t_`MjV7($JsuA1G!S8cNr1I!Dq?eww7F{lF_Iz*P53djY0_$xNgM1 zeSPF_w48rd-^cSI%O_N%U6!C z8A=yQKM$# zrHdAY1Zv?bpr+Myt&HkoWfUby;0m3l#XpzWXtaDNImPoK`wu(qvL~`rB6|$`@0wO- z#tZVos7n6k`9KL0XwTF85a@mEXQ7sC&C*72Ha}z4iW1}~PZdg#z;g5SyF~Q6m=D?S z#>x{vsj%{GGVs7~a*gK$(~g83SLFMUBMuQG4ic!Pt|+#1?M@)DJHd|pBB8GKm2dKh z9KU^#9O3zp6)%Q=;u z5;+UA|L&Qq5iwUo2@+_Jmz8TzssVda?PsBuoL@;Ba^_{g%qtdw<>uMNYKUE|a?WWJ zawcs5#uRE=Za#PZoc;?Db7zzwA!o?)eaN{p5p!oGP)l9guFLlhvR#q(3NK2Kz%_4A zEW?0UhMjg9bFfn)qZIbvJ+TZ!#4=EV1lr>fVb}g$1NQIQ&q6I3e~>n0WWs>RL@WZ! zP1EF#UqkHpl`$EckdY$$H>S`NTQWp!2_;C#2$FmsJ(~1&9O}8jUav(0wbV6w86&gz z8lVITTuaxqy*$+5m;{gq$$_#XhZCdmN844kdajTH>S`NdnF?FiV`GbgjK!|8G9un z_KE~*;m!!|>GOTBqwe$lYTUm<2@*1fELV7CEZl%txSe(xv$jVA8RfSB?umsH5er8N z5@?U7ith_Qdn2g<`@-#Kp_YtaOB*t>Z9rr@7J=oaX>upIA$F3>n7&QOl?MAarqH!E zQK!UBBGx8Qf`nXwuuFm85)-4FC;Lsc+XoV;h5I!$?U8GZ#oil*5+rahg{H~1A_8kg z_LwTybnKMKRUkRm%C#aQ){0Pq1lrRyv4{RBdqZFkz5OiIlIuIthFJO8ob(HUm7iDy zmK#4?#I@_5h+X$`&C4d_N}T;0Q|MW{BVz3iB}m8>I{7|wtsi1G`P!Z=;o~_HsHN@} zDa_X(>op4`V&5xDkicCep0!j0YpHhH<(j9R61hrh|J}2eO2k?!N{~Q%{5%=g_XY&M zH?W_DT5|nU+Suz_86~hX8jHYk<16m2FBFLQLP4$x+k{-Hwtr&^HEoG&ZJUU-ZImD( zSFq*#kZapStZgHKTI#MBxxZbn!`}x=kigwAp1lSH_8Qn}mwN*2l*nBK_TN2w4T#ul zfD$Co9{(!Z^=$@$Z!_#?p_beqAZ^H<0|a&s#3HcV_$k(|uQ`bLnnUiHunD=7!~Tsa zKrTqRmE5uyMUO5W9@FDf~ zhM4~EUpZXgTK3Q1&DyndpB?q;+%m)*+xnR!*VQDXVdW5W@rNglZ0UVT{&FGaXWyri za6TDeT`eAA6DUDKoDb(d^H9@T78qm=$lcf`P=dss;vuHP`-$ULIdM1Oz6(RF-y#q4 zU;HElcou58|L*!4@O9xbsoWY-vSDf3#DD5+pExd@D}G zuU4XE{%9hra+@E5V6>4Fr^IIzG?sT3l8DZO4*s-uV zpj(Vx?sNJVHfvk1-`yh%n|-^)ILeh4w}98%`qA0(aLZT(YGH}+Q{?6+vgYk?9ILF5 z_$#EadHUrWN0Gt<*fx?EC}K`I@XpSM`?t8^ z2=m0hARiIpOpwoY?<-1>xN@nmxv}#*ht^fxCb;z15zhM&{cRg4Nxr7A8B_Y5W6D+U zA8gF;x5U|^VsD#JYydHGcwuwP$QZ{|`!>OVGMk)Fce_rAMFO?3+(eDlv?A4B+jrL- z4Xq^FL8$mvU*yC6``G)6X1%vhLS1*)yk2=HIHG3{C%Zg=q67)?o43Kx%HPF#`rW49 z46gikxAXAM?y(5BR^t~H%`3~EhPv*qd6Qs5j&}pjI&;qrrzpYair?2tKM$SUNZi}k z>srnnsp36!zI)#;7U9-vc&noM^x3me*WER3udUAU@v~+X4QftNg3lGdv;F!aG~Fm+ z<3+sOIX15Lx1zfI8jEmi4VYQcOgH{jsOz?y9n}u!D3c+Nb)aZjiV}RT_|1E`P}fa= z#VWVSF|%-SE9^?KScF@v8Mo1W!mCi%Z8sXpowH%|5bK3;n22Zbx*IBb%bE8pcz%n& zXMYhBx^Clgo)7QOYjRXAH^j=f>xE6YB}m+PQNdij_g$##wwpw&v*rwcKfns<-QB=v zp_ceNZ}Xu6U4@OcA#-x9+&jn`vZtnjT5Xb5G!OZ{3l;a{sKnecvvVZu-^ZHxZjNok z{VXK%g;X>fSBwdD-H#KXi6zY{no*VBhPv*@nPmEyKdlprC0J4E~EcO0(GXmxLYcvTgx1{J-ic&@0UpOd@n^&h%a zPoK{I?O5Dbw2x0w-<Unf4B~?i5EabAcyPmLd z?aU=-i)^P?{n@IMLZB9w2#;Uw%Vr%2ZoBGnXcZ+@pKEJ9p6DvWF?LOy`?QWVZDfVjH~dpllpwLO zsw;)AyEBKRYiBK3R(Eyl{(l=tpqBg{>LRACi?F_gcU+zK^ELw|NHjNGsrt?C8BU#y zur`HfUY)|&W}pO#qB2#ps)=?!yz4;g{JY$%M=a=|5U3@6AG=r5w2q4-tycBct#UT> zHBf>?k?gLVFL$osHsb#iWtHE!de!yD-$Ri=Ew_K=@)NseyR|Yf*Ic7^L?7Cbk6x?( ze&P^!fQlL}d_yrVeMwV^@1*_P;kpB~*45i9!%vhk+HW6BQG$fpKE%k`-1$4n&F5-A z61=V0t;nZnB{OH$M-JB=pn`BDnq%JqiV}RT9D`*WESO~7s`C6+xx+196F=VfWvmzD z5O;mbo?7uyWX|v8UVV?xo5L1)**zS3GRZf;b1=sW9iPNk$!ca>UGLWc^t#VL10^C= zZbJMP{+z3CZy7v$)i$d;&3SltEW)jou5?B7dhQs9>(Dwe1Vi9hwQZ*}@3lF|^xNZ&o^+B@L(*`xBWs`YRl;Cs4 zZ{8ovR-2$}yHzb#RH9{f2E`)WT9^1(n}7H#hwJW4uZ)LR_52V>uhPnP-+p%JOUJbx zOZAw870pZyUO2=}p{kAar0puN*fo0vJfo&a$H{8b4p|2dSJ3tFpZnJ7qOflLh zO>u=lEj3j~YTa5H_5PGGxn*aiw!b=C(M-AJxkKE3DpKXH`TP{1mA6(NPw>XbJh!!N z!!1DqQ^@CPqb971_xXb{@?%SdKrLb8UGf)>b%R7tec|frRmQZ`G%TdHO}HgL67Dh- zt)oXy*GcAlZ`@95doQ(XUU1iTyZ;b2+#Zffpv3)K`0ee#7B}Z{pXkeBFYbk-4U{Z> zSi)S$wTkGP;zg;1`?;d6A@Me{jJcN6>+8kvoTCjSP;2(3GUjSdSWDjgK%iv)eqzq$ zT7Ad^`wjkg&XKrtnwWDq-Sq7JA8cT%Pzy_)`*3R$I_pPA+VhXE`%9S(N`&iW^4#;> zX(9ZC)FaB6SHe2!;ytMZO5`c#x*+ylFw9x;JJ`Q}PN0@g3u;z#wAbe^5q`_>m1`XgaTu$tJNl z2zk?=Es>{j+rP!_eEdeXI0%#=Aff6L#b=Nij_}9u%iUexO+Y;lj zff6L->Hq&hpq9M#F%AMHNXS$3|ARm+tkeJIThuF*AR$kJkHZEMsD(9O(~4!NZXLgz z$r9Gy*Un`w|Fl})zu>!lR--s|QM`jhcXFER&#cma{jBl61PPR2ZFm26^*%_TjUY!J zvvT>3`lAPL6nm--_p?Mwkmz?YkNI%)M!j-o(eI)SBv7mE;(X?%0$cU_Gavjwprqxt zeCF78TlGI@-2Wd_g+!k>`OV@hcgS(@XQ@IhY{6%*M~Rn-iwFZ(`TsR(9PrH$Xz(Y-~$d)y(GEjrZ-e%lne!AW(wDl57FywB~p9 z5k>Ct(nT9cpjMX0nan9K?&!CV3cmyilw`P@!5n_;hMs)w8y%md5-34pbJld`_NJHh zRux6vMH@(<7M7vf2A@~SY&N#^(xBXk*)*VM1L;|%2El*|6|H{u$Yhy1ftp_aI# zoVQPT+a~X&Deq70cHZ~mR<`w4KGKkT;k=h-yvMWO8t-`+?p9&G|?_?uDa0eg_Za10_i0$-IeWPLY?Kw!QG55vWzS z*G4w|R375;!jVA9nR9Dc*s5IQAos%2_Rmv=MChm0>~!s1#N~yf4SW`Ax&I#93m3OO zb8p5jcX=AS{hQB-825$b`}ntS7)r&x#N2ncCE^}r?v>lWFE<*+9-Rw~gFp!q;-+Tq z5&j2(T0c(}N{|qDK68&S4jV|I7M94r`4+wp);@7Vy8F3&Cc*f;Ar2cTK|`5I1MXoev~X%iW@4kDMq$LcIUD-v<(?h4tl za490ZaI~$K6-tocktoLFPI4SX8%UrQ_DZS^lpw()QH)2V44h?B_{g*K2tEfF94?^KES*q?n$5fLLpdv?w}sX_@7 z&v<<7^XcN`kUctMs*pe}5g+5xFgZFSff5lPJ8-8k*~dp`eA3TTg@lNYoorNCj?QQU zpM_fPzsDY(`8c7w#|hq2br^Bl2@T}8M+p+bcHF)X5~#(!DE+7Yl}Cbv$cNiIQ&WY{LM`sw>2BXnC9r(>NG*d5=iwqg z=AOm>oInW@B0k0=U_^v~^ z0!EY=Su6szung7yN<_8XaVilXbH|f-oJs#_G|EGumUzlfV`Lr)65{#dzhlo0@L8xO zQs<81d7?N}HEK#7QU@femaB3@`) zEi05DA=-(k{Yu0uR;o}-v@+4!TsaqguIPcp`w-EtJ{Py@O}S4kMi|jki1#e|5z+2l zHjqFG62co3y@son{ER>?(U1HaZ$|=C^$U-7J!`yG7ZESCXUFtC`9KL0BHEQZ^Cta_ z?Ng%-Bv4C4yXy7YDA%2lK#7QU@fenVi2Ky|q@Sk>2@&n$@hrLSj5hFDsOA29Y@b^A zH^R>m=266hTER#qeMiF$Is;2wus=kQ-u-{ zkK-{jdu7~ByK;^MN{|rIH6Amw*SUY5bJP+MH6AmQYuji8C1rRNZCJN({UP_&(e}@6 zAR(e_JZ5IEbN`$`Ei7sA-uzbcp2r@YTYoJ<#11pzQ}aD#MC?x!{*L>%YdlAS?_9OD zgoN)lvww?s{&NB)NL)^BkOkbH%cn*gNT61u!-R-EelDLH36wm0ScZtbe8Q*3C#g9{ z2@-X+l6Hx>d}_3T1ZrU!3LEZ!Ln+@2Ox(Nq1?~R5=2&Gi`BQuQI~}*S`2V34B}fdb zS%t5<_Q)Q))uIFm`6Rgy`Cls@8@2=q`TKt(Y%Q5T58)?vf7(3*-^EDyzDGxI?xo&6 zO+<-0gfA*=xOX&*H2q7U1PNJV945goqC>2Py9rN=@{|=ykl_1B3EyGraPKhvH&sZW7M8lF zXRzD(dmhzpTq2waFI@IGOw=XWGcZ@_%KpkGP=bW)!EIW#fdp#FzMXk?e~O+uR;ol) zo5!k|@WRoaY6B%meBe>-7Y94Dv+muW9veuYR%ss94*uGid3Jw#2$byOQSEaVyE5U0 zFL`N z>5<#Nr4Jtmff6L7M;-?uJu+J&eK`BK^dI9OP=bW?GXH}>E$P+9L7)VQpO+O9s3pDg zIBcK<34AyIzCY2EVku(j3W9rCzuQm=F zC_zGcvj0J#mh{f!AW(vY^vM5%KrO7(YU!c`2|2Tf!v+$lg*D$31F*+h5!L3qKbhS9 zDIzTPb465}@BU<--Jc?sVG}69+V1}C>V0I?AeIdg)#kBkCU<{&?5U}8KTFgGBt%r3 z$E}%X_opXSNT8O8YV#O2yY1fn=^;=eqT1uyZDn%z=l_r@BxKA_~|7qs%Pf9k$OGPdpKFxmH?Mph9PfZ>lI?axb z6kqp0_#*|qGVp}6;+4|$*uIpc`jk^Fsy1XIP4GVPnLkG_+l_JXXRzDuG&93j92oEf-9GuSl!w=?CPm)v3s+ zM$xR&Egy32U@CHLc{FSCBr%y?JvCV{Hkuu6@560$D?QYCH(h`0@;~zw2@tyxduZAzIOK7(aQQed;=*HmYS@)6V0mJ=HLDIOikivIm6O+^Cqb^f8sy#49m&S z7Uti+_T1n+*ruCxuTCxl3Dl~&F*UjNKAKhEAkH;dmLR)x&hhS6t{JNglpt|!i$Cem z;tZSGP7oIsw`Aoax>%oH9aRX_T3Xegng14tnyquB@t{Bap)D-7_ zwAr78I$JleR^6CFP=Z93u#}|x`DnJsJ}KnY-8)8L?e^BHj1v_Cwa$d6Bs=!;cg{;) z(|o4w(W_1#Z23;s4XmS`uBRf4X*4^L?#K5LldrgOXk~xvm!qW(EJY+RwVHNz>=+|5 zM<1(diBt-KT38qOH@v@{G^!O1x7MsVuhbGG)O@tRyvIo2w!2j(k&i;47S;B}i z(Iy~^Rq$SRy7;<3DSi7i`xN0r8l6u=1`RvI>c8?PrFy0%4?9M)bDu?v8aX-{4V#$I zde=XgklPB2}0<{{?Pfhm4oMOFhh=byj|aF@p}@wByk$jKjbW%yUv@8J&}fl zPdUTRzVs&8=6OC=wKoQ5uVU4&l9r+b2`p)T=gap%W5eG1R`7>J3V~W`Uvl1inlU)0 zqV;)ZDvA;$)b}yH!$hOmgWA@)wVFbpmO83+Tz=FzREbzc^CzV!K>|x%(|jvEFbI_yE|FYbv7C(K>|kxeyaSr~*CmSe10(&A&t2Xb9p&x5# zy?(JxAy5lz4?o3Y{Uqb$hR)X5c{2=@Cb`XO?z8Yt}Idr)I!fd(*l#Xc3zm+&#IL#tKtD5@q;IG z#&Qn$t*f=Q{c?iOLM`-HG;Lg!jP(4nG*;O(zVu1OjAWJ9Wj4Uli0|tRBxTb}>_c-e zlC)_CQgPH}7T!X9g`FyM5?a}r*c!4pC$0Y^Es1D!hP_Rr_UG73Xj)LocSfgMxvjoc z{3$*QZK%ZbJ$|&SS8^*QKe+`ZNE~jHjx4WomNhLRzDl`$$d{h@?ql^U6s!=ag{kEy z_Fm`SYqc!aiKF+8%%uXzm*O|s*=8|%g+Bwx;7`|C<61F#p52+qwYyi@#~YvcHzu9( z`_pe3iFN1tABNU43win5U3N9$L)|!^g|zm$!*-5-sN<9PX+3N6(VHNq3XgYWSMl*yEL(_N|)D>OSkTLZB9=P}2@hFGhEU=CzKr8*J2UosF28@3WY1 z7xbyavXU`v?y`EB@93CXeqLLeB6LmJ+*XfaGnITGvEpGCa-zT;HX%lQT~n`QVY;JZ zE-QJ}g$jXMm?us9rEDfEvO;yMcaj1`?1kYwUzmv9i=8xluM88B|I>>C$f@ghS)1Cz z2AiJA3Qknr+8RF}K?xFa-+`Q~y}I|!>Ak(VwIFnaLZDXFkC{ogi4Pc=DZX*f*f)!n zBDkux*Ka;ayfYn1k^Bk^a%e>CE#muQm{p5^F*p5d^`|Z40l$U)6<$b zxRH_%B)$*NNM5hL$xb(W%WX8QrdjEdHM5rNKdF=zYGLisw28d~tOLoaS+AS*QR)>E zVpkR4E5*br5bvpvXR|{8s$?xZzQesM$R54$ohzfA_A<=dx?Qur6&{sS899-_+QUzq z9&y!q`A`e%{nRLhKrI~S`TQejrZaECPF9{RiRXNd&*jGDG{>}R9fnMPLCc=e4_d$JP0Ummb@ zpD*Zd_GKkm%06J__;0l@IsV5tBlDex*6!N%m7W2K&-=5Iat5#Mg4U*=%0xe`s$dlx z*hC>v3;QuXI$N8K7Q;(hmp`Ug`gTk^jw?I{P^pIzI=hyY-SAOH93-$5G_62bGNZ_+ zw$}Q0Hw}CiYGFO*=MG->bg2wertE@Zu~(Cfm&FPHO=Y~ z-)ia8*gE&v+dv5tYJat9Vt`fYQ<&vltS>;droV;`ew z|Fqv~Y%1T$s+F^+(la2T){;9DDjId4Mp)Z}W+?<}VHxtV_QWcq|MXT?l|DO^vO+=~ zYu6W^ZBU;k7O8VfAy5n7tftjj=uPXND`M5J^Im!9NT?pbrD2)r zzHC7s{r=YI`ss@zK_bbJVB#BZDZA85_*eH5w5OlDL>mv&l{4^Js8yd6BjYb+6M75c zCTmDfHT0oRN0uPB(&Z)b25(}ic#n+nU5pO%oJTaG3s)tk4W>@eClxM0=B(Js+6=$o z-Y;m6`WU(8vDZ}%X|5J7%ApA1Z{0YzaD#HG^sL|paco^eY`8)h?c&R znC`px)!t?8jz^=GnyTXG+S1OUe;c`*R3s=t0^dLPeKNMA{e@d_OdBUS}hD#{6XYgzcLU~EoS({n@Ja6?WN%E7KyLPY)i-gaxyJ{c$ zdDANMXr~zlN|3mlF)u0R_=CNhE=K42RXfr<{`;LJj{IswXDC1(`0lkmOK0T*q~yol ztljMk`lHkN$W6yimiVNw(V$#+dM@cSXHu=3ff6LpHlNX_XiE!k+2gF%b-F^J)?zas znKgyCl_d|kjXZ~I)1~j{J3~W18Pg}^BJ+aRv&?^LgzC9S?<-#jp?<)56pz6<5PSVYK`GUn-t60T$}iPQ$Kp4)Gy9S z1&SM3KA}|#5b|y}^W&w9rJ!lIh7X{Rx8-%#d>f*?K_uohEI@8g-OXN|7h|p8^Fj1f zim_&zEL0&-3u_NQXL|y_p=m_4UOJ1fQm>HM@@oO|%ZXhq?+#(3(aYZ`$+DAJ8ThGn zP!myWEhlOm-^JqDL}UN5ba~D(&R_CmqF5$P1A<8@zZLASCf+1yQ!r^iawXGs(U;6i zR-1n5Q^i?7ov%Wm7M41{Wy}bp!F6Xivn5HYybmO@?#)SZIM=ZY#p7`s2b2Cnm*ko6 z^d6W%Ay5nJ7_W(U8q?X?es>1fjyAM~c}Sm(TiE7N@ATJ~@{rbBwy>6`-|A|M+Vj0B zeSL4O^Fi{X21=0F9h#SP+qRX_+u}5HCH`^M7Bj5U8crl3&lXreD3bI?wH2 zuDo+3uCsh(>7<=(j2^Sr8i^+dlk# z()+uc8xe=26auxdN9Cs*e~X|&l{1kMdA1lRK|-y&J2rQxoBIqi_miCpfm&F5G;NVz zD>`F)XJ>D}Yf3FaLhTci6>LmfCtu|(n&7fRC|Xdbc|5W5V47!CCS&`}=LFj`dNtVo z`HEs_KRV;~5M!C+Z-Npea7^Se{dfIn@v~KpJE@8(eFpO~~Fg7$1Y&q#MmR|wQnYssrzt!d@bFN{OIPb%IL5~?SY;!p#cX?hY`)!9)Y zPz(JzzM_~joPO)D+nDjBrc!s&zq%MdJ4sV{0ejI|tY$dx6A69d{Sbe=&x3#f4XrOh6j3Z4?@E#y@54QVm zBI4ddl#4VBAHX&@@g=vaL@;X-Uno|@B z65ku;Cf&32WqHHJs!WlriRiJKjjdxjrYZz#RbG*s?5fv?wXjz$-)65sN1q9{LQjk( zrIrPgB&~)rui?o^)s?}d`2L}6-nXP=M4KFB^zKMjY=tPRk$EC%3 z_0vi0x0s~FNFGEERG7#DLz0o*#{)^G0+X3{WHL^4JvxY*ZOb{+C!459kcciFL{{t_ z$L3BD#LZ59=-;AeRGUMWCmN#8;P9)6HgKk{3(HT5$8bJvX$Ib?k zy&p!i?W2W_Ps=*cYelX*>TJ2@RSf=wMNh*rNw((MnujHD|jk@S8+~e1i?Q?Gg85A^LksxvYL?9Vgc`7Tn zSd{LqZjp5Gi3@CTwd4jq3$?IB_zs9nQM5w(8s@@VW0lfHVhDd9dH4w!e=QR>PR$)c z8;)IRc1to&Ay5n7tfrlOHi(vfN{kPV$x6;Kg%>*ok+tpSuv*PTO$232 z7IvG@ro9zyFv+?u^z{gb@q1QZ10_gczoKd90$b9Z^FJCn?u;Wypcc*z`HK7Wy0pcy z`{vZJWE6eezGe`KxwDW>%bSFtZ>MQ>-&dkfmJ;VsqI!KujOZ6cy7phhPS~XzvMH2? zt{(2J&?Zpv`cMmfMp3UC(QZvPnY%tGqWE0>Z4lY%w~)mV(mP z`I|b82L2SEg*2v?-$avvN9aQbI(zyQq$oi`wQ+flLBqp-bzVFgq!6fuWysIJUR{KK zuNmolm@2RpxE&9Z!UZv@b0oR@FcmxC` zNT}oBqfR+!^ZKKm;e$%jSuxqk^WIUc&%Wejb($bjC-G?ZpmYk-tX2?dK5;Z_`nRxA zod(l<&&D_hmnlV2g2W`>AhM{=Xx68A3Qi2^8%%GE9Pdm#xuim%*3QgpbWVqP&J-~r6vyy=D{_)N*ZQzz&652vo)0>gn@(7_-09P~AjKRaaV;bVc`|(v z>k=SrEFV~qR;$0qIWam&Ay5m;kl%UlpO3a{y41PL%&(L#65VbElZY#WSw3E;dCc;8 zE;@D99H;l*!U};}E2;*QFS&-W8#4uQ_qspr_G^CY<@?9R)N%#LjV0aeIl!l3c}c6m z-PxVONk}37_x;Pd*)t2CstlQEg}gbfl;fWoC_!Rhi@c<6=^jkKCVJ7H$r8}~O{-Y_ z&g@hO)C%QmRrj}bw`VeZ5AF$X8ZUVRE74!c4fH1T?0LzA(LGtVUOtNVp=lKgrlDU? zSFnampJ&}C;-8yd|0|s}HvENw z5+tw`c=UXHL7Hdn3TLt2xoL$_dC80`U0MA0NeKFkDsixUL3;G#L1&{!St&}8!1|_X z`7Rcu+XKCAbX zvT1EN`!GR72cv71pk@3vIlW0{iV`FeZ!JJpO$)c9Uz(P3e=vQJc&f8r=@JxsOB}D% zo;p?GLNssp1k4mUL`2dZ5lk=he@?3V~Ya;b>afVZ~|5M!z|?=FFq`K1du72qfPYOlF|2RW@9*%bn{&=2A_la{+~WL?+6Iyh?*!M+{mve;{DTE9xi44*TdtTS(u7$`vk zXT{v#ZTrD!{-K`b>zJSrsD-_@rd^M`W#qG(T9I=n7$`xa`u+Um>ih0;jpfLf$3~(3 zd>3n*ISPSV>ZtZ)a%Y;S=XfJ$lQ~M{4&!Cm{xvPct2?bY^f!a1ny9pMByeWI?^g?r zpb?#R@KN#)g+MLzmNo72&OUVRoIT`>*AxRKNZ_1`-!YLpg8GjdYNk8BO(9TAtyhyf z_MvUMI?boMrWz;}in5FxtY25hdyC z>wh>K_-3NvvkQ`)LE&sosYC?(LF^y7hx}`6WB=TNR@Dg_!SDI-Yrq`drO9#DiQP^i z)}wA;X=UVEI?y^h>mMB@NZ|L8nwGaoD`WYZf!6iH-*lAV7moNOzO(=1LL;VmZ_Ddz zd4duof_y?r^_d-6a=x0WX@8_SW_-TZ*{T*bLLpGAWztac_mqzI`Y^BUBN`ZK{~l;v zPS}B5xL%l)8Pb)}P>taCgZT9!j}-Z2r(5f0vKCByYhWqjs1~nk5#m>{3(GZGoU`32 zxETFbE35rOB>79a)kt!bZyx&5c_aqfl~ zdwrPK_Q+<`XZ{ms{@bk-0=2NE@oxcoccNSOIGv5_S5(>{67ve^q~(w{_G&+mK)z~7 zy#_g)tqLDA=4>rVUTkZ}*u7W!!K)?s8bW)P?T*?@@H?tX)uWddSB}Hp>U=iCd z=xSdwXhaZYIV)IuQ+pXGL1NO_P~sidL9U;F*j$kIxmD6C8Rn}HsD=F)pV1GwYTQlQ z(c0C1D#39AQ;7WvukAiwv|hfZR(t)iGU6bCsnxV*X?^L)Y;`O;v6z9+LM^qwy7#ak z&DFcG)wxU;W&A(_`(VBYvUVu#lPZgK`Q!|RKrO62nl|WlJ=*-LN5+xgTUs%dh(e$i zjzoN~+O%25&8Xhi!<;9TQ4I;z%b0kznQ?B{K&xW2;tGLUIHK}B6T_d8f|DXCSuvk% zU00GU4fx;?JFxNW3_N**k2ukfN#6yL)VMR3pu~L=hWHW%pTxhyPM_0Qd1(+W`Q(Kn zL89Y;B4kIzd&jZA#9o6`Ge#K&miMGJ!fP4$EYxaptO(hg=Yzxbb22w8A*Gc>P=7!Y4sG3giD4QSsV1DH)ftBC_&=e zT!ZWl{NQlyp${nPZTvANlJ;+(Um;KnPgvor`ep?E9DIL*~Q8pY^= zllZ2d)(P1BijQ>v9h8hq=4F5Dz;_jQ>P?3QU1G@+EjCbsgx_-hf;l~Xq43C_Z0=15 z^t{aS)mW$ysO8vBNrpBF*v>?P*qG>7dMRfvcC0`ex+isUGPP6!7FaqF$+M;;DP17} z%keZG@mW!d%y_TKuTm1+tw;MLs>OEZN={LNMD{tQ$jr(K*k29Be(KVJP3WIThO>b$ z6DkC1jVc;SUerp!WZJErsUsr|OmD#Ua^z6=1omi&C8BA+jTk_)bht~3 z^1aR|L8AA%awM(4m)srQFJU`+<>8+ObM#aQ)VlBsC4I(!ak#z(@a4N+4)`81dY7$e zpah9F+{U=%UatMyTGZF}bXfo6#-3dj6auyWT3e1J{9ChkfAdIDyBf6dUx}#Lzl%1i zRny7EpnEu)Hs3G?6q6CR98+7s@zL)*g4d10#y)(V^<{7EH?65+h z7S>RHe{H)C^g)s}jJ&_4)LkT&7Su_vx(V2hMeq3=+}5T7O&B)Wk&v$d72Z*lJSvjF z{{9r}Sim}d!p0-b{zjFj>UCA>JeR=OlRgtg2@+V}__uwv%F%VH#~Wg|IufWgVr@~< zkZJa}otpN0c|zwcIb(?3>L@{CNtIG$YHwcB_O}4r#s<^QVdZGnm;^>pxpHLe)GrS4 z)y7q$9BDKBi$i?#fo-0DJ#aP=eSWeb?Q#1KL9NtN%aR;bKRCpfC@N8}&k4ilMmW95 zzhglO5`9ONC4t31IK)>leD#%$F&PNF|CIlr&^d450 zyeaU(;rfE-(zwKi->OKu;DD)|E`?fnA{3t+lznX^KKTnZ&hIhOo-IO#hJJ8}uP{sb z6(#iwesaw1;!V`j-8d#0t(T$%UDfE8ff6K^H!Mn~w)x@^U+QYwj1;-)t^~f+{?Y>8 z6l&p{)wJYfnGw;oGkwRu7{QSRQ-~uG|8}YMZDSALA)TA=9zY2am|DIbHO`MV{alVt z<6kHsfm+xe`E0vD8M?Q0V!D=p1%VPIuvTi?p~|&rRF30@!FSywfm+xeHLYC37Bovl z42fUsy@3)W)PA>A&vtaolr=2#)kg|}T53BVpM=jpo_bU9O#}91*jBI~<130Qf@q!K za&*nP+)59J1hxV`ue}mLOLi(p`}6Ok@L8yZCBjd1nEJ`Me5Vl=-$$VY2^`z`?$3;` zjs6K5Q}M+J5~zi5mhYiY)Z6fH)Q`RoNvyncBvij7SEUzZ&8SGaH^BnMTS6`L&iMD7 zHFMFqDT>q1@yGN1WJO5U)SnzL{z^>Rye&+|<^ABe_IqN|G)rM}dRmMlke_j&X#;9T z(T^V<>-*1*CyjzbNZY!9IVwf^5`OcyI2q6JaJDZQktBp{y7|x{&TY`N5~~W(z=U43 z_`SqRpNK8$dgUVIQkO4|Nc;4QVLf`#lYu^bx7H>DpSAyOA@Zd8BZoMFqrD8lQ+G-I*wcyWp%Pu7|k|hkMZWycLNF3Qghy- zLM57Q&phMY^Ar>%Nc8GZgbe7fv9bIV22J~t!l2n&Z!_i;NTm>{rS@0HyAqmu>@Z{a zl&s48KmtcQ-Y2dsLwkQMNDs6~K_<=*Av4OpbPTMLgnaSh=W+(UbL`{$)T`aWsc52qYSWs(_z_Gm<|F^`!sN-tw~o&R#Ez{SUp1Qe zmu58V%UpsIB*Iu>Ql6g)xU-uex)d>uCVzCJUCs0gfm&C%jcb?RIwJB5qQRR*M#K5N z=r8To5|ki;^Bukm=}mTHd!OIvkV_#7fm%4H;_GTnj~KtUYeSRW7-3*79yZ>0gtVZWe_=Eqwocem?i6 z(Rf!Y`kB-*P=bW|23PzaS7#kx#qqWA#R-rAfnb3^LLdYS2^#Lq9Gu{V;_eB-NpKCW z!HT<6-1TN}vEl?N?pma{OW{4UH~jkS`yU_9dG2m@XJ=+-pZT6F^HlYYz3BVhVm1Y4 zVT&=0gsJ67`dmz?)+vN~$A-w1CH~&8305x#gveciPxmiR=_xyI50U=I9_`O`K=->_ zFIJ(z`5hDPc;zRIpaOeTb~Ju!N>5tmP1rv?jZJ}BmtTg+HXR@B?_%+4<@;g(sK)FUwv8X_{w+^=DosfUe_M<& zf{GnqL*(ilANL1F=)XL7>Z){q#t`vqRDPQRv#_7%JNUyvB7NS3@Il20BdC~_DO83o z|FM5-O5I=mHMTOfUpqqvga_Ibn1%g3zfJrjXw&ma&aK;u5=Kywa#^VKPoLcRsfF%E zQ^XVHSo~a`FB4=_V3vLSXxUs*kx4Q8qKXx4l^rB9JO@UcBYV$ki)n90LTZ2~jpJ^M< zQGvY#yG6dVq%DK?C}+l59N4QL@jC^ zZ&P3v&Z4-Lr0P#O@^w@t3wzn-SE#U$gU=QYq1cDn)Xn}AZL>Sf!r34nqd{59K0H2Q z>B&&a+CD_i3ya#nX{(pK(K$pu^O~_gv6|Qa>lq%uEl+96El#L$sF>|JN5zro5P4wQ zy8Rv4J8BpgYnA7{ug-*`-|Y&_!d{7Yr9752H1cqnb?b{zm48B{N6yNn^H27Y*PDmP zv}G5Ut{;|B-r#?q75{Fl&j03bMTZ*F$3DT%l})^C3d|bB6)I8>johCso%XOq?o%XQ z-f^~CRG2V=iZ5+L2sI&ke;8Rh7;NFQTXSR=Yu;;HzB31E2iL6C)4otJk< zC~9zIjkx`yuj)1gOByqig5m%}}(Wt`fC%%eSI z&l($fl~X&iL8sg4;R_oQ(r3(DRxTNOr7VgEY@ zwjV;TnudvUd5hStE-HTEE1jp*jPOZL{nS<;8AFTv78bYfFH#smg}s$@Pd0>INK4DD z4Jl<)U{+&3#=U!!N^jVvkCBf54*z2X6BhjUcUW(Y*bnOC{rA*PY+0M;`SeKmtzS-C ze}!`tyJAyZTe@4Vf5QE&@2q?N^S4levk%^*$oHeKZ~cT*d_VBFFv~tK*;{W2mA{j0 z-}aKl6#j+ym+LmYb#VLrS1k9=@U*eiWkIO3=EC{b{rDL{1s>ZlD*Zl$3Lgk}2KNlK zDKKjdA7k98&ifbgUMZ$u%o|A8d^bAFjcuOqy{x^oro#vtcsT z@vn}V9rQ8Em&m8OT^j5vvvJ2y_PkYTA!&x}&|j3UTnd#Nqu)D>ZhAej-`aV~2=C>( zH#J0I1QjLPhRGMbK05L}*NV)is!+38sa#JRC#dM^VX|M3ua1N~9sne;Q?Ire1JGqTzZx2jtQJG=6y9`kbr(mIo*cQxy8vLEAd=GSV)%wJsds;gc3L~hnU#o;xscE-p?0Qrx zuT9ZoXsGPl^_`<4b7b*s+24NpoZ7Z3$~CI}GFt={qxt=O>*#lmY1SG*iwSpB&g$)5 zjoTNr{T-NvSDnX?y&Ki@n>}5Jm#>o;L50_vQ28$Wy<_TCt6h1_P*L4tUGJ`~w<$0S z+Z)eIdbXtKTc6FBCA?KbUP;M*?1iHoucS2ZSV9hSJ$H=Hp5FGPu{UaXC0hOIaRTw3 zOq$UP&HGH6s|(Hh^o|UZg$5epR1bYWRt~B}FU{?uUb}*X5mXGn93~H4P9fTV)~zHU zTQ%C&X-Yz1Nq?IHvmWzv{v`IBqqViFwkNm(1vyK~bVmviMo>X1L*>~3L!`~5N9RTr zB`vHQB)9TzCsbh8p$jGC_7OiEaTdulPtGCKp!Q!02UBEJIELeOvyX$%a`vIO_llUq zhsXb%Q(GfFDhlwLWqAJAj#Ji}WsV-bXzM>|6B3xXh`)tdI0iEzcI!a;Jy&CM#NShY zuD4qAkG-W!$o*-aI&LxD7LUg}-1tlQAJMDKGesxcBB*Fmt%O|s@u?%9MY^5n-<{r% z-D?IdyI@mb7Pc6so`yzK@62b+oL|z~+7c?F+mw*w+x_DRVs0_76eTvL0{2q8W{sF( zQ(zYM+RPEoQj@;j&+Q7X?PF`BsJOYjge)BL%3)gjgsaUfM_KZRx~6T%$@WGVa?7me+rQscf5CGvB=zMW>lenzMYU`QU?%5 zP=PZw!|;4pkK#_(mbd=MYExj=m*OR)*N(T2)XWj*YBB$|Bmcm6qOa%w)-tR)9JUO* zqQ!`Iw6Jlzgv)zgDU6^3+ZeBMrfW`7xf_|2%Y3jYFbhW?p6OR>Pn(U!X4#k96-H2D zZ;9f06C&@&=Dme8Z3@h?_tYbQ)TQGQ8C}y(ge#1o!rn?cohVJ`J`{6RS|@A@%)(KE zSr#|*(wci!U6(>1N{pbwKFf$Ml8o{cZ|Ry7G2f=ZEF2m1+jb$U-#4}E#F})3GmE5E zd7-JmI3}`#u5)RsH|&_1P$e5-1QpmHGqYw-N$L~u-i&^q+NQuP91{&g#VOkCx5eBz z$D1&M3hcpoz2sX}s&?#%X>KrV3e3W`U>NK6*QQIK2Ai&s41^I>V1LZ3gX8Lx_vZ@c z``77g3e3Vb&Ah%c)#!8H7VK{DCyb!N-nVxsFQ{O*>2gqfQJVs@@M&i6`NPKayj}yL z$*Q+8Xx~jrqghJf=A@nsh@wV^Hwn#2MFnQz85+hBuK{$8zd>qFYLfp( zXijR$ffeN5sFXr;Qt@p0ZQ@}prRjZ3Xih3dP;p`r$+{g=3O6S;H#?o?{%Sjh})pCx@CcDOxW8Ox+rsizNhZD&p@Mo^LDfN;2LI~`3v zRvj4E&*G$_0<)6*6Arh_BHgKHvOFJSKXX!(zArnpOAqUvVI4HC?2!4WqD#>hCl!Ay z$;si+4iP*ye^+z+ODs+*Mo^LDHF3B(sUZ(j($JMnTmzVsiVDn1`V#MOd!z1M45X@M zD!BGCClw>8NOHqC+?>>PO%TsNz@=HI9lZpz=!q&qCv#*9~F=D92NyP{%u=X8$YhRv| z+m;V?EnrS+(pNp}Efw!MzJIdMazjgXY*;^wlZp{kVC&&^QMc>G1+EwCofEV0ZSsGv z7ngRuU<4IO?i7dH8+Ajaq)}rkTAWl=U>1(3|8wtHoK%dU0!LB9sC&ORE$km>YEEjB zzeH$GYLbIaXih3V|6EC+NgvvGcCfjdIjI;yMUrDrxH+lXJD9KY-2}}^MFnPIKjwCx zt<5sg1m~Ic=7r~uXQphS~+T{D=l+UQGr?Z=Of8eWN}il2f+J} zJqCZHuiJrk*FRxuPAW!Ffp^yJvuyfzYKxPK3e3VQ@;{%YseP6hK?RPFZpYS;0w+vx zY*~F2X5pPRjQWjRQ?Xv}5;P|jBdD;?0CsL|P7$s+QHwdLsK6|o6ET&mRC@|Jlb~ub z2lC0+a2Y$ZgV4OkX zzE}KN8TqSEC!y(k#SfQ}%R(cCn`i0&ps^D723lm*@%Q-)=%8*wlU1?qD^`#-jG?_7 zs~JxQ(kv#cVkBvwkI=*{{3YJ?`yyV=JQYKqPJOjSP|<@KTa7>U5IZfhYTqJT)xH{C zDI$4Ag};SaNxPDSo2+_oe=F5%-9U@1+W13h`LRi~&}3DtGmDjJd9S5MD>Y%~K(Q)Raq5`w*?P|)-2K2RHI?^OhJa<$- z=3QG2M|BjMnaUK811-qe_Nnq@PAW!Ffi0iE_MM5OeN#+Tidn3vz^tTQTh^@BF!KA= zqRBq{mFA?zEe(^+t9B8Zle%edn0%QxQfN+U&XCgb?DI~-%}Jfi-~aCh=O@icJyb7D zW+~iNXijR<{z0KRsrXA=KPpWT%3*ra&QafO$3R7DW+$XP*j4ngsHYq26sM2>q@p`z zQxN_ZW+m;L5pGUuy7w6=Ysm)mNBl9Fv?oev@@P@sMb)fkXQ7#**v6Qv)+#xb3gKPS zYqv?vO4{utG=JHyC^qt{ipda3n$nCBR3z=R5}Me|?dtO)Rjp(U1vBFp6_{mj?e%so zRs$U|w2&FU7(vBX-X~mOW~9*6W8PP^v7NfX&v_H(A)^Abl6Dyj_e_84{IXOv%NC`{ zs(2NX_EZZ^R^7I+xLlsMi*S=wy?n~j_3Fo-g*DLI(a>OqGFkPiV;-U zd$^bX{7S*yO{J-)sK6|oOYly;ZN;h3t+G^}dB`~8U{8c&30J6CqNEKS&hO#mB6cw0- zcb4B+KFv~rJ!9wyQ%^C13i~W0cvKU0;L1R%&eT&>U>44`n9x+|sH*AHnXZ_1ZEY9l zKJkSM%XLF~i&GZ$v_Y$)RH5QXwP8;vZOG{_WBsNH%^hpVEWJSkCXa&>-~Z8GKpbm&D*{W4U~tIEwyH0UrOhfowqFz>#fR*{u!ewq1Pc( znCTQoP|?}QFaIpNKz#45zhE6YF_`}CS=c<$cB)Lv%*@OSe-rQ9rI%ra17zzevqkSG z>16jWd{!Z|gs`ZmfgcCbfROrTe^FR1Tf3HarBdBQgF+jHKK40|ss=uo}S=N;TQXMga)=ai3Fbl5;*Eq~P zoD$nNmo=lu%kj+L%vpMx@M5xJ=TrXjJ{LZ`73V3xGy8LAzGE_&%MhGFfabuH6ZBGYzE@OVX+2eiLj8%(9==5vIzo z8-H14=`mdKR8N^>Yk+*UZLCPc#MWKS^GipW(ZYlOpJ$d6TGE#-pH=bC znG{A)adds4Y*TH7crZjOZg789dZHI){4mM(TbQN70_EvcBSqgLT2VE>FV(wQlO~;? zB4-2#$=I|5#J0BS<UQkXg9s{u z;|j<-a;VrfP2Z2eU&_*md?ECA0d@j{0<-W84P)W$ij<;GLE8Ocyu=79=57y^F*`?y zEid&kHh!&1eV7c>CUSyJfm!yyyz`BWwAx@Q>6&=kUyf(Ex@95hDf)_Qt@RV-)6Ro7 zWotxnM?4iqP+{+V3Kf5>mJRJd?Tb&AsKBf`#e?PR1~KC7CfzeM^}C?jPl}?#5%Cfu zsQBx0u#A|~N3^u)t!)<^Q?7SW^edC5FoFu~ANl+Fo=K|JroL2o2eXRdw=fIeKl$6; z{$TnvBpC%%_avNo2TUw1d-UodCNjMhXM_BAj3`DKU;d@)3j53w6-B2MmPgKa6K;Cz zxkq6%)?=fp%=A|LEzH7ssbR$TE<`2PdeHNCsR@5Ku5)1-9MVg?IPW3%LkeKc3CGCp2Jp<`^`Z$%TRybi+zp(}7 zf|7lO=DnV86eMM{7~$r4&u zLN*0v;r-`6u^)3%UrkhA1IyCP?EaFbOc9#Jy7327di#tOn#CH{BtUNLJXX}VSgd18 z22!J<<5j-!a)c37obe8jb3(=nH;eUJl>+o-`B=4Ka#@=KvzlMbFHd-k5N;N0bdAy! zlWUYJ*{2X~+RG#4xrO2iQ%K+R4v-ixVn z1!j$&?Jw_!%@$QH8vC5PAvDr=tQs(~7-0kzgMaat*~d5`n))G`wh>l z;kPi$WTtFfj#)y}Vh!Wd+s0HrB$>M6NMln}zw9r+Y?~zpF;f)(KAtUAZ%^jPGICS1 z7YZY&Snx7{No@;7A&ab9rC zn14)es`J8+MudM=7(oTT8}ex28>IE5m~w*tDRM$#1Qqzk z%B}rf3ToM_I427gyBT;9m1cip1QkgXb8CHuuWt7sdQf1L zN>Q#1;d>4CkNDiMXX0`gow_zbz1Gt`0_E`( z!-Sjt+19%Rt!}YdUAmgzrob#5wfXA)7ENO#CYqI6%=uYq!&+BQV%1tJI@otHAFgRM zjToxTy9akEjG&?y*REM_EVI^t3}gO+ORH^rqmvD)8V=b z-!qdao7NfPI~>0oWa>d`?O^kM+Q|wdsKB%3HT`!nv@LT=b9P_50<-LW;?`e!(e-r+ z&VMp)vGs|lz>$Ghyz=#={-ejphkLi%6qtoQID3kgx1vl_va6Iw-`RRQEhOgrnK@(Hju@OE0)4d#ntB=${FS$gG8YaJhdiDwzJ zI#8ctPfX1h#Rw{bxLV@ZWxIr%FFG)|JB@ymU~0Z7DljXlvS8BJjGQ~0P|A)T76CI= zmcp`gk4-|8E@zw$mJR!C6tzpe5qUBemWA?c5@!$Ux@6t9b*5o)2TaXq#C{Nap9V96 z&Tpw_*ep|M(P^F`KpsO>*TmvgZxydhJF^ zbM8=)UIxjk8P*F;Y{fZ>VPyGHl_Ez?QJVLP5mY$V1~o(12V2ni+#6Nw;3H~(gTnH{^KC-2CXbXaEEjCqCSFIs7WTj6$(0V&w&;GP znX>yT6qS2!?-rUVyNjzv{yTM-&`jBPX^P4_TXqUJQ?^fFjn^XzW`XY_$q1lVdFQaz|H&gcUvu0Ge&I6gRY6{z5jx$TV z>Rf?1pcM^|UnTo4{%*U2sKB`|)7WDp=}3cc$Ap8|YzoZ6*27=PHbzl8bu^(L6Jjxf z3j4gI`HpCskk-#UH`QrVU>445*vSz;fYQeWD@{GcYc-qeT4s2=M`-FPUN@$y9O*~R z`qfgJdWsQLB-OaIJOS)sxz>Z0znHEx^%NDDg>AtwnxBfKgj)xcrk-L16-hNtlfIu< z{@$EA{#dUno;|Lx_2oDfEE8vK6`Fc#Z;5Ran^Dm6m8u_8Pcedu!wH3CuKSzBZHs#P zwoF?}86TxI^%NDDWp5>``!t|ear2d?o?-+Q2jhd}y&LO=n|ivkb6xs)V}a7tQ&eCU zKEcc+FF%-;9?ot4$<))NT7A|x^Ko3obK#%6g{Gd`TYII)L#WTvJqdf6dWsQLB-I18 zzTGodZNg9*c_7iLsi&yGENng8Csyr6y*_Z&g-+8Xj$U|%INC8Crd&U|@O+r5sizo0 z1s>Zlro8A!$=QGr?5 z7T9LFF`Cl98m%<-6eFmx_g8O!X+wWTZd96jiVDoa-qkRQbImaCj7`jtG}UnzD%z zRFrt^Cy$l7BixkD3*MpBa!L>tWy&ThFl)ejKbfi?kBt^(bIj|k^ocT)rfm8|XP1i` zofDd}Sy|ESQb~9xYBdD14IHz11aY?u-o1^^m(BI9n z(*UMyq5`wd9rTs)AFc{FWpiA%bX0q9S~Auaq^1{qB}Na81jB(Hks?6i{jf6 z&Hk+RyPvDo_v%E)co&I&hE z*0<_M(=S_diz$l=%o(w`f_J3ErlvAER zc0;(9yb-_6$tefax*^s#e8+RRf5zu_-TSu&#V}JAvrygtk*}=s@Dl^7Qq)!oA<1QyX7bwW75wrYtHj>-tMynf}`y(c+x0V4wX!Nosc> zm^3F9TU_0C`D8+#`|k0zjh}ouxNl+`!dmlMde9zQc;0f*vBwMaDG9WT`n(aPAW!F@jW)T?9ueP zaC1`gxYASPR}bue`9*)Z)lLucB?!5p*RxeK&lyWHLV@_)N`+hRh z#Ro#~+9-a@O> zpZq|$cks+A>+4!Jv=+^0PAV!e%NdbJp4)go$vc?vu$P(cTxW}uI;K`unWy+Up}7VX zR%VrDL(U1!Nwr_yDODdPq(0k`Rx&3QBdA!C)<^a)!D@?>`cI9OG9rI7i<629%)&d% zKC)3)&C7>dTbxwvE%6Mocjc9$fZxo*siG*DcZ^^J6?kmkS$sLYIlom;i<629%);l9 z-_>e(s<6);Xr0~#0naunuvPN&5jtCuM{|8z&6eN zl5=MgR<7$$1DKPF3e3VQ!cIUn(yTtGx5Y`t2r6*A;&st(X_F@lOum9oepN6rX0!?bhI19hxQ8PW_>RAAO^KW{nI=ZtW3Qe7FJ zsIfPRG$$1!sA!nNTTb}%jF@k64VKq=&sy=tOx(?XpscdG4X57M+yjG$t|w9NA8%tYa)g$9>8rZ#?vCQS=P1!gsj z&Me!TiNZ|_jhj=-jJ+_}qJ`r5;@@#Oa~4_hMWS%iLLUXhnLobvqnb<$#Rw|;bj~81 zK1mdAT4;rqC(NFFR+<)y3d|bfokgDEW4LLdj;O!QQ5`y1v`~zo0%x+!#ToD8+BK}6 zMGHj*X5nnvF#ZhNZkC-Z&|TGqR_NZY;T5< zEzD2Ja)am!(?T(V3VY8Gc7KZecy*{n3q=KH;r(YHvhQi<&<2C4FVjLXf(pC}yvO8t zVKZCJfwYflp{T$ty#M@n_%1V}Rd@Qzv`~zo!hQ!U@BQ2CpR27!3q=KHVT)nUL}MRn z+2ppW%Cyjj!!t>r%85cV&)yx$B-b4}BQ!0v{EAF+;HE_3riD6c_)vV-WOSElp%_60 z_DbyX?wgMqw)Uojqtn+vitj z-b_)G&Q_(_OoGM;DsWuk-I=wvs9p&rDUM0dsK6|o&-3p7m3Ne%Uq0$tw191l=V*w&0@uS z!)pLLGf};PFO_DoVgwbVt9#2HVW)+g#p)WHmd5ycQA1|2q5`vUeB>RVAJS8!#IH)T zSTTZ%L8r3FRb@{LH;a|#d{OhtWhc#IMFnQzb>sW7DJ?Y_o}4s`6(gud>H8l)z+FRA3f9 zU0mh3_HlK!TwBs)Rg9nl`+RmfoykCp=hYxhRz(G7*`L~cO;gi`AB`!D$*LGZg?-MD z{%v+zQo9b_VzMeKFbn68Oe49GiVAH@P4_nzp+1e@3-4uL#13X-R)6uk{yk4rRcP)h0^P8KO=g6tN$)N z$HiY_UtgsFx|%GMb`RTXI|eFr532i1cQ5)&DPQWltr#6>|CddHS-M}>f0w&&j~o_8 zx9W${uT6_7&uOXUO^=6S7IPA_XZS3>(v5_w%}?DBJp? z%#UtwYrCkhx02W&C8&Fq02&jw)uzBK9PRikz?Nc^ql_<&==7Iu97F}SO2b&Ry%gmvN!_51l*miwZYrp5BxNoVb<*=MK1!m#%&&+{RUi94isXBco z)HYi}MfF!{w;_w%z8TfzGzk>wd`-P zif?>=r-m=cL4&*s5cU~*PO8se&r640xgiR#@Q|9OY#6OpdQzvy{v?j3vnenOkHv>c90fh)7sQ9t%mWbV+R!(I8GFJ>~^-X0tl8MGt54I^V%l>!FJ5Ds-@kI43 z^+BD?dPaEi+xvbd$6e-k{!Pif<&Zt;<&(o_L=>+B9JA_}Tp4&$J=l_ws$2=DT2oJp z<9}q9xtMc@e|eQ|r$tntw|rr7?!tZEsJzc})9dsBgb`HWH8hObA3P{9S8iJQXI7g6 zv+!&U<5-(q^sy9^ta7}v{T-;lexBzHErV&)6dy{p*RH@Uyb8Pymux6K-1=8Sw=)mq z7+#6^d$qT$ddovzTh1#uhrDI;r)lMa@rhz~ExuNr^z8L+_Wsm8e1v)V`#f6&6&p?_ zidVi_)Hoi)8MtHS{w8+=A7t3%TneygJ!N$7(qqn)@Q}F zty$$XYae9Ao?Yp$#ciCQUmde4FstZ>M6s0Dnr>S)c=9YAK<)pCQky5ukSn_ltM0l zOgP&li%o%9csIGa%9kp%V@h7ynlhupxd_f`23JWGlP_nMPpwKcX1m7J{y;ifbz`c; z2r7D9NECiGGRwWp=;XaJ^*hn4yLZ&8T$61I%-Z=!qBz?nv#e!tIV0i+lgISEf;VC+ zY@>^L#W9Lk9#3+0Ci}HIys|&ND^gn3ITo%kf(kraW~3B|rE}xQsfaS(HU(y3Ti|-a zCA(1MkW*^SnhUm8f(rZJk)uNo>U4RpDxccJrob$0G5i%Ew;%O*`a~7Km!HCKpAn0B zZS*s*i|Vh*`t4K`Y4z7+{T8W-w7iNlITej&2L1b{1qmY+>z@(*j{3;8@6$^BCGHuv zq@}6*)6$AlLAGO{;_oM?MYCWZ*=vbzSFKlHb0B(b3^Y@ zymc`JWevS#An_x2IsF%|E}t!8dc9m7(oSIY4)(} zYeYUj{8iw`)HVfX+53{g@2b#+G}G0W-@FMUsIcFUmJjOFjLwtQ`L%{kfm!xZ?Qm5| zk;{*%l0`ERMo@uQo#!RtWhi~s2de+ebT$QM*~h58le}o#5f7^I*`F|i3j6)I)#sHO z@*y*|np)JRz$_e54P$t(jr#)M zKCZ$~cUZoNpTC7!x_{K`$l9a9f`h0~ERA8Ua`)gao(D;kq2~)2uvMDeNX9m39KDi(Hd$lv` z70GLx0ieP@lNm6i8;v;YGPiYFF7dZ83+F5BHeBXI6RPJT%}HIA?6P=TC70Bk)XXg| ziS(~?O3g{FGUl?--#y)&)M{p0^3IcvhAl2gJ)5#S=xH|j*2mtTV=rMC!z$OJIu(2^ z%I4G;cZA;)UwQl3eKEb&U9luzZaFIKp3sgL{e{u(dI?Nji<~ojEy^ZFP@%t_>u>08 z_D-4|t?1Rgf6WDsQI>n==Wk(_{ywk2z`MWEXAF#>Tz&mq`K5;-E&E>eWkM`o6TDXTzr0&AFPgD86KO&$Mo_W5 z`Z;l=eRk<4#Gd@&LAMX5r+y)UHU(zkRp%X5HT|g2^#Y^`vD&AizddV0?BLJWMdd$p zOHGKqcK50X-s3CXgxG&`Ns20(l{6t%yMVNhMH6D%dE61|f}hlcSo|e+(7g+wG;52H zCd6U{6<4y~6zdx2k#0h4--vv)H(4RlgjiHy7M>x0uXPlrLo-T|Cd6u=l6D_yLhQKq zcg3{0yiyZl@obr^R-q6@_=J%r#9{;$CyU(?D<1kuHz9UsWDqqh8%mlGiwexbzlpz} z_v}Weo4QQjwwo<~$Iteo{UqA|p*9Ve2`6n zS=yhYodj;Os&)-%_keZ|;4!q5N`K|oZYn%m-dDt~0qq{p6;?5V3hk=XU-{3lvyQ!L zo-L_KP4>hcIAyz5n1wwCuX1|Uq{%V4U2j^(N{palZ9P`|R(kwDLqg z*Fq+%;^>9XIgXFKT3fdfy{wVOBCBEq71(1i1&Tc~+AH&c>j|R*vv8c}l_K`YXs?X+ z$zTK(+DWB7Ep9heVDrv2>6c<=io2(63e3XU2iG5DuaEZp=(@-lK?Tkk+2eJ#DeW5n zMQO6C_SI=uiYBXSSDyCWX|gIlH|!9)(}YfJ`B&{>vMNSUp?!ne=jSG?YNw%g9BQ{A zDliM5f8MplJ~i!E(_S^~Me*FRKjwSRJ~i!E(_S@*_7!PQ5h^eX+cEDl zWzUlKE=}Y5&KN-j-c7^M9vSVG(e;E;fmzs&dGD)7GjjDxVUblaf(rW>RrPZX+B7-0 zD-DxXQGr?Z=R-S?v=d2JYsMY`?>|2O?AWRlMc+GZQ<|)b5mexv<(xK{aaFtrsg!(dB6@M3xce&U$(P42BdFMCn!2Wjpsd;u=duq;PRg9p*em}ym zq;l%{^Bt%V(ZF z5X==lGfY>FEB2raOjgARD)88b5xRA+N}sU<)nxK8Dllsn?;~8y`w2CXnD;Jyn6HA5 z)F(|=ofo)H%$O7;HCZ(#-FiVHNNTd`*;kuH$wP&to2(k1tAb-G^TIS))g#UCqVU=v zsmZFZw=NTU@0}*A;x93iWA7??vQR79J?6XZ7^pbLg4#=>B!8QAT%ZWXUD1xwAqwm(s?@2ypPf3%vEq})YnIRQn9cS?Q|ggU+cSuYT*;RSy|dNLVqKO0Xu_SXQPhrEtoU1)h0h~@ zMIL&4CMrN_%ScGSYV;Aoj89dWmQLCH9V#Nq5@Yw8O+0)9rxS+SiVnqdJVUNny z(yI9;^!c|ZjbaunMo@w6jo%<++wYD+Q9V#Nq5?0sT8 zuT{#kcr(&0R#adXwrPH28RKhyt2UT++}RN$D% z`#;V_nA6_(vskRCz%0BXypMkCEOT&&-WH1$BdEZ!-7tDLn`eGl(UY<>ixm}^g?E;{ zYT+-;S3&LQFtb=Of(rXg#&R55xpzPtGKcCgemG>?uk!lOoz)YP(?OJl{CmO-+P z#XS4mBSH1!T5-LDX2|cu$B8<#0_3Juo^svOvEq9|fGobyQ~q|5sc*jr$Ux?28ph{L z1F7uf_9|8R39@3rUc%!Krfj@SEgx^{DKyj2nprYSe-bnG-Sfmj#bYVv?kv@7kX;c7 zSx1ia5vLM^Wz0MMWpqK^YIO5eKB_TjvOGR>usHLkfDEsZL58&+AgTuh$_|&008=5MNpyGfrLM)mUD2rQMwJE7GQDM9T-8f#N0<$LU{Y^ac z2#^oj>tj@WB+V$E`*_ZXml#1s!S-{+*ysS6&`jU+-@O}~Y0vkk4QD(RMo?jY20iC4 zGsi~sp+eawOH^Ris}u8t_rU-e(?x%S+%#>sS-*Y{YS%JeVgwcc44W^;e+ZBVKk4V= z!npnBjI~{9aQ5^HBdEY$f*nE&Kbdv>+tB?>6C^4y3*Yp37Jm4?%rNs;Dq6#naK`%j z&O*_TdxmLDB*l3bpVbnnCVi+%b)R3HemDuDUO(ezN!YrHt z8b+-Ko8*)pP3idO)P%pgInzR+-Ui4YOeF1CceZFg&tKNHh@?3t_m;bEw56-p-zbcr zqW0-o!no!yms&*97bkqwE?@W z2^gjNH!V#a+ZM7ZFbnS{&l#?tR%ho{qg}~9s~daAiZ0`Llwo!>_HeT^3>Ob#1KB68 zM;yOF*VX!D;neDMI>HDl?4#O*Mq^cOuBR6|s4P8?87^kM%P%#OPRWCp`vlymL{u!r6P#{$ibV~^iYe&>q?=)yX3Rvjqi-Ocol@4Oz^tW( zrifk4|8z4<3q{UTry5+V#OaT3QA1~wf`Nt*DY6*&ljT0U5XP%Q1Nue zAaSik0ogUTzE))#?^S087N=Z^0X79@;Wgwcd@Yu$T3L(G(1fD4tBZ=BR|bpjw*sZ+ zx*NvZRddw+=RuUXH`J!Utgk`C#EOVOsp;>$T3f#;HNT#f;@&?|Hh$DAlZI zHU(zk2*--%smy$5qv%4J6AB}!z&CHEIv!G{XG7jO`R6X10<-X~m

      {U~}uZh9Q? z)%KiUoYYNdKCWI>!}i8ZzzQDpW_>|QKFPz@u26CQKv$8DYZkdz)#mT`OFbD{j68q! zwJ9(Qp8~Go*6W5U@o!O@TQsNb`9Q^}Ke`IdM0c;lg}vLL)+`Al&6LI8!mLeeyNHLQ zi%B=Y?OnkkDBRIHlbMQFadUdv*4o5wU&?m!^W3aeQ!w3MOlBQuOxeCZQGMIZu_-XiKB|TH znP|R?kERbz=h)WaaPW{6oiSr4k0akA|>M+LrFaGkh*I}^4$deV}STWku< z!r3y{mR+?sq1EnK^8YtpVFVTUPR08Nhm4SYf_qZhKeyWym}PHQA)QRwA}W^h@MwS$ zRN&hr*TTNlT}^xzNiAuoO@UeX6c~mpWS07IxC>Q$KHWBZMFqY`v!D9(85MK83BCMn zr%i!bI9~Bzp8T@P?`%gI{%)Z#f(l%pVcJ5I@5;M)3o0@pvrU0n_Em$|?DJVOsw_2T z4&<(YE~3lq;!+bLv5&&Oiz{2t9Y}kBX{RD48S;HF1@{#4R02H?Oo+iL<`jBB*Fmri=J|pqz}bSggy}4CMN4ZPgWKv0~&( zjVPh(s_CzN_G7$j6+_EDEmWGtiV;-Q`Ylofa2+={i}lO3Xxid)Txk|7DlqHu)JUPL zz_}~SWqUl3mX2zyuB7TL%Ma@&{<L6x2xeEiZuHZ?;sv;K35gIw=Ya;awv0aZzrfjH9C;yay~8G zLG(*3FEy9509W?R`z>5*F6Zw{I|=9AaOvi99;kIt^>5UUG?x=2sHnfPgQ#;gT)MfO z^E(%y={+UgU@m9gs-3KAk@~w6s&~gmiY+6sVT9 zx-GV`94(_o%!|@e6L9%EPNf)1b9uhn&U`qGpaSnKyTTT=p&PxPDb1im1!mz@=Q<6m z0%%&EywrWgQ-ya8=Oy+#*erh;`u(Xl^<|PLMo@w8KD=J?s6M4z@kI@KH^-*HENpMQ z$K+alS~Bph3hKT>VFVTUwqzJ5Dz~6X2XCqCMdNL6ML1^QFR>4RE7v{mmY_687$c~_ z(T8XH2V>}So~i2Gns2t}1GDg1F^p6XV(3->Nh)`WbP6M=z%h~cVEGNAIw|X^NuCpJ z&mCsr3bbJ)JDHgd?WseWdWtPE^^}fc!&8UU)KhGg?7$wIj*9eaK$?1r5mY=K-%;p_ zqWViL*V>x@R81e+k~H-c6_|xj8qY=dn#w08iZt~UBdBOIti8~cL-luc{yPTkS2bTX zp|+vN)r;*N#hh(rrRMK0&C^L7x>`nR>M8aThH+_;OPS>wQeUQ?VgwbJUUw2*3YL~` z>ghi>pQD^5`)h5pxq^YN< zz$|-z^`S)_diBDGjxhD~W$j3zYkz8=Ov!qk#nG`2si~*-zQkFuG7TCPK>L__iV;+# zsnJ>J%75-J)v;Vj@Z;v*st*1r$`Gr?vac% z^%Nthz+*GNoof%a%$A-s^%NDDW$&+oVnXTO!{Vf=rx-y6woqo!dHYfO`VP|6Q&eCU zwguifdGEOz^tvHw>M2H0VIK|Jl{}!L%eEj*Jw*j(VVgFLkGt-wa#aOs1~#?^9M!P( z@Z0u1Uz!nAh{kNbZ)=ID!2XzbNKY<7(T4-*7_+?bw=fH@h+&N9N}Dz2rXbBp#Rw{} zuQZIKT-i~yeWczoClwW#g(DIBsfWkV!|Ah>CZ%Hp74})i`P~C)($$u#a?8>-1!m!h zY8YId+tgLMwL5{Ub31iqP3=zL>fBCUmsPtHxH`8}SK@U0eYiTeOIPWBVRqKlxt+R- zq;{S~k8c%;ojN#^ZOwF5;J~J#JK+b7_Vxw z^9&=X;C|lu-xtNq)w{Y@m)fd&u=5NRn8jm>^S}2fuFmb!Rl1*zE~Be+J9W)W?L2Gq zKH914Z)@k-yYyY1x-zEQc@~=?(p8kJ5NnqnKdH{2y$?V0&YyEbuC?vd6+YcAz1kH+?3&KCksGp04;7fjGjiw8IlN(fi4Ap4<4WMV3OLsZcj_vu+N;J@zn!`os`jdJ zWqGHr1MK#yaRqRft^}^DfMWy|_O{E_xlLWATYJ@bOm+SoQ@QH5Q&;TPUNx>{@6;8$ z-Ci}W0B-6^;JOMpMo@vrW`D_<1oLC5_Lf%-6_^z}vx8IDEp~g=xB|GTD}igT8dm^! z>e{&4tHu?;ox0|-MmVpUDsI0>%%h{ z=g%1uUIoM8%JMEiXMmuNv3$Hg#QZ?NvhsX5m%mcjxXqOkLMo*Yw5+D!87vQ&;SEd)2s}x2fxTYp)tA zFbmrlf1|(o*wl5sbxm)4a&R=jtIjjz(g~)n>#b{gV+0jk&)cahcDsFKT+iFob-lHZ z3>BDVe?Gdcs_pt?wPE?l_?^S~^Lq`y*EoNEAHt`=FhcsAyz%njf*IU>0Mg?Z!v%<8{iIFZ{*IWC@aAd(V#F2>irIv5u(sjLcO>c~#0*}o- zwMPS&uIsI9dZPlfu(#tC`l%&cx~{jb>5UOoU|V3uZ=*aeUDsRJ^hO0{VOwB-$-^h6 zuIsI9dSe6?XKnoz*Yh@YU2p9pLj`8x?1T6G6s_Y*ULu?2Bg1D6$6b6j4dYDV7Opy8 z$t)ikMo@v{m0@r_Zb0SmTh)sJkQwK<=^0_(mpb5yEt3w zG^Dq4DcALO`^c759BF20S=9Q%%k{jSx~`V~_RICWox1*={;De@+hVimQdPORHtbEN2u~>2`a(ypMHJp|b~2Cw6RM1Qq3z&2`3g4M=iq zZGYB6jqKOo`ofC}%=%Pzfise8hwHDsTv2DhI@~zEEnC|>| z*57j0@t2=dY0aj2hf)~3+b|2&zqFq0{QkyY_Ojebk`Bu(k6HBd7?e)z|6Qx=@nyEML|}uD%^T zEaw?UP+@;+kH&O#)ouGgY3CU#Fl*ekKF;j@*k@@u&&EV|akX?LsciT3hQIrucrWKfu7|CiXXE2yox8cZwcB|%|JSUpu#LfVjh$y0 zLB-n_eVxZy;dY+wsg>LnS+Oi_VCNYsFzd<5;m-A358LfLdur@4Yu^l`(yjdH$@9TZ zU0G8*&$te@Q&*nWwXp4qf6~X9x*oQ!g^gJYOZIj4<$BoKtHyP(ow}y9+p9L=aiV#$ zT4^eHHw)o!p&HMYc``Xxn1Ngmd%&_{gb`HOkJ0w;LuPuehpoM8sK6||>V`3rk8zmm zVQa4%Mo@8WWOrvKu7^G9hxT%2aIP?YxE{9ls-Xh2@cuJxq1HI_YUxInSIsqRtn+@n z+pG3W#XARZJ!I|KwU2}EUrsbV*%hXpXBDPQaq4=n+IiNc&se9fhpnAwYdep17Uc@s zZs%FIBIC_oVQ%LcMo__(vz@v&w%d8;y?m^Bq;dhvd4>wiI_WXO*^Db_yPanR^Ncd{ zb47FQ5Q;gs(7BeY_iE1-SI&0onz`C7#Few1y3)0~dUnbEP0ZFKD_9O8RAAP#u-VR` zT=m-RB+s2^tQm19#PXhF1QlF4+o@|~yQ^mhFNiaTRx4)t;ZT8DTshmRD}1`EXFsB3 zX3(p~mJ10LnYYh!Dz2cd9aMO>ybkwwnS`J!?JYMIMo{rC*+S+zQ8Wwe zKx0-vQ>ef!_RKi{+m&)7G1TliX`toV{)Hwxr+(zB>FmwM(Gpt>@2Or_+|1OfAKhbL zI7U!`<1VjRemR`b;n!H&%ip$9fmt}i;WcE+?2I2alq#^(2_vYm&j6COy&x~79%i}j zQGr=FQ{%nJH9cIfgM}UpZf=~^%zE_=+y~z9yhj}P8dN2`>dV+?H~O6p)@1zR<)c?sK6|Ig82*Y zgi!O>N)a@NolY1*1^cX>|Lr*B%Gsu_psk%wsK6|)obA+gvfWOnOs=tJYp$TJolY1* z1$(xgKX>i%F6@G%%mLkkETX#;2A)ALIq~w_{i0u2COkZy)9}voiKt5 zuAJ@EwXxk!r-UY(&8(SASWYKYU>1(^?76EnQBCFw+Wpue#Eu>3&)wGS%ya(SgNJ<= z-;ef6jc*c7HQ6bP5md0p&-ruL9y^3SrBvn4M^OuT!luA1d&lR*O$7I`k6e{p+4ddjK6e{3N3|(b6F8&r~VL!$*%biZ)Q>T~Z z#>EIKaAaV1^yV=M&2#spOzcTT1!iG?Y#8(AXE#qTYDLM}_lgml!ZvbVz2DHB68($i zZ$|}=aM-2|ql?+wyzqa7odyXMcvnjcNa}n}*bpVc&-<2-sJ071F(iRIA=I zqb}ExVFVTUoWSqAO2*Qm{5gGfWT?O_ocn58#yBr+{5p@XjtnEHz$YaBB6nwAsyeWg znTG4gP=Q%^r)gS?e{$2e%-ohbGK`=CpAFfi`SK(Cbeg)pIxUZ}t<_EE5s z+%~xSlb^JOxxJdJkeIb?32RcSjXvqS))LaSR3sJ6yUr4#3hUj_CZIpUsy#0BdEZ>lGmvx1e(I!uEKA4aZhj$nYC>RCwsTA z@{C#AhA_9~Eiy(>f!o$JW^J3o+&;tAZK%L3W^G$S)^>Q?on}8W-aKq=7U=R?DBN!& zsBj<0y~^p#C-IHU30%E{3e0k^UomUjE6i=-ZLfN{$`U%MRLU`H+Y*YX)W$Ju+Y)}R zQxC_iZ6(ZYsi4CMDwwrx34PV!Z8K}z7Us6p8lZw%+m`TmrD_gmHGH3so@@(qTWanw zf(mABTSC)zc-zd{wuQMZylqrqmV36uylvrn3)7o<-jk6U*XUqKUQiIq;VQvd=8-EM4u=Qvfv$nm$+!o$8Mo{6N$xMBo*Ld)KH?tf+Vxj`G za2}*-%-Xhvxh<7vc&?bWZ3#hJD$nq|@w%bjS*BZYugewwo`e=tZiGE+fsRk3e3VQ%bd7`dA2aOrSc3Ts9@H%B{XfP@{C#A zwlKG)@(dN2g?BLf$?VBv2yxUpaQdS2FTou=o%zcXzwzgv#OQktjaWKOBjtpgwFlf zDNESTuY5#kra_ZXp@j&I5%z1elH7*b^X~00am_?xT@osE*;{wTz4dJb6-xl6)(f25kxNS%}a~gSLc0`EA3; zJWpgAGzk^DFB73L3)M`6wgxg4I^IWwW*RgJ6NB7yda$ zP{HhTOX%hf|D4(9Bn))npQ8e^n0;;uk=o&(Gy9x`fiC=WW}jQaDi;1Zv(GIdnhXD& zJ@%}BorjryPQpMJ{y9ca!R&KO=;jXpoZ06j40Pe2qXM&-eQpV()#0Br`<#SJ-b!+-XZE=zTxN%V&a7<`=C<&*@d(+&(n|8M#WTXsgUc%uIAFd#@2FrmOzU6I zOlED9Ft>%bjlYFi?5k+~>k!MVZ4&0T@U}663ijxWC3ku=}Ew;ca6C71-W<9;O5y zrf=I7X0bb|mE`#E^Dw0(4^xbwg1ttqe;s0(wN1j@7Tz{Hd0I(czU=X9B{>0OFTr1* z{WXAuxh=eH%wiv5E6JbOtzdU!5_jWMj=S;OehC%qbZjMgBXiYc!PX?qZQ*U>Z()|Z zzhc%l33FR`+ZaIwdwE+)Ud)=ttZkab%dZ+;puZ zZ+>QNTf!X`-nRSfGHaWJxh=eHjG%&DcC93SgU^4LlKgj3fmwKEeLlh@KEh8NAK|xS z5$++5T|OUSO7aoL2r6*fKHpjr-`X$Pw-yzch4-V+8<aWR4lY?VGQRst{9x4i*o z;r+;O+>ghQFt>%bjS*D1dunEFlQ6f1w~Y$Sa^L6dbW3lYZlNc`dj)$wc3hl3goL>* zylsr20^2mNk*yv;;F|rmPsA)dhd$SAN^;G{2r6(k;PVkC@DYA{b}V6m_1=7F$bAy zZ3+3&AzLr&Rg_+j$Y%EW=DvXuR4_T)5~8R>&mMQ)Bq3<;XL>d&FpKHjmJlo*LO0X7 zsWVf$h0u)=R4@VD5~8R>0cQd@2?<;%;HbbX=7(EC;uMBBI~AU)NJ1MI(l|y?!Sr!U z7^FfV=e}gi2okRMuGSfa=WPkMSeV|-^R|R9EKG0ad0Rs7c9`DG^CsbX3)34Ts9>JA zC7f)B>CHTE60Wx}y>T1N^R|T2Elh9bd0WELbeP`E^CsbX3)34Ts9>JACB$xr>CHTE z60Wx}y-|T#%=5N{zUeT%ndeQy^{!hdlkmsi?k^q(^Smu#aXUOL=gzG*0 zbd*bhS@^u8Y0UE`;d-Y(H`>7a4o3s`GY<2-Nx0tI+s<{3gQ&(4PScp@O~UmSrZ+}V zf%iYpmcl!eaJ_%8b;6~eZdBwTM{dSe6?cox{}rPd%4uD39~QGr=_{n>%W z=t08u7N$2wP~pCU%=0GUdjE4N!ll40Y%xq4Z}NvNTyJ4|GY`;8Vka`s+Y)-SFuj@Q zZ3%bMVR|#qn}q8vOmB>!0((22`?L-nU>0)%Eg^@F_c6VH?wpHmL>4lK zWWH};1Qpn8v#Ux#V-n_e>C35wZ}4{Jh5e&@e#NY966Ut>wlRVVcQ4AUZ4&0T@U~Hb zS@;CN4rciZkTAD}w~Y~0Fl*Zq#0o)U;ny+_QzbExc{K z2F%*FgrF_FZ9H$h;x*`=EzE7o0yv$jc? z+rryM1!m!y<~o2Wok*D5!rR7nh5Z$_7Ov2n2-Zn;1;U3SKwN1j@7Tz{0Fbn68n)W!LG|9gj z|066XCbw9^bCR`088L-kmh^X;Gs}484i)qD0^TVzZ(0(OCq{X46gQIhD=>lzp<6Mt z$`ZnrdmE_0EMa3Y*Txb)mRo@lq1!OU!xF*`{*qgP5mX4#ig_TGL$$&qM+Ii#Ih1pn z^v_81PW8Orrl%fT1MJ0mRh8d+pzU4X-@_^gc|AQ(`2J4Hmj87tFl+Eqp0mGBspOa3 z3XGtFv%MU9hXNz0;62j$|NjpKX7TaJarqT|u1xt?_K%-_bY9I?vYO3pO0I*F7Q^e; zIm1ebuSDKR)Z`~rCw`!nA+*9%RmLc8PT~mMu}rm@x1Hwd>MJ;~pqXM(uzgKv!{B#xH`N3a$|29xD@YE*#`wQW!wy)j?j~sssv+#_#@AFeF z;`H-DC45)V@9*OKduH-Z`j00K|2_DxW~7P7G53dM`l`((eOUqdm+0xolzE2&BdFN( z_dvevE!a^bml!2KN;WX zob>nG>+%0p_(tbb-K`%lMyox((V36@t%BVNE%q~1Qn`9}cQ@RA<2KSs+Qjg62qm|Ux za&Kq7do;iZD!Av9Z>rzXx1$2HWDnoni(&*7?>`PyU>5g}R??ivedHKH1)evz0=%;H&;l{AZTE3jSR9`gL*Jx7iaRN!6U-Ucc#OSb*) zD~J(P@C?U#_uK~+m?h`!-7OI#sNfln_3pV3DliN00{4+)1Qk5PvEDuRK?P>vz2bW| zFq59Vm}F!znbJ2pV{2c1bh*WpO8@B0&jxQ57(qqS-_Gca3fxB3N^32qM*2qQB!x2? zpaLVPU{0jP{7L`l{5}O{os8IIwObUfZuwlfP=OKVHd;)k^o`EAZTGpt2rB&FH~jmQ z`u1F*0<-X*cW(nDsNkn!E9t5D?MjhvEkoAFc#TKN8W}%%OU<2<)rh3O->x&rs+vzB z>tjjJ;r_}B-@d5`WUZ(Dc2gAZyTtZN3j41dXe zum~yR={b#Q*3(ukZ9+VZQq_r?vOG;WJleMdNuXv#Xv*cIay?%ueRLJkY zdyNbgm?eAnpA|2XBa+oFdFL-HUeZG3+)2xj)h?;pbZR;Mt2jOdMo^LTw`;}gKiiPi zE~z(I%`09>inlFM)~|dDjG#hRyQBuwwc_<31!l==m(*aoR=j))jL2%2)ELQ%7jFCQ zir0U(feKz7R?_-iD_;LmV3yovNvqN9tH!Hc(gVr$*uv{B!}xovSf1U<%td+%=?D4C zDkb;5vkg>W1Qjy3l3v5b@$&%w();%c6|!Q;D~FczeH3m3e+#pc z{<|}($(3{d8EMMQPUa?Z-sSm5W*YLhJSoY{#5b10chNknE~GFr>u&k}U? zv`4}_6c|B;%->}`@!xHr0<+$~R~SKsJTJ(+=)c=Q1!mzH`S-Zx$npGOmdwUv_VnLv zU<4I1<9qjBp#rmHHYT&D|84^#sE`@oyU#8vFiU1*GT-{|HZXz;dG1NN{_b;y3e1wH zBbmqjcN-W%g=|lrfBydp%t~tQ|5acF6>{F>spbE#z%1;E+((XCa?Rx_Nq+bJ3XGsa zTIIX<3Kf_o&$RMv``_ch2rA_1Se}v{g{+mxGrAlRwsu(`k*9j;&+)#|G*n;&6|&MI zD=tn?jSAdG(%;fY$%>k|`8um=sKAJ<$BFlxtjQ&*|NqB<3Rztf7du&Da~}u(7G}wc zn)v2At7^Dc7?D*pUNf_<@LU~#>HXV4g{-cLr>*0Si`&58!Yn+~Ol7}x&CdKL$PBOS zuB^cdnCTTRSUvA@Eo3#JrQHj^Wk2_3Fh8bf6CXci7 zS?=Tb@oa8tGBAsI2S?O}i5kL`7e}HtJpoGy60P zR4KZj*L$(Y*0OG?)J^k}zHx2_FYYZ@iU0J2*&&5$@hxG*w-QsuT8?Wkl3a9tB+?`6*Uv^oakS+cH z*{gYHOObsu$}BP~kAZuI3a+u0IlO*tmhe)iCX^x-5Mh@8v4u;4SzL*$xB^2z`j045 zz05(En?E(umJBtyhD>oSnO-n^dM}$s%54^Ef6_n&W^v`O;>s{RV^?A7ok$i<6Dx(7w}x*tFoFvAah&VUXLmr9*>P34 z>+GUJKl0Mr+3cA<#S-Fe*Ni2oK#gK%+Ej}SjG)5ZcH>ILQ1kE@^W&bSTnfy3ndgO- zJ>3gEW|M5ALzNKf`6kNTk+9Lgx;LzV!F!Wk{$Hn{h5zI-E-$e^J>SFE(K=c-f~S*{TS*nJjUGFG{V3m#3Mf+c+E;b zEv0v6Svm5lvx`ya$P#Apt@8|wpaS=npM>T|(Sq+wnGdFfx)hl8;ohrOpN%QKHDY8N znbs7iEp;zB_nCe;O+!<&lFP7=5?2F>iGJ&Rf1_7WM7LBYO2en9tWIi%OpF zsQzJ(RNgFFR+aVhqk7@H!tEQ>=R0F}yB_A{24My&Fsts`Eb6zXNA%j?$u_Tsmek0qihp-R|0ACqdAlFG z*m;)>G}lj@?(L>Bt8aQ7(Y-m+dehI(tVVrvM8EcH8rM1Gy6}#gz3uQY^M|?FToF`s z4GvOYHaVg%jg*$St;cF>;l2^(vQnA77)ekv;cGdL$TQEpiyjR#k2cBTQeYNdO-dF|^Zf6>@+cq|rpPTB%2rBZ`%&dBzIHGT_D2n@+F51EMJDSULO>!wP z>uA@^YRiv&&H1b|8R*OHR*fk`%(PQ<1KVhq--Fa5^N4;h`~STjkHbsbd%hW9*4Y

      k@Dp>)d3<&f7!33*z zH(ub_@#c~>CJw83QdxLvf{}^3;s_I53qq7ApQwZ-PcS?_i?k7}%ILbrF?C3eCJt@H z-C#BxtmbgA>Yz&4!D81cf0v?4zcK5qD(Nz5hq?u4O`0pI9ATpH=c$ehZ+2NZ?`RRv zP$f*TYX0n!%6z}g7IFL8Hg!e)F~)m5Cvt>|0(q`EdQCrI<@`K|ND$_1f(ceVN%~Y- zGJcmuIO=Ux51t(PVNB!*6CKMubhO%c*vff#5c@$KM_n<&sy1!Bl)VlAu!xeAHmeUt zkNEJM$Pp&O(q22xFC=5jM>D{L@Gq!K%(Ft(4TSFectw4`LPk!BqHz3sEKP53(od z9KIE+#pf-zZ_bdhaHO99;hoOShaWDF1)epiqkd! z2x~W57C0WK7eUTB!o=7OI~C7?6|9^GfoKFGj~l_Nc3JzCdcWLpy5=8G9{wON=kC-C zU}WG36W{bZs6>|XwsLL~e}c$Cl`z4oDisbZ>+(Nyy5=7v=M9%WjdtkfssTrs=vMf+ zQg3VnE9c`t6a`_9K1{Hx@{klIrt3SWYhUWskfHL~`fd8}OCnT`FmY!6J!Nr)j+*d{ zMb1BcIYbVQve5~yDtXl~M4oMTM>BKI5hkLZ zolqQ|=36;8iMH+UXn(sAtSXm~tPD@vkl?D4fW5)8XMtPVm&iFsn8+J>NlAJ2yOr~C zAlBr+rTMrKth%!5iqgTcJHb^YBd1P~-g$3m7q&#G9ARR;@mjf+6z3G}&5>bly9x48 z%6%=lZlsN1Ro^bTitxUXAmU8oDEa^{UoW8Qs1oi2VDCTu#!kimtGSk|@83O4Hhz;| zHN7H^FwwEl0cFai3%;(Le-B~@h-+>HtD*|*Rra=C=x`Ay%TJL{PU3`rtzI%=h`t;Ud0SHc9pxlUFsLGHen0Ty09S5?><2*OhYx z#0wDS=)(l7eyVjsDH0v!a1njV1j{a;e5BSv&N;%w+iq8sfc&|>uAG}hBM^<<2v&uk zx~Oa!w8`Nj_Wp@?LEQIHQ;wp$jUr6^Rw-B6dc1%`6#OtUJPecz9{#K7U!yOa2v!}d z^I9oAQgetZW|cfg??+}EO*K1&xO;>9J?xzv|I8RIe=6!!k09q9VWM^Wol4dChgQ!2 z1ELFv{J7&V!K%fNHz=!8D=4li@fkZ(-X3~LHAe=HFfl;er&RnY+sb((5br>kP8<`g zD(taCnLD$J;;NFLi;R$w(+{eJk#mkP(fm(C$w>Rx%J~csCqZOkEMbCGp=I$PZf0(x&SlHwT#N?gXM*ud(?=Mkv4)=sZ;MN8TGm<;VaGe3CE#NrY8Di z&Z0`V(}jCu>|HNU*R50I@{O0~jD;giJpIj6`SsuyE9WmkYy)Agg)_mbM=^&TXY%Z} zh*Mv#Rkx>)l{JuajxaHNUI`^8H_poWK@fXDJjU}b6Rhgnvi5mS7=ir-9uf~#C zwYC3n>FgG1BW$WR`IQ#|*-Cg#bB^;GT}a=c3n>*kqztatXf7H?IF`a@OyYEFnW*L^s`1bY@(zXEX$ zggM7yf>o_YZgZ;B4p~()z*$-EG=8Eig(~3)6YO%}O-&%WfG}6jnP64HS9_gFH;-9W zGN7!N-X~{*Y=WF~gbBO<(FsH^5N+HDR{cBVu=C;Y3s#j3-1LPWd}_SBftfHzn6P)_ z{=K)H9(rRu-p&kpO0N+9gEV`i zIKo6o(YMY~f!nQ|r-LXDBE^kh)zX}5TDvjpEaKtLle*W0;qoO$297Y1??E2zn{#`t zoEspjf-qMHnP63L*?L;|h^-d!-TD)H({e-QJ>;AtOf0NZSlgJYSvha_KL}P0Not~H z+}mRjqt+hN%byt}n<3{MVIpdKDQ(luQ&!G@08s&iITL1rRoB2TR-^P|+;PmOj2nv*_10Ae${B4UZ3L@Mel|cG)A5!fLd?-;;KM)k zr7H#*v))Fi?7r}NJFnJbSNzI9^rqVe8L`-R#{{d`5kjX^*93j{u_1>J{*x|^uS|2)btI{`Vu1iM*6JO;4^M6w&fD)v8d5_Hug z`kP{7jKb)$;0P1kxsH()4mAzdF zy+v-QVcw%S!UX$mc*7BhmLSY~6cems*8!X2^Ay*^6DJ$y3JXV=VD}8~T>>#3gr^(9 zDs~-&Xf>~>{tzxeebg04m|(vRtIi;vfH0qAm|zvV4j9|Z716U2f{g08J~+Yz`)%fX z0gC8PL9}xtSY>k^#FJD{eg02@MrLA!&B0>A?!;AESV#|A7ibimXeU@@_tiWdMfH^* z2O5QnVdo@ycT6Piuj(wE^0y{RZpL_ZepsyYIDED5cSfnUNZ(bydl%(uqVpPG{v;s^ zSBiC31@UWqlgU5+rpE6^AdLA(Kx>PE1NJqw&bQ+<%S zFDKZ@#3;%UCU_-Xh>0NLLDa!j%LJ>~t-*WyY7SA)RShw&Vl3eZ6YK~GF&)Gi5M~D* z6Rcv_NeFerP_@aC$;K{>q8wp@ciIRs6hvbX{%!=T*b5V4Snr#vKDL+PC=sdhnm6zB zv+c(dv!n@_=aJMzD(A0o*w1)|D&Ytdwk~Ed1H_jg%r#3USj8@f5O=meP#;|yVC15%IKl*XW8+L&i)etl zVuDrd*5D1@`_t9ri-U}_s1lAa!CmE;4}v%a;<+2aDt4W)$GvHWx}f8b4|T;6CU`#< z{wff&K$xAGOt6aGGn}yDEGExCX<(M$x3zw!M~2 z*mj(XssRP$q=#*d$0K5G1gp4?h3Ibdl&3G<*YlN*wCyJ6HGOsjgm_fPU)~D6r~7QT z?{R09eQ)^6>b>RV1rPM5s9laQ!OjNWj{{;K2(wRy3085ZJl@YasIT<6pRRl0nSmor zutOt6B8b8ua#8I}u!{TXh3L1TzwF;4Q#ZSiIKl)wO+t(W;S1s|t`83Gp+C6CmR36=f2iK*e1wf)75h|hs>hF$?}LZy z<_wY}Ot2S%_n3faH*vUL*NtEmyJvV7y%#9Qp8G+6iYnm<6YS~Wv``R7K)iM%Sj8@& z5CQ#zrB|cT`e&#sjxfRAln_%vbZj_UHytb{SjGOQ5I*xK$+jKF>gJfp5hmDU!@H(3*~=jL-JV0f3mQkN z>>{ymz^(&Mhshr-JNK&OP_{+b2v)JPh3>W%ljQkxUXDhn5{@vz?g{3c|ASx^J9M}P zPfV6cVO1Q3FkW$l3HFU##7+=q=Q0zlVy6)&N5b<;tLE)^htbCtA$Q5oJonM@PDBR@J7q82(9VIx?@ z&Xy1-8U@IWB|}y7KFAR!*l)p828iPz%t~Z}RqW}ZO4f~+&10vk?@=WjVS;@ljO`#| zK>X`Qu!@~VAsSZ*l7BRvu9~~gIKl+`Ul>b3#Dn+`Dv=3RvB!#c#kZa)e=@>Vb0w7{ zOt6oKGiyMkfk<*ASjAp3PB6PWNmf~beSN4BjxfPH%Q2e(acB7qb)y@>Dt553YJmOc z^RWNCGYH;6&h8@bE5mqItG`@7^R;SrKyZW!_6>2OHHfAl%nk@9SjGFw@XH(Zl?{8p z{NPk`gbDTyaeh09ZXnE@Gr=m`zA{nd?_P4~{cP2|b8>_Ub{cW=7l;NR%t~Z}ReYu! zPD4D}Qy!Z1Of~0G9ASc;Mx6Er!T@1<+f1;^cCwjhe)W49())?pcW{L5%rhqJ9;9<- z5BaWJhAL&GjbN4i1her6FRPb4`^d#@BW>p=vV+C`7f#tMoTfIP*GGCKN7x8f*-t}k zndgdHY-vB~jbF|YCfLWr^DcKMzD(a`QeRhmv5=Rts5r8Ffwq22|nEcCkTL831W*I!7APvh(2VT0iogy z2(#mtPjO(^n)mq$QTlu*HMjX>c?Q3OBTTR#jg#>}yaG`I^A9Fi#ryn(X!fpy>W}?V z=Dux?Fu{H_>Iy_p5c%8)R`EVRA$C1#r|LLK#~gh)!UX%#cxC`$fG~FhGQld|=ZCTV z&o=7j&jO{{f5j0d*uloR&LB2|Fgt#kV3lp3pQuo@wR#r4mO0ZRRE{tqY~J>Z)*aQv z$pP^0B5ee#_@p3=iRl}ZJnsVKmb5kY6M;5P@ZA%UtAsya?JJ(%Z05H*Tk-1>f&Cwm zxjhx7_C$H{`eHl5DmuRi&xzfhIisV4<)G#`osvJdMSW+$(Z3Z@JKF6#t`};l`F0PI ztLvj9o-$<1s><_ZLh*Qk_&(%i>oL_P=!bY%)9c-Lvy>XuYw$>PFt|4=T33f?w zt}}=?Ak6MhCRoKzJl@Y)a)I99w*dJZ)y@$n*zFafNT~&S9T1+Fu`t0Z?hgPlXQ95U zK%l&eahD@Zuxkyc0mKdv`Ei{y!7A=^z!})57wPBf2FX;6R~%u2-FJ9JAW}e-!+6C6 ztGHhSYnBO%_2tKcgEh-Dzm=R_u0#eFBJ5}aAn9cR|0fZ#K0xQoDc zg1YEh*u$vVp|?!LFXspo?Dk`B0HPL%mu>{B_|$YElFz)?yY}~&C6Nz~Fv0x+LL3Lt z8HBeR!7AIy<5E-al{w!A6PEZ$@*1gelM0aVr z;T&Ot`vdUSX%PQ{sP9Iw%6`Il<=pE>?*%T4VxBP=Dns>D872Dk730Ni?CQUCw| literal 474784 zcmb@vb$As=`~N=>oE9tY?(XDdchTa60!4}wg0;8>hvFK6La;~)!68T~kjzdg?zFfU z2=4Cio0&6v^4@a}pXd9>@42q$x>D}9U-}OCxogFO|3CaM zdocq4n`o3C8cyFokJVm&YU9`K`a-(<-Aeg)v*ruwjxw9%-vE$_23nA~SSgs+%e>AD z@utfxI=|}zX(_dK2K}wqGWqv-M<{LD&-u6A2VQskwgogODn=4t_kk89I_(Rijh;n& zDHRf^5~W?(-|5d@DzqT+pi~%Lk;|J8Bv6H|VE2I*B*qmFrRQFHYbzvB_4U?8OZtC9 zX{njvvVE|h?4?2r5+zTEQUB`;y|gY8s1mJyJASSgBE#zyG}X7xQSx1v_4NGF5UEP_ zFq-~xI?M}!79@_;kEI#>XL}*GjfkLU_sx)&h#t%6JUvwY{dEE@NW3o}MTZ@B()PAO z0##UAJAwBg-d!*IE~DT6w#rLA(1L`hU+dIy|ARnPNGfdrk8r41&Lyji)fcB-h3c|DjW;;{y+;7MfWVF%Sw3b zb0koOBgXCn+a3F(PKs#yV!d-dwi9SULX5XO<2QI|D~`60Kua(Mubbdhvk-s*)9nbFFZ8A80|M^x9Sb4+N@&?{t%*zEUd7f`qXzmIfdF zUj(YKH|_O63lc9<#L^(IYb_F}`uZplb7F;yq14)!^f?tK|5kUi{M%kCw21wKMW{K( z3!zqLX;G`F{9CM#SNZB7eA|8Cb;T}YbJ+z_^>rU;K|<^wZd_XE#Rn3oQY)$#0xd|0 z{lm1ai~a|JDr^ON&C!B{*m1NzztoElBvAGB)o7XmFvs2SA@q2_aG5o^Y>d8_2#UnkIl zgxGOxPwu4cZG{A?u(Wmp??Jq~#O@IuwZ$7Zs#4h7; zDret(y$8{PgxEivOB?H@R7jvo)QLY8c_Gk(gxEhES?tXR5~#wlU~gTtAR%@fb60xn zb0koOBgXCn+a3Eu>?Nufbk4zc0xd|0@y2)IUfK!?REfPrhXdYxpaltWck$;0FFue! zl~{4c{_dQ$?e)O>TVXy{#Qvd0{^kFJ zK$Y5kcp=b&gxWv+4+2$cPvnI_3ld`gu#|-V4+2%#o1Xn)jRqvdj$^aewHB|1D*Gs@ z5$9v3e0|ABD^wiVXtb&fcitVTG^{*%}uKT85apxr*$Z@J{RmBz3N1+By+TNv2^G!KDeLRP2NJ0IZDcIX_GXsy(It8s-CN^8LU3YAUDN|DNZ?vRNOag`zul!K zOCLy}>TbD(^mOf+%Ezp}#kI-li1dLLB*dK0BNJ*QZolE9#}DW!eIS9V>yPHqK7-~e zA8X2N)28G)DBB7xNZ?M5km`Xy>O<1ykv@<>RjK5&Xx-`yl#fmyUTOYmJ4zpDu@TM) zo2tisGD&aNxuYCcNZ{^letj8}Q$D&xr_w{uwJ0h211(74E{YK4gNkv51geDZI}2m% z^`OEBT9Cjs*wt31@PP!XL>unzw9eii(g#|Qz%`f<)#uU&5~vbm;m0|fln*toOi>TC zAR)#vkIAV1P-9p6Kmt`_O#k#tobsXW59tFfNQnE9#{iTMbq`7(NT5pIn`bvDAL>4r zZG{#j#Js{|0Lq7&OQa7ZP$lM=G=8g<4>ey&A80{B%#Zx(RryeJq8wL9pi0b@r4~jh zA8OuB5dDD`Bya{7eLmR~tB5u4TGv7q&c}qr)cTPLBKP`ljUV!E7EkW&CaLJB7Go%s)*0)X_fXN%Ezuhd|A6C zAM~DozR=Nv#P(DhX{rkRS&G+>kPk66S%nGPb>DP34J1${S|O?Ct-Afles4ENZyEVY zM+*`oR>#pMIm4BYd9giN?A|xpl6_Zf1gfyr3AuQnjrL@EbE6h7)%%PK>7R+t)?Gbt z8Lg0dhP*DeIwAQ-kD|YacQXQb&C!Cyo{$Kdcx<{Vl`rXSCT{CuyypFZ1gfxa2r0Ma zkUnXBd87NPd`9LC^XPz*b7i~7Gzg=kFFE@hOUsE#zinlgWvGY`n#Eola(&lE2EY*d$>8^3Se=&XRPwp19%-7V zF}4jTZ)D>Afds0sZwL{k+7yy#iu*$l2{G$r4TXtDI}JBQe;|P>>>EPLI!7WCBTI#A@o1d# zp=Jgq`U5RUh&$@TKFf!ieV7=DNT3Q^osbgzu6=#2BNKBXT96QT@R^*J4>dE${y+j% z*f)d(^I0@z?;9GYwkX*?xLy&WW@=OPAX<Jgjjv9gsrxE@N*INPv=5Rtb<6P3j3dsGN;lQBkTTQ9to;%o8fTJ zh+~?NBMbNH<3Gfil`D3%jdmn(H%N%1ew<`I zK|(%8?AGqJDlB~wy*|a5qTE)2k=Vid8?!{y+j%*t3LO58i8*^Vuxh3N1+BZjg|{x3jP%9mAv# zBv6GTl#sI_AI!{Ci%1`6K?3)Wggkg%g!wnRnIQTc2~>%HPulyGnCZhNr0uMU{y+;7 z_MPRN4LRA?F0#%}) zlJ=rmCM-3de>@|7palupH?F9`!?-|mrJ2hR^*{nuV!T=VU_zEFR`?FI>{aQBjyqN~#fT96R;N>bEd$(lv_s5zOX4K}kHc96s?==`S6ItDFRh$)>b~;<8V9zAuUL# zxQ6oK9*46CRH@ZR`EZZJ@kolaAfe(j%7=R#&LU8yR#D}{Jr2hsLeheSiZdx6?r}Ja zK$RMa%7=R#jz_kn#YRA;n=3}s?t|Atm70l^57i&8I2@n*qy-7l|4I2i?r}JaK$V(N zl@Iqg9G}Cb1qm^Zt=unH4A~Wjvj|kFl|lJ%kHhh`NLr8(_hVA#nR^`0B2cAPIOW45 z4)+ko6)QK+71K|O!zlt)YNb{_+~aV3Zy+s5i1{%oPsTkCXA!7UI}YW;Jr2iD zMx+G^oWVWga2A0o``qp&4yRdhIKFeztT-Hx$;rPx<8b`BPg>LygrwCTRT1uSIQ}&1 zL8xaDNqffOECN+(kE(pQ$Km*su(Tkdo{*Fe_c)wIpi1pgl@IqgoYf{ss3$$;!#xgX z5vWp6mWptX!|^zS^sb(3rAj?zs8YGd;jI2ZLOppaAMSBDi$E3jre_?EM<%3q^}H;v ztDdh^sodjmRy~kVPu{9j?r}JaKo!=>GY-dNVbZ&b+{o*yU6d-7mpGgUp<+O)R9@n6 zl0cQ(cPSt4aX20w^dM9eNBMA%!&wBX)DyDu;U0&x`U43SHBvs@<8T&%D(oB2I2_-f zOYg!5k0HwIs(r93m3th{>JKDDyYVQeDwTU2&LU8Sz3CZ;<4-2iyC^%42+QlLCjeC{ z_c)wY4Lla$Km*sq6Z=FM;<*_ zrE-tMSp=%oGo13_9*5)4gVKV8xTAP{U-@v4!&wBX)H9s&;U0&x`U44Z2lIHl^5Gtb zvj|jS-*}C~$!m#Ol%ILXzg28NmC8L1XRTyNh*_JT%BWJQ)xZ^pvj|kFCw=9^Jq~B} zITB*^;ipT=$3nL_oJF7tM~r72&bmKv&uAa*?r}J4>>^>`S-QvJECN;bK6j79Sv`n^ zeP`(&hqDM&*~hMX9L^evNZ5Cl?r}JaK$ZO-bdSSXcN7x#ouzvm&LU7{A0_T_IIGW* zuSR6X6XG6+vj|k#_oD7`IBRE#gzOvjq|eXp+~RN+fhzls%smcg?XQp!W6XNe zC&WDtXA!8f@2}kBaMo@K330DjPx^$o$KfmjRrXzmdmPT%Gaw=EdFx4^5cfEoMWD*Q zTXK)XS$iKO#N1^)>GNk!w>X?dpvu1M^Ad-Xb2t+AsDYO_oFq_X-}|`7;jEb&37muZ z`JfSQCOh#HtA751S^I}gwCIJ=+QD)ux4zOh&@MGcX*U}Nt|0sgvhEL~w7(BF@g=0z z^^NBK(v4Z6&pr$-NYsnlK)22rsjY6@j1wIK9?_4(elypkAIg5YvXOqyGgJ#&dDnMe zkxeux%Mfi>#;3l2=iE#W_zu-JlzYgD=ydUP>hQJZ;kttuT2fw$qZtE+X*9!4U%V0_ zg^FCD{sH^UzAO9Ld?2xSLmd598?GI0f0_HJ_FEM*`pPBq+ao<}1ggI4ypawd!?pYs zcW@$W?!4yR&4k@P-GQM6iA{lV^j_Z)+JP*)IB_`ZX!8@v%1$>AR8I zz4Vhgk#SZB^W@+X?8=2&3@u0;yuFDY9~-3U6~}O*?wrMD{!vxfipXL%0#)|@Xb~~i z3>d4iOoa?$WeiPkYd6afF{s-fx>m!j?KAjgiU1|B`H7kq0M^NGGDeI z!?2$lyxK%}d>Eh&%;Mv~o+TvYo|X`?dJjE$V!W--k%&7NM-$f#l=RmLR82a#nYMgl z5rj;X`931&XJNhcX5xT8+IMU6YU1x_6@R4#Ix>g&dx>KJz5eqj`NoKyxDhy>d!H;- z{BLUg&1p^0;>vcyvWV*<@%xf-TK-dQz58%ocXOYKbVmB=(%+FKlW6MIzj^WT@TYv# zNX)JaADO0aOlT6ETmJo99!<*;bYJr<71rD;3ATbKf$f8YRj2=(uvEfFxmv%{u*K`V z)Wfp4x7F8c&IwIiOAuV8iS|+T_jOc|eq+$_jV^iV56dD{R7?@B2+M-k6@Qm0-AKz` zZMzpA4VJgnsuuoL-XEz3cck$Jdda`PPFNOkT_oNnZ$=X`t@7dn2}|{V*TcFyg{s8t z?)25H`m$8knD*=s%i>O0CH%h$OC{)QVcoT^v+H}Qhh-5eB&;^{^ik__NqTo^HaSZ0 z4jx#&GK~$%qI(jSMfgC%8ZrMjVW|XtU`RE3Y-mO=J}iq+Az_VaPanJ8LQRxi zl~5D2k|)8-E-gZZ1oy3ZFBKA&O3-|^^Aoe3rw_{_R7hBL`o9TFC1}c$7k^zcuNNPd zMW~Rl=3wE&`rkx@pDt+DsYRY^%d}sMIp05i(|4IxwdPmeMRpOW;%6aR(iw~8fv-FU zs=5sg*YaI-Uia$+T9DxHM`}Nx`pR3_F7K$~r$AcL=@OO-Ym2RLF-5dCzMwZBXhDLX zo@hy@GUx*dRJC{-tu;H~%?DbL;HM{A(y0vkKmt`8gJZO(zdPTlPtuG2!1lSnZGkqW ztn1DDue24mA`)%)g=yC=Ip43g`#=I!{6tZ+&I;`WT9C+GI!tqH_4XDv5~$)Qn40w) zAa)<9np8YgD|O!a=JnSJv>-9V5vpD3@s;1paCt|SD6RM3{XkXDe?zr=^_}lgf1N-J z68zmo?c#&4{8EU^JE}xKdH+?FZm(BpXPEO1doix8_w!RcjMj#~b^eNry>-!ogc!%( ze?dUpMb__0Ea$Dce4g`{BEC+b1&MwYqO{q`z5UJv5~#w`+UtSsGa>H+?PDruD}24J z(1OIFiwm_gX}$dt0urbaGv8N#7sq8mqEzG}jlTh^at)GdB7aH8MW6~>JxMQS2DBjI zzh|j7Z>6`^MFLgWH+CO5uCAqz)n>nNj#nHpb^jicn zXhEWD%qneDzU5w87YS7H6J^)^Z}))~B>4M^{|^MJgzu#D^CT}54YVMUcVDblk9_5q zDO}e=m1slnD-K$aNXdWmW2M*C00~rmeU19kAxg7;pW!f{(fX+0XSg!qcd^b>&)-f! z3ljcI*N9ck3sGgjMlmN!i|QNs_xjLPn)lyl!0Qgn8KYUh&+v60XhGsw>R8SD?=v8Q zDp6X#a(<;AmIVoYMXcui_Zje7sKQoA8dYLuKnoHZVpnP2f1d#fRDHd5(USi|tY-Z_ z1NM`>RA@mWIscV0@4wH01gb=&>gR&2b@V%(_-)BGz5?yD6 ziFMFR4-Rj;M683-GKc?Snf3b&UnkIlM8$}3&HL{&Ab~0@t-W>e9>lw=TEH^R`|mTL z1qo3<{*>XR=18Dw_T#0R_ups0UW<>5(X8KR_<9eb1&Qv@qc!ip&wvD~M4i0bAB(^Zxq`c%Rqa9i~~o&wzKZ-3MBb2=xoo zy#GD}5~vEzIaBOQyo?gGAaSl_sMf;k?=v8QD)l7e#RpoD_)<7j>`VR!fhysf?@PQ8 zXhGtB>M+gw?=v8QD(p?q{;);^64eieY2JUI0k4HB`zT3njx#Q7No@*mSa$1g@$cx5 zkkS{28V}Adl>}OlXuUE_JG^%x6*M8g?(1Q!p8v>$KoypdkbmB^GP3z(mS+cOLBd{- zYBQ@F{l-<11X_^bCDQnRt5W&)%4+mk+|q+U72autu=P*%3@^J&0xd}3{ZB~oc9HtD z#zQ5679_;eJa0Qys)Bd&>UrLe^&n7%^B5uPb}lf>y&fisu4#UE)eu)WqzTEH^EsVV zb-X0df&{KzgiQUnuV0&Y6Fdl1*-N$cd1Y2La}7zHEfMP)4Y*Il(h?H)b0!wnwY5h* zkib1EAD4yin2-DS^dL}$bs}WV>j~^)(^&~(RN{^d_i*aTLiLCL-mxsNqp%#iXh8z^ zjQk8T(@>T?F3N*I6}AW=yQ8|Zd5O;?ffgii?@I_R+mcQGoYkXsQHAZs-{EaMo(-M< zP;;+2)(Ll+glsK6oZap`Ul#;gkPxNiy{Ou%Y(h^q|KTkU0#&%f;U~O%TC=DN84ckB zElA+5hL9OyHCUUvSkU=TXz~R2{C_IHN^cc()>Pe zb4Od$X}l!Rf`omyw0?O+!k;fDco3+vm+HdfO2+YTYf3`QwY%Y#4_#u@qB z%YU~vid@Xdgb%bJfw4tGvV_$zCJd-73A7-g#+53SBRHFJWv{;nfhvqG5|S$83;oxY z&h;EENMNLpkY?|q^@10NNFQiHLfvVqRH02v=t05G^&AOQVQi6S2;~Yhn{*s5eW>|E zUJK*9NE5PW;2m1IQ_^}aW@ypUNZ4bRWky8!(HBYUxkaGLUaB9TRbqY8*OaAFbFK7& z5l<{FA){MnWFHH(@u&w9_Bi#0!-?kKDFQtRRAHS6Y4L0V`!#5TT+h|Iq>207TLeTYrmx$M_{7%`XgP9j-2w1X_>~r4?gY(7fh* zd$4ukk30xeVZ@V=KJQzxAHHNV1dSFX>~YaqbE>mcqpL^)El7xQCGLB1RYIQk&C32> z*wTYQ6`mXNcbEQnYVLaGT+h*h1fFK{_k_Denok-Il|Imdgt!OA9O*1o)wKD{gKwSd zITEPCQ&~bfZ(pEqcs)$|5N&SN5YL2>=1&vpo@;+pOA#EFu>_R;I#4KlL+9zfB8#Jrmi90_r6v<6!y z^8CbxMx6fdy@AHG%YAGFs`h9P91#oOXqN|`=RN|SpVa@V-Pb5tzaK>l5;dwnbmZ9d zM*Fl;__+T5rM{zOH{<)Mb^=xQn!lte46V;kM*WX{DO!*y6a3r}Kktn;c7X8l;-3P> zqLB@a8{6=u( zj}&_iiLyJA`Na%=t(9v2D=$^}f9;Kd15z84M>Vz)sOq34_sf=>`}=Tb8y|^7`xu4l zoYC(F)ud=aVoGRozo%(lYioy#yw~^r`WrsAOnpJ|N;U#jj@ilmDn5LrJ=wUQ`-p5d z&?pwZP1ll@r>F{EmfSDG=e4$T%4AEDwBv8eDIFfuM zZ#>jkekj6>oPIU|El8|S^VX3zt5uJ#Te=x1p1(BD_PA^#Q1w21i(_WpE2FA?YH7<5Io?xWM`jghU} zvOBy~NTBLsr(}+u{V%9e{nq%NKJh>R3;1*~0ae+1c5y5XyeO}0Cmu{%sy911l+ilp z63~LgwBDb6rPBksOd{@@wE*roO3 zohm{)jx8Sl^Vo;lg#Q@dBW>z9$VlTGCkeD5F}8l``1-S*@jyaO?`~)0I+T_PA4s6; z=fCpAZ>#x8>vC^9_Yu1}Qjha>Mz&*@?%nn7@MC_j5z;R9#?D4_pJ->UEb-gXuG6lq zU7l#8(=X>lyEv#r)3elyoKjG|}t5zPV{vNuULZ6-D;! zO0nm$Rt&UH<=H^21y?U{vP35zr_=+^~vRaQzHuaz8d>PD<8d7)ZEunBC zJ$A+b(1Jvk-s85;TKYuut0H_f`dmT(x1uwafds0sp9nExG`&@rt5mL0f<)hrA9f60 z_Cy<2QutW4Y=HjwMUYhw7lA4qV}x8-+MabBoJJD7KOEMm9(}xoqv(W(+V8uV-(!}? zaXQB%?YnV1xQ{GVTd-GuFzASsBjW4^!53j^W_0?LeYg*SRarr>vyAdaS zM{j(rO=`Z9`}j1iI4e1@u1Bd*W$*LYrO8?Da-FQ2yZRi7z>j-;@9ul71y&WKeOR;W zrq2y$yaca>DjaWw6m1c}@=bprX9jE^tZj`9)g4<7KhUZ+KFECxs5y*fpSD;MXhDL{ zD-LTW;%7w<#<6c2B=;atHGQAqXfyntw#w%g_fe|kSk`%OMP1AvXhA~w>(%SF8oOsd zjbh8^cJd%l^~pQ|&=Gp~mNsEy8cr=F21^`T+Jit9mXOcX zgFCR`JgFst79>93E$(PP3B#W!%lP3_~{ z9BxFqW0TGHT}Mg+uZ6_*+`D`mXH3-Aj?BvaZ2P>{%+!3a2Z1VVb^iWf*AM32lwBo( z79=kGxW{)wxkT;c_V2ilwzqP!$*r4v5U9ejK**yk3lqpI&$hxkZRz`^(rDg>E%W8# zK4O}8)n-OG3A7;buSRyI?0Zv-S(%d)8yhduo;UL(P?c(a^_`L2N3XoXM^Lx=Mh{0( zSr6Xl@z#AXXJ)DRbA4`WrKYA7V|Q25*o~`N&u9=?%&NJ|g2c2kCF4^!xvf?EJ{9*7 ze!imNo6C8B;I&XyC?G}r$480U@!J_V@wsni<4IgA=>shvmLJ zy7Z>@xJwT1BhSJ7db>N$$Q=@>!oJ}V$R6X3`(d}Jm?dyWw&$<9@jY7J*S_m{(Y8C| zXGQT7jMKHxiG04gRdK8_`C|onpCf@P91DabUK(Z4XI-qB!8J;d zn9u6Q`$XT>nmC?tAKzE~#c1;LJ`Vy_IAZuO0>w{YIj3dSo({d05LP`!!siOFv{a!x zxAL8Ag7v(N&(VYoJusH#s+?b+UM(F(0#)&)k|%`Sex-HXR*T0OM$QXj=Xlhh5sw<6 zYTmNs309oJPJ}ie$V$xLrZ4$Yj-myLKSGlyoafPxhcfyx<#um2Bl?`4qDCznfvR6y zk%Wn}UTZl+r}0vK)2s(8TlTSjFmr8+79@DIB_Sz_Gq&Up>~h-gj6pm6Z3L?Bt#}`w zc>A?>`_@?QgGY*(6)8d$j}*mQu_Zfkw6rhN%T+MiX6j7Qf<&PQ@8jq2sNpOgHRNXk z{-xNwafVT*O@NI+Rk^26UDQ6p_{iWVg7J}$pHX}&Z18U~L*B7rI%DU45wK&C!< z+iaJvr;%n+KZ+J4uueRO0kWz1xe68Wdvz)!{}wX_e)Z3uO@$VV76d;Fq2lC0{B6&s zLIPFzoj`jw6b|?b%fPoWoT^{LU=W9@$hb??~V`XFam1Tm-7@rNV3~e$wC?4fwTY zEUi783N1+R^A^`PtL@oTNT3SqWY4C;?;_)ul=<0<_BZnkGrA%QAv z5qmZjT9CjmP}{SqkU$l-n?0KfYmOzvZ#~ajoDOa zK?1)mY|o}b3ld^1@c&k&!fYxeP=((Xwr5kJ1qu98usxd!El7xakhh&G6=qW*fhzG0 zzoah^V>XqTKdc(!SErHo$fk06M?!oX(E2Vm&oH!SQ@IFK*-M4lRAR2>HI_BR@BU(G z?b%dlLBjs^Y|N%Y0##Tidp4D|E{Rpm+jn@K^DbsnS%k14A->3$^aWzfra}T$*dq39 zDzqShUp%&FQz3yWY&Wm#xy=7oC8VNG__aLG_1wz;Mnd_PwC8$m5vaoN>v^u{R{l2< z_OI}{ujkfV0!XN_pi1Swo?8T}@H>&7>$&x|0}}Z4O3(G&dItjubq}gixv%FIfhzn8 zr{{VuW;W4l_tW;<1L%#KD25@Myc z-X-*0&#juH3R}T*J-6Ny#4ix5^-7h>%X%&?NZ=Qby{_kyK$R$|)gqqjxn)5DzufG( zo?8T}u-!b@bF1c9Tl_|{=X!3v&xeGlhZxJEXZdfKLUuG>3sqv(PI|Y`eLc4bl zJ=b&V{V^m&Yl!>aSt|GS+#*ng-{kdN&#kx2kiakOdamczJ7Y+Qdr-`g&QiIr=N5q~ zv2rH88Rov8TQ$V5H6!i0o?G6L5G%FyzM|)PZV{-mm&$!Tw?+egFIW7VRa(#W+_E5H z|LU~+dTtS@!a8|f&*iG-?fbRP{_wJ%%br3)th-5XhIv`fC4nkYQmaKg*K^B)1b!*l zb3L~RRAIXj;`3(*wsT!7868}^yrAQS&m-Ep&rZLb?r8IRV_t?#(8{2tBn>4x8~ll2^PM%|;;b|;EhpE&^UnRa%Tc zKJS`yIFa5xm{C)aJ4K{B)7&^xJ*Onlg2bEhCE~}7yiLQ)ic^5V9zBdj-#jse4s?PVl=bK@ABCQgXnfrKAuNfV-(bb8FC2rjtMm5?Dh124IKJbXf{#pCf^)NBMnyS53T0 z^>2lbrO*4DxjzTVdY}afY(t*QS$Qm*f4YJkyLji|9mU7AIPFtymAlDs)?!YWBv7^d zZB2(6aEB&t{Vea=BqIB*o@_#6=Nk%mEhPRbTf&iI_-(q-Pux+%`qgJcDioFVKmt|R zH+<|4tjSK#tYnQuSKlI0a&{I+y>7RtBjY#RN9iW{+0@F7JqT3U`#d8bQ!hSjvLf{2 z+*!5>&R5umJicoVV%_s?lmuFkXw;*OW6_w0RJ$g!MXHdotVq+U9t5gz=HuTbo3qaR zw~F)Zu5{zHzO$!3p}l>V`d#@n#&>U%C$#qacNwpZkX94op11nR^*uu(t?Ek z-Cp07`ybO`WyINb=ITY+gP!#bajzhOD$!3?i|`D(2F2Nh*t(KH3lc-}obbJ{nfop# z&gi#4ugz*2B|QjK;VQxN0Op_36W8>S#FKi%ch&ZPLTB%lwH28PvQGKZuiKR?*%KPn zKbrf9PxeZ0b*P&p(8BBFBEBoJXV&tDsdLZvqe-74y)eX z?}W-EM+*|2n*6@C>Cz{(Vs+u8Oy|icT9Dx5Ek0=^=6l=RXq7sr^nnDb4yP|2-+JCd%0H&ZeU#Wg&{)=etDNC* z-S+vbZhYS8yEKFE6EVYyGd zAAbDQa>62q=DY`!EJ(EGB^=xGKE2fABCp5Kyj0EZI?o{STByQS;J?3H>lY)SP0|^p z)rv@Tu2?!gIiL9o7ZvkW^peg-bQvOB7q5jXd+YKXdd73;naZJ$=Q;FL<^rgG?A79`X;6?Ns%n>>e}sT_J2fhwLU z4>jjG^o-}wGnGT{vLK<(yr?UOp79)drgG?A1gdxry{pw_4n5;J^i1W@yDaL|lByhf zSKqi!Mw!Z?cUh27C#KYuL(g~)JySXKE&^3NQ$B&`&{J0qJ>xm_rplprS&-m)?+HAI zp1N}A8PB0NRSvz2K$T;5@&ukkPhC0mjOWmsDu>>6EuIlC&bFz_p$CHJ&@-MxZ>k)6 zmjwxRN={ul^o-}wQv>KpB~?>6bLd4*YB4K|Rm=e5TAUCWt@3Y?t14#( zD~H}ipv9fwIRSJ`iyO`ydXe9*sT_KFE#U)cm4~kC!E@+Ee!H%6=tbtcM@du`JD;yq z4!y|Jmp()dWqIG05IOYnZ{bhn?y~q)k79>=@u=2rk z=o!zU*HsR^i$ImiXjVRW4n5;J^oGiz7a7X(S}Jo{{%t2zKDD88=tXw4ycQBFw_25o z=g>2rLvN@YdKZBzl}WBj#dGLQoVhZ`H$fC7DAn-UYDg;j$pX>m=SJP(FALz0Py!4V6RhB2dM9&|&oxkIBr*Y499+ zL*>xBuEqO9y!jxnYbVru6IP$Qu7w2efAQ9ZDizP6H+T-cp>pV51gh+J6wjeIcn-a; za_Ak_Xh(vNWAVm_@}b@_vF;BSfhzlbuHN8@wcg;dW*oe0#l2~puf#h)l0b_)Vcq{S zZ^__!OH}18`SH9Zs`8fntT_tjE}6Gv@Vq5cWnJBI*WJW zZ;86{mUN!C#8lprc)wEa4b^*>^u->T zx8&e?OVpLOr1QKbrt+3t79{LGc;1rE^Ol&(TXGSo;=42P=A_#7@w_FS=Pfanx8$-Q zfpy~FaevX)_-$UInY(9%F22I{`QI2Sz6YtkEGPfoTzVGudlO4%&NlciJe4CYo!4Y2 z+Zhm{pW;#SjO{i{i~3fdB*YiTzW)*@|0ZNXviIi9hb`Iu+7bHAovY}))EntPsdT@! zS7Ygy;Ei-uSKUv2e^3!m0xz3=Q+Hs2Q4u;?kcfG|f`)X8Q>8j~VYxZvMIigTbCiuh zmAzD*GW9SIZu*5S_KDQdg2c}~qUp#|&iWDZ?#3m0_1IvR?Pi3HKozzKKZ7ivft489 zfJNtswACEzv?gdBJ-1~YZTzbrZ{1J5im|KZE3-zOqI9$%p}ujc+R8kqvwmrFuo?#= zYy_%~oZCQO`>dvqQs~^r&}~gwJ^z%f+)oiYT9Bx?U?c5$EtcLMD~RuZZoz70NXE|b zK1T}@>Z_Pmsd}|%hwfZ8=ghSes4A<)(Vk6XR1cn>(4A#Cz1`fCFH%Pf5(~0!rW3YD zE8??XFShu>GBbH}q>dIO)R#9^sgeZ^V)OQ7HRE`HAc3k|KW(NRx-U~c8t)szX1`l_-~HUd@ck8Y&R{ti_>W@PNb#s%)z{Z2&cXhA}>8~;L{^08>w53Fj- zH#(~oVIxpwMr@=9>RUc8HgC?-ok?yK>lmS<1qm@?_!sh&kCoeMvM*Wl8}qwH*$7m9 zI=`BReLGv#K+2)tN#_17JI$Dqra}58wqbk)mzn!9+ z9uGEFpNOy#s4CNQ8TAXYd{ms5mIgH8@A2|`5G_ckuP`bfGrRZH^1mHoB;RQ#P*pEF zoJRGqe7yNSzkV*wAYT|S62{Tf6^u`1qHF}J-fWpg`-})teLi?r9pmRtJj;7Vq>dIO)K^25kIS$9johU^ z={=f8*a%czDm;s>{>QqbYQAi1B%7P4XXC3gT98oRPE|hsec9dEU3i=RXi=n%K-H2V z(`i2bdzQ}iJZrWAMtrIUI{7h5M+*|_o2<%5kE=tBMe9aupZVBD0##E+O{Z4^tyy%< zxn9P^YYWXkUPRk=8Mw1Rn!g3Xem2r+{mlMLqII+&ad+Z$8hs#2)g#BDA;zVZQ|ZB5 z5jFx<_ELquI;5SxHJCL%7OCUz1=nyfD$nG!b~4wF<<<+8AH<3VM(Sum!f`j89v)%s z87>Wo)HfXnWIGPn2~>$ux#`&k)w&I)Fn#&xuB<@QC>*qZ+HF}x+y-6Cc9J1ugvIZ+H1~c`8OfO+GnLk=RNfKn(;>Z zVKKDzvd#2GwQ7D*>tg7x@>^)TT2=i{oQl=7N$NeYP33r*ib(;?`1FrtShCNSdpaltg%}ey)U*~xf$ST}8qa%ST9LM}U zuXkYyZCA8oj$3IBv>@@@xo}$QlGVCB`6*oCUq6}Me9!6FQ`m#4XUw9NkFHkz@n(KW zqjg+fHn#GAI$Dsx5kpAY*QtyN`-`$CDKi*Ipz6rp5c+ceM&%={`E&iz+y-p$%nLeN zkid~o$ie=b^-q`UvU@*%V<3Sld(BtHOx1H6o!N|vmvyutfp;(=ch~RHRuAgU1~fTi zBT$8{&fkj9)yjC;ZjX6l_XS()Vk_Wm$IqRYG&XJxm}!c(LJJbD^G&A{FGs1i>anqx zQSReQT0fBgrVPxlsIt$Zh5v46Od8Q4{`rBl23nBVonbl+t{JX;WO~`lC=qc>tJwIA zjs&W3T_NP{&z+3cJ?80-BhNb&UA`cIamYr8m%m#Ii24=oBqPm1@MI zdd9X)@AaJL&e>K@RN*?$bBYcZG`91d#$(>PXh9R>H#V?Tm;2rZsj}j;47lPM6oh9bnVoa60DmH07gvu2WiCt+$cEIHRKl z3EbQ9%*^&<^w+;OHN+@E0##T-Li!es*Yi$lZKR!iNk3JP3NZ?ZjA%E}iG1vI_GS)_%u@R`k{^#el9ZIt!;Xj*G4_7m` zy^5p%EQpb-+8;~fX!5}^vPBDw+|0ib8m(IQS)hX*8amk=#n)Q2Adzlb9PQC3My|o) z*FxK{!GCPgAMd|n>p^U3eBR}m97c0Ce|dl|Mj~2}xOaCm-CcgMD%H^yz1g0uo3&Ph z&e)!WQH9U#eC$qa$My|4oiHX}wZ8_k4-2!JQBBXD0w$KfVJ%0#z6lA>>}Ezv<>Fx#dn~+M6wOUgh8AjwR@u zEtLAKq)qwm>;Wh8|A)&>+b@R_~T7QYPTT1JQ^SgR7h4g_IB&IzL zrY*9^sU6v@)(P6ayCcks+y@eWtC zs^Ys&qmC5O%E!9BK03R7IYHC|El4z&Ih8hkxJdbUUSNto;>^`u!UqzlTGetIZS!5Y z^6_8(6#Dm{kNXK9Xh9+*+f2HoYp~THS%&Gw797?@e;|RX@%H53+WM8lr4J-fm92j`J!wo+K3-Ng{gzEmp^JK;1&Ic;qAA&6`FORH#+S)C zMHl^n1geI0j;3XXT0X8Uc$5&>(ntD03li%-tf7N~W~zE*UUQzVOFdZnKmt{cscY!u ze6v(N3cX!Mv+uts+X^i9DAyYY%3%jpt`bT6OCURqI_t3Z_&yD zbEFTnAklyDR+{={xbktkOOSbd)HXS;kU-V=)mvzeEQ^(o_r+40MY=@Fv5OWYaIWNW zh8L5~auYiwh;fAks?5q;Xmawq@=<8QF)q<<0kg{x%;-;OaxjpEr}U3el0Y zOzw_00#(=|JUhBcQT8hT+4u)P)VH-261a-;{KPhdEoz@!FUx)4wNQmU%lFjpbFlk6 zM(M%_T9Clq0N?4SI%Rf!6RC@OAb~0zp@i&gf5-IcbWi#~3lg|f<5@`ArkHbny(N7h zfhxSyI5C9(ZrkLXhNuTxkifkiZ>zGC=*7N1hG;7!P=zxF?~kJ2`?YLPRQf;*61bn| zznWb!vmU(qv+NHfP=zxeA@!rD>IZXWmp;&f1U>=qU#&|St5<1yT(%VwsKObXzg_X} ziT-KSf3iQ&f&@NO@jNo)o_;NUwDf@ls&FOZZB;Y3F>gf==>siD;IkniD^K|t|5k6H ziE)Jls&GZ+KJped-Y)!*aG&=%T9Ck}V*cjj;E($Dy9G?)0|`{&&Vc_WN3N_!y~guQ zd4ItE0||V(=cj!EhxC0<*O_8m;k8hOI~@N0N52dDqJY=Z2U?K8s0fcnW$&;5a_FJ- zfdr~>r^dg!u%e~@_-Gy`>VXy{Fpk3CQM{j8OI9ca6K#bAs_eVhP0t(Cu_ud2A80`W zV_Afh=~v9GI6e~-vnUd%!Wba`m9)Lx%*S=hF!3CP79=nlDKcvLyDY~7&2B-X4E0^@ z1o2&M@wfG*@u#a&x&C$$x*&wb`rfuuxxVjheYx97(0EO+5jsZtuq?`-{EjzX$w}1y ztZUs+VLZVk#IfuSM!;L88X+b=0waoz_HV4s1WAGm;^PQTT9#jX;&X9)mCU zH=fpStiNj=Wu2JFQmMF~CeDXcPKf+>LT=9QZagcnU7s*I(mKcSAXMB}(ysgx9r8;g zfhu)6pnQl^fM*{*>u?I-L8$1k@=-9cwo$2OR%8E!NbB4{5~xzA9Lh(QKE;h4O)42z zN<>+w86Jd+4l5t`j-@l|-)m?LIqo_!kp!yLX^ryHq|H11Xu%(hbh_(Q#)DANVdZ1& zf;0M0>whvr_{k_<3svgWN%=UkG*a)&0*xVuU8hUZf`p1ED<4%-<<>h^8)UrdYbQ{p z&cc+BI$K(64blxYy2M6Ur)1KCgo;xuA1Xu05E(*vEmWzD8|CA@Gqc8k%o=GyLY-MC zAHMfyngHKz8DvT|`GfhxQ=`TGX@Hk)zddKizZN80XMB-Gi9^3kK$WwTl84o2^! zEF|dzRd~V@HjYGFXY?L~I(=8Adb>Zp@yf3u zJG$SM2OtSlsR*?4k+DP?WAnDgtQS8^MGF$*-W+{tmh$m#!fri%)~@V&(I^{%Dis%3 zK8EoV(HDaQ*#Vwkf)*rHHiYu=^j&_vLh?Z@UvE2sDiz;VJ{tY8-7H+bJG=2sw7frf z=83$P%1Duat9Y^^-XA%n{cw9QTgp$v@wzJaLlSl$DkFtKMvA-^5-K}I)k9^yFp>3w z*Fu$wS*ud*%s9im-=i<rt+9OID)KM}1kt2p!kEyYn~F;@4ueG2?VU zT;~b7!gJMH-MOmI%rcRiPNk1i?k7_QW;{Z=9QlHW#fiT)5k50 z(9wc~iu)=bHHQykEx*gApUW0$BT%I>#FUTfBZjaGkE690zL7dwkWdkCbPhdfhxSa_%|)a7i7)aS7(hEMavb3=cGyRNT_oo z!25O=Li*2$Uwy2h_QN zCe961EK74{K&WVxE;1lgJV_H75GpdIi3|u8jgo&8A|hUyIy}`N;w3Fepl^OY=sf?> z#rX%`6Idr4$F4IL9nM%}D^v*lJK(e*oE1qQNT|q^ zYF%+Y*lu(k)`p)CVozZYsu++Wnzbvy_Gc+BGa%4{1dbR&jwcpp`F>0xGa!&am5OC4 zAL1;v?8`@{I7>wf5;*b+dEB)gYfxu{+2qkT1`?>U*W9tZGfQ(|qWN*j6&)=|;2lhe zI=iFd><$T3+52Nl`~maNdOxtdpU&G_7hA!;evCUFY+f1LNVXMPkWle5)mG{(m5H-d zBv6HGm+Oq4i8Fe%Afe)A%7;3mXX1<=2~^?EfWJq*Vy0g8RwtIX$R*pJ0SVl%5R&2C zHh%58EaG;011(6X2%9REI-_Uej2;P8*>_|o^QSc;KNOa&ixwnQgiZO_8CBZQhUJ!{ z9SKy~_lYXM#3AxaRFq3z3-`M!!lrzv{1PhiOVEM@?yvcm9mX{=F6EhGicAh9P=zHV z@`<;ONPi>!Y4X>=2Y=ARrBiu`Ij)$ zRxm_16eGA_D>~NT~cfxd!uh``Z7hU(eRY*cWu!)`Qs6_#92hn8kzi zfL6_9f1m{k6~9!aQh8*C$Rk4nRrnn3%Ih;AuTQRONMQZ=uM{|Q2Mv)sh}S|DK1cIk z3UTHq8e(-u3ljFWTIew=0)Z?qpO(g50sFTux2oa;iK_P2_m;w*j4J zcbYi6!~F;DckDZvg@MV>QFQ%kfUp-vaoZb_Xe`iT=oBv7T!!qjd_om$FMeY7B< zPDzyybuvof)KXpxRq8BE`B0~?RGd_!1qpT9t9+;vUYP-b1gg|onDU`ck);o`AfZmJ zl@E1NEwe?CK$SWRQ$EybxXczo3li$|UHMQa?$QSms8VNP%7;4Dmp;&fgvugNK2+v_ zY%3&CrOv{X50#xD+X^j6sB8%3LuEinA4s4|orNhMD$7FpKnoHot3&yi<;>)e;|d8> zsk1QULuHG|v5OWYRCbE;p)yi@MFs>Cs8VNP%7@B&k*E4-K|*EOC?6`bMuV&uc`a0_ zvoPi3wKIE1llO=7T+M?}*+R;P$`Fzn5O^(Ask1Q4hcgRF`ala3D(lJW4`-&6^nnDb z)LEGFp|YuDwg_5~z`2qTm9ZtWMUX(1Itx=iR34cwW>K^tVV`$JM*OL@8}+A28S(O3 zs8ZSS%7@Cjm(QGNQDjDgI{oiOU*t(O5~#wSvA4s4IXK>zDD=+JZCccn9(1HX$ zQ}L5g|DpO1RUgO`cO+1SD-j|3nfCh3T+S1Bv><`chWxqq?;={iWX=<^`#r(H%6HA!Yi+zywKmt{`GazL0>o9Zoi!Aa~A1z4W(>)>G^KLR* zuh=j90|`{&4u^kP?$|ps|JXCKKhS~%Mn!l`=J&_uzPW+Y2NI~ly&WOJOY^ev3ExW} zXh8y_B81d3Qm{)0k0wAimAs=+g*#3{l7$yxxke7v#QlL5Brulc%p?0ax4aH{WYPz! zFb3$#B-bI6T+Yr&U^J4DDQPmZPmNo!2_q_+lb#-@$2Nq}%8qW1zu0lQx_1a|+gW$a zEpVJh)efcqj_TqdBk)>6D>&iuRKaWy$+?4@;!oY+;ymu=izmhG-d z%$lta(Fz?G(2;Xy_~y8BkUlQ(8*MUZgYR_h5Y2me0sYsw%fG=hy}~dSF)lb^-I&E@ z;+caqX8L?OqIcyNPnsqM(aN9%D>QExnfUNyxkQhNlN8D-cRI{#B0q=zFm|>lISS*kdHv2vlv|bASfb45d2*R&gIUhIVD2 zCk-|W?6_#_j|`a))787fXn5-=-@~JMKNX!%!#*|Q{jsk~Yc_LOUB6i?GBLCu(Q4fx z`t5A~MsC1#PE@Peg4KLnNza=yvyDJiV4g$NaXpka_`5JC#`G`4eyIPCo|)xmXhGu9 z%7Zk2LI}+g_7f-WG|J1CyPE8`iBI+a&L?ANLBif2|Nc;t zT^yFnc(nbVi3F-}924?Ou6E{`xA$q@;2`$#*fIJ~`e0fk**A_6V~^443+K^%0jV9U zqmR&mvB7k8zGuA8*Hs8HgO~L*Pu&_|BbL87LYEg0q19%;^?h*a810xfnAUIi4WF;h zwcBT&k85EboY0G*1&MKvqqGUn*-m@PhZENatv7!t5pA|E7hoe$btCO@`nh{BO$f}$ ziQjIdWQX6^p#HZyFud-zwufml{yl|1-~Zu@G$Flx^E1C;Y3a+1jTu^y2w!}dF54DL zKhN9EYu+St9+tLpH}mDGdNu-8Lx&!vpG$_)Z*z)LHOy9#)hXS{{Ap|@h884B?LABv zHx8q*DNb`A7si%jW6oSQCydN#BT$7a10l`(`mxZG@66Hfo|77ND*K9)y-azwp=}NJv|j-eEl9*nI81xrpHEj^$;*Az=(FAI zT5O%(qH9;CcRWmEcLmeP+oybMBtJ|GE)AibI&b#vneqtj+9{ak+I)@Iyi3dub8gWf z{dHI`h8863Be6`S$>#O*Kk47M8Ehj^)vetT`n-HF9o6*~_tBtJJ9Ao-VC`x2D25g! zaOCssoyn)EZ<{PysbS-71gaWVJVqasoJR*{5o7mQk>lo#MMv~ynOoax{%G4F8k#qR zruc8Ytrd7I{QW(%+4e_zgIaYN))tA?pAXXO{GHC+d4A>f*j^wrJMqs!J;ShCHUd>R z&+|T?mVxa}e4+ncqdY?k5|v*Zq*3#D-<%oGef0e;GwbO8LGSdgq>Vrot_*~<^vT3} z{!xQ%s{XHuJEV>DI9=Z}gx-4S=fLsC_ta^=Wv#ncVJ-9AwT(n19;`o3gPVoWevK;e z*8Q+5D~qm~gKhaaBg1Q<3hy+29yRWxnLc|)c4u{I+Z}~OT*u>d^SNL;pjSce<7H#Q zay>d~PUFAOjn_gI&KSJUC;n&V+3~=95Z=HxGa%86`)J60WN9aSOzwZwH1{7jGi`5W zBT!|Z;YNo2Zr(T_M_ZeNZSyXUU7Y#&4xr09b4(SY7fIdAHYXy1=g>x2vp(x$V(O6n$2$$YF7U6)uxPRd9*Jf_c zcC@%)8U@eW2vp(x$j=Qv)Mcky=V5=n>|>$@3H!di;mV4v=ew%xO6meO0#){T_sjWt z^kuI&&GE~4hV#<5aog$c|3=C=3THk-t`5m<4%(&bk7fqhW;i77*7$?&o-~FAtrSla zYkNhRrL*qW15$NiI7i_;Zzoo+m}Y*i7pprK^kHa00_S}G3z*~knaK`^=mm!kuo0-T z*Q57|FJ|r+`HW$!@-W=*;2c%s_*RRe_>wEg*%>Fh4RoLo; z{IM@JtGu>^p&d_at2x%mzU%8+Bm-MJt%9*I)iV<F<5rADvA&8?C|cM#5^4VSdbVoW%{IM8GPGR2H;hJ& zijyk55|7E8AFRI&*hgPYA8GS}#KWq;&~3+8Dj$9G6Mf=e9}?V4g{su+d(-bb$EqDb z^Hjg;f2`V@Abg+&i9Koi(OPYnC?6@9kACslWry&AgiX~gkUp!vMES^=dZK=FN()W+ zAYega-=YEZTsj_WmUnHlI&ZZ~yDMwL2NI}CU!@=IR@>UiRIS=eZ-4c*^nn&6ejYQ5 zcD*@8`B-%7l=iyia_IvJRK>>+r^zQwR`oczwWcoqFY197B*gW_e>>|Tt}pzEdLV%+ zaeZNP?#M(PL|udrv>+kcNz}{fL$s4bnG^4rDgN9@6RwQrv&`GVIA7sx$8!y`>&BZkAI(ghzfJNZf`s;P2%Y;OM$&{dtI^PCv3!Q?iNBu>qI0M4k-|&JztuRbm9g~Wy9D6_2~@3~I)FAGwnX{po3*>Kd~F6j zl>0yn64P@Hr(3FrC?B2Un;QPTe$<5zBv94(pCNSGv0&vRN9pE9>0bMFQ4h2rVWyct zOY+~mbk^hA@+!vA`>>6x|N(hYy_ypxD{j0>EqPTOU&zi+RC;<3tkuRO&%RA^@rKDptG%zK$X}>h`Y_{ zW60~|5&7vnd+V%{%FTvdae|x!MYNK)f?dGy}4H#OG z!26$P6=%G!kF3L4xSrbc;XW$VdjsK@boGNh$(gRd4U!n-Aq5$E$kt zrsMQfzuFeefe7@%)qvv^%3VOlwaVo(2U-w;qnYAx%Wk_h*T3g72O`i5R|E7#zdp14 z*k?{~PpcC9oVh(Iq~4LFX7JLled?>EDN7DV7^CXQQ^-E~XO7!E|B z7p?{zC-KKvcUYYqlIsdBh``b8IFDLqcH69aY&Z~sUbq^d-)`&lv-m1SA;W1ra#@9cSdvQ`Mw{XWU{m&JlrLxPEY)cKMZ>ADvqAI7bU2{By~Z?J;h- zlik(OO?~vZT2sB4-*Va4< z@06WhzLJx^!4=1+Yht`gS(3c_J95)kYSFZ%Sma~X zux=qA0=@Foj`9BLp5zsIIhr`OrpO_SpSq#0)+(pbf{1_e$9QLBle{nF=Y$yeXs;Vt zda3&QfPWUnk|Ua;QKN6VgEuRczC{C#7DRMfH_bbAG09t1dKGa@E1p5#E_hDO8&J)M zKrjDOy-{F3?krnlwr;?DPJz+ocD4c*X=@hfb^5aw~P><;VBE z<=;*x#Q9FQ=sitmgTFnJGLmv9CSAI3*!h}IrQntK#c#4DHX=mHmmU+M@Mj;YrxT)= z?9Vk!qXiNF%+6-eI~zPD#A`LSs0=GdENK$i*M~r_)+w_kc6)l?>$T-CLR78%NF6&7 zwe*X!?KN5u;V=1sgf#lloK#D1)otlRpx2G*SrUIr{lL3@*a&npPP(hHEclxn(8xzp1cxu|_xjmd2F)li$7}j=irB*1z;@y6j=Y=?X1~_`OZq z#NqT*TVpm5V$!*`I)A&u%c|aZ>_eazJ|XSVKWeSB9jv=7ZBz=47DSAnmp1Wfng`z1 zy<3Q*^XevgY`+^zH&U;go-L5A$CXgOGG5%Ts5Q-Xu$R35K{xm3r_Tbbst?m> z*`YM^5_btU)_Y&NnxT5}Cgc|Np7b zEA#nFk@2n1+A(>|Kno%|4C@!Uzw{}~QKU&NaVX_+!+{9&T5xDshPPde6n9G3(zgP7l#f}_L=I}xsj)Ruu`x0M* zuN+>e9Ed6ij_MkRbp*BYgBB=cnLp{cE z+8?~+y>;$cfa?ko=tcc1G1NmzVfsNg73zs-K?Kf3bjtDao8H{cB|^PDd@uCE`O$H{ z?%PPaM^npwZ9nA^l^7aPvsUj-i2LH48Bus9mg97+J6!+N#1okoPMXrv8CBnhPPK}DyM4m1Q9ql%(_ZSYTh#3?AIfZT*%Vq3 zLFZK^B%f;aY)u+n^GZY6pK2Eo=!G>+ipD_&wA8ia-5EI)S`dLJj?sC-KUCANeDu0Z z8k)_AK(FUY?uJTEPZb#|A(bN{RC25lI;VQ=N-=EOaQXMMZ2!Nm08t3e3?qd1ZwUIr z3VUI_(SB`Ge)(qZ>as=6aa@kbQ18Rjx$tS}>}8!o{5uHA4s5JB}8J{iok zpbIS+Mxd9!7M_S<^30*iZpL7555HOPL@w%M;Wv@#yE4>w(Sis(+lw-COSP9dm;U7b zyndYTt%hD$Bc!Z3-&96D&M0SGHoYWVSBSt9$4oDg&`ZJy^ul_hUCTOkWVO%7iD~s; z;kUCXIj`>UU3(-xb)e0@D_(Hbck5Y8dDF@7rjLE1(1Hl85z-;wsVeUt{>puAU;&K? z^hz`QP-N-4=PbwE-vaV9#jqZxaWq;G;jgQdH`2;1d2`F+#DNI(>bSaV}G{oKPBq~vlS!tXU<(Ua;YEyth#WN>pmX=yk}hZeT@5y`U> zeb+wS@AdBaj^RKAj#T1KNG`|i9{tt!M(>Bp0hZ+Z5+BTPh146^qB=}S zZV&ZJcAaNX3B!RFL{Pnj-zBt$Yh6OuJ9FB!IU>-D`a)uIzbeqJjy_T6JJaT9K?Jpb z_}xXnP8spG{!zW;a^FP+df^(C6pin;(Kp}NAh_?M1rhkZq7hZ=wmbTXBXSSu=vyb^ zSiu#bfsmYP28%M}gxMczD{adA6MU-Mx-J1bX2LkR$YtEb{s1?q8J} zX|x~$M}gzCyt~LaESAd`PSmCBk`@sE^IM9L!90l|x{C8eAecKC$0}+0& zRsYdxTf1=!Gjl zdZX4zOYwzh)8=SF1dall+c#cUDHm-Qd8qFq0=;m}NNc!OxpkJ7<3u&;yJ$fKjvM+- zr)H((fltd6o&J*4g?eNPJfuiLl^x@iM5>6>$Y ze*O~fK47Ta716WkJTX?G1rhkZa-57iKa^7nbu0RC)sH>|dKLa8Z6H3~1Mkl{-x5cc z3$5kB6Z?x!>XkyH1rh#|&y8#@Z;UHfwDX*dJ_LG|IFdF{G1CJtYAI_u^PGK4cKD-g z(I+R0YP28%Yua(t@^WtR-7AYssW{wMyI7;tvZmI9U&6!c#<}@ctSEAK*kIobhlmVG z*#Zy#zV97N!7-Ujr+;_<8a1}))YASr5xwvU>9=0qe(3()vwYDp{o4Ch8HngpI9s69 zll$JbAO9qd3dgd`Y+cJ0ZJM{K4}o6T-zdY4e);}x_E_)TE)?;aH(7)tTND=)AzjA0 zsHx(s-*$O*)38D)!zWT5%bH)!`S>G^7DP~lO>mSoxQl!yQ=E#w-cwEM*vF3muMQKZ zil4k)-m!w0iDP-|1!~Xf(dv4go*FH9-_w_;iZao=yeq5E5Tfbqqw0^>R;%G%T4=N& zf+CY5q)wq3F8@8X`RsO8YDHZi0==#*nI@iHqqu1P6~u9L$Q!!k=4`r8U$cuWg6fuj z3(EvzMRAJt)`(ua5z(~&@uZ~Q_;m*TQHnGiuLL9v& zWY#t2Tvn$mR`Max%U^QR`nat5u{&`hv`0s^Dd=g;ejU|@;J7uNxUhh9MVXfg*wq&y zg#h&_!7*2!yQqfQIh2`LBMka7Sm6yFyiMFQyq!gnGqXQv$^q-Q`2B4`If_%suN zkY)lA=tVjQk*t{@T}B|J%RmbvXeUMZv>yo}?FS;zi}V^IS^Giy5-+4LK?@>iM@aZI zEM7>%f(Y~?-HAxnu#is13+ZIgf(Y8#5CFiHbzEeP$AtCS`b0?BzOlc$U*hwg|tzKKrgB%!8#r8mGmW? zE?R~3S7<>5wYQ-5u^iOiDx~p3gwLye7r{E6AP4m+71EJWPY7EOLH$vV$Upb@J=Dm}Cy z0_R|(1oS`&7`_*J;k$%R3|U!Kv*w5OKBT`9LB&q>g*4lQ=V1SwNLnA4H9xHP!Fh?0 zBB&OszL0kQ!t)r#mNt4WYkpW?f)+%Owm}3n6V(@za^R~8E^B^RUxEnqq8&_;teGIK zk6_IYbD#wgq|p#T?FVy^)+fN4ALj5Oz>9WbMY8sTv_6V8Kddi73*MKsCL*X|VGh#z zD5Loy4n&|A?I??64GU>~6l;FC9B4rVX=X%Fi^CkG^--+(;c_4Xy=Z4#@D6-X`$1YC z&6*$PKno)1{(`kR6!|6&()wuD{4fV1(2MRbcn3bnL0TWpnjhvs3nHkV1Z#7G9HjNp ztodOMM4%Vdlb|wM4$}H)*8FgLpal`s-h#C`K@QUTXx98N2O`jm+FS4re6Sp(_0g>P zu^O+i1rgM51#5GH9HjNptodOMycc>=zZJX#ALJmdk7mse*A-e2fn$?)+zYvyH9yRO z2=tUGyj#hM@HKm>Z>YQS+w>!Von!yITq1de9sVOtgL4e!8+6DeS@XksAJX~=*8H&E2Ui@V^%0+v<|nB4A+3*O%@6B+(1Hk@i5!Qt zJ}zs1Snq=f^dhZ~U}aBG??YN2mo-1E_dyFHNb4h5T@%#%kk-d#%@6B+u!LB0L^}>? zeO%W3u-*qPh#;+xU^P!r??YN2mo-1E_dx`D`JalkJ}zs1Snq@Fflo+UAHm9=px%eH zJ}zs1Snq=tMBw+Q;XD%mh|4rWWmtW3KJji*TY( z772e9nJftV9cB8G{SpdZ2jgY7m)I{alWAdRIAgK%qq)XAnfxgJ9yB>WXhDRX!7YdV z<_z%nAR^GqekYnIq>T08cWr=kOwfV|`zEp+_S-oDzB$dkd|tsXWXoZ{&rP0}{Stl- zVc)2h!^Qy2cP%2&%YL_84jX4M9B4s=T^U#o8_O^ph(IqJf3O@jUZS|J(1HlN!m%6_ zE8&=o;Xnj>**J>juyG&5ffhvAm73+CSP93L3nz4O80RsQAEh~F zV)LUos$%9P`{iZOcI9N>1{5pN95dnXL9`&kej6IJ$&b<;GvV(+M4*>l0a^}W|MmtDzP4vLj%j+wx>^K%IMt!_CeR-!p(0^iOCfnIh+ zZaFAcqB&;5&>zSc&48iOrAVJvuX!;kpD@113L8 zbIio%M{%t9IRuVolOLrxX2RctcrWzA)qu&5(i}5^Z%)I32>;ALu@cQO6Zqyd2=wx; zA2>fsbIb(3ou5PaX9kLuXpWh{x3fW@7p?|Oew5~z33H$Y5jdJnew5;v33DIK;P z@}o4zOqc^Lh``Zo@}m^TOqc@^=!L5RlOLrxX2Kk3K?IIwlOLrxX2KkZKrdVknEWWk zF%#xM3nFkdoBSxnF%#xM1bX3Wz~o1HUs242InaU#9L**_D!?%l=0F5`;cCF-M+uIZ zFb7%?fuq^vN4Xp`VGcx~7p?|Oew52G6Xrk*BK$K0#Y$X`nb`a&-aj>c7rk)(VDh6} zj+xl}DBhQS4&k3mC|064W@7WB1b?I3{3yY30Gl5bo?}dYl;)U;&5sfsGqL$m;T6ZH zYhnb)Il}o-nqww5KPqg&Zzr6)On#K+n2F7g3M0^qVkLqjBjNlg%`p?39~HJBf?_3t zqZ8r$D8(@on;#V}Aw`M8B}cT$k5U{nvH4M~128i+A}CfOI2sbpkJ217vH4M91bX?O ziee>-V9UZAh^a!Eugoew5;viOr7+TM&WYpC&)bw6gme~BL0Odysn;#XR{3v1bqgYuZ!ue6MPq&Yj*!(DC;d~WVAyIym;A_gw z2~d8N2m~4`tY`PRd+U7F2-pqeM7A%5B_X)nc0;6}BM4>U~5wKgvz> z@`}YaKPrqsFUo=nP=1sM=SR8IBE~MU`B7mDBCOuWmYnjVWZq%rme~BLFao_O3o1bQ zQ6iilB^MnkyTs;4g)NAn{HSnEoBSxbxbz=OY<^U@cCkjS7E6Tlqh!-1-Iv(>D1%@N zA}Eh3K>1N3oF64S$OB7kepDENUigG2KT2NcSbmAkk1`1E4Tzx3rvT+giEw_Dyx5@J z5}O|tMxYnvM}_-aSmmub7r?5yO<%GqZ*y%`%(mn<+bNN=ovbF+^agA}>@g;rLsB+} z;%pA9x;FQ+`gX(NuU*O*kq4W29&6~)f(Wa>GiZ~QA}K3HbKV3#FO~zjP5y_Z{13(X zA80{@RmWQn$}y3nrc76yV}c0u!Y4Gj8Ip1{H0Neu?cx*KOajY6`5%(J*ytKQ!lm zpal`sP6@3(I%^S>W1=a?M01V_S`a~P!)kT=R5rUNG@`=yLNDrL3HR2YvmBJ0p(!^* zb8ZG&5J7z`A;Sw-EQ0bsH06IN&i_CQBB+P5zTG|*=SPM5E+Wv2`fftgM!8wuhyh5WE5$Hvu)*!;UmR{cWC5qXsM$SG9y`zj5?;+5ey}Nl}b50=XRYBWDd^GG#rRPFRPSKE(d34hRVT;cw<3?&2~(#E6&agl_QKmFRPTd9Mm41of&Em zR>T_%B5Z!7<*?bArp@tQ=tX^jvokG+&9w}@2g4Rb`1>y9M`_BB@@#&T>D4wr%3Sj( zvg&xd_M!YJP5DvE=0|aci?QH{!trSGqcr75DVrY^Mxd8f`CAUkkJ6MMrEGo_XX+RW zB5+=D9LkTM;Q*ZAcE?R^YJVPXq`NB;`kWHa{v5`j$Zi zuI)^Il%o77&*n#kXMMVFc&zxxAmvAC%8&AFepGl2BEmnSC_hS3ew4ELQDFpn;rKWC zQJV6jl+BL{&n1ZPk0{EIQj{NMIPhNR<)0HNKT1)4l(P9z;TaAQ{t-p_QHt`T3BQHBHOb{s4I_X_1lxs)GeIQ*96`}#)|xUQ~yXp&8udN4b=`@}peJj|#O%_+IFR?|CX~jkJ>TqfDEl z1ra!IOn#J0`B9$Dj|zm|6X=CsNG3l@QhtW zUNLJ}TGxXq6WTM&U`-f<{DO7GZuqnOQ)3M0^qvY-+vKT3r2qx9}dsfyYBsIUbQlphtY zX_FtN&gO|OYV)JQwTm_CUja~ll=^za$f7ns${@JS5kYxOiIg8D!ue6^k*rnB=0}AQ z=!H*c@}pE_qtwN0ew0D*DgzOe`IJccQ6iilr6*5GRm|o`g%RjQ`BCBiX7Zy1Ykq8g z6#w#%=}Vl$!n>~A$4Kkru}&wPALX*<$L2?cEr_59n-|)9p{)2!aV~3qY<^TS0=!7; zH9s~#$}_vjj>Gv;9xHfkeiU$!)(D()xI;<_YIVN!I+>{HQPjz5FGw6qi?(zQ0h# zUF@rO6j|qelyiXiKHHs$56`akp5`BDBI$j8U*V11+Q(cw&j0jG_1ZrL^{#iT>0E8r zdVQS1qCokr5lw$uJ1yuQ$`m_`dC-dexL+c;&Y zSYD?d<$2Yt9^p;Z>%7W)M(WtamENZJdz$`Q>%ls2>*GG=8lRSSGY)?1eYvNpn%RAr zuN?U7cqhjROl#w1{c4n|IcBJj0}-ox%=dDY>}gBhyV|RXOC|-iA9yeHYWn$nuhi%+ z<_T#Z=iczZk_lrB2U-x(f8`9X&X8V~qhrd0f!b|S80`ll(5rGKI=ALhSIhC$@>Sws zwxNatEr>Wca*|hf`~b`G^%s4`&OA4bE&~zh)u-=7uX5X9P1AdDU~c#F;%0^eEr>X^ ze6&~n*htHf_U1Pt#jS0I0}<#oHCME^qU$HN99e#^Syua6B^k!1#S`bm=b`P(xJJ)igyOqk#-6-Anti?eDdY!G=#q%QP zT8`24M!VToWE5Nuv>@Wrt`EIDH`k{7ruiwP4EyutL{oHwf z9WWedK}3!QgS}q+gZt{V&$;iS_&R!m;Xnj> zm;({$wc=zyZ*7gamZSgq#`57u(>*Q+S`d-??f%}+Z^m1Wx1!q1O%;nM=0F5`75{Re zmv%zD<=BwDmdu)FreY4XAfoEvVcxxK6D-H5^Yvu>`6R=E2=q$(*(ctHNfRx{__&g? zR`$OQ2U-vjUv{jQF~?}j@m{4;vh)1Bn#+L*^va)NoEQ0EwB`7^PYQVIDUxb_-M-mHz7rJ!+{9&O2|IN+qC{8%kj&*^W6!V-ZC6$LB#9%XL^0k_O%={ zH;i-3ztGZfAOgK|w3z8Nb_ZCFe7&@Izj0&3ffhvU6!X3Ei~Cp(XVTn&{H2rOKm>Ya zFFxOEnzg^>NYgN_y75m#!+{n=;L3p1B3nAC+26G`9Ed=#d3w3mp~_&(ak<`7m3#5q z`me-{8ZC(MuQGnyw_Tm<-&k*a__IO;dOdL0cx|f=6PMrVve0bFI+!3&Yt++z0X$^ z)D=(H(r7^h)-;`?xOY^-poEl~IS_$fxPEY)^^3ZQ%?DrAm52i^h`=60zfL(bgS)Wi zKc*arKrdWB(5kO#SGVxhyoLiUh`^ptr`HYo%-vl5g5f{}dg1zke&;U3HaGRkl%}rG zf(RVJ^czAiDtFfSjfMje=!NSCI(Mn2BMWp$QrsSBK?Kf3w0e!Z<~Bbyz;GY}y>R{D zIKBJlk#7|lY&g(@2%J&r)VHK(?&X}PJZ^JDpck$m=w!JbugZcW;yrG2v>*cC431M~ zNJ<$wB%NRmM4%V09~|e!4+_c8tNbLG11*TaHykNa<~?+qt1>QgAOgK`{XmhT_jAde zrzW`E9%w-XzNu*iaOkxA{jeCf(cV@*1bX3$gHB#7nOd$WsogV;Ox9NT8yOL}mLRQj zqg;B`%}RQ1je}|po!l8+HBL-9(tcz0#_PPIr#=?D%B0zt@bND1jYF{_p>tmPDta23 zS?_zjj9!-EAB7e~IGgBq=o=3cKklkah%H+kUHL%)?fj8XBLcmS{JG0ZKPgtczkU=U z9)0$YD)U=@J;5oceHOTH-Gp`Cwl{}~a|w+JvHRI%)&J6JwSZ2@`(n*{FN+u~_Ov(? zQ7z+MZ)fuuv24o4h;PR3@lGs_5xH0IBSiNG%T%g%`_(URwbE#5^UZFrNx@jrrrhcX zyc1=5H&?1^mYeG0v<5y7L_Djw+soNKR;>JfHgWtuVXIny@v@qHy0H&|UhBH7_pbLC zB9d}`Pl#D}PNmVZ4 z)oSwX6y<$Sg$TY5aR(6-k2aAlE9ZC)5%S_Pg|35$9k&O_+9MX4=M7o#zKrmf!|ORp zb}lwapoI}3FaGvVqTdLVrbwK*!&le0{h47*Vj5rr${6e;CetT%ehv}x;-?B-2NB2aej?q;m3&Xd zUgzUGh<1~sd`}oe9OyM%zPF&1=}Y+RAq1mqebr1fU%TpNy)@TU99HmRu7I`Xdu^i=_jFg8<-!RXMh>#Z}{OvLR%t%@F&JU*E%Tya9 z;=foG$zGxQdA@ef-c0XCZycf7vY~sln2>3FBwt_ZGLq(~u?8Kw4%XG#n-koZ)(p{n z-;jl`5gob?B64rfAk*(??&ClNU+Z^UzmkQYB;=sL*p^~QFx z)E|E;wBUXDI#eS;M2$B6Wrf8npF@Pa_)ekgAY#;xQF3MaG9Fs+zWn!4O$QN<^LJ6l ziT2eMdttrNwZ}F6uLxs7guMm?wV>h_QL>5EQsK1YC$i#&8Y=-s09%b^5Q29T?aX`Un{Lc zy(DD8`|@?DMuG_Hi8|C15fSoYj?i@wLA_mZZ$}H>m;WBB=^!G*!(sZ`OKr^T6RJh_ z3SBdLPGleNVy`E5PJHRNk9D6rbqyk9K?GmZtmN^G8std7{}WwcbJgb%Aur~5ZE^?i z!K4tP{>_p4&!-7yW|;g)dLwI}4$UhbzX2E#-=vDy^=LXb$nmJ^C|z#ke4mA%gk~ax z;A?vOc>LZCB7USZCw~5A&~u287juNJgNQ>DN9wqVKl`4Fy*`^0<&7?zcP{xfAgFERVqwyxSv8lgMS$r74(!=(**Jzu-2E)Cb)8WuDNtkDpHInwrT z>SLQiH$cqvF_MnxF=9LUvXa(T$N`|jP_49n~(rQWZYKbkhV)1yj z#MiW1@_4nx=+Jeru6EuYpm~*n_u^~h3ta~hw35-Gl}yNj2)+(+2NASd(xKH7B0^sL zRH5r2;;m0pXkL+_1@G%G$DlOD^r(6_+>J>uYaPGWYop>s^cPPfRt?(coq8=!+^>=? za_6#r-tq@=qI=4+G>cZeUPfPvt0MbfEXJcw^?oihHpeBJhg^zkM91$^6vn!&;XD zht!DB8M*YfOci-`|9)>nrWohm^7JTc9%75vqTJ=XQ9|FCw-YDlMS38|FH%1kE;eh(A z*DmjyKjTFGO^r9b)pEC2V`RKoKdXF1*DbreMW^D$(K!P*InLR=U39+hwtBfPoKa{& zMAXN-z0yUei{U$KQ(b+wueUBZmG=MIeCI=;mwRNFSG)Xl@#MW|;@FiZLKpn`b$PLo zqb9fB?OobFLuB87FCy0&Iwif(Ofl}#>WJe_c6-HI%@EVNOdyVz3JKjOeMy<6eny2B zMC3WP%ez!;rpTC%f624sd7;-PMhg_A5!=@WV4j%NsG(=r@zCqErTNZ71bVIgA<4UQ zZKg=mXVyCUT6vUHue(xD-aA`fjlOfh+rK7OycyX(@?q>g@2yVpV*IRkBUkAI-lT4^ z;#dQhM(wb9`E=Y$I_Yn~OobLi_-BSnkFx1>-&B#aIvw^Q(9511FZiT+$Cpm491j_s;b`8pk%G{p0+|??=?u zyW`wmq6Bh{_h-#!F-oqB1v*XClJ==fD(D#wTCU(#BpYB*{6ndQQm>RJ$wlC!rtRJ^RCQPKb9}5 zYBlcf>m`W57?9&Ecsfz#zLin6$}z}?KreiE(XZS@G}W886-X>HH@n8!x%Zqs-mZ;t z;@%J2B5)?6y@}82>TTW5i;lTo(r7_MW_mj>s~s;oS3FAX@xRR<=rdhDb651at`LD< zI1^C}Ib(g@r}QZ|O}mr6nHmxP6~L8WYUVWsoi5QWyd7=L|m)!jRhFbYuN;#%tgvODI zh^d4gN$6MG6{7iS;wxG7tIadZ1F2v2A=FaHcTO$j|cXM(%FRCeFW5)s&AXl@Ub)KMQ6 zaZ9X=^dZp8Kh7WAEu}Ay7%vhJ2;Znh1onJVCk&?ZGHwm^KCNEIhd?i!l^o|u>qs5l zXN$M?kJo*(4!nXvSw%MYzULSkKt(Ngc+1{HZKAg5poPMuiVC{;DqP|)p3cl7P zkYmj>k+@`)xu%)=o84;k>aw!K*RROGv&|9%e_dxROKQc7b$8bov>%baetNyJPg$8` zx+Bqoh;);uiAj4_88rQ7=HSsjdZd)eOG+S%#n`-$o@v!7tTaNfP%iZb)n#qTsUU1QZi2udT6K_9TZ=Y&b_9%B% z$%cjl5$H8w@;tG2-+IeY;NxLp(d_oJ^SAe0v>;-6-?`%Pju6MsN$+{TkFPJeJrIFj zSnKrrKC7#!hv!?#MpRd5K|~E_mN@oeh@;GrrD{%%`ldY)fnL})j`Mg)RatJ-7B_;P zYU7agqTb2{ri5G4t`$Y*1$zwEI{nuD<_Oth&SRHLjuu4hd~J<58^1hMyHAVALv3D_ zkElHmfnL})+!O1VQ!uzE@>88HJlj0gkmc*e%&v3Ieer4Omm@2;qO+YI3hs$$K?Gl4 z*tEbtRg?Db%SFwnxZD%}KO*FXWuo;}wI%Mh?onD(PvjOH?o2RG#m`=B=p=Jr?mZP2 zPqMwFX!C6H>xUIImmDpK;99635o@2S@70&&$#gjl2O`jm>##zLSj+J}wMX+gk5#BW zLKZ}DIntJkw;Z<36}LIw3%#(`>H9obSBiTgS`fjtTldA;mczD(7ite|!H^fWjpNwy zp?Q38-~IMVuy(n(mrFOn+!t$|&JqfaLEXuY!BBf3g2&^P{p0OZML6BuE1TMCo*D37 z=!I=VyZXU7QFBk^`KnKesixj}6n%U;*yi}Ogb0p7%_T<*B6vK$zbRNI$0zo*;wm~rD>U3>f> z#TFBK4o=w`yLD-&$tHsHEu?9`6*GK)_g7L?_A+3i>M4(sA^{YkUxLC_k z`1mO?G-{s5PlXml?2TF`vNoJ-Io=yp-Yu0TN-+l_&}-(ZNtUDS!q3F^a@P$9 zS`e{m$UJd;#{|ofBF$nk;>^c}0}<%eWb{07u>AzfvAbl4K+Kgiipzl(MAWN4OY~nj z(Q+(|Ka;qvzY!y@CQP*)TP~$i34J;n z4n&~W#aq)v_kL3?$BNRMym9$Xh8(m+gmwS`RmGM4n&|A*WtF-tNiU@ zIM9L!ZvU;N*ZJGra3BJ`xG%gvWu4`){mSKXpal`!kDI1jZ#it=H5`aQFYePVKU{A) z?D#MoXh8&z$NVGLSPnY|4F@97%Z$zAYb=Ky=ccaEf(V{hnmEfXhn-6d2O`jm=a}?? z<(9+FSB3*Eh~W7#bT)R1bX4DM42xuK3Bu0lJ#BOr7EA{Kno&ptxczykNVR6+p!Veew>er6!PlYhM8`Q1``FF#X%RQX5xN(8;Yf3w z{#SF#Ij!Pd=0FP~xJ;ohebR-;YkfnGRcIL@7OKe^>AJ~13M<1bX3{h}4Er>s6Hj84U+o5W!RA5&WFwF0_(@uFr7q6HB+2b*=fqLsdRf7tbo z$LpxL7bo&c-&|MRJb_pGUU;P+MxX@|dHPP_mA*lnmA;~tzIm%50==%iJcU>KmV@4$ z9a6^mbOX(l>8sM4;D<_v3k`Z#ifM;L%FoaG(VdgXt7LTIpL3 zT4i{&(l;E4K(7<;&f%55<)D>JBCYhzN(L>6I6G<)uk6^Mj3nD7?S<5SZ z%RwuBmsa|Q0}(#2y=%GeS`J$23tH(L4hJlVuxk{{L91|=R{Ex2Ap*T-O)y`tmV;LM zZrq6mC3v-j7DO-~t@QmI9#?NH+6*;MDV;qD}Bph=Muw#2=wAPhF1EP z!_HTR11*T)`H@!omV;LMJSUodg$VTGxsui^mV;LMJnx#A3|bI@Gq_plD^_7~zd{6h z;e6~kORBw3zg$M@m(^LMjf;7_D>J0o1YT2l97*GAikF&e6LnS;b(S0>`?kg$jyfC5 zx0&KO>TJ-(i^X%)*&-bIqGcCjzdvrO;KmVfe7@Pd|)z1oh=7N zoi#`XA#@-TFFso^HiUXU&c{qb6~T*VUSu7w)yz{het82&hs=EkTo1kt!VzIf5n&T` zMhhYyG+xIMVf$1R5tbAYc9{ba=*8R=5w<;%BEm8h3r7ngc4u455n;C&ItEJ z+7mYS#iym;bfS{ep0L^fKns^Pgy34BJz@J)v?nZSPuRrU5rJM2A`>QZhZaQOYS2VK6h%J_2O`i5#|>q&7HzJ&FAtUjEr`I?po!ur zisG2|Km>YW%bG}$qDYacE3_a2SA!-Rr70R^I1qte*h3xXc<}ZlpHlU_xKk@QBK2w2=wB1N?wanBvnx))o`E%5vFazQ3HzBDvH*cXcQvQi~Cz> z9c&`P9z}#rR1GbN;69cdHK3@ops2IqKm>a6xCyNWO=Mf7ZWrW03nF-|Bu5SAtoYoe z=(*uQ1bXrK53TL!YhuWkE=A}~U7-aLJm!<52DA$xX&1n>2O`jm=dt9~674j&w9{ZX z(1Hm3(l-$=Nf9r@fe7@%m70mFNs6kOzU#9<%mKgjP2`R;WlwqBcM*YJzWJD=gDyn} z7581VAOdG?{^kn(i`IL#&k{|S#(Vr1dkz*|S6^t)t1{OiZ~m_zfnKaedR92j+{ur? z`ywBnQ|?Eg1rhY5g8u(sI1qtecuu*W11*T4GMF_ydh>O(Mg)4{Ipv6o)@VTlo;vPF zpal{9gzeHV`j?U;0=@9maX-gjy*G%#8`jXhrYwIlYKEx$bf{)9D?dR|zf@ioHum653wBUX1S!@5ofe7@%8u33Bw(YkC;zXfpNnW;0KWxOl z;76bZ5q!EX{osA|^J-)d zY{FjY=RgZ0x_^`;&P|K+9u4bHnJ>xzqBSDW>%xR2aY)2_)32TTe|3eUmRmD4QgQqz zGw_H)3nIAZ)BjUl`TzM5=tXmipqav(G+@_S#6)YfAOg$x-w5<7(l<#I?K9nbF=E%7 zegs+&@!xfY2=wayWs=yEa=KS}Ql<)ij(@(RJd#C8-aA9HZ^Rj{z<}xE=-4E$bgC2^ z{0Oul0!P7rBhc&8(COl@=p^rhkDsphBhZ2foV6+ECsiw%R5XRIzx}qis?09&eWmGM zsq7acCj62lYK)uiZJn|zqG{P(Vv&ybvSymh`B67IyTg`j5-mo3Jwk> z67P~+c#`fi5%Wab<0(rf*E2=u~} z)M;1$NE#W)bJIO|zKZWWdOYnNpOzx2KRj_;JU->N*cGY%F>+3iS-MSr z8F%A=LJJ~r9&?<6&GO0PyUNSBxPv|fdf^+@aWZu2E4|kWy2Dd0R`Xt?J-n51-sJu7 zMfgUPZ-zU&Xt2EV*NjM~e5^t*MEl2Js;GgoeXk7arRy;YEr{^<-I)0UWv%H$==`X+ zd7Dm*}dxa`Me4(h`_NzzhG9XjcixusaiE-jfV*I!kN!;TIR|pox)k< z>_1-6*dBbcAD!^$@#%ipvXpmMyoih$df0vYY;lbiMEHB+l)5$Lgj2=q!{ zdbdc?C)Rr_-)S1Py=Rt?BZp2FInPRs7DV{R;Oe@~Wu|s%bi%~k>W@mhDJ~l4HCdED z66clk&3B7)@5Olw52vAV{(w$b%kuuuDrs{wg%(6$O*_t?FL#nHUx-$LNjrTA^unj5 z+Rfcfj#+%gTebVBLJK0W$Iz&K{DC~NFonC~t(3l!qZigXMWc$emlIlyabJ{&ePa+2 z_@;K8E?b((jQMxFjS6h@Ah4q#EXx--nV*doL_t1-Xn@eOz{TJ$q?yp!JkS$ zbF0-(r@DX8$~Pw>;$rVT;&VOC%d;&9anx>JMizOr!7G*{(uY7VtaZoH8|uoR8+@Wt zyphdUyNJN@InIg=AIJ=?XQ^CM&ih&ry|DMtFJQ*BkdJ=4t@5-O=j$bi@YmH>KR1`x zhosi0hvfDl&62 z#D$2dUY*6<9vRa&l<6jB*FWAWq0oW|Y)!{`SJsh{tupI(^TzuS=oL$RohwfDj>QV% zXi}$vy!AtB{itiaLJK0W798jP$JJ#0oHta9OsO>@(Cfj`Cy-TRB@^}t3{{{1h+wn$w!4VKiXW=&rG;GMMe6Z zyfUpuYP%LOzp&Bp*FJPPxb!JdhWcECq(*=!!%kDQRd7A zv3qu1gQhrK)De;JfonJrfnIlSo)^u2sADMLm;>!%Xj0l=vMjb0M`{F z&}&ufT_GYi1cG&yX+amawR=9mb%hp0w0-@d=rZVbWRT-&-D_fS#tV_mfe7?!Q|y6Q zJor{*kYjwKZbnti9B4s=y-x6PBrwOnAdHv&dxEbViNIkjcwbwlL|#Krh=)UXa7~E5m^nMA$xNIc(oG9EdUwl70 zPX7Ki-R>J7d(+ws^SwC{;pZ6kTAbUuVs$l6_wymp%RgVeetCzxX~;O$d_hNz7DQl~ zD8ub=LpionHhnF9N#7d>-zB|&-Y4eVn&R=B$Z@uptS{%SOQ)w@nX1r&2sSctZ;3DOo#+XH>g7(|ic@@;}w-Ypvyqp7&M%JtY-d5V6NQDwcTBmLp^9 z_vPpm>2$_?egt}9jX2H+wfe{<5BjNE4Pw--miI-}+Zz-4opC3{9Z_ullSHmjtPxrv zryC#_r;1UF_m%e56(YKJyd_TMdci)`>~DL^okdovLsd%p5a@;V<~Sc;9W0x^@pa;A zYLCi)KN8z2+==9;s$J<%@%M*!68Nd?-xGqXj8_kQBC{`=K@`w{4c^%i`pN%fBjek#iz;1XJn0F>O+h~wCj3n;m^G?mJxmG6H>VAiXH%>VvnxAOsi?P4w15p3&fUybJS>EE|p9v^5ygn!j% zX9meL10vAN&J32r&Y}`#QDZ@bol$Lj*qK`LOpW(KFZ<14Iof{y*gcwKsrzQZhPvb* zdqhHDinw?$L!@0_3toAryLCh~l+oteaV|I9?YfP}xJS!&^dZp8zSZnH(TOc42cZRSUy*Vt1RMaB{D zT8^8IkGgFW8mLmmI%%{Z0@n|Y^AqJ|eDJ>y3-Z_M%Ytok8xBOE*Q-nKiOWBHlNkIe+WX5@_p?+xJuU}Y5P|DC+6fw*OD4pA z<#Amh0=>4@cqB59{yibcajWc2xB9!K3lHiLw@@45w$FLN*@Bf>^$!U*FJk{Rgi9{4QlGHf*LJ|z!}4F z&L65LS5#kYI1qte{#9Snihvw)e4Ls>9B4rV&KQ)*TKavtrgjIzfe7^Sudm*z_m;f6 z;dN6Ev>*a!4EimL?k#1N$#*@jD@34|f1Nn|g?D7dj&nRN2U-w;GX|aFI;ge$>2|k7 z=0F5`;VQ~;YTSQE>M>sixINH<2%KZ+ccW^zlD8j!D}ckS;n2&!E@}L0EmaDA{`HPQ!r+^ujfY<4pgdteijlN5g>@MBp4lD!qEu zWXb58?wc#Zqt>i(&)o4Kku4){o^X|80=Ij5snd^q<62pP$ z5_|TDjUUE{tyRm>ckTG4E#<|e6moW@+uoyWN#b_j8A4YrTdnDhBwATa7o}cZ8L^#q zEld9pFY49hUCTlhy2(bBZ;E`!j;J`==h)OgR-Ea2IwEDsU1Bl)zGSIS-~WGzFX9Kv z*P3@1IWEspcrQedmPPRXtxI|qiYJ~JDjU7MQM9bv&xb%S+9wvgUtEj!is_W&ORZ%& zin-6OyvDP8LgFClZ?H_XyDNAvH@L$)W=J<#qRM`ER+qdAEr`IUrKod;{&MF0cz5MD zm3#>FqFrjid(y$3>TY)i$p&w=a8G_+PoV`7{&Ji?+EmUzdsyx6^*=?L9>MyLjil?T z{%w*dHZNA>Yxa5sX+Q)kJF<`tgd!6)tI3YjQ|e~vZY#7Pg3n5&GgIw(sYy;L8U1}B zeeCo>9|FDjY*tow1l1y+Ke_DoDzsJIxY1bi`LT44tT{uL&v~U&Pt94c!x!ul8OFtk z8f;osy$(~X^EopK>I`Le3jxp1bSha9B0CSymDXN zjQX`I`7~M(!RNoysjh<0fOVYrTD&X^^~r}x^E zdov7P?K=Ist3kJWXtZEWe<3I$~I_+S6R#I+hGS=H%Q2G$) zh2?Xcm$SbmV_uhP@(%@kB}W9-y5r2~*HTu#_Luj!V(WIja zEr`HTKxa-K=`DxssH8@SWj+LY;VeOQ^-4oozh`#Y<7Rkw$$Tl|7vurj1sruWMtt<< zyEG@BJK8|rEuBWjCrnjnL4)Tu=rSr)gD z&wjh@USBp=p#>2IX@@s8{f_v(bG*ab^HOt}Vn}LP;ou8C1bP*%xLZuV5huK;{Dde{ zzqy>#HI1Bm|9bcE?62Jx z^;3BVw)GE1Yt4EW5&phgw#O#-tv?@&PSN4LRD(b-{BEaTo2Ij!-x-+E-5=M|_kE5C z9FLBZ_O0}?(tv4hr*-vw2=wy5Ik*1PQhr(~h5RDdZ4cjlSU)&xQ|?lg4zkdtWc>$+A-3p3D$+=c}}ZlwVdW&Ry)eq zi&?$J+C@JDD6pSHSe>;&BPy)fHVE|M`!f%E^L4bgDo?VETV&Or=Dt=H`Y#ByAi}Cm z4H|i(H6qXpYs8O03nHv)_Fp)Bh;efSE3)aHi?OEt9Hc=OtZ;fvI%Lvu3f5z=meZ=~ z{-xwrVQMT^vu&=eGTZR^Ik5j=zhXV)zqbe8%j!_geUaPGffhtqMXPY4PZs%a1bY2< z$a-eTWmvwFlfLnDAOgLx*8K>qE2|eZwQIGibUkIcAAuG`aDU_fM{mCNk8||0 zs!0+5oQf4Kh~WOlPy9RwBGBu(!L z=akDhq5jF$Ep#4vU2=v17=trOh5jJPzUpNqfUN|=W95{>OZ0G-C zNybELv>@WYX9h%|7k*zQGjMN53nKh$(PWGtfnKL7YVk6)U7!9gP-5VDF(^uUt`z z71FGZMg)41GFq^bHK>jzWwgf%X;w$01ra!I=&av%X(TJ8SshKvXu)byR!8H!Lds}y zp1z-h>S$6%yR49Abu?NKfi+ER!Flt8WHG)PwP0Oj25hrW_2`L5P?00_Hh=b zP^^$~UM zAT70EO*QMOaYiOBwO|Do>#6;1PFiZ0HPx)AMhhZHOD$N{8q`yhmRhi;n)TF(KrgIy zQmZ%k#AQu2>#5O#2rM7XiLGb3tf^)_H6qXpdk-nkhTe3yuV^77W=!<;D@6F~YRJ8m zGOBh9S#Lxk9|FB_6gUoPsU>TwSx-$`YQg#lR@RV~TChTz_0*)L797tC?)H(ETC%2^ z_0(uV1oj2`orzYNC2Oi#PmKulA}zJxJ;|V+nzYoCHPx)AMhhaa795AP)GlkPSx=1! z^dc>_;8;U&H=MN8E^De;Pwlfnuk^L1Lt1K=HPx)AMg)41mRhiWFsP>{Ew#&w!4&AVXx6A$bBZPam3R|M82(fyjpUZ8?tq zFQ@y39ws03DW$I8doS=}ibtjeZ$>N$T#*mV^|4$_0-vRMU|TRlBjKh>74JU%v7bhE z99?yO9w0KUIBwTIT|PV?NZ3!x;&#JybeY_Nq)YeBnrh1a+=0>89~durX;GlOxMvaH zW%wdcb>bDlN?AmpS471{fyUMTFn6L|fEo2go!AcUtPaC8S`Z;yWDvX0{bo6S%a}s6 zoqEo2_z>VVW=DGQ-Nl=hqk@WI6sywNJdXq@m$J3nKir`|j(VMZf3f+0$1KN&BM(Hj(ov>8 z(1Q2H)^r?F;tE#ea(f^Gy>RVIG0V6+?gyV%kr~dW(l}~ybp3L3ptv&Ugzbr~vz~G* zk18(Lwt7{g1ra!INO@LTyUXX~lD#uU_z>uY(o^anxYAp}F9iz~Kh?aY+i(!wh*zqy(oqg`d zNnPcayG#2J==IKD)kT`JzgUhx7O!!06zVD$KAo!2f`}U*WE5q-ylpu)ZlCY2AJbRP zeY2zwfnMi7&L~nJy=^&${`R)J<3c~Vh&XUO<2XmO<5Zg3-#uM)uuRjVq(TcKGE~SQ z+WZyb7*~3VJ2+;5Y*osSKrjDO^}4oJO#S2&*`QM?H8Eq}z`47@*#~E$&#&eQoZj-t zmVEv{m&KkcgXE;RX$mcf!1B?rf6q!1hkNyuRpuo55a>1bVxGWfYafZP3-Ae&+wUnc z{L_}QQ^iyoEr|GsX4GZR9*V|MoL%!%nT2l8BLBFfw>I?6)Hpw4pLU$MiGy4>(|-5N z(2l;oiwGQ#GzP_Iu1-oVPc&`hL!j4<$m*g{{VR4v^dH05fe7@%zCiktAHHy_E^i=5 z69-xlfpZsWSnhxA7MxVclmijy3O{Nk>y8<4-IOz9gR z=!I`0$LTbSzH2{fB4^#0>RVYN0^bt!>y&vi$Y$x@liOb`=|i9wu7gSMvqifTzUwLP zkIka0RQ@e8@483g$=c|MX_s$CCa!-ZYJC$OF*uVGxO)7NC?)dIT(bI99=CsVFIhh0 z_rCcGXCgl$@8{dxk4oPWY4Y^a7r)6CX!Q8LDEZRkh}J2y1-d=GFM4hHE8?ehSp)0x zJfsr`_+;xxPkPH89f!Ja_nM|2ZcZJ@TJWJrJ3b-e_cmz*!&5&HTVpmvjEhSdxRd^& zSUGqsMRD#g7$&ooc_ao8a1~k*vE^3kz-8iI{_S)^d{4@nxdR5fYbVU`5P@DXb5jQ9 zrFtm78^;`nXOEC+{<%F*9nm(TF7g&Zi@G2megoL#JLse0{=(Zdq7!HZ13Am&XPfbfJjD> z;D9jG-3UlhF_8o$DIk&sB#gk2laezi2uRKu=Ikm(5F{y*lpsnFkStL^{dU!<)AJS_ z{`dFYwOIE!d%wNAD|L1EuBT!%-g5VRyoVL(d%Wp4>w3lQP$Y|`K(FCnq>lTSXW@VB zR=d%rs-D6tdhWbCr{X8p3>oX+9E0p(tHE0*%!b<5T&6Z>FS zin#MR@4ADAzZQ!#1AevCc&t0&SiHaVR0(U&fU^NSlH+8aozwfIP)|SWr~L(5P+|9| zZtrIGW~7MsKfIsbQlOXk<3jA8Pu+E0p?YoQ21C3zxApJ~R?j5Rf(q>Od_T`#!Rxss z-oKirC7}YnXveYGiW%>^msfnrb$(`BIWNoRc)vo8mV_2m%q)E@_I9efZpmf?S+VNP z%wE1-W&I}?#z?%&U>zKLGE>~UdG5G{I^^c-i0?Vbo7gj#pPyShT2O(t$!n^AJm8I7 zoYT*-q`aj-ui{Np#dR)n$1Ucn6}buTr}f($yzU+Qrh-HZDzM-1I{Ht_`M>PE?zL!| z!BU_Xj$@8iOH)jia3k2NNu7mjw0Q><%S-}`u< z7qg&*H6}j0DOue7Znxc%uMMh#v6&z+><$0&!j%4;grQapRBYzEL9)Vk+^=8V#Wk4! z*>Zl|=A3?)=|5Wv^ujXaS;hv(fA^c0{R=a{6KFvNwn|=WSzx>8ZGPDw-yoS)y6A;% zfnyBq>>Xa%#4nuvia-l0@P5Us$yep}o_e*G|7+p=Rx3d-Y@z&tv2G3js8`5;Z9`Up z<&(MO{n(HHx$U-XJ+KO16TeT~6ytwAs;s~E+iU_Ys3`yEz1Ug&j-yLc)jzW2%;7&* zzqY^ZUF=zt7)t zQ;*-g7S*5BD3w@a^d)_^w&J1d2+n=M%xzm%7dsP0ffl^ld(+k=j;wYQQJxg^Cw_Ohg5GJ$|G{3o5WJB()Kh`+*Ad!n=g6Knp4!->y)BUe6A>6&qXk zj=Q(tL2ilN$9*jtr@ZEV`f3N+Y5fzSA^iM0=e?A%oeO6UmHOwV`_0z7RnqOq9J+Py zrh6#aeZJRTZZVSPb~@)S+tE)w6@}nSLn!j4p?CXiq4U>ox*75%=ecNZF_YG|?c&WW z(p#d1pO6AYrXx8+`T0vqjhpFMk$r_HYWKh6{xYkNr9dzHta?;E*jS~+fz+WFGVpP~`ld>bO({bTKZU=%My+YMmZ`qn`1@7&TR)>j3o3G@ zP9JKR{+8P; z-f;F>XNBskbyJ5X^E2n{d}}yH!xWw6jC(!3(x=A=w4lO{F}QTRyzk$V8AP8PPUvTTFH-#7Jh4BVxRrRGpA83{D-%1&&IpJDK3PsCa*m6Wa9T zUAOmSm31F;Zxp@uOT0fSnXN!C`>dW!o=&{+Y;M0Wy&|zK@sn35^6johp-iDF{H*rO zN9tLvOYY1f*S50$ft4{5EvUH3>KXi=x?nZ+o_bl2+~UZ~wftUX@>>e@!ZPGtd;ZQW z+rEC)o&4FGvQYaBq1*gkq|(u0N`zwdwd30iAw*B1eG4f>LI74q#mn*90 z@=IkJZYj_UTfXBo9ooxhUwu=gTq(1#lNm()1MR(pt*HWMt_B5uXof<6q4eRCo z*T0LzI}45y*jM;{``S-Lo0yy4-W!dqJ0~h|#NbT8)(6C)IXV4n`^#Gj^uiKh%I4Rf zi&JxI`JW83%L*0tSTd>9Oz~aerhc(*hpqZRFT0ie{Z1~CZ)p#I(da=|ouk4YMfax8 zE>8W`*S}l9zJH(>-b);3VV1e#$M*ktr%SvpnczWcMUbL+@K6isUfxS2;?`fY@GVwV3=tNB?uq zPCyGPI1hl5vJ?JXJwxp3+g@iUpaQ-4>mns(K#a~XROIN<-QO{{w8~BhEU36t^g`&5 zx2~HEh_2h4i;nMg@xQD%)>5Dse$1#E4(KDR!EV&6W($0x8KF_{!R3iqXiZASaPyzGTHBNV?W1>rBn_} za4hty(rpASU-*N$@@EUDlux#J-GBPyF#;{9z_E*Y0Ka6CH}=2bPb^x>QlOV&r$+Mq zm{?95m@lJINCW*#o`H~SIyM^&z#AD$3idrj&oyKGqG^*k2(fgP=TX1e>Yg)Q{4Q0 zuXmJ7*HXYe1Mha6lRCl^oz7113XJb+-3Rfwc=vIf=4F2ouT3lFzg6*RmC+d7E%Ba+ zu^p#mpEF`t_gMe<`V`h#p#oc_<2(`CB$9O~r!xoeSm=di$obTzLSlFOT9NF8pgvH6 zy^FtKy*@@1xmG2Toe(I{%WhW(W_>Dtx&MZaffiKYsN^`aFI5){uDqmUpaQ+HP4oQf z&59y*Vj~>`EvUdziL;|$_>;bw*u=lUb8A$f7v5Kx5BFqhF>P6Qe==u4pam872sfwr z5gM5>-rvp{5U4;ee5U5-!3z(BriCym1ji4obEbrlS_K>?g)k*VDq4slg)k*V(?S#} zgef6<#k3-YFeQZ4D(NsOgef7UXd#Le!juqFYnv4*gef7UR{JYbh^=5s2q{{KB88v@ z6-)^swU)`(q!6ZrkfMbsQV1&0izy+b)=t&bq!6Zr2t^A~q!3;op=lwC6oS{pln_$u zn!=k z65=UZh$e-+J)YFMv2{!eVM+)oeu5%}FeQZ4%CsjmDTFB@zM_RFQV3d5!IThE1dQSZ z3-D7aQ$l=23sIyHRG=4ALP)Kb3zI^a65=UZh$4kBC4>}_;>@z+RhSY&iv2M?-{LAv z2_Z$12$MpX65=UZh$4lc1r>5Jd_>1$tpA@SBN(n@G_@6e$E-J5xePt&&%y5T=BXq85Zn zAxsJJ6fH!NLeRpL5K{bvx~a}rVM+)oCdi?Jr}@g665=UZh$4lc1xp%_#90=(-}V$O zM3F+!f(k4{-Y4#@!LFi(C{hS2&`UQ7ug#RLhHLYNXF6)i-OLePQ=ri74UTZBm=ObLlov=BuK z!RK0RyY{?Q=^d#T#FD8X_ zO(3;Cod5gF5|!hrSBjNd&EBL|em|-}3o5E~?@qb?{YtA*l^{`pUVL_>hyv)XekVvA zWpMPtJ1VLYvmleL`T1f5(CRBOR?GX_7mOo zx$_wXli>Otlo>8tG73jq!`<~_a!(SnMqZ?2>wzw~u?K9}mD z>;zPx7qbC^wqTzXT2O(#;PDFdVoJzk`XE|R@%SEv3iMKE%h$;DVgD~dq6HOM-cO|X zvvb|OpPqauhXobrrOJ?PQDUG46?=bMOc!&mXT`(h7F3{@>dn!qD(HnzNRL;b1r_-0 zgQb-qQGs6g>|-mu13Rg9*@^By^%K^K`8%oK^hxfXS~u6W-LRA9{xZQmIHUVR`EY1K zMYTRV>7`#Lxliri{!rV+v36L8owVlec=xq+Z~i~VU94wRU~Kz3P=Q`6zTQFC&P{ex zb)K@)R-gqHkG~GQ52{fj(q8RnwWKHs5-q4uqigh*hzj(2{9O$#sKB<6bWZBdi3;?> zJF2Zf3o0Jpu26wq_S1G!6wUD>Rl<(bqcBssh)GcV`)*;?(^T0d`G$XKDpz1Z1@pFu zNjF-JDqDeG>YCKO1-;ep1ZnO#+G6eu`ZsfUh{;@0V&HL^_C?I!(O!>_ffiJ#FNVizwx0TIBz&C8EO2YUq=F` z;jukpL4}!jap^v04yVfApJLS$Y z?SClHOPy`>c7+yHENZ%ghP*t5{#upkq1~EMfnH`7MNiHw^^l_ek)8C#n2D5PRn@iF zuBMIJNp*gnMCI?i@DOnkEvUfQcIl!5y?z+HlRo@?66N!re<%i8P+?z(+Hsn>YI@gc zrWvW7r}eJWYR75js_9*)nLtF$Ril8b<}z1J7_J&ISB(r;P35zY;i?gH)y%HbYR75j zstLnY3oPcnpH`Una};pZJm#ti!&M{Zs_9*)nJ7lgRU^Yy3y!3@Y94ddgyE_M7E~}X zjhL%O0awjqu9`4hwLpPh%vB4nPjl5g=Bi1P=WVE{szfAPBT|c8m?NPKrg)SYOb2cTs3L9YQ$VMz3Vj2GH{N<+0ne? zG;`IY;i?5Q7G_fgY8;O>S4}WiO&YFRFk?Z5-FDTE)67+qhN~7R&8c&4BW;Y?TS3iguA0YOHEFnN zfdv)JKMPuq=BjzjRg;FR7AVk*2~@;fHM8rq+Hsn>YSM7k0t+gbixu=6%~g}kRnxmp zs~xAAtEP9I#&LydR>WL23b<;5xoXmI)dCADu%tCtO)ytY8m?NPKrj0`)Q;24Rg;FR z7F-7^u*GPun#Wu)sE9lNfU;WMx0@&$5*D25L43h zuG4l6svW19lBRc^MhhyKQ$dH19ku)vnW)1wz{okj(EVVl;JG|7}Sz3a63 z+DC?xModZ5yH1<$cob05BvaD#uG45ydsIghSeu%XCYh3^cb!HBdNE0fn3868omM+e zGbK&$I*k@oV7X~ZnqW$rG?cWYV?kM&Z!8p0(gah|q@kp#456?E6jp62N}6CwnlzNO zK!ILr$7!adnO&#Vj?+v@lZKKOSWtnjl3U3eu3&r2uCa26OOok~Lf?1$IFOwCjkE97^DvMPZf|<%a)fQBkoH7%G31%u&R>#0& zp_j>SH8D&!u8x5gRG6GH6N3q6D&tqjKm~f4EL{`BWEJZeXhDTtx+Zg3$FLOPTs3_r zCfnG=Fxk<%KG1^4#oE*aGh%|7j)4mF!da#!mB3Z1DD4K*be$9Aga)f2mq#R+bKrfU1 zYhp0-Ofd6I8s?eGBz{C;GTlrJW}XRVo=L+z3l!*OvVTnslOrrujxbtKVRCtm!sG}` zl_QK6RG8d2b5AY+T(EnXnLIY8feN8OGDhGh*hMRLnE9pn_QqA*Q5Jn3Bd^H9FAY zLs^lzYN$XjJVQ-M6HG}HhLRSH)HpiZJ&Gx5f+=ajP|||_feP&Nnvy1%k|qr$El{AB z$rm-fmMLk1DQUt`(p2`Rwx9yXE=@@jOi9x*@L1?&ay(58rlbj`r0E!FK?RP%nvy1% zlBQ#z0=-O*r-{LoG-67cj)4|b;Jt+3r8ONvOi2@llBP1S^|8>4`92}0h?1g+YDyY0 zB~2JgT3|s1-V-&El$b~=4UsfZm>h8(56{+dHib^mbI;V2Z8vJ>S#VaU!1ksoX@V(f za#@&?7AVjQ%TQC&1XI$ap`@uSZ+#}Hz&@`jX@V(f(ooU@1$tpy(3CX6lr(85X+gU} z1&)uJk|vmvrmq8!g92NVR$Z73hWYU`uQNTQt%sdl@c@|>k85!nTh?!?(m}enoo>9O&lgvCL!#oQt zOaTfM%q9yl^Na%KnPldfFwC<+fnH2DQ>(BkV4g{4o{?dm1r}78719(i&jd5i$S}`> zt7U>&h?!?(m}hY1%si9KJR`$A3oNK$Hd%<7XB05cBs0&1VV(sF^kR}yh?!>;FwZ12 z&&V*(0t+gbW)@=R83oKU$;>k{%(Fm&Ud&z!G4qT9=9ysT85!nTFsEjMSy2D>=)=r2 z!OSyZm}hE5zn)E^f~ix%^=amrVCI=H%(Fm&UiO&C%rn8vGhvu#!3c*69J_dJM#2=@ zf3&~6R<%2w-|d8k<-SX~vR98~=2?iDXJnXXYF)aypZ7{XlTvq$msLuZjjUML7QDaW zksPPhq$zZ?P7k@}y-5NssK7flfBmVDPb^5)Lmt04)KZ`q6OW(|p59hYFpo@@XC9eZ z4@`S%rmK&XJ|nMv(OTmt40A=O)ytY7Gka%D$vV5 zD`vL|X17VjZbJ(ym;#r`q&ZTgIo_-BzuaQepuWP+|94 z=Bi2NstLnY3l!+Z1hZhQ)Lb>mTs2|1YJmk6cCTfwnq;mT8LnEOKrb9oHCIhCS4|kM zS}=;5RqnX4uZS1nMWmtDHdRg=tBlZLAn zlocwly=ktRV6K`pT(v-fUUn;Cu9{%3nlxOspw3Z&{ZVt(1asA-;i?4+^ujs3=Bi2N zs!79DQ#1lyqJ~mHhN}i;#auPXTs8jks<~=`1r^LcOJuGZ1za`BTs3L9YJmd1@R~GN zO)^(a8m?L}%Amrq0Vv?A3FfLv!&M6u=w(<0dM;sqC1V0jVuo|K$uQ4C%seB*JPR@N zj2>m4DfSLCuPDCWsltY&qrW?G{32F7Ocz57DpWjX zAw`LS3iL7@rYJGcf(pZ4iV_1A=w*0PQDUG46^e_+G`lD7{`p%)XV9@7WWf(lh`Oi7Cp0~P3n z{r~YJ11gwPmB^GddX$oe$3icrStT;fio!Ijq$mlJnTc`COeDihjAgRm71&OF;|TYS1pdYYGk-- zam-aC!&Qr8t{MegHJ7<+WVmW^@ckn$@=V3_v^eIfQNUGmnX4uYS1qvc^I4$amHu(e zRil8b<}p`|3|B2spcm6`;H;Rd<}+7~3|B3VxoTv%YH`d}Bg0jTW3C#%K`>l3pSfye zxN3ogxoUxeIXrR9Ril8b<}+7K7_M5NU@B7_bJfUj)#8$#=$WhLGgplaS1mXzCISU& zrl-X*SB(O$n$KJ{VYq661rtghN~7R(94k0&07QJs(H*+lZLAn$6Pfs zT(wx{s*&NU#WGio!dx|`q`6EU(xlr#z`X&zJ3grTGb7N(>H3T8S5eN$7?e5RxcLrDu1 z=*5JlIHsggKuPnNk|qr$O)-h}+?knYu}n!LLrIHcN*V=}G@mJH(ooU@3o3ZlulURQ zIYCp>e5RyHLrDu1=!NZAQ__5nlzNOz=8_qpF#g%N}9)%G-)Vlfdah@ zja|PLVbWCR!yZ%8L8)s>n$MIpX((xd z0=?{3!jv?hDQVJB(t`Gb3cCiGlIAldO&CgApg=FXwKFBnXG)qdl(eAjqQV|`nUdx+ zC5;RvEl{8rQ__N-rYUJ2Q__T?qy_g0ynkR{(UdfgDQUt`(t^H*3VSSJN}9)%G-)Vl zfdakk(q&4T$CNZ_C}}}ip~4lIAfbO&Cg=%ak-Slr%Sz)xlpN+{ia?F5Qfd&y+N2C}}QJ z(#TNK+{m|d{)V9T-7@zNrlh${NfU;W7L4sUXW%bQaZE`w*$HMRGo1&(U+>j!y*fjH zzv{b@947vbr}m;V3bR`psk{tSpcm%{sNK?%@)^{QY&xF-EvVq{cxu--6T|HKrejzN z@ZvlNwdJT8C7bD5H6Vwm0QbPPNedU3vn+P%)iFgxT$az6qKD(uoV zyYT54cr5hdyc4wxpNV01`qTA+7F1wuYD!uhQ_^${RG^pH0no%?N}9`*G-)Vlagq54 zws!ua7#I1P$$O0Kn&&blO&UsCU_k}m+chQ4WlEYfl(ayBUO0bXLTq>+MXB~tbJ@OH^lxq(mbZ5=@@81 z1&-R9lIAfbO&kqV(t^7edNHdbxZ7z;n#YthVJK;V1r>Pr(UdfgDQVJB(t^7slPQ9G zBA%_LqnvQ`MRN%OxDQO;4(sT?|pcl4jO-b{ZlBQ#z1r<0xYD${Rlr(85 zX+e)dFMJl|vkLDyDPhk^J@%o(9^1{nmQw9&iN``Ov#XUE8JLphF(plA3{%pAQ3mUr z=_f8z(kP&$`AkWZhLYyq$-ILMCCz>N&mCkaX)aUJD4?XdOi7c5lIAicjSMBtWl9qH|YJ`&JG9^tKN?M>mFJABLG9`^_MJQ<=Q_`fN zq`7tf{f_p9DQUqq@w$DNDQOf?(mbZ5Nkd5sEKErY6wI;-Vrxp8$CNZ_C~1KLy?8~o z%ak+Uz$&@r{C~1KLy|5HCCCz0@nlzNOptUm{$Yn|z8A_VVlr#z`X@V(f!cfuz z3v;7frlgUfq`6EA(v&p8lr&)|X@Lb5Ofw70P*c)~ zDQVJB(gFo~F;ywJK21pzOi7c5k``D{Vb=#!(ugT((ooU@1$tqh*OWBDlr(85X~AfK z3MLQ*y+Bja1XI$ap`-;0^ukfXahMh6Gb>Df&a5ydSh>suBgF(`ZkWqNF;YY^rcSxc zBcm{nY*NkS{?YixvhHt11X@s0snU4&3fFnN56bfU#EH57^m>2WSdOnV+ESpGJ?=8Q z&1ZI-H0-uuc89Y*=B>HRZlm7iU*QlRf zb{mD+ZC|8H>vuc%wshycs7P#q1r>Nrj>BBF5OdXp;i?7C&e+=RnGAE)h`DOQaMgk* zY*g5-ow;f*bJc|5ss#%4vgcRKRr8puCJk3Dm|vj+d$8uJdCXOlhN~7R(2MiwgL#+c zs`<=SlZLAn+%2(<;W)3kY94ddq~WRscNSD&d(&JskGX2naMc0@dfB~}xoRGB)uiF7 z1$__|Seu%w<}p`I8m?NPKrbu>%~kW5t0oOsEf@z;fin)xRr8puCJk3DP@tDxy8RZN z7h`TT@t^y*zxRb0P0OyWqwM|a#T`8{mNwVgsDEePJeIzkvXS!kZWhOxvai&p@3tLw zf2`Ht-_U6cwS2%F^vW;9oj*06&i=JV|E^qgJS`i!j%ux~$cmvaU!YMvUh~f9?&G6n zLATFHbXlXl@JNm`;c8(~s9JHa?Mr>E7^s-??Jzodd8vs}cj(tNtMsTx&I-LMmmNXR zo?oKRkk=K>dP|&J{JpDUpam66LxX72ka;FXY?CuI>-B%))Rm(Gy`Jkdgyv?PXJTyZ z`GI(=;i@=3G0X}pP1F!K>Qn4uP_7^pz6kAE6U>u-!VG5+r5i%JVq2^9k^sQ6<1NK*g8 zbzXnmLQ?-!3{;@kKl?_J`lnitOtHyH)L1#Xt)xRNqi-*~H+!q56o5feQ3eeM7bDa17P|R6kTP(1HrpdsUwd z$9Oy2Hn(Zcp*jXC&`XULs;`G*s8KqdD44mLB-Bn)A_q}KNI7x!Bxdu8N17u_9R#e^g8iiIwh>=XJV{)F|XUIZ$J43 z$3P1zj(s?v<~`_dVjS+C*Be4TbPQCW*VMP?Q|I{uOpLo{W_bCgcGFjm7F6^ZzmNtv z;ZjgsgFRldm96BKr3oG?&}+o%8)0Risd`kP~l7?O^kF;zUp^hlS^MY z9t*v&#W+r1kxAxm_Lh!;tpw};^|HfB{R_9N{sr^Om;QT6Uk6%HakA5JQvbqjH?G7> z^3X>`bXlPSy;SQ|@xw97=c^~59hFYk2U<{}+O3Kij-gt*YVoSIqXNBDt5xmjy(9}*2XfH>@ zR8qx21$q@tKA+CsNiZ>Hp%-CaL(vBqdvVRGHhI@W1s@P z)HSI1;TRL<{2yRvdG!(pVKi=VR>;~sB#R)*nRY(m?CD=``oTn zEk!J-z&X6*EG?Bw*65wtRrP@i^ipj~wTEzw{UtAo7O$*yRog`iD)3pvaR&XGPF|E< zJrx5L=%xCGYS-ZyP3G+tBRcf(R1CDB0-vcIXIg__M6V})^i=;q1$wDIu6lGhM)5zU zh()tD>lkQ31wI?{lkiW|MX#@t`)Vvf1$wFRMU6Az7^^lk6Y-@Edul8}3o7vG)p6>s ztKol@`=I!1$KTdG(Hgs8#>uNWT0iG!KX5>NDDwF@XFvsxV?6FYDCTdOoLx@7b>Eto zpcl??m=QNEwf|YM+_K5m{61PxfujyJSV$O{6VNXM++)&RN|GzgX+sR-Y}u+0~P3nGbhJ+=2T7D zId?7{11+e)QOR*mebHQ=%w5D)Z5I{jg);-k>BzZPxRbWX<*o6A!A_5T#GnuCFSuK}LGySi>yxpxK zp#>G8xp!z?>A}=z)nr!W9Q7qF`K7acS#9o8`>G|Vs7&i_PyonR}_ ztL^?vwCLv{^j1w3BlClLqIc82a(vr{@?50j`G-=sn8~rjTU??a z@(!gNI>xu1>WC}z`pQ#Wx@bX#9b^8D>Y~|&zH;J23iN7l;u1A|Fodq@7?+P#5Jwls z%PBn?5?WA!*W@@W`fLylf8-s_yEmkvm5jM=hvR$Mp1%^^Nt{cZW zo$75dxM*LQ=^+JrVcjqjuz8}Wd7_gn#4Qo8qfns}w7bhls>tPoWytI3Yit)6k9LsN zTHB?IiaM_yqe9I`X|?0D-gZRf-`-C48)GZbYg5ld6ua+J%JcdpzK*-~E{NLk@5$w# zHzc&6;&7#dbcxx6FX$S~-Km&No4K0&gs*)5fL+w?&xy3~ME=;}?)Q}c_$2ztKVPNt zz8zF)`xLr1Ya+*3-yp3N)f&qs)R4aVeh-amJ%LvKHZk^Y&Vw|PX>2pyNwIc}oX_4D zIhHqO{tylP`&0Vn6?Glo&b%XTENvkVaJxbUdg1jkPkZtcvP8N1a?4^{ zG4R?x+Pi!lmFKI)vvr&Sn{vuVFTO6T@|B|n6`vK{M{}x!S_sfN4WoY+{a#j0=gcelHvUtdoJG>zC7G(M!_d!&kSM@Kyr6uEM(9G5< z#@u!<%6~JLlj(;vB($Ic`O8ewndfpQM`@XxM^RLuSITb^sdmMAboKWM9OL(t1I5(> zj{G29eSh$K^XdDpt10`yn7G0(&8N6rt111uN^#XHETST(S5SqQD)IAqQ(iAI_rixF z>zt4MIZNl$mNILo5r5&y&|^NmJ!>`Hh>3~I(smJ*^jFgGpVXJ1%$dIs_gBpk-yLh? zrzpRSp6|AdO06#+_iys0)L`Rsx;?afT*cJOs86+Jv^%R({CIAbI68i=*t@xnj}}y1 zKD3xxk6uCR4wqMFRcgMt+;@|x^ioSpfnN4m&1;z;j&__ZHq`CtqXiX%2Q8wH`mUr< zxeDs6YL*gv`n@J974Ky!&)f?#ZT5{CH-`D5oM@cA?{}Dm2@`Q zV(R=tg}8GWS5m(9i|EsX>dL3q9xs~RNf2)y>*%8e75P73K}QZRrdc`FS^d&@tvDE( zFPfEYWhu}L%aC`kD7`@Ry7rYg9sizHR;V~$V;TL?Y#HU|rqMg-M zyE@gXh}b=TKP9{w@AuBQhA72X^a{5tEVsLTSJThm&!=nL#vJFP4@6K3Y(*?$#>W zKWV=1D~>bp?kX`YN386=DwqFFf%&vDah1N>zPaYp?_aIbr7$AXBI-9|1-;&>3dbmz zONh1UUX>lr-tf?Ziuw2E(YR)-Xyj=1j;!~#DdLrsPs#G1$NJb)F`nIPlTX?v1{NtT zuVj42M++)2HqRNxUlAYP$}69(SkzLWSB~$OQrDErs7eQw2QVyII$7Xs0r~N&Y`nu` zk_8o)r!A#P2bNN)dX-u6;(;vkUXE09=kaGO1$x=7WMbo|<&*i7%hP@?A1$aT@Zkzd z)npO9)kT$Vo|rQ7&#QaIzq|8W3iQGj%5PX^yet zu-v#^$@^kdqdM}b#?opfs5rfOA&p71g7&9YXO*dKI{EyxO0w9D)0P6gu-qIc*Hd}r z+_f*riUp;I7E~ zjfWOg>^{PGg%peEa!Pd_ZPV12{~Z5MTzg+y3iQH~cAP5vs)!!LR*S_WI{0{B!aE#} z`TXp>cbsrmoe_V%`i?!e!#xrE4X@g25fXE={wdzA^SY%#FMHgblk9h~vWg?qo${#5p7F6IkZ>^)Z#`a-%*3g*pbM=?}zs78$5r2MezUn7w z5`46vqEolEl;-BN|DixHJ97YIpam7NwO7&Js^g->70|0 zU43aJbzHGH%9W!96_{m}6hWO8D$wiqX+!Cc=e~>*11+e)EGs((D$wiYkwdA@rKwS3 zpciIVJzjwpRAA1OeO9PIuW>m?(u@{kqns65P=Ps9b_`UYSKAe1ss8Vg451`Vf{zwd zV9r#Mzp6o0pjU-D)97%oNXAx@Cc#GwDllg%$zR1l1$w>AZ}*(#(PE$l6__(+$3O*o zExo^(y7nF!r9RMt3e1_ZW1s@P9zXh^1r?YxWye4Tdf~|DI2UfT@t^8>Slq9a*25gA zbctK&sgI}VZ~vGx#b2twf6u?&<)HX@dNu1S87lf8-9iPfPodKB4fuZEvCz-%)8pz; zOtt>j*p6p%deCOdadjpY&hsKGrhnAPOMPW0O-k0sM++)2C%|#$&z$dNACgDhd8dn| zK(F01Hd7;-Nsare80A0v#%nm}1+inv2R>R*u_@~oy0Lu*9eY>JEVDOg>ARKoi&cvU zd3c2he6_PPPNg>Q)Q_{v>fVRV{3YY|im!g2ZIu-&hO*k7K9&9%t8&$fEw1YqOGcvl z%l0=&^un);j+0oUwx8^~E#kMAl37_6s2IU9njM%*i%Y-CF@A37`RxX;7De96=A-4? z&$rNqjnk;@&YE#{jCAv#_5VorrT9B_X)6XQ-gvzjr^Vj=guKSLqKrg!n z#l3d^KaGDDP413~!}f|Te_O-N)bjoWE~_s%1}e~kimi7x(zelKX?Ur9toS-(jDO*) za$;1E=lyF7Q;SPYo+AHDE>C?ux%5MRI{bbvZw3F}d+P7d=mt-ET!V#T{3;!CilS;xm69Xb~`dGC{+iS4S`oTZl~#;=>N zkTj+K}8~~Ur2K+u1|Y)R<|<6`0*>tdcO<`u0t!(%UqLtgs+KreohtR_dm4T z?Ov&ZuPhb5oFDh>i+S~xPm=TFc2&x&&nj}ZVMVd&Ke(leRnTV@u_$#!@iYIfa%Op4 zlho?U%Vvo2dvE>IT{6AAr9dydCVq!phRFKC7194~siM1HSO(bVGeec9p? z-_7^XSzXB);}>2v)J;|AeYK)-8LH;vvpU52UHj%Paf`3BuLHfXM0o9M z<{1Ci_%x#U&T>B1^D4gDUfFJi_I3@|AjdX!-ua0b|7h836yGPfa&19{Duvd+Ef3vJ zp~@;h*T>0Ef1uV$rK=U_rOv9_-1(u`xSqm_nY>HLVpD?=i}HHo%lV-<*voE-g}JrA zGkG03lY%SPF;J12%WCNIfxiF;|SA;X)pY zTVvNCDxTyRWvUkqef)xo(U?oOVC^qMQ_kB8^eWGaS-+)D{BW*P^y0EgwWvwrr4%tf zTApXGJazW0pEfz%N|Mg%X37|UThVzN)c@o8qC)+i@ZNV?&HbEf@TG&D;@Vxe&kDV; zjXBO3Udh2LIy}gAc2$m`xy$I^W+ZaMS$Za)+J$^-SLIEcJE#6_MprkSfo*cOU6r$q z7LyOBz0CYUt9d<6IFsB{ndE3eg~@a?G1N*9&Q^cqtkBEMYD^515wByQ1r;XKEfOP~ zb+2Qf0=>-a%)~I6{W=C(P+>CNOboMnK*vA@dYM_KiD6bK=on~0g~@a?G0Z9m9Rn5U zWoFAJhFNK$W1s~UCezKtFsnIq3{;?(nf03(X2pn(ffiJlOg9t5tV+=_P=Q|N>BYn_ zD_`^q9<-psWV)FcW_68T!Gj9)GEZS9hFQTAQf(J4s4$ssCWcuhq*w5u0=>+0qKRQv zBIy-8XhDU^bTcu`Y9~^?78U4ao^eeKv!Y6<>p%-COs1QOp;mJ6iVhtE73gK2)lCeu z&P%9~0WGL78FVIwSxcs4paQ+jI|ma(t>oYp9eOo~$&(3>aN!JWJ*t^(82xv(zV@o% z6&+Ho=0J2CG1N*9 zUeV#HjCfR_m&utjG1N*9UeQ4+BOWcNF!|IbhFZzND>`)6Ju1-4{6Y5s$3|YtyX2Ffr6h4qnmW ztE_vppu*()nX*zVIe0~f&g@48dYP3ZCWczc!7Dm^RUc?Ug~?kqG0fT}y+Q#M=w((V znHXv%2e0VxRog`iDop;RiJ?|<@QMy!wOv%8msyo$VyKlIyrM&w6e#wUUEZ zbogpD2P)9ZtV%L5)JhIs(V-;Yhpuz9pu((5GBMOj4qnlr%L*0fg{9y)Y9$A+=+JE!EvPW7t4s{F zl7mMFedVY?FS~TrN)BGpAyo#p$wPEirZtZ3CRb7ao!4gYN)BGpp;vRD1r>NNaU8Xh zgI9Futb0_Tm&v&_G1N*9UeTd5`_Y05yeB%2TFJpHI&=(FpqI%VH8Ipm4qnlrW1s~U zcyDKd8L#Bv6&<89;!$CFg>zs{47HMjS9Bz*tb3DBt1YO&ISN0q@JbF|(V;W@QGs42 zm)FElD>-;Yht9f33o3A~#m_ptl7m-t=*)gppqI%>HZjyn4qnlrW1s~UIA`P>7GBB0 zD>`%xRG^p1tu`^#N)BGpp<|#06*%|hY${&K!7Dm^RUfE8FOwr~VyKlIyrRQXt2xku z3Y^0`j#|mVD>{5wU89eMUMAPw#84|actwZ44z!>GpGA1BKCk596&*STD$vX1?3);B zB?qtQ&@s@03Vf#GcEu|>ctwY<4^*I+S$kk&sFfVNqC>|(3o7v0kYn&l4qnmWsj&nV z=w;qOniy&&2e0VRt2xku3VeFy>^5G>!7DnXTFrs;L>#+tX29=vc_jz0=#XkP2U<{p zqmtvOl^ndHL$6Rk1$yBO$8pq34qnlrR}Y{C6*ww6j#|mVD>?*ZtLr-pdf`lscZ%he z9K51KXZE876*ww6j#|mVD>?|W?sW|G!Wk!LfAUHWUeOU!8S!XA1&&I*HiK7k@QMx( zRu6>lkT4G7%*k=oN)BGpp)>m}3n*|@avZgigI9Fu)dQ$NFPu3s3yD{9@QMx{11+e) zQOR-CN)BGp;j6Mj1$yDkiE}1+B?qtQ(5nZ~f(jg!_!|qaV?wOk7S;?DksfkT(~MT za}j6I{oHSnn^$LMzPaUXSGYa0WXx#ARQ-h)PXc>AqT}LR_Bqi>S7@(w(m}GZ**kFS7hQ(HpU}qmLF#@x@}gwsnPj zE|)s1ZX@Q3p7S<%BQLkK6nVf4%g}M&J2p$CD?iu!WshCDmZI!3n(@&xck((_x;c9< z5Hm6@_O2XlZI$k4;Dt5oI1BpC7YqI^G67wcnfZLhMKt=<3imgi znc3rwJv1~;G4B)3%ru!NuFCkuax+<0uFC#(oLLQC6Ef`-Z_t}vBKcR^f(k4{UK3Y3 zR_tD}+H3nskg=r|=w-6EbT4q63Qe1fZkJDb-?wWK$z0YJRG8dI-B~M$R}rp zct!clAU8@!$9Q(H{cb`@`O&}Mduh`>xVJD1I`a`G8VfnIhi$&uwh z@lMNU{6aNy`Dj7K*er`E^^6tnFrAsXsl`qq_dW0D`Z2$yKrd{ee6PKENVpqn`kB{X z_t1ihOPoRZ=C~DZ3eKQ(oL@%>ai?ZOKh$ckr9dx}e`#v4U-ma-hH|I8iXFCkShwdV zuApKk7r62Lyf`d3$65SOEt&4*f8Oa)(rP8B$neW@%8+c48_vv})HX&gsGHG`opjn# zpcj@Kw_Ufq+H1!Jiiq6bzxbwc4)4Y!VRT*h1&dh+9*kqYUgKb`X0efX-SKrbAL_-kLM{UXiy|GeH~s#|vh zRA9g1eJw}M5;e~y^M||jECqVmBiz|DQ^d}UPx%wa26^Fn^g#uV^HDQ|^qY8-1F3(T z{7dtOK1mZ~WMTvnHRN$9JI|eGy%jEk-iGgzllf|mNOm=G& z1zJ#HvS$B>0=?|7OG#If;G+cj$S5XGs;<^ z1r_-H(~f}(^fH;JQDUG475M$rj)4mFGC8+VVxR>T`2Ew4feQ38xx-Onpam89{nL(t z3iNt>D?tk?@cXA70~P3nEtL7YDMonH*8Jo4`KE_2Cv2u|f6a7Te^)U=Ptspp>lWBd zlMl{v7k;T`;jjE%%)7X0raS(pcpokJUJS=awcmDUw^f~A<975OU@6ecz8loI+{XWt zcT)O3YdX(l(CIG<_`RjVcUx${vZ?OI?^Q-);WaJ&)MNI0!%GkF(1HqlLgu%exf=OH zr|tAUyCW?Hdad5Eh0Y(E>UOxTG8)Tot?j3XP4u$XcYL&xQ#;S}yQG7FD^N zIbTcXPso_yEo~NLX6n|5URZAY2C_+Ee_s2kUW!u{Bl)8GJuWJ4zq5tzd^O!&TVKVP z_(VDXr9xkM{kj&l6zFBwhsn(JR4%8f4L-bBaOw_v!N&X~Zvs=ziApyuS8sin=26D_@9yB|FOp zd-u}*3}dNMvW&485A3C;ImS|rMj2zDIdYJ;?jJ=?Hl^6y#S7i7mmtdg*h}uL@PG=e zPN2Jdte-gNZpOU<^i98vv5Sg7pzXO6%pN>@Cge!$RxY;~Rj!{z3o3q8nSdqw)7?5L zI7Y4CS8ra@dVT21)d7|Qy;R2DHQCR^$o7>-z4tekZ%s)fv)6h+9hMBFfmsX0cB=n? zjx-!ZPrVoy`x`6nO&>^Cevac9ZR`FT>Nx*xx#w7BiI(5l>%f44bfJ3rSUeK1+S-30 z^zK?;E*)9Yih+uwtloGzfnw4W;usrWbm;3Ux#fzs^(+N?VHrBk;ExA|+LlZ!Uy+Ti z(nZBVj`3fw1X|u8E5~?sWxLRvo<~I63LjVs^um&6BG6lVXg(7*uB?v{NV%8?JP|B6 z=0^QInz}cLm-Xhv2(+LA$t1jnH&<19ZC7`BspSkyfnHeZ{4G`74gLI6yqq{bMxX^1 z$YkMnucRD)t^i<+;T; z&I`>aipujpkR3P8uoURE@6>U+c76oCs}&t*w-lGhy(!zDN+Z#NiqG;~qGkIA(dbViTU)$(@ne~RYY^)Ixi465y#8ZGHIeLvUUJch7=ad4Akl@{J7vp@a)0-dLnqk^ z^uk`iceQg%#Irfl$l`Zv$y4d}(Z8+6Qm9Sl*tSjgQLQ6mDO;mLv0Gm~L@_Hy(_CF2 z4QG)U-93l=eOqOT7F4Wa^=ejkZmULyeNQeB71HLDLsM0;6zFBwdCRoliVS~0Bd@M4 zCDDS4i_7-W*jLBVhqcRb48PbGk+q~NXI9B-DbNdRmcQeyJ1f#Qtsxs6`_rm(RIH$V zwCw$HboP?!A3gs3Q)D>VKo&kX!&0CZwl~K~RxXwN@8YYnK+|bfOGL%javv>fH;x*< zt9Eg1IwPGdUHxsjb7(nBfnG=^;qN$KwH7(jtrGM_dx>{4tWEo_Rx8ag@yxq_h-{Oa zNVK2=Yu0g&wQVMDA3Y(CrEh5|(976mj(eUf6a>1ANtdRi~IIcL(qGf4m<-8j7$JhaK$e4rl?JJ}7J+)TZ zy>zj}82$U>PxjLADP!oV_tJ2EoVorJb&$EmrQPuoEjWL`Bk`ApBPqnZG>yftPxQ88 zpaM&sSB&KNh$33CBPMdM&tpoJyS@YGR-QEvUdT*l}v_Pb(HJ>L%OvpJCl=@h*zv81GOq;78h( z&`2I%n?|Aq752O&|IP>W)5q22?HYwG1$x-axM9?S7m)W7Yr!ktNR2T`@7=b_#gqA1XU3fvpij)4mFvUd$l z(j>_17f-qkzpkUNV@Z!c-Dj(2)4$F2ML8?9pknE`>#kd6b(|`NqzI~Ap#r^rU%cAA za;9sP7}qP#aGjQI@J#gYIs5y>&L8=66a`waZXRDBs6elbCr`yrXm%n>478wv>)Yl3 z{vQhT;@0AFtBIoERzkcNuB%Fs>zsJcTK$`AFvP7y|F%mPEvVr75Akla|3iUZ>PS0I z-Hf8(5+!c!q|U0dV%#3bddCcUZO+*eBjCddr>H z^Kz`Zj>q>8w4lQLPE=|;MihniQYFi08Rg2+g2y#y8+tSbD$vV}5>aAc+vWNQaSghr z27_K;UkCONRH$o+-bzq`UR+PaJ6r2`b_}$jf@_d?SM4Z@JiR`kxa;GzUBKg z#cd%NQEdfU@VI<0cX^zN5(5?JWlAB60>=z9N6}t5#@J_t7F3*m>L)jQz5Y>RpaQ*A zA6I?-(XuiYS6Pfg|29X`zoVYjBMO{%JzjxcW(1EC11+fF`c`vPdh|L_fnMf!lo)71 zg_)^EiGd3A!r8KY3K7Cx%Yoo+K3o6Vk^M5GN3+G+-S)m0Lraq#?Km~f4+Ki%5 zGqT7G(ma1?FEdknj3P3xMTL3ZiJ~xfXHu=f+>!NfbC1%$?JLJ);aK~BJ1bP+sBOo< zW1*KB`J!A0T2Nue$N!-~FKj*bS)m0LX4H-n0~MAR+~MpP<3dYlU4swxvG85S%ePk2 zru*UN1Y3a?RN#~T;}z(&>c}cOvozW}0JNY2-woI?@EsYx{lZbgR-gqH_B*m9O@c%P zdSMwR`KxDVw4mbgZ;DWXURct04Aakb4Pu{Xuen7J9FEdT&|)j9KEn!nbfiWF?<^H~ zu{xOBJ#toHc|;K<1|G}&)?VDE)hs-U!m{uzHZoh{5uBnwpX2C*BaV5>h!O+uUij7- z+k$=NXh8+ODSo^Hy|7K&3cNzT<51-Ng;gRTNswqkg;J{jezeX}fnHco5Q1AfT2P_t zLY?uWF;IbCswN}PC3XxRsnuH!eJu0#L;qHPkGxHIR1vYD!n|#Xa#m=;mhpd!feLJ6 zk3TE);`@qvj*fCxXhDUVXQ}ztqos=q^un68&k8N5Q1ehV_j)u2Dl9MPkG$W+urbu> ziM{Ta%AoXN2|!&vvP|1!kl8(MsG>o_eYWv5B$2l(&YnM23wOi5{TxAJqneM9VL#jwc(-3*=^`|m3cXivjIuFA65 z#eW~#VxW7o__O>R^;fnyYOv*XzjyJR5-q6s+j_pgUUNJ2+A}Hr%7vOr zw4kC^=?9c;b%LvMTO8+`&)*B>ZT^GzM!F9z1$tfM7&HDI;Qo<6BP*_c>4gT=OYmYj zPX;Zhz^@Mc{rr^&TS7w|Pi60*0=?9oI`Wl+ckOv)E1mncumAn>7_t4Q81;!fQ-%5?T$RIMzV^D|ugFbmd?WtMQ_attC#^&aDspWqvEckOe!k76tg`xyvjzGe8S6gXqL5W?Tpxwjhy}fJ`^lcGBJo(L zFnI^A%2eQe0nUyQ-7=)|dvB;`DbNeg)^Yk>A1^*kchbu|v59pZs4!o~U6mQZEAKb7 z7Hw0k^0x99cRUt)nJ@9K$|-Z4Z9{j4sz3d}UBRvWhu?+sfnGRD@E7-b>*&b*oPLA&dJ-+D!0U6I=KnRIy+v+&%d)q$6zGMc zgyZzgn2|mx)8A{v-%`ErplLHF2+sm=->W4M%-wB zipnn@?iS=$-R#p7^v7Q#T(xTt_7%?kNVi#BZuFtQY*>sy3o1%qI8IgTjMQq*thv5R z6q(-E@3+NPpcnQo$JxI18F6`PZ~yFcdxYzM^D2FweTe%jk9Js_yl-FA%Ho}`diiop zj6e%2X4k(&mC_A$uj;#6ueI&P-7G!*YujuEdSQt$BR)f2@tOC9SE6+1NPdZK)p*~< zUf?(dPNoq1E;sU0W$A784@+Tvea+wQXX?G@1FsRs6c*;GjrX4VYL z9UsNGd%I`WfB&|5S+_%@Y|MdFio}|w{KKtUTNXulj40IaE)~nW3&ttMp@NnCx8Kh0 zU%9^P5k!QQYmDF{e?y%Imz&-Mgg~5epty{jPkxgnPcbQtXba=nr4J#oN9p zk0z_4BI2cD+^bN)t^bN*v2N^G(SN(#IPZ-CMYJMf!Q-mmOs6%3*d^&>{2U+E@%sGo z+#`yJmx{p*Tf=*u!0gXZ{0n~Ou8m!FtVsDNFD&VQE7WkOmDu4rj#4y;dBH#1dYD#3 zET~Ywua&Cij?ADGrI_Sdtz8Ab@M7_ZBI2cDmw2v~`&*wHM&X<&?^oJ-Tq`1$|Btf2 z0M8<4-~Zvkp}4!dyY|imcU_>!vbeiDEfg=%;!cY@#r@6%cUv45Us!Z;DeNx%ugv5w z=j^k*-}m<%2gh@7uj?~slF1~QNv;I1tA3x#*M_CastA>;GHYr5c`ZM?W+377QW|fH z1+%O_OX_Q95K+M>&e!BgYZE>TURV8IRD298v1&gNH`bTopF>OVErll9sY1f%r8Ekc z4`wqLY#`z~5yeWBg#E%Z`<-`aIFo0M>( zCXCz%%s4~S*o4o5g! zA>oO#EqGn^o1QM=JcH^vr>9oJQyWeAyp#q#|H5fYbju(ses39U3tm_KrdC2YZApG= zuVUOTAx1thS(P+Zwr8KBL7OIDH zS~zN{CA8GG1+S}qQ>!gh{}|nKO4W1Xwa`oboq9Oo^n<$Rl&a@M3li!#^|iw3Yjw{l zRnPfv!sn&_PCcA(`awld&nZ>Ui59%B`c3_#aQa%6sys7xT4Ro7;QuCkUh40@UE1kH z9qKv%C_ddPMLj24@Ve@Ewo+L{BfGENKs{&00ky35)N}ru@Odf1xBELqZT-B*`h7re zo}f*Dz_B`x^zRS3Ba-Z!#I|oyr&J!vJl1<)Nf00K{TyEVdy={?o!raR$-Ons#j!f2 z3TCT^s#bK!U#Uf^;Xypk$mo-MZ34aUiv{hAQ+b?7o;ipYnGhh*f<*7|C_1xmEPE_e z|M6hYMRBfHARkEQz9NBM_-1JsWk$XhneUC_E9e|v^cvgogD5&b-gyhngQ3lj6LzY`VDjb+EDsZ_lWOKxpWIEu%iGbfQiFMNBU_u7|vtdiwM^3qgR zXh8zsUg({(LOH9{kP*DppqKkSD(vbM>+m0g_-#7H6)i}N?eaj3oHLP?zNzZf z`Jk27;3WO|mO*X;y|7jq#;&OK*3p-J`B6HJ7A;7`u6cVZR9NfG*?cD2f61kzj*5^q`Y-P+|M?L zjeD@Mf?*7pLTAftE=&AbiyhU=(QpC8Bw_8ELQ!p8fAR&J7oo4>&_ExazE#o zTlf3N%BmDTV`spYqp4fq*4*%~cKxW5i| zj!G!A{MnRun&&3aOLVv_)^?i4UUQZ6L8W8LD5DimPbc@H1qm!envPuX-s%+8mitlN zMFPFL7ri1byr0Ty*yjo7D*x8Xn5!KRru%^wB;5Doa<1aCPvdfY`35@K`n4s*&2V}v zp);}%92c)2&tY+T&)uBt;c+qY;vClUSy*{$sS8$=zb?$jH?|EB`m9%WcIw?VNb7T7 znRD*z(xc_%s!hdsj=cc_El9XEKJ_RsV}2{jZ%8+RUR$yVk$2TH7BfnnEt}wdX*q$; zf%tn>fItfp%QhbtX2e3)t&O_pRpaE7=_4!h*mPPmKHKEW#UH|ICKr3NiAbH?h-Z?{@%4mh})#R-VCy}rI&!9KU$V$*Ko z&at+paik~z_AT5*3ldkGFJp%aI@)wjwRMvXy4a7myyqs+3sY+tF(-d94<2sFZ&wO8 zv%grwtTK@-|1svN{&h7=C?i>3ZhA1abmnC2`{vWz&G_vR;jVljF>1j|Rx-;Lc4x3U znUohlX;xeF3(q;zO`sR%i6TJn=H^wc;=F&GrRK4`o7nA{YwfbyIeY_4K6C>+a?A6t zRGoR8nm63U`9FywT&Y5$|BH1jfAUQ%^q@MWa%z(JeA@L|JkLaTs?ZBdglgiWW_;|U zd*;EQaPzmETiDYnD_QYj+;iz@BzqNe4Lib2&o0^rDQEaGWT?W3jj=!8d%c;A$hlJQUtQ5YM#d;WG*IkvW zdKISYoJaYWKrdB>af{B> z8tpSS;&(fLwmLAUtb7(EvK@$IZI1gi4kc>MXZAa0tv(-N-wz*wUW3wH`t(T}ID|5kK76Ye6=OI>MB=fzqhZTtazWTODF zaFs*&EJ&#KMLoIBj&hHV^yhVRPh`2Dy9xAC8uxZA)f$7h_T|}2BsDX~im+4Vvml|` z5!F&S8kx3q<_C)`Gz)BZ6X=C?n)b2?ZO;>S+iK2XPU-rd10+;Sr=E33Bf;ihcwnNF zX45(D+KyiMq!~t{!o6ks5>>26O_!QCwoHsJ#XU6Bx1hUo4@!-g%nE&(rE@+dOMB_5 zw%z)&GQva)5-&4{u(IcUwdD5u06910p_RB}xQjrqwjzWH(^nJwR%>6%N#)DYxEg-N zI=-%@JWn+d3G}LD%w$4yc^nvXy)Y=i0j<6VIKGVP(6j%vHA zyFEjl-b-CmQR*J3=jQ9hl{)8%2ep$e59~6#^mCplp9Kk(Yn4jp4(2=6ODMuW5pTy$)8SZ+{kx+L}mA0di|8ajgYS;jg{J5JyFMQ@{r2pom zxc{ghZ*(@ozURJi8;+1v4ZV`iH-^jhD1%j$_Vy{$$*GAx3lgd)P%XEUs=LD@tX)St z@f6411bV6GX7ig(x^&luN-Jz=8(yIHQu~SWS&&dYn(BcZjW{{u%l5l#@dZzvXV6EW zmufLWPHoT{chC6Aw9jhrmuH=p!Dm52^~|a#bu@z07nBJm7vfLyEVJ7ZAAw$2dkiDl z%d)cX&MbW2pk=Olg@hVAsM_dgl&;l4CU5!8?9%4^M-D!wd3< z!`hfZn@jWT8MdEd&+uLid4$fZn`Q(DrM?7?ax4YNJ@E8`9KR2s7*U_CqBZ? zUr)(0uMOlElWk`$&n&a|Hk({>8+#VM(*BM4qsaSGsm%vFZ<~Ma?!Z-wRLWGURIXL- z)jrZH*DCkwH=Tk(<@76+mnti?Afd`n>8LWKJ$_?!GW~l@Vn<#Mb(JobD5jQ9^h`d^ z9F#eQC$#YpS3Z#VvS1s_vunOiRj%`~&61&8yjhNqauMj&x&3x_efE64+gq!@2b-O9 zc!knH3ljBuZ)ShDpYF@~=HJ;I5hj!d66lpa!xlF2W0=;Mm6Mw#CYG_323nB#sm40C z^UY+fF)-yqmjB`{TLTI7n!SG=OH*gE)@ZxsB8%$K-_}425*IQqV|zPJ&>Hm{-1nSW z9m`VrKmxrQR$s;vg^$-7=WbT^FPn3mt$`LKhR}Xz18e&=5ZU0>;_vO)sA)b*83ot8*5?vw|W7o~v~Bvd)6d^sAboK$%!4J6P@ zm6OV&qoMAFx+h8lEl8;Qt?rMbq3*Z3?@9v+^iua*-77~!)hSiClm=RmQ1w>TGe<+! zTUCFR1`_C{>aD7Cj)rK(^$MzYa5Pkprg}EjtKqj7>_zdb5uJ~7 zsi#>v?N7Y);W!*ENVxmjK~4P3^+snd9$zt$Krb9Q(W>HAp`PQ*n{ofg2{>Aiczk6( zdvMd&pHGc_L?rIjg~xAt#q}Kyy>R42d!FqWZ@nn<3lFbx%R~zjI1Zv&vN~I>YIiF0 zsMd)%T9D{;YB~!#6{-94DWBh1*_Kt~<(Azrkw7mT2ho|{+v3U-MsB_u; zwcjn(8ck+(mdmbxW{F2%G0}nqj>ruocgtFG%$pEX@Rg^;H^BS=KJ`)eOpc%|)P>JLi%4qpVG7s>-hZ*G+uS#P{00t*5gNHA8gH=jEii ziC+uKL{z$HK?2{r>HF?)*=3%=esU+}90~MN*H<=Y)TdIkiBhIgg%%|63j%!|j8j>* z_TOz)S&@(avetz^RWQ>~*xH%+u4;eIO;iMq(T-5p=!FS z@v63?1qoHtRV{TiR83bkUe$Ia&`+Z zFd;_^66zUOPlA&wRnt|CSG64p^m4z^H_4lXhel+vOBXFjsJ2SAEsnJ5-UFVz#M zcG$^>>Iqbjpn3zeAc0?1>70guy8Pm(zLu(qNT3&%f?=3xoAAHN?Y07^-7?XF1b!W+ zv#_ZrP(6a`4Uj-Dcj?;iY4pCP-qrBU6yGNC4T*MK+>(qp7?{ialDh#%3ldm{)DM=A z#jSDE*sydzy9o5cHzfLA(jXV-NkjHOuV0m;1qm!e+EX_Co0+D+pQSXAKrehlqBr_D zX?e!LF_zLm3ldm{hLO&D!QB64xvhZ&df^)q?NpfKp&29Og{^@WB=A|GxuV=-%=#rC z+Zsrq7rr6UyFpY>GjEmjQso0JNZ>PX7}e%=XQdXzlB%qbKrehlqWiI8k@pqLWow`X z32g1CuPvI!TK)bXJ0D1(7rr6UQ`>!#^=@QpTLUdfV5?1YMb;W?`-?NS1`_CnZ%BsG zbN?IbbHp9{exL;j?Cq#tWqxM$oH@kSKmxt+4T<`wxfx{2ldWwHv><`~BaKD>h$Rce zsUXz-Kmxt+4aqRlq{$_}1o$y^&(VSej)`bQMso&vZ)7)>1`_CnZ%BqQ?p{h6SvAa5 z8fZZRM^T0`IL1lqWsi-v1`_CnZ%8zf`F7p<>-0xk11(74xRjp3Jw2_Sk6+jtNT3(K zA<=%}BN|#+E@$K_A80`W$JcaHY>NbOiP(d%S&_V!v%TLUdf;G2bE zs1{VUq^cD~0=@9t8STqS-}%({KJ~2+ElA+kNLuN%_K6w#uBGoZb4F*y*=HQm`IC(H zqPKt3+2o9N9A_DZwxaJ0bYeO?cI2w>#B@eyi`Z{*bQS=kUHI+abY3o_J^b|<>vSqR z3mI6?K9wCUbmA?e(=cr>I#nS0O0@d(RSq*-<-GP;@n}JU&a!26UZ>We^XS>)f+7Et zD)geW4j7$MqTe~`%zN|kx|8;q_h>QE zffgj_EL%qBz-o=GNw2ZX32QK=fdqQd85)ev1JN3vhj6p(nmDG?KnoIdmMv5NYHTk< zwWP`PHB9|e8c3iQodv?wKj#~Oy1vp;8fZa6Rm^ip|H`i_PwCskfb z11(6Xd!fqC(NOn7-4msO1bV4^p~}(GQ1@HiccpY3bxPGOrGW%`sXC?V zgQKD9t*XCD11(6XXG7IxtwGO*dPbB666mF#4OOol4fXt~=TK>&1qt=^s%O&CXq@7R z_&N1>TLTI7Qmuu0q8$y@DyY`sN!no?El8+#M70`@hH80K3#9Ua1bV4fNVP_e#;1%; zMq=N}d0)^iUfaR_K+vbzyuHEl8;L zP_>Irn@A_vn}1$z=R3ik#V9=1w$MrQENkI0_HQ~BmC*^WT4UX&#pdso``Ks3qXh{% zL!P}eMrn<=V=J0JB^qF#d5;8o(W$76&bHMWk>xUocEd;6XWpX)2|6*It@t}oYg`?W z!5Sw9+8Rip7oCdA=!{;i5%qAP1*ft{Tacg=+F6j{lme}}n|sEJvAG@Jw_&u2*FrBk z6_wFh!&)QV+n6#-wHChf=%X!2(7Ew!V!UxWAAj}EBl}M&>pPD=nm{kC3)I)nEhl&X zRoFg{9xX_0I}b6A^xzfdE;1{f8Ev8k2~}@ZopUtugbn4Z zhu1d4)BCvy^it1;s>_bXh2=x|$>K3YMbbbE5~|*+I_GF?IXavt*q+XcAPpqYOFbK^ zE;|~vuEpeO+q96Isb#=Xk!nZOy;feTeNpwn(NHx+)f81$XhA~NDOGD6jpVuW^Y$r9 z%f0k`Ac0=$*-+1jqw!*XC7$JFPWfh50uwDrsAogfWk+LS&*uCHdt<4xLIS<86zD97 z>7Due(U+{_Mf^;(AfcXd^-MY%s#W+*t%J%r66obF-4R9{xqJK!`;2uuorlpW=Jpvp z*tXMY#EecJ*JrF(oOs4Mu|Ci~V;wC>U|&Mx_8oVuQ*}<+XT>9dUUaH5qm#$A#=#wn ztb7Z0`p%<|wjhChqG8NyFvUt05Qj(Qpwk`UTIfZmLo+&gTx%@MnAggm`<|_V79_B5 zr*j$t7Kv|#Qrj9xpckET&FDmPtq~`Es{Ip6zp^#Zf&`9H=ya8HvCScSQ}9oe4<_FEyMUbXoY!e`rr2bKmxt!)N!W%<%m-2cZnrj#DwKdR!1il*@M&64H%pt2{%JMbqb0pA9wJ)lj zaWuBo`tywOugcq*IjI7nUh6T{64V z8S6M^KmuDOYIpz6BlpcoX`dC31bVqgOH=2^mDBR1^_@o_J@!EYTP0e7z5kN+E<;t{ zdGyf)df`Zo&L$r^+p1T~V{4!V32c?zoE zTLUdfV5?*pb03v6m&9yo=K~4!!jY3Se1Qc8kU%dSIng}l!NR=ntn+5eLzy^Qkib^S zFtP_X;hoG0rn(1L&Ac3tC#af29=6BQP5_3oc3G~8|0eyR2 zT7#Ep6US2da9N;z#8$~LuJ)6E%d@X(buT-jK58kUT*IeVdkj3 zUadW~Q>Ef>D8fdl7#vJ3J?AfK@&2#l$(57b`9MNNCs9m}P!URW3g6X+{7vmI7OU(g z&*r7Nap`vzF{0+s+2o-}fe&TAi8dsO@sX=jh-1v zT98nYH55A|oama>@00QSW2(r^2i*jEVTl+dJyA@KP?1m6 zpT{lAmlnz|z2n>jdSSWIiRr8EnHfJelV=0nImbMycqWRr5Gtn0FkU}6XcjWt$dd=c zO|&5KLsg1n=AUCT|NmtJe6Yx{(6Y31-WOrAKs)a_sJ42SRlj&USu)Ww7lB@#JquN&p4K?M zW0X~DWp~+l$5In5Na&SATI0cq&0=ED{&IXsxQjrq;9u;>K&^3eR&!A!?f}_uWw?nJ zB=ia>ts#@0WaFOnlSwId2?_MVlBQXiy~WHNW&6nZqa#eTAfeY~X^q3BW|-Mqb(Ke` zCL)1e?mPHkczQW>gopRrwA3zLiZ`%xsMpEZ*Hw3xqPcX=8y+epUxeh~%_cba+-E^T zuYl31y1ufGjO-GJm#4@uycT*5I2NKJ!?Z@~Yz?Vo|28A4QxpVPkkBh&v_>+&*0Ry4 zV`icY6lnnjdhN(HNkxWfjj)SdWU8o{=CeN|Otc`O*UV^*w4Q$Q^&G>zeIwjOpqGw< z&>A|Xfk8}zZ9zh>#nBoKkMx&W`%Dx^o<&DN*aUj1)KdJH)>s_XS5A8w&r0{gNtMrn zgkFoKH6~Qo2m^wqw@eGfwIHEJ*0pTUz67gZi>u zg&6X1d*=@N2=u}h!!TBd*Ooor#g+A1Ikm*smLQ>5g=vlatc09eEw@~>+THq~7q%;g zA?Nq!@6XH?ebYvm*dy!pCH8gQy|a$(V=A@}ElB8CyH){ejKq>{}6b@9eW6q1T#djmMt?xEb`&e5Rt8;acdWdS{Ao(;D?EHsX_? zMVTL|-9-x$dJT)#s1>UUZ`m$6-?c2lMWC1J2Pwi$Yn%%%$O|?v#8;GEYWIUa3le&D zlGc!?6Z04ss_|kJgN4^ZFV$aBgqzmzQhd};Wg2i5AB7eq^eQW@QFHkf^Tpbh{CA3Q zLjt{2TS*aaT4T%6)n?I29r@D!PP^-~AfZ=_X^jzI@|iVf_TkS4xe4@AZ9YY~X^kTk z{TV<}pp#!Z{fEzjgkHm@H6Hf$6R&Cw;Em{>!4MrZt*w5@M>^pZ8zk^lCl} z5_&D3)<_xm_J5JoaHL0M35;*?5lsWo1D zm6lNPIC{O8of5s0OQ%Z3;!sSEQ1LiuK?1cY+R2GsveYVX9G_#JupNtD*Jr79eP}_# zopZge&r<99kU%eN?V{K9dDXf;v>>6^d+E}x<*b3^f#26a+O+|nTD`JL6KZ8Nt&p}? zN23J^Y*#2%wECJ>VcRRPkw7oKLQHF@b$ub9-T6ns&D9EQY@@Iguw9`& zAZUd*t@O6b3N1+JRcN}b^x9gk*483{Uf8Zguixdce%HR|Na$5)T0^f9=4y>FUJJdj zT`>%`GMZLMbG14eEl6OyLVG&V>T6ns&D9EQv>>6^t?5*$72c6)s&ZI+Zs!BN-0f9v zT18H)$?eib3le(Wn$}P&)oH~#SF6>LKrbBoM#lo|SEZ}hj@j43QJ-G7rZx1sa0ctb z|A)YFsbQ!U-n7!&js?JLp%qa0>{_1|BbVT-h?&ucB;_JopX9( zRcwY-Pc6RD;Yd%fLen`{E2C+Jw7ohSElA*)k#<6$)z`ENTdGyXNT8QqO{X=~3U6xV zEY-rH1qmF<(w^kBikw!HTWTda66l3@mUhRdmFmj_XIU?3wK`gmz!5op#c|?41jK*X z=|wNBG12ScB&>(Cdo{fV&ZhO+IGuA9_e%Y(RDCU4kkBzkb{|Y%&uR5Ft-_XS1vcJ6 zENOg?rrp?Sh4=b^y7v7*3le%&piY&JE0U@eMFPF>J=!q5PVAC|*d_ZpM*{Ol;}R!6 zN_wg1#A~4!zIjK-U`dFNBY|154|4J{;lK6 z>=BM(=y)|tMg5`$iPv%&Gj49vV;>!_W{;MTKrbDyrU@MlXh&!26{dDdj;5H-w!PkL zd+m;z!3ue{YC=Z?+7X~gpqE}ps>fG48qkhpMXx(a=CgUVx7*kKF@Y8&cFm#v02(PoG=pTRd&QgwmH{Kt)b(c z?KokyAfZ>|YYiP!ZNGUTfnI6yPG(cX!?cEu^tK5dJz!t!V`vzgoYHw$8+#&@Jq&by z)2e%l@}_@wL@pBOg?fg8sX_}9`%i_i%ekiMRQ-rRuOH_F(~c<&iZ`3JSUW*$=%{!* zA80{B$86}*)sgphWHA!xbu#UIR%z3Ct)ce=un8SwVqa^jxr~+D<9MB}u$1NO;Un~Z z0CuX7Krhsz*;i*j09yksNYs0|fNk;jY5a&lFLyrlP6&3Y@Xa0H=rOg1@uQq0VeDJQ zyoo0MA7zDJSZ+W5&VVWWwmFh*`RJ=xde;a$A80{B$294Ct|H>8CAFUqB+zU0)6Gnz zn6C4I1X_?-5rcL-iJYYgye=kx04+#dp0J&z^F(M3y|;*0wTVce7p9QbOgMXs*!e&U5|M+q zvqxzcXpJ8c=;hA2-W|qLBV_!Zgx`ShOGtEVpQWNw(1HZ!k4^xisF$86s|yufg9Liv z*96+>mLh8?!p4pUL<<_X%rI0G z5=A4~8c3iQesiE*ZYa`eP>hqd23nB7r;FY>DVmC+s_ZBsB+v`LInYWcirAvaEn5RE zNVr=c6%|I&VYUVm=!IVpC<_F6nYb;s7Z>R^r+_p3G~7@WZIFGA~PvM(~bs23lcciqFO@HpA-dZ zDGemh3*XzRkD>@uiZr#<^MMv5aKuUbMo|1xOGoh8Uo7anB4@`e`wKl;kAoH@^a?1Ork&EAHS~6*1rq3`*Sc$sy%fno5gq<yV`15_;vj zCI(Qn$d}%E>_`i=AfeZO=~QK=h?MkiW7?4xNT8Qq>#j9a)C)zwm@4uGElB7!Y+6IF zp|>L~kU%fJhF)u^=$$JAGT4z8XhA}+#nT!pLTF353`|8qAc0;wIznrxD5Te8E85Wm zXhA}+DbyM&(upFTFw(-l7JBKp5Ursi2PpS;+=Pzvu`N2T$o{QYo@xyh$w3hvQso0J zNa)BXt#OK?MJQ@Ss;Cqs&`Yl))fy@yg(6d=ib_EX5;}rQYm}S2$fW2OsUj_qKrg+H zRBPy1GCSvJK|)6lX$=*ORpo<8Y)7FB8BXT5wswoqldJHibA4jBs(8S zpcmdv!%&e<6!9cg#0XlD(9uI$L&p`_5hF;Tm%EmHq=*!XOtCevmf+pg5nNj15JkOE z^oyMjv>>6^Q|q!)ku}ffJ7t9gdg+)it)ZfKD2m69;6V!#dM&rs(6MCpJx2n)bS#s3>oWWVJQWf<(Io>)DVf z-@CJpWVJPrKrhUnVdzL!TLUdf9PG83)oU|V=i^5NdSNNhd3R1^u~SyL=d;4UkF~Eg zu>C@I>6G(Z$Ia-RBY_qq?uUl6&PyDcPK0)1k?ou#fnHeZv}dLhi)^O~El5;|wSxUU z&$%~0CeRD-&5v`ADO?a^CcA&y_f1B}ZQJ=k3lcj1N0*h34Y%`w1bXevG>siQI!WI_ z9e-|XpalsX|D!c@jJvIY1bS6?6T;}9*3hx~_MQVe2FJcutT$ts_qy}-RLB2l4IQg* zYoG;*YU{_d=XHGFMRlycoew0?3sV>!t8Z(d1&OyuC$W*4d|!$%=SZNJJLh^Q1dn>o zb!3p8LpgOUJ2robT|QVMw9lQh6N0_l0$PyRabzs3)?uM8-5(L?h2=)E$j%-R_TC9P zmdHs}jEU@BdgqHdrj}-xoIN1y{Ta|AfoM2w94j!&_f7vt1bShf+@o+DZ3hO1GXKY0 z?A+q$+)bbbiEZ8xmh^>h{zLDuVXFIq1bShKP_)x{dxs6C+IF-cVf{3T4L-YG-;W;= z=!NBG7%HA&N-<%nmH$^JV_NB+yI8F=-7Ii*rA`wXJ~`Byfys7%JX};(lxmB+yI8F=>sC6jMa8MN-A% zpalsWqZ)>aTgr8?u&sdvdg(YOt)XJ0C`QWGKnoH$Mx_}nioc>bEIZ~03G~u&Oj<+5 zcuh?Ir=?>X4011(74yP;vIxIT*SGnEDs=%wSBw8mSC9i$jSQ>El?D>%rQ?{i#$JknO!#*mJ0=b-NZ`9V?H5jQmdo20=Bh100=;y6 zl-5wOoD|c^RXitJkif4LhN0p`x9)0X$Bg257uzlzKT@woF{u=rYN@zXv><`4l3}R0 zSBihNV_%U#FC5j92F2D=jIAACixwoXRWgi;6u;YI#aUYe3G~9zAngK0F~SrpELEH^ zT9Ck2iK6Hz4w>SSZ4D&Q3&(S`K9ORbDdySMKnoJsDp3R|#ZyyUwWVUJkw7mT&(Rtd zirJ>vZK-0B(SiiFN)&%iap4pnZs!9D^ujR_t?Q%MbBaN??+03tz*fmHRD3(dx!W2@ zpcjtq3`51xQ!Kr$ffgjNRWb|}r%&B<(jq z`wsZ4*l;A!3rA6gq4qSOy$zVUA1({DoY*SS+yw2Luqb0*Q{8hU&a)H2ZC475js zsWi}n1hz_sq4s~EeIQJg4 zd$&+mti^p@F6NYr>P>&@OZB62&Y1SObYXd(L>P z4=GpSfA0rg3%$;sIpbB={$CmUqbu+3Z`19FeJy;>f5{ZX+rQPJ|Ik1S5~aOWy-$~I{|^G|F4nRC|8kDR z{pndfF(bU5|1Dj-7J6ZQbC(s?pV>v5?(dTH|D`4(F=YPT{S}%W`9D&HUfA-vQ-$>> zWc*3*ihpM8SGmRfxe2r&QN7$rZ}whuZTiOqdSMN96Ie?s8ol;UTXo95&v^gc1X_^T z(Y#WHbi2;{M=e1Dy#{tm<6l3|>Hi?m(mFw;f6i#ED)RJcl=n|Iolxq1VWR zr9GFX?D`J^Ex|R~c&cpM@c)o1B-Tew^(+mW{T~{bD)hp-;JzQ&B4bOPVb5Go-p-Rf z|NBIt1&Mimk9y{8y73?N3JLUT|M0YDcEt?;2Qf6Q<+)lbrJa%?EmnA5CLi)2sX_}9 zHB0UGj80SbKL}JW@a?qc!SN)eRcM=+ErZu|u$tJ%gsKHy&Y0WSD%od-L9%r&#k@Eip%@(!49%JW|mD_Um-a7F-^-em) zdFon9nM6_I&&XwTj(f@3bG^SU43Zz$ z1c=TJZ|)C!{z?21qx~BC?XP~nJKS!~qJqEe{}?Aq5{8DRdyclZzF?5i8J>E^ASAX-V_vENIT4Pg;AS-O< z5V@gyfItfpFLFQi{_)crtx=|KXX|0AVRBRlH-TO!6QA`y@BL0|G+$BQGTIK8lLiF{ zv>@@k!b%H^llh$~AaDj+=5hzp8^MM3&miI|&YWXJCqbI6s z;CK;{AxN74BG3z4KEn_hvdK*KYsgoT0YbOoLbb@cZ5Jc^pNOn9ZkCwz=(yN3bpy3N z3npcdx7XB>RjFPLcrru0Eqzk_v^=B#vJ2D2wUnpC#f#j(^OFdXVWwq2n{?9not*Mh zxvFyd61N6k*G;s1nNbGLtu3bwrZy3-g~Yznv&4qNCq#i{_bFAs{gP3(iBm@=9quO3 z3sXy{nV(ND=a#H1^NkA-nD&9^!bJY_r$qdcwf~im)d$kabzkesU#7Y>ka)0Vn#kDv zjEMEA4c(9B4b#Z0C+o|fSGWoE!gh>ie$FP9p{*Osv(zS{1&Q&krim3Z&**v;;Fm-` z4Q(Q){)<2_Z0!uA&`6K$xvP*oG&VrQKDb}hEVDwqx<_Xflj;G)`x8?9VEj$1_99SASk?eh{mY zCrGaA?Cx=ppr_08{iz+XXfEsVK2Y`==qAvs%i|`VG!H)N)@Sd-qb%isKv|Yjg%%{9 zzH8!17sJ;w#7z2)6<;$-Htypl&@1oLa8HlfAGC&l?Ud%`zedX1{Q?A9kf4^x^Sy=Z zma?ANV&HIjZ;P8iuP+r7u+zz2X^q4C2b!_U4VAxd3=n8RB0tx=FZuJWE~>Vf&}#p?0b(hZq9P^ueSZ=fPHQPz3R27 z%6^;uP;11`xzntfypQ~QXMjKp64b-7?>%SVtLM!Uv%1ONz1#$P)jiRi<>~Dk0c8K{ zs`=qv7uk>QAX<=!*wvhsX>nISwc*#Fneo$fkRQjm3G`}tb~syg^Qz8AyO!_G(bL=v6Ea?Q_5Kq}E8^JQ4pTvZ*XgBLK7@LG23r z-ukdfDf!kD4dtgcZUVi6E{Cymr%#EYCF;;~{wO>Z-xjl>97y*ZEg2_FXJ6`^5;<#C z^G9vNn2{kh&$_;WY(NBBkSI$hJG?w_QgrEBj5I2hP0P1tuP?XIy8#mD)yta8a{O^r z=e+BnwA}A~Jz0bZ^qTT)2Fq3Iq!3jz`n!pXY0~izBkRd8)SsgTi4C!4u|CaCh_aR6 zQy+EbNp@cMS~Z#Xq?^}$CO+pT&`Z6I(L0<_?{KvC{BU-@=0i0(fKr7P^`1uWYvLTe-Jv#}qI9+( zkK2&RpYOOekkD^;_E^F&o&}WVfh9}HTGSihwa}~7^sVf-tDAJrFHiOGEGrAiHj4rT zT99~G>ku2>dXXlA3smRtg0sue^8o_A^gE{rp^*%YVwf63I3t-$Evj;{E2k{&brb02 z)>wb84xijKgFM|OK%fN)8j~Tt#-oji4Ui6iM{1{&`ofnGF%Vrp!nMo~0>ey|aL zojZjrPfrw$B$(>?)o9}WoHOi#cdDIR8lNyV>QG}8+KaVqeSYVD8hK!7fEu|(TaZ9) zI!mZaJ$}AqI{A$HS|rem#&S%Ji`00IcE7k?m+$y9ot#E(B3h7e=i{HwP5Fr{0Jvo2C(R zV>aM&h|$dD{w? z%_-FSAc0>0?0&#TRjaEtIxg+X<0igrjv)dqNZcv;fVEEP(~z%v@|iIYn2-0n3H0jR z{!exzWh$-FKCmy3=&{MnB4}g@79=JY{FBWnlt$-csox-;@Zb!yb`Lj!Uaw=kX1OE& z@u>S`823{T<~2h?%)UJX1X_@|mgY4}vg03*x|=knJ~Wi4I@ZH17VIX_E9ac|EUNEz zt&uhNa6UL;V>2%GgJ?k_^{n@-cl=#iqsyU@{Bhm%X8L(<0=-W3{ltn}1+>QY8>9H% z9Bn)WmSBB5I@ynjpxa3H-TRIO8Xs+=|uERy2@L4Z!}?BkkG&PYYj?O z)|t~p>hGyS!uHbn^Ew(O?*;PKAHv03YN^qJ*VTFQIvNe{jiML6*J1{J@j?Q<^qtij zUFi-UsGHt`J7`;w(Dz1bq^DYPJz--j-uGH!6X>ODsMff)b0~iu(bKv_Z>eZOLf0{^ zk-6w#KJ)5iD*?6CNT8Q~(u7l1Yv_sk?Z6BRo+#Ubgnm|pQ&v;g_vI-DZ?yb(L_dQz zfnK`B&>B0>^yGCnAF!s;=oKwU=x1JQOrzGPaiYss(D&BIz7~4vc1&w*Y15Ub$alq3 zUk%WLgl@aEMun^$`Il3FScx~e3G~t}xYqbmsSS^j?z1Jox74-;3Ec*3jZd-}Kb$Lp zod3NyunF|i{fgFT?AMe(Y?xTypgsyMNMN5xW1sOq@os*}Wo61a66i%^U8dfpoqL|F z`A>XV-Q==15okdId+lfq4jN2dOVjpm?BVFt(94bZKYl6rPc#BR3lcP*W@_~8jHzYo z`uxc6Y4~0m0U&{1x~FDNO-wqh9yc4rwi=NehV`m0zkE3zPu|;2 zpcjplnHvA9(XwGwtW}q1*`A))rzZ+6G$Lkd1gl2Hs7*17x9jk>l``JKYH_u^}ZfgZ(evU^wRHeI#tK#rRHB7 zG~ntx1A4uocfe-{PqGSwOZeU(H8HtVYCd>g1N#}oYau~nU8Y91&Up9Ru2g*3n+AM1 zX&`}KGy-R8^z4kn6R$|g#mr@KvSHBT&KxKs%B=mc< z-AWin*7}LLU!tb`5BdU$1bXRj13Kq%2FKwa6Sm~(CP#k*uq{aFw|lLzzQucU>-4t# z==bjoHi2IH8;8~?b>@lrba4khh`!dM1quC?LTj{0d)<7xwF}QgV^Ji~OMk1;8pW=i zH{;Ff#`{p)jus^J*A}fYsT!@h^XtP8QeTS%dg*UYT4O`cW#)pJ{rO*;qrWZL79{jn zBdw7vRj9dn_8<=5uWSOn^p`NL5hr+>d1&1rUW4itT9D9RzqCg3=l#v#CPVoq$_EnY zrN04cjr8=b@0WqY`Q0ti-}-C|68bBi)>u|IrMcj*k-XaX?};{nUiw?6*2sCM8T(v2 zh_|H{j%GvsY5tU{`BR$b^rzWSre;I+{GcZGw~t}wnm>vs9uOe#y84@?of5Z({*ub! zOR9Y>B=lERoe%xBmaDI|crEmDr)qe>Al9^45FgMf`unb}fdtK-cxaA=Idd$jreB}%$awt6nBaD{(>N0eZ4)y8*M>?W@7i# zd@Xb4Ya8Ya7Gc?gculIi^u2vQ&9XB!%dY39>~f>|+Wj;W&(usjoi4xOt+(jpAU=e? zC!z%jEJGS)Exh=Tvi*0?qt{hltHdgZMroFt>4 zDVUn4pg73d^To*5f!v-SbXGmsC5m2p-q8L#jV$j*i08Kh`7P2wFRHt0-qC(0+=QOB zu5XZDrD?5k}-LeIo%4L!rl)eJ9Q z3%&GQvDS!mW|29}BHI=us6|yX)mlT(RC6^`jn_giJ?E`8syMUZ9A?993lh{bs2O*y zp=aE=nsLW#p_iV!*BURJS$+N|-9fY>70)6`p%^RAY&R2n(?PJJGaS_UN0OV223jryz8$r>r@@n+Kk1bWe% zmQZg->TSzSq~4QWcBxjE9~c)s!)sp)33`VT>MhB6kGj(*gACtShkvD7g4aSXdWW*# zn4I^hdv!C)Rw?T6&NR1;7J7#g>di>KN8y!d@12_&<+D|_c`RD>f)*s`9m;W!B*E!%W5h||tCf_5aZBUT$mED?8m?6H6Mda+oXIveQOUAqr;o#31bR`FhoCq!9UJ~}_5~~Dnl?OMxk={3!E;1g zbDy|5vW41vM^OB$z3;=N6?4U)TKmL`Faar)_=NOO+3kbj@OI|S|ZBWSk>`}Y_6`y2ZE;Q_6PNIUSVb>VF% zo}yKJ6D>%f9>x5$y=pbP(}~CW=;tEPt5nrFB443>B0)Z-v2Vc@YeW1_ymNR?6D>$! ziO?BUTMk(V4mRW`d*3xNhe*7*Jx|1Kx=*BNS&cNV*V=AnH7j!2I4MU95)@q{C~{B7 z5B6BP$};8`=f}OdTm*XUtvFwN^6V3xMHSLmoI0*`;Aof`qsst}_xaM~MdEzhz2ea2 zG9LFmKfNuZweRg}bINbMRm@LxZ9w8g@kOHl*uCQB^s=PUt3fVnZILZz=;fX+0=?Ge zTqI&l-YXJpR>bhQ<*nNtkD1wecHwBLRBoXNIJ8$(o#6kkR2{w1);gc=jk#@qOP2-` ztNa&;-@fe?Emx`YyjH#*Ze^Vump7Tw&_$pZmK)7lmY-wYiII)}-mbhlpEJ7LkvRW+ zzNnjWpE&=vB59QEyTl5(kdNP7Qq)DDm-~KPOczhiT$Nge9LdaQWQY(2^6e9)GZgZC zEfXPz&{H(lo8RNVbcu)`ykB^d79x#`*)qyq`-;elrG7QvtPU50TkaQkWlqn9BTK}% zI9~ChaBj~LBHoVOFJ^xzNW`;M8ReX6Mda(kZUVhdjEfNSSMC${E9WGlW^fXD=yGb= z_C*?w>X<5|4I}+4KiRrs2D$u9YK|5pmX?hWrRh13y*WQ=)X0}gPXCxoW_$Y0L;}6s zsmi?}z4a+bvfiIYaBS7EecXOzu}Je~ulT)-YDMeE{!{qvTj{A=A&{d532cKY<}A-_ z>*cE~R_$~B_&C2MB3-k6qW80so`ZDVf^^+eblpZ}X|{vf;E@|jkVb`jU@^R_|~TtIb}KF+&Lt=Fc#~yKT0DiY>FAENJh_ITFo|go`|f_ln@m zMJZJsuU@d;4qItWKh@GjpqIDu5;6GjKC!+|aU#aOykNyn{HygXK_iY9BzBX=JkrRQ zL1`@Pc*nYyPgn=){^TOiYjl+*;?t&vy$ux{q4&e4JdK4}!ym@S6v z5dWhUwx+C$K(Dw9mx!G`_6xH@VbYj7I)U6(If+a%Fb78q68PL0#y`}nS=6hwj0*Mi zSr{hjU*9dBq~GkpKB{W3nW9q+%K64n(m(<&NMQd+d#lUW*7o1q@nvnpT-QZC+RaYT zUQBi`Y8d?o$CX*nwBYfFhN(UCqAf^74GIy;p98TsXr!*mk-mZlkA1kcg}Gy5x)gLu{E9y zo)qRm3lfJu?G{I-go%j-&QYqiQLcwj?w3=}kw7msc2H&KXf(c`g^!G^DgRCy=II@G zi*|*WxIG-YLYly zIUkKK!)})3o~&hLvm0&#y|6?mPWVC<{_y28;h6lqu zXhDMZLKC!Kpf0QJ2@Jky`7iQMDk~(=>-SiZ;;&M{VrpHb@%C_}S#wTbd9!GkhxX4C zv@f82t^Om{ilmE2iLBwF3~4&?mY*?0cXXGJ6NY)vg2dj|>qWblL1M|D<4J?>eQsVX z-9eTa|L=11>Wf`-Di{!yW#Lm+y zmZd?Qscd*Ficlyt-Gi31k5-7QZ-$8x)s`{562&wuk82+Bj*_PrPIqY_@gc`bu{z;! z;n#C1X{`F1!hBMHlw5JnO`sQ+pkxs>8_k35qWi<*wS%` z*thcprRwGFR@SSR!(`XZZUVjB^=jv?vtr!(Kp7IpU3Zbly=Q?K-fM^`oA@wk+$qzK z=IkgIfSxG47J6aLH;g2|Keftk?jU#39mM;Lxjp@Rh%k-^i2@lPkjA5lU#yE|+Q_f; zM4<%<+7nXH4ve}jNs&0N%$B&NY)3sO66jU?Qiw=+JxJs#rZkeRN+YYjsxRMO3-h1_ z3EC44Q5fnI6vjTIkPjTb%hsyp~FkjXB|3(01g!aQg}!kv$AX)DUr`SZ)D1a1PotjMwA z&uinwv2XWDqf~oZcfMkV)gtF~k7}z_4ODk+_qQQpQiu6sa-AKl-`im#Rr{IZ(#B&% zOq$tSk z+;E9BmQ8Fg+cbG;oy_Sb&c*1o;2f!ic&cv#HM$PS?!)f#XdTfCiUs1O!bYb z)o`AuoyUXZxclkFXddQ43lgmo4Hens0?~NQW=d6pH^b#YtCnTGpY9^i%U!xR>kXF= z`~s{ON8EQ1iM?-zh;^ZKH;->84Qui+S@TH;Ywlz>fnIq3=`_LjnPl~Akp}jNg~0x?P5)V#FVQ3naaraw@dPI z)Ry42&`XU&)p*M(-GVWgY_+HmPq8%2gI--`jTg6SZ53~0eniA&6QmIpCa@O z!nKfC-DkY0UwEt7TRIP=s_eCVt$G_o(zZVnv8ZV`nXm6fb6V~& z4_Y3~3>2+euN7-E4`8Tm75KeuN6fP4Iqs-^ZLpZ6cAFEu_@V=O1ylJ?&)nbL%S9}_2?BYRk&#d{3Cvy|%g-^3#WO%~l z7;kQwKXyqI$#5#Vxs=h#e)$$Tj6l%25G584~Cf zP~wOf{C0u3-9u^gZ&gx0Tv1$}$Xmcf3lbg691#^SE)XAgD~+cQi%V-_S$XF|Cx!%i zl|Oe}ls!6Eyk4v{_|Jvq86tA;%5S0tiOe&OiB(PKi8hOrMv1L?W#zjS<*P5<84~D~ z{{3kYoP|!JxuP^Wbj%^!45%c#yv$>w*OKk0#6SPc5~YW3_jeOl&Sa8#Ggg;#GUPVV zg2dGOr^T}bvqa(EDpj${WReGesx7;}ZO4#6uT>|{h!E-rH{VmKx;HY7-1WG&%yBKZ zi54VoeLg4pOr|sM8!L@BO_InkF~=`Z)1Z^*Kb$O;Xe1!-mQjQAtg- zAaStvpJH_2IFYp7HX@32$Zt)kFj8JTU7R6-UMt#v5U*)`)p4QHIK4Q)`X|Y7`D=1_ zs&1!vF6L$#FN*&wg@#clb4x4m&M-9~*j+KY;v|vyfVzXZ`mDCrXYM1v z2BkHTK(FiOUD2Y|B=O+1(sFbyYU~uzHm0gqACup+YMk#Rb4D~`XhCAnpew@v+*FaifzsIa>vQYq z?l!Vck*p>X=;f}v#-JfD!6UoYsl)aYwnP@?x z>dw!i#@S$zB9_vquzG`7dOuLE-q+ON9sb&|v2e*%sxjV)+ z(SpS7Tyd@77h}YWAxfjMU#K_!;UJmKo1GznUh4Paam{8e73la;eZxXFCZ4(2p?I4Xrm5a-4 zkIKqwc|#Zy=!Nmzv>(9TqH=CzN%t2{q^SW#v>c z_rhe+_Cg>ZnrNF4u~vyXvEI$)~F^U zI9iZ+-+r@r6l0y}T}lx(A1<)EeOP3rYukm#DzQ-%?YB`B*jd7JtLjGaN2`q@!=4hJ zsuwnj3r{x+{~$HT^4I1$)|8`jt!B@=a%DcHfd7cdDkeDR2F;q@Xo8%}|aOBusO!h%qr-oLi>myb6~8*&1@8p_Mdr zpo>5+cdBC4=x9~8ezLB=9Kg|n#L|j;MfSuu@oE&{!&)YNdcHsY zM%f~gq9Q3#NQesWnUSm^p(6XfFNGHEp+r*FLfN-0*;>^5eeT%zec$(e-^u!$+b5sj zna}sX9-Y_oeeTS?GjnF{%ssb1tyKI&M@jb_tMJpK(Ht+A00-V=!06r448Ln!y>&el zHrWk*#B+?xBu;>uzXtmx1EqVdNa?L5CT7mq3{%3zC(N3u&sEyjHp-3Z-4xH!ArgUA zxJ)8KuH(QPwW-Hfe?1|!LEP@@@6Lk}&g-GuQCs1oeS!_&W73Gnd^<&POU3V+F)iMI zjI7T0Y3lQ=^*<@LU;@9j7Fpj~8}Z(Kta#Lj>I@TDh2M;e{Uw3rxalKvZqT_F!xsET z5&x3-D%X{-N|A2`zPqTYo$9m~t#wr(Cw~E7cVy93B_IAFEa1_p*ubv2N>E#V_lDcyw+*9B<eOy6K9EhZ1rtfX6zKMJ87$9lBZx+ie<~NU zJ$RK-HzfkA?(PCO{%JWpcTkBy$J%^t|K|MhZ=l$MiFH#HSaf_j1eJ3Y#JON=PAW9x z-mAqV5B(Na8Mp!LJ(&SVEYNZCqLYWy?&uJ5LA8zNNu$@jd6*8-=i{QW}g5 z@YP0(zpdXdg+>v6f-rM#%kFRap}hNXpT-LdS(XOBQoOZApo1!_)8WH_9@<3l{{a`% zAgfU~LAVUDW-r=R<&ElBV%UO-Piu4#GH#iOo;nG_>#H-X*YdgIeW|KMVAa9QLdeTc zhf&8m3Sz)PGnO5@O?h%t%ZeTp!pov%F!*d+?Wq1@KjN-sVE3f0w%5QyxS6#K&X{-z z!ma6IdSFXCWw2u)dpM&2s=r+UwifQh88gmtEAW z`yi!G)>wuunAmGl2pLLGV z8sxqmB8Z=<+iB0uL-?<>?G#&Zi^45UqX`)OgKm!T@+xie6aA* z?0a1{b`j;#1N%|`6djBWO@q5>gSGhnyNmyK5dWVn{x90#gVroHp&tKPb`r%FOvq2k z!ppv_^}~w%h}Rc_39PE1D}>r1OH0;XJ5;w}H-0g0@pOQ6RruPmKe6Jqt`b|D+lfQR zWzw^Y30w;r&5Z14wBwvk-00XXiNLC`0eUd}m<}Od)c$IGjYaglz9)~U`kP`4CgdJ2 zaF_$#U8WoNK3$z*0;`_i*TcD2%b?pp^=Xd{o&|5cD)GcAKye8UX4rxW>`$W!3W=uyW%3mLv5^viRk&9Y&sF>>k*#@!GI!8GslUR6 z+?O-vbWA-?l?lb>9nP&D< zF?lvrBCrZS$KrmBSWZ8WeyD{1=);4eO0rcDk3Tz6dtrONiuTJHq- zZIBK!WOl~$la7-k=JJ29IBmi)%g z%hKqK2^?{Xx$~5+?5bkGKh0Ys5m<#IS+P1;hS3{OCh?avQ;Ntcz0ku^5uLUEPjsfy z4E%bYET|jA-Ia9|M`4)2txK%+87(6tUXJF6hFz8jtisWNh)Wjk(HpHE!2`^nP;9{j zZvUbj&m6U-9`xdiYMC%hU=@BA#9PbrCdw7@?v8p@l-8atz$!d96j8=aTbA&}gU@eiMsYNWqvhF0_5v4gMo(@& zE82PDvLP&`=#!HD!i?bE%0vD3!olAuka6{l_K<%84EeE8%!*e2hrkw0$Psem1}#_| zbK#?NzYy#lUlpdsp43zqR*k#x!FRqBY{3MM&c$L>ziw>S*_wQjZoNccm3&p97prj7 zjUD;-a|>yzUJtD&r^0=|^IANX+}WoCmrtpni8wDxZe042QnhzqUO6?5VhbklxT4W) zyqT`pjUL0Dk1mx6tTGWZmKnwipzjRT#|Z01%0%0-yyDk1iY=JHqsciY=Is$EZu~t1-*H-FeZjhSGC|?sMw`9-c!lC zIGG=+xs>AT#k~(MpV*&x#29MD1oIV@Q>Bt)0{4&N%k@ryWTABkKel#`L||1Z^Fp{% ze*tJeo)hJ89@2xZ3YfxUy<#c0U_vg(G_O>;+i?NEoR4cyjtW zJ(xX|myYjAu>}*j-oy&awJFN%mm&P^$k$~5{0t~vGZcbm=}C_&nNaRj2-xk?llV>> zVECQsuw%;_v3uu>PZPfAP)pu{w7f4!B1eEDFAC9-XL@anD^!}9$ zvkfl^;=+=)%zdf@kM}A^@ScBs7U0wC9OyB74%jxa7DS3}yz=-!7$>HE2;LWr_aPg) zr^A^aA@HEe2|*mN4&--F>{J3KXr$ed74xRUg6xIhfBFc)yBjr{u?NQU%O4Lb^D;V1 z7EA=EO^2WR7Q&y)>ORX?n|kt-1FCT{qzl1&UGbj8t$Sl2uzC{MdEO92lT*I@#lFgX z(ZwzVTQGrlH)=Eo%X#xMc{& z3ASJ&b;nGwITa5-BGnzg8*91qf~n1Tqij!!z$&~GScGt!n(~M4?!153l>}QbvH4Ow z)LkBI<_)>PelzM}05$aOjXJg=UIL|~O%@-0OxmAj>lEEp3P8-J$GMT_CTyGjpgA=`#5mw>+f`z}- zQ{&zlpVJU|!*@H-)!vc($U$p@&-vhUMUPU~!-LA&WnU<)Sj znI?@U@>?I8V-(I!{be7R#wUiv{;Ou4=<%iDe4tMp!4^!k_Sy<<%who?64dAFz-rpy z;uOAQyMshvm3$Iudus!>^kMR2$9Kj0)O*0RU)toU!hnR-F1d;`ZAWg?r2P~1rzurnrMSj+4MtTAkSIj zC=pmCmwaajEt}iciJ$pep5Rd*pC6PXfaZUivV#5Yyv(8U1Y0nHPdJKQNJp)h-DEFr zYLzGvSam8e7YgssfxIa{UxY!A$VCn2@T z7uy1nNn#FktXoSEw!QBtH%$ie6CN{ZsM#K<)q569XzNd&R?dNMHnYItPH%#LNu#OQ z!H}<8-GiUcOq6_JV&&z%ke56MqJruOA5-d-;}(wI+|O0MDy+g+DE6d!8FJU{J$V^@ z2%WudJGd1^!-I_pWb=pZP=SefBs`wnG1(4>H^o5WeD&GwJg79UH@G)ny(Elc3nqpH z?}j-aXTT=UVS>0Y{EpJN=OEtb+BAv4DqJHX`_M5BH%;ixy?C5dSC~jUvIqLTnh7yO z{e_SB*#`X1OCO&8aE3%+6|Oh2Ke2;``?&k@q78vk$#I!Vx7-4iKSaR1>_x)Ir>;*F zyS#yXRq$YnEtq)uaRY4in+}t&sJ+k1BW3vc8@>7X;UgsitK80Sg#MqxAR<{k2l?kx z1->cLhp*c)kUp|r4ZE#FVCDEcV(7XWHrEM(Hx2U$rbTw({uOxhnLhm5x1khUFrkdt z2zL*M!I*c&ed5jX{9K|BFEw?PL|~PCRVS90=U1op=6%bzrnq;mav~j?cM1Uq?-OLP z*>c!?Cm70gKPt+xzkGRq=xA@Q-`ARAOX05NQ1@{#3`##t@GpsT6F(j(o|<9JH z2PW{$LVTa0e3HVt2lK>Ed!^sPDtY_}D(Ijbi3sQ0Pb?wWf(bm65pPBlv!TVaXui0k zi9}$Pe15Q(cBf)8NX#JHWlLi%9$)2>N3{E;g!Jyued5fdl4Bw_c`?+<425fT)mc&0 zkP7^eeQ(|%$W^C$A2D^LD~G0lQX>Ku4!lk7HBE)d{^9Vn!!0RZ z5qr%kqx{`tWb9%1H!P;WCLR<7{Q# z)wCzyKG&XN3nqTuSqPQ3gu&7dSA~xuzE%17tKMAc<17(ag=<0daAVAP=N(;n-TL*V zlH)S%a-9cem7?L~y8FUM+L&s5h;t7<+^Pb_7EItsO?(k3-jd%l?#%u6*OdsYT4$03 zhr(mv@k}*(js0!OpP%f+S#BMQEtuF_dJa@97YA3()tEYXl_hW6sSAIUY)G*M6F6EH ztLNjac`3&Z{N6}wiNLDYv5C-VLL4|csXl&RvF2;^?fJQ~HWXVhQFm?vycB)=nwcuG zy>nfj_|lW_`B|1?3nuV9L40jtk}c2N;=%no*h&OeeLfox%G#MQ+FAACx4@P!4DsMT z@9ZeHVB%%BSaYhGji`&uimdul|n1rvBS zsnJv^<-nJTJXJ9-9V7y)&RmUy=g-B--!7_;Jg4S-j9&}xJ;j(}3nuV9TDQZC*(NsEuYOPUQfWQIG7f5gO!arz2?T}*KbO( z1rz57MMJmmNf6dq?Muq6Ys{m5y72)soFoFPNFN=O2fc=2b7|O9WQo8WFM2 z8_ExEx94`rb)~w(gz<+^$X6CYzv7Y8zhM(TBfTY`wp%L^ScTWlL=--3werGl4Bs4- zDy`PyXcDh2i?1hbyrY!r*q=vu&6n1YF(F5NDX!DT@ayXu zO9WQQE0BkBFDoDV4(C-`cc9pU2^>XfG=tsZl-H-H^2FZG5`k46#h!HAnz8VCh#Da; z{<=yDc{P!j(RQKOf(aZmiXB@6oRsAFP`-1Kr$k^?E6r~4RmWNI@Toexv%NM$iE#|# zz0(I#Y{7&aQ@4D+A3k0U<3q{}kO-{WnVSdGwR7Q|sXCjO{MAo+KYI#q&^?S|3nuUr zBlfCYYNSNPPvxf~W=RBA$*bo_`=l!0Pmkl5?c~*SOyGAGVmwdk!_J(nz&-1lOK+F( z>M(x4BUV_xwPP&?*z?HGe$sm!OyGH<*sE6Fm6adUocCzXB?7DPTL+D1Zf`3Vy1EN* zW^hY-AB72d2D#>54R*RwSKhZ=MT&n5tK{|e9b*ic%Xxo(b#WbvEttS7_u`%Ku(h;p zxrsc|rI+*;0IQB0<-sbOxiImZI=E&CJ|UA&()%K4OA?yyilsH8Ndb| zPlMVmJ3z%+W;E;PVz_a%GqikAo%T;jgB^?7!RLNvRHI3@N&#()NWNj34NY}B4Hy5o z!^&n=XjYk%@H(g!baJag*`E_owyPUlSz#gweT(Tzy}^_CW1}RRCr(a{cK3wx{j1Q2 zm$$*niXKoS%Y;6kkO$NHYGF%(N_e%g*w9O5(h0Z9(H-5<8a-ZF$9wp4{@$ zFUbccHbstx*AcVf@+{Ry%YwT6%0y3|`nrPjTUZt8KMsl-CIB2!iA=o>UkmN{A@RNz zTcRok!n4Ggu*9p1^h+Ae=pA+Vl~V0^^Shps1rtyI1i_d!GvIb;72#vn#@gKfP+J~6 zaiT1Fa5!r{(iU+T$1`hL~RqAbaW963LOCN4;#~y zi3_27`$3@NYB}CMuguqs>BwL9SRoNub?{pp1ei^OnNL(7MuFyhcH_=`XOS<(7EIW> z&xH`Lap1XB_2DtpijVhd&sUZ6mk6wq@8Hn&Ullux-h5-LrF6UZ3iwjd2cWA7b!nIZ zk=DH+=DV?UwHnRTO9s5=F<%~(-c7P#!f)3Su-X#OUcrLwmv`&~xykS+5i0;__qt%D;;ouG59+M>2O9aPqz7|rckGKwvjn7?2>q@C^p z<%@mXuX#!dXfc?tU%fygunO0@ShLjJQWBpGE(eTnx? z55;$WC=ZKkB3UpoetRCw7)l{W(Bj!0HcTm-70fp^Y%UR4h5Ip)1$^&qSa&d(-*TEI z^?kTclzX_tX%&=dPT@TCPXoyZCgO(cVa{kR+!~->)w#t^%96A&UZX=}iNGpcBjSrd zJP{6ejO0xX<(?Y%&g~bShPvO~VOQ}z-_x=WjO!c9pSOvl*n$cDwtG-^O-r~iOnt7L zKURY0VpKabyp}{@)x8z>An>Fc4F03GsAb>l>20e;@ygbgR6W;h7w-nkb;fi|?qxWO+A$%2V1ryfAsW;fVXr22T@Y>B>4g(yB%Ybg;}C0|vi zP4{&Z`i|sVraq*%#8rJB)D%)Cn$m6J@1-+ZLU%_K>6b*m8+T5(qER3}=O*^nqB_BZ z`uE|4mO$&Nb>;1JL}z?Iln*!+^FPF26|NBxi+aw`ANcS}Y4c_ym0HY732)nN#bHC*al2hHz_%>SNPj3%FS3fO0Eu z0>c(eBxGEK25sv?&qUQn>xGqJhWk5Z&6A-LfmOJC8qJdH=k;sO?pKO#PLN8Di4~u3 zfm<^haWX~qq2IvugJQU1*LR{sU=^+fvCr~@3p8oBPr3AGf>d%`ra^adq4S6O@Nt9c z!>&p^lq&aHso*_~VGAa%*yO?<^QQ1=m0DL<+-HD83Rl`+pCA!f<+UXT?B_RtDQi_9 z^Q+HhUa@B7b!xl_DIK2hlYFmQcO!ca) z#;*q-4@H@Fbb>@+)mob@2p!=BcVbl^5hFCp&@oRGuYh3;TQD)S>>8NpqXpZZst*hC z%V`l!18o;Y8Xuk7tSQ6jKPzABUV$CdE+mRwt=8S{UX1gY@@ zA->(+ikX&S3nqNmEQC2B-mqe- z>LcK@B{!+Sc-bq-6vu<_2SfvFI34^}SC!&NanGk(@T)Z_FD$c6vS30#G#36Ohk)a4 zHR^jFTa!nhB7B9@N{PTK91V*1A45#|<-0Ap`T0vy)Q5@d2jakR{#2-Dr}mxa826 zJ6|j>5m@!$?g^OOwmE#bruuko8UPNqBl-Tk2NYW{fk$fbRh2FK!FZ5A|8=nf!vt16 zewYhU#|TblSvbECsb<9c0rRNMCyTQDI<$kuje zlm-{vxRbw$)M~K`_ZS*Y*`()+PY~l7KfXx43?}5KeR##EiglGH{Nz_tsV~7Q+>eQO z^b0>JhK|nMqFQCChr@*2K8k!z^odGk-mRgZ6lLJHB9G@y5)<`pitPBEr1sM2j0xOs z#J4QomxJYcTi$o`yDPp(a;v$I@g6^3np+Y5c?B%mKL99u;wp|I!FXo;Zan4J*lOGl6$o&ui)8& zVGAa3D-b6qX$xgV7c2fYtfNF=6&@co8ttKxig9=&vA)|<8V50fTY*M%>f3l_T4Z(p z+Mu&UU=?0L5+^{t7Aa%1ZTaL$Zqj&;3EXbP4hZXcO7gKvd|+uWiNGqnGNsWRHd>}E zo>!GWf7hO23nt`o@Ll0Hecom(W%JiaHZOY%+}iR*f6dE+M!eV#*0HDcp5-j*xo-+w zYjaq?*w|9^SA|{Q=q%rV)VI7J!#?)Og@e<*bVH9=(SeI{p{~POU7F5{_BYD~r^K_m z`gvA@Fg13EG8dESmb_pV0@is9PxLO{;77!>6$dG^&z+!`Bv*>XCa8OHO=(L44PA) z8j%cJFmX-LtsiaI_A9HFqyOYl`o;@wXwDg#z$&%mzuO$vE-5Z~$4!0ob`@t(t0keV zaLqmNZEHiii8;s6CvTz2;yPquFLR2oR=nYD_(1PGW(GYvEtG|SJO`zRTakBP&1u=K z7a`_?4H=eXP6u^40UMwqX;8DKxT@_w=k!gy;%P7QP=+m-z`iw_K7+65eEQ9$Gs8ld zI+saZUWcf28TIe)F4n}it9*rmu)n7JJZBDFyCj6+YsZB8_p7tD$kh?*{jmLhOJ|!N zO_zKM{U745N-lZcsj_gob26RrBA8vDvkyibup>J*nNx3{6VSMwEomj@QMg9L>W9}y zy??`G3ZH|ey26Ae`XY?IZbLSRdJ`*mW1r{)@6V%NWkMtZt8l$(G#78oflcQU=}Pku zb|z^R#E)%6wmdSY*F;q8_1%^17Ey6+$5qh%TnjRyI0`>HIuh2W&!rdN1~Y7VpSTI; z_H06;BFriNC2@MW^B5@Dltg>n4wigi!hB2?-0^WDNpWg9n%(q;yE_tTVt{;ASS7cQ zTdWg=e@~{hHv}_m!NiobJy7RX0}@d@kMgL|3LYO%rY-Vi0;_P_6mK&Q8N=AkJ!#Rn zaMq;BCTMG4iByiSNvE{h2uU$jNv|F?=}?Q!uqL@WSz@6+yT1;b!IN+PRIv_c*n){U zWjDabPiEwukxF#bv?^+uPHZqW57xvS97pUs_ku%h=4!f{wFGk=o@g z{?lr`OU=`p76sCshr^_v0k;XR;uzr#I{) zBm%4O)oL`8a`W{w&orcV0g+NUFd_GFWj^oFf9zMAdOwi~tSW1r4d-5;(i&G&d(lru z!FrwFCz4bznrU_x!Xy7Q?Y(oB^bXqvM~jwg{ZIWfe*AwgIxjmxzern}-g*$l@b6-x zf72ac8lq@l`lvpZw_2dDmRFI^TNcHzXC5>iK!zKDD6D!lNv9b?L zoF0@7V?G_%ZnaT;aP#H*iwCPxvtcrURdUIFdQ{X0?e-;fLkxRcE*ExfJ=^BqZYx^v zbPjxcTTz>|-ir2&&xiHa-L-Fqs^eg(?CN^|j3_ccCWc{^=NjQ=m;)Wcf; zt6)A!9~i^%Z(+iD(H_VM>Y;TDP<;$t@1kGbZYzm1mkCLQ?vwZq~SN_zKYh-XbL7Z+nZPQ1H${f-+8#Q^>$djv(-`I~W{?YqAIVK$ zVnr+U%?10iL)wfM@q>-{f99ELTHQd^N2@oRbtiV#A>OBB7`9-dzlb=NJDhE!MjRT= z-7md$-3>;N@*;;VCa}s<_^8;8`w8rTh9jhBX(KjC*Bu% z{5EUvcK1Xkf15vOaKuh7{)%53dkLj0{OOpITjE5318zqP@2)kkBVsXJHgN1L9%c*F{F&%`hstKk?f=ywhjS$@)`?o@ragqPP>KiCb9ZH-~rf{9+@X&-Fe zUH`iHX}=v{svlVt0+tCffmLs=?}1(69{PskR3ABot@Oif_P{DlOmSaw&_7MD_9aIw z_CV^WK>f=$Rut1>&z)%ly~nuaP(fs##uiKjt=R(`JM_>m9H9EpfwlhY$P}nHKqjzC zzN)3^OZEL+jTPPWD2Air@Nzp~k}ucS>HOaa`Te>1dfyl2mAI^b`jWq~GbSD@J0PcJ zp8j@_+WRyeI75GbvqtfHCliuNwA#NlqS1`|I$1yP{Zr`F`=2)W*Mf<$Zo6Ph*%kVr z6RHn7$w$BA)(IHAS0=Cu*PG}QqweeD?1^F+6TuF>%>qOHFMYm^1q~OGw=VLnzOfh+ zGfg)^=)_7;DMlU7qh{aLTN-v#8Xpd4*n)}SBHmpJ72%(F*ZGJBo~`b!ROl-cShctH zMz|SN6&i?$L+qfdZVjiR1}e$QbavBx1LR#dgB;_UbexDqQj)8~ViAkHGFuPtS6ITg z%W4GRQ@=iRS~6Lgy*-R!3nl`@{A0sAJ7`@z|4`D}LYuac%G&dx5`k5HLRUeH^hWUd zo*KhhzwQXBiHS<)xDbXdn82&iq7A<3125B)6rVT2(yB9FPsYC_=22C`q1@iN%Bk1E zk`GMCtF>pu`4r8~M8(=nzACK3YrP@|Pd`U+UYe|wIuR_r1;Fe3xJ)9WX9rg}cO+Ta zUl7c&1rvDXUZe3ebBFMk$x7`#GJ#ccU9J3Rt?zp%R_Svflx2&V$>|40`Xs-a#d91n z{}B7l%_)Afq0tz8nW4{2o2OXXgfMI=nb#B(^81ffrA+l@Jm)IW;UNrLFrof!)502h ziaC{dk7Hd;-_0~hX*KYFiN7k9`2V*{uG^aGpM2}97&i`QJB1~*+GqXgz?u}72|xK7 z&E|qseYXKql)xQf3|laP%cs%ov%8}Aa-X3bj0%+qtcnnG(Ko}aK%I+T@{jB6=x{zNj|8>sc;vu3^C z$Niu8pY7JJ*LN3xi+riC=ju;Ca8s(Cj`$zquL{?QM&tCXzJ7VF#)^C2NU7wikH3UE zyB~IMyZ%cV)kl8S#`+1ZJ(bp85fXt__&$j@?j6qP*EVdSB)yXRM7(x_%O}1q(mzLE z)!tFrG+r(_Ce-Nl?_YnGqL2S+p!_};RlEl9w?;9c zM(2M=39-L@O0Mqd(8sWPShPf7RTUBYY@h3|?_i{koVzRy^*z4j!-G%JOtPTg#bdB| z!>h#WTHnotDcTr`z^aEVuc`G}} zJSh`cg=0IB)$08Q-PW~x^)uhdQ6DDox|T+Bs86P@ex|cN;)hIN6^;Nknlp!9>&Dip zMi&o`Vt74Cy=#m4dhH4EEq{5&@;U02uI02U^iQZf|G3|lZE_tf^D)xa-zk`i__Od_xf z#}cAX+*=lAPm59f4~9xn1}5-GBzB(7F$E`|xr$ql5Q)Glyu(AZ^PUD!)hk)q_EL_0 zFd>g>H5N_bMMKw7laPP2r4coc+Q{o+5Oi@dahbyZW=kXgWKrsF7RqBb#?xxHsamY+ z-aZWObV(=g+vfa-s9QgrYhL%IlXd^*^D6!=On4fGLDs%yWO}@sW$dTOGWKX|7h3hR zOkh<>-ldYOx^{3VFXi^0o~!$BwzOi4xrN9$b!r|N*z@v#u4?6j5uDe5On;P0`J46a ze~3ogqTtD(WK#e9MR8T0ea7=1-H+4yJ~Dw-B^l?6>rm|SF30$efeqO~ixlnICSrf+ zgap#5+kJ96b_Uq>olTx!y!$tsU`aWg5<2il$8Fi?p($FdT5?OgmrtET{&c+cA0qBx zSMK)Al2uy&Z#Kc=-@=4**I3Xlo=f)ER8Kp->*>uqM%G}Kr)2`GN;1xsTvbYJ0N?hm zENdgOhGGjQj#h~Uhu?EaRtxpCQ`@@(xGta+dnhvAVgjr1z0qj8FRRAwF7#x#L|v8S zfGqZYEi)0?jgBMM%O8>xB5UvI?Qz85wt6P+<|;Eje_IbWSLC(CmWESi!^ZYAh_AsT zf`3WOw)fQFZ5_SY+E%g;OnezL8w|V6AT15mlX@SY*5sxgy0cTBGJ#bozY<{Qx*248 z1(mQGR*TnM>&4cLOwnS?$l3|uIc_F#I`i;9R~6mDhF4zQiCNB*ePCi-YCP0`I+Hxu ztd{)5cRSvBPJ31aGJ#bkSr|+1;De1VxX!mFGZT46u>})Hs*5bj)8k41;{2Q^&$Q<8 zKbo-PWn}`Z@G~veui^}O@UVVtipb&i$S4V3t%xDcFYl8ZBDd)GBQfNL<%9o}{8+8B zJhV(dHcAlqPGO?l>A4VpH-?mTRnI79{x;(4JNvVfBGVrxunIph;=2Y%S1LpOr?NDW zg|E%cC9v&&C`o*AnpCg95PGecPDYKt@;C2mNnPzfkfT^npUl2Erf9KhZr}nq`F1+l zZ*=WH#O)4;m3GZ0FiXpSGu{^e7A6ipoG&snL=f9ZHLI?FI$pyeG>1T2kh1kdlJKR zTT`?h$FG4pX<=k^#1`_>HUm=Hh7xL~|C<-Nq^_zJoF^Wc(JZQ6szj7zrY%-gyuJ>W zGz%vujMcOHrfyYf*qA8xS>%Jn7EF}nMK19%BrBD6n;pzbIiyGgRwblvf;}4|$+5Ky zg^!;HO(5!247)0F&za{60i!l{1~~Tla5v;9?6VI)$Wx<*rbYI`X*i zL4M6tCVPjnIwmrKRrr|}`%6}5QSaCwc1&b`$9011>g$xvV3i+5DyGdBJ{G8Bc zwoBwu#1>4HWbQ60N7aF+Xw&R*Y=y{WiV3W;8M+1T8^)4-2h==@``f;vtEvrWy<=0f z*n)|XrrA)>V+N^~J5~^nrj};!+y}5X2U4`yf{BvM<|S8US*r$1O7~_>M8yj{jz` z{~yBYPaa(EnM{1%z8Bx1OEc=lu6L})x&+DuR+VIzFYz&v3gTw0;}ZvkuAQl zWnI{n2iyLeVYT?G28b-Kng=;6vk|DKmY=bJZmlLKki!F71Yr zX_aTd;&@Qtw* z__n4pfmJ2>U`u=~?AnocxL%iE5_N@Derw`kMAKcQk>$U+WlM;?RR|xS)R+$t;~@Sm zOw12Rgqw5skSVt+iL3IoaOKPIx$s=^lwbm@N;2V=_{evv#~%!8&wrJc?;s`u=FI`W z#X01WQ)%I&+sHZ`I&|g*V}^>e-!&j%`9359{zmy^2RxBks? zTyj?L>RO+SV>l0RKHns=0XggXHgbv%#;bN;(x-Rlla2T zgC}W%sPrb9k59=5pE{{pY_T344pw8T(1jQ)^|(x6RY_jkl9ErmH;r#DvqY)V_1}!Q#THD|Ul0v5I&LPZ zd!`B>VkF>=^0F0mG{C=wRVCSWOMJNeoWQS6+OPEc|IEF`7EClxi-w8aHuz8@G;xs9R#&ER?6uk7`9;In@a|) zs$D?7j#r6MP=g0`YtEqhS^9pX$mP^eNA7YvZAk_&a=)FOHp6WdH1#SZemm6sIEi(v zc&+>0 zm8F`!?x$0Z;DX4&Bm%3-9M6DG9|}mbv#O6#Z{n3@DUZnMiNOq8FoB`NTBJTlgq*^^)?yZ3JHw=}xf)6S;eqK%{pe*^%up2yOQZ zibKp$UdbRxBCu-Pl_lUQh}~<{Oij;5Z-rqe+!Vt%;p|YO3}{rhfcQ>tseSff0X+V& zySSZu&RqeX!wQHesQIJv{f|MwIe&#!n$EBV6RqqQz_vL#q|+Xi*j%@UVqJNya^U`C ziNLCMV^+Yo$ps{|l$u>-)a!XryH*Wl@{&mDs&Gri{xq7H$35X~mHQA>E1F>oCUBb< z_v76>eYrX{VEgeHiNGq{+liTQ_8BE4b0D{0m_~6eCS)!JP4`0bb5jp3zE5KQ5qm;e zWE;TKM(0TP0~4QjFNNFP3W-IT9-`#qO+ZO2^x}@1B8kANje}BQmP;P7{ibG*xDcAJ zj4f!-&+aY9umuzI$ECrZu7zY@bQeKnM{ZFXoN?tp*4LH@tXj}K9VUq$&N9+d5QdM| zD!(^3;jL#nFl^b=I$eZag(PZ#rxyDb=Q+n@Dvgdg@G+a5B_Eh@c$N+gEJeu+)qF); z7sM*3ZdTxXo^_W9tin%>SXB!it+aFgrY!UB%diC#4P2K)zx@Sd!6r3Z+WvJeO5)0W zO8KW_Bm%4CCvno``g~6xExRY`Y@cO-5th zzP*;M`99}w9^PV0NxodNU%#LY{w1;Rb$&BmCDV=NZkjQ~k35mx@pNx%X6$f;e%P4@?oHN{p9gHUC3*CSn(48g$nKc4a20t| zoZa!$&spG>l|)Y8ie^*SZiYo`c92)ZMO%_Jl&E<|R5@uDvOm_@a{l1d1|iaGJR3TP#Ln)h)x!92`&e|cGF#(p<((C z(yg^hxXv+DG;OQXCp97%wqOFsLE=5m9WSM<#{k;?>@|(lFP*zh?O-fVF*tq;bIlCB+GH}*jJLdnW&kYWrDaHDzl=$ zl0|PK7`9*{z4HzjeRebH*Hpdd#{;`6`=dPQoTecXfmQfw#r~2>_Poo1`mBBGN!mnw zBjw=O?WEOlM{U-;?O>3#o#?*UYKNQb0AG)7BO+d`*b^|jOweSM;iB) z2&}?)Q)Iiba^S6LJ+}DA35u^5_Y$~#VvH(n$B)dmV3q2AlS+;Wxi87esmSNmF3Wm& zI57NMSS6SIgPk!S(5wury{my#4oox@nPM+3SVcYzR3qdM<`uY8pI>xW3ulSIs*=o5 z#kDSGcN=SQ-$6~-%d4j;o}*jd>YM;Rz|#)zZFX# zRh?l1t8ff2cFKwj#BmSJnNgR2GY}Wg0Wcv)`mMJuRj#>hpn8!D8}|k{rj~1W>$Y6w z-s0ml&n!TyD@@?1Uqt#@uSBc;PKQn;5`k6t3dI-x44x|XFMrd%%ZPN(F@fhLV$JfB z$g1mGfvx@CR3flSE_t1>B-(lHIQHYs5*la>z!TC*(!0Leqfhm4-z1%s@*JjJ>7s|U zBWYy*3pGFIpM%!S&{4~(4w&~hOC?crXL=^<;PJFHQZ;q3Hbkd`F)P!_&Aw{X_cU*T zUbkZiYun3b-ed07|0l1mw6)0&ol z^U)XgcDNrC8HlqZ>4#clsZ+fmW|>_8U-MTGJ1;k_+lm4Rc(8(Ox#_AkODKfugEB~- zj~cfdUJRsF;)c_aZKg16!31Ae0Ea%TAj6KRbAyo+=hD~()9CjDlO!LQHab@T_s6av zmm9eY;%ki&^ybE`bZ6gj3|lbKrnC-b^;khZZC9hdvA%lhOc&D%?!zPkt7exg1k;@5 z#QCO5j8N>^<+p`&u}33T`J~8G?UGJnu6EXb2`GfG8P;iX+Dk3ZNv<5C=Cu`j2OE3P zJ!dDeBet0mfmOJ5iFMI64HR$92-e*7x@#Kf5pVW$^**T_m{{4DL&ULk z65Ga0T-9NdYW(6}4|cP^d_S-X-y1R3t~#LP9D77FdiG#=?877HuTUM7ev(0o{M1#0 zwE^c9Bj56@|6and1rz&vh#bJpGs&tnb*z10pQ)^=YsD7cZ6gs_b-tP&E?ihanhk6v z2;b6rC51L-Y-~M-EtohVazozuw48itQrtdl?OCHA4y>QWVT$`D++X46Se(tc)P_~J zwPRTmf+)6N!rod3t=}vqA+HCDt6HAjo3(0Gj?L6|lnAVn+lS5KKGgAmKYJggVYnZ} zPv6S`kx%@6Itlu$_M$bdHqgyM1DIRe;}lykA@|fl?VnJu{+*d!pIZ`vRk%jPd4n-V ztSWS7t%s*eb%lwNY;feCOv(onYO!qxh?qwuO9WPxne*w`(e|v|+m>wD z2OW%Dv7Ai%(pHPhWH(d?2|mk-zN4DCcZknLI%KdT8`R#0VGAbYa-3`UhF+Xhkxd@& zA`w_6_i!=iYOtEWE3)ctH5s;G0zV5PZg+QLZ5uzNr6-w71XkhRRimlUsuS~0yh+=? zenGJX6L^HvXljI&;b(gounK*h8E!>53d2vnnB5te@E2ZHS-qzg3|laP<2kXa*58cZ zv#-vY+&7U3timy)MpL<|33XL%^gv%F@?=xiWpFczz$)CkihlP;N}C~z zYOwrn-crAd2^?{VXZLP2-2G9JO%h`|{w=J+ql8#h>tv!GaPbArn?76`4KRV@AhFI6 zu^X07JWV@H94ir6mG-s(eooCK9z)eJDxlgKQnYjqec2|MVGAbY7>@O?Ob_2|N-J!c zE)iITBTn%h;cqRWR-F#C*QanP7RB)=_ASnstZ`Kg){Li3o==l}U;@wX#hT1msuX(c zq60>cmk6wqYj@R(1Z8IG4jOc4lvG!kkmt1tH@7Ndwx6RmV*(@st8io>b`EqgXBTX? zQHR-DhNDTxK7~+k$1-AR|KG?m#KedxV^-64V>(H_C?@3S)g|x|wRwAt4tm;MBCraN z5*p2|OS@^mV`pi7*S^wdfC>DJi5xuL#?$9s^Vv*aH%@(^xumuyi&5N-%yb*nVrYkeO zU0ouu3P&Fr&G{#i)4yNMCTe!jl5cJk zHD|3Hm(1BPgl#_aiB6tsMlSpAg&Mz8NcxpCTD;S#Bug#%Cx7k0hxJ&sA#GXV=xWkT z82i96qxcryuw?!+I1?Mx^dCptkcEwB|MKR`QkhICx30q`uWPnYhzjL&42UP7F#fZ zXL{m|Vy|?iZuA(oHi_j4+lP@IQ%2fe419TvcXtkWpAU_vg(@jsP$ zV5!b5IAx(kU{y&*1fu2u7N_DDUxUDhQ`w=%3;yP5D88zaFX9t5lP;bcYBcu!14*=X z2&*bG#bOI4O1@7{{>c>kZnO^_?mdOgY7r|DSS8OnqraLk+tS{w3Uid&2W}I8LJHvX zy;O3xznUrbkE;p0FwvV83~fZQ1rs>x7w=MU-=wKshcabB4~f7ke1&2MUC3>E{n`*_ zp6v7Y%k{-2!~~v;h}?iT7E)R;ky)7pNd#8OC3n^t@OsyMSg_+v>i<3mYJQtVI(_sa z{`x&I$zT?lXzNdAinHkF0%nn|rPM5AOM9E}_IJElKeM_tb?*YWIBGhXJ?uL9a6AR- zYz`+opWh;L2d2Oy&j@nj5duPlOkqaipK+ zBhoH65wg0(k%r&Z-Rf6vHsE)Uv|_Es_|cwL(?NG}0f}yUij?I4AZnJ7vD3oDm%ta1 zn$6X$B&L0v@E=cFGIQsaRNE*LEIj6uNrNttU#B9W-J4|cr~W0fWN{S4u9!#G*j*Du zgp)h(eZz@GTbogA!9?o|F_11!D2$w_o`P7nyD|Uv(2Y4bHjxOd8aX%`%6v~E)*aO| z4WG_5;7tm(thTNJeLZ(3?7bCF0!}<2A0NfR%k#5|Rrozpw$TjuvwAkE(L&8#tFvcXB?Adgmd?ZQm zqDu@}(n=-nx><7bE}dDQ=XEKzV1f)zg0H1w2n$w;-Tf^2D3{L6ccx5W6>bIMJm+>p zJ~Gaa&4_lT4zL{N8ikM!9S@WFm6ky_;}Fv7@o}Q_ONaemLddKA>Mn0D_X^zGqc{8H z?@F-+6IWdqL(5~Kq|#+ITUuWHPbGg|e^x}yBm%2)^A^JIQqze6zaoe*yQ;kQ4{w&# z%9&ydCLUE@1XgpxNXL&V;dSGW;<&Ca``VGvPxUgv`D_SDnxrQi?`OievLR$-ww~bf ziJW0$FDak44`&&>+fzT^4e;yfbfOVCOD||Pg2RyMq+s0|aUcZuMfLmX4MPtRj({p<~T(QctWRiG(3(<+e-BTugdcS7k${BxkDua zt8h(gH0zs{;-9MfvUd4lbkM}z(DmmG;?!;!3BQ#MlN-m9i5uext_4w7;_I!g@_Mq0 z-k}s*Ffn`eb}+JwA*K;(_95$>QharLUzT$@NFuNb*PHkPf9r~T!p*MCYH1S15lf8* z1u*;N9OCfWid;3=3(w2XB`dqAnSo-AME29>-fXz{T#7B2_$D%;wmvY2Obo6q2$Kh8 z`9~jb*4|wvuqw`q1rY$kz3y%wUusIUJM=^wAt*Gt!#i9r1WSy%?Qa z*|Xut+OZRbb0h+*M!wB~i*x3XT_$R_o3o|0EPb{Un|-??!4^#5a{(I7oPM3yqQN%o zQEi#PDtrz>e93cdYr1^xbY^H;iUu3(hT!yBq;!@jQ?IS?!!nk5{EjF5^-kzLc^2v7 zsOENR?93@SIf4CHnJQT@fzND+cD~$z-OcL9LS3~IfmQP9fuQ;;X;qJ@Y;`LKf=|BS z6DruBM)RY}4!YPskY%_yO4p7Fd|E|(4>|2DeROav`#PktL|_%ZLh;q1v`RF8XcW_C zTN8ZR=|JXsSY;kgB08)g_@tFMGrD3{o9IO`?4aRz$%2XhW9%&8s#w}Te(Z~#D5x0N zgWF!9!%`hcaEzYs`GAB*V-^uo8GxE{{!rd%r8ojO)6 zt-D9z-A6y}p06Jv*W~)(E7^Auv><`+F>!rjrJ{20A5-bMLvA_(z3}ZS@rE0d-+7Fs zw^p?y_~snGgNOGn{;vMb)$;w23AAEDdx91u^zTPm7Tzf@xAdT1M>psQ^ujvv^Ksc< zuC&sd&a!sZ-M5jz_p$g4U~vz5b9P_)_F4}efnL}OJfBz10*Wc73*8Y^Ny57@&d9NT zd@SjhOF8q&l{U?rTX#Q4LO*Zs{Ozt>{OAx$YpvAP9KEpB`L_+9UX=SdjG#7=t#s!D z34Hs|V6coWqI_A`iPG))bTcxXYaz|Q<^4Q|GRe0Oty5*G?l}Vqd|#1|KCPa~er?@p ztIoVs@MMBs`cegNw^FR1yU^56xphx0_>_Y2_&jlBNoAma2kNXW)XgA~(7$EcrFUUv zRk3dLOg9G|fnNBIDqnA3kyrU~t0#S2$AO>)-+k4WYS$MFMQZO#e-zWlKtlgM=e6%S zl)5?lQvZC8x>BJRwj0kf#=mT=v~NR`UP}buamF{Ku@(3#&aW~`?`tk}TTZHb?n46K z&gSdwudS5r_1n|w-g*MPu-*8$+nDEl?c+>$pDrumb0$8E=u0(na(U%lYD?PwT}}xt zNZ@k`zn|YKuXMF*MJHM;)YSvMutoUwG0;{yo7R%nYDaZ#g#^9<&eyMgHdU-6>QZl` zBf)p4@ttb@GtRC<^_4mo8`DKq9SK^Hz<0R0R&8TVrR{AaT{Li!jzBLgA%72YR1L)< zMWUx_w$MGrA%X9rbFFh)6{YI~2U>VP)e-2WuX#=P%F3}165W5HvV>1`_#BP(<6q@! zP)o^Y-<-aR&nuw?34EsJbJ3hl6mqv7t$BWluIA{4tHmp^j}+8SEZxUn^@AlDeH9vdSN_+q1(moN}i1c z=!{+M30jcAuRHL&bAc|(I=f=jU+$zM&`V#BY=2c#etd35pG@qmTPecTAzTmQ`)YUU zDz;(uX=oiM-AWM>m!f=Fm{%N$t1i}-@}Fz0jCxm_=5nc}BhU+1jrcd6(pxFt?aR^< z4n-uiAYsq5>aHjkM+RgUF-lqWP$F~Wr+wD$(6ugl;kn@&`k%d&JI8a;+eV(b7rr`z zL_)49thQAgne^)rk8vw#sN!4huJq#B03Cr|`md2p`jpB(uk@kKhPdnI?K^pn)L0rp zY(Lrj@l<4aAVzNdXcP^!`kl*EUDL(YY_~vbv`UeBQz51g=7w<|y?%=S!oX1`)I%p?@k` zG}M}GY#cxnu0GHa=ryhRdN$f7i1;)X&*!!kUK=ed^Y6Arm5|Vagubm>&n_n~IPOh* zY;e&L=%rt$9$IUH+#zKG_1-;3LJJc5o_OZkO?gC>{`7Q6sE$A{TqEc8Xp>8cn$wAP zc|23MdX9wtiN5inAFN7kPx`WSl!QANNa%L~cFeA4>T2sl3(xb@t?477Kj$ZN1xVJu z6X=`ogLDLX;hqIoSyY`Rt-Q$JpzG9Hw>NC8q*q%^=Z4)vW`G6+$-d&u!}BKc~piby1MFiMv>63e)O)L8Gq(n zIa}Ty&c9i+wTF&CFT6H+Ho+_7<-=<|X`6hFbk`sfxQfen$yOd_jgqF)w_kJW2=u}+ zhQF)tSYLK-?n{pz_@En0kigXh{?*eq73H`DKWZ7fPe-5^u50jhhUs>)XRsfAcr2cv z1quB+!@8!y%-AiEwmwo+N1&H}y(H(pUu^l#%~HX4V<~1@NZ*yfYPWJG8%me>BkMxF z{FUT~C$39Yk?y*z3rG}twv+{oFp|lgMSiv1y)UvS2X;#ig~sX#^ui1bT<=pYn>_gW zL#fon!4xe>IBs0aJli%RK5Cx0^H)$!}4P(=E}fK8$aWZvF2NAkhf}%!(t<ZR1U z+h84mURXl@O{aE#tiWVN8uMffMGF%8FBN7lAIctjDN>yqdIG)lHQzSa-4y%YBw0Tm ztA6#=oGS&hpsZMXhZT8Qjf~`(CHXT>rPZb`TlhJjK9-^d34K16iU)GC{&`+W&Ow89 z1bSf`8VnP1=ViV86sc-Ued{8j&tp=1UQuRqRgsF-(i1u_U9OauL-U*Lo>ZWXTv|~r z3mXv`J@fPLuNGTbjnuDQLc;p-w^GU$HMRMWk2dbrQ&$fp#P5bns}Y6MT(^|V+GN+} zxm2^SdnUr{CB8LkZgu{iSJcb&wf;ltq#O6t+@f2iHzGZGc2JQibY4g!BJzyB;pgLV zY+ce-&19Bs?mUyVg+FcJU@eu3y~7fAHz7_ulj@ig_ZW$6LMHHxr-gZL9_M9^h=sez zkXQV6r0GIFe_DcPSVapGX)gC!so*B0=4X*FHNIK_w&3zqx^_evT@0j;%st7j?Dv>%%dYG^H5{ z1X0DHgpXk?n4Uk??UckA&G(#s2omPYx-9?NCJqpXqhkMeuHKywb^uiMIXSMFP*!EI>G zok+VrBF4p%%jF5(J?PI`%_X!Tu`?-|{aEKh9@Q7byZjsE%VmerD+gvtXhEX8yn+>9 z-kKZ;6s3xb+b>_k|rdx3&&kZWi>{EoL{Ljx)bf3tFts9W)AD&I)E(N zUr;)9GLE&I-H+TnR!|yzZw|AI?n5GZmUFI@y=0+u8rg-)%{u8UNR+6Rz}D|~B|*2u z_2E72mt1RMXL`P3f{s8h8@hn`mF`R?@eJgAWcdC~?w!9kZBe+bgcc<7lv&79n|39O z)x5}F)o#jXuk@kss>kUF^uku)>!Q*%xkA6ev~{?Xgcc-jA6Ul9+-gVWRu<>us^3xB zYv3^IJ*9J`dBkF1F}|?GbEb_(*bTo@lEvm5L~}vbUtOXD^V@ zf`s8yF#A=~lf{czDG%D z`BBS{HL#ybj&?7sJCeb0@=IC8;a3a#^xiO?1&Kay$FaPAp`>R!aX!YTmsc*OJJKBc zs_6*yn%sR9>soy}*>XtKeAB`TN*7lr`rv&52`$}rjbPPZO((0D7StVyKc$|npjZVs z(L!5t>nunlyN+P~Rx^m>d=VqEd_|=LbE5NZejwPo=(VciP_Dn4NxpOzg#D!t^1Hfr z^x3ogwAJ27*85z4;$OO$RIk-cmKr~lOd45Kcir$E#g;jhx^o)QJCPrC79>v84P~=m zjVEJ=iYsbkzI;lahRtb#{g-rv&I`^zzXqcUDbF@Fq$ii(l&~)$vGPnX`>|&dxluvH zm^iJ7a<@=pTJiXK9f4lhV+@88$F|CET#M1lg$cdeF_w9+=|%?SEH34!JDbgD+LP4c z8G)Crn!_55>qr_;6?u4n-rXjjt6@W5UuZzlf<&2piOg?LJMw9g$d`IGW{Es^Z86%Z zgM*GhuZnBqShZU1N#RW*hX2dC^3b}4sLRe)6fH=s=r)fzly5_heiKCDhDYV>F4lC< z@p`&?;Mv3yavfRi$MUl8wdv(w#VA^k&|UL}sk^SqaVHwk=t@O(1bSf!`B+luj@&n& z6P@e#K|%`>IJ)w0p6%HsKg>m`U9&do7^_ z2^?K{UVy^0L$Ow-ifB~$w!euujKRF+1~L@h=-cF_uVKL`DFhAG{@y95?YYJ*#Or-?#?AIU)-G@ zP0CA=(0QFb#wIw{Cze-5J>KlP!W>(<)2=-pN(QhXfpa4Mw0*W8tFyzETGX(hNT8Q~ zzB_VyMOJRmP-^nHr<(~QfwN45VcHijQli+C10hI?LSD6nop7cH0=J zn}s8xpCMN%?w($mCSmevvIC1&~+!;j=n_Z@ZGK{N#2m>iwf3MGF$xr@2}^v6MV}LRtE@X)7Ip zUigH}wKz9Q%TH$1qi(Gm>YkmEz&>p-%=vMQMRDEI7XB?gJQjNCpHfRXZDrrGH=;9^ zH_$!NBY}OIzqd^&vm9BGwx8~-BhX9#%vq~#X%>;(n0B{mpnHNuLVtbq_Y5;ln$wsj z4c8Osh0nYEoOk}7zWf<~6C%t)_aux2K7Voziy=r6|116xy?WH!VDhoKo4xowAzKhR zWgV~nURWfAcn8MwF9Q8Zm@R)2p(lfg_mw68L72S+9r7ZWyzt(f1!0#|mH6f_q09R! zh<~28|11^eDB?6T)Bofv`jaqQ#Bt3;9=--Jb51oDQAMl)AR$^YKBN&7Pw|-fUC{dn z)McYxMRs{4@Jwl5M0nwvgPuSO5?Tq>7Wvp+^z>Yy9`lmqDyip7QDyb#G_@GkL~k(c8@yB<^zhd|)tp>Qw)K5a=aJ z#jju{u3&wsgyoIm&&CzaVSk4I9$YPeeRj$5|11>}=Qy48HIVJ~&!0sMb3M=tTSQ-~ zKU>s%fBpB?MT_{2#Nl-kA=7kc}zg zy@~%tn7su3w7CoERBL-ygmylJm$}`<@7Iby5$7p$4724=g3~1He)R{TdcEN>l70q~ zM`ivzgJ{uWsD!xE+Pn!OYhIT7qf|(s*Wa8N&^?HhKUVM$LLAq8#}S0-c`z9}t(WfZ zley;R`w|joIX!(|Fv%y8EMk}m^uju2j$v*^B#!YIVFQE7hpM%*h+!ts3tK@SLtNXd z_77)gAKDP{`)9{~tl}YeB1(0v+CWykT+1waiP?gL_+2}^Crc%v|3R3&L=4`i*}wL7 z)q=+rzZ*R0!cK3Un?(%svC!)}C%PVL!+L)eZ*$=Fffhl$UF5*Fti7hz+VfGS#=OZ=CJW`_tk1PIe8`gwn%=EDyNT8SaZN5Kdu7}xzgc$h_ zPH)5{zB};m1bT_z=GjMPV&c2utj+z3{A<5bEuvING$sC|{Xp>@ zmOpFGd*W}x>?P<0^@2(LmFZbrA7+d2LgL?NeMp$S1Z~wMm;_Eq%_4@`BD|0=&ocG( zz`NxgPJB%aX0NUo&7;r1+&Rtn)ISM6jxjNF*2fSfF%#mq*-QN9rD9pnkj<7q2|m|m zS!wo)y^3klwCEbCdg`B;K5dx_utJh6X0=c)yX%bf7+I+gWoB)+Tm zXTLHZ3%vww9{Dm8W(yMH3Z8anI2+YNsHy&pVJ6T^{5FrrnF;fKTa;wa`z~ZS9|y&6 z^UNSKVYd89JhXEqxf%y&Q7RvUpRciX|OYqyV_)XbOHjGtWxr}80 zEWScJV!lyPdR3+Oo79t#K(Eg;_pr#xi^%lrTRGwQ++LYduQn}oVLU+#63aI3XVQ`+ zGIF4pQ+qfxR$ff5L$5{FmXJWN#u5A3w16b?NER{Nc|MCZkG4<~E_D#`0YNI2L-{pL2x$ zJ$)W|J4?jaeXWL)ZYj}QV@D9QATiYLD0>z&kCaRmF=ofwDzC=1pn3XMm5@NM#_Nx< zai8Ldy|0L|{Z|F0UAi+}Yd4Uf1&MVzPq5kz;z+9tBF5fhWt5zjt!ND28ASrU7TiD1 z9u=gV>M6Fj(rgm)QN(!LlCRM3>`1%4tt26VUY{19 zWtUIPB5N9n7Jl zFEPJSQDi_b5yLC_qFi_AP&%zxX$cARYPSD6D;^(C_B;?VM);qQFZLNl;~d%&v>9$F0lp=$eQTVn0VN6grW<^eZkQfnK@DBlfGwD%qOG2*f@=m)DQf0?xd%P1F468SmU^`;`ssFn?5?YY(^)kq|E+J&oNwJ=Iu-OP^ z8Wczebg!hltD%?2;?L}Okx=rOiF(9Y@h?d)oJu#Hvyjk&guWh?-Jh_TsFk=e}-B?A|U7%vL`Vo`_vY2|k{30jcAc2jfLNak!eJVy;NXRqS9Cx|&O70+oy zblGlx6KFw#=bj+uyg3Gg$a}`~pD7~u8G2zno*#?+lWQyDLoRAlrjPP|f|@z&w*`qj z$q}S}$L;)G^!I$$S9+oqeQ>kAa;%D;Krfy@N@O$BzN|X?KwD*UqcZdn&*CcnDy-H% z{fs%6Y$L-H!%5*?+0?kAWa95!Q`D-La^m4%^mCG$UyYb8NQm|mrOe0xCbEC=EMStz z048c@CeTZ?vS^iz7=ye%%ihNZ(g)dMjda3VvW*0h^)m;Pzc+6rN!HWIvHJ}O&r2t= zfN8{&JNcCtTYFIN-mylsAn~NiCXzIM8tHyfWB>~qXrYw);!0oE))VN(^R5w|hf9m` zuv2xV*58y)S*zw(`)xsDVfa>3t@lha;*rSb<$kMy;#s;eoy+ri;jz#QTb;jS;^m}l zaHve%{+OjZA4r^}+sM?K;Us8QE*_)nh*nC09TjMCo>do*g9`i%FUOKBUd9C1j&*GO2mVmmHWBA#yc}>{(jPyDcg#Ul`&~3+-1kFaEY55uKDw zs!M)kXVOews^tT$WcQ*x=j0kRXv>3M>ljJ&uJ!!c{F-Ei?;oUxkY?%^3 zqECpdRy)&E0X{W3kmeXzQE@tr;f|ECr8nsyfM07g2eTvYl*RV5E<=1gvY2g z?XqmF#WP?O&=cr|J(SC z@;-#Q?))Q$)ww}Zv6Lya-7+<=R)#K`kk9}?E zwvsM%bYhGVEl4!{ID?e62q8V4#aE!-)GJKy`gWr=%IFF78dWudgiQ+~(>{r>C*=(( zMQ_A*pchKT7}0`+$Fv#5&^Lr+3%SXOXFpofZ63CCW|tV_Tq&4%mJcT#U9OXBJ$Wg@ zXOKbuH`V%>>%?_r#~r9sS z3L^zsDDjQE#fhk1HR$Yol-}bp(1HZU<}-ltb!lslX7t|ASvmr}+Ioi(T4oygbwk8R zx!8<;%~6;B&HFA|kkHrTF#oP|<$Ja1zy^8(y{di>CBcbdWYI+tqh&XDdZ_htsW`8P z=xw4uiTj-x2}ExczpLl)C&j);lb7|+abnQ*f%Ijw&(e8*2GR1ZY9JZ;Jd(uoOv-p9 zo^N7iUpir74oY~gMzkPdT_}h&=U?R--C6YAjd?rKfq|CvGrvb6fnL}O{M!k?c-Em8 zCF$nF`g4v%;r>D7uMrVsT&U=Yi{`YYWxdMqe5QH=y|BOWnM~g)bW*Y5(q;cxa%JgpUXQniQFPyg(~>XGc#CHZz3@Eo>!Xb? zeKoPC)F_?X+_xQjG{kGp6=Lfo0f*qbq1>TorXrZ#(L zEZZ+eN1#_qpbr^zdNFBUW-*UZ`T10Or(aol=cibabCQU=r#M#E1V6IqZ8C{%GD97` z|B12Wasb^>Q(;#!a%cXIj>NDCA5x;-67pceLLOt=jX-J~eBac1n3~b^H-TRIQtdcn zLsz7?Q92ciG2)DMZToQYq4_p4s9`R3e)`YswQ;e^)Ml}hQj1^bIIl$_XwXbDF<>ic zU!VXl)r7K*soRYP$|T;~kw7mo;}f&BjMhEX0Bpxk`bfMp>FiSzCy~rIchfA-xeem(`lr`{*9#5 zxB5KB>X82QS_^~X@kPz(`I|tm=DCB(n#1eJqmHhe=&uZ=j_dEryZPvYmM!D>_k)(L zB{jCWsq^W7O65jI(WY*vWORAjAXJlAI^uqqe zb55R~Nauf9Cdb*T*-wA>L?qtWO(mW3uOeamDUyGsAbm1@>=+~8;xlAC7J6Z?K68jCJMkQsk;@bbv><^`FZ_)vo~@8)EtJ0VjD;dAA)(BlAZH79f4juNAQeqtrn0seMQEQGqn`? zW83=DdZ&>TEl5}%+fDinOd?a>iyR8pW8IbeRu`nim2D-g;c(|P;+;F5(6sJGY!QRu zSa3h(^~#e{HM&ICR!EfUn?}M`a5`D!WARwfR_Xu2Bt`mt(Gln+vi$M9dRnGGQ%W1f z**0AYnP#A9LBcRNjZD87PnvFP&tt4|a#rNeJEgVzbL$B7YCJrRIDU&KH%U8AjA}xZ zUf!Fe5><**v}_}3WbT~=GIxC|BgW<`y$!V#=e*0LH{WXLVjxjHUm7|0X+BZPh-?LC z=2$2TIs{3jDs|Km=!NHozZGw1p;WsYD1G+qNYR4CM~gJ#|8qXs^Ht^Is(1)=RDt$VCh|)fo@CgMvbn?#AEViQY^TU@pQvvQo(vNX}+t8F@>g(j#pF3 zsQRMsTF}kXR}XtytEMG=P&Ap;+Ovsdd)&-8K5sJFyJi!qYHx2mXPrWJ%}yn$eVTKk zUz$aQ7)5v5}ZwfVjaoa?GzFI-TBdJl4;s}D~YIUz3v|rjjDdF-7 z9f4lw52ljW*;n)TiX=|>47H<9lgiWNJUoNT?sa7B_I0GRO*7+m-*u#j&pLA8hS6Bj zeFNzivW8UpY2?Ju+ZE{jFSTj)(XxbINKbsRhEy-Ify~+~hy?c{bl=W;^u(}x5?YYZ z*Zg5|3)<$F13i3S))DAc;l*kqH%=wh4-pEiduSe&2!nrOVaZ(Phiu=?L_~c>J5>?)RnGLY?W(5_=`IAkpgQDw0o0B~__t z-3H&jOBY(WP@|=+BhX7FE#Db;WzslLCV z@!8^J65b#q+baJOn~R!24!3lgVdQ%IXh8;Omz$Sil&CsnHIkt*Hm!gEMf zT2DrlUr#E(Y+#)2vYu3Iv!29lsBdKazkl)n@5O)fFP{9|BDMdyS6b4yuZ}=3jK_0G zFH4jRxz#3X`V?}ihKO-*ydB;8Em`{8t|}GRxVYBEb#A(nN;W#CkPeNS{BhNe zX<3)v!RUq^FL zv>>4$;R?mqqbcFPq;qd`>In40mNpn#RCJ8g%~x&h{4xO9w$g&T)Rru z_jpjWAc6gu>-5vNNadV~q|_O$BhX9S>BJpR-0k>#!X@uY?c2FY&wdP`XhA~U4@I97 z_e8$Cbk``^$8M3H*pJqYaCjHR5rgj)J((ks?2n{(^Lyz=1|+bD@{H*t_elG)y^!*s z>YyXg3$J-TUUhvamAPf0m8%oo2!{mrP`+R5|3JFi;i6P)Z(ALKUf2o-!<5km`k?$p zX--8)iWVfWhw_!8)!FHog^MM(0UdM%dg)u&e`;BJeM*9qR?MEF1qmFLgucZ5Pmr!( zoh!VR^f|Fi?PEAQH+zf!2I=PQNDLdim0X!SU#0(@Krfub>j|_VVP(CE%=kMdix}5J z!bo(1jObqH!pQdb8BY`Ye#|6wLbD>!g2azg5k&ket~7nAkU%eSd|}H>palt0IuY}K z6X+%CChC}(KnoJX-IB=aq|pB$(5rK+WhDRNtYV-AiRJlMklJIXWf21j^qQN#hFG=> z&w@Y;61ASJCC%z))w)Qa*T44?v>@U3eG}O+c2*XpLIS<8hw6KY=%0cTXG&ZTqW_BD z;#pT*RhiEqT96ReqPW8TH-TO_8`PHyV~8hhQGRh;EUlhE3lgH8L`!5Y6%yzr&bK&M znF+KYAjqiFitGy;Tt9 z#$A%8z8tD7%xfXx?mh0;=iU@gE6JrB@kQI+-$PEv9Qf!|d!3)TV9=l22l}(KL zwtDs4O8S|1rM%Q}97PKf9a}FTH#~Ne3)#im(#l^oCCjn9ZQf1p ze-lKp*)64a2hPbsMTStcG%v?<&z;&$hAg!Iqg3l1Mo612zQ`4__tM2cV&S*>2|?Bz+rfp*(NfQAeN`wwu8)eSCtnaZp9Y;#y;h79@f{@La-1i9 zZcL03El6m}8ZAcPjMB7R+jjIiSG^#CUfS+}Mhx>BNV_F}kvjd1F@EV0L|oRcW#^8# z5uXav$gtFnY~_On=GAkJcwDUqeYm9nwdK12+FH13L84jeG%{(#CN|%_HecDU3`Lrj;mtKI}NG@iFSQwlF`$*vO#ZzB4tRK#&q1x26P(V z|G;CRm%irXq{?*R6esG&*W1y81g#fNF57Qon`49`B{fe4`u1ZhIxOe!Jr=c8=!LCr zFuZIWNH5k~NVay0H9q(CA*DJlW{x+PkhNU<{H|9ri&_#0x5>WbviEEjZ!a?HtVo$eR~=s{pS`6g z(5qm5AL3gwf%y;H#fds4eCU`0Q{`v%VvT5-ZRbOjfCN?~|IR;3<+Ei9eQq^KwqFrz z-hEX|g~X-`K4gxZ$lQX&UTS;3ml}4`MGoM5soMUjN}w0^1^(sX&4F}iNqcsu>hE34 zOvGRLeTc2YB9uxt>?dozNO6=IM6(V33)#VJeW0w>T5>A<=n#4CLU+w3A# z7D0i7sl%jKatPPS;5o-uIF&z$Ec+h87PyNT4qPMiJp8Mii|b_2f`q0IP+Npw=O230 zlMQn##PY=NFYFKh+=rbUn? z{b|ujdB#ULO|hdLE0WwU8pL*zD`pLg_V=8{tmwT;9h8abztstuh_bK4$^F$q>|Iy! zUg`q>vNZ1@7iG<~7$aJyRSPFw8wIn-F4zBv(O{A-t^Kv764+HA1BrVC$Cu59JouMpe5# zo1ARs%i5MbLPiC|lJFLOY|N75W<8vCW+UF5la@9esbshMt+`VzNHpjiO@1u)XW_ff z^B6Z*yppy~9ITAxJJp(YOeN4u-``qzeUnbSAD|4%r|*eK6nYg&_ErdF5o1IKu*nHRY}1=KUaD&Q->|lJ0g6|6tPw3pxV}y% z*$4QsmP5Io%ncSQ5?BW2ItX7xkjd7hj2E9>tytE>hMKQ%A;bH zm3sWDMGF#1{#!}JpqVUZF`<*`e!YP*#ip_1&PP!s&`VP^YiBUYyQY#YucW-^IvKPe z;q-J9@v9leQX_;;=H1DBirt8wN{eB!Is&~k{jL^c#NtBAt6SZa*qGm%ZPkKAkpmlv zt2B+(Q*|<3dK#3bUj3DZUw-R%RRX;xoL)yd8h$!KdmOspYkYe4F6p^@Q=7?z=v5gHk;m63!_1}#WvD;6wc-A8C-xK>8h$smDV zLL>O%)Q%vj$3XKfkXJZ*U8KIHkS{YgBWVD?sCic&@ zeQqX{E6HIvJsn;aV9cbTXRug9+`2rU_ALgFz@PxY9xvDhq9A zl!-l4p|Ie4k4&g6v^`e!>f-N5afJm}TF63Wffgi$!h$OlScb|%C@ik}q{>2NAruyT zzmW-*g-}>zE3!!r2Y9~b~o$#FFc@`=szK6~-luknB#MMrU zP&%n9r`_wAP&x^f6W1{@p>z@|C%$LTGL%k2<;2xaicmVC7t%uI#5GMUL+K<`PF(Gz z2&EHRkkI#Cp>pDCCq*cokU%e?a^fl>mZ5YKDkrXXl7-RZsD4m4LiL0Gtp>#q5z4Y}E8X2yY zQG`xL)0C*!xzNb)-D)OuGI%x(2BDGRS{X&?WYB_y(8zEF2FuXN2#pNa$|yo7g9Li% zdx_AOeyS?FYtKrd_szQV#aGF&U82%QXCkih=N zwK!ZO!?iMs(8(ZyUi#J*8X2yYQG`wgElA*~q~GDK;I^2oT(ni~S2!boBQjcF+oH`G z{$YYBT9CjV`j5X*)?kbs^X8LjT{6eh6L?%CZWWwQ653|a|4yJ6J}2l2v>>tb^K4Sf zxH*fOBY|Fp`^1pR^Rgn)g2ch1v1H4ejakG%0=)tPW)b_xo3bF#g2Wb61S#}lLly*D zka%z^icH_}Uj%x|U1t)nlWVhxffghN_6a9`scZg&Krba5e}Bm;D*`P@RCzL!G^+kz z1bTIjoq?B=q`dibHWkH|?iF1#)5T||1{)0d-oSp0Y zE|z^s&FMsP%P9N5*8?p`_#6l$`Dj+9LIS;%s8Dif{-P}EffgiEtA&vzc^3Z%fnM7V zgc4`>q$~)uAW=6dj9i?b@E-(v<#-#)XJ=UvXhFhxZ5VmpZcY|4(1Ju0zZqm>rT-$( z>)pYbWNMk{EMg2wTuZz^&rmIWuB|2Y%SWic_m162It+};f!i#0l`nEy>y%Mv{A$O05Wl<`$AQ6~n zF6o^z{XYowT3>lSseL~*3j!@j94$GYIBdwOR7jwg=inrA{#aHq(1JvVSBYekeO57$ zK(D*A7L#F%vWkHgB#t*i?%`w5>e7J(sWl=F_1tndNG-} z|I8`|T97cLtt6)W8DpisUm<~BIJ)Wyodu5TyJih>9GO+$MFPEW4Cd>iT>qFW_jQxd zK;j68N3L*W85+nET>r>*kg5g}3G@>BN3M2c85&5Tf8;tyRRf6@p?~D6MkX|ncqH*v zl`k^aL8=-^v>+k$k6f?FGBl7v|HyTavd};xfnL~d{HqaM|HyTavd}=H1qq>lGtMxz&5*} z)?^~kOJDQ%x0)zU0ER`FSos@|{FDxP7Mc#f*e&sz}CD4Mz`8$n_ zr8n%*Vw8ILQEn3HmWe1`_Bs*RDtU@Io1_&b2tP1*zY%j5GKmz{_;7#tJq1E89JrsFot zv=}pt4d{y_ja33INZc%!Y8tiFRcos^c9b5LYGfkNYs&mY(?p*cS_~y-5@o9wsn@x6 z=cA?~Gve*V*w<e)eDcr6+%vZ=&T~C$x(@PvhyI%oe^COU!Hd(26H9VI1Z6>PhI$>(%-L!eeUCq94Anjan zHWOAP&cuh9ygV=+Cc{ z)Yioo#g;DGbdRZYp8}?gdT`}AHPzao5@kFog)}8x#Fl~9}MJ58h@>JMlO3v9u zi&1)G8QN-6TPoV>atkk$&#&dGC1-_Tlhvoi>Tm7p(qgQtT!VIKMO6YVNIb5QWV zx)$TbAc` zn8wcRrV?0ltWzUXOViV3TeTSTn>~~4ligJUEl6l%rPfvzd+e0v>a2Qo+B;oJ61WaTDJ9aXkKc^3H7&j_t9cFH~MB@>}Ljn79?8myr0o4 zk7+ULH@Zt=CI+Z6kU%diA^$SPmNAlDktr&H791bXRf z?y@P5TuS!ORC6rh0E<+6+ww=W7`Yb&%aLomRRS$YXmbgzt;Q|eEQeZ+&qSctk+Igs z{TrDUqx`3)isSdXD&b&?H`X5)u3FZ9jxsKdnXCTRW@lOqr?%CVxW8Jc1X_>?X+6;B zv}K(ZW8{z$%G&##G7;#7CFJ^&u#a-{m2N7579^(bZDc$jxkHQ5anTj|?8o7m2=vm| zJbs9iA`h#q5?FJrQ`;pgjqz{BYcX6K_EcWj@oa+pAG9E$&9$|*YVdHd5@h{S9j}l; zuLyaU(R8$~7GwSGK;^{>gL?nKXPm(gjvME;uvYI&e9Zs-yu)?j zf6zE@!&U9Bwz;9NGJIJtwNyx;7nYE}&9PyEvh`|;N}vUaS@yE=wGQJiAEeQOW%~_Zv}o)$fdoDRN~;%y<~jx1?unjF8he@fCUKv{H=2TS_f=En%i!GPB_^hCNxrtmnvVB(H5?^BJttq%$hb$E(`Km7m!AA;y)l%T_3DbzO@70n_l%AT7`oGnPQ>O#v6}cxVeqEg;v>=h(t2|?MpKJ9PnloO` zTgg)yyd#nzfnH0yRAAkDJlA4GuU{^2Pamt~5UmRqBx;qZz{3AB$C&N6MUL+@PRU;~ zk|2Rzc^5ddOPB9!F>E~d$(!WiO0PUl5?YWL`MMXYJL|Sq4~x(%vSp9qN@}i1f&_ZK z+t{0}-*Q`vk-YV~Z2fhRV&L^a3leol^=9)%n`1QW^-ey1%1tTtGMXTPUivdwwj5tE zDBnxDH>{~98xUEx{Mmrj$FZiAyqxp#TV z*W0hu8Xnt|mzZX}QrqWi3k!0*@N2E+CrlG0%e#}5Y0X<%1}KAWL=Ys< zOB>;|7*z|EA)AZ(DTR1F(1OI`?D6(@T9{+l#I>~FKQvJBY#T+8K(Emk3?{FipR^eF zI~HdlW&ISdL?;O?NCcFyHH}LCq}8MMqD5@piU4JQg(!jqdW}9@&D8OZImVckDQt+F zuacM711(5Qm|4wKJJK8@(j!Fi@iOp4H_XFO_m7y&qv>;(zeasZ^ zm@#%43?JP)%AKD~R&w)FA%R{vb{P!GA3sX1t_@TQ^XnYPa2(s)AL&J^c$lyAWvlK; z^sJk*>YJm479>UuZAIRmy|1-ytEFe9eNRUy{Xa$!B+#ov@0R5H+y~kjd|KqN^mN-W zr2?-9T9D{hq$L?8J}X{7cX+`8TllbX9ge zj3j75qHY!bwVULlT3cm*Scj%hMYz9h7ihDx3kJ*RALc#C_9d zt#!w2t3lhpCu-}W1&MLzcqW0*o3&Ea{a{Bs4QQYkd0QcYUbRo8lD`u-X)$UxYe)}& zYN-797D>>8M8nw4 z6hR9T+Wbn3u_mb{O`cpvX~pY-1bQ8*wV$*+lBmTfy`~-gRl!>6@rdUb01Fa#=ba#D zOi@~l-9tOlIYSC5bDld&NT652!1H8SlMpRNw(735@=^=s$ju0X79<=mohJ`H_?wgJ z%<^#Cp46va4y7xv2NLM@CE)@&wk$}CvDvLJJ@e*+oH)3pgcc;OUARlm@9L-#_h-4& zkZX_SiszyUT9C+AEfBeU|4p}pB_ANj|Kk~MbLtTYczkBJ6l6LA03Yb&|Ph2v9nhqbp(3l z>G+u}e)T>*qwls)^Q6=2&XJBii7>Yn5tdq}7i7@05=4|lJ5R<8B3HXfw0Ewl()E|W z&$((rV)B9aq|)j=#*BIlT0Mo%*x)K{fA{;Gs|0#!b<$!4U-P1dN%qoe-nwW(!m;89 zGS9SKi!ncFDqTO-O4{%}(%g5|W1*MU3R;Yq4O8fYl>5ZZ!%0F5600tKBI8X3wHOn3 z1<;{Q<`E-rT_n&;YhC+{wlbQ0Y5j5`B%ap;El5ni`H6gA{N6sJt(Nu(qd=n1 zSYS>W4~|4WaUvbJB5M z540e0@bFzya(hQDM#HgVsHe?dsU+_uNT8QC@@X+T{5_g_B(9f2-F}avss)MGh8Lu1 zNNFv`{1)TrhTueLH!l?)3%&4~=PTwGgys*bOg9YFudrZ`Ipe#5lv%!6i;<_1J+)1* zO*_<%B4|NEn?Gpvn0c`QJ=UiY9mcP7B+yHn)o6spoiozY;v;GGzaxk?dsQt5UOSNn zQl+XdeSiD+6TNCd!e+oMGB29=9LNcSm>p#ifA!fx{j8*I(t&7@$VIuOvK?5IfzB-YpovZLnEcI4U=g(_unfl zDuG_wGn^LV!qIT)*|G`Ljn@M$NW4kTOBxP&rNxN8y<8ezV4~VfkU%fIn)!}m{ms(t z(xYkOfZxxxYIGz{{4$dKrypuDrhVKm6&g64y6{rrvCs>zd4r*fU3SwV;z!T-*RMKb zk0~5n&D6NhCoRT2?-Hz8^FUgxdlW$n656VW)>ak9FJTr-0_Z!wUV;RAX=@xBF>%8c zxmvs7^d?_t(AN4?i-SF15o~x{Es3_ys1bdq9+aI+52xk-b~LY9W+DcEuFh5lJk{!P zb;x$vZNCRiDf)ZOQYFw!TQAjOe7LnzE>dSKeZX56ElAA$QJ(pnd#1&RZXGXgxALT4 z`RIcLdTHyvT8w3up>j;pL^`ka?=@uAf`k%(%T%N0J1vG|ufg*Af>Y@G_}^>DDuG_w z>W&uUTDBhY-RQ~m2(JfPkSLpS!ZhruIfm&%HF>~oKeg{7fnNGEnAjkP>})lK#_@iI z79_6iZfAN_)7-CI%kN;*oBPrYyi`b_7xo^WPqs_*ed|TS{m_;_ZM)wtUA)t#wx)%dh-htOp%lFPb2MUfSBS*1Dz3 z=T%El7;9p1~#>&uB5Gea)tfy4aVBxep!-z3?h981}DxBe#j|N3Znz zy?U<3K;l@D!OYO+rWT_XyCu8Z52D$5sqk3ng;$rsum9S4g{8$Z9*l)akflD_i0&g?o1*^hF&*>TTC#?K8F zvL$7AvrnTN8Mhu-$SmLPX7`7SZ!X(K+sj)ERFN(<_0bXNbv}FnJMFfc?YkhpVQQKj zDz9$5R5F$vr7Km6?E;o9d^fY$*u+@)=mOS@f1jbxMe$AYdMC!q-5$)8E;k)V(SpR0 zdJEXZ(B14>tRT8w8!l(R9w6l`HbF2;ZLUe%ezE2AlYcBo>~1lieKMx8Va$mW z!$$6uUG`O^>3QsQ1bUr*&h@Cp(%9*D;(WB-`bmDkvrhljuAayW#JJvB{o=`2{`)Qe zy?;_a? z8#k?yR$Pr|w|gmUPWCRw&dNMyOBI%Djk|G5bUb@!C9}8jLpTvPqK;DMovpGzV!Kqm zN&*XUQdq(K9gRpIEt0@?Qkj)4(3cZo2P!FdqpB*eZH`Mx!xGub(~PAzcQ7jX6IsD@ znZ2g=#ts&VY?(=BIbB7rlrF)Il<3BJm1}LD=m_+>xhsL~Hp;B|sVAG9kBjk~`1@D!HZrqnCvsZMm{d(^KCP(ICi1I<79^UFU%;x~H?jMY=_e#HZ7Nly{KK86LlVLlq-w~lJacgUqys#5c@G+kNo<``9l6>bH=!{ zggZqG5-|=7Sc^O9%qmD^IGSpiU2(EJMcRMqqa)Buf1Ph=93h{Iyhp0t^rUzl;8lz9 z_!syimdW3(985bNPt;veNbKb!Lrp$198*UI`@jow>d!tbSI7t*fnHcbgW*$;OY+^s z{PKr0Ln&I2n3i`DE9IKTJf4Yc9x27%$+I0t%V~#t>j?BRIWA&e`_tIkcJ(;%FrU5h z=+;uQb4hJ_@_GXMzQ@Fd?C)kg(jbuyI^fXJ?8QB(Oyc zhDI-YD1&Gdsok5LG~cEKW;B>sv*2zHiS=0^uE7^e9hCZAJ4pG5m($f8 zX{-}hsDG)h{H(MyT98=#YCbFEkj{!+6>ViWTv)l{7blgv=&U2q3+u#dzTu&q zeeO-Efn6Jl79>{MC$j6mcC$V!#kZrcuUs!bdh$xT(4~uxKrg(~_^wRpM{@049qF?0 zLlWLCah%uRIUnVICmS9%p`+Gir)WU}$9%5ebu6S*?r%eb>0+q~aSnLh`J(UP22J`WV@}^i$4Mn=4twT+$Kfg+1S3 z@So?x^M>D)!ej18Xh8z&#MQB;T1uya*QBJ5*1D?}y|CvS4CjUwRyNelM!h;$rD#C{ z`xwt4dHRNY`BW~t-_fWe&zA{mDqnuXUnr2IHO3{LZeqPf2oU?MSSx)8XU6XFk zfb#_X48T3Gmy$DWpUgHW5?YW*j*Vv%O2{lRNz5`FAN5wccQVQ2OnL&nyqCnYz6P0X zU#HGXM%Gk(eJd$LkINFy6L5~ApEIx?R4KeUm*U}kPC^S3SXzG03-nZStY0F}&huDD zpjRQM1okw5F}F=(+^yZIzfyP6JlS*DSqUvj=FN-g*QhJ zz>RNPTj>Vv&Ee})fD z%p`)UXfz;hT}T>?3!NLQ4WHJ5Jxi)mA`w(Y`+QN`*)X*Hu}|IGV-LUeG!3#(7ehn40)4Bm zX)v%*)b{oTdfHZWItTNyxNFKn_2k3?PA!z6{zOb&c_RMxslQsYQ9h>@N@Ubp485xr zgXi~rQQMz13`W0Kt>IHvmPAmMoQ{nxKC2NfBbAKtt(iE562vV9|J)=XPO1cPL&862 zSl+3T21{8HZ2OWce55orNBv_TC6FIu)Iy0S8`7ZMfg&)ik|&4>Z|w11KvUdxE|b%~ zmd@_%o~MKOC=sf6P8Y=P>s|2~8lZ2zJc*zx+6U`&^&^I&>yu*jRkb}*?ot&kCvlop zMpw+JSpjuEc~S{dg8CCJYGoIklv)u-^^^&!`t~plZe1#dHMRvJ9Wi-!_-o3J{lz5e&1}>+IAl+8;@otwFu6oo!34#t1K~*&36m8J1GrIn2s1y{rNRcHasLi zsJ8^-ejjH!4iRuKY$ZI-)XsG_T55>CYX&NRV(p~fhxRL9!{)(8`$9Mo{aHMfxzZH# zb2}-WBW5vbp~R!8d7$<#goiDD38J`tGj!_ON$K9Ui9}G;6??mC6z%ri-R;Mg4!K~;x* zW`Vs?4m3&cA&8*z6R_&=OFXsO07fm8SYSE}4(N8lnjhT-f!ijd^A6zAH}^{fRarMo zhDx6K@F1_5AZkWN;N(*?IaHQYPE(tCItBt#wnC9nk{}Koi^H1B?=qA6D;Tv<;zdF< zOlMobI%J_B2JDE%%4;ln*;6NppeoN@(Qs$*W;h^L@x?iJXX4T3uiZ>J=+nNB8WHV7i4?F{6*7Qnz?HjG**G1Mp$8skdnw_Q7p{ovPVjQggjH}6C1v^MDSBL+XX+N(d~8cPIK?SB^mnW-ya?ui0HbV~@syN%P-Dvv9&s(Yhg zaZWl6ICq={zmI~tqtfB>&f{#~p9q*US`ghe9}}C#pie7LHR)h8Mt_U?kcoNG({W0< zW$MPiCrZCXiLi_)v38aYf36-EKE|94#;4ZX)aI{xNd#5VrxkhC$^i{4wnHBeZ{CeZ zz|{K7VC$hH%=mo->{FM3zwZe~`!R9b<`jGU*4+VJN_t2HRXr#SgG)ZE!2FYz@)<+D z@zDMTSf_zKrxr@ced4U#p4fXw4a`&BB!a4{ZHj;^G3()mn^v#x)v!gc9Zs0pKA3+! z9uD3OH$a668(IDG;ZU#Z1{mPGiJh7r2D6&4hV3)+1raMwt#9qx68nZu=N(!_!MR6U zA@c4*cCd3ecouAeZ#z~o`b#=p=@AjdY;KRKFJmMhlqjnb4xLgqKyi}xRD1t!i5vSl zW9aB`iJ&U_ggV{Ww(aqxIDua=pUvlm#X-Mb*#K$N+1$@j@Hr_H%)JsBeOj@8)vFm^ z4|B!-uac#7P-2N!Bn%z54cdR#+WC&&Hu$`zD;Cz9EfG{j(r?-#TLTZmCjUQ6hG5ELgwH2IE81g^zpw zHh4178T$zz^tY&r=9@TyhBwFOnGSf~W4V-anx-G2vtgHeA$)bP6+X6=T7vYmYV#=3BJHZ#j1O^5$xZpepx@Nsydh2o+R~NOf(Cr^Yo$KP8jX zNSMYbG}aa?!W%oI+tq5AWsxmK;gpagnWPJYu*-mpYN?Vd5mY75CL9Ob;>RYfG5PF9 zP9r4x?35PoIXik_jcs+%@y>cqEtH_SAbQdG;kc{+G1X?@I*FjF@wMiIcl9E;^H_`F z{ip8k5?I-S|}k$eZ8hm$NR(Qmdt&V!KsDDiS(C5d8`V?zgmg6d6ruxAC#ao z3lY733dB9n=c@VDwo3$6(Hzm~RuqiF5l1(ub-LzCDW?RT6^o~u?T>b!PpT6FWP+;X z63nmakDYo~RE8K#Wi)!Bahn{;*i9Ua>!6~N@Mkrn7D~_vP^TMeGYI`YR8l4^I4TiT zMdMO&BXn&KjGNqCIdCzUQ41yHSoGr;TRbsH+$7-DLL#V2j(7iV;)}K?YAbKWkMbsMH}BvTd}UdVYtI*w5(>e_m-Mr_WAjNYtO`spF>M&K04&pg5LO3ngf~5%=R{ zL||OYHEg4Aq(o2^eM0dK@9tpq8sMhp7BAq`LJ8V}b-HU&LAdf&j2iknK_aM1PI>6n zk?6GijJo(w3a1uI&|X`_)S;8`%JWUC_xMQ?K~)8l&2;s5^}V3x~wx695u)0?fOduRncfrL}Vo` z(4mqmmb*7qiux!a$8dL?9C7(@C#6onYiS*hwqV+0h(7UDH>{p%rUbsO%Bh7Cv^9&B z)ER^E>QDovaL+fXFQF>h^NFvp&rQLDy|Vd>=}kDbP=dB*apUcdFmzuO#%Jf4N(5EW zxv03^adHf1Z=J)enG>fLO3*qj?xK4Zi-%WqU~|{jlL)G!vq|yBeMU4|wtoVVJM1~N zP=eNJ@m9Y|9A*V9gDG9ANCZ{UxuJLy_bVJP1rApC-?HS?LJ3-@#rK@+qp+Q&q8=Xo ziBW>8=uA({Im-oO6Wg`wif6{0S|~y5w7Avkeh9v`T%kU_bca!bs^~0C+`+SIJg)e0 zMy=aT$Ek%9boL_75ZXN+|E#~DmUta!l%Og)Zxg*w&Mxe-n5cBy>BcGa2~1uOZ+|SWdgj6$a4>=R9dlsxM%oE=(op73|mfJiH{|ubM zBdR@z&wY}>FgoA8W{U@KY-tJvs`>85Q*MK$Sum_CZ76&U%cz0hcKTq&`w={4^Dc1x z77q`%CA0F*Sy26b3@pf5!rq(Y!HzB=&`H&9mK(6YF}_Stuy>Q8oX$*NH4lf9UFi^Q zb)Ky$7XwFnErJJbmjqG%b7SmqTEUln{W!Hy;(CWrIQ2RWcJ;a`h%VKw@Z)_2C%@?{ z5mc4&Ed~tyQ{j~76+s-fGs8{~yWnYq_WZBn#ZWpT3a*X0$?n^yLC}C`c;a=3nO$27 ze^ng|6HfgUMC(K|9J;3q9y{T}sf7~j0v3T9*wnavLbv2cqyelX~Q26G%awQLqq@zLlRP?q@cKTkEGN&{?m&>Q2gJ4ik#QB-~| zRIQu<*G(S@9|QX}!14>cF?*~`P}QrMbHH|T0<>(S5!IZmFruCZjvT>xf^HVf&k;9} zX5D8gFQ&kxV+-M6>MIttG7-fx0OX0`0Vv2fb*Fc27KT$Z;o5EtIgDmkcjH%z}-H8gaL~ z70!C!5eI}SQeK_Eo&e9Dr9iK4a=wW*GJh+)3>`7|n+K=)Ly7XHGvHw7`LOV$b~9iS@xC) zs*+n&=i~LTPjDA>F6qsenyi8ycf+8vSb?f>dIdOi35OOvPqX5ID`1;-5KIZxd{miJ zACK4Xg0EZna%!PO;licRXl(@Cu+my>#1J!lo$rlxLb^!=RsFh~4n|p#u-xmqAXcW- z!*&b0;Lfjoq^F|(4&!!VOFvvkmSY zi-hrSH?l>acfz8lW8g#TUO_BsS{(!L`C{UT(VSW+QPE`s>}V7YuUlzE!K&(5>839Z zGan%lRQ1Sm1LRwV!@5ZtF=>k_4!PF}vr3crlj?imYvb9_;%+~7V|5{HSvnJPeMhl% zSBqfp!nqI^+(-~nlj~uAole;MO){qzO5}_ccf@U&1NEY{@neo!7Yow8aD(q`$w$WV z0`PyC2r~i(NdCl{Ol)0TaLo(L?j>^iyObCimJf498{FPWTaAkIGRCd-x?^fWyhKoy zJVtpq)x@ipy5UwOj#CRIcD&yOhRO_>7Ok!6ADmYM%gyt_)CSQKK~;2o6!WO-_84)q z6a0^O<2Y#jc&rSA2OxaxUwz6PynLF89 zV2x6aL$}Q3)Iy012K%AO;kocQT&pE(t6SiRmmKRYkqN4z^-bKKUBv-M%xZ~Y&*j{u zxlq9spyI6I+9DyJ4oJX~}H8qHb-cTg*jks*$F_DOSGGI^0i zP*tb9C2-qqE#x}15I(*gal$|2Y%uBkB2F!oxUjVZ_FUKqSL*B$J_a;)#hO#BaoWtq z5?Xp;YxnlJuWAzgb5Uo8<- zbvJbvjLO~xH_BNH9}b&ZVY+i$9C>Xurxr@A^xg$SE%IUdbOwPY=)7D~_)!NmJ0kA}GNLI-@7uudYV>fN?=5bj?L z_fYduqr?JjJl*hH#5ztbl*m=rfv+7v=CMB_9mk3+umg9)$r&<1Rq{SEBL`bdEV9Q| zV-|AS1JE{4+lttGUeFZnEnIPM;e4t0p#*LJVmEG5Gwc)Qg5g{ysH)-O(>%+j?{>aYb#;n&b?5Xk;IQ3D}`x~Qo+7Mf%~0r z=OJir8r<$z;O_kJ5OncOge?oT-lzPo>e#fO54Ork=F~!o1rN@^bHgRjW~%0+*X7!H zGsYW-jZTpWs*;~-z3m>=H7F2EqayhYeh&r@odXZg2&%elc^n2` zn+gM$XruGCgh6oVeiXXD9LVWxv~%G%=yGlr)HcX>r}JI0pL+5}=-4j`jjj!rX2O){ zG3=9=za_#4>wJ;&)0ea1VQCazis>m4R7K~}V#n{zkML3#iI1X&b84YP?uPf!|7ap) zx7U2^dR9X{+&Ti^4jm~GRCUPb70isE4K)HZ;+E~^lJN=A*tv3FX?{*~;g*=I&%PfB z6a6ejUQMoXv1Ho!Xmn`Sl~W5Pe~UVsQ854iZ6C+AnQ85(uSbnvbOq2A52! zBla7ZI{ZWYYxytnyXR17a$H+y$o|?G3Jqe>cBi94p=IPSz&ui+PKHz_vv*d zf~qthj*t4lg#wMJ5Vf|zBTAaDDmgf02F}l&C! z*@uv^!xi$r8T0Y|9z)VJS4e$pEKcKWzQC}g7OgrNWBmQW_lQq4e`}%m?d$Nd83njW_UWB>xI*V`Rw7jY{XAW4!$K%>} zITArtO)s5?thEg8dHoW^Y=d*q*(e^bby>m^Mwh_cKt0?UT7zdAoPk%t9iWSA4K5R- z%F>~!8jo`d=QFBGb3F%_|Fnm7?fy$t3R?iH&c|cAI6;8^79~0_IR{qX+e4mx4UzKq z2L?lDlNq=uH(4U6isp#eVVc-UJv%rWm+#)i{$5oCBlj@4JE{hsZ7J>v@74+W*Z;)~ z5ATIL12~)=tNCz!(^b7$D;n?L%8@LTn6zsz%nIPJ=O4ni(Mt7NC-S8~AD=aDhi`{FN4JExg!-hec56=p@>gv*|cx~)c$wG;p@!O#Gr(W>> zm9{2x$fpKozUzbI(>}2ICzinQh@tTAm@)UuTLujZ21D!xV`*JWr@Qg~iu%?r5NG<` zX3iEHAYq0t?5kUYr!L+C8Rxn|6_KN|j|tb#sBvBsa9PF;MlF=^-LM6QAL<69{wa@T ztyR^=aWWQmxgrr%C8yln%>euK9E=OPRFIyRri1#{>00*sqL%g=jw2JwBp;M;Y_$er zE&IZZ?^^q~xwuTdZZ;b8-R?^SRnZ&~t5HqN(XE0H7L|Tw?BgtObqa^?GmUwZ_VXaz zXCic3{@>hP-`WJL9`wbcxPPM=c z=8d<_TX1TjguIgaGOID3Xyl2(X-*PBRq}dbX2LD?TXX>W*X=8<;;g=12#cJD0_@n! zoagU{a}UPDoh#aUd*sFHIOM!9mRmZE)Ab#?0!3Gl#LO$P94;swfM-*CNIob**RsU> zkE(aogxCPQyu?!?sER(JSbIHkO!fae5UY4OaB88%h^%}l>(>WDi?mg>mdDI+c(gaJ z{JRUMYkG9Gp03G>{Uw#^p?+aEbdGnGRtG6T%SN;)#SmF~KO9xwULvT9KB4HTKYUax zjUI+G8(DB_p@iJd4_-Q>E(s6B2_=>iK~-|f3l|iqpRA@}e8cLTS|~w#RGlul$!qnu z$zW`5Ig8U+oz8b?L@vH7+WSTI4<3MvjwWzwp#+`#h&?O=@2l6uTP*#vaEYKQInwva zxvyF@AC9i4r*dkcgj{!ny->YeF%Wkj8X^;acZYeVR*Uz zZ$=5KqGP)_LBKjiy&n~ZPeZOUYM}%j=SA)+6V%W8Nb#|0p+r!X95ZAttAll4d0}J! z6i#Qnbbe0DU+e_*uYsqhcSG1cTbeslg0B0D`FT$rj$GXzhdhmx2&$sxFW&Zb*5Ocl zKTNO;=F~z7y6!9HYN7Adb^-o4Z}v!upenf+-Sn&yK3mlXM=KMgK9LgiEvZg7ca9M* zKkbXRqbEuPRnfNtV#TXUOV!ON94)qw68ixD|G6c7cS~olV*hS?y?SI(7~cA8h%`&3 zg#3p0T3RhNb9N+lDCaE^R7GcDI-NmF2eq+%1P;@Ab84YPhrk=q9Y;gZ18oh!2;RWG zvC&x5%3dOGIcs0Fj5aOVU&PA!!1pMMp;932QQR@&@tc|-x2gvDa1MNNsI zDmt?e-xXDQ0F6JyU_(D+PA!x$dvggE^!9}sf3%+A&b+-)sa_oR`~F3mt5Fr5i)f>o zlX|^Q46X~zlHztc7olxaoGmi1j(VX_EVkIcM{0wVptB6IP95r?dQOVQqrIO<1Xa-< zLwp%lqo(SxHwJ$WcqR2El#tW$bANwz{fvM5%vENQNP#;=wXcuj(XyWv7Z^WES@zERz69AHgU$B z{*pM$Vz@O51?>xCW0MFcH4BN(MM?%#U@P2+oel5O7l?8kk#) zw>}=|?pRl{P-1&*AiRo6fvdAMBIs5VJQ~1oQ`ATvzcv~M`^7@yrkec8pI{ijaTfd) zQA6@A_Np0L;fP5J?#~}AStt=#bs9XKlL*UvwE6kBw&FdJS4Z45kV^zr(I*rmXI(RF zbm-aMQD6;nf@wskGx1G_gA-;6rp>rs0+wa_$0%}s&D zi^qcPpW1@38ext-uC>Rcox3C-?}o;MBEIhM+aUWBU*w){fTqtnV0qXqJqab&w~K)a zoy88Q{xyYHyX7D^0wG#}EEhCx!(I)b>IS{=8u`dhm{8UB163(KBp#K*bbX#TbV z{y5o^4_`bV=IaMT_yiN4S91|K{OJjSvrTz_vouHz_l3i6wA@W!-xdA+%rGmZg=C?` zlITTXf65pB+G;9@OF>?kwn^OFvoc8{sH%DM70~pqBRn*$FNm;{J@M|58fcvD%Bh7C zn;WFVGE;9@9If4WTU4PR4$L*gg<>BWC8(-;S_T-^b^@V*tU5t_iKLZad+|lpf@iJpYK_hk zK~-{@e+sq5m+jr~ZCQOO<+S(d9TWujS0zH-9a^9GxJPsRxn7TFC$!_#LJ8XEi&>F( z3%q5;@zcrj5Rl%N@-!Mv0 z)fn@M@To&G)cc@~A8V^NMMpDFymsd^qa)ej5rObHAq76IFy^&_17S&g3b-%Sh|+aU zG32xdK97CHsD%>e9*9*n?-b~ssSy_4t+DF_PYi8q!08A{{mG-+ZL!ZF%gYn@_ttT0 zp#=3Uc7>H#3k5eO5nw?xIi&CGG_+gUQW3;8_Qa7;E%Y-DB`x{TAsV5mXiMaV0D`;{--GHNx^; zIXwLOhx((2vqCMDNQae>n&SjvKQ-cNcd^^|yfL17RwVUTIc--!>TO48@w=YXSBh`k zBN*<=HO7704oVhEl=NHyi7y=?^qJNt7CdZ?C-2lo7vEPBK~?k##n&|x8)KB#Mw#&RmmxDaLyf%nl?xG%O29GMn@mHPpp2~ z6(28ZiVv5~k$N~v$YWHwBTdomv^DNAzAh0|MI!^TXS=;6el<78J3-~72!IkaM|3)O zi*h(-MqS*0&{`s>ibgo%?1XWb)sU)&n72tUMKYA2wNmTbH>fS$%VPsSUx}b9I?E6@ z-mZ#L^|minmvR2m{DTs-b%}ki{cDRas>;-HhV}|ADO!THw{M1+o>gJiG&51=Wj(uM zg-_qrp4*OcTKnj@+j86{$o*glmj{^(;>pvhs=?iCcBd#-v0G9AYl3^}T?aSdE$M;JE;NR|1uATKhW!I?rb24fX;Q)jol;FV{5~da^tpwjdwM$IA5Qyt+O2>rWk?I zjQYIDZ5!MUt_jV1Y2*2}rMJN6`)svOL73DtP}ObIt+4l|3G6Y}hiJmZ z`Taa_->8(d&uqY7-z*oC+PMNf&P@Dl^<5uBj1MZ(u2qVvLD!h8N0jKE`Ujrr>s6EHt+3zO^YN5ow zWrYy-CbK9=&^q0-S5?*i)$SC}+aMEEMe|McC0BLomDelSDITZLKC0=tJ@Da8RsH-e z|Lw0v8&*+E+9$Evc5w>r$tdxrav|hpUvR&luRYbl;F+ram^X`^86go=Mbjt7+RR$2 zXYx9|-C#K#lrS1p2+b;ubPp8eFVyHl)`4oY-R$%pkHX6xV7|L3Vr zR#X4V0cH~~6I4Y<37xLt%nIr&BOC5CHCj10JO{>qJf+WWY|byX&V`^%Rd3eYoYSWj zZ(j{6sLlhd`R&wbDIJs;VxJ3j!d3kXL5q_L-Kwe|Mp~9+p;R^k2UGJ*hr#oR|sTDdkwhDrWq0_*UrmxhgwXs*N}|j~l9os*mG;YDOs3 zLJ8$ZCTyDbOYdT>^`aj)MySDGg7_q(V2PkAIpub)M(V2!SDr8~N=i8;Dp}^h#aCzb z#W&M``QhXc<%Wp#eZIS}d=crNpT8cGCfKs9 zN2dJVtkq!W=)wk1*T%udu`l3S#v=aUW2izcl;8oI!6vjJ3(nOd%fMN;;nBG{d|b;g ziJ+>vmA1l%k0$JGH7$4jdv?GEmfyHj_;)@@tS5B%%aOeo>j@u3OuglnBXbck^}>Cd z!T66MbD6H??y%RcICjfdp8Ni{WT8YL6JHTLbY%BGYESifOAGvZ_Z@He*hHbfMOAY} zgxosHiS76&Lasey6t<{!hvz1>=aJ!?AZ&{vTRYU8?}^_Cb&geIwL3T9eGaUKJX>p4 z`IYumBMqjZ=a^3X%hRR&$HE*KUBO+ysB1&saGv^UzN~M5M}nExVJ2kn?95YstOsG1#^02>urNHqETuH z4(&IWmkx8_)N-e3CiGi;K>t_chLUgbjTzXd{0f7Vxgsr3x! zYL3QNrG*??W=I58(L5CEq94cMWUG_>{u4JTcPTMNd^r$*%a9!ysQIX!I~K>pT;L7B zQ6i{{mW{Y|Aw2{?UN{0%o37!>vvQyZu#)Xw4S8|&F8C4RRx+i%CI3=;H*}eiSyX?g zmRIx4V{lEkF|hnAmn@VBi^+vny{w8`fu$gNyo$ltvBOHfj(3&_s=6{Z7Zx}M9*Eng z5kLKdFl^^q^@p<)FR$)^4*ta@riP*n?q|ZT?BbG}mKNMazXb}8{wR6yLQ8qqDWmbb z#Xj|&IJ1UYC?Ut~RZa%tv{}d0wB^ncK~=vUH$$Ty<-sgR^U*P49M+$9Mnwk~PA!!1 z4cQ1E&KtrzQS(L2kQIz=D=tu5m19ymo{Y}~^+H}re@8h@I$h66q3CTgLtW8Z)GLx& zO5EzU6AZHFl+1Xhl}E#~Q?c*X!RknZWfDPEv}DD1sX38YqkJ>fFUCPCb4v6M66IgO zN+O-L@@V@u5+8Q1sg57UC4#DG`HR!6W_sg?obT%Hwr8bz6wNC-^A@{`cQ?ms>F?BE zCiN6LKcgynt`=&RaB^j5^_6V zoal{Drn<4C?X4t&s(QT=U+{#u>!FwCb1TKx@|7wcGZ4J1Xa;dTbwR7*bmDJ-}92l#nO0A33=pP zUS|-#O)ICwr8r9jRr!gx0JUm4v4Q`*1?WA#3~c?A`HLZ83XLX0I&6daGitKFVr_xO zE8^>#&sQO=(k#BRMYt4~P=ZE-VzqWu57j)lW|^@h1zr zE7U>>C1)i>ZgpZyDrvFL%X0x}v*)flJ*WexeK>9BXDh6NRf}6fk2zW-V>`G%=6v|1 z4tlhhQwt^Ns*#9f%m!j3a|7%d86H>f+!`PeR7F?3#oO1y2da_l zC3T!%4{0r&t}V(>75L?+dgH?hb@nZ9$p8IueQ1+6!;gRrMS4?l@c`s7jut_BE`HsU!Py_mJ+=ER_;; z>=OGj#GT<8p(*^tm%$Q2RkZICU$UlGL$92z-1?iBG@5*g zCHIK~ed}Q2&N7}?+fJbtO33rUka`B__o=QDi&hF7y9@&Bda!&?Q(p5+8q|#NWrON%^}ph`cPnm!I( z9;dLMQ^a=+gg&=;9BdT-e=7d3)BWAk8XKSSRDM2v&!~kG^l8Q2fP$zbhzg%&f~u%* zv8PB7_e9DU8GewSiV||lBSbnTiFAB1lhZ*}^a*vkr>(8gOb~`1Kc&2)1kGtNceb_0 z@O_?&?IM|=Dw@+`_h%1l{Bp`uDUJWYsD%#~SgZr()mWqeM`ZT!L-9t+D5E zPo+}-PmEe9(fr&vusNH;ZiHwh_@}8gt}gIYEXMqn2&$6vYK(7FJn_~;(dUSp*GV0v zb=U8FAhhh2!cK3~d`vuPjlN1pWl~Uc9@c*%^lh2U^2Kg5|93%9H71b_=w5?w+Bg}e zRZ3z*x@db1I{Vq6@>x;7#{FT`GAM2$d@)RB^>j6)UlMIFzZt%c@2I?}uahj4IBPZ$ zOgkhqn}7Bij4Iz0+YRwhMog7i8Ce`3@^2|49~ zYpgL)=czPEti&lnRa*v*hd8qo=J`)Mx7%xtL(Dyu@=eQgYM}(pX>l4!6>HqJ*;9G- zP9~^|mcQ7IE9$PdsJkKAKc&8e60}zmD-+Bb0}gpAKaPEo2&$qrM!Z)`vc~z7Je8V7 zKN+=9g4Q0f&vLOfb`SAX9)x|92&$56V!1Qz@y5hfN^Fq_pIwp+4PK9BK~L-OcP_~= zMjyz^uns?zEcRv18_U*L(Dvelg}P$f3${w=bWh1bi866wjP1`!Y^;q&*spJcA0D(* z7QLJ<5maTrIvT$9i)Ch8wOx9v&N|?;>5j^y4RtuRP@?+zD2NVZ)|~HQf|-jkbF>Lp_&X8pN(bJpJ_gB)aiixEn6vpsWL%T zv@VFR2MRd$&oWjrP8M^z3QX6K<$>4I%%`JChpy_XoRWKq^gxfP!)|n#G3xn zb82ocQzi9{qvCyNJ`BDzjKwvm!yoiagNV$2ETBT&|3orp?(I_)7X@;nvYkxwQ*iyTc!KJ zrxHO`z3R^qx3P_7Q&(#HETa=EVQfxoW!b?B3bjz8o%bBbSw5D9PSA+vrwlOI=odHl zbCgy;XbexIb8+sVzB;yCUrw2l)l!PvDIrJtZzm5>{VrYRM=p+1HuqZw9*w)QQ$Ol* z`o?VM{pDa&%airps>SVTp1sw)yb@l=b-Y3?l#o}Wu54eb=9Dkx#%aSOf~x2WlKB4P z(HixOO-03^UJr$~9QuT`ZHnC@8#k)g9m*@aYxzoTkP`H1#eRm}*VUo>43+CI+$4gk ziLg3wNOItcVAjHM#HY=N`-=75s62lC!aH87!(aw^nH zBB+Y?`QpT^SwB>hy*A1Yle*GqKnb}Grk$UHR&$H_puk~l?9E6BzPywD3;lCk`vO$yj5YEsm6#>A++Ey0w7Jm|HoW`^c5Q*UgC%?kThj6b`!GEm zD!gCGjIQhv#LM^1(6!7>@k$=XCrpnN-_9>#^&L+9d;bU1?*I6!etz!I(Mm!g1 zUn%37EACzYzq<#Rb_-XWxb-XLaxv>GZvFbRYaU!|e}J9d_eq>IWuD#{S3Rkwm^91g z)Iy0Rr{=+HwTOMGq1~c%V2>?sUSzAR+P_I6sLHL}JlIgMpDq8Yo${ZM%%dtc2RF*|>|o%wl{TeDcg@XWmX1KDGz9!n%5U#kb!QiFna} zCY-Fjn+2+V5-r{?>6;__<)CaRS<30}Qes2{apGzDJT~yXcDA~WV{<&0>!7R~yj&uv zs{EhXU{O%Wlq=f#?ei?#qh;G>%9q!P+^lI79J;fW@t+IXwA?6Y*CLZ$NT2YLf@yj7U+(dcUnoN>TGc~LG^BB+Yyp?L3nr3F@XcTu+a zNAT9q!eET=2G+dCCU)j!7~Gt@fz@2Jk=-~J4s{!BVBW#n%_mlWH^ZYV+AC#^VmP%> z!c7+rqt0(+RaUGO#QC-^IJkXFW#r~iiJ&T)BjW6xsW$l2&{e6HCFd0-mUoQ=W#~3m zR4-Ndh!c0Ew2pICJdY$xxl2_v-^BN|?ONfR>CTE#Xt0!Wnx+k@VbEyoD)#4?);``p zbV4?wwZd)<=hQ+8xeZBH&ikde)+oRVA#!7%<6l#Ac8I9a828~yl#90$4# zgNyHkPtL#}e&r7&ylNpmJ53Y*iG(iVMAwIpGlY-LooC>ZomJTS8}k^oP+~%CG<0y; z!s?`H_X2dA6OXm_9f#o++DimgSq4T!gYlc$vVIyd;!G^AX=SY5pR|&F+7u6|zL{*5 z;dExRI38ws?_g;Kp^VaEhmemrhyFEF)#MJ6g%Y!7N5lQin^~Li1;WR|^>O&3iGgbV z*i9m+N`9&y{sHJ2`cD1a-jB_Uo(-Ma?PgZP?b!6{vta4lo$M^@!Jc)V1?wv0u#va5 zJKS!aoPgIpoL8F__LVG@7~5?oM5JdiN6!F3jJ*_&0d5KEkPF)-f~shahRNU34d$@;{6L<9uUN9H@mhNGX+LRYQz7H6Hk8V{~s=ltoX}hD*0Bv1j zg{6LPT(G-_Qn^PXPA!z6{fbEW!GXA@rGc{hO$&*jD!J7jzuyxl6&foY&Utcbp#<$8 zb-J&whGXp|&-luv?h-*&X|hxf0bIN|_KEtHVQkNfS%;_1p~ zcDXY%;RVN48-Ae+WdQiBztO>E7g*d zHPc`uFJfc9Y4_JoDc=l}s&~RZixL>M(0WDdn~34wJD~42Cp;~_?xzG*6|WI@neHoM zndP*5Ml%+5!+@V=IA(HHPA!!9a%&#^zE{Y6DrooPWRB}D&e1c$Gf!Gc1Xca-o(}eZ zx9UDB9)xYTU*y>xb2*JB|97hq({3ZCF{3!oGR7aLTAbqJM(1*Bp~V00M`GIj#X4Q$ zx&W-(I)^WRvRxvm%1E58Z)jY^oStd1X#R)^n4yMp<0aXgS||}L?kw(WRLnN~b7yho zH^CTn{}KD$eXT@LRg$=w^iPj{tW~(?V{wdl<8EEAq-E`OoLVUHzuTwS|J`3Z=xZq2 zk1|y+XQoI5Rk@1$irB)vtoXcE9#KuFV2bGiwRhTVPA!yJEbg!EFl9d*bWo(5Qc!%B&us#E64kkT=qT|TY(_}Fhe9=u0<|ITNpt+m;NZ&);LYgYM#d;g$hmvyMQ_}^trmXFz911) zMeBmtvDGR7`#gG~ngx7d)ItfGBjU_~%@fec64mkvt)yB)RkTiv_1%V{Xg)PjHF)4E z)m=)^Jk;sD=7eLMrRs%YC3(d)HH+;hbMPIs9qwLwbAHTkQ6a$E|&TdO3XZ&1kEq+VfkmZGCvV892ZGkr!bjhpw)m_?Yo*JBjS@js@{ImjcnnVUbmj%s zW2LyA&J$?tE51d(5Q3v-tl+zy#F>C(Za@hdeTdk{FA^{7#W`U=#F>DEpei}u)xQeG zW9R2^E5ACNS|~xI50O_3W3f$QDa+bbULvSUjx77!h{WON?6~1~YfdecpwWleIWRH~ za~@4B=@(K4=)3J|^wK@Bi!z({vOIwc-<6xn$5k4K{hc#QL zv;Wi>5iIWvzOs{h|T<*dcdR6*p7`K z*m?HL48K+Ejx%;0l_D}4Ytdg4JK{@P;)K_F>@i%&sf7~q$l2Lf0rbJLxMx8X+{-NZbl}T~tveQKTQr4HJmF96;QnUmk)-Q)4 zI+Yb>Yb9uhV=!>gB7UT>fKv-4XgnuwK3O>o%cAyjuNr$Kf~vNpEf+Hum91Q*`50h1 z6wmYkzPHOBPA!z6xgd7RHX4GPtPb-DI+>uVW($|YM01s;E!TW}?b8+GXH-xIcgW+^ zLJ3+;sphw@A6W;p%c|lvu+2 z7LC@^b|X&tFPnzN$7-u@-mZ~a6eaZ6mc#Y<64rEq=EE~<3O4qdss;>ODiKsgV@9$2 zGi*Grt-D2SWHFCZ3nkVrUJm=Qn5iEEgpU_B{P9hPcWSxW6D5MGXp||wGVR_6Hzyn7 zMZf<4-kteRluC)Z1D3-xvtl-3@krrg^)WBZhXxqo+xz(Pwcs;{Y===%r6yyBu`B2iVW;z4UuVWI)(}V%9CWukbOEm&b}* zyJG6Fy_{MovGdw8=p=mSZ}bzy$l8r?!X^j&6e1H;_4Dv@$a5=Z?S>2%#L&l;(WF~% z{Bb6PQwt?%`oxV>jUK5#ZnVNPN9rr76EmQo`vG<^zMI~_d<6^{T+ELC?yg_#umYy~ z9AM_LorI6XjJIm2yD3_nZ=p~NC2Uu$fXt!;tiy}Wf~eU6RIAf1aN^qL5j4%wRP)il)h;!A_FHw-!QKijDO!S*7GE`v+pezqSQ9PsJrru8M2n{@pt-pyrvn{@ zk5;vc)PCoiVARF75BNCob;6}S3gtbyp8TWCk_G{IcfCW}`C_K~;QX2HX`d3tHalB8X3J&RB6{RppG$Q%)_E*uFOd z4ltFaKj@>S!^9Tf-)O2F*`rDXRTVj8KnGW3$K84gqFvpIc)e$!>Sef-(>{v!iC?@j zK%ZB_&TbhZh(czAW+3dR?6GT-+!aYM@XHC1{T!-k9`i zhZeP;sOPKJlnAQI&B=h9v*au%oDo~ewJ)^6g|LJ2vqMqV0#Tlc?Gq3U9ZpekAy#5>{H zE!FgDQEFQDbcMDY+RxLLrqdlAI8jw~iRzZ%X;K@c1npx)yz7*zHeGL^4%-(h5meRw zV%ft;nS25iJ&Su%7YHtZM9neD`JYpp*T2R88 z_wmxlIIM&kVmx0|%Ucl3e>X$>EvEVk_dOMAp@bX(JjpS^&_=<_uAcx-5u9!*R_6U)cd_>KEFSFJbXOP>&foUdv|u`?3{Ux%QW=} zY?N!hZ=ynQ6@R*@#{GFe{m1^vB6q=4QTJw?W)`JEg0Y*C&kgxo)L>X*7^pwUUM}+7 zj|(2*1fM4w3|2#%=nr1j!3mqv1)neRH!`1*84Ty*Tk4}@3SpnVN0gZtC-|}HJI<;e zdb{n1g+-g=3c*!;W@#`)RqCZDHPpqre#ezLCnwbF$jh#*zp^QbpPN<2q46uUHvu{D z<)W=JTB???LUWpt1B0?`>G?R-*@C>CEihx80eOUvmiV}fb`W@8Rj+%iG1mWbPH=*& z{y59QUv^e>jFo-O^oG#|u=ZO^<*fMZg&)sgm~f<$Uhc>d@j|YZVIw_G@SceFddafZ zCpGU>3Erd9dvGA?_n#$*^p%wrf~)v%Lu-nb zw$`iJloq=x*FqlQ1b^nKPo%ZZKfR5jNVhTy!BzYzFc|vu@1k!NYmDY;X2>I);C+|D z(0uJc-O6S;9O?K`d7`+AKP%*+FmRae*!^hk*FsN}tN|x@A562mTjTZ4vz;~PM>z_? zRXl@0&RK=V>rda6Fu4raDR_hveC$hm%GN2T-&x-U8-%=vBd3>WUWQbVGK;|Q4>Cs8)@?cF))65 zbvRD`wZ&IO!z%ykM6?=INpGFm3iW)^;=$r$+Q-Oc@Mb}#n{&nqZQ`dT;1-za){)!< zr?#98cJn0BcvDR7Yr7x}E!sv%hb$Keh7JQe|8ixYGkX;De{T-8$=}_}YZRCqr6XI& z-ATE=SwVQ{imTueN&id8|4(^463+FMMExp#b9a}gUB9dx{y*Yhl_W}a^?@0Oq=#GA z(^9Su<$GPT)WgY0@elZaJ#kmt+qFHHhdwkzQK22Y7?|EV3uFD)$I}= zw4w%od>J%A@CYZ=W0<8bG38r19^+3=5~=QYwAeAxu<+Clx6?`Yv?r-i&?a|>Tg~w| zv@umDgY`N2oA0?CVJdZQB3_`G7mskF5Ioj?R)_?rWO*G%(-u?MoKYAt#ZSy8-^Zbo ze8D}dI=CLZp_wg@fqf5mxbb6C#w$L*zMxoFTxuCEk{+DY9+z1H&B=}OQ_6Ym%BcmA z?v&}4LSBvi<_1IXDtT5fd;D#(FVY9k)Se}HgcCV-d0NuvdC<11bdXFPbH=pc_F(*! z>#q=8#m|;}m&Tkl9cnuSU#8Abu7eXx{I6+S4$gsMpX8NSUXf$UyEPnF>k5Op7pvmcTybqnh&63 zY|d?@$5*q%k*`&Pt5SOFTF|k0nCaG@h@3r*^^fHmVp81&f=99%>Drc%1lY3^|L3gI zHrne2i`(MRF$!q`W(Gan>&34MBb3c zNN{%21MXR2$j60(M>vs0{?4`BRzUAx{?0S}opodHx_EMZtU_?rACF}C?Y(^7teL)O zWF5?ZagpE=PW*9khTs0qTT3_7Czq*%g#wo-1Xn#YW@%1K*1@|@(zCecC@1}1YF!+Y zzEtoCC*E$`t+_NxgKr0<_ws5Q@7^-j$ALHE6oRY1*lf`{!FITOTpr{3#76pt$2RD; zDnW47&~jU~?(P{7{C91mN_-Eu)q}>`;dj3z!6TeVpSM{nn7$cuKFYId)!JGQYwCbg z(vuZ}tNu71Lv_1dbXJ9aTI$OlIAQa|6@sh&_%MTXXjX|o-peSxmwAK}e;k%U@m@yh zz03)&`s1n$8@Tr}O7CSJ;eJ!_y!TAZ{3c*!9b2GIG1;b%{?Vdy& zOe~{cOK*?8p81J1_l?^9OF_)0H)|#8ghGX&NU*H5U2D~D3LMXs?p%x36EUhi zHry8|c!U#yH@9dL8_tCB>%xdwvaystJJSmtEoLYLSMf8XK5sKH z{0`0Q+bpnaDX)Cg5;Ohj!8RzK%~lAmQm?$qnv%Nhi;h@x%ShqjzfPOF-yf>$tDxn) zbz0PMf9M#p3J!hD&|IGlgUYl9%V2o@t*~Au*BiYuMhG6^1aA@g#*#r!m}R|i?Ayu8 zm2(1SY|uQa1VY`UL^{UUg=O@P@7v@3;AslMRs46N-4HL8(jTAgh&6il7whh=(8d(@ zh2dLrVffaSntuUb*r)ILpX)GRTS~ujr6U$TFhIEuPMoZgs+DWx3-3qED=%8NlwS01 zM~v?`R3W&Ew;}CSJgBN3yv+k&_3#uAOD)l=#rT8AyUTFJd8y`f%nwTDU4pN@;W^I-b2kI=14sMe_YTxhyd zy3xLgv(#&DX@QqaD0qYu&&;Q2=UTNx7}J`S@#YK!BxX)6>EWi=0Xh* zdF9udSn9e>3taxBgWwTPqFJwFi(_ghJ#b4^QqZ}k=!vAB~$aMiMbd1&4EcM4T-0??nBZc6q&o{|%6Mj=_ny#}{ffHw41AXY$^Ct`$ouO5AUjP#ZT%uznSFzNa=4*lZ=5C|@`!5Q?RqE~+t!r88tG2r1`T0(QKSlgmQJ<(<8!hw$B|R|1xxU~LPN+}R zJ9_SSO5AX;l)a&?E@|0<^>u4;O zdKGSxANAG`ouSir(b=;R@O#IqIbsQ8`k z-7sr6Q>nv&n0b8@aMi?|ENxZ-z|3L)OZ@x@CSTeg{#9TG@V~{09|>97@N|HoM3ei_ z%T}h2-2-vwsm%((RU6mr){4dp*g`Jn)Klm6(dtzU#qb@G%GL5#s1kcui`&}_TK#I> z*h2Q&qE{ifE-(#vgcFs1)@5L_kyUpt~1B<9Ft+;_^aUHUs1TTl85!#h9I9$`0V*JCM2)wAZF z(7E9*;K!rc#MZL8_K6_~?=C43PRRd1U*!&4H^{ciSX3-``CTF|nEpTFUzH^OyN*`Z zHfiV12Vlh+odnOf@mwFz&(U*!%S}s43BvqaoR!QSC*(2y%W|e4o2{)655fmUnkocW z`NzD_j(H4#UG_3BYToZdZl9$yaL4yLf=4(Z|Np3QFDT?JXDoM5bk^3*n1PS))%yR4 ze^tEIY5(@`yK{d!2V=j7W`alf-_^0eN~yb@v9x-IB;`7-2e= zISteAl@L6_3EpGS-F|DKX~^WMm_MYTLU7e%^KDvCR6BV6Q;y+wt({={67Po}2b={S z;e^_k6!;clN`5(=-Z&R^ZiF_C6oGl-Aw1cSPsPeU*6>pXsTyiS z^x6A*;)5CO1&?r|>5z1-zfT`{mn_?AXoV7bu8lVi-Q7kZxaxn#SIs_|+M4-buUs2t zw8RPZ9rgE}!g{2s2Tr(OTOqiLzeVZ$IXU*kKJSC?KNe6%eVkC=Q4e~Q*7qfL#Zn*N zDx(ap;$LeFh7w!vnr>SUz(?d8&cCI+sc}R*b$J5RUNi*wJxye^%gMh2@oWou z{T{EVqeE-FzAsA2A#;LXAAOY}FYMT9p7?^iu=(HODxTw@ebvYdyIN9r{7GKeJi-aJ zt(vqk=q2oX;E0-&6@shO%tZa*d#1ET1F`XneoCH!6THWux}u6NOyO^RutZQVh2ScF z=Nk-{%AYcwd^H>wJpd(ZzzN=C7z~>C71P0tq1Yj-nL=6{hU^OZfiJK?7A{Cpw(3K zcWZAdk$cPcPfCOn&B<@OjCV(9`dz-G_T5d^Vt>xSs1`*8AF*&1f1}b$*)^ZEa`}UB z&8iy8o0Aj%x9 zBLi`gO>w~quHttL&F;nyFm2oKi!pk2!6Ted-ychwwlQtk<%fpq^%R1u_#H!j6U%3t zY(7mvi+SY#!R}E`@b?vs^uLWYwI4DK-Riq51XuAphVt$66HL2CPr#O2y9plQ1b>Ut zcZ1;@O_R5e!Btj66oRYNo}p>)yQcM9`eXVtU*#(@C;0n{o{xG3^nKU8(YMlUh2Sdw z&6`%eF1IhUeS+rs*++4>@*sWC2s@yPGdS0P>I$gh?9Hxa&@na} z^0^F<)n|;z=xL5kP3`qsIfrHS+5bg2K~*V`FFWf`<-Ny%%6OtyN8R#$wnA_fKU>;E z=$<{^oLm;8CDq7tJ z|5a2~@$jif zh1;e6W3a{O&Z5jW^{l9t40`R#`L&k;ze8#NtAi6TuJ9|Ew_m+?Iq{<0BB)g?2YkQm zpzDY$Hw7)P_0)QgO;hf6uAoHh2`x?V2q&mA4DL6{{{9S%a~n*2SWTa( zxhe!#QAGq4DW3DIGSpz0(YQ4>`(9no%yJey!U_I#(KkqsmUy3X)fVj?6oRW_TP%lh zMRFjig{%yF(aQ+~cG&9$np74%!U_J&lM8r#FVx1F;ni;NAh=<_tLsSd!Rsx zIk4Kj2oXc+JEy~dKA8VYJ{VJO8$`7YhiP>k;p6tLkZ2wbCmu8foV*cs!c54BmLto_ zJv(Yn0ik#_tqyFhlLoez1L4qA+83#N3Rv{_hjzDDLYsUmVN4T$C|f?2h`^0j_;#TS zitE85!`m0mKUxjrizY&!8om%dcoprclmh(vsCwDe0WHTm;Ou(#V*9c%aG(`izMXFY z)R+Y}rYJ~$a0_-Fn+ZOPW5D^^4LU}EsD}%?Ho~Zh>0&p15q&p)A@sG%Hp-_|KCN<> zJlQMAKHzuHFm+KSEVKaec+C}JY~xJ0Qzsn!<~ad5u)<#@!XcqmV;E$X1-0}T=sDrJ5e^2nMf5p!U_9=d*St)XsFgz66H70USuzA@IwDp3c*!t%=g0D5;5epSeS^# z=bGXI$9g#FYOJ_wvjwV0guo&DVNkyJ78tNK1im~R0;!>!VaAzIC|PV65&xWNiZyKN zVQ|?+f=4*9^ZFJT+aMI8tp^e@<5hKhdCv|14pj-R;w?h%L-U&8h6?p@<@q?JtvF%% zArl%-n+;b|oah)wJey$1+j{soF+m}?inklp(eH4?qg$-;^pyq5mGf)*Fnt3!+6RDN zktjOGwK8?_!FCr+@`w~X!inyV>mlu10Dxx<5x&M|_@;*ydgYH+2(J2ha6Oc{?hm%Z zBw-%xjMIJVqeXXr(ce22dfuK6pS)H>vzw_f>gjZ-n2-wX$E8B+)4tFlNZ##x_qpJ; z)mGU3b&%i@PPkoK1;hTC4((!B5aGVx3CHbgfN^^L_mRM(B!-ybf|QYh)Lj# z&v)5kZQC9S!BzL#EQ96f2Q{4}@m9CPvDKWh;;ZIja(pb58yN^>#tJd_Vj;IcAS|^w z1DrNcH|mJJbM5fe+Kz%pIN`TrDa4QSgF9Ca(J`J5azU_ffPH`TQV6b6&+52`16ID> z1iuw_5wU~kf=$OzC}w^Qbf1OvYzM*BQ|E!7Ej_i)%`k78Ev8&(uUrQwd~;*riA5l+ z^gTmoWm(t>Z&q)Fi~eb&5M0Hti5y(UIAZ%Ajq!dEh=nzyq3+=@IHKQzJ>TYlcS0z< zFMl2Q*%}NN;+*i>KX!P08Y!T=PmLxQf3^=#7)r1h?FGz_cv&jl;?KZF9r~SEJw&PL$VY!qxZ~h<+^JQCH~i?>^K7qn|exJi>{j55aIa zZXOulTqa^+mqz%hnG=?4*+L<>>VOsu$K&V0)Sg#}$a`pu1)DU(we{Kv9^ph<`9PSp zAQqZhoF&5R?C8+z0zKM7v?mICw&Ph2W~!c>(a_ zT`YuEllSgN+K1KO!XA6B_7Z&bQt_rQWW8JlXCw9lr|GL@uLfwh#s%$ty9yrRMCsuH zuxHyMs4wJMIe)Un`&*o`U%Zz>aFu#ix3@OH$UaWEu9v^yW06^3ro)N$sZgck>i-#+ zJUwEAPxm>ZXg^gMk#Qnn1oi9hlEB$)8=ckV4vskKU_*Sqe6T`r6>kxPq4*nX{9)^g zs{=X>-7# z(=J*G`i|ym-bZ_4-Et-L8{zq(dEqcfKe`DXcj^Tx7!Dl|ZiUWY9Uyc-IC$D@gQu=d z>8!pr?|{9n%ys-~P$HaI(CBeE7jCp9=B8ouHt7)@4;5hFeB1I zuTiA5avhwQIXD`ogk(a8Qu6oMeY_zK-D=c3&MT!5T*X^~su~NA$C*!c(}QI#!6JDk zG@7#s;@k$qj)^nDebq*=**QpQ5nAIFItd?APBF%~ULkn94P8MyXJ>Dtv8ZgTyhD>P zutSEa?YI`o-{r?U9vA}l?Ki;e3sZ^Ex03t!4tLY>YRiB}I58|C2+R(zCHHLEUrkE! zM{~1Dri!oa6@sf?H=Y5VORj^6aCLm6c{nbA1ZpS zgol%pfzwoJaX1(!uKA&jDcMAcaH4Bm5UhBU2C>cLSv}Yvh$9Ahnq2SMD+E`mXVryP zKMbtqCfvtWgohRV!MsL1bT7OM?!NPbD-rSFc{CHI9rA;%Y4MQfDBlKo9y72~aT_uA zS_LJ-iSMQTp^zy7MlIP&M90lRSR}oPXgFemLU0vt5gPT)2*vMN?cuSlrP5ZM*bwRu zgU_ZwbBh!@MwJtxcz5T!oY;1C6oRXGyOC${7e5@85hNy@F;lLbUv0j8f#BYHF+44J zl#XHcY65<`zDv}6-UE1q6A4-%JfXQl`ST}<$gVUVa|iAd4Ym|j2(F3{LC}3>EL=^M z#K*Ct@bjxY;TK#Cc!U!T3Isz1+Bg2C!v!L49v+B3exJm*+HHVGIPoPtglY%p!JgG} z)YrD>0G#0dT@;Kjpb%X3wO%NUelZu8kCnt8YY!a$z!KZEH2|%n2V*q3)P>xF>pf>d z&zL9}9DECUx1I&-S44sJnp;FX3i8CKS=I6WiJwLu;lxrA2GeTAKqpT*dfn*U9;?P$ zAeL}d{uWmiED{DkdQ!e*z9eSV@Wu;MD&YBQ2H+7+lw zHgGm71XuA^pbTVeFRXg47{(>$10Laod6}8e{Kp&^+eNO9PB80>rSl45%RH6fDz$a* zeXEZrYq!9KXTBRJgwu1}Zx-a6bqf|gj)2nIYzSO(8^nhQIJs^%L|wd1$1vJ7!h6%) zFn^QpMjqird%p-ki*WdPQxc;;yJP9Q)_9|V`U~>krrx*N5S9=DEAk}Kss>;>?dsTg zaWmi%P9(jY4gJ?gkZXk`2HkYVH(wnv-sZcJ6I`X9Rpb;$yyNDC5&N8gM>sLyWjKhH z;b8bRS6ipqWBN503^}F}T*X_2YJS!h$D^ft;h^n5jrD%cfzYxuVPN~Kur+TEoU)z? zx00{Iu+np(&tIXi`IP(xYmF(00dM=FZL|S6!ByE)=fmR}!BBYAMItU$J1$Cjj76Jw zg&`zmAxwJ|1dp$s2KRii5Z5aRGE1F-(}u<1Y!wKDG})KD-jXZEQ$9Q)s+$tw#2Z6A z9KGoW&aN_FQo=9Vn07D}-+i=Ha-pMcu7EoY{Na1Ts{hH0-n|tD-t9y2lz&Yn!U+rN zr7i0E!|gEHQwR5NE>5-&!uU^P6@shOv$}r6Roq${gmb2s2Oi->sc~^|tCl}#z2tSw zsu&^siuhs84iyxFtJJn?lH+4KmK%U6N9|#LVj47{9&=A3)!2?)3tM^w!S}pq@awPv zb_9gL{8RFMUah9ll>I&s53OCQL^u)Yy$P-c%!HR^t46)>%7*yjKyf9)iR73}sNW|VMm;V`L?rD}Q0KNgdWN-C2(IE;b*iZ@UPm9= zqzx9&E2!k#Iq}qb8zfE&hwgce=@_XsE9+$gJK;ownxW?^o~@@0WUEUeq+oB%n7T#C zub=X(o7|0?=d9ISc*%@X_|L*tSmJHE;1N!!dFsbB|G2Wl4jcWwK_R$`=izBqv^EJA zWKG6*rP2id9wEO!$?rvSr)>4x#OQF7vFEXAXgPkF;1Nz-N!krh8q6U-w<6S53+gzE z+*^~e&fNJ5!Bu_Yc7Vl{aL5=g^VA=b3X54&rsI0r@tsFF5%_95EKdoCfej=v<6Jk9 zH-0MG9UiL?T-A752Aml=6KbrH_ih`bNxWM<5_6w+7jb>pL7PuB2B{PSJnO6yEFW{LL`N8qfdfeOJ@{Q79UXwY*pJ+e0zHJ_(k2Pf380NuOn z6sK&4VRnnf3c*$UcOp-ul+$90eSZv_mZbb1oZ$Bu?GzHTL)5QH73=@3RS2%)U$$sX z(aMv;rBq-1kh(?r=EVvA6wr)*acKGG zc3&_2xZYau2q!Aei-(%M{9yMO*^9=PsEXr)+M&HiV};-PacUO~52>PL zojK8P)l!(_>rW%U19Xh1*K6SXh}Kx)QyqoiDmCl8vvL*8y3`(R8)NYJz{A zK`SiWq80{d)`CYk!E=BH1623GyQ6F1&??0hf~yYo2!Yk3=E2Ala)fLj3)tv%J^WOt zir^7W@Qf#|L(WD#7i^8~3*=V_uA200CKUIjcS)uk@4^dL-09d5N0%!nc!U!?*Gs!* z2f0yB#uis!`v#ogs)w|Lht0Mq*nCWm+tYeD;fJyIXg1bD@CYZ=%=VxyPB{IOJ*BHl zC-xHbubvUt_pEx&sDUHpQI>%>|Eef@jj{+eBPb9D2Md{j4o;}wwinzPgl7ld6WMeq=_u%VGc(#pp9xl@tzs@@;+HTq+xQegXQHc+Qdt;?0 zmqg8wElTE&6MV%DRS8vWjc3l3L=Re>!2cFk@vI@8)l5HZ5Lw#Peq29ssm>f2c6S$K zcPhNL9O&6hZ`N*~S*ykgHOu)ftq?}k>8l_1siF{E#aFt~TW!uT?BMj!lwKi9 z$pZ3RsG94m9Ml)hatr9y`=kSpaDty9?SQ$gFYfowuX|6utq@$b>3$5XvEK#ZPvp3L zU4kc`9%ZiQZOJEigcH0C4F)IMju=q7g8sqRMj^P0ul=Ff-JqSOVeKYjUI%yJ^9(-! zP}j-$zD_m8*Pen^YOPaN&~T#es%@}8A{^d?$(;V{m>Z_68%Chl+(?DsDs?vDQ2U|j z$MT`L;M5gmHo=KQ^>@M5yck%}M)q)j4Jxazb?S<>24^Y+SE;k2(L?j=PhR!JC;i=p zT*oEXUCFgva=n#oBk2soX_|Qr>#cvBRutEauKa72q`ZfuCla59$(5Ay{*|jKX-(0i z)_Ro^b+Er*pI>V%|BY}$J*(j3uKF$8Mp&@kd4=GrF>AA+Wi+jvys?drk!e?5f4`9l1&?szL96X>JS`mh+>rO~+w9e*=T|3U zRE3HP!BxB!Xa}0F@ur4OlhD=GLGTDCg0JoZQ>8iJxLMx2=9f>IPT_DYu)eKAa23Bp zsnVO)k^NQG0oyiq5`49QofZL=kIjbS-gkhHQE2V?83%-+4%p&_wcrs>+%QB!ZtQGG zsV>(VY%1%3n_?aDf}x~BaFsgtac|fdAC-5(U1vW7k8r~3a}>arFo+73qrN>cHb~nd z;QYH;3c*!t9#EfLW)}R_M-l@|TVh5j58R81z$2XC`7+u~_f#eP5Yq`W6WtVotH#uu z0}HhuI1q;l%dh(NN)D7@SX&S8nXs822}&bzWafDg;;YR-n3~7Y#7v zsu3Srd$eg`mLoxaFv?nta<8=SX+4nPJUYic!U!?`$>BnR&>O=j~ZjDQ**&v zl&==ztw3v74mZL0LQOF*#ZK@DC)D}i0I)@mE6p)tbXkSqD&7jz!{u1wob*=Mw0l9p zBb?y#Px2V)Sr*H^@kYy0$AA-D#an^q22+Zl--=!sf8e5$1?B{w71R2XANK?9hbjlMiqGO3*4vwK?4aAb`r0Fx2Jjw=LLscUQP+h&R%N#pTa z{d|H)IKi_Nbc|6;M2{s?P%lziA-IZXspwnLjRzvF`yjOYY*g}BoZu@DX`OzB{Aj;><{4=6O3D46+n_t`2ko9K4xWWgZG&;PXP!cE6@OFHI+@en z!pGAeU;R^9@CYZ=-{a89x*{Yn0B^ppsSsSn-_%q^7uifS$nnF{3!MayaDwL7Oli(3f@Ej@ai}UK3cGV{Ux0<>r1XuBQJ7qb? zhil7y{V`(sc)=r_;F(*4;qNj5rZ3wk(I|YHLU5HjW>~zmgDL0IB<$%mPZ{rWf@h$q zx~8o&?%G`+gG>4=>)ZMKTwR4UqHHI;omi5pEru&=ia5bD2(&lV%`P~8Phk|prz-?k z@zp}qQ$Oj8M{`~XtIE@qwNac<=bUrhdgAkt58_e_%CNANSzN_e3sDYv)*y@=d0K23 z7A1Iu6MT+Kbw$qo(82q|}-DDqaOc>z0D1 z;l6?uO$$4ROBbd8tGnR@&v8&@`}#Qa&WtrZSRJMiT*a$kXovA{=2#})3wQ1?C?hid z)tZk6Y5vj98b@_%iEBDFQ$~H9P`}saW!qwpCq~?JElwf0ijQh3!}7`=mzQwCVh(Z2 z=#>-v`>?@ax2GvSyXA;)hV4-ZuHtz{gW>E}XFS%^0VkQqDH%vk@UPaid(tRZbSuyp zZ8~Qu1XuA4EA3T04Y0d~Ew+e{2Oi-B|N2hVHAfIneXfT=3$qo1t9ag*b_(%tjmiJi zM)Qe@N=BFyd@TjlT0U-rDQjxs>X{~m;3}T+raj{Kb-*Qqs$l>06yOm~@U;}Q*5GL; zv`;s~BBhQg1XuCQJ$)IS)*CODDuM+3 z(bMaq(8&3RM>xUP{!s4|KN=sIj*5!|z9|G(@eC{Z#EqGTHAgNGtBza&9^r(#Hmal5 zRJ`f6P>g9=M#p#dWVSIQ7VO!G9_K3(C51Ss(t}rE=?r1!C)s zVK{kPrr;4ys9&n3L*>|n{wQ54Il)!3o?6yF|8}XA4wd9oiPEK#M>wHg$EIlq#EFvq zFz#ojLU7f=Y9?@)w;cSJNta5`bp@%0r5y$~-7a{96TIDMe!ieCem-W8C-rodV84N^ zDwoyezg;Sy7VN1#D?bJAjZ9No_sz^)c%4TrI)A8Y7Zg_ zL`5~Kp+6|o8pk(uRWNT%i!dg|Xz;cRL$Y^&6mjxl(O6@J*;0CT797dJd~ zc-1csR;_Gr-07}Et+8=%qiTDjqmv0veT@UB)zTqPKWx;W&-y5KFMKPUM`lCIuT(<_ zUPi-^Y>1@0#ARm({zW!d20A_2^* zNMcckN_yW`8^!0>Mup(255>qm@<%-E`$xJvhQ$`ucOOU=me)LyM>tXG#9r_jmM(%62ReR@~lF)nL54bE%IB8Q3$TuGm891J(A#c zKNliWeV3c|uRu}Z<3!{UPTc6S7hFP2TERdwtA~u8oCbPK)L!^sq>0y7H((d%YSu>U? z1XuCCOMZ7QqK8jvi({W{5%#t+$x z`YgU_D)YWIKAHVSaDuCND^MN%w~wZduFkk)TYlsbPN+TgV63CNQnuDjzbH7tRlF4_ z19`?p-!;Ajo?due>DxKM-wc!kxYk9__wtE|ESseeT&4EyD~dJJ6Ve`vyccFl-_GAY zyw|4hgAJ?cAwNrE*9Ya1M>wIJq2bKMlcp-xb+PxGdJ4f+BVXk}-ShFV`b|6fJ>Ep^ zHl0p)z|sY4B9Cx_w=`v)mpGeF^l`=1r8Ww|Rn=CJpEtcf?v9ej=xc86`ksi08iq^g4LRjj68y8EnekEe9N4%x0VMhN6yk2{gNR?b2QF6 zuop@lN`d#^8W}rv+Y9-Jr@**QvKP(#SwqCUj1kj2PsKnBsu6Tffo%sIjQk8$qHEbl zkmj&cOnNdNd4v=EY-x2u(jalH^I5S4hAISC@w26w*XLBQ(hH&1w~ulioKUa)FSBKE zrX{V;eAhuCxavTkT$o-s5h|w25x~dd0b+E=KB#wlEoOviaNHsuI*KkvK6_EeS1Y~Z zMXf@#FX!-6f=4*P=Owge`)3^t>DC0#uTK|zM9;@_e9mAn*!vX5YF_U6#PPT?H{b+6 zHdRO`92K(yx}$5$QwqUVeC|Vgh3(%bwiW7$4+or5<~W>CuOo4R8J^85j*e@pp@n@m zWLvI;ZF_8$5$jxXI4{zCB`jDg-G?spsDqpPRl=BeKLn5PH?lfrm`zV?m-xz9p~V@6 z;Hsu++3+@eCA4l;hmLXXb6uS2WP_In?-zVj%tsvjnrK9}vm_3`)dU-by;OcdPVmu( z!QkMtTg*Dp5*;4W)w9tySMj@t_F*}lDq^O(;pm;_$RnKKGXR4jsG?Eiy>Y?aYi$&Q ztJHfp`TYv}E!q?*fswT90*`Ql z-wU)8bkHr)V9hJx*`|#`a24-~Xa#n`lBOZ8$6>wJS;}aM&rH~ejt_Xj8VFH2*Fcc}G#V~_V&xF`fy@wXjSvd-V5?QUs> zt_@l$Z#7Qv{?TCYpBQP{Y*rK7e=#ZqSMj$tt>ma0XPR@hEOw~cMtM7Pg1@h*%JgoY z>Dj)YV!vlgh2Sbar=r%4j5j3(-4ILr^hF-w1b_P&3`IIcnr0u_D*Wz@PzbK#GbHMF zv*+gaZ#q|mdix@eaDu-dsb?780H8dGI)j1~f~)wPio6Fp<%sSjbz#%GFAff03pPJ? z{CW%j9FhU@pL`<^vEK~xpX^;}ugOc~7xu#fFDI&fBJT%NCv1k#lQ#e96Z^jP7sniY zMdihlkpJC9o*7WPT?Q=K>|hL=z7^Wu*Z^~D$ob$`de093=Z!c*>)iR1%Fjf7Y8Q6B zE}RRU6;Eq-Mjqh=Kent5-y#M+PZG~}4OIxP;$sP_=Uf^gMx6{0WvfqA#tfWLufu*y zkf?WPfT)-^Ss}QJ|2C9w5AhM{nO;KMH%%G)aN-SBc(=;f0B3AuTg~!x75R@^iSIrA z6@shO-+V>b6-cdk6pH!;Bad(*rs)oNo|5)wwq3bZML1OVr*Xs1P=(+sb$m)bE5Q#jnL)sW@zRw&no;| zl*pViPi#mWrx0Ale}DQuSSmtz-HZ^YKaW@Lc1~z?*B7O`-hF=IQ%fVRFIP?9JSR!nos#c6`6?w2)=@UK?vKv&3od=zP+YxV#iEKnExURrd4(}?ku%}s;TzE=U|ytyWz7@6q!*;AA8t{VejLi zeaUR-P{-Yv{52jf7SD#XeD20HOn}vt=?tqTXLmiitQ32Pl+d$BwnZM{MDv=7u>H(l z7?$it#Qcg`Vr-!^rj)2&3c*!-wkN`oQ`vC1ypf2KzDq^5x(7_L?*<`{aKdSGB8=I- z7an|-Im`A_(nZ0f@g|%4V-$j`n%_=>1AVh$&wQD)yt8?_xL;tA>F%!a$RnKS)HVrj zPS^{V^2=k4o<2l0Js4=3pFUY3xQe$rjl!>IiL(Z4{qiDPrFD6`_4bN`4@0w|Vm?ng zMuCcV#m>_W^*5!fAdhe&!Zi-wpU8&GV`OH#_x)?)NYS>sUFDa86I`X=T@F^gvmxk1 z2O7mm zP|Qp3J@l$VaFu#i#m`z`cUL={)8xDe-I@#yj^)Dh+x3hW*Cj*A)45QjSbd|mDj9}0 z&4s(>^4mm!!2+B7ZHEP0ofka9iRV`mpxzJ@49;*OB6Lq}oIJQPMqB()2(Icv-$6b` zYtX5*yc46g)y66(>!ZWA(}G7haf31+Ivr#7c6p3br|fXe?9%8^?Sn#a)&4K>KnB`S zabIg9_SUjSU)nXI^rK^fM>tW1s{0?c&|!Wx=??7F&IxaHD30F`KUD~>YVkb|+B%xx z(jxhL%*<|pHO5$B)rI>7k8r{?C=Nci)?sXrJVpeqlc~P2FuI<xUXKJ*LLp!fOyGg_xB)0JM7pCRutXdmIA zL!xR+9lkdvUkldDaDpG3#_bjEiM4sn_7;0RTp_rM_k5J0UsVuWM6QHXs*>grPW)Xz z306PL0gLbQTM-79B?rC*#uU$P3c*!N3MGOQWu&&Qli8>dU+Ut)HOEYEE7wQLqXAm$T&E7MXx3cM*I|}Ia24ZxT?{!{% zU>xX~xp1duU-|`?wjGB@HkLHmnq>(d;RN5SoMzka`s1>*9wx`H&lQ5J_}xQ$X6_n@ zyJjvod9*$vc!U#tuX4&?*?VB;^;b1iJi-aSS2@*~ zlogoRtBSrgiZWkp^*6a^>jR|u}+yYW*-cyJ#a{xnyN4c;$!g!?A&V^eK-J|FCTez}n%nFgZrg~G@qoLEvd z9_E^Iq4+%zE@)c&sUm#~;}vk8py|+YE-X6Az0Wo*82O z-~EukA-RgbeQ4*FIr*@1rK{q7YzyUG%L#rwy7KZBFyQuj@$ow<1XuC*mBC$F;_(X8BCD4%JfLgPh=ZC9SL}=#5S4*qFQ*lu`(;;{7r8i9hm){cTNpzWiCYrpXd*Hm?e{9Zg*yl9$$76$-RhddeA_Je@Xtc6(YdY0KWi>ES^NBF zou&4BEvIydA*UFVbcy-%yh{e!0Z(2q*rm3e$eqB6qvh zL7$dcS%2S%{NaDEB>i=CuHt7)HHzdALryWebcvA;G4vMDq)W`7FMpa`%lBs`p!R#6 z<@4Rv7<#6WUL)%N)^cjnX`$q`9EiLft9_`SY5cQFQhu2RoRddiTuj4pj;c!U$`FDRXE$ni#(Za19ZD&8XG?L>Yr zL# zxheYopfu%f=c+$zbhO`VAnRF?H%GB4y7if~f4@ilig4o3I!jINw?%Ut@_QlQ7hQV3 z@V~`X((i>vHrj8`mwOdAnDpx-^~-%?1dniHpwC`NejKX}IVwG0e2pJXx9|1VuiK7P z2(J3Gsz>|12GXim2|d1f7rk+#uK%vy`4!>BpS6*i+<${2WdFl0=fv|d?3Y*^eYSnU6pw7+&a0~R+Mv&)=uTuha1wXCjNV(tZ+AgE9 zyaaS3ruKH6y{%#fsrS7 zYJH~sG-8t&xZ<``+rF?6xJ-|Mn@KyhYuDut8;MgxF=6D_iytNXJ*!x4l0xPxUzdc_Tcfb$Zs_IeA^1+?1GvT@a9PQ1xYY=Kb3w(2; zwC$d^pg2{lUwjayx%ZWI+vZChu&%#@-ePhC@v=fV+?o`jUFv%0SDil9ifgh~Ka;BN z?-(Mr>|d4l<&CueL+^UJ?Z|W?{a$FlIn9SWU;gYN^Q$MKUI?gf`PCEAmpF2k|EX8f zUs|pZ-N^5yg?*-$N}ey$?}gk*v_$fJS!9ZVeigH{@xMG@22Zg;xBhnevwo?9M>rw< zUdYi!`|bI1`ic#H*Ba_)`mRz4u1X`n7uqRL3;yN#vb%OYs_bv7``w5Y((mP(%@$31 zzDU0pa&gh5=gYLyq0n{aX07Ef&lis>_3-`eruwW3iv*8wLi)XsKZ`c!m*>kY-3^aa zs-b_4R0*!)EkgAlKkMPll}+>p7vhw*;)L{jAx9VOx97|9+x0Nqr-?o^DM2B)inp7= z@G#jL(+)W57p^Z*uAEm3Gp3R5)58xJvrHP_3}`+w&!Hbbb65<*cU-^cT|ag?wK$>G>l4UdY8ot4N+N zzNdUa8<(n$`{ns^eVG-GI_aV>`x+#8gcH*5g=&+v-<~he$~VMWK~41yd#5VL;I!|l z>2Ry>O07Vbwe);=4tK_@={CBp(;zy=e-TcUCcl?{MG~~LzdT?+HcR7@AVqs!jUfemEye>f~(ZC zGG1zehRzOp@men8NrzC#7(7?ACeIh?_d<>*n)H0(XG>o*CfMRnw`O|9JMES0;Dq#h zAx9VOx97`-%8k%i!bz`F#6uytieD3Dw!Ir;+IUCZDjJ0Jd!c<9H0k*w{a(n$MU$Q{ z{A>+|pC9dL&kuS>g`sjCoREGm0w3ieHn#ApKs*_eGbU zFVgRYd|x!_`6B&ZXkQjhdcH`%7jk#eetW)rCBK)oHq@6yxCkEML^Aokth_N>TWXa1 zu!ND{OH)sKece};;40}IM!VQ)$>bkKtEnbBW9op0decpwLb|k&CyOSXTBOGdIl5@l z=S3yf86C0an#OvI-EM+MCXo+W(y^IZH}WFme~D_`Pc*@d8xFct0ej^boOnWhFP%OF zYkhusz6_`Rmg{$Dqz~=XLLs{-tE=Da>5Ow; z+v@kzycB|~)U(P|7l@S>yq+1Mmz-ZDj#$c#($`QZrwb5Vpm@0Tgy26l)izc06)MI?f*981jA5q)UwSdm(=o?YHO4N6XrH z{+p{lEF@YXxQZW}_F)Ne!t#5qb?^Cel(XW5^m`#k7cKuU&zE@>nqkM0R{HmtXocV^ zeod5NNved_0ko;gfED6(^(?4=Dn?sEE-KQ0h1^y&>A_OfD-&#t;acV|2bWIR1RKAu zr?<;X5In*O=@3JHFxqdIm=0U23&xkPCzPDo!K za;edzHxKO;lHrIQt6S?m;ua|cSMlG*V5s!BEn59Qy3RVTs;v9}$1X(0E^NhCY`FVu z5Cp_dtWn3p4oX1;13~OU1qHiD>}KC>=a{38oioN*V~&pXTl?PoJipKO>ob4(nzi2S z)AyWp_F3=o)n&_^EB^C6r|r&L`CiE4B9!w5w}@d>J5hu8JX%fqj9ad4DXP#% zTg@#jU+*~ayQk_kIeKSt=`^#Y^t+i^iy-0iWD6TxeX>ZOs+=#;JzV9bg8|Yb!%rhH z3zwGq6cu)tb+0r#>W)8U zy|wkqk#fU~b?j!w7G|c!iB8G&*p}%V+2|$XMJD#MwngYJN8f3&Fs#G=UC0I z4Ie97=1gEODz9d)lgEnSneoi~ICZc~9xE={d@NTA^|uc2iIjs&yK50744-vu#DW+R zc0=`uk6pp7-p8Wk^S}iffmyhOhOzbhMr+RNBW1x^-rBMwaWHKI%NjmjeB0ie#&Fsx ztw#P~a`j>#jle8C7N|o1_)A9Sjj{5t5tUfy%W3S`urVT&YZ}YEa5-x-EK*#`JD=s4 zw3N;1JVwN}SKV8;wHzbd+QrJh=T+7sNZd+W&hCwj6kGnDM@01B#WE%hi^x6#t)lD>732zt4SW$rmv`1U7*g>hiA#VUJ`mErkx0<&<>(!8aw?&g9e zW98$bBUz?3i`cBgqeWnYoh&~Y3J$uA5iMqK)|QsK?;Y*J&W((f3%-@pB1qhumqy>d zjuG#jmeNu!@)+hZ;B>64kh7vjU>0t5`r653k2x%IxIF9@#J1g^&30!*iEwhexZRn< z&NPVEOYnnI8M@yH9g){=Q zaGmJu0rHFFE7VPPe4B~*Y3z>6c(I#ZW%*uAV+YH{im5}duqF+rv*zn#gv(0RpL(p1 z!T;_5lblmKixxqmUfUV$OWHV*xaT(_uKfM4Ips`GnZ0#0jleA2B8D-k=QXqOvS8Wz zVoq&aAu%{+HcRvxD~2vrow;LvK4hNWG*mYDj=(J3Zq%*EB@eH7yt536($^f=VQ$n^&gK+Ctphr>(q`PL06fZ(&xP zTOw=UV1k&|PIcxkvA7g}SR+t2>gT~Qg2Zp+#;M^uQH-_uadPh~&BLRb%Poftjlit? z;}clcz7xf=k?Lt;+^+JxY-BT;{hq-vg2X^GV{E&EWFexaypm$;rKozgdvLtRB&mS<9kv;>vB+XS-%kPtKawk|7#_;s!Zt8XuU%mi;kVG@f~zg;$JYGlx$WDR&gHpkX~eVnsuFX8czR{w*9sC#qFx zKwX;aORonFwZDZ#VEFbBM#)2YdU0N zXPw5g<@7AOxbIcAq%?J4zcp2`l~>vRr?Kpm^E8qDjOx)?_((TCWM@_>Z|DSOZJ9Za zjp;o@6q={bs52V}^Jx!HTdNPq!TMbt%gU{sC3@dH!!kOP!z9yeQP}w`>m44&ejhzY zEbu%@M3XN=`GXVEy58DRiy(35#%R_g^CGdniSh!x_&I`?Kb~lP7gR_iFw5C}42vqd zP>dU}hluR^VtI}i2Q#vdFR#^Gb2^P-6}(eLj(sb?tG$k>9?OjqvqjXGGFk+QE#=0r zxz=RSd%W_>Bs3Yz*KG2%_SrH_BQOh>&@fIf8q1r+G_jU-Eyyr}#GKk=n2cE{3OK1X zZ%Mu3%(9)Veys{?1ZL@Le&={3fAnW}^TFP_tU`ma?8D+!Vj+2D=8{up_n_4xM$x%|>Ww?28*Ax)LL z@k9CAJ_pUBcVe^%5+6H_XU#Wk5EoCV`;t+A4(FTu>@uIfX{r&Jr7u;?@4mc3cm;Be zW@jzBPhmsiw~L?uc4AG^<5=jxEn-pMn%WZ5+oj^I`R~h%^6KO`#3eyuOu0BVAbqn~ z{YO1os&9?E@_r3-@H{uNXar{A64E>2he14g-zDo$;pwKMFTCx&ELPI>3VqlhAAa_J zUOD^OdJ`i^=+*OPOKS4Yu5MEPxlSW63*QdVm&F@L@of*&L}=AjCcY(cbY-)>8PngG za2dusT=+G^nv`T>1c^&zp{bX)OEk---mz5MH;Ru-Y-o+&J3}KdYv!mpc4E;s;W|Kh zWg2%3=V5NStgPV#6C+6YlZ9r|tF5A5HATewhw{(@ovlS04AltC>P8ltKf`|!_iQGb z*P+3@M-FLiApsI7fobX3)hKdOSKpG@`RZfK>};F^I(OkE%RIIE*PgDe2NL?bi87!1a%=US)_=Oq)d18my#K&*eoyyz9Iya_#%dCPt8`+<7#+ zJ$;e*I#^wI4|WgWuj>?-lVfXZ1ZH84oO~=XZTXWK`Q*jp#k5*D5*x$Eu+z)ui%m8Y z&8xw_+~p59yJUhjRl{OR2CVER&CWgrtO^TTqK?3Wr^vgN3GT*tL z%V|wBYXoLBA`6Z8lksA&%|z3l*WjOSH<4w03YZu{0xQteb0DHRZ!pqRI(7QOkie{F zWT81+d!qQ$W}-PXvJSofXdpMtDrI5>39OOR)7`&BtZyJs^~$3Wn6-v1H0)2h-?iN* zI+d@-YYBJx&!ZA1Mv%bzKHUMFsK-|))sw@zePBpn)&R259Q-s{{An}MY&f;ZoU&xN z%+|WSIVxifTVok3K9GrK=$2nt?rG!2V=~bUVVjso(0Gw8x4HwUnAF2uxMrlR(I>$y zy?q<&H#JVQkFL)G^U!y2yW&J|ulj5qoqJh|O%>@j6HS4ISJ>uB;j)H|H!*^Q@0wk# zN~5VF_d3<4M-HFMSZNroP2r>zGP zdewPHmiy-2t-a;?KTVCmtbhELv0Yb3i}N-U%_yI5=BMbc@}GfqOpG9bXBu^5U%Jxt zY|}^jY)Ch877EUK(W`@5j-EF6X6h#YO8>9V%XSsTSvETHZ0#j;z>^?(DmGoK4kCf` zi^z+dEia$-(nmh;vq2*;%h8+8R?DPs$*SeCW}ZJ+KdLZ~oIpBQOh(O8VYlU-N;|YBR9cJNdI{M2BP4S_p4j@n8Cd_i_WaT5 z_e8d=`c4t)pIy5(Ly6I3!gIR3+azF zxLcfs&oc9B&mTzO{3810^bO+kj%4CH>ozrMt{9`aUAFmRj?S94d0n`KG$X!HPM)!} z3;*d^aa%7-IwEXyD{&4J&An8|oNfN4VJxIhx?i8uy@^v#H7oPK5hQR4X{o-|;xFDb z=52nyq!F0)XzFaXZS5Xm+}%R&4H8=f@Q7xm_|~PL8Ag!M*W*$3K%R4DQQl)v1rrI( za+ru5b2*bnw&KPb7hd9aH4`I9;C7>L`+kby<1WASs9f}s_Pm_tF_x`*uv(P+FhzT^ zB*)0kaeVow!~2~Ra+>)3ii9gUWgb7+D7y8ud1a19@i?oi=~Xd{Mqm~`AsfbT5mEf} z!hB|fttCy2An}o$GJXBFijk5onmFW`mOa|(w}Gh`;>Y9aDYZ&79OE=PrcKf2Ul>H&kxryaYh2pTf;jJ zvI%~0=SR1@%iamDCPt9ZXSe-5qds>o;4TB}I%x!E>31^aoEr0Wb!y8!%|9}XAW?#x zGCm&?gp5@c$fHq=f0|oO?wh_>BQQ&!r8nnOGrqK3IXN=tVr~8&5?Em~j0~qX+`DKI zc|XIV5txND1nHa6@}2psyiT%7LKbcAAQD*jqk4(84(~mso=iI3z*JtJ|I8OuP8sr= z2<4T*tw2XfHh13ok-HoiUERb85(YVCthuL%=Qgj*{u+&V>GrjytdUnEFblVWVH`Vc z;Xl2vDyt-aVOj+K?w4h;%*|t(cxLm;oGS0f>vu0J-+dJtfmyf}s2k$2_B^R?ewnyr zxmN!~0;`eqp7VMSKK`B|{VMos1ZL@V(Jb%!^Os%jS~tbzWEepL>!sA=_kL|Yxk!Dv z!`s8eEs8UeaJ$j>&fmzpbgHiGxVxr_5hV1dyUnLO_~?M@a?s-Z8i85373h1l`99ow zp`5Iml-0xt68JPpo$-Ea$19A>FSk@W$&kP-+zM2!9UH_ytjr-jr(DwN#z^2ZE_L7^ z(U13?b>CWK)h>;|EUd5^hHs0$Jf!0v)-{(OX_ZtY@L8SiUJH-n$;qp%br+q|2+Y#w z?>-$hjQ7g7!+LpDCKDq_V9kNv8w?KNRXfhNW=wO|2+YEo6TO?L(wo1J{=*v9ifPp- zBye^k%}xmI#M3%vmOkm-Gy=1*GDW{?*&FibZdK*!Y7r(zkkDsl9%xmW54qP+{#0YK zMqrjcU-W*~Xl?}6GWRsq>(n??8Y|F-akXtMAK{mY9exw9{W>FoTiq~*xsT%;_FWR5 zTd!yYX5lY2-St%-!`Hvhlvp+^!?GRdnEU*SjGBmMp=!(Ec~UW`c?91?sch& zb#bYNCPt9Jsv+45wvFY(@01bI>vaON@Ryq2hF6T@r4CLOgZ$c<7(oInp7g{L9LXC- z9b!i&w9^R8!rykfTZ$aR2i1;d=Y5Bp7(oK-u=E}Moss+yb%(k9EleXYOTTCEd^(bs zt{rF=m^EFy-$erJ$z*D};Kr}lXedJ}j?w0-;nTK0(`o2MC;sGNE7`X60Bzn95?BwQ zn*O`&{NelJK=zfb<>nEd1_YNfBK%=-e4es6$_f#KVX)%Oy*%S?(GDPz%2aIhQ8pL z>ci{gtRy=$G_)@`@GY`_pZMye$xF1VCNmZ{*6#X{(BJSLy=CFc4po;~(-vt2X5n2e zbz{%on16d!M-F?pP`i6Y0^cap+t(ZQ`N&=Mw*i@N1N zZ4wE5&rNeba@6LQpPR@M|L)NU%))x9VdSk;o!1}CWL%GAh7lxiP5?a#XLI9M_i)*t zdLAQzSy;uT**i`Z`0v5KGNj>Rt-gx{&W515AA8F3gp1AOrn*uiFbnI~hH+|KF+Ocw zOIdgHQic&Ea8`$5JU?BCNB-JcJ~?(mBQOi=@YGe_%)uvh=pyrXThB0pgg)yf>qCRb zjqEOWF1w`>n5EY&{h$A4x?BjBwNG2MZ>^BP8BkO`4>@7Z88%2}3;d!Hn1%IH>dMt_ zmg(#pCa*od$}ob2K96jP=WO%U=MXvLcs{N6idlL^c>JOw=BaLDXc(>1%2}ST7$--C=ho_pNa(Zl)^@*>(LW+up6*yhBQOi= zrQ{92*Uq}O+8DVnD7RJ@MMAIjU7Z$Yt$H;~&dgpzBQOiEc82k9+&=66!b4=MbXTpu ziv(8m=uJcLY3uvg{_@7d0FA&b{VMA8Ad`GqCrI`%o0=FwLa+5@KGlyODLl)1aQk-c zO*OuEbbKN0_yN+Uj#e8MW!#8P5OeFtFMPDr{IgqbtLh!hG$L*1YBW?OKftYgzc0XlCYvD*V`9lSjmV)W$#p>sp2}kK8!q z$g%lx@NZ!jt{?e157*+44^@^i@%qdG{2DN8!dy1>l@NEgETGEWh*JLiV%zL;BAHKc zt^sE0?`vHxb@;F%m81)Oi;NK@l*5L;Y<7I_OkXZ@`hwZ^^)eEerMxxt)v@E7>LFx^ zAybT1Sz>VC;y!nD-f(<>t_(3`im@t73`UT^vFS=ph8Qx%Sd}FP3CvQ480zgT?3Ng1 zh#^yqRF)WwAfc~^GQ^N6Mk-4T5}4)aOk(@8+%R0s!Tg<1d+T4nZq?RYS(B)Dtx)D9 zoUdURsjj2=rr;XFW&H;2{6IqaWvIKZP>vbH7?LZ5zntHkO}VYl{lF~!E?ik?$VOu- z6Aea?aP*dOe1$Cohw(e*Bg}}Y^E3jp^k)O_W5K-U^>t?8nu(2$MBW}?9e5{_;(j<2wlg@$Z2HWLjJn1$z~VJHg?*=TGg z8jK*}=yK!u3R_ud$VOu`(IA0Y`gyJ_G-RW(Die*e&`{54p-eQ&LPI^Og)-473k~&o z7IqVjve1x?Mk*7Hvd~a3a-mE#%0feZw}mp%C<_hs#};-Ijk3^?jfN`|jk3^CcYmQw zG|EClHUXhbG|ECl9r=abM58P;WTWBAM58P;L&gGOH_<2y4cTb8GSMgt4cTafGSMgt4RtjZ%0#0qG~}ES(q^Jj78EHq@J;mSmV1ZF7<4LN6o-9)1-G-RXU%0z<^B$S1QoHN31 zqEQwaveDQ~G#EibS!k$_v9OzHl!bnz3k}(5Y$h6vAfYTY zqQM9f%0fe3aE0AOqbxLJqp_K2kiaZQKRRJI(I}@3xn-pC%GjJT z^Q}U8Wt3BfOff=vW$-wrc>v^;A-9ZFUKxxap`0@0fDv}DjB?75TSh9c3=){7pC6X$ z^!Dm%O?fZ(1rsAkC{GTVVuW(#7>2UxkX1)2qYe_7rEEIX`(D_MI?5?SZW&W~W$>z| zoHEo0T_~>%UWw=#hnzCxmNAuA1|vu)rwkcOgxxEnoHFE=F_l*a3CzMP5%uICrwqAe zY+f0RAfcQxWGoSOuZ(iakXy#)l|cft@Y+RHXL8DrTgK*|Pn=lp(i_sk|~6K?1il-6xV$hTJly^2#8A zS;{FxZUABT$|$D{xn)e{mB9!Sc*M{<7IMlIYkZU`uZ(iaP{(?qyfVruLml#k^2#Wu z47pQ;-7BMwS4KHy$Sq@4UK!<-As>WLUK!<-p$_mud1V}Z z%7ne!v~tRjTgIxqGRi4Ko!5o(%HR^}gmTJ|TSh3a3`UT^r6m;vIc3N#V^v-mBrpq? zmO7YGuX}RK2<4T*2on05E2j*(WrXs|Ac0xRDML;LVfV@?rwqAetja5+oHAr|5Xviq z_tg5`l5)zBTgIxqG8jPupJeE0C#MX#Wu)@T;4=W;o#8VB^&}^!47p{b^2%TY2^^bx z-IG&>+%i_>l|cft@Y#p@k&#n|+%i_>mB9!S`g$m*47p{b^2#_m;|bMI9e)#*Q-=D7 z3%gfFIc3N#Bb8SMBS`4KoXROfZW*b(GDu*SqgSA?cmGyS8FI@=<(0vET)gAJb)q^o zIc3N#Bb8SMBS_%A1Z~|z|ff z#^#kl0<-XWha7I?lp(i_MR{c~f&~6P(z`oy%8*+|R3NVm5}1WgNQSX=b17b{bS?RO z!GF7++OA|PcK^bj$EMr{non0zve1x?Mk*5x{w>VX&vRwEA>)k| zY&W+14`sR`i-%CQ8)dp7ql>WHZWgyqVB4-w7k-yxxbnJ?heas2i^FMRd(PCKIhDPI zEG|MBTrh(B0RNIOz4HB58Z!2Y?AsdYqOfJ>iH||UK!LW}>tEH{?TdR`Q3JJ`@ZAf)$GTo5z#;R;L7(qf` z4`sR`Zjit%{U}k!9y0exW$nT3gJUR@4|RhU%H~5eoybB%HX5l+G#EhwuU&?* zo_rJ0A4w=Ql4<&+^GjIeuUlv9S>GFIi4!3Yw{DMS7NVfV@?rwqAe ztja5c1ZF9x3|U-+-7BM|e?Mkue0a>`KuaAEh#D5ng$Wu)@T zU<3)}lpzOMR$|*x#?S~G z#0V18$iDJ<+X4~wz9U^rl!bvy_E~I^+wxiAGsy$VOvTCK`+&q5pm;3k}(5tja`#R{$IjuNX9IlC}fcXspUa zgApWfZ0bBr78 zvy_E~y6_9TiAGsy$VMZTi3Wd*l!b;2D?*uQl!bI=JxMpA`1=KXly1LBrprFt~5uOEHq@Jv6*Nvf&|__ z&|7`7(2$MBW}-m?v+!4fzU?Cm4cTa?5Ox!dve1x?Mk*5xMv%aM z=!T&zG-RWZ%0z<%X5q0wZyLx#LpBV!ZR8nV&YOf*Pf7T((#hBCyEDMl(w40goFE2`cdzqV^8e&vy$jJ|(B zGYKG}Uw3buD$CR8yX}Jmf6)lcLJt95smVe^HX5l+G`LjgX~6NQQbZOSve8IoqQM9f z%0ff_31K(UC<_hQXrwaHAc0xaOl^7EHq@Jk;+7a1ZLs0k6|ba4cTa{%0z<^B=DJvy6=&N zhHNxeWun1fNX)`tA9~s*3k}(5q%zT91PL6Ex*?KcBbA8;BS_%cMNU1k(2$Kr zDiaM7n1#O*^dw9c8nV$yWun0d5_pv$kNbcB8_x%Puv%WeFPM?;U(U=#ASaj47cu`hOFc^>e|^?B&y0`~UA4KDkpf7GK}M zR3xzW-Tgm(I$}}(9fe|F!Y83UX{QR_y{@(;U6!ab`K7(wEbv5ZNdd_Nci3CzO%ua6Nvuq|8gaXM3LUc6QfX6{;K`?vGFhL+A9 zcmH62U<8TTLD`sZ`4u)=9|H-@!hNF?7(t@!KYJ`C$Xl$I_J0$Y^}qKyt~oAY-l$P* zTfLYcjDZm(9DDW$+X@NHYBnl?S(AJIU<`~P@wn)G_G+o;4+xAP;W!q4uvAE3*5%kV zmi=tuAB=%lfVJ1t*`eT*o@yW9HAdeb7(t@vr;RM)X~GYd3JJ`@CDg~j2ojsduVL}S zZv0>jBrxlLuX&}s#l@99sY0!-<9d~${(XI|DY}-KXZ!#9Qegy%i&r8tii}ukqjjR{ zI$zPP{2beMcVyX?{c%hgQOtG85B3K}kiaXdJ_Zt)HQ@5gjIaAw{a_4?Ac5C>eGJDr zVOzthgWXx|lLfZz<2WjRu;v&+qIQ+e%=avHHu^v3ITDzKS8#o)QrishT<5mg_P5#v z^|$nV{fq72j%&;hmI@d?QtjPXlKNtfE%);%a zj}fvUS>(%A)%Le$=9(#%j&EiA_pLJN8H1Mv{b0>8f<#28@nYNc;Xha^BrxlLAMF@H zVsp=*#k0WpAB=$nX5pEpuQ{HzpSI6oRSo3jahIQ%2A1oCTn1#oJ zJ_bgRcvSk~{sz0#e=r6Tn1#o*J_hb{+&8Vytq^gUGXG!?a7P+2@8I3*M|gV zb(_6jJkPxC2glVvrDu!&%lw%-pB-aZ)W3ZWO%!{k46^-yeLXOO1YYg_H-TCF$^g;# z&7>cUfe|F|daRFu>(M`OvFN?E{Qp@eoxo*BqIRiO;%m}-+gAAB1ZFw5wC#6SCvdyt z{^%t)iLA>!ey~3J)H>ffxe%~BZ@G)9h|6=JTr-<5?7*dV5~+-Rvj zqO>_YeSU)x7nKV{Y7x%6!EdGv)Q^*fAMAN6yX=( zY(`x37R?qU319lRVVsOEDVsF&I*)fmS7JaGGpBIqw*QUJocVi$y^GJoN5GqS4 zIqys6mHj&S@vAHJ^}sB*jCk?%_A$pkKjU6NrgiY)dk?0W7(s%*T@%U=YPX+Gy_HXf zbnun+)6+~x#P$uJgRp(oR@F5@6q#~fsN;=l`Z4)smm5AZVNaTg5hPY#TOjUqkz#J< zcC;R2R^^t}T>_-r9G$?dSdRozG4wxU)V-KrR!;Si(`gKhAW^mQLNU=t3TLO*G)CT^ z3&_{*KC=8?8UrG&awUu98CH=s$kT#kG;jk=}BdOfxa!I6s6sKX7d7i?h9uyqE4J z<9F#}AmKPa#Ckf@=quA*h2+I;Uh>5Poxm)|*(F?Ud+@n)Ub$($pWHMh)x7wY`u=6? z6*K<+W=SnRRm`})S0tu?u`FCVQS@4LlHR2%%0KMG5>E~meQNF$pYN;wqPb2v$$yCGSI0rRo!efA*~+*Tz=gjqxtYNmk_nvfRoA+89WD3XKz+Ja>u@?$v1w zxiqI77!oM&4@=ev%+l9^5$_|#ds?az%_h+pzfQ?3CnN>P-|EcKh(yT3 zW19MxxE7PgGW*Gl3qPC9&Cz0bu_Uqj;9=IUL|c)4!7}lv#98M2dbHSWohQ1rI!myqYP1jr3HDw!BT z!n^EHad7)|ad)9w^Xsl9ejvd@Vc8i85*n!9DLE-$xXvR=y#?BwGJ(L~0I%WLzS zZAXj{cT*;bLhJIG_*6`;t+H-1&m}HLByD0CL88{|A!1YFWU;tHKDtjVdaN={P$5f< z>t>C>tbQd1i+4@pMbS6v&a%t(O0vmeZ#l|s3!Ml5KXT?C?GL{M(PF*xcS|*>dL_BG zQ&XA$*%oaKBo6fo77r&RhUQENA7Rva$x0Th7ly%c_j#+<^9C^{Dp|I8i}!&s7T zk?sGeE+bZ?GW@$p%#{;F_VJ^{*l-sb;}>f^`D}3m8T5?&u}~4hEIi(5TYaq~U;oxf zmTS9G+g3=dIUgwk!=uFjmjX0KtMxTy#xoDOtl?UXz$`oq45RkiwlYtvg7RYVX>4W5 zxgx2EpO_O>)SMSJOVl~pO59pq#Kc+_eFagrjZ6(LEE8JKU>HGSYyMfn{ab4h99M*v zY9aabF4c0Cc_RmE1ZLqDF^t)}{N(;VW#yU9v$bu7M9(?X#57A+5izJRjd5^(Q`w?r zCHdQ>B#poG2r*U(yiYk zYe}Ec3?oSVnl(kF%&96`PAN`f1nur7b9Bxs>xFdF2+YF$WEeHdbd~Pwv&)JVCTRNu ziM+EH3MZHPqS?D*G)C@A9pxSWyt2}j$r^!Kc=XU)LH1;?j~I zXIP9p<9||w4sNTh2NL_EXq`elGKMvFrKPIXW1Q^!FsF6n>h>CeS-4KrORs&5y#Lz; zwmW-UhP9slWzt23>!mIA`nu8_mvnKb2l;U>0se>WsHBRt}JV?eF-g zm9}+}xYU2Mm|ib<-?-gsjNz+dW!={C8Fh~71ZLrurl-`aQSwbwKQm>fKf|gMR-)hn@7=Hd}r<|G+x`fxZOI@RkT2X`YgzH6}^zZyX-Bp@cwyz zVi-XJYvk0|AheSl*~y8|X%nvznB_HSj)>&}thrB7T95LZykze1D!l9MWcI3Iyy#~M zW`D|pW*k-0O1|jNMm#R~-Ft&Vuf62c%2oK~3CRqzW?17zwkQ2r-Y4G^8~^o^RZCal zff30J-!vf6?@YYda=1U6^IYALO)BColYWsgTG#c9xjGtrcszR^6AhEZ0It zmMzIMjssB-5ZRt4Fpp?wvtsXHac)8aQ%^$r`>6JPTxIu%{(MjEtqij| zoedUM+a$14YrZE26e%OmboJ-oMs8vFw~+X?_+U|_Nj$4;d%7E)r>wkH(w}pW$r^!K zxYen`a;b`JlHZH39<*88x=3^xH(30WE1nfK)HCPYa5tGene&F*(lr9J@aUmu=XE9J z!dHI$kXL21W{#oa{Hp0JJn23AaAUBDe?5);k@AUsz0pd1e72C;>kK#dmy}*P{rQ0* z6-5Et>PT9)wEXLK03S1Zo3=lYaJ&&> z>WvWfvm8@emRcOZ%a_*)%);Z1I)(U`lr3ZYc%F~-w5^NV?MaCcao%S(yBB#=)nr~2 zlqd4E;2U1~nixSMaBXK1GB}N?njFpk99BX;2x`W=Ol_wTn6>Ili1_Q&YH^2GgSd~(%(CPt9>I6qv3bVy<5Kgzuv z_=~ID9OlJcM-R{l%yLu>nZ2I4@`JNnv&f(4%{0dhuNfld?AyjvT|IMfv{-y?BRg9z zoQ>QZDeAhdXXoa|(HOVSJIN()n)BD~rfURdWl!!S3VE(&_G)d`lKJI}vH?7)ccO_A zBo+jW5xmD5wx{S!8Y8`B0a^LDKY!XSUL!Ee!-x=l&Ms#;7o`&Mv6GA3Il`a6xH-wh z$mwU{;#%S|mVefAhGSD#m2?-mvAI8YYcfe21Bn_>!bQJU%UG3`s_NXZZ9dubRvFd^XIVFCG(OVg!k0Gs8uh{weI+QMCtG8bxH`3x0gv{h=CxS-3ap zJK+=g5z*#rUO6PupWiB-WcDgKK~&AWl?ARnl}Y~GxII@R zFbj`k>favYEW@TX<1uqmOU4 zd@HhxwVzjkma5;-JhDSf06&qMtPz-{ulb{od1dM+KmM@PB5gg8$owr%l-j zPs*pfGK=ZY{r4`=2+YE*PVb#l3-LZjz4)!!FroK~D-##Ku=lPPt zyp7?-TP;j8F@gkrnaR|bl=iPP2M;a8Z@ls1@gsEtvp$Vnz=GnAI@Tjs^`d;@36qba zcfuG!g1#_i>WfhOSEf0?7Ujpvntal1oxm*mqLr!dRMl6lbT4|l0H5)tDIfYa)of0V z_1C-ivf1Sg=IEwtJByl}oXP&Ge$es${Cw_$y!R(>?nz@{1PMAHRc~C|8BCSb(1JX4 zjW<8CUMDb1-ydNsa`LGITks)`=9}|>iDmWtHnYQzyR(luJF;>4GHloRRhME|u>t9< z$4}~vdb}qmZy(%(H+(wJ#0U}x55=&A4(ZH`-ozS4cyvx~)@{N4|4!1z7&>s$KYPK+VGdNlQjaf8oe08 z@_AoyY+bj0Ir%@i19`(9OH7O)vEF+M+tF?h+Z>jc#+a}mC%=)@oFB-ZrV*Hh`-ysz zKhDqpyzj%eIHhWP5Q#4?iOkE`%PRe&%vnuy7U0)~4{y*`Col_-9_keGOCdgMHuXW; z5NCFEjbL#I*S z{8@*a_;-;=9uUp~-YjMf3vHn>Qcf1;=R*CsaV=CMFbnsSVf-b&4`TI>`|#Gwlv}_lRaj!)p^FUtG`}g?XJvY>pz4zo(=Xk z^Wvp`F30!03otQ)#OdQRSkJ739NX&DOvd-!tH{4?_BAnr#D=hGEUHv2D_uuDO$_N| z;jbrE=KaFFH3GACf1b+PCC9S2F4u`z&OQ0iTUGe>mE6S0tTI!W@`fFgw-}CX7%Tie zc;!4*`K+p@HU<*pi(|@Jrkrtx(Ya?6{#)T{+-Ew|2+She98=c0-0kiV5tB&0=X~pv zx7cF7zc7g@Kj7RRci8B2WF6i%nJuS(pE(xILYyW$wpCTH+Wbjkect_=#l);vO(wC7 zF7a##xsY{YTc29|T&D(nMJO{df&_D&$do5}$pf_>wIbBMTj0=d`yKheDkzE=DlV~Yylt5$}~94MsJ(X77ZQE?)-k_yQ3sBl=H&#%kr}+ zJ+-3*iNt%eSw@y9Houg*`dnRP@{bS7@z2G&YXoND5lZLBY=6Egv@q}9eW2N4^>P+@ zx~1(H{m?#{{hc|2)!4q9?ebs1Zv7p>_H{WxV_Z1Xl805v$=BDIX?|F_fgP*U#rDe* z*=rZe?i_5pXSiA|ot2&(!;aMHN5qT0&3TOmdHIao(@l)L3tz|T*NJ4Kb0jeQOEgz) zU30$XUS3{wd!jZ565kH5Wy%{?y+1`9+{Y*Zyr2J8v}`-+AU+9>019!3-vt6 zkGA4J7t6!n7aOAyn1x&2FgE9C&P()m;j0>jYWo9;&^(J-XmmJxeNN4+dFB(qKe`m+ zd5;a%2+YF0N#9FeY{r*e$;+=zOEVo-X50PeuJjD{X4ov&t5|TRZjNCe|4{dd^<0|swso9%qis5YS$OnNonfvY_x;C-4}6$v;TXQ4|iyiD)o;a55Q=7(UoEE^}UeCk7^|RF7HZ3!pdd zO?|oZ-}$&WkY-}U(V4*Z{E2^wtnBA~`R+RT_|2XA7)YoY#p*f7KC3u#baS3QFDI`? zbDi;TVHO?>)CaO;GrseXGw*vkP21;4sHZOVT%~F!^xk=RGoH1JGk>vJCol`oG{abQ zu^1m3!T9}|X(m1?QconNzVKIlk?>iRW^7rDb64u-`TDzOP9z+CYni=oZPe4!yb)`{ z!=~y_shAa8ej{_Qvcqwdyhy0XefrkpUNiHldtP_}Z zK57#ywPLGdj56=4@(w<=_^^aD6C+408@`Es7`e$YMy>aC_|EcGcsSJ=kie|hA0@kT zFx4?ewm%y1nxY&(w>r(l2ojDi4304-C3*1Nol5b2@j8K7)P0|+F2VK={PQ|`^1UNU z@_w`)7@@BIO!e(oo&9lax-y*eq=`S{pd1Uo{}FU~(Ezx$$y>@z>j#0d7L!oNf=({Pi&m{(LTq?!yy zkihO)^v2!O^41UTj-hx&v6ic*urgG9R6T7(oKNfYBS1=N4{> zE-vrWFDDY1g}uqh;NorJv)h!AU#Fy*7{M+c_?PJSe7q-L)ug0cM@I=pkiZTiWXKC@ z$j9+=@;+@VBrvPyuj%Z4@)pOMH}WFy(w!=D_tG>IBS>J^Lc=&br8-aARYO*otP_}p z-D0V}+lBMqp+#gKs@&m`fqPT$K(qRjFHimGEQhR0GckgMbL?+yK%&mI-{PNt~^5pMH+8CFL>`%1nyyz6 zas2iP^{xQNrZ1}c`tf|9ourlS05F1t<5$#S0DD)!k9!B_l?QI>1ZFvYscl~m(VL&M z&H3X(`DC$Olg#HAe_;U?+S$GmP}L5qX9!jCP<1n^X9!h0qr1MGfjoMGvvj)G>>e3wmb&of;kFbj_b zs?fiuJLG@!$oz9=Y5N=rRUe}Yn8<9ak&XP;oKNVQNA@~1MbfzF@l7uk5SEp`irWk zRF{EGdG%7IWDGy=2m z7^8dY5O==5PhIJjVKG%5gX$SV)iP8agDMq5)iNFxoxt7F-i4i1J6@+RVLRCU&9=y`<<5CGP2xx@D|0>QrV*H>ABm%$RpO7{ zTjX}ZO;rb@s+Ul;FjeiM8kSHMuhbg7S)o>Q9Qz~mSs9*}d&xOfx|^!*LX{PvYA>qh zN0k+!>VEYO3}PiFF0`F1hLL4NSw7+^m!3zunixSsRSBt*Csd`-FwXWZ&8toKkrT5u z*9gqgm#W@h<@qO*%PNO`O^hI+DuYz}6ZY!hKeH2S?R9mW7g8#hON8XMes%Dx7jE$8`^If04Wv_XCv@wuS6+EiT301|Tx8W(Sd^gRatF)%4 zMqm~mJ%-_yHwP~h+g9!zHrjkHnzFZhR@si9?DJc(p$|6Mey<{a4QIEyEfrbXuBI`Z zA7|mCXS9(c`AieD#_sCQieKGpyOU8hxNFtYg}n~vTRIP4UbTh1Tza~R5mkeu%9RE;`CHJ{=we}nOZ1?c9Qlg=%*7i91j_gwNv5j7 zQB_E&I-IJ(QDsd`r8*q$f5XV`l$%Gy1jo{p8(f0Ft6`CK=n2wMBN3|hf-WJ?qYGJk>k-HEN9xovyw)((V`hcznFFsF)H(84AzpK(mwdcdzm_23n4{r%#`&_l5Vz8o_c3&3 zz`uoAcwM18OJ6t3x%Odv%dtgfgX29t`p}97n!jy+n@(*)#_q2e_`;x?Ta6<7d?xz1fy=oa(TtEKgtv= zFH(zy@l)B8O^hJ%SIHy$u2=hmWjkJwma6lgRmE?4!}ya@I)PcAQqSzGWchHf=Op0F%u|M+eXmJ|WP zuSO_e?wqDA6%vPu?$h=!R0=-<B!X+1j9FAhdlRye#b>){v7t;?$KmMZs8 zl|&`lRv)(MV<0i|=I(vf9=%|jSFNBiL>X7HyLKp_PyI`9sW1!AG{ac8;FRaT{X_X( zS}N==G^qQhJ)@SqWMOV87MI|0+ovvm$t?9!Xp9lDk35$WkwgSWdY=z!@+J8tJKQYA zf`5t3a;KavFZ+e^=2REO2ojUi%6Pnse#vSrUrb{-Mc20EC1THqn#$K#_fSpWK~zFVrb1;Q)?`-Jl6^vj7$g+#%K^Bz&@ zFW7`ut7(io9j0135RrS5PGHtI&jOy`mON)MHPrmwjt54u)h|Q%dYbY3LYDNrRP;G3 zIBt(6>TDIyim}hwiha^@Zh4~RO2%`?70x;+g2lfG;aBPX2S$)+)BdeOS+_n=O4 z)DMEf*`)2ETpmg`F@nThx3Zpd9{gLxH&>Zk zkB_nu*k2O6Q@*Qs%5v-Z1_#lOo^f1yb+!@MixWFi`Uf{)zl=N`Q z*s&AoS)wbOTyBPg_?(I6UuCIfBe2gh(l?Gpv0guoa}d+nFy3yku&S+#eUGspa>dOn zSlJB)9K?$n<9On;99Fed*y$E~U^^#nX3v(4&am%~CKtx>fBHORionjZ*y%R*#8x)? z_^+OJVqDn~ywIlYrXsN0EOw#Y8MvNJE^)_VC%9i9o~_7p8-X2rk)Bp%ISXxDjM<5Y zU)u5T&;neIfqjIL{xWv~n{mW+5Ub;9hIf@}HUfJUBVA%wBJ0wzkAuiu!;P1rxr60s z4D6tcbjsv#_QYd?gV?t#-RzZTq-_lB%#3}V`_9Y3W?x(7Abva1&;0e>7#o58o00C6 zKf~hlVxxoD-G$~bmx!?u*!>&nN?t832ZFaah`H|TGW`3++6e4Pj`Xuee|c=EPjB^Y z=itC#7i+I`(KZ5m;39pZf=fo0)>|FKqIQR@jrdR-f&F)}v+kp7Z!$*3taT929{+2# z#Pzfh_yri!e^e_k7Vb}T5KVup&L4$XQ!Ny{G(ld_Aqoi3HY@4P)5eT0Gx}`tqf-sS%ik z6;}FEPK%8+_|B-O(4Z($bBZlykVH_LFj&5x_29j`vPg!LYFV3j)0a-1K# zs#M{f%W>P9V+08tn>v44U3n3j<*n8n3CzNo+0-@kX(fJP2jeIA)YE2QBcacGt=hH{ zzcHQhC(lfcz$~0EPMuqRD#(wNZ!6V4$6rhQeZ@1_Fg{VOuWg}Dwxb;*NQ^%0!8(6T zb-c$3>FUA*H@CJO?MPr2p276>*|VJdx=#mLaAyYMW2AuMXD_ND&ezvy``kS~b_1f_k^K#4nv>q5i;&`T1*5Mm-Y~6leTksKy1#R033Cz;3 zC0^w^aL=20Z2JQvNHiM1i1nV<*l~q>kQQUUc;++NFi{O=r-uCTn%X2NrZ#!!- zg2cbs7PEQ5zRdnkIHXV@FTA>#?W{!tv+zn}7)M{X=Fk3LSLYoU#r3uEQEXVF#u7^` z*kUEI0lRarHDX005 zcgOehjDJ7pyED7@Oxb&$d#+b4T8HH>DoE&k$c|3Vv}*4LG=Pmc5*URm7ufYNasd4> zt3JIt*GK0)M?&u;Cu@7rA$xzMSAO)@5g3I|dA3v2y>is?;0Rj&$~@hgpEv%$io@Te zav!>W<;&@e@>K3Tl1_4t(XC@a;@>iZcq8?1(YkKi;aD}A?JOATrXAI`@E35?R;ch3x}NPD>b&c_@TBx1koBDUE+ z+FpzmXCzGH*9X3T;v1{}UGziw^Wwv#c&fg`p@Kxafxj7BretWpZrPIIjU&3IyxJvN%pUKHr)p_@4tuQ~&?t#Eh+$f3HvF*^UYlI8JOf>fIEn z(Q#{*Ac0X%QS~id6Ax%vk~H{l%e?eBTASTPQ9%O7iFKhp9W6DBilu=pOOU{*E%%yO zX8kT}S(2H)*;1#|6rLrhAb}&x-pB?;Nk8AWW(g7)6}z^z<>}LtT9$k+*=U)taWc;m zRFKe*`GIqhQhI0Sb1V&-af_c2QUb9qNW2TP-lXX=9B=j|wzC|^pwe8Hba^VUc zfl*jVVSeg9&*g+PAO1YYc`BU0nzpvF)Wdtd_RipCUry`$wLa)@M}aicj*-OWc$(>=}g$68dhsqe~vktuA>g>b(RBj52xJOI<7(lC>wtMVk-u z%(1SDdM`l*34K508mk`3kGHuiYL*~@Q8QzW(mSUk+?~R@x8}W*XZ`V;lC^9(K?MnY zx9QSjMRHJ?o03IV>j;dp%Niji{CGw4Wz0PoBPWfF=2?QXjyO-LpMm`I*?WU;KKqJbg`+qCRnuz^I@d%Pjl0rfb9x`xnXULnC;Wpn^pF>o=B# zO*6DHU%JaIpYt{;>b(RBjA~zNjb);1jz)y`TPSCh4^z}P8B~zS@F*`O{H$nWp3pW@ z-g_%tQQwx3z$hnqv*qcb;~HU;pD2(0D}-kWDoE5AUQPPf?Tj|&^NxkdN8&?rUT2|6r0lHaSE&$g%_pj7lm#YH8i! ziAJn?dDqfoph@|Ib@}&8DRz*(<)>2oYI5q6U(Ia&sP~wZfk1U9$2OkXFk8Q ztm$u3ikXuG6(q{~MrHSMDU%Y9sg<9-u{Kg}ZeEj8M&xLTJk~u=B)A`wUV|vn3Q@G^v6KL+rE8H`NR^bWh;dp z<3h|&Qa5&1m8hP;sFAFe8bAE8blq32rFysQEG6|ZDGO{;2r63jRjSD9wfOzmdS}1R zQiiihS$AWt?wccF!;aBp!y~DtlUftraWPsVi%m+i6{~avM!id`VR36$pk-p}+m6!G zVw1A;^-6*Y5}BR5bM}H$h0>#wwM0BNo092XS8CnZtdzCZ9|MV{PY-9OI}}Rm!c-r? zp*UMc}DZljKOV9gKl%TpS=Jvm7aWRF zD$%j7?C`qcbUssr)gG)5=_@~LOl>6F^r?zEJBSJrf8BeQ)3xw`cBjrdUdb`J*Hr!n zfCNUZt{-7|?U|_&&r4fLJrm;;^*s?4Bp!AAkTYVxtlg=Pc5C6dtSpw_+mXPi4t{Zl zHuj1}Sd4bkFBPZoHvm+SFeO#66b=7JyHh{t{*z<4R}8nK-UvW5@KOD1L880;86mTWF}Z|LYZ1VVRr7CDp7r`Xv)okkF5L&`o#a ztPy5qo3cVjV3gf$;?TzRzU1Cf%@VhR6OEmRo0XpruOO(j`FPQ>i|>8u=!J$N9-GbS zhs-fL4mB&k=-0qwbA^mS-EgiPhiyf)@e>_-`|%ed{n(r z>v!%pMpCo#^vw!_%A&HPPOUl=O76$&esfkK$1{yVPG)6rwUxSWj>MIqVyBvO3#G0x zwb?Pc46@%tsWAOByYJo!ttQ5on3VbxSLwb7MqNI&*3i`E znf9!mx~$AtCBmdcrLHBYAd!8(uVKNIVyXM#LUxRvuU{Bn1hD7FBRzppsSEoV?yW7B z>U_G#h@8}7E zAwQu+a%iJI2g$4J#w>S}a&(-Yz^EN-n;Tx*lu9Ef9Arf2lgEth*fElr-v^b*#^;=_ z?tLl=t+#x0Rt=k`8qYAIN|OEYGf~@KBrwWr(8lz^tIH(&9xBnb=)E|;{#0HiLmvR% zweva$8EvnmYX1lSyzsYJy{7ePfC>_LKW4`;{wKC|jpI)PBrqziPPnl{)eP-v;A`F@ zhCGbrPXknt!22=l5nukT7*Tl&e;OcxQEgmfjkYH&+S7oX-z2{Ejp0uNRFJ^?F`G1) z_KJD3C-bKP5*Ssr#cX5K0lC`q!}Z6FV$iiH{xm=Z3H@Evsrn0XY!x$q8X$pDdwVQ2 z?tXtsd%x^(e|38Qd5|zteHF`|X)W-b6m<;mizaX9^NMO{H+=k-+!c#Tk z&b{^I%KeG_{~#(z46XOT*gxa2Hs&Kh*nSORvi`s4-8C-d^cM7q3> zMOL!}6(n+|ZWaG~Tkq?8;>}R{>ep?uT75+VqxOfTiq4}7EY`WD6&Hf&l`Yw_I=6%h z5|g&<5v%z$(Z>9j)DXJk;NP-3Yk&ks4SIS&>^$#|#X7e%cuF80eLPE6XAMw6qOW(B zxVmm@ZOl`92h*hTTjUTnYk&ks*)=&VZmLvjvCb_mZZe(@Dm);ob4#coF|z7$vGXK* zZOlz&fppWjO|m+-gak&l^!ry#`R$X%y6aoNAN=Uzp&7C|Yk&$8Z^?DBu}eQ~%aQHDFQfOiIGR?w zGS3oJkhq?;UwmFVO&jww9pmZkUD=YFB}iaYYQIde^0wq0YnIr~nL;Z)sK~Pf6(o8^ zSj4hNv$Zjgy)}h?D$bJB8Av2Bs-&SJu4}M1$C@SmDn!#m2^Dyjpn}Aj(i5U_*aB_L z?T1Cvs4oX3b#4g>jB1qgj~I}@CC8d2&8M5`-mW%0OHe_g!s<)nzb}_*V_xIBnXc}h zA*oq{1V$CCED(nn_vTo$EO%hlA0w* zVASgeW#W?V$8)U2L?NCYUDAZ8eg<^Vp=++_#valAmjulZ_iRu+Em!Y>sNPFZL1L(F zra0x&MT2$BtMp=3hS`mYIs=IWMy;v5U)(=nkzJQ@9ZefFYedw02@)6;nw2A_jb3WB626CVzSqB>8lQ{Z!@DgTK3YCkeq$9zn1 z6y3O>AyKmg35=TA{)AX#?HZ$%__s+E{dvtTQLPE1g2acB1!8EWcLwX2JA90!Co44| zYL*~@Q8P~EiQC6*HCl<3H<7g8@*ARhFF^$f#}#Gb=a05V>zL2089~L<^@y4!NMKa@ zwkP6dlC2T<3xa8tYbS{M#6jO9IwkcU$c|}~Xy)2|M9mUZkQgv{kJxJ818vL$y9d#q zrXDBiy#xu2TJm^{xbl1x(V8VQcTA-IP4*Ji^@0i#W2FqS>C7^1%(vAEq$PWg@+?6D zqpFtMEhfye6RlZNd1w&bK;MWEI|UJ9;O^No?#ukty!|L z-7ZqPG=!>If(jA=iM7R)cWK&~udKa-Y_$uc>b(RBj2d0|k8#ysSsKx2(hf4KdoWe+ zC8!{=XY&u@Ul+2qF=s7%$u9Q(qrR6Qflx{K#E;-=G9;&F03RkH*YBqki_A+~9MOB?eKSCdHh z*a=jG_?!t?d+EKSu=#tY8a5@^T0H>DI~I zS%U;d4G7w4Ayc!pED;~ql(#cNy_cYZ1Xi%wJ`EW?yI z=ZG5eE;}<-?jU%7~!q69);5`sjDq@*v=%mL>N)RF~y15j;y!K?2uJ zvE68cyUMnw!g!V-fl;nq3M>_yKGw2ik3+tkxHFKdPaJezqfcA!z~0m0u-q#zn0s+h zK_a^52TO3oE^W-a9m$h7)(qfTf&@nW^}3BTC}fjHY)w$)V|f#}7Y7w2Di)TP`kqVI z#(YNp1=;bXAI}mbFv{GZvos@cheljnC&`Pa2JkFF1&Ku+t4e>Lm$WgTn0ikBWz9IA zB}ibDUv5w7(YP9hULDF*42mCwvoUnbVdk* zC3&yx>|&iSK?Mn{zO(LokB`Y0yZG`s86+?Y{Ti$@g;%Hj z=4^jHw}b>nq3?vvg*#@*{mTXO`72bAKsN;IbNBkB9G@S+=g5%2DD=+=!jVS@zg*0|E?ddjAv(s z1V%;7YiH?{_*Ofsdvo7Q*BV&o^l=3sx@@p^%X&wbYa>sa9?M4%6(rCzqCk7=^W4)~)A%t>mj?Vt6K^f&}_!*a{xsH_{W^Dcs|Q1V&-)RuGy!YAIL08^y0E zRFFXb3|lvG`K6Q>XPwhW0;8~Y%lx~&Tgca0Rfc=KpjwOs`e)evD)PB>sH$~NA3qDD zuy)JdukJLHKN%wUY%MBCU@oxzaaNQ`BO6)g^pU_Qz4xP=@LZZSGeW7!au*dO^m&!G zWP@~dWu(%dmAQm{3Pax-}Yzr zl5wm`c2s{1B(P4wcD!BUX(?g#LH|5Gfl=sAVjUe0x)_UCm8>aq2%&<6zDm}4bz|`f zF)4%DH^(zM=&;Gqv%mFwAkDha_E;;PT^*^6V&5DUBnG6X7%v-MYgcW%yb`fWQiQUQ zeRCu*N?(-;`qGpX^axi*u(Lu1iNo_Y8W*+vdWDWY8s*pWoLy7Rsryn1i`0SD9L8-HuawuDo9|}f%V0iK7hO*7sj9GNMID!sn|Y> zwZciIXsaI%6(q2F!uH4=Jdj+U9>K3#Brpo=ZGy0DN+g+k)#~d*1qrMIu|2)V4JLUX zP5kbI1V&-qko7`(Zzc~|?yCRjQ9%N$S!zF6;jNFox_J9?d;Ps33vs#M$0X=3iQw_Siq9|H*N!nTEsyNzGFmyz`eh)2 zQU8U;it%$VYed689+2%D+?4Z2QV1&89}GW#OChIg+`w3}z%Id&I1qoc| z#~ebNuabzKKD?@r1V&+1RuDpFl#&Luy!kbV3KF$(vLLM7 zQ$~h2vO3~XK?2uZvb$*JO;SJ1pI?JWU=&u#nakq$=j6!_A6}zJ1qtlD!2F4}w~5Pz z@%$P@0;90nF9`ce>rwGARc0nLH!jPk#d?1Z{hr>a(OWUID+)ggqlV2+77r~yu3aB#4%KOX>95LP?D{|j3Cw)9 zALKI|dLv;7E6(W&j9Py$UhMQRUpvN%4{u1(sS!#rJ1bO>z-yDasY+a_%e^OZ7uFr- z+NHZ+fg1^Zm*#f4{pp_k8p@H}ZwTvd4t&l5 zyMhbCy8n65s_n1I8xHHw3hT9aJT_

      q%`wuJQ^mDo9{`m_411ZgipigjbP~z$kr} z<|%ewG_&<}Ua3X}39NIoo@aLMwBURxuX7@SQTkrR$-j@G38QZEiaRPuV7;F8Z};}3 zg?*m!dMy$dh3k0*VZs(4T7BbfSzY0V3KHl$5QNW3Uer1L1+P0Jfl;`gm;Fo4^rbs8 z?#gP_5)~xSKf&gfqQ}q+r(VhGYCt3~3fJ?pd4?hWbilCtvRb1@1qtkz!p8jUSh{WC z8{Q)Y35>!Oz=CkM*qi!vJSnedR}@|!ZBN}3`+PT;Un`hn?5zG7NA0d=$h(+N9~C5? z9WN1gKB}i(wL@LT)Bepi$pI|ek-#XuJ0WrQ1RBtFiM)%Q6)H#=7Lyz$o+qvFm(%G@X>}&Rs~TAc5`_)-7~p6g_c!2EPW8z$o-HvHu3mrqCZ+ zdGc!z6(q0&5nG$_eKalF`3LW8gak&RFN^K5zB-KB{LoQ8$g&+X(Y*haxMBG&p0Ai= zg7CfttI_9Hkaw<5A*dj+0n*JN77zqv)7jY0yW(AC3MFN-ns``T}eYK0dSB+#A0=9YR+q5fA}Sk(F;5*UT< zB-Wqdd@S9R@Xo0Iuhl8wVbOVJ*j!W`?XuaErHI9D`{&ZzOxs6Gc#K>~Yvu{&Jobh@!gTZ`KL0tt*l z*P9?zxE)DbSD7PTX4#IJ`1j?vVz{NIQO#G(F+q6oDuT}c^^&+_72C5I95hJuY57WA zX35|*+Y4e-I88rWo6KO@js!;Ooi%4ahf+HSM^ebn3Kb-xj=dCHZ9SwNBkXnveb&H- zv}b391V(kVl!)UV*AuPR;6wLdS{yiw3}k183OYIPlUS{2eJ~x8G>1EcP(cEnBW(Af zoJn-yeShvRK?0-DYs6|3GeT(h?SFC)3o1yU1BUIxn;%A}y$Ikw86+?YJyUGYms_Fq ze>U^DV+$1|(8`q=iGw0-vNSW2M(I3kf?JY_9@~|`y-}zjfzB#HSa@SHZJ#!YsMjD87=>OuR#$V5qAk`Z67?EH z1qtku$5!fj#!ySWFy0vt35-Hdp&&f?Bar^HIGMa)*^ZewKqwI%W;W*eia90-q22vy zp6hn9hpqoW1&QOicf|%7!?bMQJIjYIDaj$kHz5+pDRyXpwSs4rva;wtMz>zth8^@Ay@V1V-uiWbHQ7lkK})NK~IC zDoCJ*O%Q54bEVVYzUFryBrr<9cjl}W?)2H~dqnj!pn?SEf*^G3HInZ8@{-?0k-#YZ z?vCdNj-+<0o|9_|d%uERPLa^()ugV&XuW`PR9)|k1V-V`l58bwy*e~2qYs_W_Hfg> zyo>5?l%@NU#IOswJYV&D#kZPgOD|t?rXt%d4HYEL42%^sLN9CC9@nNET{>tOt;D_u z5*UR$+p}FNyFVwk(Icrh`yQwu;a%M<8qHUTgm%GA{z$ok?#d?z4<&&9dfxOccDo9|@R8~v%d&K6c{dlJ-BrpoQ zPO*F9)EpAH!-s~mY{yJI^TjAuKlgy=E9My6UFFp_QaZq&4rJMm3KGvYR~5VYKh?6` z$u^l3&I_dLShgd9QF>=)`DZi9?3iHsCp#-tkjSlPBiimM(~i-`Wh}8N38Cj$zi=cl zYGh)H(Yfwxjo9a5AYrMo{MW^S` zL;|C*dluX4H+USm;~hoS=O8Lbpi7s{;y62yjXNiEk1!G#h266Rp`g`Ra_M0tzoJk< z0$sX-P&}>&Im5i1>OV*%Fbcb834+~SFXA~VoO^^(K>}U6f-p0=8(EiSb$=p(QP@38 zy`ntH+u@nE5>??wM9k9ByOEu|xM-$D?O(Ce@=i&|}f^fC9MS3!Xt$tx6h-Y%`;9yHp2kZAh znswk`T2cPKNdygG-y9Vrnr=H|2`GM{-F+I??IhQl8Ah*4dIF>LKID>tuCgDSN509< z3Kb-j_2`oe=k7-qi_WV>&3cdlf2>A@$?PL zcFaWIcRxv6rWNyi#T*la#!d(1;hE!T49j*@kmzk-e(G+wwQO&<@}&Ikus4lm*^UH8 z>0RD|yRXToXL!)+K`8_kBu>@#l?3OT+A;c)5;^6PE45)~g#<>0G@2_#8qaIQp8l1T zrsu8wMX}>Mt_%3%bhepEx;egzd_>Hz)$KQhq_slO&TRFkK-pUQ5>&ic zwGwQ!cc@@|`^Vh9Ohq7g(5pvn3QdQeiJm%d)mgc9+-)%?)taU#8>N%HM9NHCJuRYG~h4Zc*6MsDjU(zojav9pDycC{~>W z!?9I25<2&|+EV<^`q76-PeSA8<{l{15wYlnTyxlNQAX+`QNp5SqeMN%jqCKcRBk!0 zG6SOE=s^L4qyI80pe7!$ePGQ|>@IH?QNq1P+=PxvUY38`YHr701(KwAw&8~;$$5+a zw$;*<34ce)W4}gja5PBzq_JxkGxV>Ho`?MQ!#3H_yl~gL} z?UKfB$Jm^|rLv2C;0jA6^*JmdGAsGCzwG^ZVA|RPj!|7*P5CWa7oF%pkW?!C`~S9; zk+0K!$bfZ{#xy$fG1%S7VyCO93;z)Kr|{E_Vr87D<;WX1d`?*$R|3WF@VsM6(4u<= zOYs{ahh;-OE~XqS>qQPFka4!StFkj>k5ct7BgmwK+X&-z?xHUI%DG~7fn6P+TK{?O z)@s|7VPw4O`% zl#gX&06qUa$D`Tr&VO4MG9XI#wOIMVo_N3c%b1^c*?m&r^}jWTHH2mN?BuMPt~jU; z{#%a;EBp>NEpREDfw<^bRn$c->)ZC}$JO>X&KVkt=fWo;^mJgIyhYpI*IhNVTQb;quGr;k?o+qzH!8Ry3}QyqR3{vDMFb!&a)0PZvDZ>eB;lS@+7 zGdq{43$OgQRCNX!c{S?)`fq>0@#6Ta1}*4ed=gCRu3@z^o!?`1Tw5H`XCg%*V9?B5e?g~wSExk zQ>DUqnE_F7O+fClcIf4?%5VNb$;i8{DOz5zF=*4~YRTWg;S!O_#WHVGd;luYBs`*U& z(~`sWqilxz-{%g@6u;*D~Mm1h-{%6)oD3ZoBC+_Va;QQiE{KiRm zS!9s0^HL$Qow0A&-ZC4`y6Sjr?|wwdj!%>s5GC1H6W#idbqz+SZiA*#1SOE6ub`r$ z`FowMJcN$jZ&r{DqdkiI{>d@}q9m(tyLyMLPCc!n?IS6)`VeF|g{Vl!UD07Lq2pjs z4eHz_O*vO1NM=A3-20%07wXaGs_qffGDDTA6e zrIG|PBuhWrBY<8n?xK$MX+ZzG+xj0J`nI_$(ywWwza@5ID9>jEU0Sl#$NuRvX@4f6 z;4TAAu!^9y&~~-zrxIz`02#qzXQ7YX=8~nB%?u{zVySlSk@CLBc!>c~a9@JZo+}A- z&TA{?uwoyE637@Qb~31TvWs_0*$lT!FeW~?!dKJwG01=@$@WFVM5($Re5B@d8LvSJ zWavfBkuKQ9c177t?QIi5_r1$f%D*m=7!pddsjWRm&>m@N2J6yi8UhlDu_IeW_sj1^ z8H0q51ug;f%=!SOu3rNV83>{zOTV49FFjPDzv^DqiA%d`$cRi)(fK*9MSf-LV10)M z)OS)^7-<*Xvg2XoMX@ z?{*u|r{5TbnlkiwzM<&qcZ{MTp23_CJ7@?G#L)Ej7C{2lIN@riqR!{PG-a*e! zV4rhXtr|^y;x8P-==D4mnceb1msP)P`>B<91?Q;jHYXz%+h}xQ&YQ} zlcSds*=2M{J-^nNI4_*bJZC*p&$q5FM&kQD1Nh>X$H=31d$gh7KHpwJVk30&_;_wokVGmSk0Dum=Q0%XN!71AgNxSBXDBaAMO(7)oyYT8VFeR5 zx7ATms&x0(e1*+N627?_Ejlojp~0pY)mCuM?wRbh*LGz}<$<{NHglwFREgKGHhn$SDLu!A)@Vh>ZA6}P-yHD^Sx=%|P z^0sCua4WVBSj;Bwaba6FbDWm8h;0~P&H8#U!DxLvjt|V;g6}LbArOUP7BXbnk)eeb z|HJ5#5yu;D>!dcfYpmIh&1ER+O}?33Cvsp`HbX~ixtX=}A*TlIV8eD=sU`75v@RMO z$D?x^kvfK8{PL!&>~54Q7-8$Zxgnq>t^V=6#DJ(yPbRXN<)-0|!;%G~a;`g{@zaG~ z`{ODxAZm8uD7FC46uSGi6+5rbj=bS>Lf4IZgP{a6DxzM@c2f#Qx9^teXkDLMPY$3S zSEoq~h`O@IkDWcR1fy^ZvH#8S31Br=C(^lFZY#AC>!|lyiaAQZWS{==Rl{#2e(yud z+hWzFgY_;^s?dE11@36WUUu$JhP|H3QSwi*viKJq=<`mn-ngJ5wcu&SKNuBF%SWyy zh5rA%6|7yWt+dmlXOQ64lmEkT7VB$jVQ7J1Tdh_RT3evM_E9jDd&jhoeTI>Z-eDZo zej-+uzV1a$zhTs(vKW=~3iWk91Uo}P>(x> z`VZv^I^f3;`cQyYR3b8?+=E0u`E|bG#gVTn9PK7Ia+&+0e8XG&?xeKtE`~Cz6gZFR zC3Kv#PUPbXyRh-!=CQ|>b~1h97S*gn2a=GO!}POK)VQK<1hNsbuuJ5}cJyTthms@) zL_ysM4L=&sPxmXQxs7ofk?idKrUWucsw%9mjf<#9=7Xuc`Jskd z!5bS54PU`fY=4H<+7Xnxn58e6#Plf^M0yf(8kfMAT<*!be`rHaHx=!knF_sFZv26kVt0Su^5 z>`B67c>S;<{QJgaqOZAzp#x`CVrH}#hUm|MbEaE)x&cd-;@6oud62ZdO!jh z@){MK62tS3%)u)>&j6`&!5G|;R(M0h(-B(3XbuiS8&~d*+Zga2&F6onmqx^Fi zntZ|s&1kH6)ZfL@8!h)lp?BOoKZ(DG);6GeEyQ|q(=v!}I$VyXo|!}jFI&jo@AkmC zrVACb$BWpp(G*76bibi2+et@>j8ry&Um1`wTHtPm2oXJ?9(IP1RmvD1nT)#w(f0S!dC*p)O)SSY;4D z?0t{if0IOdEZ@lP$A4GQ+aXF}`<1NnXA}HscJ6=bF+FSqKT_ug**~qJ#DH~zx)HkC zy%&!h@`YSZTSxBtE@b9k8saeyw-nfJP#;2z{`BDw$9*J$gBK7efefe*p;;Ha`OW6G zG}(S3`8Itlb2b}=C)V7j=#3(n&No{0yw>L(4~qWSp}Fz?z3gb0H|q$L zK!)zYOok>7z$mV_U_7;G&)@#3Nh_k|5(A=O3B|nI(3g9*dq{rFE+r8@i`ck`48`gK zmTb7Uj`Ns5E01GMY(<}lg_6g(z93I`{v=QWtv+ZCB1Ddi;fcBf>Mrs~g zA-%P*53={IW$PDd$_lerf-!Vh7|- zb3Qs`n9A2?EXB`X1WBub#E|OY`Lj1)oP3WAtC=UwS8yh3@oOo2KJu|rGR#E0wSg%E zc%OtbWL~eG1WF(S)=%u{3#ane-A3ab3;Ro@l3En3S7OJq%#YhA-XNxDeh@etz6A`MwY4O>S;5v=ZJI zRI<1^e|on9?SICYLJ4Ht*Yph4^Hufd#SR9&3wP(9Z-0`P)_(|;Kn84SVd&WjfWN+9E|PbzzObG^^*QQ?BIH!zUf z_Tr?b{VM_`kO4;wLeH)S@#{_V$(lj8BnCv;?o4C#{z+2&Ycvx&-Zmc0SB0!5HLISH z7!bA2Z!KGKLP%xHMp2X)(Yehb` zol7JMumCs3E@xV08@0eqFBk=fBlx86JqRAROJYFOP49JV$oFVNVdDV7FdsUe&vTtg zq7O|Y(Dwp;GO&cgBRqK&KeBxWNsZnm*`kmE^&xc3<%L$iRcqSkq`Bn3l6+QAM>6CT zq@vEJMX8)FIP&bfwsc(NRf2#7GCo9wvgr6D2A_uq1*3Ad8P_-NKu^qHNpudwm|k6~ z>U%xIXlHNXdmEt^eYl79a|Q_ioH)_=eN`|L9Rhf#P7SE#hYTfs))a=^kEum3-{I$@ zBH8Xvx$3&S4_JBFFgkwd9wi z13pQ3?$X-vC9Dx0@xzFqwoweZ<)|q35r!yP$Lp<*{6p_HRDW=d#DFM$?+Avzr>J_5 zvYKC<)P#HC*3|x37J(ATK%M(Bq%;w2bw)5ue0%WRsPrs2iat2RwLS`3BUa-d2er zp}<%`Xv&R1-f~B6nl|kWcJ7+Q%m%(wcc1z$wH0hbguZtl%!{i1BsY+&I=A% z(xG?EDU?74ob!bj=W%6zX{iJ4J-C|0fGGL>7_rQOJ4~uc=Y^H0Py!k0!)CzJ+C42Y6O58`Xa@GVv+$%%zCRoH`YT)n$Kn-wKiWB09o3LOpi zjp5F{kC7&s)1@ASsMHkU@jh6G>H3Jb4i#mL<#d8Z9?o<04lkI)icXp{+a(_`WXPpT z+A)xS>ivZrJ?}vv1EOG^gx_pX+ zKJ@6)0DiLSBx2I#wT29{nJ#0s8v4wfKon#nbnR9IpR=qlncp@?IyZo41;+mKS$c!= z>|MT@s7KecgLuM96I{Q>AI<5XwG8*nhCVk}QyVoP`bn!<^7=4!;|K@A zSk+@Rzq~^8*|_JTmeqYTLuNPgP+n^S*&TjvU^{xORbw|d6O6e#BDlviBV|%*u?8iO zA?vWW2;R;<-IO?@KD8JJZ|4za?ne} z5rDS{qEc@O#+}Mc-}H%Kq>dfW%`2@Y^PBofXDo1S-`O;U>903pX#ZWoNUJrR*Q>Re zJa^h5*;jBqf4*dv@MW%3(ZmCSF*som?^1M%{3_Z&pae4D`3^#6Zc)5rgEZ2z(1*aX zLzG;q+Et?Y^)GWs>*(!Ln?Tg^pcFRqb!*nIO_^uA{2I(lepIHlc3vc~Md5q}ZB&HL zT6f_`s+Xq+^LG%4f^698BFe(2FAv*VN*)bLBGUT|`bO@Lm?PnQ)3tMC(GwLz21LOb z1EK2UC-QRLw~&O;VG5jaAnJad6sGIt$U=*RA0AzBjNz9bL=o?mPZ(rClsvQUuR0uODr9mn1Clsv*_bOF<~(y??_kw7o5m=mWb@O#~l zVLPip$?FUm@+g^H8qYmVOL6}WRV2SLM8PqJ&`6`{{C2Jz$-S~eVnCGS_eJOTPUD}G z8W8t%BLXFm0pCZ2zK9-lc;!#}u4pYWAWHV{X1|W+^%pcC!>Py!jU-G1+V96uhd zs-|D+YS0r8dlR-BLXFL*@l93(N$jS>2G~9j1;??l+tViT0rAVoP@_8-G9U`R|Dxvo zM)Qr~DyiV0Nb?m$N$(?ie{=v}H2WOUXr{~nvnZUE5SsVhpSzELLnbR1rTGfZ25@JI z(3pq4dC$lLWK{5N0%tXdf;&s$v#b!te|%j)5|uoO0a5aySLv;l z-qij}SZdwYOgF$nytPeR$MCa@7h;z&dM&-~d{%VXf)!OTB?zG2xu-J!j}{DFts@wT z6DIPtS9+78Y11VJM9C{>oBiW>tF-ZC!_x&41ES!%E8-KI#_-fuJz2@g85%4JtViP3 zRV=q+efA04i&AOclldex3-`LeLSjG^EFnThePg(phrhO@TMOx24W6aRCvpEo#qx9C z%r)UFk{A$m>Csx|f3yYLx2epMNt-y5*GjyO zs>sl6TcKmUT@deba3enXv>FecAR;-swN#6A7P1YOo-EFaXYIeARaUC#Qo{e3UdQkI zILQovsuw$zo$P5acz!Rl6Hoh0=8xM=^GO=JT7z*C&;qt46Zt>-YHZxo42c0zuoZ;&<4P?5A|gb(&l{`3hz(dms9VHo zOpWDv8z-=T-j0(P5T!dReBs7-)zGsF@J%2d+=4I7g;SBRTug*oAr(9sB?aDj2DdSN&SQXn%_g zW^&DrZq>J!82}~Mqy9Q`=2xQ*J@uwLl_mc^S8m<=zeZ}OYdg^JOFp#mYZEqa%s$1| zeKod?6ES{2T@*A-oSB1m6L-lj&eBRJ*iyZXBJ~Gk%Z#Rrax}*yt*O^`2MV7HJvuNJ z524O4FKHvbwxz|@YfB6X_0(HL?=3DwshVir&soQ{2XP)WHmEk0{A~~g;{C+Dd#6YX z+}w`(RH{S~M5QQVuH9uo`%dG%?;5heoDiRoH)U~sMuXOBVK%N*H`764KoqPWLYrqz z(SA4aq-M{WNcDgW2ZJfg9r@MgeYt$0qx#&1n)P;Pdc?cA#E?)@f5dFH)P~k_rope> zC~SAgu-)}QMaFd%eZxGVIO05;03#+N)^bga5?6T7NsPP2UH9ZA$Je>GyvFDb z)Oq0p3?=ZnQfX0xb|$<7>Py!hSS~Rjs_V&qEVTYC^+4UvLdOR4=6vsXLa*$uqd*B{ z!1DyL^E%sxC!2fHb53VfD1i*Qt(Ffxs!fXUUG?9i6COLnEZsy&j>`F2{Pn2 z>X(ZJztB@h@yRtrI*9?JM0y|5JEs-u>s=77>pML~4NUf>hi5rT z3jMk|g+;nt@SyL)W07H(t&yAR;Caf4lt?Up*Q2S(86}4z#K!?OR7bvap z0d#Js_?q>jrdO)UrIHw{T~Yfg2K|!Dq8{4{4l=h7lukYENTnGW%)8PIjw&{4%8J{1 zQWVohp4$OKu1DPON?I42Ui5vB>Qs_I2DnKecH0$evgnJxH1<~$nE_Dn=7O+yGb?Fn zcp%-A{)b2sz(BG0RAl98&>b$TxzT(hc6mon%D2>%Zb3*W*y?EW;c{%ziJmk@{~rcG zNj-}qdww%Kof%2jJv>6ti6j-}&oStp+!4J7`T+I~dNppQdLV8pUG{2(#3;&Gq1sN^ zXz0=Du_(KnD{2;DK#{k^Z{x|8)gCKi=qCFaVpsLAL}FO^wY`5}fuV(oIGaR%LlO^e zY#Kp(yb|}kU`b#J!IMNpN}dDDT$e}-K3n6Wm+5MHk1dAt{l!eZ*G)b7Ce2{D^8`!! zP>aYJY+zSMy10%nN1qntqq*S*r*W?^@;qxm=iLnVABx#oit--ip2tpPI?=NosJJIQ zO+}@@3X7J%ml-`KsiYC z&-NGriLSheZ~uJDaI)_+tPiWio;%+&tjc^X7)}>Iu@Q%-)BSTyBpr|~GY7m+QU0`rt|5B7{Fez;MCBQZTbIM3K< zk>UBgr~fI{tsOC1WWNuj^|fG*!f&W(WN!odBUbuVw^h{UOCdV?6{D!_Dzf`rsBid5 z)FWz_jTW&XpLn~K-HHceR}XF|z>$x(Pj1F)h*$&jS>nDLlt6~`eoVM9Kx?$jjV>>3 z&e5v9DjG4tpnoOak1gVULyrvxU7|Q2f~7@|=gidFH|t4%*jMDz4X~w^nXc~^gWjxE zW+U&FgS73AeQ0q~d07YSL8uQ+eUPU0O;hN;3w7nTf+(mDz4$&;Yi?YZzB1@!25eDS zKXmW1tF~}WZCW#-i(D$mfUS-u+WTqGD%;VeO@$8lEQo@m2L*pW#a=}Xr*mdLk;fJ6 z8#u<0zWAcL@ka-`%*l>RqZ%^c%!f`cU!g7XbE99DJIFPM?E`P^p|3A9G{?4&$${Y_ zcLMBNh=QXMP01>!T^%}@Zg>4G?+Z==5&BE|()9K>P%ZhCt}ji(34_ zM1LCbWQ=xT4Q553u)1pbN384CmFY_QsZo`GVD#9Rp>`f>QL*@qOmCIrmiZm1{kbEW zB#8=S=zJSh&&7#rswYEdYy_h$zGQvx>fBG)fo5*rs7cR_>BG>1AXR507?O@nPa5)= zW%e}Zp?IU91TvsLH1+mB+QHjHY07d1M`gG&)S-pC`|V2%_c*tQb!MZ(2dh_t%jR8s zaou`HYdgAO%YF@k=fb|x+eNaXC$m(2^~%CNioNN{&!{iSsB|$W0)~XDIzo*6o~mw0 z8Dm~hRo;a6rR3`z23r@FP%hQ4J5~AD`n_n|NDrw$AWCXORBK-={&`6w+P+woS{K#> zmKLF)84dV#ua2}J&q#yMh5JuwRH8#GF#jB2Ol!ZtAdOu(mZVld7b80Ju}w-zQWDoB z2^irpW(J|it{r)i+hOu#VL1*N5LNUknibtiQgzdXC4xRXbmJD+I9Yb+tp+8K0b_I! zatZ9tTTY!s_V=j5Ap@ea?&;aYse@F%^<`%)c{fY65hAxijeExw*lVyittz!-&NCaT zs8yL|xo^G^Z(pf5t>rmXgA&M)#xzPieN|^R>4yp(Tgt|6MU%?h zW{p2RT`5bGB=B94-obz)@hl-Ak>04*Oxy#n&U7808mxleOO_s-$HZL#tLZHFVmQrS zcu}6I;T#NYU-V0yVU`>pN&9ZUDKj7n?03XXQ!{7Hw=|kAwC}1(RtB(^Wjk?dwNqN= z)M2z&j$UF&C{RCf8!)$#w&_|VO*yz*lk6R6mjHdjr+&AYX5VEZ9hb0BgLXT#4J8{D z&AYpbji^7Je!k*CB>Noh2Y{_D?q+POzyb@$(|Pyy5@<(DJ3ZKLXsFM7X0>n>v%b8Ip(YaV-lrUMG)7EP%rMwlP}ey^9PFj zk{~)3My^U8Xq4T~jSn4TMKi+=OHpAkQW{2VBJ`kokv7t`JB{xDOyqw2_pCtjazY;| zdNV3pn>*K!(vQM30T}=VPXt5+_Kj?9L870C{;W=A$-ll==-(H&ww$SUESb>lP7YL- z{L7I2*O&UY)EH0ymk*^c$L-V5oyH7p{>OlVgf#(jOUMl0lP9%K{oJWnWIAWd0Jn-~YMY?QG7_ zNm~Qz{~Js9xzT_#x3sHU@Rp3s&E$E(!wlV{vpl%dO?r7sKRHl`7d&>-n zl4@?&=N~QY)COYyrng)VsAB-Q$&L=j-_)Epb84xAaV->OB9aS3| z_(GJ*EKH0mM-^p=8{|+2EG^m?(wy%*^@Kz%wv-tVCE22*KR4jjd)U*}?k_Y1C6EEE zS`n9VHHP=W<+OXLgESZw1aHX0SPFzLpNZj~DYf~i#M8Sv~u{yV$%!eC~H6)!{ zt-;tKh=Q>c!hdBvp67dC$5BmoNeqaBQBUH;Wb=3)mzRc5H`uK~31rAo7K>uTcu;s> z(zeD)i2+e^l($=pV1E7BL~`NXXDJFviaY}G;v$=s`2haDTPxCP^Dilq95P_!5JD#o z1n`QxhmdcB#ApZ4f+*Q~jX$H~F9z%-?)R%p_O67A6*pf7{5GUVm96KGf4AX}PVXQQ z1$GhxK@=RJ$l;R-$F(xZ$IOmgn#q#8id&yY4Ep&Z`^D?d4DAr!^QC3GBL9m<+&4U* z{7MiED1q|_oQcpD&s*B?_|ifiJW8IaAw$Z^Q50T@FM7Kj=Ux?lIEaG!V15p<6xHV| z`#F;qfgQM%xdSpbirrnXt3kJ~tgRe-+wfbS8eV&+v&?{~`GV2Icz;oaYJ&0kR%`yQ z%`WVsd2$3LkkMJ(1#+&uUq7~{U`!iq$5Se-BMqLq$!!H&7xoSMR9KhidiE!^&$N>n z5C!$29IXwn|8*=e3~I#@lmLbtdA8lF1rN|yAlK)Lxg9VhlvIzQmBseP;u`)GAo7s` z31sL&q??FzYSx`=`60N{kvbeo;4KK<%VnZJLiVS}l*Qa_UObqG(-%sW6+bm7fed)R zLChr&8gl#W^CWChGm#wzj8{0qK`V&Jv%771_MiS_@P(EfmL0wy(%XfqjP>UuHbfAg znzbbcM8P*0p?+g~@s6$PkT>s5IV?Lw!C68?)=UZINdf!uhiC6K$bcyMHpge1p}gq5YzY{aH zV=S+i*-i6*ZYD7#6v+D`?i?a6pPFgAm19o9@@K$N^649pJWXTF~y!7=SLcxMozWG`o(^F8<> zv+8twh@-@SC>W_AqFB2G^Y`wb$?0E{G$?@#c*hK(V!lTEc{-e)4qYn6Oh|DO&@YZG zle4tfi$>G#!BZu#v&4WNXjE%^qShyF5yh8)1+UuHF#nIPvYd$z8-yx z)#;BD>Bg-S6exiVB%N&=e>G-7#}nz`h;u4rK$PU&LFG2-+0~EkG^L-59M1qUAWGQ< zQ8k}NZ0GORbmk^6i6Nmtq?^d)UGE<2>|jG1PVX#5f5M1QDIOO6+Ivm?xH*xY=%ru; zazDacYB0x|xCdFTvbx!~KV3AUGDVd{4#=zx7}-@4p2j1tMT6I2biSJS4f0N+efEpk zy5m!5v*RgJu1WoZlLouH*?8xSG$mv0F~j}a+c4^QNM!Md)mv&_>EZO^ofA?%ONd&v zVTAg6NjmR}IOW1HuP4pM-6I$#()?vI_e&Y_j z+rEk@)u(eaHOoQKG(UVVh7!m?gKnrEleUP{8J%DpoiR(B7#dCM=4VL^h_b7-O5Hg# z3tMy;A{bn^Si7g1c7aq!c%g7KiKgT^Mu(f2c2VwkTF)(Mst zp^ulVYc3Y?wA1O47>+o|mKn!Sn`$$*$I;_McSsBgCFL;nuI8t8co<7>o)#I8*4UGCelF*R!9tpf+Jttf><+Ma|jtmvqR4iIKm<7RQG*qy@<6qq~ixs zk4)D=nvG9y8n@YqLIy<1??<_@9azNlcxsU-c8XxWf+Gg@tjK^_O|PXbjih5=EhDfb zupV;jlARG+cBi5AM7b*x1EOFFMbyjm(X3XgH}%-lih3q}HcZ$%AKT1oBceBcXtBiW0RA=cKmKfQmK|(HDpzM$V$D4@2 zUfWz-RN0>DvV;!6fGD{K&)06N)x6h$X5_Y$7!W1Z3B}lr(*k${I^Z0oPy!in#E9Gd z?{;a=H;t#=@fr+Q%jSi~>@&^~af8d;;F>5hA+*}9EqEMGwMSzKl)%i~aMnhs$Av7- z_Qo(;iDwchfebnOcb5)(wYd$4Q}aJ-BnCvmnMha}TefK91_aa6O*aXYKnBb^AZE108(|XVELYuEFFEJoWp4;8b z=4<%UL6)j|LKlBBOaoR_lQW98+yFDpuEsA)ai{j z^twCU-K!FXC4s2)Ic=G~*;tHrHxvw7)rdd87(nAvvj}`HEY<0|?#$-(96bBxRZ*(o z}C(3hG0sr%?b;xn)L)K~G>7QkcUM=C%~s*bln#>Nd^ktmVUr?*157 z_KvXa$%L zTV&F?Vafd-d(#I;a|rB%@wYsgZr*%+#4StdQQDJLA0Ca{ncNXQxcGT>zWsY!I(g{> zi2+dyhIVJh$)mAZ&$2ySRyRBTu(h~j@_Zn9d&-}cZkUIyJYyAD61hK)CN$*p$}2SW z$~=hyQBi$^*jraUjvkgHO64}jk*^4BO&hM?LZAdPV8&I1>L~U+b3+TdxImK_5M{SF zf<^m=;6eP6(9yrVE3ceZn_lq0NK&_tV$nr`cukY47^2SBnZdRUYlE$>m%UM^X$Sr? z`8(O*bb&w#%r6V`ry}I;)s+XSFNpQNQ&MJC$bh*U5xV6#kUudwK!!VLQdUQp$r0wf zL+IX#;r#XC)ue9eE&?TxA?LH~U_62!_F6@HqTLb$qF{~#kz0NF7;d#~9C==vPM`!b zU}jA5jgfDWylsbIQn*KEK$M(2LAPr>kFDcF_HI~BBnim4DQDRXyH=j>bRR%Bw0?*` zRdZr-xvNF?_4*z#FMN?nE7l@oIYzAlM4!(aT9xnp6-3?k{J~HH8E_nnjPJ|Mc{!i1 zG}ogWfeeU(Z-K}=nCZmZeQrj}58XrHTLi~39An};0hb%{#_Jl>#;xv442Xgw6rtHy zTJr#ZQ+i?2CjxV3LKGaK;wyYQXKuE{g!(_084v~YXNsNIJuhA~tUR4R_cehM$dE^S zPup(1-abhVXon*lW_T1k`t3nH;mRSRFFh~iDuxU=ro}g3>?ZINya8!5bCono z;K-12H==*a#qjW+X?U(@_(1zW{7WCk|rW8sb1KOnsWsE7&{KEXGUMnv# zAPQQ8BH!zYY^~n%x->u0lRD)#WjU!Im7AAlW7uxS0WQo|BRG9_H&OGHCxu#xl?82N z=S86eGGL2{9N2xYX@2_~QLp?a5(A=StFOcBOIoh0JssA+3562KfGvVh`!PSY!1eC* zsL>w+84v|6PK3PT&TB7McBAL^-<9k{h=O|&5#=3nUpp4kkAAAZNn$`0w46m`f1|hB z***j4_74*Y{Pq!?wV@>|c17DO^1$8Q>GoAA(pQuq16ocZQufbpZC89}y8cVP#DFMh zcZqsjt;OTJwWWg(UnS5IhA7#-YFNvJzuDb_8a@9bF(3-Ix`=2TV#cEr?P#%gWvK@t z<7MZb>`P2%+-yx#F|PJz|I+Mc*wE&08cGa^g5wRLh`PVDk~=n(o^2?NE6B+C+?maq z>VWN{dJ7#Hb027yFU{$M)HV_WqTpK~yw2~>YTcCDP zODakXh=SIDXsc*ze(^?q8oRYTg%ZesBSxIjFLdB5;vHz?1y>{s8KR(tBQi(&*5u!7 zD)dN@L9)Uj3cf2ME*x8OV=EmsIloe3K$L7>iLXHMt7E#-OCl#Slt2c2gT?n!jXsMA znZdN&M2vKmx5I0#@-O(~vhtZmg3S|cPrkdmfLa+2kwSM0s=szasFqBBo1!p1R z1ZxP_Qp%5_y*CV$JVlTp&v5ncF4k^;ZACXsZ9$(B&%v~e~ zL_rT5LLL?#+U1RIG;&5Oi2+fv_anaXb9VE70R3^mM)H?PD9OKj;DWhUvU?zHnEaDK z4~yjAmA+9oJFcbbHdWk@GCeAttHE0|@lzqpajsMsAhe4HTSGQhW;;7vw&!x2SM zb8Y;c6(p?oL@s^938LVwJ=AUEP;JtACsJHLT4q2Lycvi}@6OTYB=;x7pG3(Fh=N~< zLhJU;(@cvxl8_k_Xw@H#AgWWi91jN> zFiICKT)JHgkF7-eZTFYscOe5t&7zi$+q6n|N7A8hQ>B|0FydQ|11N|(rUl0jqlwk$ zNO7+a1)~VW8rAx$mQF;JMH6=nV;EpG1iW=4b`yQFwIS(|v_cdmk_5z0ND&ukdCF%k zJZ&(&7XCrH83s{u)Jx5k^?3y?fR0Dh@R`_%sAK+k5Z&z$7ZT5*m@Y zwZxqtkO2{*V0;lmwJuNNxFk(E|FVn3fG9afV{wwm8x3xL98eW5D z)cZ!D1TtU_bm8$@@>c75(~>&Zbdqd1nE4CZS|UC%VVBmgmOb5d$eBV3WXL(TY=4(% zZRc3i-lt^-M9H@3#})BfmGX`0&JEGCx?hOz^})1O!F7CpyboTt zZ7D{sH+_0saKzDt!e3^)&|Mc+AJ5q)e)sSbKC+a7lSt(Qlc+Mf1JRv2tf)OQg{3Vd z5tEf*8xd<#;-QF>apm85hGQez(1&|2kmk?C?SbDDFydI%&lT|#_s3ycd0~j&7Mj zzfk-}rlW2ucfZ6@$7?p?e$2VH`V&(Pp%-ssG;x%XYfd2Ow>D5R01zgm`Q-)t}Hk>;bndk9}M|K;<-F4gB|)M4@W;o^($ zV;qBN;g{(|7ZxCH>jbL$RS$7`m$n!MnyN*cZ{hpb-7xytL@in^?xLgG!xxk4yMpP1 zC*q!0qBw7|O*QD-UXbbm+2TG<&lvLEwH@8O)taLHHsTrez0trU7`>^F(fwE-G`tW; z&OWK+4DX`cU9wBaH+#;+t=wE`c?*%dZIxa@&PYL<3-R?PyOam(?^$Oq0RUlMU%t& zk#-&DY7m94%)?nGx!v!JyHy(cTrM`7eItTO9; zc-{A5I43f}!2ayTuLB0-h0V&V=eHDzQkCy+MbG+Gq{}zfrwtZO#y7(*D@$JwDf^x* zF8iLWz4)H2*u&xf`Od63E9&DaqJt{X#8%%)lhQf3Xy`+we3&N=Qd01Qh9N zYWQEDzIWPmdZK@CAza`i2;ZN4!zwCGmb7 z9odEc+F?U0+s0y@`EsnZ_Yq~?wD02788}~@l8Cn1C(e*?-~au>>h5QW)aF7vb@H^6 z>h<5Ehq|85PaoBr6fe!iR%e>15ASs+aU*kadgiXYBHBr`mG{;}8a4L0+B)8iK?!73 zJe-4V-JI3*8fA=TUE*o$>DSdQ6>Dmc0Z}4HC;s<~x1ru~^ylmxuV}m05(A>1x8E)z z!XgW7V?BkAeQhG>^yx#Cd08cz@ujsQULwWKGun}qeid=1{zoCIE%GQ_7w?LHYJu*Q zxOZ1icm?%Z0qR>>=vcfapRmQV$fe(5;x0gC@h#`1LVY9gJ%*qX1r@z0&<_@|s*sJ6 z=FY*@Yj+}k3&nTC*L4wn>RF)g_g=icd)&~@1BJykL{2#P4OkS}p&1^vEs@s9{-fw_ zAMvSJCl~9B%PGaJDkyU!%HFx(E-)TaobblfAXm-e>HDE0#do&?9RYc8)-F4h8BP~Ye?ca+XfBOJ@m)Gx_I<{y;`@vZ+&1CE zb`=G??8}R)e;7R@zIT`XZ3~7H$Piz$!~cFym`@o;(U`qt?X4>k1EPAlXX1|^&MBq3 zJn=n9Z*>x_;<}dXNNbFtK5PT@Q9|aX0u2Oq+*DIY*nm0p}Dga zbo;Q-vD`eKhSV=dt{>fwp~S*02RntH@^P&1p!6D*i}9CIA5`S!CURzOjH3yx5n1aj z79sE~h=RHi>i8moc1U@zR6M*_nhj2S?ZQQmu6c@_4<1mT_-fCm1iJdh0Bqc91%?vH zfck_L-adxb{<9GOnU+ZE?c0FQRB5ZWy5Nty>DS|empST(i-RznmBc+SzgTKM@iD%y z8%%clEf#rKt1&cRtN_lb7^%(0H=Pb(l(Rx)2r4hW+adl(PZlT8k7ph5x44to@%?

      43UL6q46e8t&<&Ez7sl z&`8mGf&InTLF|a@yk)rMqOq(;2RriHG!>6Y3SsYB*AlbO;mql@xbO+vQdC=m63BqM z#o3+ZRO)!rQENM>iKGMNtr51*0ESH4O8P{GjWf~o)zW_28VkVyC|E*qrv?A}1>%P{ zV_KR4$x=Rd*N{?ENi=3@6@*X4@hc9_i=QlMeuYH&l>1N@R3&hDw@kZtRh>7da&t5lKJM1#DJ)m z*(o^pWKX4L>QM21oEN8KpT#$F{Y7k4mRllDF!fM|?VpJu3bMud#~4cQd4DJ2jh>Q@ zv*Ym9G&5}E(-uRNTo3Q=&U9ju3H84HNn$`0Yz1M3+YP5{z3vgCK{itB!WM-qgBT?Z z!sw|9m&vRxjs!{|<4U8AnAR?jbEDde{`dWKnY~XItEsqOsCD6Mb=MkNT38VU}+Ir_F)(`+jEroo6I7x?69q}zOKg| zEUzh_2IY%V?Y=si{YQ60J1N_$b;cWPJqPjMK=X_VWppKn83#apLYW zh|Xy6f4F+~6%k z&z{BZ?#6D#Zut$L=lSaF`#)aHb=|vXV>V`X<|1vpWdX$!+#maV=c}LU5_RI^hfv0+ zX~FDd><9X@&q|6Vn1MABL^pohjg?vcg7$c~Kw@ANSoPKa%U=y|s^_+49ebBxnGaSM zTJ`@*Fazr`$QtV1jM?=B&w;A@B@Kt?IsPT^%kb#SJUW}`)BMd+t-h#>)%PVfqy*WzWX9EXjUFSQc8z{+{UYNe`@K>i^|~g>0Ly z4lF6ijP;APD71O~m0$+ee6Ryh+}ZspW!bEPPZVo1%$6Au7M`rgypQxqS}BG#Cr07& zz)R2Q$(DV4PeV4z42;4W9Cntq99gC0U-U|+%93u!jG}2#>bGG7mCwZs?VQ;wELnkd zS=PwbhG7Y2$R}arql%0^E5l-b$_$LUcdxU`OBxh$Wf7EdxJD0VRUwCVjXXzyynZZxdQ^d~h6v+DkpV21o1lhVD})Wbzt{OxarH;@o__5aJatF1JupZmAa+&*nr zjZIS3JJpsP@C}*^-!bBQV^*U^1=i@uWjZSdR()frW~_TcHEvE&jqt+C`1XW~Z!8E| zGgf7_T9#!ed!CZ+GB5*|2V*z83A^ZBgx$(~CowPz*OrjA^BS;U+s&EJlHU}6Ij)J! zcweD5JNBy-Q#}8dv-odYVU#=)H-<8HD)J$9G5w}kf*EpKwf9xnmH|)bM{jvwf>Cmx zH?7=;efW8b-s$^-Nxy`&QBx;M&a=Wp5#SC*ykph zG^+hYX(VFCy{LJru|#Ln+lA3kM%2uHta+IQbZndB5(A^a(^37GPgq~nkDV}IPU~FC zl^7U>=M5ouZ?6E%>B?d;} zc7qfB_i$EX)M#2WeJ{mzpU`rly4T8A+vFOr;u;dN?`9;MJ$WEyleQK5a{m27%)o0f zctFe;${Ye0(dlnSQ(6S-doo`$ZaAT4z>bxiuEI&y1vS_mPL{SWG*hVq(7MmQ3}wBe zCerS`GN^gC>FTvDi?oMpS4*h3FEi9{Bd%%fJHj0k$*CO1F1u&Y{;zjQ42;4xgy*BL zN3jYEEU5eJDHKaE13UrMfBBt{6^~(k;u}(P%ViP+qwpyl;#pQ3%`Vrws*ZUzMLM5j zhJ4yi9+1Gu{zNtHM6|@fDCu-hc7@ro@1Gr5kjqm^GvK>Wtd-ynz^V-Eyv4wZ1cB#d z1Gpi`9?M&v}K>~D{OI#DH4O|Au72( zQ8OHQs2W=jS4qweEwAqzV3f*mW(Pdn*!tcX)L0C3;_?|9S#nLqvGtaf3)9?g@!T>2)|ZV;{y z*4oqIjhLH99>pz+8MtpC`u8GRb_1gCAN_MzVo0b1;1jiDu*o>HaDFW5-Gx=>cj%CV zd!%`e*AJ{E;AR`LY~&WRV18~sQh!J--7^VpEY4}h@P|-FraP?8w=1#-c9ztLB$yGi zH(51|%hU3%754e=gMHZVu-EkE_+}DAISB7o&Ry5Yv+L@!1Bq(uW!tqKtZ-b#2X$ej z-EV68kV~SzIIm(A5{>}4)@qcQ#Xv1bjgMOsjA`h3(dH{6vfsoxU;+v!aS$s)2%%X6pubU zyF89gR5u0u(eCbe3SVw+K8Q6+f~eW?+f*#U4Ef9VWc6dp@^5s*q|y=tqhjYwP@9kX zsV&Nen1|%olQ6cp<1Om7^)AN}+`962RJ4j_S&uTQ%?DrE+J|g+l1-14EEvgnMj)Mh zbc|%}!xp}*Pcv1E7S(uGcwx@TpXCO!_;yF=fL9ZBTsm%D%m$Cf<1y^~j4kvc!~?iB zda`P7Q;i2T_$0Lg{ystm?;6UgmN`V%dD(Kzz^H_7X=+Tn3f!=&0NUy_@6O(@F2+7p zbI@^3@LD3T9~m(!tKja;oSr7{%bM9+4fUC#c)jS{w?+CU^RZ;BCSOEBGkTHggQ%^q22gW7^AUImDVgUq8!`gv`AuLl*K(b z$#mST^>|%qKhH1SmEB4GPVWw%EHN-DIbo6-O0Ph?@WNPOu{J$en_Lt1a5Jym!|Du;8~_VHd6^c> zY_?pd?Jpdb7#M}ihI3SAdv+vcHf>VcOkfFS^kzXdV6f3a%#uW_K{qN1EWwPt&v0@q=dh1VFN_to@@y~mR)o^*yZJh9QT$Ev zcTB$2iIq<4MFVP<5}1Ke_BUs#q-;MecT-`uX7A2@+0B;a>9eyR9ircmp46{LOpje3(+V~+|v_tisb4-cLL6-TkyqqFG%_mULv?lGgP`&89_gfq`g zdJQvbf1`Nz{Awzl`)h`V=U~jfDe9tfjy$(+5h^o=v>n4{^a-cqElR6cg3G|a1aT&u z`?4o9e$&-8YO7ceVhxAqJe&=h4QEF}chZLq@+F;!HIb|tIz5d6pVzhYpnir+5~LF) z&j^wVnQrFIaiWh_w9rEbg9R(V4KkjTrWhsrOpGm+#NMtnr*~X$@n^%Pt4Ze!{KL!Q z6t~r>qBB)XyO#Wsbp`12Hv_>&fAXDL?ZzjLC76NB20xweW7&k3yA`)Bt#w?w;oV%w zi`ASHpPE!=oU%@2#)^Z~r4Om}9hia3hPO)-6WE7hgJ_S;y&Qin{#{%{@R=Atnq9m( zkw!RvkQf*xwK};mY&0voWHudIw6zIKFhd?CH$sQAoqR9tbbX?KIXK2IfLDCKYGw_}fY{Y>nEVFw(b@hvJQlDeHBc28D znxlCV%1x=P17=_R3gbafCK|iavr$MDMD3)M` zbn+&P2aaL0-z`^1+x0Ab+xPdZj~V#n4cXGVCo{L;aCLRZQyjM_o{!j$3o#&8B{AO> z5BQrpA0&o^Le^!tq3;;awinIdz0M>T=66=N{r@?yA#Sbuf0?H7+yvXins}D6xjy$T z4LQA$pA}}{`AEpaOT*cE&n)%HkKOu)fH|tgj6Cf^V{4kb8t!se{nm2t*ZzM&<>I>wrItdC3UN5qS6Pi)5QCMJZV)E=XQT_&em4v$Jy&OSrL~|8%t0v27dI3j0aHjn|9>_SJeM z-#hPrd8+^VSz!jQEu83|#IyC0EqIm7V+-?C|7Bp5>>IVvWfVJp@1s_+)e0R;FhlrPu4{0I$no-%Rzc|s1 z&1O~Egnc$lx`{8_7NQ&7^e6AvsrddHGAYk5&3+}=Gi8W{bf-@c1A7HRrtvkkSwL1r z7Mxu|Vqg@$7Y9G&{tzo;WhJHruaNE;@J*V0f}GlAFiUmT=vnXn6yFr!6+qVQA7JHl z0Pnk3CqJ364##U0)+>ZG`#z2pjdSs9JfBG3A{ZsFwGk|dxu5x|?Y`7dVn`_DsRC_v zVl4X>vzwc&nn?a7m?7(uCDRj_P3Bi_*wa~JU=;Qu0l%g2cy^~>ZM{;>j*@=~X5je` z?}~=TG52P9eEZpP(yYbv18WJmlUXo=t&K8j2Iq|u1EcT^hPSVd!fqQa(uoD1Qt zM+sh02}x}}h}qvsQ(4C+5(A^~8IF+AqkR>3O9$o<+=7vB?%=ZxIpGsCAzsugFH(vt zWY>!S_-s!%Gb&eY99UYj|1gkex8(6n&i9B=<2w1Ug?65dY{`c*s6T}Lll{Vxzc?Y^ zcUsaV)P>Zi zyy}{O=jr-gS-$?PuLvNCzDx@M{)>{5@ZyF>Ney2hD9^XMf9SUV5k8Y&+1qXiFA-{qs^I|h)DS_-nU+6*f zZUT=O`8%F;*+94KZ^wd`5=I17$t*LCRJ@`}4D?H2!76r`?yuRCsq-OYI%44R*LQAdfa=G(1w17i>G0f#5OCc6}{AoeJpAZuWSBE zFhhP_V~W40wD)slpJoLxNe|+;IY`@qjed-!|L87m?0mW(lU}%BhNR)Py7p3vpY&sA zOS(yKW$^nSxmMTzSSY88C@fZUkr)!H%VvdKDDH3UQE0(BmQqP=*{wYrwgmJQl3)gI z1=v$}n&ZDOuq(@+SzcmDs82f;VyI^#aaW;?k?VEUa$#52*s83=AQ)u{@w@EX9Wa)L zz9Gxn%vO*8=*dXY5{zI8W)yv?keIe6W6#1e9v;@z_)1Z%af74O7+pk#M?fZH=zUcx z!`h^f!ShUp+3+@t+!}FH-90yfWpsrX>sT@l{OeqfnR2&1QKerZZX4rGT|c&DW;JRt z+&=gX79KsY*0wj9g5Z|E;knY%xFYtWv*AIhi5$HG_U?Zpln{5<@BaHNhA}hmgW%JQ zB$#oejzT7Y1Q;2r{fMIyPDzWhk6;h#kUv;Wdmc8xQO-OH7aCxM$H#yPRl;u@u;SH)+ zn>H_ZMeP}yD8GDJ262hU6&x^p`=Cl?lM`1as=<++X!Uacc`Ji!DAg)-;Suf1(irwI zYMb1;9wU_8>hn$caS#5}gNsW>syd5dM+XA~wfmcHK%}*#q6Zg7xz;ORFL={A>Kt`0RPLsTC7#-LW7)VlTu|k3)OvZ5N z8{7)S)vi39=v0x#KJF;@AZAE?Q!=rKI;CYB7PQPpz!~XZPhpfaN_J)|)GW3p8&#o& zAozE24e>XT-l22Vl%I*rr=X55jlQ+851q5vl$ZKW&C8vxw62?FIx_tkjFQP$M$-nT zTeI%NECpF`ULm&QO@^HxA^-Ugg_N0Q$_@IelHuU9k#owF=l=;9z3jTGK?C4jL#6&w z8TfaN&0qW1{4(2QwzkkR+V9sRC4EX93vivH<2RgmPRNW6%L3HiUSrvN+s?Wq!R>=* z7df-$vO2KeKsHBxBGpQoQMe6Bt*NzXbhpl|V09TGwG~F8c7r&OUJ~ieHoAz>B zVTRNnt)I=O$JEN~_sIa6fl;CF6f(%kMDBirw)(tdK0OkAgO<$dEeMui27dWQ>RC0S zmv0SW*C*_S>=FO8zNDR{_q7XbiqQ*`d$T^(3M7W~3Ky>{p|ZY)!oliyO8ru4GMBmXC1WBUVDMQy5gc5KbFvpKMSqlmruN=AN@Kp>mS=ChJ?y# z4h(q1d!o>%Xt(oAYRDYO=$CX2myT;Cl}83yY@h{u!r8|Avvf(~TSpBYVWt^<)z~RXE0+oL zZf}74ty?=S>G)eXT?E7gK+`j|k=v#BvdO;BD`Or?s68ufL4Z%<5Nmb_D+lMW% zIIQPxZmVXEZKY++{i8}KsjWuLD9M~*PrcuLg(B4#)k>-@S!`*;ejlLh!KX=5t#El3 zt9q(r$xzKAw$Nj1^CfTAs+k?j-nc=>5^Q(IwsbRe=CM5YNL`mOKhgF^VSz<^iX2RH{xAAWFf6XAq6xyPCJ&T(zJ4)I{9h|7RV1cWsLLs!Iy<4!ow|wU1<8 zRgBKCzjk?}8r$wt>>F(~8NL)o5cm-6L_4ocWJzvoxg(%EN+ zGrOTBIM%xuWn5{aTHGt41$BkKAqf)~soA~}Y+SV~@~VdRhSHiyW-Skti@Low)qVF$#Vswjm0M~KO`P3_J#Cn+6SM+IC^UM&->2w$y0m=}wjraPyq-6& z02Y(FCUWq%O2Xmq-1#O_yKq&z6}E%U?ooq9`S{8VjKaG!@;>`CeG>bVmhTU{SNyxL z>#Ag44U_RP=vvGsp1tS#uLj%m#k#K2z8y!^kj69_^5Q*xV^~MKoC?Ptl{C;p;2U+Y2q5>#Kz zuv66BzCTPPzi^F8>iL{j+2+TBYr^RcOYo|{+zBFjTrnAo6?&e<54%FAH}YqTmch;v zOE5zkCApJ2(_YQSvfY7>(&)pZ5|4aBF6MNj*qu4NI zJS9ki8S?xnVQbAMzAMU-e_9KvMLi%s_}U5@*;n>Iv0hH@uEqY;Ezd5dmX#SeA`H^` z;JvfUjNO~lfE{dJQf6QjZgpZ;yeL~1;=~-)@^XJ*25xE6`^!SQ=iNxwsq-z4XDZeo zxTOghn%$X(8^$uvQuS0U!3^AP;QKLaAUzrv%jU+nk#1Np3Tr#K_vt*4Ha;H4EJ_@f z7!pd_x365~!j|r-zygnc(D90lS86E^582bJKATlrC#k&F0Z`lcTT8}W+=)qkb??nh^;FCVtUMY}4CFw-3DSPOEK?*y$333)=iNwI`#~hch z)V#YRtI)Bk%)o02?i(`o;1hbUzXNMj2QsE(31&z==rgDx-Y|ad}Td84CS%E!vBz=zipIqMAoaMSj(SUp_ znSoGp880diq|Z~GSS7VF!&Y5vC6z3(r23c5lpkrr+L)>{NrIw_;b>-X9(;L}hJ)2| zTK5VJ+tn~zvf~kt+>^9In|5r`m=}`GOG05A8>#=gA`4vEl8JE0Ac-XSw2kdwgxs9g zkX5-sh zC>$k^B=v+U#bHo;0=I%*ud{ih6! zWcM8-eYZiBp_&lCz_^33Eh@P^Suu9L>>sfNEdBP=;s3vfTv1jTd$O%J%@|m~JdAPR zcW3<;B#?6^93snIEe|hRbNwd;FIVS{G6PNb;Z;|4^N~L6e&0XzQ;);`KlZOyt!qC6 z#y_^qxRzT*-Bu)uy>UMUkptbljcwpv=*PVhL;j^fFXySHt`B3Iv-e93jG7);SAh)C zYMvM9Gvf00u`)O*fz4PN3t#^4YjJt!sVRo%L599!R}7?mae7;+iPiI?i+;3QV1=pPj`BowM4ct;0sr>7Q0vzz(`wM9-T zHK*xHIDO6b8S&_Xl3#y4#L%ndBSn-XNfV4Tv|c6 z|9|-zA#Sx&m?`$f|1!l+T@2^Tc0F0gr$r?OMnU#U)%H!W^xr{cf-Le{m*&YAZ1mbKfh4~q)L4HPD9z-^p(4WSS z>&o1w6e-M|`L}e8f=q47zigY^_0jb1(td3B;~RzfIsY;+YR1udN{^qb)MHLZp;pgY z%%ar}_hWOGouXKR87FRERo?n%s?8Ul1V%mAg>-+(aMsO#oy5Q>sTD}w?whHxXc%+b zvam4U-QV`X42YDjxTj>Q>9H%I43e>f4secSUpqxe3<)K*?(OFrl-*tGvSt07G2+$0 zht!y%k{XRblkLhTr6S>FbT9S#z}Nm?`p2n#GdsZlf2BsMG1k=~=VUu3Oa3t+E~|1T z!&@D&Cm9%jtV^ifqpPyg-#QfLgG7>l49PQsjHuC^ez&z{C0jIO5VKwRzxDJ}gOHa{`IoJE;wYxP@NoiPf}e|TBE*qqjh z4rklDT$UIZg;zN6dO4xcNHLgYe?LsI1T(P4fLvRat!NMD;p|qu6%qrZr1g=+l!>L; zHp5xJfEQKulBjv&NM`6BEHN+&uS5`gr@|I`8sbwe{k}|Ead6+@)sB#M zX7^~r?qO`quw&9Xh#7JuPm6wcY27Jd%zpJ@Rg$3om;1b?=Q95#eVVdHhyRxy`0r|f z`(M^$5euT!&U5|Pt4*%b`hii9pVj|wW@1v@a9SM;xqhEPu3tQsFba=+c#-Q`f?k7s z!h0c~FqU8jWRg(+FV8UC`&4aAuR^|wVG~>>21Y@y3*}!%&nug|(a%xM*vcU_B?d;} z*#$A^9GBAymD{r*R;)13=->4Yqaah0^0>=9HNW*YSU*+_-$a`vcVk`??^4XbD7^X* z;y+xc=XZ8xc8||fEWr$yxH78OviWL{G>A+~v^B?QR%CBha@tmjfl+wQLkzkS;E9^m zlf@ORD9jrAcfG?5$Z(_%=s91tpS2pwIQIS?-Pf@Xn>pPmF)&IVSIbM)WTJChRxdMI zEf^WD9?&Kht|}fl3T;;Vo@(;G$q-fd4#Z-;pIDVy-fho5oy%6S1T%2tafn+RSCTb3 z9?X_n2GiVLP1K+{u+~1EqhOR=E8B?$)NNN6_SrQ_Vqg^hCWyy;aWyUN)|&NvUy2zE zekq2D@Fw_xm5TcV_do3VK4s97%^6D@QbS^36dq#`A8uMlx(%|cY=`VBcy-1oJdPn& zaXA3mLe3XErq;b(mzfW5Dy@T`Cis4*6E1o(m-oe)v9XV8>^VdwYwY1{6QGhqabR03uHxE4tjY3$tlz21 z>}g{^ievQQ7^e5;r>bsCd#ev?Izt(?XSHAlpH*emLSrQcM#&NW77g@bwkB)#wwOtZ z@CW$^RdIlo-Qan?LNE+qJzTB~A1-`jbWIW6mycYZmS4OHYyW~Nw>L=Q=&8zCN zDNi3s3<-r=0Xzp%sxC%!r*-U;WSoVj_RM42-H;N!D>+|ZUBlzTZzK7BNGRmP1o>-+ z{GhS%ec6k?izNp3zrubw@V4)C0iAffH#@ZJwTk^qFbey75i;MgIn~#6WcS9DXVU8m z{Ek6-EAvzxLr(S?7xO9BI2eUz8pMG3 zREM?Qu)ku~?B+x_w!6_ei6NoTyn(lU zi!ag4t+my;uff`Vvu9X>8F(x}9<0Vs=+C;9 z*!!Mt5(A@f&w|}~&v?4sV9n~hH!!R@@!ZC}3DLz8chjhuHCW{~jT!D+35E0uyet+Q zY0zgo7WmmqVqndH-*AJcQ|vjqpm#&olG`y!f__(eS4e(#K1W@jIKM}vd zlC4V*hy#24%)nBT>QOAgo}ls@tdlzw=Jc>3>ozBoV+poR;djY!=4=qio~^FLYL06u zMS;Q$*@87?R&O@1_j0-}=#q|KEaUi2@=Ml@H^P{ecPPzTd{|;&6n+N_p3A<8Oet4d zZ#S^KF1=VraUbyOT*&jYEs_0bWUuG@9^#mRQ8*_7>@25LG8wcK#=kX@vp%70P}qM0 zJZo%SX&t9tEVI{dUGjRse)`zAfv{Ec>E4*iEOrO@>0=)TjKbddWa`QT^uwJwbo%K5 zvd=tdBaFDJX94s?1O0u6f+FOmq)t^I;T`7qdmC5D7THfYFc0lo~a zJi^(C<|8BzA<3^(^5t9rdxdrog(lm*hl)L@Fa!IM!cExpLDXw#4|X*68*{a>pPAtL3Qexm2 zx%gcnA=B37s*6fAXEPqwmR|$n-<94$>Y?-0jyr3y154!BY|fy$>PSzBI)tJ(N+^^84s2ct zA*`oY5$1U`mgAU-IIbFw$_6{Kx4qaFtr*+aZ=A%yC^;&y>vbPi<*f~4EjLP$JaOa} zDY7oPy2qTwZ*gLN-{I{N+8baLjub;6;a(+n$Y{^f-@|KJ#E?)Z8Vy(hR)3<6#@e!H z8FupC2ce|sH)PY=vvdxx%F;4CB?d;xdpOgtZ}jrTDy)OGqqGah3{}c^XIlT9E-G%x z92>Yv42;4%PC`2DF3GZwlxNlh>qt9G%)r?g2&plp0$aPjBD-3ohQz=qY3EGVjjPBS z)Tzi0t+SGL$e4jMFc9)(E9|d2Td~M*MI{DCNjFF&{akalb0lGJil3%9j|I;3C+D=V zso9NP`gNJs%ZEtmC~pR4;LHVZ%h|Rad%5`uJzxHu#K0(=;qdnuv{39uv%vBlbGy#j?&JU(`W= zCQG?eaExD^rv-dDH^#AY?+&Qd&Kji*E|?+bB|G~mS&ZGii!U^qw5#XOXwz#~@vn5< zL2I6MOlyAgyvgpGgSP11N$uD64AX^2j@b}<=WLW%aOs$yWc66v60%b}d#0UM1{h|a z_iHDQx@lx;;%>}_u`6Q5@zeA58O~V>mSBclMvGbPgw^BfqK$=%mVR!Qc6!TfZN^mx zt?RLcTAf={H1fs98SYQ2mkmww}M8POr zp2stDt(#}A7J8yOw65`Zx;|k=oY;6$Xjp<7ZyfARe-h4U-cVaYp060KpP!T<0#Y`b zFax6&Rqt(@QT4QzyWe&dhqU!R>yw%{-{^>Q2YtisqgIulrN2i?8vMjv4 zFdIDRa=vLkw^Ky5A`uFfV1`^qi$(otuOnl`?Cl#AjKbwTIBBL-*>X^`xKk6pyh;1Z zbd7bSsOhX}Sb`bt10s|OsT;Lc|NHXg5AV~6CgI|6&KeVDU{ukd-b#wyR;|?Q`taok z%X+ffnveK(r7~Yze!Vh)Mr%#sw|0D+qr8cqsTnVq@xpA_$uzZN`@&j_8E<10EWr%9 zjMLu(nQ2)Kk$!81f>F4lx)If8zHB z=C-Np8Rg7Xdy`RZ<%QYcjqqa(D@8-}IkB+{mSBclMw!eMW)>NsUYqq$!6;l_cK?%# z(Q1RgF*d~uV)nO4V3Skg=x1j;jwP5e`JqYa+0#+^2(^VcMJuCO-IKd%<3)QEEa^~m zkK(Y&0NHdu@4~+XxdDF!vvyxB*v9GYv=Y|yluwZv%1ZdHm)=Vis|S;mtU67zF&pAc zBz0kvA%n}Y^{XTXM&YvImNVXsIfVEzyAEjz{#{(&F(=3-YPnV+d9m>2y+**DPuoCt zsq$?NOE3d8YoRVv3biZbsH%IK7JWU0`GxP$!f)R6KUwvd(g7qxA}c6LMy_J~{?1co zB)ER2r*?(1J^|?pmS6@h8{QQS>rNBB$Ffo7cPSW!%c~yw(yzg_Gm7D1arh47+QX{8 zDVbTsRpeNL86P?n9Qbtej57Rx-$C-a@&}7kSn0r(3YK)4I>}_&`IM4=wq`c|C9vwp zX6V_EMzf72#+fb*Z=lurdEkFvK6Rdr_NO6N3?=68!fc37eKvdFAK>Vqu}4g?DDt8y&C43`%(wL0tO zD1|x(UNx2t64xG8W}{YB;x>)>`xBD&@Uo#*!8O;#C<}cH#B~ z1xqjkmksM+{6JA;$4mOwv|Pa`T;BJILi0_vR7m+Zpcw|I$BA2`r_hOa_iI>!8F*(v z$c+~XA|xQ17Fk=uA2Tq@ywe%&=2JU=qxEelW9^|7aj=vdZ}j4hKVIoE3bWx2))FQr zA9E6BpGNs__#DgaJ|=Mz8sk-}w~;S$kLIMsPNhof6#lSiZw@!ko`g81bQV5d79zY@ z2T2k)YC6wK3F4uXHz~s$7w~x>y*V-Vf*!2hcc2(w|CMe&FF}%A`MH?4J6VUfTQo!Y z**uHSyI{_Vfj~CePCuhX*q@#H@mraaWcvD5yhr~(T1uBz%GmGg_^u9DH4<|g7!HS$ zMA(H|`n}LWN{w}!_>S8vG~zzin+)8-$;Dn8v9eP-4BW;&E)|Cn5)0pP^?I^+K6^gb zS0t#C1TlO+ZH3mTY$E@&JI72&5e+*w;+B=YRV-<2vz=$vn&(SG?|MtWM24IlCq7kb zqHP`k*}eyE;$+`)6FHKrV0Ot5n|bP}Z>CbiW-5?buKhUiqFs5u=v@VB9J_&&+(8=g zeXL-%%-A$JM)bI{Ro^h&OARep#*O2va1!)ZiN3aqKMa4T)l59D;C2IBYD`a&ZC+AD zl^d@;Z#9kQ?d-}4_+Ab=KacO*;=_#_KPtF4q0fgYVr9OwXt}l#H!l;$Ev?dcw?Q+M zBmUt$@^Ts{lO8E}#1P_`;Uc=N_ZM#K2XGP?$WIoT%Z=BrNQ@?%+wpmkvpA{K3%)#L zmXkOd$HeL$o*YYX8MthS<5kT@)Gpap)JeanozL#WGoPh%l2Ft;Gp7xoxD|faVv{%i zC5QqwY@D#FahksiJE!8-m0A?_Ka9lVN#alMpS-1dMq=P`Whk?rldh{Zl3(Zt(CyS% zaWj+ZLrjZRNrHYi%W)ki4G(K1A{Q7_zYP^%YaZ0=zW<=$9>l#S&yNw~!i8P*J^h9E zS&4yBcy_^P-#kFnKles|`Ym0-{ftratliqTix~FQTm80m38q zo(cB{?gP08^WQZP4l}68E>~CTL5#v$30|3c`-(++BQfwh8T zVLz>D8xKbE`-8@BlVjX4g_2W~;qNV;xyL6`Qhy{5s?$Xyag*VVNaH>>!h3dgzH(<9 zh_cxp@<$srqhT84n+OE$e;_C8A^eShiHtBfi0pnZ_|+0{Z#keX=+`%zaUQ%%LhL5I zKTqg-7wVA?W%ymLBTk=m(leScCP_8}yGt#e+Xrfhe~DD-=qPyjMBT*$UTwLCaZ;lR z&uu%2lIyKF3GT*oJ3`$to7|}ECJv`=*K_XHVZ^rwCjnzQ5ff-uy%wNHQXq3ds>~+q z^E`!Zi${81h&hzej1%X1+?X()8cPRo@-2fKcTAx8mtcQ&sG-clq#71sAz7*P9-53FH}-Pw>fE?zA2E;aTs`bK|T!&{mVnHxh>* z`HC(fMKsJve%pzEt$ma$_f?4vnP{#x6dS54V&st%9RF6<_O3kFJeQNAw)A*jW4`U< zDL&y`VNUPs_uR$yL|Es0Z*N}`%6K)wO|*K~ShV`~j$;X~2`(Grekk>Xe`{5geC((n8Q+Cp$Xw4?4dg0` zg1%X@7RK)!75@_K!n?Q&FB@+WRS~k8BNVQo%oxdC#g{vcMeCkr^xW00IVrmszQtE6 zW6FRK-nqp>UhPq;3VYGdE6MBSRnu~x&V+QCWu?Z-r(>Qx_VHQ>0v7<|K76o0*fV+m&9 z@*w|U$@U_3KfId!5G<8}*?2DjQRU~f7Q>(0ikm&(YPePyCF|Xx6_do&pYydBryEJT zCA?CTkPG8K zz9apKR@SXAFd{}IiPqomYV=AyiDCFOhZDc*oOD<#vEi+LqZDCbyNm}%?$N&Vn9hBR zbmwg8bJgkeH16&a#tjzF)kTKsJoMIJp0}YeCWrDSRtT3#`qkkjbaHMUCj-ZUUUa4I zix%)+v%~q>Jn+SvHIrveAH|JRs{*58(r7Vr#RNU%&2LUdui&IrOHQWx%MA2Ogs90W zBDGo^FA~2F9~IQ=q_S@loBq(RX(Bf48HGS5AL-pR@x`x-h|Vgb#L+c zPBC%ny&^F%>U2;lw@QiU(=C$`d1W3+ij8<7=iGnhs*d_{t(<V3>F7A#z)oiBZNY97{06 zd|n#2{XCBUc(Vx@T2c=&b5$wvA^3_)yTNn+%PJLlVQUt`8b=C9ub^e52wk|(|KP*BA+uZ0vJhA z{Y0F&sh>_5ElUuC+(_f0UEvqp`vaq8xlr-u>ka+cFZf+7K@3A|22UlX5M#b)0 z$Onu+qSd|-4~#1Bg2afCRy=QcB}Rrq>4V#9MkDMd@y-&J4Ydjh5+Q4D^6S3f2Y?v} zmC2{`A3kTbb74j(T7wM z8xS*@1fOXy*87wb6^0L^k_0jEn1=nXQ=rgRRuM5}Tx13s`O=&xwJ)|2Z8{dwTh*<> zdc~*k^rWlWpJ}kWM`KJLS1ECAgm$c^{+`I0t7|X(v1rF6&t_4=6zr%)p}u zqN*I|Ad+6b*4H*SNel^v#{y|!XeTPzn2FW<7tslIqIl8#mE8F@j5v(KV}WdUW8z}R zS|Vu=XfGtey(#y{j-+;CY?zfuS9Yl-ibe4SPxkOK728sbl2?PdH3P)^gO1{?`F#a5 zFbc0Fgmez?C@kMp5!>or*6>=3QFtW+pQ0ESVH==`>>g1HK1WsV)0i8aE^P zAje2kPZ99kTUhLx0lvonPFt7}+Rm4gt>>TzVMY+&gTA7}7iaOuwT7OyIg&puwUnP* zw^zld7po_s{AK=DUS%}IHYIkE9^&#iPZ1PcL&p-#kWVbfM>ZCJ`nZWY5oQttqiTlt z<*x_k@FRWAp;m3Cdx_g$JjC$c?>UxWhJ5l0YVIp41~w8e8a0#7gZK;>pAF|7gT{>$ zJfV#I_CBKME>A%mI%!yf8MqB0I?TR?qUvZ>{2J0y9lE|VuT%9fzcss+)CY3w_B!J! zey#Hq1tUI53<kUSfVrH*u`94<$%4tCJr$x*p@CQ$M=oL|6W0 zfZzuEPQbXPxrmugeq!PMODbky6s|4!cs*z)oEFs)KRwGzqXeUHi$F%UAFAk{U59^d z-H=IlFL>odx{Hvd`&4mz%vJ7i+DT?0l%)BH^|S!te` zxzTeUH`WM&@0fJ3sc5#(RvbUnnMxA$yI5<(zGRY@@SN%ar-`Bx1Ea78hy8A|KvBWV zT5NIfRo{9>@O#$#`MmQ6icwf=LzLz=O+|&v^~AsxT{XX*AJcC=f0`Z*Wt{R15RZ?S5!KB1 zQ%QpMDDv3#@>PVRsk$ipF-u}#6du!%#WgKJboQ<-PT#03Yh*ND@rVImgK0h@b%Tf4 z54n%AcE%_?df)}<*g`;~W##$QUJ$tAZDGMadbxdBm6i`Su)*D}2ihmeFzb z#FOi1`HDwOzCA|_>BgJfiggiZ4l@0ir4Pe5*cc^`#L>@P#E94~`VbEk!&2<;OQn%>S{>#89bgK@TlmooP^Z}3bwO7kax99lA z9FJ*;Okwa8IbDm0-VX3O6WzCClwqEMgDWa06${U5?fZF)@r{cLi-aE(OE3e^0=Ubt z^AZgMD~MaQ^CSjF8KzK9wt-dIvG82GcZ!d=5n53sq+g;~f*H~*Al-*~h=8v(M42l` zBnCzWMXQ|D+snz|!WlK&qp_%Q+EzFYUqi73GvxX4DA`kdO|L78U0y6PFv_sipOfQo zzi$~1W&DPn>yfkdMR-^u#S+YrbUxX1(o_6)a27ARL`w{e!aFChG)(spjT(4}Zy#K# zBtf$l&rLXOKV>4Q~iF1d%g;v~0!Fwu0tkBArDa3$ zpkhysC3tSj``tsQn+qGi+QO|Y+}I&231;BiHi(A!zL~JIbr6+{@0S=Dh4BNE=_znr6lTx^yPD zkLt@UBAUZ!=dXv0ZpOWOgwI}WYRG)<8aR==)@>o7FdH(zZ&$@(KPB$Vwe z9=diqC;skGhVzCPQO19h{<+*zPLM=mNO$`C$ApODcZ-NYw!bud8tpcGGJlr1g734S zG<5D1e&WSqZgg^mGNugaE_^4K7CRdbRq>r3X5jl$$XFONPF#9cPS1bvN5MD$*oI&m zu!-A8ywXBVfl!9i&16x%ELd4*>`*Ndz|v55>z>?4y(zX8;9nxdEFwvK>0MEeE}gB` zt+1KLId0H=>-Umu6NZcp{DO0VW?b0~${@d!#Lquf^lc7aDwg2im1{Mm=2$Uocn`hx z!siNRVAO%2)%%t7=`-@;wNT| z5(BLk>u;hcjz-lw7KJ`Ki^_cu>>>lSb!IxFGq_r+ehmIS5%M~7-jst zf`5Ci^4uYX_w9#w$B89A$$G;@Csi!L3_KPHxotK|>|;yyfUX5WQ`NcV2!c=tpxOEac>8C^znc7?hG# zW^tnkG5YmMoqAN0B$)Ae=p3F~dNR-LUU*Y9D{Qd1n|D)RUD89HerN{QOU~t299vP0 zl6$b{&v0>Y;vGF|@LB~kFsk_enNY?op5^TiWu!x`Vh0!SPx)u5WPL#`Du1~}v%#W7 zn3KL>!6}J>QLdp2c;z$2`L8{Nwuv*#B1FF)iheC$P%Oa=61SY^E;Z-IJwt%exCFc$ zs5n4BtR9jW7=^7TaIRe$CL+lUT`##)w%6d_#TGhp{Ka7L{=gi)`-&B^?G7=9onOLx zZdQ2OurR1qr}%K;XT3qM6*@;^NGN2LgFF4k5h7~gX8n5D1j#0d8MyypMuiU)tpZNz z!(YNK9{mnoflebQT)|5mXCk1M=0AY_~p zD)Lu<)GHibCG8n71CKZG_jwR5mTkMO@3n8w@%}>^eQ1XRHm_G>Mb9dev{7B!QtW?$ z{W2u44#M3M#T?5x9(T!K_IpL19J24nHir~p+`Wo7uCPYIeihIALS$$X`DCATcls`IzR zZs8n0ZI&O8*|kh68)g*v$=s>hTpv_@kb=wbdODSde2C^pO5c@Rgls7}PFxvmtv_ma z%!EB%Fk_$f6gX*5f;|g?8C7vnym;0-LGL?bDaQdS_$QEhK6;pX{OdE~0L zs@0lIUgZYiy(lI(r=%pU%zqJ+`mSBdZ+iZS6xDEf^Bn?LUf!E>U#oIgjdAIr+mS6_<90D(k zMUf)({RO?f^&5$SQL?v4*tVYHQ{56`!O%4vOE3d_4#A1Vyq9<|rMMW~L}p-=d`c}v z+lYvE)}r&850VcHW?;`DLIzc9BZeniiw6H;V3d4zZkyFa-0SHqzPG3>ot-fQdk#Si zh}KO+$bM&dZ6Px-3S0hQpH;Gf2-xN)_AIS0`9NX@_H-nqf6yrLX-THuf1HQ(dI0yP zJg%0xjS|~amg_%;I7>4MGvu+`_E?-)lRjA=_T`3xC73Zea5~@SH;CWNF7zq7_F$B# zKYFP?^z1kdGcYPQD2*Gtg9k+EhrnLznj1w_;@7(57T#JMbmv%bjO*c zq%{gNem*nb%{j?rQqE*zHdR~- z-=t1yJy0UB7M?9bTwmH0QNHGo`n6{@X?=zXyrw23z3W7=KmVv29Uv1}3(tLF-)Hh9 z@ofAlb==Ip6iYCHS7C5Jj(w87#_Y(HS@h75m-y^Q3{+rcZ%N03;pwSct(Z^JadAmm#Krr#j{h2Os>KAa}-}7 zMFOJuJIGZW7bNQLtEgIatH5wP6pka5)}mxzR-l+azmxjC%3lQ&SPRDlz&DoCATj)p zySg~_n-t533A`4CZ`)4-MaQ{A)%5$HB?4>7YtG4Shl-SsDeC(>XB8QK7`_ zeSq*T$yPg8kO{1XW3gZ_ymo*{Fg>d_dYCWA^5L~Cj;14J4uQgbR*AZ#QMMw*@*zTw zNp0F|sBoxtPuBrP0GM|!075o>1G5q)-kqd2w>`zU!2d1lH$(WFW(@h!Ut z#W7b{3wt|Q6}9Utw13USu^!cRn7~?i#~bFNU5AJt;Y93ynai;Rdulu~Kt^kIxH#DC zi~6s}UWve3I3}48)7l|ohxteK%Fi;6C78e?9PF@|OcE{+Ppi*9jgSbeh3BXck>W5} z^o%{G{^=Ji&0aBqXElUuyFXEQOggKMc(YB1e+z5jnG>w;tTwv932_$iG{;#x03xh^ zZOSE0M=OcDOEqNRZaasxeu~yY)sV<_hsxjUW1UOF+Bxfqc{?`cX*X_!`O^@4ZCi*{ zX}=TxAC|4XJNbVRRi3wZ{qr}Dl@9s0K>96Apt4~Gu=$Rmj0t>Oe*S{J5Z_wY(X^Ah z60rEBP8+$)Znw@y+1&@e)tcVQCfS|gsb)W3mHQXUn77l^iIl|`5pBIg<5M8g`u+7H z$g`6@IUpHgpflXa`W(AzU-S{!3##ez^zTvcSy?VIfqW$--`-xt7pw&sxFbU3fM$c9WErr>&$ zYJ@DD6_c+gG;5c;kiPLixY%id$;i;<5>FSE> z9k++oJNQ=RQ{-42-xi)~>V!N)8A&1Eov;KGTKh~L(QdTW-tGd#{(sC3?J+BSxihXS z@?|L{ArrGn);y`+Al|3V2Dr6I%aXNk9HqL#^@D01^2wZCq0fiF>NUu9lFGmYDi8L3 z4tYE4Yd1V-m$Ov6xIJ(?5s%Jq3_VJBvb8Ijyi`ZZ7C97mg%(6(qI{~+>~(EJ?Wz-c zy5jo5mTx&F6ZT5p&9&i{iF8R zB`(ra;q#S}?Jo44V(7KWw>G=N38ep6H74*$O>%WkKetCvSB>Z0D8y~+@iG}sK@7=D zon@(DTY%WwhTRLl0kPnC6E{-20{Y-+TaU_AAw8qv)I*g#?UXu-HWec9`!2{U-`xP- z!zg-ifxZQUURxDl0&C&233=&NmZ$eV&QH|>EWreRLio~fw5F@RjKMy^dE~hh^r+r; zmSHXm!FL?uI~7TroF6%QV$;2JN7CRD+}sdw*u@6CO!+UM8)uP&;6HHRB)t$_QJdAs!ytAxpq_VVX1>$PBgn>*e;mxak^LCLWn82Qov>nmL;1j)BS}xhQS4YZ?4wG#|n?U{rhuO(SFK+d>S}#>^?dwP zQXj;9lk|$*VzBm%4ka!G-5N>oos%~6HAI_k>v2H;#iVb+6ocPQY--{{umls>V#ulq z!3NK;tM!h2iNIRe-bikrTlv4Ct{z;raMQNgPf7gDY;Exnd32UW&X}@LgIz5dJ;qTQ z`*8i>dLz4%vJKwnRgW9_xZmO4MV7(&lD<{*iYw~x=UihQV(=wZD|i5T8tQ%h!O_zp z?s>DXe)P%J`hTD#<8mR4oLM6eI|8wK_i;lDR_c+MFZC#?7olH*BR2I7{d`WUE&Pil zn80_ZlIy#U8TugYeItjUFMN3Yq3tZdj|JFSuF=nAeos3G**~=G$NOPUSb_=3ddRG$ z2Mo14H#^@6`&az^9RCvBv7Y4M@)26l()!0zGHA4LJrMAUBI3LcU6S&27O=YMnU%wg!`d<6% zOKd*D5=>YPf!Y-gY2Vn9VqNajZSVeQ1@lLr-26fBVFq>9 z^hLo>DC1mQ!$K`&N`r6kww60Q6c307C2F-?@)gD<>@mp72d`Z8c9rt-em*87E$lJK zBT~J{63U1jwXvw`F6*;Xn4l1zz7%Y2exsYt&>^2Wy-EU}U{%?T4&E1#d# zkff(}ldt$ddn}#OE=S*jp}W32V*+b^`*3wqgk>X{CZ5lX38LhH9y3c^8Iu+#Wj-MUBxm43+ zic_^hy-(bm>+dRABDTIrOUNMcImcs31t`OOczYN9o8MwH^9hzbL>YSOR-wjyeO;ss9BRyavPsenN=G9d^tx3m>$VJ75B9;irW;_3&sm@=OP{ z{n{)}9w$<5oHWq;lCW3S?EO?HG3{y#h(7C0|8*|lCIP=CElfk+6jN(9s8Atdv^Eyh16J(C?I>X8BS_=LpI2+!f1FQGcO|)BVDwTl=`Kk8YwPE*HIg72a zI({#=C$%a$$!{EKtsMCTcQE}v&&d``1(yxcxSu<)F$dj6pOrT`mS6&x2VbfKJ2Kw` z8u7MYILBJJJQwajEuAlMj|tY$9{0z#W8D*&SpBjqFPiF0cMdtt2d6kFY?Bk+V19|m zr@JVahPb7=_H5sICo$>9eI1ryLN3FzNoQuOa}zsVW8AS8E-z_lFipE!%q@TFN41%x z0~3x%)DZht>|g-2dFBF6>=r2PclW1Le$U};I?PurW4tLD0yCz0uwPEPO=`vbiwCLs z=QM0>s}O2Cx*m7%ft5S5M56PdB*1}toX}fh+Oo#1%aVy)RPMk?@d zFWEFPS!czZHkB0hPxFA=Hvh9zAklb@OFo^nXSIJ0;adwG8QxF8MClnVbqe@WbR=;h zJXK@QF6_%^ru%iftwcy#(%M;l?#VwbgBvQ41QSO-FQ?~HUK9mS)1Sdg%kgI? zm-^`bxm-;muom7sfn0h4fo$+2W8TQ93d0gi95&xTy_CB}t3JUl75Q;}EbDl`C!bJ$ zTiQ>+T3Y|@lvH-mX^ZqR^eNVpSf#8`omZn0iIB9=UKX5?9yy)4?P$y015)IDG4#9I znY$^8bcGCU`kkVN5i?kKyUV(MH(;fRehX{i{W%!bdPKANXDf4yLmmqD?O3a<;(i*C zV5ut(42Cjh=ftv~BX;R-HHG*@w3@(L*v~_}=*dVnZejN%afDpRFQ9w2)Pi!?k``iMw=bu+s>?|$7~~b_roxo$cCN5Z$X@x*h@4-g#|@0 z#|2B&ft!t0OgJn_rkxU}@V?zzNHln#2{T!Z7Bkewo<=GjGcbXF3FdHpk{ z8A}8neJ~Ak>U#lf$eSu+jr|_os(+Ty_Kk+|fxqih(_PD{--O=0V)+Tp#F}gAnaEDuW3>^C2G1KS>{90rVwPJyjz<=+X%py# zZ40>FmJ^yPALr8NKPEvAsnbx#`DMLW+v*L(jdR7kXT}1Wo-%`n1Ul z;UrqJW;VUGX)bRtx;vEdX{0k7o7h>rJ5^D|5=_V=P6XT?r9`@j#zECpEWslj9v}5% zZ2;SIx01N=`wY+ZoQvRNEnx7AHfDa@QJQiEF+MVC6eZ z#H6Ap97`}U;%^-FI=zm6&Ct&*Lst!Adlpm|Cx73N2&`pOI)^sO*ufj$s|#fWJn74F z#@7+In`KA@)=GL5POIn+aiVDlM9EDDHuk)Os8LnJ?H&xH`IPhchwT(R8sKpSJcF4F zvna9=TJIeafweAI7)G7E3;5il^`MM>a~;^^+76;eWIo3dOyCg}?)hoq!UkG)7X3`V zNd(qX{|={7`3L#Y1pRz>!bK;xq@Rr_Hzz8VU_zcVSXj6)v&)@CT+R9tfweZ0aWvt_ zR=&mJ6tu_uS}w5L)kz5J`YM)S0$UGcvodmHH%dE*p(XVs0&8Kbgi|SIj9ol#C3e&; zqLg$k;$-Y3<@MeEv~^Y?Pron}tmIYm*#;_DOM4)ghNP-od%Fh^ z{c5?hxf87g`wq9Ud4I-M8T?G*fRedFkfiJuzHq3IRi&)tc+7;OnCMr%_scFb)SoP|6_B?4>VT7WU?k~PzOaTC7=C2Ft)6L`%4xp5CTG5gx~qM@gy zG#X$Uk0oGamYAg87@jKz(1z$|yB<`I;8&PQ6K_ajg?!jatX7L9B(n1e_T?;K=%2`A0N#yCU^FZ0%C-B0Cy6vr)z^#KTkTq#lK}WNX)M>Bd%; zG!m|leWbpIwXlzYoKF6JtX2av@wPpY2&{$s4aDM9^x&K(J*6In`-k1gg>-S| zc5b=Z1FU4kq~6Rsqk%Y_lc~WHOyGV49O{HuN~PL-@g(u#+1#da;Msiy()KB+4^-t)6M;q?Q_w-cnbXXG$?;a&oN*?A5S z_iY^5%d-_l{p24Kfwgu&>eVTY6#VSPcM@oMjRdaU9i$wc zvzS^stl`cF^yA>3U4vO=pTFu23wSH^hFGh7+hVFshVz{Eqk&k^zAx)yV4#M-dDVUTlP~FQdb3+w-mAxEaRt9E)>39f(tNwcJj!2xy5{{5Pj+q5cQv%f zO^Lu-=dVwq4yH?a<6-)h@ajVzEYb3+%2ydNTt8UrbB_^pb)VV%^iX|Wm2|UX8}>X_ z>t3ua5m*cFgutH606%udY{E>pEO~(MzNN> zt9B|gjBQiW)i+ZwbG%oK_XCD6Sw_EqP2{G-o5EA&I80+o#7_00Q4YrvOpu+>Hhej^ z4Ag&{*!k};c5=se)nnCct{t_A+7y8&ThUy(vn!td+O(Mu?(V3>$IXR3(sZuf)d7f> z>UcKz-!e7*+#ZR*<;i8Vems(`t^P_KuqH|(uof6CiP$gsyt9b?%!3gMB8&Qe6t(J zwb}@!QsWppIX#qH-Hn1WHZ}EO&29FomCdU#Y)e=xeDp-Rtjkc|vmL}RlI17bvonuo zs#PN#*f8s1^mU?!-+i!9k@jJwz1N$?qga)r1?uz9%N6|W<;PZ0qD+U`WQcMrJ(1c4 zhVU*2r$8C^+XS%8kc(=8$03QpTKJs^=~OwK)xVamhArJ)RCaGY_3)42mH|}pot{cv zoO|$ZAA2e$eb&+9w{!S=wHuUS+j%A{eXvwrmC>4GExZqh_vZ-t9u~o#C$3bV?m5VD z8F*g|(-4R3GK1BezEZvRti42FEnGHa5o{gGR;@m$&Q5~$C9*!;qi}iPeNsbN(7jA` z?%Mqlfwl0{5>laI1e^C}wK^bX8{M6`i5A}*&Wj)Rm+H#q`c|4>qJeKL`q6oKco_59 zlBu3K-jw26#Ltd@3HDy=O=YzdxCP^S9R*A9@9r*JPlMWq@J7b^Y*v+fOk#uj>Qv25 zQw8@TOv}Xnec%~7<*ONO0u*dZSW7zvzGjVt^MhOTJHpyyquAa>o79flOv&P~R#5(O zx}eOLUx}Iy#HOy}ScCJY)J+|oeR(j;dUs8|6ztR+8HT%|#*LF9II+Qa7(fwf{L&ZAq32J(HL`rJEpdkkU|XKz(||9YWd z2`28_hkd8u2C(kYpjtmu7au-Xm*YO+apiNIR;{Rk<+Nx!3p8IPcl<^}c zip~7ur#^EmcgGS;$hEsVKayqt3{!vqzM{bd){?)N9Bn#<{n%Tq&flM@!~P0;RM{tn zew@f=*FCKc`;B64OZKuw%?#S@Bcsx3{kD5b!*8PW1oe%k* z$(nVJ>`byo4e4Yp5m>7*G>%4IyQXuEhrGOG!e(D~BdUXH*}|M*2_|;0SVn(E*WeE` z^t0EP>po1&m>M^%zC>Ux%Yp=|S#VzWc7zs)S=qttTFnmX%{ku`EWyOn!E34U=1M#} zUB6b_>mA58cV%i?&)*V(wfy$4qd`Yb=p0Y$bA{bKHlFdjZB?@u#}q8V#J;y%=;$|p zbg2#X`7-9|#IsC76iy*hv?4 z{HR;sPVW=T8&6|B`#Y*7ZmT2$YqffwP6t=b(j6b5UkO_-oXs5e)mQ!JbWpGa6RSM- z(4_iLbh@wpK;#dPWQW|_tM{inNCejERdpXtbl;vBdl}Q_%ZKHd5zmI~yhT^ZJ5ZAXeiskIF<{z_s z6)eGDU-7qF*d1&)mK~@%hYx#oSHWM7@potM4eM#ovvYJ!to7^jqs;@E#q(wS+w95= zOE7`IbHjZTPXn1}?>StAR+0#;<-8bj43{j>-81Zdv?=puJ|CCy26dY;EWrf+UQb9t zwhvQ0VtHDVrV@d*LdI+9su4?dr)~9-166YE*}#`ec!1WCVF@O1+yR`(J>KP+O@COkf`aCu4>=uv<|-c;!!a5`ndFjleGFcUYgFe8T6aHZI^%I6KpR^1lGd+h7iX$;cV0Edwkrc zbyAPQ1okoDuM(!Qd7r*>lk^mcz*=&zZQMDEoqc$T&pAvLEWrf!F|dbxZ#G+e;SP_B z=^_zW3wsRx{T#7u@TBA1xZ@IvC76)?m1*5r_GMWq_y3V35m*cRF+#?+cVnumlr${s4Cgc?7a2wYBQ?9d9K9YvC~wb~&GnXLULaQ};XPC|H6CJmZA^Q4u`# z%h~GmtA!GQweXk-QInm++4?gB)JlOV?d1xql2XPgkdlQol#4IZv0ooXTxSPPGdutVQDhN+7?sa0#e(_jfEd~yrdM}j@ZAvkLwXjvfjZ?{1Y=wutdOXBkn#19EI6MP{Ht*ujQp7m*=bl!Q?cyCB zY?bg$c&{r9cV4G9bZW-11QYU3(V)xSSm#RH)d4q6Bm!&Ul_ks*>v%DzCwZz^Ag?(w zfp?~0bZ+j)w%*TEpKbmit!uFsUQy-6C z_4J=5t?029-cN?}QHi5ja`+|nW~N3WuohlrKoru>Nvz$0<7&v{Rnqzc?=9lB2<$UV z8^{H|Q;9oXJ7GfJ7wvo`gs}!+)cNnaj#a}u-h{mKi(yY}o2xCm#7YF#if)}igRTwXZFj(l2ok+; z4m*0VHYZD}DL96j*ueg`t^+4l`4m4bA0fCcm(&L|`pB0^1}tie=RBR3GkL zEyZSIqIfFos(x_i+Hd-E#FsWiGuJUD>inj^B?4=$?Y)TxHLJmwRvHe(xaZcaaj2_s zeWa6OwsACFg40N9QExf7hG=HEB_`8_4LQ|W%<7ZRu>=!x%-x`OuFQ3#wfOcvQzEby zj;w?D#74c?(2|D2xl0(w5=`I-K|(Cnk7ehE-BY8FJSr^XE2%cE8~4~8OL4ql;l31V zxuhN1cZ09me(?*6CECUix%vt2NcPcbid}Y55|peXsqcX}s)jMw z7W>t?o9jqrbkeS+yN`6@eQd^3+?ue@P;(YLGIhS%TnUgQn2_7N=C%&3<2yHT^Jrxi z$06d@#4%-rBy4tP7MDASobHb~mS6(66J$58>BGhiZz@)%q)RP`TMfrwLSCF1fow}? zWwHFm04XvP6Sy@YtGs0}b9!7+Sd`jI1lAHo%juElgZXjSP_W(U^~bXlCO6awi!E+g zf(hKR5GV62lpW9*A=6cboWZjbqwX0uy!ywvMc zu2L+)glr{7SEHCo??!6nC6yJ4K(-|Nl1HbbS;)}M{99351xxVnYM+B8T6*e8z*n%u zg}NwaL6++pU+FCoSW7xdLi`G%SX$3Tx{OwS(isy>kh$rU95e&VuMX|;Iy!<)E?cJ_ zn4MPCw*FFj=S?`zc`hV7mVJAe(;RlAUqvldndQ^thPOjm9q$9`?G{NAfwk`0ETrL!61lC1{(RKDKC{@VCJWSvKp!1018dA@`H`uQtri$xcu zZ^HO%FMcPu;pp@z7M%A)O$y$}@w4NoVjPnUyB}Xhv5K1>t9z?tO9a-!?*ylWf+sP* ztEbfV9eQ#s!32(!CS(R5$L=n2EAnwb{b41QT-HYucVbw!^lPIGegdBCwY1McYjAVY>!47H7jgNj?!1a@?!Uwl-|; z{v`Fx2)LmFeaXeq0(jOBkxs$(?Dgy&YGH6o>6X}&RpEw2 zU@g2(Ammxa;cN^2rrO`#Lh;NSM?K-WFT@B(1heipjKl#JN3jGGc(Zn9tf_-UimYw?p{F9GZGUc=eX=3mrpUZoO&wXm0f zQ`nyZS=MG_alY#wjwP6o>ni?WU$*c-9kIxCzeHdyIZ7`i(vRI~USHVOuOP+HV?vH- zta^R`o0?r)G}yRFiV?;HZcX^Q6hD}GE~zfseMyw!EU^~07_i+Yeys6$GqIs7QE<#A z){-NzbGpHe?=g+Uqpwq>XhR$!hGV(G?^e{Xcj>00dTg;AZHQtAafCS`U%VXIl%_^v z*tZ{2+$+|?(PD7M09(-mLpXPxqv}<}Y(+3u!!J-h3*8})m5uP(b zjBw@{R=e&)b$LM@9iHjob47U84;dKNhcfMj!|M8AcZz5CSZmp??R3b9Kf1Vq-Y{E= zq;psk<77T4+epFl9X!9f-eDj88QEL6%zFh8W)U&$J*}#mKP;hGf(g7%fS8G(IV`u{ zVt#t2Tn467$7jH-2C_GePk=Jqenc~;Q%f}!e%eb=oEV~MO(wY`Skg8?U4zbkZ*P_p)u6b zJA&VMZ>4GSZ7i*43Au`i#s;z>9&%)-204h;pLFh6f(cE+SlX}sLLNKG3f`mids|k~ zx{Ijfvs)r0t;&AX=Hd!YPCEc$v8freGVu`|j$YK^G6>S@{oR-TdJIHHeK>#pzJbEd z4TjS-O)luLU195!$|E-+%G(9rqj0N*bjl2C;dg==Ku#cQu&uJF*>0j{nOP#8o973o z>@PcFOT=~zUbMF_Te8?fG`lukBCr;ITG;ow)s-!&+D6<~b{63>u$KH(V*)#~iOt=_ zsahT!zb)>AxZdD2hqf&{9^XX_KEGLq39N-{fe`;XJ=pg~O~tuSZ741sTMT|$$UtKr zz~7f()_NbJ(WtHPs_mgCq}!iJ3W>bg9{+B64siJXKM8 zEK7As;4`~ymI$mR`7UxC<|Q8s>hQZ+D=C&>qQvz8Eq-(zGK#c>%nYgL0&|-{wc-QF$Kj+x2-lBm!%# ze|JXr>p)^r*`qd)ug<<+h;#aKLoODPJ>rZ;+hDi5HX_c!&nQRJa<7MmRQ+_Y4a$s9W`FL17}KC_CzzvVY7liOV~))5k6@7&}7Pi?;1g@oLNr@CDHInU7)@q#EPxHqeqAK5)LG2E|`#W#oEK7a<9dUJISAH&k zB_-qQIe)Hc#bYuzz!=-axn|HDT_daQn)k8)z*A+~oz8D_g&0~8OE9r?brap64qW3= zY0Y8CHvN2Zq19!f&s8L_1QQ(!tMV^&8)Pd?hNtqVUc>Esuetg>TM~h_Vz*q-#reQa zPDm-(#=uM7PMe2S)n}U$Jwo^BhBq6pDL1d_urGTNcdZlx)|Z!spB6^w&gqUPVp0ut zg)I?VJGM%Q{TLIR|LVaxgO%VO_0ubruP&1UgMk%)M$tuu3cQ~5JA_gvRlWJczqTcfqx5^VL91~Hi?7WDTcrHw(A_8 zowv|u9+C*G)ni;U>Uv-^ce?nw8QfL?MBNJ(Ir^uC>m6% zDZOf0q@~^t*mw0Gmr3cr-`q*DE7b1cS+$*0!_F88{I&}V$MFO@A8KK+y=+$wr_9|< z7FT!s0q=n&n7};^_Li2f%gdO&-O$gmT}^4TmaqQg2s5W32W(@ITcqhk=a6S925UE8 zu!KJ}3Wi!dWIyQSI$f(Se4%q$P)9>*zR4O}xPw<&@*U>4jk09B+I(}2)1#Jk4efy?n7|ea`N&dCa=o0Y z8S09b?&Uw`ZGhiRJ%kBdHbfhGSIX~eyTQ=U@yLQloZ+K0dDHuU+)2LvSr*ldayj`n zK41SHxD9aI;Fg698%tW`c@BAGcn>VW1a5!GbbIZK^W>5gLwn%1#pPYd9?DamK^DwN zBd}dp*ZKLKLOc!cfhCye(0r8cR?B@l67kd?o@#?|8Q!MA;1e-{wNi3>@cH|b;7r_J zD5Kx&Q3b1ZRWpnRSgXk}7rxCLPR_xfOssD+!?|HevEe;lI&RW5c(72D+Nw*o$3Ls7 z#tY63lkHh}{s5=8>i>2~2#45YZ~#rPQO`K;Rh?o{{1H54QWm+Nu1& zfn0t6z@_7-l4mkiYlRe!p%wqnsD{TS-$%*1mk#?V(UxXIdvw^J_o%)hcdaz4VXc8n z7Z%kSP@;)Hr=OR+@G^BNGEXqP2bN%>Zk)O9ey2<*V!3pw2|dr7ec-?cIY#-$35 z*cKqS$lx}vMlmS{yTTGoguiLcE3|@hQ-;4a|7I09-M9Hac7?T$x!dqQ{nm40sh=|} z-*U^f?5Wl;a^fs`5I#VBh~AsbMCg zCc|Y16af^tq?)nzm97`~fdh?rmxq)5)GqUx019OLucQe=(Ca_kF zS4;QE+6VrtJz9Hi%iWv=IUu2bTxxbuV`|)ASG=`)HeRL5eb8y+HKa-QOE7_Z zGkk-rndex)C<)q9E3jv{G!!>d)LmB!Wh0DP7_|OF1?cD#K zg>RU?$vL5Sy5Xs?1QY8U1{W=_cUD(i&=h*DAHALxlhxeN2Qh)QezptNjr*Iy-wnBx z3h@l?*Ry8)7l9?1NL$oRw>cbU`i8$DyKcBPJsfKoqp$=MZ#q3L@=FFAi>wW{QPQ}T z^YNfbhBn7Dq?fbz(t)E=VHDNc$g?HSN(*yu*W8({uPaPo&xvUWzxrinn?>9WmWVB` zs8<{Nh*}4D|2593*h1l~rDFa+1eRdpmv_ga5jFqYb`M!Ma5?7b3I0@GM`0~o3$Q~! zqC(-k(bseJvv4fIgj`p@w*T+_z0E36a1lF23p|(boSgg^0e+P4h$7XY#Zw+1b ze+aDAEw?Jo?EG{0|M(KT8-=|D>2!Dr{I!D z27iU01n-eyUkTQ}uPEnVMHtG!5=`J)02?r>;@bDVjoUAH4{S?#R)gOU&P{BZh8~5>D0;9|BXVFC7G~>&YXtI(`X=Q4SmA20D=fhT zt~Z#AmaKJ6?NZTTySNPe?3ji#yd_5JyRrqk75C;aDbF^(Lm_p5j#$O&LP{YsJNa^8 zfg1f|rnr*r#_?E$M<20?>$;ln<-232fgis5s;xT4FGduo9r*u@A0F3I@yJkW7q7c) zy`O)qJROJ&KdbR!iEvY8UN??C8TO(t?gSOR?tPFS-x&eK6r%}r|KK>GJ7~}U$5SUA z+luE5^EL&$JNX^tN}-;3eC)E~es{bW)xR0XyAgPOelWTYJ^VP8$KRg<#2lkaENWkn zaBaFrhxgd=t^r<6!mir>gGx%JFmY{y4ad86xIEX&A2nlt?c^_P!=Q{mM_*FMTCpPM zp%cf?j^|ndj;%DSJrD4u{q*lqTxYLp?lDcQn$m*fx!QAaSJx>P=5VR|EHAzNp!5H} zlV6Dm1!B9KsrXQBfEef>!d>_E;;SdXdZ|^A2G2!9hB)ylX&ZRMi|2soxV@tIIX75* zf4^0SwJSA7x0pjTpOVzTY zEl=FCi=W@9mCC?n!%diOHAD~Be&YC_t}4DY5Yv$b9r)L^`TXhbBj6pnE~_Z6TKS8= zO>CqxFfBbHu^sb6-MBGO^d0A;^0+p9LCRTv??Gk7W49~3^)bl5Yoy3!Eb3KNw7T41 zJfGpCVhJX2d4wF#sU*sC2aA)%P1IB6&OGx|37>bqu2cpt8}`Ujf2zi>g2ku}b=1)NH6T_h@&KdjxnYxIFE(2Hd0QI@b>9 z4L|d&R#87d$I+qBn71GOvll|v8QT4=?{L13i)<8iXZPVc2#pU5Agt6BAhgvOe zi0JH8Tfx7D%kc7S%}L%Re($yZO!Z)&m+I6mL&cC6gOoe|ZTM1~bA0MCIQPE+?CO3A zC&vDYOkBSHR~=*;BsLf|mnDe6WkW{my`R;T`hlXxUdZ-?v~YPz{oJ_L`Xnd)^yi(g zK@8a>e}8eT^JeAJk+$4HbAqpQ8mD;dcjx3(F(-A#%1=uMi#w`EzX0L-XPYF!gj~jz zM>o_PWBo+EiI{H*^sLuz`qVi3(Jin>fT1h4( zEo)CsIznd2NPRA(h0Ct1KY|*FK-!sUt99k%TO!vUgx^A15>3L&pQ$G&e^Zx4GgkQ@ z8$Nr*V$M7kDyeO|!M(>d*Riqi@LR(dAFYaOuB;y6S!=$X!{ej!rRWg{<6_*?5aBa^rSkv2JtHtg74sw zi0Q^gVsfpDJZbn4`8_Zp-PCl?_oAA$`C`$T)CqDK_--FelgTE(=%tUjMaNBI+0>aq zng#Q^>AcEdUW;$=!FSA%b$c%;nr_F6$e#&pbem?hPV7IrC)eS|A$+TmbYIcH#ueGT zMaOlUOM;oC73K;VfueQVH_-klyE&Y~4mW4Ik_r6Bpgz(WUP%knrZ6F)_D;?sr9`2GAzNw@pxN$8a$Dr_e7-rwHr$9 zu=i?K-|p=0^3Jr(If47kUZCL2Xflzq^`o-k%}v!Zup7kW{O7kYfy;&wr}-=8h(#6g z9af2>UFWhrJJXeniT z!!*uF3v0F2B})3v4r1zFOZIYH2YM)eKW}0YCB+e98lv=OJyPoZ|aJE>PIJM}ua;nonv9(6N zl#vwETa4P$fs4=ZC=-32i7GAMC{w!+5@F{zDp-PZ%Hr}MVr%?8<@mi}V$=G`Qm$G| zmF=)oOV zc+&~J6r6=tCNzUSDE@PY2~)?03YK6(eyV|kzbWgh4Hw-;ZKPNWmxnXb!VXKtKgt^4 zq2g3xI>i!96gO{0Q&+<*yqv;&ylz{S{W%mMo;Z|humoqf#lHlZrpEtKUN#vfJ~mF! zVFKT-foW*L2EUZFYeU6@O1q@{KQM8nuobNXtEE=3T7oksCyd$8@Bk6j$VkO^iQwBq zWMX;vcjcc2LqwmZbtM989gAy2=fOJh4y+Ri8MU}F3z|7d)TrG_#S(l!3ND+FUtKG+ zxw{65PHQ`=876kLXWN}TB4855C(&@Ge2B|GSmdVT+*a{AMFu{uD@u>=!03!BpBPq*+2eRjYOOX}Z`$|186;=5?au>=$HdsKe# zUO5pIBCNk$k_fC7xbCsJin!#}Z7)wR`OHJ0;`7FcBPY zp<)7SwOQAQx{G~qW6V@2qsPnl%D@%FMAnK%DwbdZTMR_KxV~08b{r}Orus<))`~6Y zKtI9`%VWb1OMY@~R(8lwTwmp`VhJW>+ikXsE0woT5vy8P=Xk#j@5AACf*C-MC(4O) zqr{=jhou(8Z8LGUG0lFso7dY`58nLEt_#ZjfbpVBoqHThFoEk3)*t6el|nL3v>VV$ z#RS$eb2owvG>5pdIt1QWQ{;l#T48RcZ-F=Fjke~G|ai`tpf z(RBn*s&X94_%P&!Qs@0pQ8&&{#S%>5T8H?njmE4w?88my+ec~-+y>YaK@9!Z^~#zy z5u#dm6W%wAYZB`3lve9y526S&r4k8IawW!~jbaWb`&iV3VW%;c)(Os@lcZKgGpF|XcwWpCXu zamLt1#S%<3biJf$S|yi1ObQ3$q4gf6ZRr%TQ`14k5=`Khh0!^Ar_w5KlCTIHE)iI3 zSgWFMCUEj@ucJD{zlV z;0LAp_h9j3w68ScU_x$l+Zq;h;paMPyY}#;$@=YOBKJRPEck7zS$p_wF{TAfiO3Hsf< z2h|-W?YYkf|I`y1=GE!^$Qj~FuOx}UTF)&`x);BB!q>0X-*3=jRuyWdogrAuBn3+_ zK|Xga@`!xOwW^+|_}z$3$%z(o%bX5+su(Q-BA zSb~WKY2Avtro7^B8?^@_bekz{HY!#Ox^`0{u$D)pndXf3b3WHvpKY3SH>WGc$BOsU zuX8NHMCg$2MSa@7;E7Rs!Y;QqZGA6BJlSBOVghT0*F5d6wtmF#H>nB4pk8Kl&Vv|n z=yxL(OE6*CBG-P#&PTkI>4{e*HR$AFvqk2!(Gr2Rc1?}9|260$kIE?lpZIjE1^wOQ zxvo!c9PEDJJC^_BOJuLqKF3_)8o`G(jgfbXknaji57gXRBy_P}dhhc$Fo%BZQ%4OC zj$x7n5wagkOs%4%X}YT$ZbMEa^jlafEi6D|JhLWW-(n?{v7x~sdbCT7TCv$Ih9#K5 zehg-PT`MT5?^mmNXTl`{Ykj^uSi>v2@qeen{v0XZvxg=x->&+*D)l~IQQTe`#0ZvPqHiB}vVJ8ey1p+MkPncylz3=5B5%GK+ngB*DLH+TWcFOyk;P`YeKH zVlL5rX061nqOLN5wYF*DE_C>Y;I7XWx}0vJ78N>+UtaamqwDldC85z08)_$tk3L&VhCe-$jj1RjG4Nji9f_UbiB%vgR*BCuBU zqV5{)$a}m+XZ^@&d+09poj6gHw?C<12_~d5m^i#YM=P9)5Uv*!Bm!%_i|wWfyZV@q z`>W5`d%ON)TB~7%C<3KNFypqOuI#Y^q3>u#+;#;z*=~Ggm0rY~kK~jEW_g zkVgZv3WJrupRD-#W>IV@tUr!Mnd=&!1OJM?0!Uv6$o!eXigB|@{_o1!5+P~D+K8BuUX{6D{iweToGh`W0?W%?|t z4uA}Kn7~?vtF~!YUp3*67wKoOZ_c z((IADsMDt%JK1o(#>TsdZw{TKVE-ujG1Aejp7PYIw>Z(uOd_yWcKlk6>EqKp&NKqv zWW`7PWEH)?T2g^3TdqtK-|j6{umls>kAe5u z)mb^YKT@POv62X^W%^*1=I4{AJanTElreQ1Q+95dC3ej3tY8Tyuva2vYqpK@A}d;? z@^Fd?tfdLttNHimQ(n0rgEH)HxhoT^Mhhp%E{r9ZkUiYCNA^nj-)OP$q_+kWSj%tb zUX4k&XZ)M6hcY$&d>tRcF@d$-o!zTh|Mdxv zvA2RUN`7gSuYIFM_;bdw1QU480QY%awpSj8MTww@2NHp`94GJ7m;^oI;o16~?WT?0 zl!^VKL~hhojwP7Dejerw*7i!L>a#`k5DOI(SnJmL)tY&o?sF?s6DT7t(?xN77Ae|| zX`o^WCh)idQNeJ=0@U(Uezab)Q&TA@~?=skF}iY1u9 z;|gS;fwkI-@<=hT(G+RK!J|x@3`hGXLsf3pd?u8USel^hn=+v2p(S`~{IwX3IMPT& zuJ6<;X&=4S0f)jFX$4v7s=m;XTQEOIBLnu}a7Wd|rOMp!iR$_>p%Q_$dUe058L4T( z>%7-{>XBE+D6=jlsZ$H5GAzLa_TaEqdput$td^$UA38xIuvUxs%bL$6y}4N}{dec0 ze1GL^EuntsJ&s`sCZrVriN6!7XkT4YA5R$}5m;+)>_tsV8eA%trl0A5gFD)i$xF4t zj-gDF;4uTw=ZU9ZsFIdI#Ie?cWCCf`p%*msQdjVohxFfsw_Wm5*0ioIk|O+=Bte9< z0wCVohAOXGG!Wf=yGsPtYJRU&GxFCqZsM%Z^50KYlm*@`MDO+<3`;P9M>vSa?KE2P zgquly|lFt6gQg)$!QQIy*=T!rKFc1)6>m4!5-5+!B2a&lx>(Y&UG zL}0Cny-#a;Ry@KZXX~^4J3sHDytwNt0&3P}Sb_;WKEk~HYM64wv%m1EUP&UbR`H+5 z8sdM7lUrd>M&hgCO3~mU;?bB_3YK7^!Q2y?VQ!bWCSHHHQ=s1r<Fkcy^ohsaq&R4Jm6L<_JEL`_T=B@QLSqzcx1pnA5P2mj!@S23Kv5+43h|~_1SNO=6OLW zzfwu>+wJx_DtlsQh~mhRDwbdZ`+QhCYj4sAJ7$SfdnZYw0UiOG^uOxvcAfL&XEUIT z7Vveg>zzo^pH5M+1QYUTaIw5TeQg>oE{A$a1l9^#)k2f8GMihRZwO_a*twqC_l_33 zi|th`!Ni$^f$rg3a=7wOBOs#MEp(ZbHb=bKRb9oBW32;<`hu2;Nh2ypk`L;;kv_7G z6?s#NIF?{Sj-ek~J|zF_nK;ogsSU>x9Gj1$@!?LSeZGa2fJn@1E5+$!0!R77+8`-K zS^BCfH<~h?rT(czX9w2R`MSVb292Wf$QkCHqB!n2$89{rB?4;|o7JIjEz)!@&GkE8 zb9?Vo26tY}$L)e_X-I+zJnj-w^>v1lc=r#*85s;2WT&@P1HvlW|K{dP`0aP7C;~g zCh!;xK5^MP<^0i7HN|w8L}0D_(h9T^naOA6>i5XvqgN_b>#DOnY zepdahj{e$TA|$QJH7H4h$kP!0uG;9S%aqFZ{-}FOA&v}5Fd>b>B+qoAvh{U+p%_7a zHAG;o)fawiZrn}fO~HSHT^(4eeCb_JJo52mSb_;W2Ez@K>GPGKGHcPVW@m}OT2Jo$ z&`j!Zh#xzk-&N~;L*0$aw-Ld@#O0de zwBfU+#kC8(zy4NsG$P{>6~4qJBqKKF$(rg`sD8a0_H_6&+p zumlr$M1|ej4;vL5-84}v(O4p|miE;<&FQ$*$3W-yEWj|3BV zeEff1oq1f2>G#KPm3>K}O^iu)gGQKA_Y=ktW9!=tg@g)`ib`n_`DP!&7-<;GF!p_k z?(1A3B4iIKYm9v#gNFH?r`PW_^SQqN&FghO@8{0cb6w{;*Eye?-6;<(*4ylekuBGx zdn17=b?01A?HAqTKUt34r5Q+|>Pfhz_f@x>A}^-{|5O`CZq}_sqNRInA1{m`fhSA8 zF*&$eZx%mE?j1c#Ac3j{+bq3H7nO=5BbxCuvW<;;nSZogSn4k@f&`vL*)c1BwZ5TS zw471+SRqh#skN2&tL$RoW$VPxh|JueFJBrZOGAnTMv%b#fqhb6uGSa*6)E%G90>_j zHG2Ho>qy@#qT~DO{0xu0_4fzQQ+grj>eVWQ6Q9C{Q6#wd`Gi*QHh` zg->=q@6MGUBcMr!ZnG9wxqxSfF-TB%O2fCW` zlKLe#y!XzVBKK$$_#IOJMv%aKMbpyC?|A>bH$kqe+e0Bx)!<&bm*>>oqInN3j8%zz7nUukZwDw=C~#w(Qz6zLAp2V2*;*b(-eBr~+dBP=!A&zi0GFxL)`!UQV0aRQY!xf!#2gHsOzMdY!Wg^7r_g3V|y1 z|L&x-j{1@_Q)R}Rs>=UeB=Gmd9yYZ`>ub)$%KXOdl;0qBz~EmGzZYPNm+tT}PA(Yg zqx_X1(LZ;USKy|DBBgN*|CPkpdFcOr79+y~$0-D=)W7zaI?4LM;AnYWhA4mSNZ|K| zy`x{P)%_zT$d!&mm2VVwz~Hx;yA8YK>Q3Hcp!1bMyvlCdjS*Z+T+`i5MSi@APl3i3cV9`5F9DZ$05)h)h{NOxe{? zg?lh(OX>Uc2j|Dhrysd581`)>f~wZ_e&%~gG`JVQ&*&SSr&Dy06n3i>0#%qx@NcmH zcHO#Xh#Zi+T*(=bXyIt%ee~IB(e_94Tllu`7W!sKf4T0RnwOvoa}@JRy+t3_C{RXq zDpax;BrZkSdOKMk6%*w|enxoToqDnLw{rTQ9~A;sn0K)Y?aQ^gd#WzWhT17P9IB#9 z>U;M~*&!M&N#bYpUcE&h_N29J*`~EZpbB$TuIUe5t>^b>CoiYBQgTrwc5q)}wX|PE z>ptemF!yE~b+2Lv*=<-?g-}$GIdk>=^)~%Z;!CPGV4#w>V}8AeiKd2H@e#|#{c-B~+B^%bTmvQz!a%DRgLuBg0Txh~gB^P{9+d`qQ25jziYedM~& z4{7@O7n5YJYgfVu64-^vZ&z`fu1EYGC8xQEDg>(3b$7#pwfg2B6J&>)Y9@mOuBiOC z8+TkEemhj!`G2SMCt^<`uBiMSta?{}xq5`WIlmua1PQf2@qEft{k3(lTsEYZLZC`r zsV!@k>1owRN&AQPN}i|?N@stUhBx)fM?>Tnb4rw46#Mis59SVts;~8cQ^B(EP@IzQ zB7r-Drj>;7+op$)mcxfHQL=C(aQ1-R_r7_mS2{mRJ{yu~;Af!{Ws&HrEzKjMJ^}`OKa(h`j9V1BKvr3mqf)xj19Q z-mzOQ>xCV(%?{(k`O5QZ+yo z?mn9KQ(e-%hMMHt%C$`xK|-DL+VS?J-o9Ha**LhVLZC|7ue6IB3_U6N3u*n(#e@+g z)Ooc4j}yAnd>h%fw}(O~DrFz+YI{U?^r?L9N8VRfEl1wv6lWs*-Uo$u<0d;UNfPTX?`5hT=k&aQ*X^mZSEX5nHpDeG6_U@y(vj%2dVMbNW0IIp()>r4Q7g2wOsMT5^l-XYG-RLv= z(2fhln9Ji70#!;iTDv~xjGi^Cy%WGnPA@UYyI( z@=}ayt+})R#g!aBU+$eSg#R0#t<}joNf&z$rtJEmCgtaaf5+QaR^q2mO~lSS=38Xp zkVjq1{HQ!V%%ntsxcACgBqx6+f_^sli~h0gFr9bGqB&1TCg=pv`Y&oZ1T9H#ff3}TUE`3Rsz5^9v1*$@7vzq`{&%ZTS&##Q! zLWfQ`$eG(cP1?CnhE{#O(5CPi092}@!;KEvc>g%jlpTz;`jh_zi4L7ZM6GD7nydtp$Q{MJg}%Q-mKX#Ds_lw zVr=$0Di8FP(Rx*dK$YF)x5lmU$Hdh8<~!k$GxyM&KYZmyw@N0AAaOj(Ry5$#T~x*C z&f&LBq+cH_J&s=0kwBGI<{P64SG>RHiZ}NG{C$X$G6u^bT~6s3LBi3|MjYW&YKMwb z>iSK)sA0%Rxg=)2LZB-3A%ANJ^ZZARq5KTT7su$f=NLIy=={FSYle@{O_6$Ikd7+! zec}Clu0aEjjh8+HEK~w~YHoFYZtS0OTco;}>(rC`7m)4dadK_=C2x%2=ibSyBU(2q z5yfkIFj4yTdAiVloILNEl(>JqjJO;okU-Ui!`F=F9(P3Ei{|`{!C?h7czn35 z`_~eI5hO}lSc~Tiu8HksjhTpll|w%-m>?hL6e|R(CM+yAlBVAj=Vmoz;=!$48k5A& zNUu#8L83`~Ws&;vlF-_itIqG<9;0{>D#Pao(6lk-#)Z>W%X6tMD&|rPm!GA>eq&|- zxwixos8Suw4vaMD`zsSzwif`mPP&y8EF#SKfdciW{~r|74waOqm&A~1q}xagk7 zb?WaP(ux_QrFQdMfu3hbsD5PQ&t9O1j^m^;$zJgzLjs@8=i1~q^jqKv`Palt3V|y8 zH*waNeUCyHjFOL={jCtFQXR~K13%C)t6_3`o&#Y73H;sgZC}SHbn9i1oW1G`g+LYh zpK+#tcLZ{7(oL6Dmk-^dPqxoMsX6)C?bI> z)sJk@+1vE)#R&N@p`YTbh6H}Qc*ex;5nY=bEdO3^rx2)8{m44bFQfPtqh#278^t9J z3H;8pm&M*^WD!47-d(?0aY;iJu0)!4@cBbpaCnq-xBbl<*Fju&an;teN++*SAO0(` zKGH|=@j?~uCERCu{sztYG(ztDCO{=%UqVkWO>1-H0-e1!OuB|IQ(U?5b8&}b2h4?~ z6#r<5od3&8g+LWLg7JGZoQ~0-1w7r~Qg!7*0{30MX=rqX+UNF{HA^olK3=FoM=(C0 z4=||4n%*+UMKfUp3CtffZPT(sI{M5=+ z8F?ai{7L$7xTZW4#61a02BS<{zdD#g0r*k>w zLMZug=khx4Tt-4sg{(IGcq*lL#Z=12yJ>WQJC~nu=duP7B#zFyX#Dw4=kmPJ!L+Qa zq}je>6arPR|6FCXY#SmjY%-r9hk7Q`=;#Y%mltfp2on8M&Kn!JbJ?e&bNS#XU!wO< z=zY)O3W2IO0V|Co8R^1!Y3{$ukBX)lDVjXYZf_Vt;-J@AV-|NVKdtCo{_v|#r&`vQ zg8%WhY7Dzo}Z z{wJo5LMW;^+xbn2IYJ9E->X^Yg^}mr{&I$MEmNP_%Zxfa+mmXZ?E%$0-+W_aP`nj}zRHd$tGc@oiIIN}wAGae5KVd>HWoFy zCsI$C&x5_@52v7S5~O2ThBp$Z`okjDNT2&q6puFFZC~9TP376~(&OrnUKl~5Zmn3u z@54h8bkv=Rym~Xq^Sdds>$D|ZF@gl1`q=SgZ8C-Kog!C1?=6r()w%Ro- z{EVn`GiYB`zKP3=5g0)N&x!ob`wdA{e;s>Zw=7Z!RJl)xGn`HL#j|CN_!&VS)5*U^ zoP2ZTp1=qacuwT5mzIgtpDYqviP?cG@)R_6ttjzS^QYk(=MutZ;B#a<2?|q)J znft60xzCzC2l~a3xu3c@_fsQ*s=WT0#v|^hzFg5yeeU;Us=|Fs?YM6VBS=KOD=><< z)2Vw!r&C~^WHNVhRL%`i2voJrU1gZNMW$7Bi_~?SPLuc!GKTLUF@nU$uPzv$v8zg1 zg{z7-Esa){O_H_ydnp8}uI))TViI6!N>VFZZ>=Pn!j*#9p3 zwmlQkO()UJrEzlKB@2Z>)rQ5h4CmoHM3v8r_{=%HtQT2oQ{~#N2L(ouP<_vvJPM(j zF7fhEuL}YrNT}ZGMKv?2u4{~(@}Y*n2%d`3rCrmGK3z=Z4zaSx)k5)aM*_XW`PTAG zsd(yVLmqb%)%q^fbUW|7mh-Q3%g>+R6*baq>8oS>=39&aG0-l+*ckiNNIPz>A%|7J zEe;+|r1x{<6arPP`d-a(V&|5m3g?#6?$@}|n?Q$8#+fjJM7>>ujg;S;iq3(H_!&(O z6p3M7)>HhsD1}f|U%B%8CI<>_t$99bVT04+uxGGbzyGD;(9*BIy>V{Z8PWCeBxMEX zp6x0}#a{n$GU~}`g}|Lbn^&LL-J3%DZ!kY&*xH*SGB;K_+wueux}1PYS@X3i#TSKV z>{K~#UKfQ>RN!U8YkQk}V!)QE^77;_bPXa%;0n&3JbQ}73L{x|n!mwYAz;ryFB7f~ zHoPP3jwH)|BbIt&1V0zoe0CmoDHikNQsjWTXS|R=6?&QQPu2IHm^36s7FEgg!Uz($ z=5uAjy;zufrpUeiUIGbJp_hrKjhl5x)OSpgZPyPF7(oJe3I2Z6y(acGOO_*?iWCA> z=w-rh2X?tB=D$mlRt}{CBS_$y&ppD^uZUr55~cfWCqe>M4QidpF}teVs&G}wUQ;Rx z5)-9UJ7>ZO64fJn8Rm)nsXUR--fhFqi>f?%U%-?1NTBLj?ZTYq|4iODn_Da@^W>y0 zPflV43D2m0hAq!pI#$eDMozmX%6PiwG*8zcfvSmvF6aC^T{G|c4Y7~ASc|xe6(dO4 z?(sM7a^GuqMc?bu4|l{$?qbd6E>0(S|%akpG40-mKvoAN#a z2~^o-UC;T+ZHKtxXU{uMRJH@Hs+lCW73T3C^-O?|k~1KIzkhy{fSm_T=PuR^ z?qbEyLKWsj?7#cSo$7GUcFjj)mD~pj{5#e(+bx}F8_%m{^Sl~<7OF5))3kLX+EFIY zJAcRX&KN-gzmM$7wZAjDkBygYE4NSxRN*SYYx}A;G;Bk({4jwbF|YH12Sq+?(@BIeDQ9_g%g#Dz8noZ}`hz`>HFaJ4N+_qoFyl zXH9eS9c1dNR&=9Bf4O3bjY4Rsg0ms7?XPQ5zE5{q{*LcCF@nVMhK5#cpGci=_TKq5 zvK85;cu3i^jY@zD&%2xf?64xM&L9tpb3s?D} zwvS4H3eWBAAW&MFzJKT-S7!84&gaVKj%{LSy)#6rgSpNyDzOFa`?a<#vmc}qpu+kC zcZ-zPpdQ~?%1)I7lsbb3gqG{VodfLY)Wlpb+1u$0`uNvVYMvaV5}?953U`G)sz(RB zifMaRh*B?6K3B=%=0ER5pG>(_W~LvVcxs}OGL=wNP;KMc*M;q< z$5Cr~wT(MDAfgbEk#k@8_Dz&mmMGp?MVpkG9@P5Oj+BRde?H~u9C7AxltL&fcsAb& zzurh+?o1a)ZKIW+N+FaUmX^C$P_@6EDepS}-^I@Y6;=v)B6sdq`ek_-9jF>^QX)WL z-H+?LVQXmVp5YWVcY;ZY0HO4qXzA|1(DGYrs9-p?AY5U9esANR>@$e=23&(PLmK_-kKfqf^Mwr}wQ^3421Rnq+w z0##V|;~i(*0y;PA6S*z+GhqY?tk$zL_oi8-&9ajRe(j+UsKUA*yA(WGKo-*-2Amhik&xJZm!84M(|mR3aXKOj;g+y$|ECXdb1DSSP{gY8SFdZ z-oe8^)0XX%<+#SfypTW@*8TXMlP%X%WWhwK?RO=ta$!{sZ+kWE#)p;U;};>PwF^`T zRADVk(^lPCOHIa1kgN6#C5#|}9Uk1LzhEsL;jViZ?z%?;Rand7b$7{nYQ{dozFfJ( z2ol&6!aWnMH<3$0giK0kqY$XV$`rrj{q#mUT@oRu_HRQNK>|BG*k1ITEi^GElHKti z3nWmbo()Ey{fTb0n=G@=pH$8UNMJ3Czfs2p`LB+UZ5ml9-6Gg!q4s{~>Ch?BPD=Ei==3h{3TrQ$-Yl{a({ z7SrodQS)Sz5`oWEs%@IK-%fZeXLsYPQxrl`DelHILu|yv;v~`@@NFMNkicpi--g$* z7KbYBqTpJ*I|HGp(A87B->AB1H+CmEv}FP!3IVwmdlmaxiQFzFH1aKX$^wBInTD>O zn#WZOVNs=oY%Tfj4kP%vkY)0_$=`i4Ha@bHA57fqj0CFC)l<9YZ7Ht0TFHG*X5wFm zP$d_|+*fL+v(A87hCjT(9E;vfZWF|0z1Z4gEmsInKv3XE?IUtO? zKaoHcx_WA_)>sM`t%FR+W`9wPAc1EQZTplDhRu#1vffQsl|U7^dUAa?Llbi^^^oN| zn7{}Uc&5_A8^1E%-}_E>n_NpJK!vWJocnlJ5itwDmtu5HlM(?!IU8!nD_e=m*8(Li zvQh{|1rFNmQ}o})BC1V;em<{1&bj&hzWZ8h?X}lld#!8lXLj(60KaxK0%lJ4 zvTFDL;ZF-QuIA5tLHhAs^Q~=zYaPY;kEfyB?x_mtcR|WD^rmS;QTn~ssUKnqs6e88 z_d< z?bWIOu&p5BcvDv{l`wf~tr)O%p$oPfdp@qsSSTNB;yWLtev%^pK6lakAC?Ld$1iP^ z>HFur{zs{xYu39=neg6Tn}AATV1exNnB@5nO9hF;`g>&hWXFmBqg2qf_Wc2w=yi8O zE#h;VQ=)Xv7cUux+9Xx~KJjuG>fEJF{`Xm}Yxk?8@grpAPuvuy?0r{FmH+)(gkP-~ zP=ROjzxOM69SC2Xl~M`q0@--%IfuuEg!cAundZxUYn2KT&;@%B8v|a0zCNeq<9eQP zW3ES*fY%))x|@{C^p35rwMqpE=-Pbzj7&5-sqC{R@193Hw|J&wGR_jqSVKp)^)5!Kn3AM4)wXLYseN`g{-^grNGvi) zmFZha|LZ;oUA{>XGBIjLZ6c!4Nu^Yht`CMH50At0@8+)up<sUWer zPIc>=Th;FEuvF0XEbWjSPiJ~<0^TPAP<4xL?lF!T=h+bsj-rr&vHv>(T{>3PJuzuW z?du#WkofQQfTh}ax1Zd@A4m0Pu6edp@Y;sN`+3!OyCNH#TIU=R(AB!*WI5jDx3vj4 zr}}bntL&=(NBD=Of<*nJyJcE2v-ao%O9fs3eZ2amzfV5agTFjbS-jP+{%a zD=Zas!8T-T4#y>T@1#=c3cg+WPsc<^bW1WSmgs_4wMRJEccBYDm$0SM52>E-_WMhL z;2n9A_Hv~ZV|9JL*7<-6B(jfH&v$iRp;`p&)n0+s&jagA6#uaALc%b+n(kDls1*aY zJ9NS461L`gi%-kv_K<}eGMrsKdrhS?vhboa^1p9VjH(p_Dv-FhsG9JiGbc6%oE5uu zsCM}dANfCK$ndTYiT@r0642!scwDYWNVhSyN(B{2z&f$@fb$O+4_*Z<0ToEt%U)DitK43yv{t40u0>_i)%NSpq7MNYy!{lzMw~JBM1Of&_GJZCd>tm6Kk36oprm zO=P5e+?>|z)%D*?1&Q_LZZe%0TKjGQO9fqUuFb}P<<%ciC?7XCVE}W@vjmI*3E$6~ zWcqbK;eWIhbp5B1L5ek>I6r@|8})z1Xd|I@$AGmU?hs+xcbBmxW@ zDnEr*&pQ4)0bOU$j8GO%tUil>BSh)gQjd_1NhwkKEx9Qr|7HoOoPM}bxjLtMoT8=u z_mNlvDv+S0lK%Za#DD~J)zsrZ5U}i!roaC|>q3GaNtD`7YK6bmhbTkg07n0^B)MP)SS)#hf@6qLhjT5y;L=|m0i+x>HOTg!{5&!Y(?6-Dyg+47i{&v z#rXFbgoJcuNxkOpG2pSFi=HRxI{XhrO^=h6nx6RoP^$kx{O8f<-}R^|q3n|SlvLxt z*Q2IXN=cEfYpJKywAH`+!r$8J-wGrsDIGzk|2qL)HEs1D2-u1>gjiFmf7kDCG5)PU zqNap0{oe`bg6D}PV0mlKxmvtbC5iX zmPs@HpR=rGBJ5cdLqHc?Rp+=ClkH@pbx0I}3M9I<%#~y01xYbFc?8JBI{OHQfG)W9 z&T%ifWik=FIE+9A6653l$T6N4Nh?Krwr-ILpXZ?r0bOvlp5rWj?vROtks$;sknp1` zg;HA`^pRprjVqCf)fqDx0=n2;fVm@2$i$O6GYC{5abL8MV>oT`r!m?GK9C7~a|%O1 z7hH|zIP*pyWa7?hZvqua#LyiYsUCg{q$5@vst)AD-ZzB_* zpAKON=wesTm%L~%6a9w|B2a;ZA$@w4+REs?^nAYlc^8?8pJc}n&;@sBIIey{cbV`q zP!gy>;w60&mSXHI@}@C7ocqhfhkPrBfG)VF!*Pw0kxaDzY(by`iFNeZS&A|AthAPK zFxf#Sg6f$v1a!e2A&%P>=qM8!KROVoK%&)`P1P~xOEK=043~+eb&VJTy5PPM$7LLJ zk%?Uwnh~f#q7!|xkm_--mnV(U(sH~^v`*A!28i672X^fPYv*j2lG=m|a3+_{KoKO33nYgkcK@Am1Y@@5{QjF%;M$;G#JtJje zz+QKTfG)V3#c}TjM`W4`rnjjZs=tD%8`2hXi!NT{(K~*3`UD z&s-iVkZ4W!Af*^7`qFM+R!!^vDAYlafG)V2z;PipXYlZ-4$KM!B&N|_QYpqKd4KRx zO)vSAColwb!Sx_|1}9ec#8La*5mX>?mS#psG3MA0rS-6?>FstK6Bq)z;Jy)^Wz<|z zX0tPx9VJK@(JTuo#-9z+?$W86t9Iq@LWY1YxH83YZ)!${lJs57P8B2^>3)k8V{4)m zV`t6i)7q_!A)pJcWzn)ZSC4RoC6^FXATgHa0Z1{L+_a}LcGrxe=8fJk1a!eQCyvXh z8L8h#enC)y#8H}^AjMcFuc}4X+zo8wv;;^%7hIX*IK7%Xj#;9%02N3`_bw^Mm+=E= zJx0{r)!JNa#t_g2*RnXytme)+ubzPc&4?*gjt&d+~zU&W#8sMKBGqHo3u(RmT2l2aW8!BEhJY@(a?f!moT_IsNd;B{R3LHjaf%!x z;Hi?v2+FUXExk2RG6ZzN)lZJ=Q!^vGKFLmi3M49M#*I{u&vXZZj=nXszWCvT7y`QB z8Y#y$+fhBUEPggbfC@uw3zuVj_+m?A3~g0Cdu@DS6hqhm7hF}P_Z>y`3^}r5i~to# zWL7!LF@B7cR%b>*plkee4G@c^N;GMyT_3s3;|s*M}y|r$x>~*Zv1~&eL$I#@n}fh{nmWw{iC=2(D!~1^lQiE;`ghm<$>p5YPqp@i=btxDzse>UEp|OM*rl6-&q6ex^E4LR!bF&Y5VEI8E+l z{@>!{SpQNWF(ELiRHEmdl<4d^&b;)uM+GbaT`+%w?1QiGWx_ebn<1bJ=7DgW$@cFuVQ=Fl zKm`);>Y^(X&FaX#+;pS|LqJz+CcorbOcR-~aB~x&0tt9E)A^-I^;MhTK2(5L>U)~y zE4Aq0V+vI3sx9dx#~9VdUVsWD9?~oei8g5{%`zTx-DTqS9wkFS7rU!}!@93ba20(7 zs6e8G=7C5tP8mtFrSbkqCQRCOWeDhk88;j^^3njAn9Z9BP=Q1N%}9}A{CFe9n4>pX zChC1{#}Lp3^KvNBV0d*sUKt5cfkdAPxpIu~AUhhvIm%5Y8re5t2DJRJ9}#dw)$ zyHi_$3M3BDOdhEoLst%@G1|=Wl!x+fy88*YarF*&|XIxW2}2M4HJV z#rT~xgvJOz9xfBtkIiQY=z@8q95>B5QYNPE8H1n#iH0--Mv8Gve%ela5G50*K3X#b zbiv#fj?;;ZmI-$!b0!xY60K;)jTECGWjL+JlfoF8Fy2+4A)pIpz|hv!tiCIkG~Ulc z1rkeW_Kp5;8QWpxHuFj5YAp89I2 zK%zCx*_UD@pOseCen(WF!9LFB3;|tihEPIHFVU;ARzn36ujo4hQjAMIrPV>Fnx5Ea z-x!8~E|{IfaRY05d+3SzYN$XWjb=wnF|str(ipRAuBbi_H!uWr!Hgu1YgKdAYMjbb zLj@AIYOZrr`JD!fnvtP#&tisvE||kacM@wxpUh)K4HZc2q?zPWJ)-wYxluPXszGSaau$ zdS%2A&;_$XIc`wR-P!JII|3C*Jf-h3NiqI9CGD8BtC<1h@n#GGT`+f)?s?VBG9ue` zB~XDx1buHxijnedGL2zZGn3g+(T5?R3uc?r`F_o8$z`vSKm`(dG;30d(e0}=#~)WS zBTH#x&k)cBvnlCwZOyDN%Y7(;3MAlrI<)3fs-M;VdL75?hQpjxsYKErX&x=s&Q%14+Y6hlClejt|X z(a%AO@vB$$TT+$FBM4L=0pFpZnFDW93eK+49cs1 zR*SUpB2a+@d{2kt9BZD{dXDs92i16-dBqp5uC1S&@r_%!Mb$>FB`S0KD|^T>fE7 zyz;nK7@n;az^mUZR8E{b8$S)4%qOJoSJJ)hN9WZezl;#Bq&+}m=QY8X?xyg2w0Va*k_ep^4m?!7f?YifXn$PIi?*XfL_-^_YAsoiEi zAhHQ1#aCC^U?_`o$*@|G^*vp;&cq+;4mES!6`sb0nf%2uw>0S_jet|n3 zMOv;oE6&li6tp%ggtW6sX8pb;^2-EE50%?)B$;j8x1Ha4UZkbEZ`vI9 z%#Rk_*R?}gx0B3%qeA}N?Ip_gcazMzTJ7W$62>X-_-czI0t@-ik0wxJ^1ROE*a0il zaV$?JwVaH*yEakXc&LlQdrijEPE1ghZqY@z6+!sAudizK;>PrxYx(Js4h>GC2n_{! zpE(?F@W@fEyju@#h<3n2_bsa7E9;_y0S@@<(F&DkW*tg&wAin98sAL7YMziWdRVjf zOx1_9pZwRc+IZ*4>8ko=-}%li+BoPyvg+dUZ?xw2mTL940$U-reRHz&N*mlQNmM;( z@rxJg8R787ggtHzv7!k*2VW-Z>x+l-%z4n3q5tOo)JRT zR~z+ZPnB5EVyEih$(Q`&hG)bJZT70%r@!XY0?vpZ9Scql2FEoq9QmFP5)XCG>hu2}OrRqJrk5#SV-hcAJvS za*k@0?oO%Xlj-l?b=H<@J5=%qM=n!+E?QQ4VreBMHg5J1)BBqXqng+e*Q_M7V~Z_S z&dc8LCv2`Yclonr5leIw93#;Rj>!eu zx46GVb-(ot)rgE+e18KS@j&@})rjSHC~h|fIe87?%vAaJ~y%}@^NZ72Dj;+uv>iEaD_DB`n@^S;h=#i&k)74F4qN{kIX zq&{1aR7=t>@ozfy$E)46#bc|b>*MIk4eE|9 zoP>OprZ8xzG5%taQ*tEuIDbsb9B=P9P?h`h6hm`daYme)?Dr5#vYw#(#|-d?=IN@j zw=VPJ`|D#1vq`FEUoPopkFL-d4lkY6x+bH9B_+DTrS)3a@BL-lyJ^Sx zh=8Ve^!1^o4;!6gX!jK>SvS(=*$k`-sZzz+G(r;{B5-0iPPF%Ff^HW?;6LdzRNYoK zrK9NEhlu2j>4fs*IuWQqVso8D>|D}NT;IZw61_Hfk%u|!QQYWb>Jaxuc>9Plam}$t z2tQkZ@0p$ucdgPzM*Wsxoi10!3H9|T;Sey2Oe%SeK0n>39^7Ou9`jeW`1N%?)IKZ} zzp}~|gKpG8xlz%0eWwHBk?uN_xchKA;l~|Azuw1T55;19(!L=MYNLr3`Ygmh{Wv@% z>NnqK+5$XS{4UlV^_ABAiTO0LHTEh}2sRihkhpv$9w$Ai5?gKgL5Y+1n~{U{kdUd^ zgJ$0ujdwb_h<|On&bP>L!|5k&#iE=FerwD){LbA?^wPUZiFu8K$Pd*Dbj^4^8d#Bt zizmDko%S5%f4*Ld(>s-mW`_>&+h-@^up}+)JRVb`fmwG_ruhYZifk;rT^EYIGs=`M zxq^$;_3KnkgxJnon<`# zXdJe@Q>dJnmB3FL?}c^d{8S#f<4cJSx1)&ryI;K0vkp?8*@@3Ke55!&xLi@`R)`nu z+ohPk#z$$`JRiq}dMTUfjHh?!U#DY;soH=ac%4Hf+B@;p)Ad!KH~1@kJ{4ly-Hlb> zZKo?CO?NXqBFV+ALwM60&Pf0Hc5J)sib@>(Kxt>b9T&WOr)vK8o$|@XJe(Zf-sY>( z3mT*3M;PgTYXzTF8jsRnY{Xyl3dHsgeE40BH{t=ai^aXor}Ia4WZ>9=m5VwZ#gDT-SE$LBA?;09QWMY6sLDPKnb(2(Ii`Y z18@082X%aqip6=ovAxAnUehQQ-_ujzu(PN6l^0X6u2y^8YTz+S*v7H#A22$vOly5|MKgPO^^1bgn>gey*?CT_dDIy0aJHkY3^)kXOGf8 z7s$U`G!l^E`2xK6i>PvXDy`6`S%;B?Pft{?U6a)*^>@gw-b?$VsW0>7-!{9g5q~WY zxBszA6_+aQc{OnfCbnNUm!_X9R`0yGt=i?*8>KjB%fCA&TcTY9v+;Q4R@IXrOG+Fc z)k6KKQH)@;!hjD=5=6)8J9(*OzyER)KN?p5ZqR9@cyL-F-z!yzp22zLQ;AE-RTQeR znD@`wgpV9)E)%^kZ^G(F&E(&^k~iV_-c5LqmfIC{g!>gi623U0f{=B5v_>Ir)oKAf z4t+wNSAg42iBOJzR;CEqvjZ!JZ&F&GR#9R~_b3v64WXQXQ4Fz1vk*_y`a4b64%$VN z_CL*0x0WM#cw9)>?A?j$Iao!E2L)g9VF>7YLGNRq^gbx|UTaB9bucBC zL=HI5$J=Z1P=Um*p+$JukT29N{W+u?M{YjL;pasCQbGc{mK`X*3d#pmI^%ZM@=AE1=Eei(5!ScW#b2l7yX#Ks*v zaH2zX?knB@ITuD;PsStPw%H5;UF`X&vYkgd)|-QR{qf?V0*Rj;^6@BfYfbB(42>Y` z6THyaCmsv|U9d0ERbGA;`P!rib-WtMrzp4KbALUNkM;Ux4&LK&U+I5rk7DtvzxP2QZ7Y8vi2U4$(M;!fhJdd3Hre=geJ!~k z(^Ze%p5$ubFQjjo#B*EM;EHFKeERK8id9F};DcUPvg_ud^?1ravl?RdnlU6Sx`A-@ zR5Jgt%}QLifahlgZ%|nEU5P~oRDZixQVyqlQoHw--_6|wrp#q8fVN3A3rJgm!s&n?_bl;A`fZrky z6-e|9U4Y{|P36P2rL2*gHUmh8j+xLhbQwcH*Y}_WxL@mlni!k*@uXP0t8ll~G9D_B zm}x&B*U_I@LvWXE$?@p!!qy{)c&I=krF8_J^l~=8qVFhG<|F@Jlr0|5YSbz!3#HC|F0O$ zzqKXn2MiYc_s`>@0txH)&iK#qiMLFPqorE& z)qo^@a1stxPG<<{a=UJiFMV236XW=X5_R(_Gli|@t@yoG_r#|!w#iD&Yb_ktAzS`E z^>;nIw(}PLl){h32zYr+{ixLp;p?_GJX9dj<8wV6KX*$_jDoPM>Me9%IJ4PQhJY?R zx6Ziz()D~_ZYGVfUFWVk+0S3-Tw={b1rmoY8Df{>%$gVr+PqOar~3%rgAqeO*UA2! z@sp41Ylu|cc(u4WTnJtDLb>$wGV#gE0$CX}uUK5&bcg)=&h|4R>72)pZ!?jWiqlL} z=S-O^tSkSlgbF0;=bsVRjmoQuG0ZGO{owL!;Z9wShXi!NR;T$jziiYa3ZsN~BSa;f zizFv46{lubmyq}_6%>IWKI(TX+(_>$j*ec6E zo-Prs!*AhU`#bUZqgVpEicWNwW1z1R(W&ew4zpgzj~g9BpaO}P+RoywMxRSUV%}52 z-N;y7(4ZYZ?tC;uK-cc;@p6m>xgRJ|UfM^!VCpJ1_5n(mxG;S5e|pZlJn; zehPmxbsm8VB!(mxh=O6g((J?2V@|hp~2~;3) zcwuMEFY8zOc$6l6j*9YosaE`{P%fD7%Mj4@FtD>6!_r+M?iqF@5B?-6rw?)@1KxRI z`xBw1w%QHR$1*S3^-8B98tUsQ|8_{wrNpgxW0DZkl7BF97(+l;S|0~2nz)sYy;zSD z;ad%fUwM(Ta}Os1U0kaX@^J@Q>mZiMp4^mlzq?DRyUmp_3LqwN4leRKBV?69$mlDq`HObu0 z_Iw?~i3|ZvR^BmOYU6 zKl-QkB)mzea@ZIfhJdaEeIw);{1a*A?#FKhIh`~@saAC-=R;#;WzD;0C?q5T&+eR5 zYW}z>()gYr|NH8n(*AM!0Xw3|C{%tA>O!CbiN}gW{Iqma>CSO2Dbd(?5E*3NP#M&= z14BU94&y{QM#UJ3`0D9G`tR^ko_1_bcKENv!@lk-O>=9D`ns-^T^mNUMUbZVkA+U; z?r1F~8DvPH0*TT?$uey}(1^xZGGi#oy{et77OH`bjDVOS=gE{JJl!2SQTB9mk+nL7LZ7`2~ z%YLgeOpRt%is0(dnB?kpCc0HbiA9a#Nb|ly;@Y^KxXQgqK5o5LgHcI`B0O62w5qw! zV3fY9`rp6r9zuy8Npa-Q<2|C)USA9qNaQ~(!t)MpQEliZy+7FTMjWY}Hc52esKF4> zWu~`Fj@|b9NJ<>5iX)pQq>A;AUQ|H^5_jwD!l}O2s*vGQj7dM@$jsy}qB7_xLqJ#E z7Q68N9e#VhkCO#h$R3=*&;U{e! zMQ%y$7(@Kxi1*LAIBr-2CI%$B>?^`PS2e`r8d5!y`q8|S&W^aHbu>dj7d$s~{c2wv z5jq)SugKpbR3H(3st8wPUr{|ZkYaQxizAwa8aVgX4~Bp)cy8#b^XnLr(ES588!KR! zm;&7TWTB{0;(!(z7vg@|2gGE@5$I27A#Q!AP~4a&y`6d4AeKCKEytZ>(ij4|V5`$F z2rP^xb1$66nRKTIDv(gTEyU|fGemWFsbATZ#uCpjrTEaR4h#WZurF}j%z_wl)0tDR zSveHLvcozxoK}ES>XwTy=1KXY7FIFjn*pbGdaxNo1rpmP=41DZr$psE>HP;^%NSy0 z+DNUnb0R}P*XL#hc%(&zxL;q2(M2no^!wdeeLi_H)_%MlN4(I$LdX!*hpz9b(?5#m ze1;<9COhz~mrumrU!?a3y~ae7`QGi+ZH?kER3LH7DIcTCCt_K5=}Wh*gQH2nr>5$F z<+~UHx?ljpP`L#-(J${x$m+_GVP(A z+U;r{h6*GmFU!LpCN#$L4@uW~Y*{4nGP6?GomjyT&=sDMhaZM=xJzFtzumii6ge}n zpW5K(dJGjvwC=qf{~4@fyilO4mR;^h38jF??K-6iXg3Kx~SV4AIDIE#N2y1*xkA#-ee;6 z_VVHga^AvDy=(kyhJY@3o@idi-3VfNdYC$7?jh!UK*IULHr#cTF)j~upfO(SM-toe z!Rn~Wy$k_eu=j8r8ZnQoP4`qAgg?gbyKTWYuG`{OMLY`3%ErqE_rg6N2nel*{ zM?TN=P~X^m2Se9|(ri3on-xCYz^)c?EPWpFJTyUVyx|tpx{$cpcq{G|-2+csB=xIx zcjl4c*<;nJV-*YmU9hF;+jm~!h zP=Q3MLnhrfbi%_2OYbiI(FrHNw)v^ge{0AP(6z-S6T2rn;pv_dQRh(@8TrjiZEn?4 z-6nB8E^EgpS2l8+#-BryFp9))0JrRCh{jGz=$OXN*-Z&~2;MSFOc8 zihXftS~v76aUFi!!5g0(Xo*fVSdW+Xbi&VXnp5H|E!Eh9@#=elCTgfaqILiE_~3_0 zc-6ihln96mCk@VzR67^6S9hti1~*?m4cnD;K@IHI;#@QZ&q(cxO6hMM2RFRfL7I^@ zFr7#CPq$Nt`*cuG4M@i`hR(oxr%jP-1J;CIi_}kbZoVlVSB@FVTh-S(UtUpLsUGBadzx+N6&q>!u9%ak%5%&<>$Fl`` zW}b$}ewm1ywv;jl9EU}b!#Z`Lg_XHYQRmWBtO%QhCw^;+TD(ie zak>-ng~581(DaEV<4f%E zr`AsO%4TuIzH>jEZkEo}0}=&X3ikUFi0`PSy={@ilBK)6aCzi*hJY@(OHNmc&czW& z6F-rkY=C#teaS>)Z=8sJ@cIjq@y>Prc#5crU}-tdGcS(3YjQ|zq-)320}_|kCgY3a zrs5szv}mbDWyBGZUM||*9>x&R1?xng2kG-i(YhPTv_X56i$*2m{FpKLk>V9U{#g<> zS~?hS>i>>!<(Z5pyc&%g8@}M_7qh(LNLh9$zu;p_MuEg4-DLc&pAt`SctDAH^r=Yy zNL#*qOMixduBTzicF7U1uO|9+!e{VG|mh6Iv{1eq}+=mXUpCyUk(~5LIS$j^YQad9I5x)O*NiZ zi%@~YQX1nN_QHD&ztI>MUc`}KFSAwFHWwKJx?o?R@2jngCUc!m@n_f8K`{RU=4IU6 zn~b*(>VbVSFVPrB%VS8u#ALp4++!XpkSM3mS(k<@@nqdIlsHlqL*8^=%1^&}lOdq% z`;HVm)XWY)alAl@BDy}ky!U*5TIewzDke=*@YuM)xYG4Hb0oS3kRD5VyqLwmSMOyM zNa+1e#+v(vVEvOfXpE3vu|#vxc0M$%h#{a0_86LTXA(!U7LDX*Oj*K11rlE8l5y_6 z;duL&J2b|xF>$1gZ-4%;&wdO6U2IP*z7$FJe!9))r*uOwg9c{S!1F}&^hZULUh&!d z!^H8c5p4r#de3Jtv4bvupmfR7;CDt7VjSB^u_g>S6F2G$L6 zFVn1A#BLHnoKko38qJ*%JQgHIr={U(#2DM`m$G0yjUq@z+!OwnofAVq7i>fNe$>%O zvhD3oe)Mr$rgb5)%rOo7J#K@G)=IlSqjjT*Z*d`?@VO5|Ko`t_qW7qi;iOqN2hrQ=t7aR3m zM2XltbIE|>gZ%ggOVC_#3$Fb6Kvh1aJAX>K1)pvnBYs<;sFkth-!Yub_DJL>w~a?I zmkScMwwrLLcbVe#=VNG$?SI0^!Lk&7ZUsv~7t9vpI920$BtbuzCvWGXZ)Q0-BEeoX zT+)vB+`kp0pb_HBeWpAtE&cM>-Eb0SK8GJyIFG3ZB;0#s<8r@1aYb1#TB>n*;UxTE zBtJbbiXos2)`>n9y_`q#*Ld-s>C=#bunpI_VktJPGT?(r4(_zsMO8JdDc`|67k?Vv zN__me0gW-VO$0HH^WcpqPC-zCgj;qlz8$A8X2j}HB63PJx!A^>pYgmCI;mfX+vE;Y zZK+IChP5rg2`3k;PURIS6MN<3L)t?W-}Q@>^v>BNniynR@+tGWBd9>a@N7QLsk2g* zHB5R7V%(c3k}}JR?-0_HA)sr``h5JV!FpBY?h;CvwumD>SGD+oXR`QQ&mw&7tzGGx zV^0)q+7;nB9p;xl`J|_WS%@?v#XOcc<;>^HGB5B@fdrdv_{JudY!B1p9ZH|@P=Ulf zVJB{y@u{>?=r~#`#l0Ak6Qa-Gy8e?PpbKU?a@_KWIMV3oPo?g$Dg6HXMfh~xz!LSy zj*9Kaig4-0oh5lQ7Aat9>6_IqainTD$M2vS4p4!_-QXg;(9*JWNy=rqQ*C7xN9t&5 z@|@OchJY^EhIC~3?nbt3(-h{CAe8iGIX;Mb@|}ZImFdIMuz&mh{DVDxl_N@5WA9Gp zeE*|1wB}ohJK5N~u3)&RAA$-bV0IF{5AGXBRF^b`;jddV1mgl3P#kwSaU4kwtS2nI zTgK!@L4wV6TEcmdhSRhJ6J0tMfnz}z%&emK^AFyn<)T#t zm2`#PwJC3>NLPM|%*1o`8}JrrAgy`JbT6VAcNEnRQqR&kc-6 zzaFJImZ&p7q02wx5mX=n&l9~5-t-`!<6k0+I@1{fx?l-u&EI>FDOsP8qmMO$3M62w z)0NcolgP1I?~q@iAwxhHTk|_pyhz5(Pe`*K;TZ*-O*S8{;D9$-Zd{2@tzF6x&}I5{ z1FrAVfsSs{pM_<8$$+%>LeKA62)>;K-`bk3j>QAgTzP}sgY*nqo#;HdyUDkA>zk($XLY*P=Q3d zC6T!OENwpN38I9~7HhIN?FXv7_y<7(x@Ihl#mjIjK5m7S)%bl&0NI^;4*8s0#KSCK zm?_C-{Jwe-NCF0(Ko#6U9x9N4IhXVeh13A@ZSgTQ?R8TG3Fz8)ax-q$rApar>mb@z z^A5})s|OS#qiuQ!Dv*Ggp!AEA*)z!^*KH`Vz>FcFYeN5Aysluca{q4WYiapfq2xln z927h}oXJUrnYoarrFs`i&g{=X-Ust}s6YZ{>C(5i9YTrE*)=FkM+ZRyy4X^A?43ip z)n9^U9jt?(0tuLXBs^Xyn37BV1?>Isf z**~WZ`tai!LqHe2Khp0y`^J#gKfdu6*=v~lAS7VcH2q#U%~vv87seMnp3D%?1@GGQ zt~Ni8jP!Ehe>`i-+|MDwW?)CsRfE&LcPU*XZYklhpzD02U3i@B$V1;Q-`+)6qq_K! zzji%A_A?TBIFiBacxJ5Rf^w#iqKS9VzO5=|OoRly3TT%1Oh3{W-$d`n7$A5o=z@1U zy7v0YpM1*wK5-fk#EZF~7J1mgntV459WcRKm7B_G{->A~Ec zApv_Rtw-?;;@2+&6*Qc|5YXl3oP&4v*sMHOyqR8uo9>2^Iw8@hPSG#~6-dAyO4q6D z&mpD_C!sMxV;KUv>~*%|9*1p|t)22{jDe@-k@$#q=#f(&1QkfY87C#eBFGR=O(e|V z83MZCT$_%f(a|Js+ETvvtk%q&8WQkL8@lTJBAQ(CY0ppfXvGlF1)l)u7n-;+By`g= z)XXr8nU}yBN5IH6xbeDr{PqhcY0a%#Pa;N_&m&KRRR}7Ofb%Z;Hb=l@GW~7A7G^0euOcS&o|+7C;o)>(B?66$}Ag=e}>j zdYVg>I-{@C7}>jmi9=c>8d5(VK?M@<%+j2@#v#OifhQ80E@BAi>Xot$YbQ2Pu3B}U z#?Yg0T6o^;fV!>sM^J$Td(IbV(4B^Nb&>Iy0EU1r_WdZeZzMTBY&EZQU@(FTB-kgf zR*&gEXRN^AzwXEo&;{SkqF+{x7)&f$Y6_38s!*ff3vkbv{`{qi*Gf2(y*)e`r_vd+ z&5kNs^M&rC$hUTtD7En(1QkfY-b3?!I=GS0?f227oC6F2T{@=exOnPE<)p7aX^c;8 zJjlLor;-1wd;}FpFujLsp5RHMeyY&(eMJlbU78Cv;Ag@f<^4PKd5b%})sN&>ZbiS! zwjiiL0`?v{hs*aTd#hHXcjvY;1a#T>W#QsH4`rutZ5m_C?HMG;ZXOywZ8d@lBw+8M z`H2f=663`a(Tg)I0bLqrv+=rKd5SrM8qyeZx6US&H%yW7l>`J8NWk7h=RObT5dYsg z=;NA23;|tm&4G?3Y4eEA-7NlV;#33`NWk~}=$IHBK|0)W=bLtz%n;DUu4VLJ=R!hf z6V$ZjJ#?y03T|b&TzR1RFdoi*M^9RfBTRjiULUP#%`0bFk>~T@qpU<-0lqB>-=c(b zU-}hA{qAH~>R0sTaU%gLkZ@WUhFyC;S61|rzMaswuqSCS{VNKXTc07I3(l75Bg?VD zL|IvZyfoN(JFF9oO`n~^9Y|Ar1sSychM)ooT^ITWPv5%A;D!;jR4+a&2|0Tog}2jU zN(Ei8MQ9GoD1l7Ly@N7!HJG-7#C)4Y_^#oG(*C1X(HORV{mBmPS7<}Wx(oqb?0cz- zA!fvMkgo6(*Ao;C0a}5$bhl#t_hT;js^nHEhNw40NV3-mdCMZavfz?kJiGP=N$In{;Nmq7{j) zswX%Yv}OqCV&AXrea3`5IjAMHS>IBC3M613qxlT?TagPl>k3;-TQdZ7!FPM<-gcEK z>7>*Unl)<9y!8tS_I&6k>yl*vb3SYu9CmC7=Q#%TD-oJ_r@ zDZDPDJq0L`VCxY=|2rlPTmC@zX8b^qfUdip<8jc=j$)54`83A*Rfv45e1)$2d_how z1nkFjEj()&89C%Svg!PgA)w2D%2K@fdlS*yb{&n;vimS%ujh*7e zu&hKW#><(ccdP#BP_Hb8fUZpK4S3s$2daQJo|M?xD1d~2oPzjIdk|D0@wMq%JZ*4} z?VRb--o&q&0c7B9FJ$Knji>yF^rs z%jDk$CgJXy`C{V79lYJH64BW|9xB7od5)79#ki0Qd!g{ohisThC{r z$7^Y?=$KI;2@zJH5qr`RR3HK4(abaD405n}JSsO|%@ELKc6&L_+;?0Q_GZ%<8;?vS zn^h^O=eryP6-dDP(f{sJl0P}?y%fzg*~Jjhb^Lf5o?!S>)yGHLUD8qM5baalg^=Hz zFr{b|o*$5<+H`>M?PiU_u5D9G-R~6hMFtb_;WKr_TbGYg!r)*-VmjDDIO?MzKm`)l z&y2@yH?2@@&nlrrpRo4mu4f(a_Ywr&~=%9>nW-KGEwKgRCDd{PGtQth0vEipF;%_ zuzvKNpNH*8_wfp$sA@4oKo|Q>j#Fu^iAy*V9xPgkpaKcDt*p-*5Kj+5nEQS+LqHe& z9tho=2(crtg1ZR6qOGxL9E1(p6p2;6zVnwHrs0;FIbt8nFZ_TnQ}Eu6S>n*X(z|5m zv=qdr)KaJv_lZz}#H9hgc+;Ep;w~%cJuk;e)}-;~-olRozDkAwu0dMfxT`+>dY4lr zB~(7W$hB4d1btzq5-RYxP4y??w-1(!fAP{=bj4G;lZW>df{}$Q4+-eXe(ZtgtzIT- z%z90U(`X236xvn@OAJ@W$A{p|Tcx7=(NDaUNf3U2ZkHH-=L0{-FBp$~ykFesDZSg* zv6}-KTi;aJKiG~@An~K&bbNT$4)MeCH3_j|O7yB;|9lzeB#B38+(z|anAq~5UjY{X@#cz&_M|XYY zN3NKSn@lPbk63-=g%#mA@OHU)PWLk<)^&3xCGIVRey>6p0=6`y=}OV;;iS`OBVq9G z1xlzuqSpC1GK_4zU?kYy7{HVSx)x`K;1j_mVn&{HK8!C6B8_$136D&&c&I=Ewjq6X z4jo7=9(51~3}}EL0bN0!fw=AH3^DfGJsM-JsV$j&u#52Rssn-wBw(x4QpH=5u4Y|@ z=bM%?1a!sK^TV%K1&dY1Qclt9dtJ%deU`%hZ>tbgAineq8OO{gD-D9A1`vf zC$2G)-agx8R6_!~&dyqZ z`;Pn|4sw!Wgdb@~4)?PWZl7Yu#J~D_VmqxFV($FwJRFbdmxs@qlL$L&VX$HbGwwnH zm-^vVUssEEiPC-W%N$Gc{B~bKyLlgmfG&7n;kfChy-8D}-a^;%=FI&A66VYN@wqyi z#EbOXbabWYUT?ym?JZnf@q&lPf-ZQsqicOh{fV)4Paz?78*?9oL_o?k{NZGd82eiq zMNjut68FK~g>Tsg3;|sO%L4KK?)l=!j?x$Ye)O>?<1;!5hU@E#P=UlZ&tQD@_ zwUnhd`ScL-w8}(??Yp1vX7KStA?>WO1Cg`vA#83hvc6C-fz)U)Dg zrF708cXuZ_uj&iR!+*O!bKFPK zvHb`Bi0*uRi98kEqbm8{%VTi#kqXgt>?2B`8579$r5ZxJPz?kXNUWS5iSI5yA;!Is zW_>pwxRI4*^@N$@2Qvh8C48NSTYM@Kn>3NWLAT-QBr@R5ca;CZ49~ES$Fu$3if>DQ z^ICpU_>t!|aq+9K{Ho8@!EH(?@qLzK)xTVD_qLFrGg41TqZ=|-Mub~9eYUc zxR;iXA@zzI2sRgnGRK0hrhn$*hF{CX$ed@Cxc}LiOnTZ(=y~`u4;4u8!$R?kDf>mP zsWg`OTMi*+*)4^4mbM5I&{gkOFg~xFC9Wxz@+?;r+mSH^Cc>X@K?o|4Sk-j~)_t8O zl1bMnalMNT$sN~L7-_toA)w3pVIa-Qoh1f2ouS0Nr&CFP{vv9l@fdfAS%fF=)5Ipu znh1`yu+{0Clf8Y(_`6S#$HvRd`G5o*wK>j(eyR7tuP?};JdGis3!WSL#L~%w%kWbVa!5d-V&e4nn1gi2%P&Sk~GV=Pi1p zNS&2k>q~|HbL*21FO7wvzWM_Eh9M-9`uNc=lCH2R&)ZI0S3jT`X}85#(0HiJ5YV;p zyALj!5v#&~_EMrauPuo+YAJ-)*A$=viETdv@t>LRRXWQKP@=N36Pfg(l~CEO5N{WUhvxP+@)@K?M?KH$t#`M6g)qdYlsGb^DXxCoO~r#UevM z7dw`0zcr9->DyHJ&TToZh-%uxvyNWk%!_T8oaq~BtiS#!-ngamZK??cje8j1qQ zt}ho*i^wS=R3LG#UjnwssE<3|k?zg`^MlBrqawO;Dv0^kBy_>AR?@M(GK6G~-i%gg zmNDP6ghVrvh{v~RiT$*tFCko8I+wUQB%wj>c=JWP=SP=!+c!u>Av{>q%^j_@tjQdJbi`g z4%I`DfG#x`hc9}c76&Yq#&(lQ!^y0_G=!$Z3e@lmq43M0XRU&81==Lew3gl&G5tD} z1XgGWN4D)zLj@Ar-lk7x+(&3FXMDEdy`bEM!EvovZR$@^I#Q2K$mqFAN(mWRlNU4`WlH& zy&+`krCfB$L5Eazn2(no4-;2R(L>#D&%vLP{l&*WbWy)i(HQwI7lY`RDrs+D;7DS% zO3+i?dITzvXxVZ$p4cZsY`nYyCA=mMBKviYBZV)=5YTnXI0T2TT_o1ktWSx@HXh{Z z`9kE{>ZBTe;}w4U^^kQOUbtwFxXxLMv3tijQkY(dnwwXsp#q7}ck^-H&;s%BD5)M{ zX>Mc?cNqD$yUGyI)oMdH4nCJD_IN0LA=cu7D;alhC7?$3;|uM_9x=~EzgTO z!=x{ToF48?Hn(1aez!lZh6*IuFZP~|@+ZHCjYTV4A7u#WQXEOeDMp{g_9oJ|MY4W+ zk>r#{yz9^}YWU3xcs?qZZ@^=(n2Bj;I#D7bW+M5)4dDwTGze560naSQ#jNrs$g>OY z*Y&*`63|uGX+5^+6C*b4VM=4X@C_n?*$YeeOHnBkMMT0P1O-J91+LwZQcx5V#O}lZlnzCa zR6syQ#Ki6vc0#cO3(;EvySqD{+25Q0InO&k9>@a#j7fUXuRHjqd| zSG;M5x|4O~)v4^hQHXX#yW12hkbw8cV;QSvvehfblnoC!ClJtO=(wJg^vS@qNoRfy zzuVK;f^7q}=XczoP=SQ_ta1m0vdT&mCFJ!ffq<^#E!L86VTWX?TIFFYan zCnSiqcC-_D)bzFP>$V8TQ;FjFXrn?LkNK|AkCe2oANT=;;y#4I&>1@Q&vvO6R z#}Xu<>*T}~vZK;~XKzuXA1xi`GSiiNy~z6rD=$zcwMpr`0(1_>_6<&hnMA z?6zBh1a$enOd~6N+K}Cy)s}P0kuc`6b%8wEY=ki9WfYW2{>B**rgKq(*|hntM$d2- zb}B_~^~y`gvkeI)C!Oql+lGsLh#Y?QhtgXhpsUy}jo=kJB>IUuqHk?H zk8RCPmFHb;E<*(pgZP~Ar+7=^dPIG?w+-T0r#7B)bHCw|_GtzQE_5Z@qAwD3HCUWM zx&(G6G1lrxxW8pIGkGvcev?)yK?M@K-c@$DP&voz1XlA^K1NEGnu{HvPZ7p zI7fyGB*ap3xn?q3S94f?&^ARNpeu6z5^`hUOI-JxI->t{aVE=;+$?{XGDe09Bw$(K zak!Z1l|YPV|nQ(!o09?%WX?@%VyEr=k;bRH-lTkVx#UCGA= z*ARPJrGutBRtdEzBnr(Jki?c#ahKzV`F-?E_G8Va{*?oUF@bxN4Ce0VI#j(%bk|R%TR%Y zgccL+-RC&{j2egAb7m3?J9c)wcTJTC&GIBr5s2sMBw=Gm(rk`~m#ZH?5gRbm0QKr{ zQYcrjELkm#CT3sraB|3b{;T}*{aK63dT9659WqoP0o!1{=C17^R_}Hl^sFFDAfQVe zbH@9OU|Gc<<%nhDWvD;`wy3<9kusirk)OyG56lGuy5M+MqbX=JojoqDkZG5*!q^!S zutnu(K^&jWjyWHbt?xb3!oLMwaNN$Pi1D`t0=i(ljA#BDEwTL7jZyRdCuFEV0+t@$syX5Adsf-V@#;%EIv&1Ib{cFQN?`x2-?0!F4Z8sZwk2KFkH^WPs52WGDG}pu0do*SmqsNrwr(q+uU5GVyXuEW6^DPbzx*QK&#-^xZt7H`bf%u2C~! zZZ(Q!txiqGma9hy1a$p*kwgA{aO8W4jXCkfHiqTB&iB}7J(EHO64r~Bla2Q}liD2h zSKZ5qVg*r|Qg&9HKtR`>PRoef?^YzTR*f^r@8`3eii6UfswEUEkPt^+kE4yBNwwn5D}%4KpZIAOT0L{4{rM61&*IPg#`ub}H6!!9TEl(Q~0lA!_#ag4L@UJU!7+gAQq-C7`^OU!s;el(Kp zdhIP6ERu!%C6ItCHhDJP{3zD`N=LaQq_;pomzXJJraK>VKK7Ginokq*en0}Q@#Le_ z@cGQ;K__|ql^Fs7U2xSbuiG1kvm@91~uE6XrAoO@W^H}Qge*0( zeKIzY4kd+I%U`8;$>o+lxEve`$h5DTqzH>-S&&?vOPI!`EH`SSj_WKf< zmt~4nx^}HVKo|Vx`EHJt{Hs0iU9xsxNT33Vq5~Pk{jL-7Y^2T`%*~BwqdQy6sjn|! zNI(}H_3<4%=CLgIONhLD!3Zr>Ac2Oak>%&iNQ#cSlB0WrC>EeBlsop$62_d+1xK$u zvYi{w{4EOQgg(!NaV;e3_%0#AsdY)XuDXKm!0lPgbJ{j}h`EC>c7`rEZs&2h(^Hvy zsv;k)H%b_vL&7e6G3hy^0{1XcM-vxaCNNE_({jxGG=YFF7=PgRVKZLZ7DUhWYH=z?(+K0g>Rh%NN4mB&|=3-J<2z`YK< zM;0)c$#W{@PQm8|0=i&yhnM!sf$ZAGD{_`Yr4aXl1l;Su=LbVZFiU(;ZhhmlKtLB< z@y%EK?havLS9i;4FDrx<@sNOf9r#|E%F)bp-CB9~q;moRU9gtm*$`icuzFoeI=$Kop_CHXsn*$H7TMOcsVb^3+zY-yWgq*c0sP{Tn&?7i-IAJ4{p z>p&vrv=RvDg0(Bp&+s{pQJWTI{5&V2-h~A0qw+a=-#E6uPM$Wcp|?OlSLn=a^2x9( zDZiuk6Ym0NWeZS&s5kZj2+2{l~*60DG<juxGP=N&O zqw>0aXDI8lrbynqVWvPpmz`+}G4ua|6B?=42)3Werm-S9xcx#36-bEv-JqPQ%(2;C zIcY|+KtNZ-nPf8i&V6j2rRJKva&t19_GOR!#(f!u3MAkh5`R`3c!Z_SNjbZ9wm?9a zv%vzQIerQMtZKlo5wvqGYqGywo;S3JLIo0|qZX3VfD8DAm)ZlUx;%otjlLz{ULg|D zHB5;i@7wd$hHusOylKI3W@~&)4lv$Ep#llH*VwK(afTx4lUf*MI3hG6Ej#1B0m{%6fy6N8|zpR2OR3K5*dnK{((vqxm?KyE}cr?4)aWc7dHB2C& zE2djM3AkiOOfRWp=bES}b}Ge;OxUoHLIn~z9}CE{gVyBNOEsJB#q0Cg*cofIKUORg z2q13MAl~03L_q^ElU!r^+Xt4hsZyy*-jbe#chhD_hjH zA33+jvj;}2Wy2|@6e^H_>rVK2sXW_4mib8f*V3HA{LL_rG|czR_l8f6VhuO=(VIQ( zg-pLw|vQt{{^_(#N6)+1gyq1kIEvX7f*<8g&>!p#lllPpe7G z=UqvRyE=b<&n$}Fcz%G`w2K!A=t>|w+jK!&^7&aiP7v=%mTA6>eDO}DP=UmrtU{6+ z(V83~>I#UY(eqgUl|{Hg-&FzuT`lkCle!NL$m3BKoWLi;nQy&0We!OjDO4cQJ%0sx z`Jo~IW|5h5YSaPI)}_y{~C8mQe#V#|Aw+zRe91ZeM+GMiSl>3 zWW&S<_}NkQ`v^9i#%w(FAfU^}E`ubFID?l>R=R5_xM~U&NVL0` zMGlzn!};yiuXcZzD0ane65SH3Phqxlm`@$%L+2+oaU(I6f zTo}nt?z&AbEr=Hg=<*IJBHlsGiQQB+!?;EHd^XDc5GgTBqfmiFZ}VdE(a(^4zo(X6 zmsp;eVvq|No4rOLpzC?BRb;u-Z|vl**3><3gt7n5-@skxZ>3Oy#EjZPzK8cUP8+Y5 z-B7dHEcxwjZEKISuL zCoU08nKO;pbuOkoXRId~-9O-5Cr5eNbG~9nTZ50)?<#-4w1!mroX7WCbmWBh$S|g3 zZAqr5ZKqIygt$(oacwC3G-G+$YL9Y(fG)FfE6L`IC3wIE^*g_OWjfE_zDOGpbd^E{ z5^!CPM$^E3BGYUiD}AwlDG<=*{wjxfHk^WE^3`WGCTtAr+|A&LbQ^z~%j$O=iBI0xMWF%-xb};FtKtNaXm=e-Gau2@z zuN%Kc&FC;TXR|(Ob7DJ%3M62uN+QWjX(V& zn7!M0Vsd5;g$g9#*TvWG_K#x~E!=SR8!rmaRflI^iD#^jUKhi>SO_-26DU+50m}lf z6EDRuz40G$qd%hs0=nW}^W3;KgYf`k^(30yM^UWNSbdT)HGx6}60j`rm1k39*dv!v zvfpp4KtR`fzwKmr+y}B%!m0LJFcQ6{yPTowR0twh(;d_yf&1R+=BMH?%CJ@jCdzt)vMsC zu6v!b$-uVx*x6a_g}*F_V%NV-pxLhf$f;iINL&wJg4emrD?hC#qdIFzd@#?Fcx)~C zGpQ%BI_b;_ug_7ec*GzY+`Jiu3M6i?Ur$!+bRnUK)GumaZ4_%6;6SspwE_WMuwTm8 zUzJC(b>*hi@X7!R6-a1P){~3&t%%?MTAV#=BiVvxkI1Q(u>t{IuwTl*THZtM>On}` z!KoA~kYJbBl7As}$xth`-@ep4g0;Lin3(o076|Bq{Zc*?mm9`HG80(~X(m4P;+Ak8!mGaz7HB zY)PR43D}})G$qyv?D>whWV>Tsfq*V}BA-Sx^=2Gf)OQY%S{%zB zHF!&&eRZHvfdp((c~0_Mv247TA$>uN1p>O@sdjv)MQsezvDcxvgA0WUBw&lmOS@St zySK!Iei~*W5YQ!_`gXKu44YM_5smxLok9f?utnwhcc;X#x&zzM-J`4p0=nQCb-XUw z5Y47JwV)kNdQzxBLTqaH_#U;VT>)(50kU!EyuGgGw_Qg(1+ zxy5$n>M3iqqq#SN3M7ILX4=Z%HfSB4Hgm$%ahvk*M?17x+gl)@E0q&IN{M#Ib~TUJ z%QoATE6Hupb2mQ(75H@FwfQ=IJPKbJV2J{4{e^2l0=`*|=FsMUSZ8!Qv>;#nRnXOX z$V6Q5d9$`v{wDsbTGW`5mxbo2tAAev6-dDHrqTHL2ayN5=BWN6k$|qTLF2Hq#|v%N zh!y-Ad1L*_yj3P>;(l5>gecvS#&}BDxJdVF)B8`^Q`8DPYNTuuM zTOobhp2+&OAxWQkP}|nEP&#U3O=d4h*5-FzC*6uMB!%a*wcT59;Dq(Y<(%Eq`x?PFiabR3HJL2w#o6 zaS&~~z9Tvt;wBK#Rhni<-r9`RCh4m85x*drK5(-~*GrudR3ITfUGK7GRQuNf?cDDm z5YW}@tQCoqzI!-!Qumk~v)o7j4zWes@;W2<)?oetNOPiq($K$l$g++Nf(j)5o$w$h zqV{|2EZD=Z;XYzF)oJL6wk#0|=n{X`^WlVcad1MVdo2-EAmQ}JgNz@2!hIe+%CGVG z`yongUD1L0W�SmElh0OW$GcLoca2Uv8c{LrucmP}!|!2r7^WyQ(F}J~meDe;nt; zI{5;9Q4gVTCw+l{uGaHqQtfz1`P=IPCwfi)LFwxrsKWKHJf?II*)&cMYqp%1!VCJ4 z1tWJV1HDd5g=>40+GBUhw(n6m(fRKQdVjwsYClsC!M`>0M>n!_OebYFIW56o%QGPi z-%VdMmXXQd=EARngmH>Bsn{^zqktUa*VwgU6P@^|2WsVNDG<;FpE^J1$2N_yzNM18sMjGR7V) zS??wg&;`FuUYFd^rC&$eA&>XsR|^SPukgLdiJ!^FY1U}auU^7e3teK%8Mkl{dt}fY z9gZo`!n|WJZ`ixs`J{K?X}oEgy07Tg{r>FxHWQ?u*X#!FFpIDv*E~!898EP&YO)%^FoUoi7m3wZm~5 ziLP3VFX^iLaeO14nD$>s)Z8>*h6*HLMljxTzO!TOdPg*N;~{~7E-`atlN&q_p90rOnv0I?m|Oj9MX|B_!b2%)i>}2JGCF zZm8G5_W}W3F#9IYVt!J?wiLObIvf7UP=SP4GmOytL#LhXf}E4|giM~$1#@)r9V2F^ z$>2ZT(Z-N&X#d82SiiS{*3tKv1l!&Bjh^9E9&bI$PpLIS?bVOu_!t*dYwnDo0twg# z^O$9!HQnyg6ODh=Ss{iSaU? z(Dm<)4XLr1;Fk2ioHY}hZl)gtdm;bu<_Ic~fORl0SN%uQdfi5$diCDO_fHv*64^Bi;Z(0=ljj>X1nvZn)pgJ;e$CM{%@lYhU!pu?gDWvI%hxHum^v zctYy!Z%)41mz0*zIW2v=Vo5%~8?1airtZRi{dzf_6*3V04z7cs0tqA9iM$=6D5<$> zPQXZ`71XcsFy#9Fy$lKHa_`fYSf}PGn=AjfZ@a}Nx+FRn9h2|LP=UnZ!49N0`JrNV z^(McDRoZ3xYuo_TV?(Xnp=WpUxS&)q-G5nnSksHxT+zqX8I_X%YFDDy?x}LwrjiqF zYHR4yet~Gt_KPx9AdwjCMP^>G#JBC$UBAn&e5Ml{_d#b`UXvFN_a_U@3~=kmm!*Q# zzU0q|c9)Qgf+4#2RDqhuEAZbP+R#53&DgtLh6*Ik+;StXp{97m&uUI+ z3Hcp6Lb>&?UaX8pE@+SQ&vjB z62Vdp%W=%~W@PAp{$&pvo#({dPoXq=aRB<;rZIvFBwz{UDYV51R_l5Sq zHWWQJ&k+ddg5L_yYp{L~?KmwE4QTmUKBZ$vwsr7Qw){RX!MY39c08|IFNNNA<8}M* zM>13(0qZfIJNh!CD;p0*Z@jAn0=nS0$=81Dt)grC4@U3boDsfSNWeNqqw#F}gu0Ny z=-8tJ0wK7Br|Vhyi{9t;?x!1@gl7c_vA+7%u>mW#8h~2VTP6_D1KWoQp8zr^4ruO4;`)UKexQ} ziTZksK+fMs$xwj=KI=)W_Gs}AJv9U7c2ga;{9Z81>uxI$(AD~iKe0GJ5^w4Dk`vcg z)?=>|f{<}`R~agh=*IdGFTa7f>Y|!mOu62OJ$^SBo!j|If&_HM?h7O-d9(3HBQ?A6 z6W1o}MA0CW(YT%r6-b2V^e4kLlW=mOnmgKSa4QyhI{+CqUoAlby5eUHBlDF7`05`u zt4e9HDZ5?R4|Q+9Pl5_0rnnCwA1b48VAv~8_|0q2_tE>JlNag>1aukx9zhoH-0C$S zKXT&8_73d95+8K7+(m*4B)%)dN&ovPxMuKMPUyDo%r-5Q(17sz7!uIcc+xmRSsvc= z;R`1|YaLkYSS@;xljH#vNWk3T{A4-X?kqRK1#M}M2qd6u^M=VpcVIDo_~Sdj#*QAY z>_nk6a=LFwpaKb)(VXvy#ccusUE>eUAhyr9;HHLZX1qrWWj4FHJ=znw zj6ekvFf%*vky-k(t=rq89!Fk@1jzXQqG%3zy<{K0W~J`ITHmZU`_QZ{D*bkqKn4C? zm^+@2yngj#hn!lXl3&d!B%tel@I2C?QyCuDLCvJ&;A+dZSM@?B-PcO+dxp8SgT0*0#XY+@~J{*Q>Gv^Bgbctm&^cJ=2F%n4? zg#rOxu;;|T!R)(q$$z8Jk&%mKs6Ya?D?C!vwVM8v#-IcF3j_kX#2(qPFN4{?zJ};} zWIG{0HT))ErfZF+&eH%^j*ZdHj0QpuY)HVbi`R+I`>{OOMO zWalz%kxBD)`mNx!2OrC@NYqvn8iF{QFm5s;)0ee?<3?ShXg#o zf##OQO_-Oy z4_X$oK_H+@JY(d+EnRlQ&lkiZd@k@r>+s6YaqDxlG9c{_;t zU2KMiHJvID&;`#l;r;e+16Yq2#;D@+TmltHz|#@;&92PDkbo|DDh=swk@ML(fukSjc?U@e+0=nR-G<@vbxCd+F-UT(B-AslGB;ctVJWKQRZftp2S9H3z zuRuT-JOzcXfLLtDx=eII`f15BR3HIQ57B6z*S2NFIWB1a&#eLhU2tZDM?XHaW_EH9 z6c}_sh6*I$nNJ$cwx-QlpTj-S+k*1~0bOurgZC^8o3I|UJMfW{g)TU+%KM_T>ae_)2oZ&=W<9F_p^8?VL$EE@SUH!auaOmplp8Nlo_4MwoL^rc6A7ra*h2Y<{+mUHo zIcSB)*}EqsNb~XF%?!8P3BAzwM;#GVAd$`KZm)NER4-HKwtcMi%KF$LB=@!#2Y>$;)w@4F(XK%!z-rfunrCfYxp)tR3GkF`qOtnSEyk5nN6 zU7`IxDYLJeXno$Qv-&fLfpTiM6Pgpy6F~(MXLs|pSOp!m-ro;%La$pxWpJA=sI1Ig zAfOAbNaA@1EAO~}S`~z{3Jei^?sdP^#~ZDTlvz^M|M$-03?8}14H|)#?W-@mK}g(M zm!kMjyjIrpt~&ow;c&~n@9!a~bxIR~fG$|x_&Q5TavyRh813GuFO)<`G~beGn^7K7 zw)wd_S2Xc&5ZUW90Bveuf;7i49{Vh!G;~IV)MZF9u9ObDkC}L0st!4Z@3w8};XhL? ziK}yMNY#Sg=>DK~2r7`67&srtS)cG2c36Gqsci-mV(f)VXV?e?bY-JM*sRwMkEWv- zCqCxcknVrnQQLG!1QkexE}w(9?K9TCzoowO%WtQXX2f#%(RiMO9!=#kL- zxD>zW9j=$T*qtb6rE9IPpUCP31CUkE76>YkxLp1j4~RQkrf+HKYCej*4h*rtb|0txXx=1zD@Mh(>> z`LDe&iwy5ceCPcmE|N36hCA`qMtFmefcM8&U}vl+5B(52^s%ErKo=~bymiLANeJzO zbW1FSk_ZWSe;UodH!F$H6+h%!Vj&RF1-~@js`>69ZMzRfrkD&q~>!N2bgi zf*#v95eUHrzJLC!40)dZGb7N=-8w?e00~&e_zt(uL&TmI47?&BEib1Q zaJk<=G+AkZpaKd1OAGLw?nm4rSN|{baNJV2uz{1%u$9l`&n20*cG~8O<-jV*U^D-B zkH$*)w;NKzjU`IMKV6k?*6KXxrJzOb{+Sbyf7n|YDv*G6FkiQH`gYH2Rg;lx;sb$z zuH~k>_-gn-W$TdJ{2CWRlw-?#O+xpop7H#+|EE9#wk2v7^R>#i4Kq;i$x8wOUF)v* z#h4pjn*s-@oi|09#b zmD%%aIPq!oe`Uuz%tKf7R?AR<#G+woidEr4#rnBA`&wv`SLS>m5?wfxCJ@kdWMii7 zIr|jF^_`lf`FwjFMXroPx%NHfO*irfG+sl_`bWA&y?};F?=Q9 zWEm=ufKP#EwEh{Oc>BemqxGi?1ayh-W9?xbMdKEW>;s3(P=N$|PZ~|XO*S}p&0Msu ze2)xE9DHuDO!M_V2~F{je&HzIWwTIrApxHu?;(E-R=nTOLWiGVfq*XfZE7^>4!x8{ zPv@X!hYtwfAS7Tp=DW`>WtKKMJ011hdQ~8x3)UDsWAC_TWlfAi(Z0rKgt`P0Rs4&( z9v7@A_0_y;y~3*Sjb{ny$J>8W$14Fi*Edi3^y-1+65Jnu4qmC`X&y_dkM;1e;W zhxT+G^7U>K3Txd!fdq8zcGt&BW}b4zL7lH%Q80mo7bT(2@7gPGpQK^$R_m0@GkDHB z@O-)+Ps8tqty7%lsK2VtUsuvJHwhg}Yb8Mi67Wg$K3q#*^4K#8&Cd=K2aV)p)`Z;Xm56@jJd~gU30M|*54lxaGR!Lho&D8Bh6HqFHB7^=q6!tmG_}6U z`I}tYYv4e1`%(*GtX46^7dI&$U)FQ_RSAw{_!#GsM$!8?9KC*~D~xdP}HyqF+hjwi!y!$iB+ZXKDt_v`UOupAAH7XBji7K%%8dhT`cuK`DHz&gv_r zK19a8sH$yyfq<@E?F}%l>7#fYQdcMV=kFtC8xWc?pd(xQYXH_?+goY*=B)%>UyKc~ zZ~9o}Y=!!(PH&h)u1EDn86V6TR3HJb$5&Y_>q-LJ4@c*jo4CZ~ zW5dF&c>M5@$n=R0g9;?zQ{a(19Sgj=WHcJvLL(5+^@Tra&Ex6H&;a#WP5d_!)7fp% z9B)51m@B82I4Xe|Z=|y>8A|VIj*8BiH`BoZ_GL(6Rjg{=hDzV3C6h2{ zvctSPO7HB#paKc_Hu-Fy#c{ID+75NvDhmX3`PL7_{pWO2`t4Cyq@dxqh{GF4WcIBm zg9;>IdE@gRZw+b7SiX$oh?hV>SI4q+T$#{GndSR|Ut`P2V>mQyA{uq%rTl5t#ti18NB{_ayjAzI9P%Z|j^=^mOKk)IU(@=}mw`8b5!pdX|UVkl2 zskxx`WS(uW#H%mNKqYH03IudjTP?vUKV~Y+zo~>t-=?IZ?;JGA;IIr8NQ5VC#nfn- z;yO&Nsq6J?PHwqJAY-2I6%x=D@Ovdb7?iJk_EGEI^>01Nhc;2@&#Xlb(R&K9=@y5M+|>#Mbmf(A$9ny@D!Z4d^_A1T-sDtD0@CYHUxuylx%aDZ zt@nDR>fa-wo#)?R%@pz~E)n_rQbB>l$>D`~m&+z)|0DGp2MuSFPd$^+;t@jy0=i&- zg~xZ7r<1GGl92t;wpyq_qRF8`d}7}wW#I+257*~<2I)RL2|e0hh9Lo6uouPqC0ljq zn+EYHWc_FIxZx#y)$)KcZ02j}#%KlaY`I%G%FhaKz3w9Z=y_NfyGO0BW}SXbymAuI zkZ-F9R3LHwOBt@x*{f*(s(n$n@h{25j)~~i?4|+%U2EH3#9NylQR;nAi8ceTlcLc$8Q&=p z75ppWS^oY{frRe&Qe4q&mvS&veS_vxDVez_0eO&0fq<^GPv`NYs{KlNj7oem+d+D4 zi$|*lHE@Jx(Y|P1W{%nNLG{rZg6n ze&FkUfC7mQUO#Yr{$)kqMSUMX4z{H)eB;ri7b(Kug08SvKe5e(Ys!@fwZ+LdJ4R~4 zBT?#}WO?_?Gx)02N@aP`T?zg|m*@ZC&&>}hAL^)mAAk4zWXJRvG>Q1jP=N&ewR{in zzpoBe@Ptj z*_$sA&?OtZ#`TY!R&@8M{gUwT<;3sueDr~zp9xC?eA2x#&f(xrTa{=%bu>|%vzL_5 zjzaTRMafWs1bl`(!cuyL{IrfkHI3~A0=ni+y@TJj!%Dpg>Nglce-oPv@hEE3c?l|z zfX|SRQX?AB?2H6-F49RLpsQJvYJBt-QJxy9Z_q8YIc+yI0kt}C+yg3*fKQ!ACJdU< z-J=swPOB|^Zs7m^7Ic+wuEsCV62A-<1h`4)6tEpKt$ z6@h@R@AftL;88`%o3FmX@0yKdYf=o_yCg_>gYezJ8iPMw=kw&j-#E1Rgt1UFKmtB> zp6mYiEpjJ10XbU}3H~kUf;AuCYiaq8jK7tDng>h~YB)&1XUL<@r(cmRT@q2T_JbDw zE$D*vG0z$?p)O71@shw$3k(%Vz^Bef!l&!dAx9F>&qekG63_)(BK{4wX+m{Z#G{;> zJA@Vo65{)Cu4+R2r1Pg6_d_6{3$~AZWu~u0M`~yBH@KDF3#i4Lhiy^v=Y5cJr(eRK ze0M3H)^DY6e`~OI%s$2Xn%Ym?_sE8R+dB`{WX4jcKtjC6bZdM1X3cz5>oZ*-psUN; z8hmc_QDqjt9^V-@*pklkk3o7*?I~0s0q=>&09-rM#Pn!n@x)OepzC?TYn(l?TsbsE zy+*oCXWFYlEJ}Q#N1*}FwJw z=**301S*h#^&_vZ1`VPIVx!T-uXQLSpzGzG`sAg>9mTYp`aXU|52NXSqfvIN>jWy0 zFp8~D?hmd}%!<{TdSTfN+O1C%y4~=rKtR`@&!st|2jGv(mMb^4Y7MtNZyB-M8H>F8dQ+%CVz_TQ zHuEf0CXZC>tG#D;5Rd98WRM>w5YS~bHXY9hDp2+gR@*53Vdu$;-I3_XrbG%ANO*a# z#t-HeDI*J1;y=?`@lWyD(SovfBmmm>G518JT#wp`xk-oW-O;rfdsrBAFDY(AYCp-AuH`vfq*U; zFXd}%zn>zvi(*je#{eOc3JLfW_^Ou%2Z(QI9Qyp*ULc?gMpgN<3Rz8NEs8@e^BgHu zAOYVd->J7RiL?w)Kn+LN5eVplQB~f*TCXKGqY}~DQI!NLkT|kfA5XfvTp2n`?e&@7 zXhBBsvB6@ic!7W}7>DJf)Q;x#>Ft^5mCaFVVvcbq>mp@q*LMv@C26+Shsug$g9#o8{S)>g&?+G4oKKQJO$N*YjsPaL;2U%5-D3BsL9xL`HOr zK`+hwQ>Z{feCJ8`C^_hofVz~vAdrAAI6~rUYl})qdDlebQhk6x1rji-&Q}f`$|EaZ zC8B$N(*y###F1BR-#F6DItjU69Yvr52^b^ir^{CbkfYm@P@^}27!uG0qul&l83QBo z=t>g8hbL>H0tqqRp1uAyW`mPZ+Tsi$#tvQLY(~X+4|0BP9GbDlT^KvVu{sKh{Pl?T~1FM8UBW`F-T7wP@XBJ^HLk zB(fPFB@oaBzfE4l;WqTh$hj!DWwG!LLZbB0CA>Falk(@5+N$+gX-5z2o`DkV%LD?t zV2z>C46pA>XB16At#4is>Jmt-sJw)yClxDMyVQIc?mH3fc47n?X8fJre{%_!&=ty} z_z#j)gXzn4gNjJw^)SIqQPVzWy(YLhb(^~c{RR3Kp)wG-EEo24XVsP|FY z(T4sj9)~8_JQE1$a+3?BgCR=7V3NRD1{0n z;PrUTFr$|E#7ss>W;Frnyt`;gM1E(c2EW6tB;;b>y=O zg+HE27T432qj%GkFKeGm@vqaB4YkS2=F@8JQ+QgR)K8gtv#nObh_gtpx6ArR2jaMMowb9)~pbfdb<^kVs7>X+IXd6sl%P=Q3tFpRza zj#IW+ed5Hn&r|5BIvvp8a;-o>mtCg{YHGxWK%rGPl=PDXC;9_FddrdElpB!{}=SeK6vyyyAN>g9;?pZQO}d+#4%D zt5xD*?m!wcT@TIm8Y~ddCC+BNH1MHQ=hQ`&CxRGMAYrPcuiP$ulE%Q=z?=${Je>x z8N}(k5sGd#NSO12gg6uD)ba^_=x&VOJqQ#C=n`l9zTBLJ2aVH5p}&I}R3HIo{&)|- zFNJz{zAC489minFSZ!8;6}h&|=ipZfzDdmcy5QU7vl*uS=|9g3dF`D^3@VV=TAGdxt8bQhO;W$XdXw#G zy9dwY1|H)C0=nSasO@+vE{py=s!$=$_o>(j*2INc`zxfa61}$_AZP%hjg9LbCGg4|&SwF#-Wy!rRm= zX%I_#UVS1byH8?Jfka`S4CT(@n`NiW)oYYq|ALM4-pD~E69fXfgt=nPlh^Us78w#3`0Vnoy0^=AR;zWp<@P`tGHf&&KIs)L46Vi28?IL@JwHmY2PpOv=QZ`D zad-@>c6vdf0twg~B6@n^KY@TQvG;1((3V!GO+rpaw}jp+Bw%k)qiJhp zMiXvNL-Q?p{y{KyhAucN<|i*!Hm2$M(^1-=Q$oB160kSO_Z#fip?BuZLcKN|6bR^o zu@jAE)sOeY^TjN5w#z{Z6-dC|Adh&Bsv%Az!%$$>27!Ps7(wFe;i55lzA_wD=C2VV zMUa3!KweXCTuXjTj6_|!qzD9b!AKaN|9C!^Y^jYxGoM5Y5idx@!318l)HMLB#+`+Tze=-DZTJXO4F&pXZ|cx z4)#{-lIEp(G;?ArWc(YkVAr=;f5;R?ciK1U9RK$SOthidDr zdnAjxAQNQiM*sxTjy#=5_35W-95KOAfOBOOL^^cVIesZKNCedoS{&GL{|9#?0<2g;_Ru8qvkE% zL>~2?fX=>uB@oaB`=vZGajS;xsuzM1KG$PVfrQtVbnI;tp&0#C>%^-jI`nFB0J0g_ zQXrrU_Dgx*^T}=Lwp+gF#T*L;6-d-C*ohq+=PQn#)c#f5d}o^0QbMOU*a!r4!G0+p zO@SHRbPuvlvGx(j+^(na__AaSU) z7JHnJRVMdTzuLRg7t!N4JEC#5E&>5v@Z02hYxif+majUZkD<=OR||>lUEgAh0SQX_ z>9716RflqDy=U#v(hWTY0=i%w!$&Nc8T8@teki5HfHg4wiyQshrHuLdS-LamFK)A` zSSg$NRcin54IXJ*r2N~h)(i*6WYB%DeUO7&3kDTP7#hFD3s)~!E=*PLe3fG|-Fd4w z`m?CHKtLC)ANd-3yD0kUVE_tDYRI4hYgBk`zV^H(hAyodh(@9Y!ZjfA_|Y3|dTFEL z{8oMErE3?_=81z)-9jCKfG+q%_^SJn!SqT{UsTI;rL-S~@ryr;m91Mp2=#eFiwbPu zv_z@aSFe$OU@|?w%pXnFY0jVmTL5@}8co*RaO%+88|gG`EfCOEXHP92o13aEOHtoP z%#8)q*wPEV`)bOd0txt}`6**Qsnm6g2bvPqRv@4&$NDWk&-YH`wpPnk3SCOew@4^u zr#XWPB;fn!G0VRBv`g0>Xk=M?fq*Xk=)c&ZDub^U`o^!(WZY(Yva}AeUKha65C4lz zcTZCW>Hd)VEclC;8#pWV+y9h$cYBLp^>(asx^5H)}VTouU2=i0h-n?p||U2+r% z=z>uZzPrZ!40(9N8-1$VL5O}p0;G1$StC(d zCmkV*0|~ggmFJq=V@~$EO+jh;_k>6hbipVUpZU4H9J}XeUS3lB3@5v6rn=>i<%7k;7%Zc(?7G;!#gRvi zl)}b8IMH{bA6@F?gQgXmGuZaQdIh#ud_4Gb7&Ra2gY1IL7*rqu>li-f^qfG;j!Fm* zXfF`Z1=}m0b!ggLx*%FY{Rg*WP=N%jV|b?Y%6Pi_xGO3@VJi^O1=}k=c7B*bW6fQW zUL9Ko6-dB3hVNr(okhw?DJ?<^3|1zR{ZOFerb;1rlQI^XT6Ss@ZOh zw*Pb%2wd% z?WtU}YPdi^7mV)kHY&ZCZd_F^pX)zXi2FdIj`>^6>>rkCW7Y5D&hr&?LeUYq)29gn z0bMW##8>t&D5N{Hm&;SXPh(Jl#G)n@I5jN4Y=geq;Y%*#ZGwFb2eX;m4B6*iq|bJsi%U0*RyjGnB7;GRn@RtI;TV zULA5tzf4XVJzF54ON=dbG+K;T{o5>mY9G#^0*NdhjdHHHvP{=Uy+)XHhQ4NFQNw^0 zGR&V=TGf@fo^6I5I^2_B&Rm{}&F>gBbsmT2>@5*;<3i#cvM1ep{!@-5s5^3}f7wPy zof(7H^j8D|x?t{KzOSfyEj7A17L7AxLXKZZd`<5_8g!{vjGw4`k@ae_Xh{AT^w;>h zKtLDFRj$#D3`n7O&W%IS`4vJIb4c`@XhMAWdg=xH)Qr}hPL1a+=UB9VYpp;)7tCnR zXP1%&)2hwmQTmbFGE^Y(WQ744d1twDEJEGWpyTF1#~mJvY{$G12B&NDLYB6IW)=R0=(Ba$?JCkN?NjS;l4YeDD88BoqXT5>W)j zAVdiR?i~q15ETVc2}Qy{8bPoN6){o47P}J*b^`3cZpH2fR0NCP?C1aBd*=Vlm)G@X z_uiPDIdkR=-&r*dnVdZ?X<6x$8`loVI?W!b`|fQ*JSLoz)jW%Np~YWpdvv+{<&<)D ze|>VL+nXey5dnK7s6fKFK!+R}QzpBuRn`etY_+C)^%78+{Xv0%u37i%@v_X_vXP6j z7WqjRXS&KX1@$_TCqV@g=%+4eIOC?g{v8FL}b4@zxWY}3CpljgzrX<|+ zom`QkWZgga97I#{)6jdz1PLmTfY*(;i9d%?&y%UBEH6zUpzD~eA(>S0KsIltTwPW* zh}PC6p~!p7B&a|F-hbZHFPcE>KgFPmoHG)9!ULO_ks#+Aa-XycHGC@hXghx_4O}-C z4S8@QC?a^5DYCaJN=z`BQkE#tHL*q|PKyj5@gr^-6 zmyL}`fa7y{m!-10#;z`c1{TGm9}$HD0bSxRKQT6yw*Af5ZOgMIs6ZlSmoe$8TP=@X zqpStcUooDZ{E&=3@17wL&;_qLpDW6kL4OZOL)x7s;eJ3u-Px4<>GMyv{iQ@8!_*nn zpyxz1dSVZOfG+s-@OjSSdGt$cI=XE2R1FnKMC6%~&=(D`iI*}P?p!~Mnt5cPfi15I z1a!f-fUgELUP7l;q@x#S%iW;@34_P2NSIqgd}E>#9V8w(^x5hRwDR!`fq*XfZmLwB zidWHjy(Xe90rLq|AmOLkn#?rR#G95WeFm4%V%qu1c(k`dEj2XlNXA9z;tmI%tBr1V zCGTw8;VriB)J`8dkqMof<57vqJ2<=eJZ*JuJX(9EN>Cs%|7bVTVN^#Pdr!Gm8zN5A zot1H@_lxHO0bLV|yO4V`&9K9NYXKI1zdb07HX(KA}Gg+m^8M)epOlWkq(?2ju!0?qfmjw=)|7H=#dTnV5{`o zv)jC(iy|V>;?=PN0bN&JyO9@7`Mw!Z%30;_uA&!52BU6gS5v4!V)p4?#5}|jS9Vlt zM^{vTq^>`MQKH{Qfq*WDncYeJOH=$HRynK9|Mt*V)8o;>J&3lP-^^$xK_W_N&_E!dD?8qbG%D4{ z)!NGY@oCK_8c>^xen0F9~GRvz9 zXln0?NcXFq8Y+;0EfN1leO^yDhom7}je!CIU196nk{<4jarc!9=)568wm3FuK+XC7-CI!81+FybSB;c2U zkM0&MrgLJFQP+sU0s&oj$F(L$d;F1S99LG+4Xv3)Tj?gE9;pi?s6YaK;rMKZ&pdjj zVFI%0pDPg1<%?U9i8}A)GE1emG;-uDD)F4VHD3xPs6YaKsd?sEQ4dx(vjei+HkS^I z2`2`N=Hbf^{-|9$MUfwIOYpP$dUe3E7?OW&5#C#`)FiLSQM2)v%usIZS_&0N*t*4$ z?yXniEgLmC(ND{RRaqLK6Q_y<0=j~>#glb0%kb3&TAbLW*OyKItcCK1$P_A&7%C@` z=1J>t2QP&gmr|%eV#k!J zWK9QNU&>xNtH2`=yT$nMikrI`+)SGZl_RzMBCnT ziKhNj9BQNda_uj%?APy=QqR&|0s&oJ*X59m?VoU4)25s_TRN5{Yb}+kE4EUoK*Gy# z0l5}jg*VS>!ioD^<5*T`lvKWPk3c|I=k|+<#hJf2X;lkO_&dfk--uz-x5e8jR3LFN zCzpJPK_nmgY)sc)yi4jP`R_aA?=as&}e~xt|)mF zIX!m?o`3B(KStQ*-psVPJ^G}VM4|x+dy|lF}CQaODYQ zUhPd@cXp<`BbuQVK%oK&_$A^yA~@QzbMt$n8-*qU0bQSY-9X#nQ*iuVWlngF>0f$p zb_6<-vxl@^+LP=X?t;(l{i0r~_8@C_d*cQ+Kh!fP_9ox1^uS*3N)Nf;Of6=8Gz1;H zXi1?0iK7-?q>+yoMk|%yvABgMi#;|BJ$TYZAfW4sw>vp>pa;e~l(YIcv=O_~V-Pwy zc_M`hB;ucXla4+J&%dwSk6c-sHR&9P25y-y5YYATrx|I{<*e#$^;xZl51Q(+ zg+c`qiIaVZ!GWH5Qnm72k#UXKk+!~QY1B@EfUXJIh-8&?#jCWH9&!V10~XlQ9rgNf zoDsaYx+uk8)OX`Wdj1K?9Kb z(78lB9eP=Q40*8Ze^iy!`SS2;#pMl*Ig z%NtqO6$k`$!RyBFho>>?v!@q|lTK2oK%!s30CMrD2VVG7`Q;ibTCfMRctzkeA`s98 zuN$wwJI91+S2-Z-iiZ>`knlb`kUZ+p1J}nl;K#@)Z)RCm%~ z9j=9=S^e9nizGK<_qQiLUHM*p_^=0Qoal$Qmw!^bUi2azpA5vY#Y*(t@n~ZfXfh1V z*Ez|@l>bv8(W$dP*%mMouRWlQ?*7;`X9F(>B9qcm0tx84G$4Syxjzb5%}{1c9)51c z{?z%Ri6#~lDv;**;~2iuNHP< zOBXw#FOPC5R3Op4CX{S{mx<3GQ0|~@M|+kY%6E#ryIUZjE5#^+M2}6y1Co{dF{-*d zGqh=q7Pny(Dv;22iYA7k({Y?$Lr#pTabYLonxau{?+FBSeUf6yu(N6Sb&=BF9Uo-E zp1&J_0`_H)bX7l+RW||;KlWAqrt?5DYeO84+f%JBjt(SyZzSMjhm?`9w!S6XJ*zMJ zwxNnZ1rpaMg^>6O)366q#sZOWoPsGdAdcX@NjMSH0$FlG}U^UhSh?-Mg!LvS*iD zp(MBc6e^Ht{(cPUc`^qde5HJA$t^eb+RzZSesxwLpzCGF@noibHg2|Gxw^(qeOP#7 zO*HfL9SRjlR8}XF6z5#raHtL^+O+j#{ib}CRI}d+1aw_&okCIz=3=b|N-w;boiEFn za$nMU|CvGs627{V$&Vog`08<`Pkmd=SF3>XS?1wBbU4afq<^w z*F(tQxnpqMBjwpGZ)MB+f9r(O_8z2AfdqX2dF1Yl1FP+Cfo@H{BoNS*(0mkm-hMo; zG*(&$zxz&X;;*LY_3jD^6-bCJgPn;hOP{WVRD-Jo0=fpY8B5wv9)shN^6aj%xlQ+W z7=zBYZ6;+@+LK?Yrr3J)E8&S*w8549>+gs&e=0GVx1n$8{rG5kNsY^b$1 z+OoQaLIo1ya}_kng(dW^k(^B%GDtwz%?sm*X?6&HxnGHXJX+U|9X{ZVM&G$l;CBi3 z?%}tD?*V$WGyCJ@hWgKGPoV+{I8NZ-j|E*>yhk_m^HZ!qKo|U$@OWYeSJwJv2fiXV zmqG;+FcQY|00#AD`iZTOw*F3mfG+qg;dRf$5i^Z7KnLF!Q>Z`!M#5C8YyUjhjgkha z(T{5a0bTH0!bieme3{9q&rwSiPXxOWGAn_Q5L9tqqN%vvU?qmN}sbo3j}nDU$w5|hcL2mv$X44HH8W! zT;t}D=Y7`V#_tUIF}e&J$Rb;=mTa49GDtwzcdMCX;n@tlELI_2JQ>8o-p!Ww4c2B* zfkfiWY|?+l9DMd&b53;p`jFoHJqG>yIa-*5g5ys(3&eW>@7~jf`=imkXDcyOAOXjs zJTl?)nm)f2gBrhjED+EIXMuRd#lmmYYTGFEsOCC>3MAlIl-G3H`Gsyj6p4Dhd?^sn z1!sZyoba#T)bQvCG-aAZp#ljw7Uey%y)|_DzEJdB>L(D;1!sZymord<1=kNohCw+L zDv*Fo|1n_8ozMu6O2VadGl&Il@t?*?)S_Ml$bA9QxPqf&>*v z1UGw$%@60vKDtVV(1Iq6nEXmam%R=P1avj_dyVIm?vSsIQSwWSn^cmg-%`*DtMw98 zAaT;+2R`jrEN5&|X7!&s>d--rGSHIQnF0Y_$Ald@>-uK{1}FTf60A|6m;R+CJ8E#fX}f? zWpw8SIhYZTyvk*PfUb4NpW&O2C(7Ro@AG4PFF#7w8;nN_>#j;rfdqUXdA;x+1*HF$ z7<9$yr9eOz+y#Zl^j8KG!q>?L)qRzq0twiz@ZQokJ7Q@YfgVp%AxJXybT~3St1A%DCGM^=aOY^+ZS_dhaL5Z`MJ}v)7km0M zUbK9-oX}Z`MlIPgjJjmTB0qedLIo1A{vFT8{SrzWj~k0JwiAJXuIkj!_`{x~^7WO< zh-JtrFWO8i89A_(6e^H__3u=wY1Ee{YNepfC5r?Cy80V@#^yJ%Tv4OEwUOuD=!@)h zH2h0Ag$g8K{W~628{MD&NScU-21W@4bj4Tv!S!Aj<&FK6SYH#X06H=#1I_)Rrci+d ztY*h^AcIHJ$CoA|lP~=Q0=i~*(De-zTQ}t=L$V}8RF+d=o z3szI+wI)Y@Cfy!PK_9y4Q>Z`!R)pg9$V%>!nkUoH`_uvg3Fv~=l=&E^oRM{>rX#KG z-!W7m0V`Ya+Ef&im9M8G2hYy#kbo{&O_`4%V|S7UH>ac5qXwv<0tr~5i{Fou9Yn)( zI{KNnMf%7lUsimaw@)Xp~w~IhP7p%X`ziKlR z$@s!dv}<*|1QkfY`s6&bW_kuW8aWBAGoL9C&;={`^4@DJUox_1D*AY5t56{p60puX zKdY$|NUwh>Xhi%rfq*Vp?^mVjx-^9Z97sgNw;dO%G(!URQF+#j?M5>DdX>c z3s!9AD~o+kl74qm(670hh5FQxfPGY+m(j9<=trcZBmVOR0=i(WYM!xmOhwODWT3Pi zi4s&G0ehUhFWRX&z4AK?Eer1;5YPpyTk~9lAUpbi*F(Nnaz+gmNWdN^?_Vu)r4uhs zLAy6qxdZK2Yen)R51&X(Sjp#llmN9EC|X8q}neUlNp*p)y6x?puuJ`=Yk zlBRfMq1=zt2~;2f`=z|^Q=Uvyr%gglHeV44=z^^_uSnWyE)9#~S*#I12~;2fd(M2u zecK{B_e?69e!_}E0=mSnf%eKQcH+k{>GH|tr0=^NGHpvI(kw|Ol@>1~J$KuZGha2O zz8@BleDAhoznwBizx@Z#viRX6HPtF3P=UnJL%C#Ttv&gitVC-sbnRWYVD@~%B6e^GiC|^X(W_Kl@zA7^fcJngXhIa#{^$86H z0=k;B1!RP=DT&chqJviZCNZmu!P3|lCKM`=2>P5u7OpWPbpcAO??9)CtdcF1#;COf z0=mN7=8+3t`Xr%^66HKyoyuNKS}t|JsYjs#iPn+x$qzdN^2$#+t3EbKY|qXE($#)< zd3N&u{uXr2iJC+H#HdKWDN3|9X>$V8eRWLoDt}I(0tu^Wb4g@T17a~qIjg`u+}Gc+*=A*Kf?glX91ZSBo!0FpP=Q3e*DR72^96q?QO?S{PYet6 zcq8e|87>geHOXlvk?P;!C6|@RcBs>6_O_^6%3f|xpaO{%HB-q{)5rMUFC{x6DI=Uc z_@#jgDo(pY0=gP4$Re$lT)~&zm67mtw-7d|tT7svxI;KeVcb-5%*9`AevMYZDezD^^C;o1AV`Bo$(X2HaB&a|F?ljN8gFRf>I0JJO zrq9=UfxiV^Cuhfza{)c@oUk%}jDp{tnWcGKbl}l#2`Z52JUxmWX<9FznMgR%Kg){6 zJ+eS^rhO3z=vx0PiX4caE|dBroLKkFlm%~UhaL|8D?tSk_sd6+wi}npyEYYbBH!GQ z4fn7@e;?{1NI=)ruYn|bs;8S~>wTPPHAb5~dTE1RHrGc`frMppAQ{qjNy*U1$2ie_ zY!zMpyA!%~)JPzptG>*QlubJ9ws+M5PGoO;PYuU7pe_rWBd9=P%|;*c_~gTq-3Me& z49ver@2%^GhUXax1ax)#>_$dMl=YrSPjJGf(@Va;fh%gM(nC;z1l+lsuXZYZNFT)a zLQ(S@3j}nfTz4lYs}1BXb*20m@e|+El%W#poB2zE3M9l`z~hph)35O!$Yp4)KtNZk zbcsB2I4b|^bBP~gdE8s-w$lgs_IWNr1rjeR`VgCIjqsy|x0GN0;0B!@>x+!^zX=3% zO{nWm_Kvib6UkXlTx)WPruX$nciL4-P=SPXPZ#oPRk3V#_$nuAz8$7t9{Hft$=V1K z&{hB0hE!NY^_ubD`|;}cZdy0Q55*4GLQsLk8O_dQm$j$7$sR|75SihU78`NK*GnbHTl_PTk)wR<(Id7pFuCXd7yEf zTMGnq%^uQ(RL?GPTdS$OQJvUWdgZkz%FZ=MP=Ul@V?*LJ%*d@;PiYxW1*vI7CkdS_ zX)h4aRoUb%UhVe9?bMl*oUnT1K()4eqVEZo!k)#DxVc7?#8lnx{bczWPISp`L7TSo zL`Tc41OmF?{>8i=z$HtnJ;xs{4l@z7i}_c)#{RYQaL}yfYcUr#*_YN-)Lij zfG)V#GhcnSumkO(I~3i&tb?Ee3AhH6XV9HCq4^6#koN>_fq*W!*E5em?lz-U#bM~G z`nLoXNWe9id?o9#8e;b{6zN)OAV@$L+`pL5T5kGHDvCy;Hw(W@P=SQFo->C$BgfiD zq8BeJ1p>O@KHR*YSgJw0Oo%}{Up^Lg=!OJb=gIe1`}UR``4Wrpj0XY%T`+Px$mEkA!kAfOAzOLB+ov@a){ssVDv*F{ns^4C z(;C|2brNzh?j-`Pl8HVs65XZ)c9+8C0Y@kixH_iEK!ziX50kBIy%>W4bJ z+JH#pl>9MX$ppOaw}Rd-3`0G?KcG;7#15)W-UnZhyF69myFW7WX?8(4(z$v|AfQVw zF(6YTugXV$DE-~WR?DfaOEh{^S4^P-3CBqWWXAe?alMAfW5` z2xD@%*;6^@fRb}}$ZP}6;5+15pFTjL0*U=P#>6x2tvugJIV=C5UG$)9BwF(Ns6as1 z(yJE4GrUrka+Pa!Wzt@1{$n)S^>`PB3M9HESde!1wX(XUa#r1TouKUvMkr#2*?X^Lz8 zlw&L#`H{+pd!g#inr!?`XX4ge8#@`+tIs@fCieUP$pzh2(uT423wS=ki~woK?fY z59qS-Jm-*Lx{m_2EXGb&UPJVX9m zovx++Mh>V?o<4)h89-cfa3Kr&f0d`-SMn1NrG26Mc6CL`28IFwUGNO~SgrB{ZSl?) zMOC+CP=Q4FcYD%b|Gu2!rW|9U{EQwL+ZCBy6$$7PfB97BC-g>5XJquooIwQ=cDXj> z;^R_z#c<_*96EH87JgTuS5^I3?Jym(f4~H}QRy!=3o#@OoD${g<$u&IgLKH_-_G*k ztIBhAH|;c?*yNow)O8?(3M9;Wn2@QHdda;fD#x%2IYqlXxgzNf94ZjdwKqVAY-wOD zKk`=Y`PoSqsei|5(&_zCtWhr=vToDH60Mp)>W^MJ#L(_tNz`t>in6^4>F@frB&n@( ztqNN{r0v6kB%j%%1p>N!R@sny)q6|))JkkAVA(yoarJX)^-q6hamI$&Cuhn#253m| ztO_I(k{gyHADgN?S3_Md(KELzB@1nT1{FxatDsUPTb`mjf*YgT0eu7lx^@K`l8n+N z@{T0s>b5?8oNn;tRqLF3F{nVoX0Q%PIKD`}u~cbGnmX>Mhu?HUw=dWV1ax(kbjY26 zLix3a(!#B^&|scJOwr!%mdtjcJ2^MHM&8uEfpq1HJ25}@QnqFdB)4Q2;#>Y$*2q*M zsoP5bQPX)X(EYj&3@VVITU^Lp)g`%)p>lN}hy9=ndl{o7zOun?v%HIOVL?oPSTxnl?lBOS%dKbZyyZL!@2%a&WNn zl-zFqkZ!%8kIsDT!Jq<(evR6aX8l*lrkTq75uI?AF4%5{#y@Zr2Q9=H&-%Q|^YD`oY-vEYByWz|V3*4$qppsVDj3rRZWE!S2n#1I=D zHv5iRx^5TDEW*6WI3q3j@-}U0+-?`*UtCmDG`68+S>i$_wpH;xl9dSkOMMl?pPi&K z!x0QBkPur2k2gQ5(T5>Y&JmG-uBdG`WGDJr^3PoP<(iw{(Y&_NQqYrd1{FxamWZz< zbGb%yv|6dE&Z1`j9sl8RoQ@jX{0>OKJIi-D#&y*A!#ru5!BByKE_l`XPUD6u z*7n*8>E7=^;eJ3uyyw@VwAtK>4C&fWk$^7vEbvT@mfEb<>?1*1=}t@ zO1-9H6OFY{aj_$V3M3kxb0J^Ki{#vO%5ydKQZ2Qo+9+*PcY%N|*mm)l%=aI(gWo^N z+prgd3M77nI*>^TtL5cil~yz*@iV=&x?Y+a=_U}+1=}vZYv_g#^w8oj(%rKj3@VU- zUsT?E4SY_&-2Wx9?R^9Sx?tPI=bigLpbfn0q+@Ab3@VU--(bFaVBb~hHCGpT43-1} zx?pR^SJAaROTU~nK;3w4b*MlBeuH^trYEK+i`t?|iyZ|5y2MuW@8N?~|E(QLY1NTI z1rp-d`E`{E>paC8k@LSOTxIC28%RDq?~J>bYf9pZ!#3@V*z*c&6sA@&s6gUgTR(C? z*BWmRR-UV-O%0jDNk{a}_alV_biq7ZUR%UjpEc6%hThm#QK&#-ZA(uwqMrqB^+x$} zE=tj2Ka169{g(Rz0bOGL?(F;qjBlWU>dKx_s6b-F+up>})C6zQP`;eshu6?1o%~Vp z+fxDoUE(NpA*rNqef-hrffp%MAR&&50+zg>X>SK3?{CEd0bOu}%-1LyKcQAf2cg^B zE(l|1NWf7TUp-)OgC6-Dj85g13Iue)*Z|+VW=1*v@GS^+SbkB60YCzd4f$>bCZ*JV z@^CbG{3(HeE*RtBebIPK%Z`VjjkB%@u?$GSF)q*RyLE_;m=}tocb^vs=z_5tzB<$I z0M(uT@R3L%0O-SRIlk&rlO8+XL<$gM{j8|jV z*Aocnf)PDF8y;!S{{G@4;gbCnuDmYu8bY$02ji@2o(&Z}V zSzQoWf5jiyOjBBh4{utt2hsMZF#NheKo?vs&F8%AE!ngU?NI-9A1G8HVK8GT>GxW~ z&Q;2n^GKEj8y#eYtlxYU2AFr6z%#!sTWQ;DY(_~PA#K!Uva>maQ&kj(s6J8Cm zUJlqn;Y*nsR;Zj59_SzcF8mlc3&;{E^K32P> z&u*kyqu!SrF{nV|Z(}c_Lk+Q|n{v-pTeVr}O-D4i^*;&;=z{GdUy)m-$pU*iqEmYs zFsMKR#!h%1K(Al)!gMuy5&wxo0=i)P$Rm(iKd2k8>s4s`ok9f?FiNFTef##7o?7jV z3~utM6o_m=7mS^$R1@@G(THt*P<2$T5F>*GjBD|lPCobP<;1?I=H@qnfG!vV(z_^x5wg1RP`g*Mo8Wa9UAfOAzGF7TC-dE`AMhH1H)@4wE1dIpq zT!Z!(>9RBlX-72{2qB8 z%AgCheLFier@~T*0YE~$R@?OM&}7fH2%qmP5YPo<9K3?Sl>2mNVLN0IZzIGqAOY_U z&uDD@k|M8G=+vFg0s&nxR>Lc+4tY(3{Mw-tW37ak3?yJQlCMxW`-NJaYJ*&+wG#;F zf-xulo?ok?t>0RsH74dlYzY!Ds>-7VpMF!F?v|)mRV#sjE*J^pv5cwpeBB+-#TngP z7(qe;wnRM7a+DT(Q_}`XpN#|py5MM%_e)B2n64q;Jz`EX1{Fxa7L|{kGn=sC&zd8v zvQ`2CUC*BSld-cK;GU0^=*RXChAjC+OSJNkF@p*u;Fp2NmYN%}bZs4!JgSXAKv&tl z!DN=NHb#Aw+HI|uny?ldbkT*itr%1w0l#qkDcRbFEe@}f)-ACR2&;SkBHD*wO1pHF-u|a|jTOR&LGHBdVAfT&$LIhcS$`uFSQGUnltL<5S zWh3Nks>j>J|0$4wJr3UbWOQT(DUHy-Xr7fau(F&K!o=|}VtVO_c2QRDGo1}1bpg3QsO$A-B;t|gfGHT4s zj|8I-H+`WN5+q>t0^SSX)Rdi%4M2^hp#lM2uy@Wge#=bR!UrD6PGf=4Z-)e|Uch_E zS1ee5mmcWY&|LxnUE&?I7}uT+*Re%Q#+Op4Kmt}T;29A2JF=HyZINC1LxF%U`1J7J z(qB8~`Mo*PJNrp^t{_qO64o{FzhuYE^7N3=l79jLUGOd7Yh`L3Sx{ZQ)PIQUw-yq^dc={vFTL=LdZnJshx2yq zX7wxSF0WAq{}yz?R*C1ghfiWb;e)A8swHjQr-1B`VoCfGTdAd7K)N1_CaKHqq!RxB zy52!#p0^D@Ml_kkq|XxdUusXG0*P~t*N_~?f#lu8&YaL5k;zWZX-b_s`U?bft@9}$ z7M|{8(FH3`=vZa4dAWaxe%%NP6-b1btRcP@J;=@$%2`d=K8cypRb=dhOo4!|W!0<5 z+oBHS_Xnkl;E0PE?6yS|aqN^$p#q6%g#YqYmgM`}cAR*wo6Z8t&+-j#Rtf}k4eqdl zR6j8!^AEJ*ghomlo7FnU{Z8kN6e^G~ezKA@c+r@=3b#?_zKg=iF4PEwIg_*#6W&>0Rgx3KdASd%B1mX?+N#8ca)B+zmtc5+hgVA09p?Cjwl67g3t zNI;iZ1LEp|U^eKUgOt2Mhd~7r*PG5KmV*c3@<1bgj2&MGu%$i5N+rAW1p>NY{RzGv z$Jd{IsGlGmjcz7Xrhr7)`dMUzy*K`LTe*X~wS8DStCiB`;Y|esy6h_^k{^r4;8(wu znzA?f9zs(+@}-sjMhq&D2;4G>{OH*Whol>DqR%Wh_OEWA^kT4yKnSjw31sGE2W;uA z9OK`3_`IJ|DP-to2bPz9QkwqCN+6)iE_@WR)-k~I zT$DDk`QJ`#{==nG&tctJo44^qPWdj+=+#6T;2cT5ZaX0RG|-cle;P$LYrU6~ot2d@ zPe-+5f$8~@e^n0#6-XT4FogK;*(pzVQF?uW%!0XfKPY9aaS;gUk|KtXI*TWA)BkFP z%{XMjCQK}o5-nXBR3I@ivOhWWWXcibUuGxcInfkf4Y{$y>~HaYK!Lim}r zVCHelq|*ny1p>M(R}Uc<&kT`=zEQ5OQ$btSWLH0F>Uj?~se2?DcP>;e*{mmxG>s(o zLz>DDUg$|8@u9?&<&N$v%}(-VP=SOv6L+z1Ggdx1S<2D%7YOKrzmNCGjx=KaOR}Zn zo&$v60SP$s$J@k#I_y*KF6ln66bt_rbiwsI0wzMUY0au zSIQqs?~2s|0bTIv;VZpukI}%%_39}B32c_?3U*!Hq@>LKryAz7xZ3f27GKMfdDhAt zz4Y-G4ZdzHU8;>`P=N%TQRdO}yDzD$cZK@V>S%$0uCh5cM7^*_$*Vvm*0=Fx9SvEc zDS2o_FsMKR&W!W<^T#T7wfL-h>Gd#yfG)#)7b0KrF4>W#ydTcjb=Zn5J;||a2!jeF z;N9f8QTz4Smrak|A9;<&uD{hS7a|4~NL08bko(cma_~H*rQR0S zg$*BAq+WbREfCN(@=rWjtvkD<^tnPLu6JbF&U@9!s3(I8BvMkcNSaMO1-6!pl0m# z)?3mPPge$8HP~{(c7^Av?KWbwejb6UH`Dgv=Li`1`-m+kVDJ7|5xiH-66 zqKhEXs-M3X`e$CqE|o+yXE-UEpqc)3Kd8k+p*z4;;FYX^0LykVv(s-%D!nY^fF)% z3HES!o7kiaTlws;G&QNS(361#>}&Ctcc48xT(wT>GT&AppbI`RDpmL(7xrU#zGNBN zUg(iQ0`>s;I>-(^*^9?>q<@_|2n2M6duNdab}H-@rPS>2J_WH`O{PkN$}JdFAOU-_ z{0_GCX4KAGN--A+=qhZufD9_u$7_t0@rPTXKlAO;Q%ad<#GnER*dyop)aM5??TALw z+Z_f10bRX6E+ZcLV{q2W*8CWm^~0Fc#)eXh5n2o?kbol#p3xW`$tF(Tt@giIO(6kY z=8*+t`{iwT;3Z{TyX|HSJN0y_x*vH#p#q63e3V+GI)}$@R>saw$KzOk^K$oL4a)@r zx@ybUlUv>w@za)_IB_8_w4OO1@#}iVR-ySp4ulH_& zfUcf#g=C>i6<*%WffLUi(%7H+Xc7{)fkFim?CM5RKcWE%Zg0nlTW{0Z`g4pFHJ&FB z(3RY83t6paKvruwbK*&P28*qJO`0yvpiqH?dv+nY+{Kji+tiH{KJ7BuvN@(SWl=wY zfUf)*Tgbzm?TKenFHS_MGg*UZJ6ay*LZJeQ2Ze=Xt!7sef7F!|f4nl;_-%ve=I4zC z0=lZ~Hj@YUdy^Fh)SMXkb`q;H8BMR3R1v5^qTpL03Ab}6Q->+UGu?CayTxuPeSEl( z2?#TyVUC|lHTcwJ`mZyV4tE{KpaKb)lg#UjHh)C7Ym`WRp9Bd6bio`y-e(y3oSsg* zB(01bC}e*^0_I}zr{v!!IxFC^)ZvA{KtLDF1m(4HuYaWn-#(Tc%=$8@Kmz8J@v6Xf zwY2B<$5QBWPl13g*dyol+o$}dRW+X^&G+sMDv*G=aeNk_K?5e)ew2DG?=29}CHC}R zY|~^{JJd-RE;|b&NJzjOKmHwTsLO2gen<{yy9)$#!G0HCWm?pT?>*2E4b15x^vECq z=a6`mbD9CWY4%%MzsFV}pbPfS_;)b3DI1ipf%?C&VNihtoI~R4Qe%vmzr!0z%hFyT zpbL(|d0m4ACT#qa&yol2Bz!p`0q2lZs`;jE*yvyPqy|-;1p>O@SCp@uq*kn|WNEP18uYa~3vO zs>Ecr+PJZwC!R=YdD;vrkbpIX`3N!@v70^>Qm<4Efq*VpbDi%d*u6y`T7e4bio}4_?}3|TC>v~eNjyFX2RYBkbwI_ z@EsBM8L?MS2ckjO@`U{jpbPGlz*mM%)MsBbLQuo+eK1rY0r$7ytA2yC*!uykrKA(K z6jrwJ(OW{~9**R~cmoMmqv2nJU6a_HLMLf>Rc{IvNMyR@lBRyG$n=FuT-0XgM0RId zhO~W+y+A-0tVY9s$FwwdZ_O-eXA2h!6-a1oTR>*}8InT@N>r`ufMj;O@!e_`#fJUp54wal}aXcpiqHC*Wx*3b>VmX)>%15O#fJB{r$FdtzA2TfUe61Gs)Z` zPjUW#s~|$|M>FJnS6aWQ7ljHW%ty~6RiB^XYvXAYoHfyCba(}?MeEBNex(b@^~hp{H#RA{)fk3c}zvtbj7 zwQUKGv{sHWZU0bqcaR2hD~_a4frORDB(gQD1e>o^vh-rz0@*}seN>k2ClJu}eq9pz zH180;(O$`1E_NHl#zp9(c{L#vDv+>uNhPDh4r8l2<*XJo@@IApP0-2;2Z4aD(MRJ* z$9Fq$Q$1ysP+|sr75ehL*>rwNd`jAQyU5dbWM#L zO48+-`1)U^zNq8$PON2Y9~6GTl|Tg&^@oQMbE~*c zpsUq2KVoq)4DaZ!)TZjut0n849EcJwI;f!ni4i~g6NiErd}O*(K{>0kF?%$3C_1s} zl0ZOL+IcVX$IK50M<~^-ToN0xpbH_${l_siR3Pz#?|gFi)eyXWwX&aZhNg;XEDuG7 zsVyZ)K-Y$~YLd9X6-Ta6Dq1^V`9lL=hN02AdJN??>G|I^Ubim^;1rq+jX5T9vFoxr^ZQ8fkffS?xb;M8$7bBQrCG*Lq_k6 zjY6XemI?%PeMMb}OV4`w__PX6MEl9Kq9_`rcrB8k0*SlL?1;D21oxey?3enba1UK{ zJ_?!j-7XN&Rg+^)w7Wi%jb1DeP=(3kZG z1p>OneP1K1^JvMf@o46a6%te+vF~|1z89S){>7Bt<&T_QLdSfFLutR32?TV(J!kpq z%y(<)Mz;i17Z4-tMhl5;o2&_9dN?Kg4L?R`c0O$#n22a~gg`(S+&h;?&x5y8uLVh{ zMMf)Ok6cJJ4eCJpUu%Z1S12{fA8y}Bx92CLr%PK11a!eYfK{q_kM`1M6Oz&LO{>&U zfkf>$8)BJegx4XZg?spR2i=sIf;NnvClJsDcP8d_KfI38_|-}1Zb~~06-Zp2+==LI zH^!6aDixHE86TtrvXfE8;8g+vU2sokp5@&K)17DI(XDak2vi_3=vim-G~5W&y-HP; zr_YYlUrQ3uUiv^FpbPFT%_9?qr)l)Tv8ZV>qELavFAG~@JFgjzIIdJ9@%5y1qvJS~ zU+pgt&;|F%=6N!OW%SR?81!-E6k#uHNF;Y`PXhnyU}>%LbxyrhL|2_3hqfGu5eVpl z^=o)!yU{_q7mq{w+tY+Sy&>_uzBO4I^iQrYP`-mx-fX7&aq(!*n2`bjU1D7v&Bq(4 z&)*3sW_mJ(3M5|cHX;vxewGgxDfi>e`sFm!JPAD?6(JDN1uI>vRC{JFp`kqz(WT>Q zLPcvxbn0Y4rWZevU8|H{#^jhe^w7CvL_S3e1a!fQ-Mo(1@L6>Ipd{3E;|!rPHzcyB zX_KsB*Ja0Gq;h`)Hy%7q9G6ESo1Q_v7e` zD7tPy9Ln|EClJsDE5Y-&Bz-cq%#TDzl5PnV-yxxG^ba?w-zSf(QJ$;R_zXI3(@3jPWUcLN`&C0jPPG6MYk>;F4|E?Z^4whC41az&5 ze~fSH7s_oslsib`;;DaB2->vyuTb|K665AS#^)cdmY?V<$MC`7^hTHA=%eXxfq<@O zpUd$!nlI0ps@%aPC86|~T`-y+(~v<05(_l1;B$YM$VEQNSz-48+BIY-+F7e95YT1b zALE3K#q#S%N-H}3xj+3G9f;h|=`pB4!YUl&_kZWgJ9jE)<&>_b_pb$_s3H0S0bR`( z?8PQ^b7ZSg$}#dby3-ju{n3{8Mhq&D&|0+@+dHJo4z|iMDyP{|8Yjy0bLW; zt;I#wbL31%rQbgIgeCo0F#sJt+nhlK5}rG9u$N7m-29i)-)%Xs33b~u6#2~16$t1W zv?d4NpFUfDXs!?z`BlVXLMU=*)__3;5{pg^#D14&$xa^1J|;_MUnI0F25m*pC?ufk z)zE~>| z(B*!r5x(fPST5VC^pGcCZb5>FWg^de=@crE7<)8Fwy;_(ODRfEKij7vxez)9%@0Ka z0bR|uH^Rq?crA-uh4|C63~PE#Lu70V3Kd9S^!?&cZK}zqjHRmZ8qb|<&%-mjX()1kZ9-{fa^CblJ7iLj^XT9h0jM% zK|4&5KtR_b{RQ~rq&2eM0_EyTEj3Aex5>yqGDLz3B#gJr$FUt($XC`W*J}5tHe}AF zEc9+&xIjQxz@GwK6tYtO?yV51z6NAZ{3I0RG+TlSB(&`3tqpaN=Ec9lriK z4LPh_D-h82sQo;gT{l6_`}vR)zCjzX-C5o*i9IPn1riOr`{9n2YFVrD9w!Fv%EF1> zE>HxM6fj&+*s!F{npR{M2nYnyb-B zAfQX!?WWfBv|RRc5K8qiLQsK3EYE)UIp57KOYg2n#PPz4dLOIcBeFi=mjF4C3E&>5v(Sy?Q zln!NXLysxMy)jPMyQC*FbM1zp0*Uzk-{i!bChp!}PH;lsXeW-D;)=8~odg29;`5U5 zu0uxdmG=}P*lRZadc+ZxbnAtn0*NQmXW8%RV0WKRhdB{qe;+^o;eckH>Man^wJ0YJ zH!~dMep5#wCKMgO-nE?(U*M0R0twR}Z)Nid^WCGe_i*CqL2aV3sS|pi)JGtoYkb@o zJVrIo-PlJV{%tiU??1Ok#f!WUR3OnRC>pQ&zTMq)QLN)FCBB(%OR7fOta(nN-C^VlF6I@S_j1}!r2T3HL>w&Zz zXU{(EZfdoj6M4=@$p$-f)IQuFK?M?>hm6Kk%T3e~QVu6t9ehlp?zTcB>ih%(y7XS} z#ufHj>IBavoJg}cBtLmF1Nnui)bCPqJE~e9Xm9>LV1W9Dv(%>7sy4f2h@9BD};~75*+R@1NAw(Ng$x>+|%5S89fiE zC(dfk38zQFAtV!r$1XdN67w@+R3GSvO$quh?QF?-d| z-mm1u#doI1)5xlg+=M?N3AOFecT<;2M$ zt4Y_=H1zshfdmyuP|JomFJq^AiBBmf+@{DRJ3k&}JS74FUD_iX;Hi#V)z+EsI8l(V zqMm=pptO#+B&a|l`>huqzJ9Yh-0>qPe9W5A`7gtfLw&74K-adW9ys;ZI(1n0M*Iny zoZf|co*jzXB5ec}NCe-SiC@oLqt4XQl{ zsd8!-;@5fq@82vs2OCe`tIoPO)Q#ujOi!SG4>M82=grhmfyCoo<(S#*RF7yA&I!CH ziQ;jYhz3j&2%@Y(g0+B-HCV*Oi?;v$8j3 z@BKTkeBNKr^Yhp1=JB}qysmStbDeXp=d(E@Ebh-2_fDQg3VVL#2eMV7R-nbz!?{TlxzJCzqgZS(=PkWkJNq8*|9Aj>{2L zAOTy1J#mt~#AOE($g2j5`(2q$obENpP=N$&5msG3 zE=iO+#*#DM-W&m4Z4HYBgPz;a`8I1=43oGVap;a{;#E5dLj@9iTm9&`TGUuQnK=8c z|0=7E)jzzPDsA`f(#_M0<2AoA(e$T}~jU z)~I2qKmxWpI}>gDiL(l3lS|3&906T^cNYrVV~f#@{M9UmUU`)GshrhastCbQfdp)I zne4VKMf~eJSq%+uo_JeKCl>Rdkch-sc|GFHjR67!Y49(O0f0q%f`}`o92+jR{gl= z2PELLomI8M3YyE_?vi)*=LqP6&l2{{=z0}#PewfHk{f`b0*Qj#z5;UIfd-)hwjYb0 z>WfGB#FFUKOF06%;Io8%uU6wK&eMn?FEuw{s6gV=kOhLb-BvWkLg9g@ir&;?tXWttitE#@RmCBxTl#!!I-ywcd&o;O!~?h!_2jy}l|&;?tX ztrqdk5YzoelShy0FjOGHUxU|5vP9oUtZulrj6edq_#@acOd-g6bSCtP2U(r|TCx7| zJk)ToFLFAYZf#_`0A1SYftH_3w|4oq1Z6Mk#g2JW#X}+TNl%jfqZ^4ipKe`xAst=1 z+YRkz?;JhN^H3Kb3j}*O?A~7VP?)FYPE<cSDw1^Yp4JwxXdVaiW$vYqAGf(j(+FQ;2Kp{voK(QQ}^i&jnPg|+^~sGku>Ko{S? zN`00tXbl`hQlvKA+XN(PucTX-ONJc@DAM5w=z{MetS(uROeFrU z#In?mRCP-bJ_IjANo^ds7VZ2336oy0K%LUsu^95ESEyPBAvq_l2~^-Qfc-~S;pqKc znmM)~`I_I3BcSV8giNR^UXMYC!uSqj})X+e-v5~ z!}k33&>Z3NB4g6!`~U(KNR-#4TUY1Ap!Q>jG2&Blo_My@me@D3Cw_f?2t7y6M^|@R zp*e%U2#4RzM8Bh5QPI&VVZYaWRP5P<5yx#t(2+}>SX}@Y?uvp(u%+b(g{NXMigR^k z#KfyN=$y|^WT#qB0u@NWvxoH)Lz{@E7i@{Sz8gnCSKyJEg8J=LRA)KacEY1Qt8x}IPBTW-Wmc>$b&Gn zH8fJ_YBdh^DjkioVx|d;+s!~%{01`O_vq_XkJX|JRrDoLfrP&NrDEW{D0CrBdCc`H z%jvJ3W+X|o4@W>3yt}dy$l~tw(+M-u^l2aNz6*&Dr_!zK!{gD7&;BgN)ntWG)4_ts zLcKWxy5L<~CM)RJfp(qPj+A%nPvAKUW59Eots`5wnGW92mORqv&z!?J#q?H@!h<6}ttUOwwgfgJsc$ z;)_kw$=+OnBcKb8Ah3}XlilK=plFg_-W)>(65sZ`6pC(aMw|R6uo$<4ip0y+(PYUn zGmd~RIOf2fIJ5VNS1colG-d>b3M4$HJ{J}a+K4(NZ(uP3%y)>wrzs>iYdS|j7ku+( zcORd<;;0p2q;TeH3>8RBZg?U*$y$r5j-6&PuASH}ww@MB9?Eub1a!f7L$+pO%WiSS zn~|j5=d&0pkXX^+zJ{mwjvltzAZ4n=D4kAq*?{Wlm!JaJ3t5&~N>@d!soGFnJ zs6gVm{e9ue)@&4>-IAR_4R=?IpL+QbS*<2VKo{RbPHdhldhPWf@17VEs6ayFE*16* z>F8?rPAta#^Yg_glfB4=Ql5Y=_)YMUM0-_#$rt45(q}b` zkntF0FFfVhb+K86J2A-CBv66G7i2;U4yK~uK?aO4W;M?)#&;vlpXhT0bd`Q-OY5>{ zAfFyx8FAp$U2*@tAaW^ZGahQGMsMw2i{4GyB>zSAXx-{n=vrK%yt{pC>N+P6rChqe z&P3IQdePwYAkx2kIfe=(bX_~rODD6?+r^ia=Wgn2ac7(_x%2HZM?lxQp{BI<#}f3` zQpUFG{hY62&P@-}96iENfds4aLG8_FC>;NzwQDv;2(cBN)lB2mN8wv2e7{f%9Nok`yN)*Jy{rtv-LtFTe% zcbx+xo}RxezS$E(!fK*$+7xxVaNGuT*I}~U)Iy(JxqA!f{(3I_4S?ezS{6X{?KA4mQZQ}^&g6+mCJDA9%B0WFiqjvy91roO| zInXvGOVRO=S{7rWQ4?wLo8H8z*Hw;yF4%7DiBqjE9USV$R%|`OP=Unlt?qQRY9i9f zS7mKwyh=@K+2BMT4*$au&;?tX%_4vCm6{mok^AaVI3p>8TI}nCK2$r&ySb**uI2>w z+?g&Hhb^WP&kaRh@9o%rynF2l|TCUa|t7k-|8*h%V|&U zS4MCIbp2vAy}wQlMX7zeFe3F5mg@eP5WOa;7%Gsctxlmwb4H0(B-TWPj}9VL8FgYF(Sx^<)mt3O;-L&!cc+4an;#0R&@#zU(IJk#h`AI_epy) z`OkQcfG*qpQ|aWdbJ2`&b4G;wI!H|$9Ekp=cnlRt9Jo7$E`2-;J57vvG5zL@p#lkbWMwk1G%u$hS98ElAVeznKs7( zLj@A>$glyt|ogT>ComW=vUSv7Gr_TQ7U-fgZM4zf}sKlcw}X= z@3vi}V!cyk0z(B7{4saCYbMPK^CmrH zY8(Mwdd5Sjk8e7%U!KfjoV0o`8jKu6nk=xx$sPuDbl5tiS=?G4u-B5-;Q|z|qA#~j zw4h}+`N+3Cnw?kIx5*^gz#y`(gFl7}B_`k}d0TpUPl8a8kQbnWl$Mcbdx zLdm_`vbO5eqK!0Qwm*5lO&>!A5|RB`4TYsk(Z^0EjF74fC3LPYG1=drBcSV=7(m5G zi;$Do97asi=pYTK@F1}k5g00vkhdK}%i5$O*SvX*&^c-*shYVFLz66yfUb&H!L-+e zIS7lTjHofPlJ>0XM)nr0#ZZAne%d6OP!WYf^7k^L?OJQ;T5(r0Yui4KfUaj(!|8Iv zF!a8Oa&++J+pbcKp#^br6){vG5t2QPj-EOU)g(5KSvIkiEc%;}4)h8~K-ZutQMBFB zzG$U+GjB&7c@_F2O3>8S+?w>)kYK)QVj*l!x{39=E+Ls^r@}jF80bN7o z%jk5|W~j+_Jr;u?f2sECGkkdUNemT8Xj-hG6_Y;5L%#lGG5i_=q^1jQ;Yo#OI0Cu` zU0Y7uPOOzj^;7m<7o!ovyHTQpK`b62do+KWA}8a{%{`3M68rt<-YUV8utjR*ZNgkCk+!W>{F7 z%@NQwOV~``{CuD|Gr^7#S$c8O)S?~es@psa6-ellZB(t+UTFSNpAm*QUP?8eioSM< z&So*v%iBl|n|w)w?|2Lq zNWi)^Elg#j1#u3ofRr06AWj-oxTEb$)ZZeUqB{y<(K>>yeB;ehZt+|Ua zl?wKECq|F=a0GNcn>B*Y?>Y@VEWXQPRO?wt?JRA{ktGyEg(JB8?p0(VIqO;yeC#Sm zzJQLa@pyk;$JIA%ibh2O(afdss}vhP3AtfUdW4auU3A2|ZL+_fX9 zMve=b{YH7!I_ug?7cR9RJ^kNds6YbVU0MI?rK9v=vKBda^$SNpSLFP8bQv{9$vMia zHguF+`h7`8qFX%2P=N%zyRw;T6C#C@PZ&ova0GNM(OW{%fsgXn(Y7qc#8LgE$yN`s z^zk-^3MAm&m95{^93a)JU&E8T-{T1A(w>n`j~1276SACG4E2`7q(j{g2fb90as+oJ++?R1eNplfKzN}6C1Dj)lyCyS99H&%KrZNT(aHHHc#;N6wwpnEi4 zs^6Q7o3@uY0=m}RUQHKVJm7w)P|jlfPM<8z>M#r6SX_po0tt9`Wp_~_LVB`dG@kus z7e_$Xs*mgFo9XrnovofM#)EFtB$cer7#&`Vp#lkbcV(+Z=EX=)Yr5b)u^Tx8y4Gu~ zq1#S8P)zAChQ%=3IbHe_+!`14F2GQM#E~6qsj2=fAy*#Gi03iWrHTw=oc3xJM?lvI zwS4LqFA3{RG8tjAe3tZf&sj7&a507oB+7Kx(cZBY!ahCa9E(LzoTTx1J=)$Rkt3kX z?@s|8pK?RcaaPW;?CGj2RYngb*FKF!uvZ*-!;4=2l*1fsl^xeZ{_UwJZJIxb9QRs- zpaKd0&1<8Xp;U(kki6aBIRd(1PgW+gzGNb0m-&#qL=y}ZNWeEewn9j&qxAbMAs((n zIRd(1PnM0U-LsPB#rGm@zfH$bfdm|LVA)$8Z6v>1Co*g5a*lv5*pp?wrH=Lzb?QRA zjW=MZKw|W)So$<#99o#QpWWNHhd4;LL(R$1o8=qMaFB9y(4)7x*oV>(G})aX#K{+j994WD@{45MKXoW7%Gr}BWx`1psv5v zy|p^ouT#Jg(3Sown;yiD$SNj_#qcN^AT4ujM*Qp2FjOD`$AH-StK9+8@(?YOej|z_ zplgNSayqeNFZ5uqGm8;x7$DUKwII5oE-c^uKLrwSl#10XHXb6a>8e9U=^JwdbUo~l zOVxKFG%aQg>yh1PK3K9i*@~2RI*gzKiS?#g)XsiD;}y)ZsuTxGq(PVL8=T1z(BChFLo zkV0#kQFvA^56VLDjA>QXl};i$=?NG30z_5>n4bx4|qDbisKlR;g*>ebK9(1DPt<=jNjz0cZYL zp6wp>;;x}=UDQ1dj({#Wd&X95^?4*VIfh8$Lw;Tj5^z3})!Qz9ENZswOVl<#dnQXQC z&pPpOP8gZBv=erTZc5Y5HlZnVTFT*gGMr;$tJT>&=dX`rNJ1A+3>8Sgv1QixN&F~& zcN{_b1jcg&bip|`nQVm*n^#L2On%PEz)*n%99w4D5Syz>@~M7g$Cd3I0bOv8jaB+P zt0noUdXeWV4q>Q30*)=qWPwYxrBV9sWS)90M?e>xm1Covk9DQi3%ip=tsh~iKmv{} zv#*`DXiJVu?TAXwZ;pU2ezs5bn~rp5wG|n5SdBmh68xw$%2tW#BUd(!){82+zbi0wxhlHZnHI0Cxhy^`HUBi@NVR&9vsh%Vec z5fb*}`q9t1ZBgD(7_jX8VWO`A% zkSFrFVW})ez<}f8y>|xW@&RX#fG+qXV)-nEb7HqCMkLv!8~2QYMAdgpy^pMtYbNBe z7^u%zvBMO7Qb4W9-MfL5YIw+{s|5(U(4!I5{!WQ}^u~pZxU>6}*g>xiId!lrfeIvG zJejQSfr{k4QJ2hLWX%!K6*7{|lFj@nKXNCG#qfIfTXd~xLE81QAy9z?Y&SNt?Zaw} zoNP{hx_9CT=(_kgl+H73jTU+auo#ZM8j{!Z7UbfcP6R5DfXAPWq_%4Qn00z8-auboGWDO0Cu#IMizUL7q3@v1a!d>R`w0=OkGxq zrXT6{ZXq|43JEyp$#Q=_)|Q+c1`*xtAdY}8I8w}3&>c{fzHJ^(g6(^8Bf^k?bGNK+ zM$T_hzi1Ts!D@)YzXe@z#GB1cw0f|AV-8rFzk%fpFj^Dqn*NbvouzHh6=+`@2D znKzdspbM^`WK~=j)QE*Y#*nXh>oHUy0sC|84brq)Y};%M>A1FpBcKbepk(vQ&d0<9 z3x|@GLoQ&bK!SfO(s!&9o6jFYW*Oe+2{n&3_{(hLbyAOYVE+0)?s8Zm00E4eqY14lp?TtUg^ zCYGg(OJ;T>+Q)4OR3HJrJ&?(gYh%R2=befDXP$sAxPp?ct?d>dF526j?7D1EpaKc_ z4Fwyg_K=I8j<^z;WWy2A1=n24WZofWV&M&UvI*G`s6YaK3&bjoN3|CZNB1Ey@7i+& zbn$CB-)F0cIa&UsLPwv=2LK89EfA{)wc$M-QZs_IkkmK=x?uJK_T{~KIc=LVmQ3C7 ziOW&|iQC*)LN_&5(!D*Wkkp$OI0Cw076!IbcDf{Q`s=}EsODHVi8S|jl|~%CrD6%#9TLR;n?nFRrL-^;+5-5`clIj z&(@sF5zzHgBS5Ir`CK_Y=^Z1C9;u1d$$>cBJ6?hcB%U@45PbKgSB>*h5`AUXVnI{~ zTsR|vBcLmL&r+esu|Jhhe!OQyMOshMCU*c{Q#@OO3M5(|SSrZ&W>&pDsw9F-M~GF& zjPO{WIF5iW-;7-XF>G3O=IKX9xIUdEss(!EMe#Ews6axVze^A{kErvzI>~=d50ZtogB>( z&;@G|vL}wPQ`8(e8}}PEMS=<>nzVl{NL?OQ$>)4yF}@U3iu&=3uvdLJM?hD-7psbB z`@AZ2$4^H1wJ#G*-tEA0T{gc46iD>2c`eL7*jlk#R~aMdR)zS^em_1|K87Qp3)aeE z_x6va;?#4Ou>XP)5>z13H|4jGtKD6p-btBZTv1aYj+uW0SH}$F2uZn(-R(bB zp;fKiDkIk-@kzI~WI&ml1QkeV#s3!UYL_Vv)+mqpwdn04-fl|D7dvwVbXg77piu`h z6qmAKTZ4ZKrd!r4s-`Nl&@LXdN$l9FCwXtykt3kX0c+6O z0h<(0dVgiaV2zbxfmulxSNAt!~QPyTEsoSE621k4c3`iZz)jQt)))T&l+1av*! zYC(sqsSBsuD6c3)4~kJy;bc3?5TODInCVz1^Km>bj{7v0?1;(d2A~~4a zMT81RaGAN!8DABn(r?R)SV4f)MUmry_wz%L96-dC0=Ik5Z1xH1< z+(;tri;zPCy4EJy(#WwLgu$yCSd6}z72@%M(d5VZas(Afz|8EdLU*4kv9og&`SkM$ zM?lxi$}aSJim_nd`UQ(|E2>2F3yLCM6FOt4Kmul%XIIqKJ)(wlB+*KB;0WmI{<1Tj zYSUU68~udE2#wz&e)t_hRP?4}s6YZ{%4e$+wiSynu1z72QsOuQy3~xU>Etn*f@P^P zTc~67X7SYaNyKVYE`|yuV8(w|;fR)r(`Qa14}8-&0=j0uwWHr>7zyU%AF~*RJIX~h zw~6FR!9olbNWjVktafJfaS=I8WaA})906U+xA&mews#gfbb7{ObnrSQ&VCV2+DsmW zp#lk5fq{LoURNjfE({}@l^r<(y2`OTwf)sgIQmw3%s(%?CpH-wO2n>RFjOD`D@m}K zpY`v>8?2^9!16l?641rhb|NO9#k|=eq|21I2r7_(6)|M8mfO@M)9Jx%t#b@VKo_hl zC6i_Qv4TiwBx$xW13?86u(Agm)2A&Y^UHz6?3S4v643S3W*|*nA0b5SRQB{g__mVb z4-6sxnLFiBfds5j!p`=oZ6&+U{mG@KMidgz^~!cA?K)zv5V=eF9Q<^roz(EnkG$S- zL4XP*V5Jqd8h5dU?=PU_X!m7IwE!4c3Esu)X;F31uVvuryoQ@WRf6gs;X8Q%T@g$g8KNWFd<65Y%o5h{>?6_r?@;dg&&!oB81KPs6cpiArCOgc1okMOFW zves5rdw;2o*qkKXpDscL60kB9n}b|ASPER#gcP4&#u3mpOp!p}cB&LiUMp*cwckBN z%FJ#;R4f;WP=N%jaK+XEEDe%c+P=c&J2E)}y1HwpP+9d^;d`yJ^84N8Bc*RPukg5{ z6cH+rfR(yfuHuU!(y`Om@s?3(906UiC(>y2t@}dz3=I~ea@{y-@|x@TVboL+Dv*E` z$JleQ%LM7znjGLN~(xGF!@s^WVgbE~J1vr`PS$2$c`Q-|1rZs>g zpes&o8LiA{L2VZ)YwAhwr%63#XW@y?-Xc^W0V~&lma@kB zx)1S^`I%p6vyq<&6-dC!f-GZ}&Rl6+NeXIn2yp~-73XJD^Z9+~@=wa@*;?wGY{ft$B%3-`qG9*V%+4pzBq17L_S{sI#XIi*fJET*>y}Z4{c+LWBw= z_U}ojDPQgAt7*!!ee;(@sp>}=n&Pa&5zzH8GLyD5^QNI0T8tRqDN*Y4P!lH&dO)E9 ziR#K_wAYTV^w=9^g}iXPB+2>+o5PuWiX)(F%JK|qbhtPDaZPzIY4>xkq-oI!#|3Pp zP=SQc^QAPYurqBHqpV(M9-k=1jxfP(8s>5YbgkXDjJn-*qP=zgu;)k3`Z?0c-u^ge zY&!}SNQBCl(iZP6Xx;6-e|fSVVnXb?KXd%3j|{wHeX_#RhzuoaYGWYT~nq1}#>hGc;~7VnA4=)Xu#E zpVl|RP=N#@3#k0=b7AR;T1Et(nJBF-J%Vj#2XX{-+00l#dj*~oTntY!qIlm}$=QtzI=8cqcPS@dQGuCkgbj2J`qiqK*7oJ#GGNOOYV5x{c z$Ek<*VW>c2b^8=L&tQ_^P+h@@bzk~RdMoSk)s;0I0bO^kQfbs~bHSmrGBdYP@7~hG zCcp556Spx`Afd7{mL5`lpm=Xo#)xI=u2LtYLdsI#a0GPy%$-G>%U}K3MA5dgwy*&a$L_8Z)e19MMtTiOqU#ZuEi11wZm{CZRSAw6|zUXP+7n^`N#K0bOu~2V3d%{GE8$qytI% zV8*TefW&(bIdyX}k$WX?V==6kJQCFhn-Gh;{Av;Cg6lw7-{;2>G5=0S(*K|>feIuJ zT3OQQlr;GY$Bit;w3>rr&;A{Vz;XgY0=oEBFS+Yii&Kith*0mst$KlkWkWN%bZWWW ztmkSLW31P5QLr>2@%eI&fG)U7lg(|fh!ou$OvszH9^4vXNcd_#6te5?%P%fhuB>@# zJx)CGp)JvE@Zt#Qg6oCZx{Ujd;&|GYlpFLVP=N%WzkTjqmZ52b5s^IlaRhY1oK5SCl7O=KDw0<$I&@mt%4)O$a@!7?EZmH7bIDOK#B!J5<28kcl>DK8U zJ<)*TWEP`O?;K(6bbYep98W+O%;U$tH`w?KzdbRUWG2@tzmP`CudQ|2*Vb&E1X6x8 z*n@pD$W}ujqvY)WG2xW z+FO}BTCU7Py^`gjW*K|s?f;jVndJeM|I6`vf81)haz?R~%_wdh`!B0}HT(VFyd#^n zbpMxC{_8grqPguXj#y|Xu`1~-??zLB_%y|=c02lJa#zuEmWc zd;e}^oPIstY^x)&dgN%=BQGKOj}~Ti!;#U#;liWcns~F`Xtc7TkC30Fe4bBU_Z*Mz zr%G}Y+@!)1D}=X~C^mb`@Gi*;9X+*D@$-TVe+sroaZv?|oo zfy z{vcx)LzEcjs&Je62eG*q^lw(i@3bv3&TU5Yvwn-;9*sl8oyG{(h3eQmEf~%D5-51E z)iC^i+*>*YPaG0PM#P_0)@nq7JuWFcVs9f>O%i$E*sn<0a|30x)Iu(UCn$W5Ut#A} zh3`PDp%X?PU%jfV&L#h^($~EKcjViK6)9HCe1|IcpOu#l*rND#T{)h(E-G4HxLKdH zEDMnI)}&h>TV$^YSoR7HWxv11v{Y!izeeN9GWVIQbrsnQUNa(9y_>vE#0Vm*)Rd;L zW_21KPf-jVP>&MX?;@3niXQRx$iQ%!d+(m1iq)^{8PV%(dwEwj3xFGH#Wu|K^kRzQ z<=Gd=nf-S0Oi)-1eTn9%E_1*AWtL*ggO`kmOwMs%^e&kk9kN}%bQN<=$yO9ze2C7o z-w89a73-QkMyz&``@fnlFuq199^Wa^S*~LBVJf#DA1e-h*ctT z|5xECdw&B;{5FZK2)Ky%c-@uX50op8In<)H2ky%+-ti+^+(A^hYNXHkI|E}J}Ah+Q`i~s0Cki4B2V8zLhTvlnB|1LBluT&2#I{P2``Rt zMum6uh0$B?ppQ)*kadZQ@S{l`VwG3XznZK~d>-KS@{zE3d*g!UHhk!$tQmfQOrLaefj{9nzN62sxBox+~9+Tf3m4c5|5B%152O2SVv#>Nw&h90);c;Z2c`;qN zKSAvIVGS~P?no2dZ18Zy)u^wD3oX{O!a46(qG#on^vBB%jJRN&NKSQXi)&r?QT7Ib z{(CcFZ!GA)HzD@6g#NupZQd3~UWIqTLEF5p`fs@Ai2QS|RE zbyI8tDK4?Xc_kf0_ST3LE{?QjiY{hvcgQ%+fi}F+#;v6#XrzG=4cAcKcZ-|(ka@4v zN$wB@8)1n-tz*^-mR{<(t9u0M)_#RhxIq;MZjD51!*hi5OO!-PVGJ1-9gY7qT`WFH zN=L8ib*W*tE`AWV1eu;wqZ9iz!`;6vMGvc0>3u8Z`}ypH+y zS>K$Fh9$%Z)kBV>WbYYhdw!nqu;?Nq)Zf{Xg%4bbt-UHPP#uGA_FF8J20THV8$wXo zwJafj_)9eFav0J%vsyT8^@)-zhYg9YE{8hoaq)^Az;YK4dd5 z6zyyIM{#T>WrTTaZE{9tN{%gWMOd#GZU0|yJMqmR6rSkmuG+qYquB_{ht{MvNt3iU zG9|AIW}xwFtL1}>A`n}}jFjt}53}{nY}GXSx1M@Qlinn}<_kvgkCb0XBmBRwt=Tu# z=)W8p>>F-m_v-lX32g1iLvoLMgTPaS|?cPK$;b{!CO`VGK?lXjuDH6=omN^f?|^IIj6;8!ig z&JV^>?`FG@Jou`hsnZ`n{kap}+*&JK`{9STjoyidT{w}CB+Qtmym4nlN{4u2tv*)Nb*!f?<`$yh*4=6Dc7nC- zHlyx!ZnRw)!Z$ZJOJl~GomeneRz7OQF7j~k8Ez1=df&1l4 zy6r@VG<@B^w^8Pk(fvG(IL9_4hZ{0b=l8j2do#?=9rgt{%0>O#{Qb(1KOT-<`jMHV zOvoqi40J`2fkyrbXe87$mY|~7qZ)s+Y+Xp1$LmvL9PGqFtV)Q2{32lg*-sn1^nSk~joYnZ7Wzs_b za%@eFwjt(>-7(McoMB%P^WX}Gng7KL16e^I=RqSru zx26fov)!qbT^~tXgjOn=B2*w@cwraX_eD?)e2N({Iw6rL9OXjJr_LM!T`JlojWOC7 z5=Q8y&LK1EdI~)iLqw=R!nkxtBXRwhDuD6F*>GnM-W|k{Q9@w3AY!}?KpK?q= zCfk^4kIOs@(Mb6g#giy|Ms&OqMTVedRo@e+2o*?}fB#FXjdoCO)uU--Ug30wrr&Ok zfG)U&tk%}a8Dz=EYYLx`LJ=yE_*PWZxP_kcd$1T&Th1av*?q-Z3^0-sCMW{f+x!qdSx;|e~y-G<`4jN0g z7G9CR`u>e0pes5i7maaFSM)SBWrWI!U^2yJk^7FfYSNkW%CQPIx3j1GjS+@1letI*Xm~=!M_WMHZEC>^f%x3EXKsvL&?Uc ztK0*_T5tq(@muvNrU%(kF&r906Uh-DI+Ue%541;BWcd^}VH#pOL6Q zGp(xnfiCX-b}aHbF{8>&qd6Yq_xFB(G_W~~@s#B}zfo<3w5|@2ma|L*f=OUi(50sM zs8i#Yt2^OVAp$B6v#Ler zzZiK<EdNwN_uFF-E$xlCbp3!3XwgA?rD_q;ZcbSl@=N*4+3B1>QK@ z_`BKYFNm!}miH{ssX8oIu7_Jba}7RnO%u&*h*hpC{yzm0yH4I~q;H*8u1-jb-iaev zF20<{(>MaU;1;r+XFm^N`HheA!j;hyR3Ndvzgpvd9LZO%Dh_f#hR<#KD6bEUdF7B&qt`8{N z>|QeM9!efEkLVXPZ4 z{hD3uSSbHF-|K^q>&zwUgR40Ly3+5Y%F8tV_IcS?5RiOr{gES} z3+@y98gPde%W4!vJpG2F54Bz>|3gmW9y&a9MW6cr?N`CEepZ{jM1|a~9z{IQ2XM0h zkf>~9jUJ!<+gp>#>Vtpcs16}yRnkI^fG#+Pz*e!&{)l7Ojw9{g_f~#6`G2zukeJ=a z3N^4N=HKIyQ1S$?2?!_i4@GkXbg?fgk+Qx;4Xba#?(IM7@T>ZX#BNX*<(HHHr$8ca zryeTX_xCM;y=`wii~VOrkm@C!I0Cx%ylILuqBj3;t5VvHAs5U3-~nOjC_ASBwVVF; zX>W5pAK8XF{dH~0M^~QNqZPL|u&wf$987M6sgcp$Gms1@kbv*hGFf7m@#JCWcX-g{ zrO3Bt4XP4Mk@3_m?mO5h-ktuP8e_oNGFj(MVdT}xXZX*)B?!78?Z0+CYG(HLdCSJa z%_fkrgnM{ug91SX5@i`1P-^#bVVRT~ubdRsQpIpGmA1+oe$}2ukpK(>4XINh-cMotA2c*LtJ`z;jF=fIRd(z zU+qFqw9@_;qkUKsY5U_F>Qb1Gpi6#sH#*n+k^Aw!XWU=7l%h{9-n;L)Zp307c%DoQ z3{JSe+<#Sm>QO1O?>DBh>v(hbi#lvL&C~x-|6H#s<#LpU^BbMJbynTGARF z&ecVbfG$3U`IKaG&o2R;{PR%`UFjL6DC*>8wiWD{aa&dUVIJ9Exf@xH{3C}7B)0gM zqK^H)G}0_raYYhY?(z*S_8f;G0bQ^~Snf8DBvNawgLky*!?hJ8j6-)Lf0e)eIQBe$ zJC_U^Vvp&s0UQBc{PB2tV;<@8O%v4@RiJT`cB7|9?pIal_{*otOVPRd(5g2LYI1mN z*c*L)5^-6qhth6*JxW?(58DWL%QX?pri}h&X^wJAAk&%#BXi4e3>8Qe z))gVWNi78@i>B;}@cDThDGiQARod}5%ApXgnHV9AtnP-6nr=m{ti6TzwPuLr0Y(4v zI^Sp;PujGPMrv-elv$epPk}_H(^eE(>nSX?F=H_lKUj6uXE|tJWhy?eyABo3s1RPU z9H039Iwb0p2#zjch~)uA|MH8LtHcpE+e|d|L@I^~BnFmkK$7ihp-J@+76VJOh-XR_ z`o4WJM?e?cT4hC@IMRe=;qkkZ#O((p203p=#U)8X;z@TF<4#c=u{b>kUEe*IBcKbm zA*-8_6-UAcZb5tY#9^;VtI@JoR|NO|X^3S&MgQeSJ<@X(%4+pWNWRGWM>5%&IO2V; z2<`44i=hIE#bfeOjpkS3ee7~ZZ0gB+`A5po<8~wQ8&(tb!k6Z>^_h)mX5I?qutI~@ zyRSv}yqBZyIZf!wAD zO>|u~6M5MC(x~<~8By1N9%;TP1$8}hoKw_lGLifMrWf{{=l+sRCcaD}jz5;764yJN z0*RKNGSTX#aw;Eimc=kDN+jne)Sx#$su*q+bisXM_mVzI#PGxlWYfF}h6*I|+hrk7 zU3dEI+-Vl0V|^m=-?0XL!`d7HU3^N*KjmzA z*Kf&W&!x$7yZhGe?(P}rO>GFxF8zWc*gMb64Z(Ep$G2$YvvkyMXH2Hf9*F1Us4$+k3eTM6^5u<<4baJRMMuSuSQo>^TE@ z8=qAQNI(}nvTW2~(LCbYZVnw4yr06k=C;E!(V@IZn$S-B|C@K#DxXI*S52V3e0EVd zBMpfc-7?V>qe!~4k8+)U+X>0UJ3m%P4`0d=&;?tBl+EGt)CB57NHhPs4(rkb0w(9urQ=#P+A*x)Uz zBhzd&z1X(}-r}5%{%B686Rg^>7=G&$iTR~#)Zh3Qg$g8o4`x*tTTG{9g_1D$OC)8M zPiXma6%i_sST!~WISrUjOSc;_V&RZPQm%8HPBqsRp#q6#Hp@}am(jG9k#ZjAmeE{N zT%#%Kb#BEG(516D2N@2VPBVKOGvWu0C!Nfk#l_pq#5tey(3r05+CJ9-*F~&A?NB5g zaLNLU+wxGSx+uEfawkUAwoD-N*4m3}u9=EZ*{~@WbsH5!?Vg%q_?Kj|P7@NyEtk%s zdVB{i1|-_6<)X0O(`b>Ua@~@B;vACIQ9~@x>%#pH@no`1EUUnGd;GVULS&Y7HoS|Zyx9Hxw6GuQ7zg3@_#1UupQQ{@%_M-oi)hO-w7&>8~ zBd)hxjj+>LdN|7gpU_^7mO2ik&u`hV7}m|=$c26*#l!<9B2*wTdPD*0Up=1oxMRl% zyF+oL-vuJxX>P|6&;?tBtppqxM>@0%6e|{*a%}~P=89ElRYe$`y4;q**R4q3TPI4^r;=`6si9Y zVZ3cEI#fE0b{wf(osbw1NBVmPh{fY9M5sVQwlgL+V-O^%GHem9%^unHGD_iM=! z(B-ec9Ri`HC)62IvfFA{GPXZ6;IYy3>PQ6 zU8cj1ZAEp47S#T`Cyr{d1)ZJmKqD4;;QZu5bgS5cdd4VM)=XFzPmWIr7MoYyqELZE zd_y5R6y->rhAP*p*_6&9g&VP`b9yWF=&~K9)o9XLi~8chYl@J67Xzx2=z~YA7NP&g z)tSd*@xA~5jzYVNQqpQko2V4`oO3B6EhveS7VWY`WJ!rEp(4?uXrr`CQrt7Qv@cq< zr+weFY18&Q^LhNA=^h1n77pqOr*<>f z&VLb1#3gJasnxBes>ws-GvB`m#+;O-fnLVa39^S|bX+MKCyb=k&vp}iaf5i-WF&2B zxrdOpQ^f9z9T{PDCI;f$JP=2H{wCrTRC-VMlK4(rRf8>DDPF_G)(9Vofpg#LNwtfA zh&Y0Y=+k?NcFr}`13g!EjMe*M;L>a($>jbYj=-wtxh$U;-&|Z=>K+o65g__^ zk&of>dJ*(tBc)nxLyo{Id=1$i#cCJmSFH_uKm5-TfyiD7Cd?}VubO1;2;@H}R92BR zbtJ4$ZUWOD1W+8o1YUp1R!cb!g+23IunMtp9D!BL*OdJ8OHF^{35}*{!?pSq+}c5I zy&#$wVP6yL$3msG7BsVBV-6I-1pbBWPJHPJ-*?r6q}lBGLIhTgD9a*KOw7rEV>T=s zHKxuTHs@wiNDv7ecfqzLV3<-di7^4M_^TBVJ%UNZb9snnd}(Mn*;vy z=9s5mME-N_V9p-oKUX~Fz(M}G*R@|Y5_}HcpnB(T$c}8p@c+BJ;gzz?F^C-h>m?N3 zbSUKOJfyZqAIZ)@eBshWzel{aGB??^kvM+|$IusLF)uz=> z5)(2>XsI)f{i^9#BcPeND?R^Op39RDJ+`A|gdNoX< z!H4Qo9Ki&hm1Ae_5CXpESJN;Z9ge^%eAQWnrt}b)|0jpu?XrvD2qyR$MazxB;Nh~3 zzHT4E5m?2~S|(m&Gy3zt()XmCo7=`cDt-!BEsOgTV9}(nv{irs_k3Ui_pWRW{d*rU zn^8mkfAr@FtisQVLJ@Y`8@|Q9qTTDyp*VsGzTa(|ISDjls_6`!*&KmY_*r55IX_MT zgU^*TXnHio5lko=ZDf1m9tjJ_X3I~l_YA1XK0=MGd^rNE@Uy~l05@2L=2knY!ST72 zi=e;j?wUvTSZorGAKb)_VS70MtQT&eUC()N1XkhujqOFQ42Gr`qv_}qKHPnU345Ia zVo_luv~}6ej*+1k21n~nq84F;IRdNjQ^5A)ybgy2dR=Ic`4H~;zyzK{Vio>8qhR0d zdUUi!caFd+{4}%m4EE7r*&vlD9(UxPb4>8FOHZ;E!m`4)Y%i1+M_?5{KbZZ4%@r+Q zOY+;ha=Re#G4MPUt0;FZ99pbxKp*IMb2C_&z*m9o0EI9Z5oAow*=z>>TUceaJfCPU zZ6vH(^?5t9nl#8IdoqM_zF^zmcf93@`ZSZ=Iz^d6JSCeLIwMfCG)9e^M9*>2A;jie;2U!$H zFo8#BEZ^RJG|V_yOO0wbas*Z}zcTXA$&C4u0rDmL8^Ht~Isec543PKPUjnO`4;uOB zuhuNq0qne6fTwaT#Su*KW9rt!09F_2L;0S~9D!AM#Q8thH~7!>4M*_!6Caz^z;?BV z2OV^vwS&kV0~5@@nEdlazUw~}jL&F7!ChAU0-YgN@mF`zELTvrcuQM1IxM@s{k>M0 zVE)DApD%Jut1(bJJV{ENvt=8HVMV>kkmah}|M!+Vjn1Qq&x-Ps9X2M?d#hBwQWqO5$gZ zQvU8s#QPPQBMSNFm7;OHBMfHuZl|c$vh&H`2qs*X z%qOG!yb!9aJlHqRYgTh$)m3fSa#W8au!=dNkbhn&+n<}j<8}36``c!+^U2=`CORcW zkso53x^I@$mH@3#zA;jblD z_oJvMbn2xI8=BPz9Ki%W9&k_jN8GFfofn{q_3YqBjQI3XafIGp@?cy?-N^z_|gomrU&e z6Q2~*mQ8MQ1g9#`ARDyX3A0+eu`_qca|3BhIi0oO5mlfFCh*ri+xyDg5GHJ|pz2$% zIRdL1k77GO`!^7Rn#en#ysi&|Rl*H=sqPQO5lrxHp8jDVoZs<`>N;rwCa}uXcLCY5 z=8E!mro4M=zflip-24Y!*`qn&2qtjLvO0IBUEpV!7L-P|;0UZ@^^3^A%0~K|Tf+9} z=FqxRTe(ir-v}o7Ht*1+C0K3H17DRMM_?7Ji$tFMt+&*$h&el+|4v`KKBBDh6Zx;A z6srhD{QrNgC|0?NDE`)T3OGQaN$Zcaxb8j05lk$$i6_-)RAeH_6#gXSE^2s%Xv>IV0hIK7tMEeRmSnb&WO5UEQID!fMYgq=-svCcw?wT)NNi0!LsK?#Ec3 zVZ&tDYqpBM+;^PouQ0(J$cgMte&~PRaXTieLVf5SM{j!7o zUjnQ6yJX`yR=YiS0{xRwKyd^U%*~!Obv$6(xWtTIt5&vwFmg{C-F#v$9bC1P931~j zblHE5v>cmCelKV#m1~|OKi?#iOp|k>*J_Npbf8Wb|Fed8QxT@ph#vg`zoV8X0AjpQ6S zAwrS71OKqLA1ro`qUp)`9D!9c5;949ml$#WMtS%5h~gkHXg7$C+_;9~2qy4qQ?_<6 zFc>CScc3{Ht2qLz@G4#QRx1dDdS5P*vEvfC)wr0z>tUHgMeA_rHzbSHY+B3_ScTUP zvy~h-Od1H>iX@;b{Ica0%!LubgPcPWlwqWu+LlD^1R ze6M|)5huNR!1XJgpxodbM_`rpBR{f!$6PVMMP4=O)u=68ts|h(e?9Fx!kg^SStwS} z2W0C)FY?~QU7XbXI+=HO4B0belz1xtCL>NiXbB}+6mpdNDUM*G^?G-bdD>RonWCUvGK8^PBrU;QWE!Q2c!r#g&Gfj!hwnGvdS{-){e( zszc)&Sip^seW35LAd2e|VL~dKMpk{x6781C>qWD*`orCX-r#F&#}Qby({eVsd33Yb zVZaMUe0gRAy-)Ro)$O$?j$q#ZGJEH#CL1|Z;*Fo9J~%fd+F z+Y{okeeycXl6w6hbD=pT9E;~_I^pXU;NwR+j#)1*`hK4gu`UBZvtAE)y3Cd02qy6P zvDyj71e)G3gDr6#IRdN3Ees$hv-XG{Z{*5&OYaPVA}15LqJ5U&2qy6Pu~o%^Lt%49 z2T(nn!x30DGJPJ=op?k%YANp~zjbOPjBzvo<(w)dj$nenR>vaUp`?K>?DNx>Fo9Lc zCnE{fye#@{`N59iyv`l+M>hp>^?_vHI)XIQIx9+szsYx>Aaeagv1r!r8(EzjMMh^- ziZc$$H5#`|ZgAhN1t^ZckZ=SOwr7ILNV~)03Xm%ZJU%d%z18YNM%zAWOkfqOvrY_R z&Wk79hY~1uy<4!kZP_7ID!fMbg|t7O#xyTn1d_Z4T1@*GEbR7F4WHz zFQ1n0-6;dscs?BRZnz$)wh-emeAr8vKf{2rWft390k+#9s|pQAW}iM{&c zNkwIS@y^v_j4+PW1=p%RpcDO^Bd`kBQdB4w%xwz!t9rtTA9WN*FmbbT9O;;wt}57A z%8t=`u{H!I^?*9k05E}7e2vCFUV}huZ(}(9zLd*M;7WWr=b%vREpq~kA@yNLN-@O| zOpJcBh-~e)N*o<4kCq0;4TTmnf71~jDQ5?ZU!=;g=-HP+#SwVhkJ!8D!@qqfEv8EyQ zdm2rWO>c{5Z@nRX(-xBGqgA4@=VOvFCyLxlJ1NGze87n81WyQ=qyc@dSyLRrgjx|p zE>Aft4oa4H2|e_4hs5~};8EiV9D!8{-y%rs&wE8(-D`}vTjK~*FE@qmU)EAwy%DSM z9m7_bwiyXVKN>(%ZYEa;5);k~7m+CYLUB~kd3KDDfg_>8l6r8k`Bsj=DtyPVm6^v! z!@c#Ns83if#Su)f3iIS&<@yGVSasOQS9G)IPL9ATe2=ldUCRq}#@(SuX6MUw=>OiM zn0VhVffTgbCpOLz*?Hv5^@1^`SLpLsdpQED_2OpEvr&Iv+6SYRZky!f?mWM8l+mr5m<%KiLKaLGXe6{)ihiq znc@g0m|p<-=OmC5F#&RqU!^ZDW^n{o;j6&zb}|)8YbDxjPb$R`OyDnlHj=qA8G5b} zX-?k_9D!B*)t#KfYGq{Yp(A3~P#nPo&J8FOJJNihVsk0I@w<>CunK35SZ$H4DKJZK z7u6uUD2`wP=LXpG(a9SuS{|g`+Es7_R^hA>bIx*~1oaf#Y0BI(iX)i7xdHZlUgrZZ z)3(r~OOA5{R^hA>a~az<9jeTd==9)&6h|QOk{+DUM)*&l()47X;^?_M){*cmk_%)`;ax-UP#|8@lvo?P`i6nBaH)KC+q% z8Y{X{p<+EpU=^Q@DlQlarF-?EGkwmzW!|j}BaW^o#I3X56Wq_U6ay6?LjE@R*=Y)~n`umN1QV;iM3ZQP zyW)*H`CCo5@p#zf)BqwvLI{rFw-5eHY%Hql30)Ux!_M4K+%YhL-$ZQp+1kTUdqPk8D=|geyFm-55;Lytp?fCU9TLR_}xihifmI!-08z9D!B%Jl`6X zuO);RC2{X_OyIX2^P*cj7?x`rfZ|soM_?5meXw-^Tc$y_&NDiqx7wCsvAM_|>tW{XMu==CW9-369`O+4x>y_myHcY#UoequMp+2&`H^Hl7@_ z(~`;~#NR%a%$rst)|AQjuEk7WxT*D;h8gXVa0Cg} zeAmc7M>bFIAm|dFP3^u@j=(DBYDVImn@fcOvWHuFgJ6J|rF6cryBbF@!F<=qKSwsF zjCs)Jnm@hv-IXJ-3RjqC>qTD#gR{pVdg|IzuHrkc@_xI=3S#rqK$?G7uB9Qh3^IS zwf));maHwHA(d0rxCg*J1Fn?MepUB5Fspn$_3RR>#t}^5zKhMuu&P|+4U_4$#wi?u zRk&@~Hx7FSyFXt_6JKYlaRd{%4^}81EcS=EivhIy%zBQ%sx!%{5v z8L;T#1?q9dlrq;Z@}HX+?(NPmizhACD5M@clsR?9fRU;|lkUR@eZ?->F`yHd#eLE5y!36Hd*!-aWTo`zGKV7=b zScM6!syvfOE}m^E={}Mx2&7a8!QMan>FRi02}dx2dp>q`-9jK`;1+7|I-Dc0>RM3} zxmc+$^_JvJ>ddHMpmljPByt2+;V}_=pNCpNptCJlFTO8qdE!kXvQor)bKj5_dJ{>_!!+>}`9Q7=no4rt zt`qlJ*0TFb+omrVmRQ4bk75x=Fwtzv1p^g#np9;{|*Bquy(@|prtC%w_ zaqGQN^xh~e_ry>xp&uZJ63VABddThnj^4^x$TmFKD_tu z*ukaM?ZLqzTz1v{8^OfbqccgusMTWPTKS1;r{@60+WMeVoXQbcb>1?7T&1~UptW3W z`cr~AT&yd!Q+JoCra>8JF8qK-DOcy9-SBbdPL#MXrm9SBSJSi*O`&LSqT zil0%ucw7k|C-j0A$w3m1U;?)j^ElMAgU0b@u=UUpj=-uZ#eT%>#Wqp5vE0MCtg?fe z;U@6YT}zE4n7}QoP!!B^0JHoKkU89(Be05j3zKJq3PgWjxjyy%r4BHo$Pi|4aZ%$4 zCUDELN>kUJz<#zK?C%!D5m?3ilF2_OZX-L{CkYeUbl0Fu}L^6o+B((xoAI zzg@!-Sk-xc2zhO}O$@jte}7apa01PMD>UcCC-s^3!6al&yx2gaAsyfrP3Y7#F@QOS zy#E+Tg8QY4^_g=Tb66ce4D6?$rMuJLsc{4oPC8NK^XN6=g%bIz$R^AQ+UP&0F5*3o zz$)IgXVl4I(6r%w>iG7y8b>hEHanaIUC0qFn0G7l8P)KDJ~q#2mwKz!%srWGjVu!l zGc_r5ZYKYEI{SpjlF|`p#g~KSdNT7Jydf$046U!TON}F#ke^A9*&ycrvU~TvcL1+2qy5aRVearO@i-+B3(nba0FJ>u#x`Hs5|1tZE~&q z{Cd8SXT6y=2`W4|V+s6a3N zeyQ%vYETumFBCJow4tWvDP+<3lj4f$t>~K3ONmjBeDTZz*{z_w#0L({oJyaLdaA|| zOoWsrkjobji^*5yt7{W68T?D<&;p~IYOGpSyp$9hToiSNwV*sP@xw&;sgXqcO}eVa z5ljSo#FK&%N5s{~We4JcU&n*gZxekztBNDA>acYTSrWfrT|?Pl-2V8r<{>J)uK zjU$-Ywji3UGbs^|_LA>irzCf1F!dg-zy1(MU={z=t|=P|EnEGhTcRpBA1v-!(G4SG zPi+yuy^(A7AI}>GclF;=L(@vN6N+Ghf1Dr>(bgJdm@D*_>&vlbYD(q)zmA;1XcwuP9VcqEfG(=XvvQ8dsPqEbud(DTT9BZ z=L7cXz|IxSbs^LeE_|*Qe)taLJS{MRJv-Q*(Zaq^G<*#S@$SzNSXI3%lKjc^SM|)0 zzf#MR1W?~eCDTUqEXNT{@NOPkJO;yosQsjgxd}&L)h@TC0|iON}F#z}{}G zN99-D|YC;P*0;~AvBSAGBinjfrdaVwsaRd|iDPXJB_qjo8;ZqvAM#T|Wg`Z|N zB0J~~EmxkV`Oz1+rxp|VDPVIG$zHHy^EUd-_a;YR74DVT3ZWuTNa&MEOP9akdLK;S zds?BeGa3hPJr+=d+3z_5t8nkia%2-dK)+-Ty|7kMjw6`hpN}Dv#zE${!BoTHC)ZPB z74Gxd3e)uQP?B#Zv#x+?~z8_I%SG|`?h0u;^3E4py|U4B!HM%na@FmXsPVOuFfVlSpG$g<`BEaT)|4Wi zUSdS?oggTDw2`hU=tOY@6T5$~@AKullA)(ON55-q2-F=;r>?8nN>=o@uu7GlO!n5a zkU}3{WyJk{VbJDoJRP&_C&3X+jAARvKSg(ttV`s4No4L^nDb%_^$z{T{dRojm}cMS zmGfBboh;hw>p_Aen84SN?O1;m2A`4>=~nAfj=(DZS7rJ}z}wQfv~8t7!4XWnKAKGS zfw>fNN?r+gIwuNF4H`+)CmC{1nCpvDh|N7qX;9NY#8*fr%|9ATs~&!5#NJa;@X3E9 z)zIoE;s_@AV|;iS0V{_G(vsJ^1RTM?3jZZmL7;Ouw3?JaYuhdoa0CAAxzxob59 zsj!2nLSgtN0!kN8pjo*GB^<#-*6n1n_-$ut>?-+-V?G1XdLnrjo_q zdP#5R%3my7^rnL2gg3PIa-9m#DB;{Yo;Ok`9PFln>!4>;dx@8XBbeYbsdWu!!h}b+ z=-U@b9D!AMMu6oqTFi!lS1!=Y`${An!356SDirhd1Hk!i8THFL#t~SB^JT0`+R7kk zwR8tHF8V6r2qthona#@Ng+TfI)pSSmUmSr|d>+nlTqt-aC(y&@dTJcO1kQ`InYd%& zY^~2w`s_$&j=(DH2g~*-T0}wsTOHJ;E9IPGF~NJwIv6d4+xII-*OhN2>{E;HvA2P2 z7ocj0)PJx%(%)tl4S&`sXy4+G5{_VkzprYIN_x{A%H$&w7R^?pz3Zn^>e^)j9O`OsTBMD-c**(?$= z-()HaP3EX^1QR~@RuP>^_R^keLq=?G83p>sr;CQ!<2eGW-nnIvuD(O0CQkCGZ`{UE z`0#QVh4@KoJgltjqp*8bOYw>joH)Dbc{A(48#BCAqwaG2g*I+zHU=`nj z_Zme($Kh{|e~*Ej?cVRo~B%`m~K2M=*i!7*@-BMkK5!Hq@ncBaXl-{G_p~ z%lh^u^}Xm2`bokOOyK^J-HAr?;YqtV>g{urBd`i*?pX!p2lHXw`xu)2Xg`;s#{}-R z*@_giFwo6OqZ)Au9D!AM27=8^%nyULhpn%k{d0^d{##gu=c(9eY2a+Q7+6MoSUGYtSeU@$N0tjewg}cX zDI_e~I?Ktd3kSFb^h&V>#eWN{@Qyk*X6O_Nx~X00sNLNu zj$i^;n`b*fnNw_Q=4Q6d$D1Rt3h$_6^9J{stL}Jns*~VOaRd{%;y=rtGymEjbBEHW zt7A9G z9+HsJ!4yX@fqfwqilFupFu`>PX}&RlBe071o9I%w2nKgZAf>sv+!HmMRex_&F-ZDx zy#e=hu?jTBiy)`Fw{YykIj)L1CUBK*_BFvgy<;ofrIrELIRdM&*Eh4xfQ3*suS{y_ z{EBk{#{{lb&N7f*teWo6-qMHOaq9GsS>*Wv6Y0mR4s>jrb;QYNfV91pDUGzsBqJ)# zrM8vwD8un*IDAnomG;(#s&NDp>mAn+qrrl->~t4KY+_fpbVY?2(rN)mU=<$Ku-vOE z0y645N*#IxsBr`nZIiOdkFj=A-9*{zSL_)H@9(#g8ho0`5m<%CL9E}kUjQM$`>7Y! ztd_8MJFa@m`?%{ri2}DLz113Smn0m)1g?O~>bJj-gc(2Esuw{=H72lXaP3x-*H%;V zFqf+v*FKE^;~%=}n*~&jBbb;wbPHMAxS6!Jo?LVJgMK)eJ$NX+d>Xr=mc5(YgjMae2SQH>**aBQDLJ`QaxeY-E$*%kxmLDE16iKJ}c2&{Txx0YmB z{uC{3E zrZ=KRj68b1v^xOiW)+hYXAi4!1QW`mE68%gFJfn-){MA1Yc{m)Y(X=u$~gk7@XQ8V zfqio}1fLv4JA@uq;|M0qjh7RnSXrN!@*>=+kqBVq5yA?igFzDtUvA^SvA2dafoR@+A1=S^q;?1yzs}0HtxNNgMtj zRqYcDLHP}(juku9San1%mwXLAC=Sdu|3Ad(LVp-H`}x4Zt&XYj-@*i+<($8FHq`D* z7vS+Fj=-u0F6&75ehbAW7V=%9`+X`*)mTWPPCirP2qth=mF18>PXhf#dF0#bT8_Xf z+t=x2P?H&AWTxzhFtqbHSn{g{EnKfrjw6`Bxn7o;sC9?9cr*HYbVH87s!O^_q|+!@ zvC>Wc5^iT54KM1ikP?@4Qsb)G?}zRnUJEvh$x{Wo;LT3*x_Y$eqA%AZ-!~!>M%XQp z8o5kT;|L~j%PJI4nZH5BOnYf}Ni;`bReY1}WWYQJamDHW>=-#a=0UbXS6cCVy&6X_ zfm@c%0zfbrEZZiY{I-)Luu5`66_U;?)+yH?v~ zfsh(5Xe_?Q5m@yuEt_~=GZR-s(%>Z-uurEPM=-&+`Sp6E;OuGzb#>O|2&~#ve<^V- zZ6dB~E&G^k?cfip3>OmC`MCP%yOm_~)Q95pL+xmvkX7V))K#(Z@%Gg3?mCix@{PE3 ziu`=^ei#7Cph#g}BT0=Tm< zuiijLXg*?o6K~H;k9+y4aRd{q-fkoIU9XFU6|yftyh#*{&ipCGj<@6ptZJ{jgUo&P zRP6h85F-}(E`USV73zLrx@sK3ME-=G#N+ZAQHYRx(ecjFKy~%icXkv>n82#`dv}mG z;wQ1&9A`#MJj%ZA+O$zuPYRT91QXAG?j*PJu8G%w3}eKKs|_LKmH|Ww27s$%9cee3 z6vV$(u9&-p;95^?heCKu$c=9YUrd{ERiH4jq0X1=@n58p{uHqr0;_O+FXqA1xi37_X$J%Qp5XS^ zVuG*x(PX0y4D4wDeH#{W1XkhQBWz7kI~zFF*$5U7-oov*#Kfu|{-p7nm16nC8|+$1 zK5tQs3 z$q`tEch0i))Vm$woU0Lh5L!?i!9-$CFgY1iDz4uySEeZaHXP0zH-KGtk8(SzunO;$ zVr%Y9+#vCw9t`j_A~=ExNDn7|)#tE5*h>1)gyF zbwf~0Z6V?aCh*<^g<^vJc&Izx050U*QDFkB@J=g*qQxb)m89DY;y5G7y&tMGm-=9V^n5?gckorX+oMsNfZct(i52e(atlkNY|*t8=YfmL{y zG3$3<_<-r3Z}jTahun^3OyFHGET=DcgUQD_dPgv&_-|nq-qp(LeppR}u3qoxr9(X^ zj$i_>LuWO%!hGP9>nqxF+Gw6YyLs@gR`xzWKLz@j+@?)6T_}#=zsqMJ`zohEiqTct zDL0TKunO;LWjm3&PKOuck5h%_Y>Fe8;B%H%hBHCZDWMPFhI0f~;a#mPe|2sSWX{j0 zA7)JCDrR8<&v~zID!d0 zGtNBq1}%ii+gs2%@mgHg8LM#qntidjM#G?5WBTl}JC}#U1V6Vuy3IoP5!H}xh)CfG ztim}tHclL{5DXW5BG)JFmv96Vc&3qke>g3IMS;!9{U;AO0;_ONj-C1Kh43jOTQIz% zp~ewR;F(6YzjpXSC>^391>Mo*2&}@cc5H^1`HU7F9U|U+V8prCVFJ%hvCQ3_1u(rh zMasKr&JkFJed*W^p11{2+GUvJ+hZW-!iNbw$Hw+eSVY0st(T>dT9hNO3OmlRcT|rk zaC)~<`l2(8bC$ydpX)2|iUb$M7ilQ-qr-m-tICiM9-Au~!+ZgnpOmJw7|nUOVFKqC znLp0<2yicHq`ucS)>hlT4o0;_P2l=VJ^EL;0@m1@fCEovOW1kNoohwd9e@TX@CG3j2&5m<$D zq->NiXfC9-%_irQcdKy(6FB?H9Mca5!pRM_Oqpci)Rd|OZ+uffz6Wn?)rL7Wos&NDpeAe0Uv>!aP z2%!4yws8bj;nkF^r+z*MI{g|(tN-le)>&eLZx4<1Ab7U84Q+aJD@R}zUUSK2emVrh zte=%cvd&ZE2qtj*vnNVF6jo$w5SOLvI0CB{O3dRltCLjwTwX8w`amcw)^QM1hp$%S z2qth=oxN*eKHSb+CHXc;;s~rtsMg-)x z91f>)+NeDPMsWmI-P*K?WNTVT{>AcKkzg4C&+qk6uX$*##t}^5968HVhekl&m67U+ zZFM*TtC}y^LdLi3D`gY_J4Wxs2$<~Tt+risSHclY@D7r>k#j)1z5#js?UWj4($2Hl zj01|3;>^t*D9(Pdb(TQ^VEOr$ahkt#SjYayTR2*OR?vmqiCdUi&suuO|f@ zfmJyB#lD2c%>&EBlcZe>H>hz06B8V^lF#o>h?o91o6&2}dcEb%zuiI@iJA_($+=x6VpHc4j5v6U)z})ioAhnltQ==$1A{V%PybYvb;phr=Y84U z42=nJBx4xyaMa-PyO`*2xSq6py;^l-jhuVc&z}sJi#m~u2Wr*$Z($YAU$gaatWR9l zI729HbeqdlV`AUnEo7XqRrNGL&erbkKZkt@pH`|`pXCUw!g+XwLiv)t)utX+>2%w} z<=ZhqZfqx=f9zAmtdO7DeXHkzRp?r=&MJo^unNy7us7%La8SJ#Mf=~;+`IuM+Faa4 zioS{}muK?)N7EB*?DN7vN*nCM5m<%iMOd3xM#Js$R??0xM%?@dCa{kx8!a7L2oWdU zC5zQRB>cCq3eVQC**?n{D4soBDt#W!d6{B@cUW!W69eu~qovSZjX46Vu=6Tg^)i1E zsA4Wi)7tcwu%GNjVK=c3Js^&pGvfbvvYN4VOZS&tke()FaL2#|zVlf{>qpTr;!cs2 zQ>n?#M`0D7X=1fMS@!(r#uL)eU{f`YU;;nEYz@ol2nblXO{%ximm{zW&or{9ZQxf9l#uH5NP6ID!e>qq6tl zU4QuGmr<6jJjxMRh36yLj;azr7;ac8c-F5};|M13n}OBr&z=rD)@~z<((iEuR`I)1 zOoSP*|D;ITRo&+Hm|z0GyV%IGxIp}Jz*=WB!CI5^3Mno3JUdw_csnPLTZ0NDD2S> zOiuL&9Kpm?*Dzs$NrlqmpqddzQ#ui?$t)Fqr#nYr)tzyNg?pV^E1l<@WQ5n%?ldZ< zFLY)VZ_k=P5e~Uq30>{?lep1M$)~t7WwvH1IY}Q09}0p6#TmKE|AFxibVyZSs0p_K z9Kpniu1!dPlXk*Tg?#4M4q4GNhk8PXbptp8t2R166ee3{3mwO8VZ`LG3G{QaDMTh% zgUOr5BzevOp_BDGawD=aS$8H)=-+NLsoP~tO72m?eEW7r4EIT=Sq*wZm8%8d2qx@K z8IuL%o3eM0LPiv?-$V5a`oPQ9A|RD|zW?#kNBj;Ll@D*&f>Qh8>hDbz#nTE3#{14^<#@ zTdxYSBwvPk*p8_b$)C5T zE@#kwsT8zkw&Mt_a+}bOTs&;A>}n)2V$b3)^m{~qF#oIx>vA1Q_2JuPJNBwbNR|^> z?7d6nHuwa=wSU>zXHz|x*L(o9uK2>$5yr&C(otmVWF1kl?F>6cWKk2Czo;Ly3w_EF zScR(|Ga{@Rb?RseJ!1gyJ$j4o5EA2#2?kv@{GaE;@xWVB=VAu25y0K;n5YZfC5+IH z70z~)d(kGb_2|>cUa&LNh9j^FKb!1p`_wm*I@$_mu`2mEf{FJ{p9^c1HOiyM<@RV3 zXF?l|Qo^2ibB@5O{jHmmexCZukB#N(##(hJ$vOjjcyYfg;NJ3byDLJK<47gUJw|Zv z%HFlZK9D+pCom~6;`&`oL@#+K)K87Kl~kwLF>J54pf-bt!d5#&j=-ub>om!<4_9sP ztvt?%8UCH<-5n#rtz|2~5lm!s*CGj7Ys(U;>^E^*2&4C(j{#z*fXLY`$e5eXWsjPk zA>#(>k?v*_RV}|>BDPMQh)L2aReqIRA$F+MZgO1P7-}cj18z0^hQn7{p&ITq6AzTSCc3YmUGw+%{}By!THHLjnH5{7pNGn z%e4n4_!hKOj-rPqyTi`)S{#8@xHZ`*ytNk%6}>>qq>kbUCLSEuCm&m7syy$=J6X>R zjH4@Jd?4B8E=OS1m*lQQ%i@ko|EXL%`rezB^!Mc{FsJ?ziX)gfJIsV6xPDV*UA@Z) z{~cRtlR{ruxqUZBVAVV5PWli0qbgY_SLSvfwt=qhH3}5d>S#-K4^rc%jixNmi+ZB2AKKT};W zm0e<%l@`*eHEytU=v#^-n7~(^z0WU{(>2Y;z&rbE9D!ADO$L%IcWv=_mb@ZGar`Cy ze%lFbBW}}nVU*nIU99?Tca}V=wj-t&8;W;Qsz_GSF!HOSvshjt|Ej4szf)67XV?>b zl;Q{`X1*Lwjztd;6O-h9ESf0|!K0odOt#w15m?pUV=U28O&3e@@5@xH*cBc>;qP6n!p{x+R=fL|-v2NbntYC>Pb-HI zPm96gPS=Oz-V-2=#9rcsjrWLnY7jBrD~LOF9rfVc2U4kF{8T zbyy1qJR{(8{VK%~Okme0mKSZL3${fA;X(cdj=(B@3|FqH5AD-z;NcFDbEv=s_L5@0 z;UC(8IUNA5V~aQftFQwHTbGe$1nP^nP#U$CbK1ZJcDrKkr#rgBhX*#WGdq?eunIeg zurb_*ZeUtz!>U0K=Nv;YF{FA5QEbT&H|ofqNUJ^iz}!Lo;d?+wj=(DHZ^Gt3u2{n( zdrO$~@-pX@f{EG7XOWMm^Tb8J{t~=B$3*-o_!agkuh3SGpuw|_oShktU zdA?v`@DV>!+-s-!sjIx>u-(ofur<32T>qXc;=hGe*l&jAUcDV*Cg}|QzWH$8HJA|F z2N3-Zd&OESxh9}a-(e8rX9!6%iZ}wR@Vp_b6}EdA=nZHKdo_PZID(0n>x0Of#6t11 z@gH`KFKpcNdV5Pa^vsBxgTyL4yU6y8+PJ_Uu{n5^4^ra@CVKS`Ayd5fi(S6U)fR?! z8U-HPbztj)yh-%Du~|7RI>@G^^`SHr-|)_IOV7x ziME+X&$4S(-Po_}>cl2TOR3G_PS9v?58`lOK8p!SaoA# zg3@{F<+6eIt}voyx~uYG+)M~fxJ@(KY73V_+*I4$Z;|>|&Vt!{qH6H|2GRK3K-gm3 zQWZe1G2+q2Q03!!Q=#XlR}@Duv247PFsSNxSy^X!WNGdz*ba_k4ie1Q0uxv@++I@% z%)T>l|Ns0yzE&!fIv>5@&2w$Qs`Ktcgl0KY$_CE9M0nzA|AWds&Bwr%8O;GlFyUOe zSh(H4#AbfBe63QQlay;}MuJl-1CGF|={*&~*CeGfQd7g&)I(bdw^2^JQ$!gsn;$UeXID zG!y_wFyTM^lQQs18^NJQ&ihR%+U z&s-M{MO?Spu=y;RmH1UK$mpS}+Alv*onGA`1qZzV7Bm1H!NiMWcZB9mzm=sF%U|1f zHvS;h2PVR^lv;`jta5j+6RJ|@sMZa-&WPjY_2}7czF=(ll;Q{`QjC5HJ&ISVYL3d^ zYT8y!l%qRZKv|hB;C9CM5^fvT@7@%Y9jEkz%iCG*72OS(z;`99f!$MIIMq^s>pOaJ z1Xkg;Q7C#D4-q=WJHi0wxQQc}z)u%@J9~@52p9oZ2Dak}tm0Zz@iOeOP(5ihTq|k; zID!ekW}Ahe88Kyc?sDBIv%S4Z#RzwZG1BD-PQ~3NA0D}pz@l+*T2~7cD1wRQEh~h_ zMr~E89&(?U7QKobx;O!5S}QmLs|xM!2@l)_)o}~C-`#pqL2sW6fki(uX(Q*S!jdD~ zR2OI5Cx?4~7LGZWs^)KeNIKm3DEvIIU6t)9SF`FHxr3x!nhR4S3OM40;R&I1Zk)=e z&mFSo)k)!!@fuaedYRauFOsWU=fRq9SrkXyd*2Y8^R}t>ZFxZOvDvqQUNvdr69z@Y zlDK1F!p;4;(8RYy)k`h!9=PpLN7@Yw1G|KHj=(B>PHYxHvk_f8Kb%$0o=9;769+xM z3i=aHs=mB^!j94Yx<5(U;tx{m3X0Emc2b_uYX()l9eU&cocY;uv(zG=-sEdM)^|fi& z!QX}G%nPc9{az6K+fSIj6gCa0P{rszW5k7QZR)i;5(fOXrZ|ELd==Oi3;jSe-bBJ- z6I+hJs(vqS3bn0@RUhif*J}5(8)Vv3Hal80li~;_aBH%hWfwIu>C7stjGfI9SY?-T zTJY?#T@|4tw|T5X0jXRU20JWLD2`wP-*4<|J0yb)y$}W;oOlAO%5)D4`7zllOJmvl zEJ-hvlr;?nkCZhOM=-&+M;;+%?zcT*&z6ROM@XYrrJAK2omZCs;u7IUOG`g0%Z5Mn z0m1hV#Su(Q$V@deAJ9w{@>PD$E5|M=b58XI=inNSz^a8;6O~PV^-+B_k@F?0%zDbg zun0I_IG^rYooaTvdxFaP-90j)e5ta8*{r~*95LIB9{O!ERXt*+ITR5!P z7fW#j6H7dnDvj60s!U$U*^e^24BHkP=fSR_IUIpiQdX*2ePdtMuL}8Yr}ysI`qYGg zam;3lBbey^AW8Y4oxf_tdO2%wf3dD@t5-qLaB~qyU{yLh#+3!0Dpdpd7&nqrZ7OX8 zpyk{n6h|<@U#so<%S-o8n*}xH*Es^Kg5~xQTB$m?$-U^O1`lnpwTssl2n|2*G1`JQ`&4&ik^<3bh?UOX$Ll`Y?gV^K6}^ z{=2g2nImAyleQdzRd`g(asX}GsD71?fq}lwxX~*n@Eyu_S{$t?+j`a;KG|t<1XkhE zIhzg7PAjWg=?gQxYPgX;Ch&D*RSK#b+bW081hbGk9D!B%D}(LfO@uo>Podp2)92_C+#qd0%k zh5Je`h_BZWFo9Kg9K_ZE#O@J>#<8lT4h;ZDFkyFNi(pf&p^C4Rj}g@6o=`Z;3r1z> za0FK2aS*HHHP3=*&zuCUn|-G^f{AXX$Art@Mytjjm#@`1k1=HTnMq(b;44R96&^XU z>|j_nd46sN?CW});s_?jw0JBS?$1y;>d3w5>wbHL2@VUP{kB$gU7U`v=XtW~vg$rb zV(oO;D_!OJ;USwF94XX#u2HR0$ZyV$-@XcgO=2M2ET4;DVt3|9;Uuh8ZD}HBYwzX( zxw|6~}|(_B^T3_0Va zyE%t6uvi57n@c$YtHx?%3)w?9tB&t~$%s==b}1)W$3SWKP13AY$;yQn(^PiwjI>_M zdb{W})q=54Nl*6gzAMB(|E8d7Pqh$FDd zgdHRASiQ2sRW$JnYM#W9DCT8*x!j}9?xynK|U_R z#}yf>>%vP?65mjmb}2(OCg2%qk>5}_cpzPMH&t%I%qjN-tEY=#mvm6V5lmPHB`dc! zU8x$-SiZU;?}~))XBWYwWfdHORk)oLiuyx42!ASL;Ka7}Tnl32!kSdG$dEMEhQ{)} z8(zCh8E_~D%wvHgunM<7b9Z#eCwsC(;n;|k>OEn}Ld5WNm4o9Og0I4_B`!i!j}@v< z_OIA6+-}V#yXQp0i_VkOID!d$Mc7X75hF-n>qxk;VH!tZm2kA7aK?VQs$#o*w{Kdf zAWxH`Va#)5HI86{zgE2(T@q|r%?!(oUL1i{GmDdzMqQSxXt3OZFS;p(qW{O$S%zh` zd~N(e1q2l=z{CcmR74cnGfNZ`P*Frh6ay15z(5pCM6kO%P_e~;y?GwHv0KFME^K{g zpD+J=-t*~P*M0xoz@9y^X3ZMsWZK;EOD-x%$lnLGI_p;@FNyA+FgGHBuAbtHDjhaU z9k5!T>7R@H#w^5*=2^9^OwBi^DJ`7h)v`a|u@1}9lv~M@)jO5nv0-=GD<$T{sfWGv z6VlWAU1zQA#Tna~zm2FMG4p79rR}*%YD51wg1G)NgFP(Pi;|*$Nd&qqEv%JeW8>A( z>#qgjxj3CYjEJJ7vrmkuAaV4Qm6H2>lG@~={?65U0c>4(6fLdsOd`;gSTx-)|Jx{a z!$X~L2`R^#ejQ9pEG`;RL1O%yG{1HCCaarH=>660yYrQ)meEwfcvd3NResqF=VzBD zs;|!L#6zvP;&W;ky>7qHhzb&K#rvpKf2umahEBLN^yBqiyy)bq2Bwl5GL@fOTdOha zKe2DCGL?mwBGo@{KC;4HX^Q=TUaCc&-ZSL4t<6WiYep^}wM?iWfp1oTqWiX+F1hxgSnn=!2_BV^5-H}Bk0$n4-J2yNTtcC{Z&zSnDit-@4 zFICw0)`$ucjReuS`B=4fsNND!dDZ4!`&x*KJzY!{)imW?#Zu~}M<1C>PMUHx$xV%I z`H{W1?w~jvE2(x2(`#Tm?r94Px?kO>te`ng*xjicPv3sdw~k~?u8JJF;JZL#Vk z5$F;p)cr;-vr*?v)rkgW`m!qnt59|Kb|zGiIOU!0*J_ZbTJ)se`?z^NReFwdq{^?` zNCdjdiIMa8G*7idx=yTE+e2B{q%L(R-OPjv5+(JyM5hL7uXvq!>eG-@%LP2G)Cg1A z18It3&#ase$3C%)>@=ms-5WX0qdu``B|0c=_Rh%Z-QuGl?v<*+2SjCZZ|Do7M7 z)j@fcbUmlxef)kb>bufUE`WsE5~=F=e(|`6EojEU^92_;cml+novRF zPh)Fke9ZNnkpJc--xJoe0pnKjyxcg6K-aPiQctc-~+$Pk!dFQzA{MAc1XK%wB7)U`8g~**b9SdG-pBuCKmGNIVLN_h*+IEmsxW&*lHPV3U#P=pZw==2x{NWQ zf&{i{u~wUH&I|ff=b>v8B?4XL{j8M+?(ehTMC)z$R=^83plc}iG9{Q$K?2*fI3HCd zgJmYv<_9m1lL&O-Y*~y3r>3%qMcsMVm9LTxwcKI+-C%xZoG|SY{A?kRq6RRT`jx6fMGm9tWs|lVLv*>QF!1+jtUZT z%(C<9r^@!evDCbVNg~jN@c?laV1_kY{4<7LJ~_-$K>}me2E&P@qe|5;{b|t72NHoU zj0cEW_^Hpzlgs_7v$d$V1Q7@%Fp@52WX+x^jZ62TU-Ldo1iCODAZmpbG-j3G^{1C_ z?{id;z*xV?@j4N~R@NRsV^Rww0$msn5Z}3B1H14thElfXa#WCz_dn{b)Y!Wkv9z+Z zDiP?C;|x{Wy<)wq4X1f?GdLhaxqyRIsOt;f>8EzukmBxaVJuDl+zOf4~8kI=Wb|DkLx zF_s3I$ppIW*QYA|ofoKiEA)8#<+@(1>FIH_dPhT!3KFM3ELHBcSgT(Dr{_i$T6(d- zL5VcgwWCC!E9mzUWnb7r^-F;Mj9;xgFz?lgG(W5zM+J$NIa`!j?^dZ*UO&`-s(`b8 znP&)751^o-n9&q5EKOQ-BH@&8r8xGUu9}(j^+(f@J=n?Z zqv&q%EQvrDuBk-?GBA}Lzb5XNoxV|8J0o#uQ+s8^sp)EkR{9Ki;p1JbQtRP#t5T*! zpbJ;}BD*d4B3m^enzju+D#ZYhsGOFj?6*!=7kcY+xR@*7Sl8r%w0Og1i9nZ{zFf)r zm9B2>r1!hFZLImwWs&r9`gcB7vAifWu$JGqiXpzGWq zO=)s)v|2p+lOV2@>B!w4Hl>E8oK2`8VLw7sn*Z&sZm#`V5T^%5@m^{Js_#)xBGBdQ zlBb*=+gF`5`imeYzl`TyE$fi?H(wJfNYr)9QylNKRXbJvDhSt^;am-z%^r^#Ych14 zq3E%x9zHZwC7aUK`qF#Q=VZ-nr|VjFpj z<1rF}E}RD&46*Mcc$2)-{L1SnX@-o%n)R7VN>dy4=Ux4My!h3YH(z(3kKff>BG84i zWwG0r(V06d|G1jcRa!wJF=1n-(sHW1`ml}u4CC--{OK5LYW^TZBG84aNs)Db!)RQtF3S6lh`UG{v36S;;rlL&O-YEtZG+{$KAr|MJHeT_}1AhErswW8&> zR{gT{zNDc0G`4z!JH2SFNCdiYH7VY?c?Y(6l@FPJ^fIA>M4WTF-`pPU)X?X8^uvD9 zW#w2x1A5h`iA11FUZu_tYpp1a#9^RCo+ea~I3eN;9iIfNFQ@CzFuHgtE|wv5@_0GZ zc%f`AGC=iCc+Jp-Q4w)Z+)7Q^e!UGn-ry)jKajxZiTLi1rtGjw5ZM%|BoXMs=#Dta zx_u=3x2y$y98p_};vj*4H-n)>*=_9jyOy-+OLd7r7e=W>RBiiN7H!68!#P(e8ifSD ze}iG`uivbuxPoV9u!}^X3!`nKze*_0BP<)yp0^nW|~(yh?@4Z09{Ca$c%BJ4GLHKFyfS^ZRi!Z|G=3 z1qr`Z_mq2CbJgs#df%S#X(-PPXie?B>?8tR(~IUQC;!Y=_qEdJ3{S`Q;wztYq*FDm zOsF97;O%*3qj9l1WxPHwX|ui!&pFtQP7VBHL;_v8jWosU+CsIml|CA5>DGkz&g)Hg zK0Y#{f`mgAO>wKULe2PZeic2t79Uq{AWf}tULw%dy=|t_@842&d7j==2fLN$al>P2 z@VMPZRFK%{o~abxTBSCAq4$YPtDEtD;#P#Z=axzYx|+9Gt~?yRLhZ3gpS>eydbGzg}(lPJbWEL;7=Dn+U2? z_q7ofB$mb8Q?8U;t2+AY@8eL^X#VtDXX>=Y%!CBGYW{nx^l)CG{@bCql4YKA_{D4| z>bu0-)Ya#mV%2$oYB}f|!#0+ceNXW_lc@G@qJQT#CZzKHR$gQ@cQc`a1hzMkH92A| zAHe)bv8^Q$=t?S|r&u?brrx#EfAeyF{HmMQ@39 z%Ku~!){G!e&s9cLkdRyAhx#{Jg&m`4ki$x6pvF}V3B?4XEMcOOf2Zm7WqYvP!9y&Me*bnR$rrKmF&s24r-UF6Z=eu2dP;BduMkLU+`09CO@Pt+B%b`Q`-t%6inXoLFaroMJgpXO*b2);6Jn1io3Zi@YL*|J_8i(xQq)pbN)cafVk-c8?gp@IaCs0Ks1>;-&AzY1jc znqyz4d8qLInvNgGCJB_#{64rUzy9tS=GhI#fMR zX|^~)y?$K(&NH6I^WA~IRPS^h6DmmH7%bv&hk9{O|K`-(wW>s*t7e3zy!^DQwKP@f5wt-iQhkIHDR1a|?Xf`v=K%T-lO~ z1iJkCSShu#7pRMZ^{lW3niVS}a=bIR3ggiP|p0GjjI6Z*^K9*xhpewR!n%~;< zbJPdx^<9AGL*DoeA3mBU%}Y08{2Oy)FlH_Gyv!yjOKjt5!_>7#RFJ?d8*vKztAUMm zji+BN)<^`pFlH@Q!fibm|2&j#jW}RL1qsX+5;MzzV_01DP-^nK-z16RU*)ZF>8?zSL!j_^Q8~DK6q(F1qsaF5?}2k z3tnVHPnyTSNd&quW^FK(pH_8?zceE34lj=_X8ylHWK|+qn zZ22;PA2+K-e~&5>fi5`~9@Bd?UuR@|X8M^GkKRm{36iBQIi=I&3)~y7xZ6`JtOcpv$}NJ7x62vg$IM zAL1F02Q1uh`lQOl88tlZD89iqP5I{AgQ#XZlXMOe3GzJcB8EpS51xbz(otcDyZ}&P3wrVr$mp&V2Pyyq>Mz!o3RboFh&N?f)zh z=)$w4;smJU4jxfFie4wJ;8_0#>*CxfO?wg{cq|s0H1Ydc<8Mmv|?~9Lj{Qy zN$xBr(oqXpqQ?MkKD)*jpC3diW0`^kx;m#dWDeGD+RHxrY^f%{%BxfvOmhRyYN#O5 z&(o9rJyu<_{jC#K!wdMv+x@BJtcAHqpzBrJMr?_PyXJF7k4D9m%jaP+{b{z}!(3F5 zC_Gk=P0g&X-6ef4+S>Sx-+tAb%nNE5kwBN%J0I5KjH@=cq#mvPo%@(82P5g@l{Q9H zkhtK}fITWLs;czWiRuU5@^%*C>KOCr#P?O4>`^%kk|RfbZY zSt*7J65l^NvFh=5+6vNV`pw)=@_ptplytYNh6K8>9UBaJZ;$bNt}*0wGbk4oBrYVn zuo9c>wZy4<^kYx<1%Bw-AadP(RwB@a?N~%6KAz*JT?bL+^(Bp{AkpDLU3NdhPBUie zU(}kmH+bb){b<2mE)nR$b}Zry)>rwqcYUbyp@BwJkoZ~Ejk!%LqxC$Xe^EQG=JW5O z0(k9tGbI9D*zygA_u6Ydu5EXEQ7MIEZ6fDPKNjy@SL@U9!T+mMlo|Af&u!O((v%pE z6^xKrwVbh`(|xqw3-r;zIP4ogyeOP9&00wWy5di@V81K2)k1sf5lEYm@7yHf?SJ;x z=BOYMvWD1*V1I42Q6CM~y)vVuA>lOkZXrVgU0?HCvKvo2X`7bnefz(@MQECD5860+ zCqo5^J$w9__0YE3rt^B=e!p>X3P|im$~6y(K-VZk8#eYwcdgrgy{Fzkzc}4V=|(p@ zZS+G037<19m~%mUt$()O5_h$>p(BezsdBOExk#YPrEWX6F{qcee5c;7zD3y3(d(V* z``gvIs31`we)D=uLbOQ}^|)y1bLGfucY9Gw=7&U}>uhikdv+^Q`#3@0C9@e>j;4AC zQ(@iOMpTdpf83faS`nh{cGPFD*J3JAvA?ZovqeXVK-cN0_H5AlUfR_+q?))_R^!6#T19c~=<~G0l+(bd8Pb$UOIkYhkPY3c`J1B^uw^ zkD3&$GopgT;SGW8-}<)NyBj(&dxRr(Ti1}H4`xXOx{kEy#8S$JYGXecM17xtqvyH* zfJizpehyC^(ul3UXQxGMxW}@u*JnPb%4i<7?z8P}8?#*d+FFC_`uwWb&hxz1>OR!` z*F=sA5^E26G3x|JtyeugAMVPuo7{XuADW!pLn6>MnfbDsSL~mgYt%ah`uiAx(J4`Qz(}M>WB?4V@m_J*-H9#xkq{kCI(#`1Y zi|%B*#KwpU5(NPY+r6`~rft@VB4;dU$gogy?93zrU0GFIFsoKAG+L;CgKp{O^!|P) z`ZcMa5fvovd}FNMA8(Cb>BPj&)^tBIh*s5@E)nR8xgQ{AGNh&6(!W8kg~jOuZ$}+B zEjOZqM05(Vu{rg$MHc$}O1V{%`1|H`DruKQplfJiD`vB^i8khw{tcebu%`0Ono+0z zM~tW-(f3(1*6p6N*7CPbSjUKpi@{AOYUDMEKv(zYt(lTgPiy*7|7st0Gf?}GFfzLm zDb?%45zfohnl*3JQM-Ol|Dr10HqekyUCI6-iLChlDM;W*Bu;0hSkR{tVbnLNf<&OJ z(#5u{>X{zeW-tBwu&QH8w}*D6ke#m>DoEhiC8~10C`pZ;g;MI7#S($8?q36$=aMLG zZ?gV<^qo|Sa;kTsP1*Jg6(n#Z61laF%h93O5L)1TOhp1+&+4{klU5DUhHTTn57+hO z$nSbb%DL4j7ZoIM>=N(8p(54&97tIM_eli0vio&pnU`a={k!$KPnK&%DmJSf-J5M@ zLPyF|R*&yg;t1yBWZ4~alm+hv{DfOpcmDY@EPI(nWji?}jW0yDw z8D5hz)BGscCrKjEb?k5`TdYNEADZfIw^&pS8uPOWPyTorER)@0sG@y4i zHcAA#nqCTHAyWrvKkn+S{oJKm^eD}ff~M>@qJo4xs;%;LrhxfQRI&d_i9lCZV>dQq zK`*W3q$1)O9=ENjutg^t@zR^0m>tL_91GJHSUq9*t;Ed@X59=?+T>;W9L_Jb1g##~ znRYiS$5BB7zXGww@h(I6M9sdfUN;yL=t|t(fu$@Ms(mV}j~^Sql%eknLTJm~nG6*q zuuY42`w9nY>C&DYUp!KfKv&fB5EkBdwB|KjA3v@KRG>j8gDH(UYp5WBUxCP5GF7Ee zkG3?TRah<(=z8lO%G|n*(_%99(IDN~krF?)rgJZHa#2A7zXDNfvPCUYe4A5N&EiHR z&~<4{7>kKc()>;O+IeI^EsAa2jJ$5uGope7egz^1@YtDRC-~Bp{B9C~t^m8`sGi`h7LvcGLH5U0#LZY}1Pb?bJ@awYzt5 zrR|g4X?D^^BPvMXS0J)?PI^$-%G#7YXTL7W=)_7pg#w*RkjtfuMpTd}`*HwlawtvP^`xjE z4lVGdBh|~%q}Zbpfv$f=`>+{hr)W!C>A(5wr%h?=9D53P-)lq#iJ-YrZ1KgJTIN5! z%4T7HV>&d}k?eP@mk4yNS9>vs^b~FU0R0Uv+uDSlU#UR{p3XI*f`pGtU-os#Z0*56 zy;|rkk;j=CTbFV!BufOkx<*AXo0-$JbGP+*$|ocDUR$?ZZKRezoXPeVS!zMBj#&FrtD)`Ou!MQ`K48 zgLr-A^{uu$9lGg9$IhJ0MFL&__H<>HYfja2V)WJBy*X~Qe+Z+?VZ(A!L88R(a5k|? zx|aV*ADzDpb)p#~#V)dGnT7DA-34j1%ThSSY*)LUyuL(2wA1iCh}4$NV4g!a&0kM&)<{G8kShmrZvRUE5WW3&Y; zPa6!odw=D@mqY1EmAM=hB(SEmSf7_KO4%VHWOa0!M4(Ilsgit)(~T7!DLpirqk;sE z+G1D6&X$6%22=9+4ibSb{2Pkf9S_>lE58op^sAoqw?YC(ZLuHaXGdkK1rv$7efV#o z3*W4$jcaYM-@HiiTl1t=f&`A*BKonqGR@CyN9*2>l?ZfU3l(?j4Xr{A#msWdm=jWK zM*>G}F{%~RpdxKsQEFVOhW{42@Jkba-ISV?)vhJo9n(kpYLUQETdbopo$1yiA|>{? zM4$_M43XDoaG{qaISr~{E%iP~;5aYNlI?P*n(G_WlMFA3Ko|CvqQ2-nce-KUh+GeL zm-<8`aGV#vM^=3@7kM%-?@W*gbYY(_&Su!ur+*hk)$B3zrM?{r9OuQHVPQjhQnD89 zKeRz2(1l}{!7#s%7uCB^jYbt@Nn;ceIL?b3^1>RC_c;f8U-q~}pbN)fk-5C4A+g!z zY4EPA(pZaxJOdb4#)qsHm!w7e9!LbbaAqJXb3bqCUjwKo^s9mqdo)Zn^1>hmsOw@4?Y`FLE^!W&TM5~JFPHDp8@36 zuTFaoRi(`zzDNYR0#3ANck49P{>A7-(TJ+l?pYmL)AX4U6(rgO1+z0*{#yDseFo6+ zfT&|(<3{BIWddFDihhW1D!(~LM7Afr<#s33v+ zxZ=cNn?t-}!`?J(*G7pz7e)%juFUR(yl`t@dfH(LM+FJo`4wxK zRFJ@ZT(P2$y~z&*iCTI?-!ml8g^@yWBiqLtoc9|@z3*;es33v+xMFoT{t;gs)t@p3 zRFDXCVWd#p%D(U+?|n)9t;#1hMFk1m#}z%p*EgK6>q~W)`{g2mE{qh4FRJfrezu#a z7FudsE-FaiKCZ|~?NZ3^zw1eDx|>|#Y*`5Xa4qW1U0|yW<&)E-1!w}0et`R zsBT^9e9ImZfi8>`im1U4aqH0LF7za4q7fA&aOYQ4RjFHq?pk-CZatPr1iCO%DC!Q@ zHqhiXK~z-PW<&)Ec~5w1k78u3){;gIHc14!Ft(`Yc!}A?t?`tWQI6x8^94t@D#e2{ z)E%>*GWq;@_qDUxq$lHPwWke71qsXV*-BoS?drZ5JpyTabPij4ZX7je?J5!I;{CFf z`o}ZWAsPSe8`R&;f}15#ZsA9U3KFm9omDE{%2Ky@>$?CGt7J1WB+>ahza#=((?6e4 z9$(+19v!RyR98i=&6kTwbV*&nP(h-M?Oo;I&0O`_e|Z@PJG^A079~;D3M(Z7T_XqH zQQpdax$xD4$J1Mf4;m^+Y~1)uX*2$kYAmD2mX;=o(}0fS$#&~qi9pwg z*FP1fzL(XD@%m3y%vD48$(r(R*(pEO==TI!RXiwY9>{>9$i^M-uK^+dW^_n1VWi(9`@%nzJUEqCg> z$Wiu{dBVN%lp9|$7ZoJ19gACBo7?ej7D*Ixvc5#1>*%Jt%Bxeks{e6)-{8^uKP=BI zS>$YoDX1WU-=p~Jp8w2dx+l}Hk2n30K-cQ(=ah`n2h?I8^=NIe`{&sDX34am_*jMt z64}R*}QDdU8rWa&Ma@smW*e3!li#K_5`ixH zuUjx>7t?+wlkbVM3MxpP`I@6#FS<)r{_3ry)QbHqZy^aKgNblSb0OxnV3hY@99;=)#dm ze1n@7^Io034EUT&SQ4-^V349pzi~TK-ac4_Uzz_YwF>e`cHLX z@;cu5OHZ1Te8Pwd68Lu$wLfRA;tO(nlD6WEM4(H}v0>wTUr_gc)pxLpZJo_6Tn5m= zx7&@VAc5~+J|7yca)J#vwZl2pfR*3gN&#kf&Gf;ci%SPC7z9@P0s=)0$uf1 z=PRds9#muN=y?DgnpfoEn-Xbj)lx=Okih=YVE7Yl$EyS*dE@*KDtbxPF}}z zP(cF6U6JejcpVF?JAuZ2nV}(pF59eS%8}h0)JbRc(RoqmWHzVm1UlnZjiG`B&L2dk z?8#)-Yxo4Z{q~T81iI=Up02#_vPNw%OyB<~n$(m997(41r+XPHNZ>q3%y)ZD;=K6~ zTJ~-&?^voL>+F45Z5E%;^2U{8GftgT&F0->t+h&Qq~%NXNOk?Z!PuS2eDUrW+IxBd zM+J#<_I50&{zG+3bv+;MsQ+~C)@&%XoHsf~zOF6hHI0{#8cqdI z`*Bo|h}vS$>J|T__F1OS;qGpl!}|x0AZ3fMM4)R(2}f4Chq;#RrN58kqi6A(=J7OT zN=1$e60B|o_Pg0%)$ONFR1ROlpO%fMba86~66or&vKniwSZiJj^|m|5b`fvS#Z5HR z=Q31~=sCY43x8BZb7-NjAph_+{DxmVrM1ackU&>d`5NrYfs)$EJNkO?>V=j3+O~L# ziBHf_LBi%Wp9zl=3rQ{-ku9TRX%<6DS?URMxC)&;3$Xgc- zr?%Jc|40o>0I{vZL_;P*3@w;)9x2V#O{%%c?2y{7YcVmB++Gt%H=;L6qCFl7H zHG=l`SYt#5313flHtMUjHgA)jGf~GipYOcanf$X4Nd&q&EN{qq{w}S3Z>#S+e`&mv zoi5jp9`<;_@!l@Hdt$|b2g;RuBh@c!ZwaF6ntd##!9Xgh+~lYrf%PH9>Hd8mS@4Ev zqT@!1K-Z*O|CG52TUEP8dL77(UPZZaS!GT>A_nlcD@O$hyc0|0>Hn$A&z?!3)*)^Zfv&Sli?W_`Z>S#{=-+vQk28NC zpGYpJ+w?A%QMhQH*VO$yeiI^q!$kBjUk*$Igj6()1NuK_~_xZiM2JN zg2dykcI@`Ix9XmK`W$ZXgf;x>s3Ejx=Ol?hSA*E9tcJ&Tm6g}$?fGZ6@|D%1sM_+? zMpTfPbD=709`QltGxRJAN1trobV}5Efqx5K9mdsR<>G&+hVS}!zNG3gUbSCm zvVL>Thzb$|uGV2*sqfUCk$SdB?2*g7a;LWRb?+OAK-a2)9xQKap=y8Yzuc%-cX*%! z(fjE|OsF7XvEPGD?e#*9_t3Lm?!~>}sizy#*4`y00$mq98?otu@73g6`o3D_jUV_{ zUl&@OZ*M{c3BTcuSnKomRI>ydO!{u0^4W~2 zRB8Hb;cP+$i9cqHeZO!)H4D-AAiITI(xFzx$U4ehBG8rTAHcpJyQ=nFrDr+?4LQt9 z*DgbIGW<+iI@+?)hi9vshy7xvFk4on;ZXI{yx+{l*MW8VByLw3sQ-1F-aW~udsxz? zP=6CDNG#zFY(|d}>i+S1X6DfC7kG=Q#mPT}O9Z;wSXE$} zENyU>diUmchQAY8I56v|L+YK^`YN@|$Q(Z3tUej9RX3r61pa>Fi+XaD-xam=Zk4Gf z5$M`+-I2M^(A0Td!}|M(8j;CAY_p^uBU?)Zy0Bh~IBD^28?WNxKu0Pm zCRC7c3bACd2WG05=jeUn^urtY!LK#w^K5U4Ko?fk5i75H8~CExp44%si&Sq3iF(|U zT@PBTKK0jUWC~xw2Wd@cWT$EpfiA4QB-Uzem-Cb5T9CC`)`SWYyqYDuv~ssf;`Erv zraCo`e<&S99vzBH1iG+>l-RZWQ^2d*&f(=s%dMpEMkkg*-*Wy|E+VxUkr(d!l;5yj z!`E&OGhxd>VtkGht9FR15+nG>70((?()^hhD zzUGU8o_=g25$M7;CVGbFhj>lJmKyxzCRC8X{!v7P%kJfOHdmx~{hCMwy0DFj?}PU8 z-syFy?qLrTDo9}8CF&F{*~aVbsYiy%btD2^*v1Toq)yxTsWZNGxo#yBDo9}OD(*Ne zvYxxzw4nU0r6mGg*eXR8D7*LkMV82TdE{^U8t%!)#4c6my*J~TCMS06%p&!-xC_`Z z(v$gjAFnnTsE^Jy+PvnY%RJ#@vjR-0AW`+W6Z06Jpl%MNsr$m*Fb`pWE zEuo(5;2M85?~4A6^n*!C=lNsl~W?Sj3155-*-_ zQ<@yws1CN%qXtbE++#mxkEdnVf94{AE{vUt`PIX3>~7aY+A-79hzb&w4ya0EKe4+s zPhWqO?`Xm2x+l`C1FjN*E{p++{E}_ud6{NoXzAk~MpTfPH~75rx#f1%|G$`}?eywA z{l#dywzIoLpbKM}BF^x+9=BKG$zMs4VwOmJ`_d0F6(QYG2Iz&k`YH~kETil zx-cdyzVnP=-bb9He{+4M6njPDQ`}qS)wV44(n3A@(RO|WU)?E|cGOxW5$M9$vcX`H z8q4=p8AKl+(*i zFJ|d8nS=MUc+bKh3O(^nBG83U z;sFzzi}ks=M4$_Igv4LB+C{#0T~iv>y_5+RBv$uuVtqzmQK_6h)8G2w4xiAsAq6)n zD-r05_~O9=OWsmP`04AxAEw8Ad!iFn+g#Oz3KCuFc(Uy96KdQ4R*-M4KJXEBE77%> zIud~{N8RFJSb*@(S6zfYa9LMIBC8SU{kQ1Xw4 z5`nH*C&q%79aPuf)K`!WZHiH`nNRtoLrqPnAaSNCV|A*pR-bp&SCH=ui&L`=7x`F~ zNd&rz>t;d)S6=upiFx9JTRh8HmIh}ul%9cvyh^=hcAu|nVMSEYS0d1b zvl@}V+w>Oi-m?f*{Z1xSkieO&xS`_1J-*fIGjCZjKqAnE^B|EqP~-tWvEmM&yQG~7 z6(n#*F7{HjxBT@<6Hgr(ED`9!_9k-G;y&=8$E$gpC7q>~hy<=I#B3?-opLxys?h=76Ikq&ajtyP7 zQjFgBcQT=Z#KsdXSmByK>bpe!tG(RSiZ&lFPUecUM4$^JVWJ*#c?+tPSe|C(RFfiJ zNVugd>|~!pbxm!(Pu#V~K*c9kAwH&xM4$^JdZG$c#h*Orp)-|_C?`ekkT_o8%{+Ge zRhM|_-+5N}TRx~~L-M|3EfMI#$fP(0QQ|4@afwj}OM?`FL?X7N2dmw~OdCE{kC*f< zc9RDux1sT;UK#PZ5xVqNJEuVzb z`n*FDfi8^uia7O-EdJT6FQqM6B}Ighc=)dho74HP`frK8A9d{aMs7Z3F!kFyNg~jN z5pR)&bZR+&dT1!E@7zv`Y$GxMe0jFZzEBO%(6e_o)|$bMYCL&ux0MKVVH{p$2zgB6 zn~smBn8+PcOdkomi6vRsr>>Z5-GIeLWchqx^Q1a-ROKT^V%Yj*zHEGQ*$yiyEd!Cbg1wevqJV#aXcl zSJaii^s{}-OL=j-Gb8D;(+G(`7w&9{Xw)$uo;oXzjz3P7cCe7JUt-C24>+RwEx#|G zadD~(w+kIk-3pgW1iEmCPDDQ(YEj?4uX$mBqscuYlGU=b(WW)B;ww^mv7g^+Y2C{e z=ef2a%;#W5t(cwOi*7wqi<0br^JkSDOsF97FS;k2b<{@-y{`AvpYv+a!)NC7HL|Rj zz5Y*GeLjpGZ(CoR9Ay6gp0WQ&6*}JBhQhLKrDq`FUA!ZE^RTYwbzbj9FCKEB;=W}m zuumC@K-VtEcC7uL@>jfX4KL)h3dWNhpo2s^SL9f zu3J(f(Dlc<1+z5TYSsO8qG@JH+V|0!{Njt5P(fmO`R1&9o2pu+XL>Js>z4&J+3!ZR z)669TUB|Ecv5E!O+UR_p2uLqV6>fTyC;MSU1&LM9o3iE=9JKXjdaTcTZ@O#@ff8wt=V#4BG7ehgQ$i$ z*Fv)@r>}7$?F)F#tPXT-<7p!*NZ`)6$W{Atkq@-%N~V7YB?4W~Hr8fg#mu#{<@NR8 zkbx&TYtxGY=dL!Qf&}i@iyYzj1Kiwf0PPN)A`$2+pIU__C75aF?De&ConG7dukdKP zIi{l#6(lh4K-BDSvXWoPA5Nun>?HzSUxUlDtoPs4@|E>CLwen%yjd+#54r4_TvU+2 z{0WiY?mC+%W{jfj1V4#DS8Bs@Z0nkD>b|df+-G9PxxC@(QS`whO=R@{PeB6nK*Tqg zHjR6!qiNkTUxoy_q6*8f9UVWZCv)|T-;%ec^SWn7QN7eH3>73WpGEYdTavl$u~F22 zcTtW6y4tTS%_5q=Q1eIV+0lQuOyVWnN7Am@bvPPWzsBMz)GeKRCuNc z?O9z-BG85F9r3pk^{;KIByBld(S!;TI0lP~S>;Pp|EV@~Xh;=_Ko_oe#45FADOwp< zfv$|QGogY6j=>_{?o^x-XI7%p#Vbezx^TTCsx7=MMl-M1rib@!O{gG&W3Y(tuKvpp zv~nf)Wi}FlE?n=3J4U`0^6=T-)ctQU6DmmH7%Zyw40**jTu^Ac>t7=h=)(1m!BFk{ zL*72971enE+=vPiI0lP|SMRHQ`;d;bwA^KhKo_oe#GLxi86GjE8`XJ#(1;2WI0lOq zq{stUQlt;9%UmT9=)(1m=u1ZK=63A{5>K9NLPgT+l|iEH_zy|Gl{R-iLPgGID9a~ePSV-!tD-0@D?5RHycwb(fi7I{i0tUhQJhyzpmUX@7%E8Mh$_aYG5xr6{RHYa;F?6B z3)eda!`>SM`Gu3Csn|aojtUYu28$}RiDBF=e-zzms7M65aJ?f&wFW)-nOE`DX;cJ9 z1qmF3MJxH%j@M`rM-TQ)mI!p=3Q4T!KX%~Xe+;AEH|KIxkiaomWY!pbdDqoLX-f85 zi9naU^0KvZ=P7P6)a=0?DF+e>tWPg0g@{@;8$$+BT;zF)Ko@3(iu2B^p0IsBed*;X zIbRfs7su`@wxz!3q-R|gW9`V{+t|+TJ!p9IB82~zvuA`dK`L=jQ$)wWCkH9z@=e>!ef&|{ZF5>MQ zoRoPhhtry)J0${LYp%3YKG%s;m0SAnk-K!Oa;xGfii=smQ9%OlUKjb)xAK(9twz!E za`PnuUFIICO3%OPYT5k-;u&$RZP>P$G1RZ&WR40Fc=x)g4y_h+QV&djV1iIoT zWGKe6vsIri`ZLzP^JgEcjiEoWQ#dL};AweL>!o-v7Cv`0m3=-LUDaHv8Zq> zyIgJ@#XRuls33u-^8>x9!wWo_dl>V(pIR4t{WB|rLbJZ)~Vg`t83o|YG@ z)EqlLsrz_Jp1n;X(1lsdA`hU56JIc4Jo$hBte}Dfo|YHcREgq_D$_W6l+r>X(1lsd z;u&QE`Q`12WI9tX7ZoJ%w7jUsUM7m?WhK!3cbg;vU6{ozGPX{Q;Rmjcq6$N8jHn=i zC*;Mh{=;-$z5WOqwWqB_pbN8@#m!kQ7V*uWqbbFDiV+ngds$K3_B=DoEhzLlHwRVdP6KLdoOn4T(S(W-*I>=TE1&BekR0?;nk* zAc1?{2191;8@y&WqQV-*Oh}*$vzSH9vhjVs_CiDIUZS)K6(n%aTb%i+^M=3u=1kcy zDo6ynFpF7aY}NR}!~HAM&PO#(s33uR-Xcb}`yY>}WlL+K>q-Q=Fz?x52yI%FtY4Uk z`aTUzs33uR-XcS&SaEWj|CM{5@RA60;m(#A2k%)^(#(ABy0MA0gN1~=8-A#+s1JAQ z7OyngMhr#U9Toq-=GZjVBj7&6*@wYULD}SYByl`l za;YoLOOTN7K08yRo-%!U66N$QB@yVtIf|%r*FIHg`7N179LbXAJ4oPNYhsqM_O@c` zG=Zj1O_vCCZC@CyoTR1d`jUE#tdVtD_W0ri()RaPP(cFkXBD~5&B9pi=@aN<^Y0oG z=*lUcrdXC*txg)C$NJnRr?TUHlBxHh>|9ikz*}R**^D+B%-2S*Yf!|91iCP9O{|1t zOzh0wL<)S~*oX=ec>Aq5eHMO=Z77>aHfu>D(1m$xqMrWwcWkcMC9Cm$q!AS)Q>f&|{rD$bwJZpgR39ZE5=Yb63*n71ZwalO)lPZ%?pUR}vHqJjk8 zi!JU2Sk#dp8#tIstv?_U=)$};F*+yp;bofkBUbaG5fvoln|rq{8pfwS=}R}(o|g!8 zVcweP8HP{f?W`l{*ssS%RFIIfyxTcW=Og>|pn&3!Bm!NSwo4JxyY`@HW&Uq=>71iCP9P24fEdmUf!qaEc(o10KU0`rAM-P(TJ`1#dsssHg} z5`iwvTN9(&>Al>uwLf{;+n7*60#A8}+3R(cA6P&%BcYT;pbPWXMD*j)F+SqA55?ZI zGogY6p7IdUbGJNR?wdCiHj)W+Vcwd-FyPEJzO;oqwck?3gbEUvog`L8SMT%34eQYI z$m$Y-F3ejKeS6>wp8VII%!|31P(cFoq{L2~$kytfU`=PoH;@Q)Vcwd-5WVRqH>7;$ zCr0?1P(cFoy+jskyCM`n;vp{|&Ljd|nCT|+WUPvkPxWIwtU^l@Do9`+kca_vwj}S9 z2lv`(VCQ{xK z62acR+53$<)mBCHeS?!L#W@+L&AeqNZ;3z`#`?t<^~Z%$@66#%x_U{w07y7Kk74SF zFX{x}QsNnj`|HyE_$|DJtGh&?3wH!W%+lmRhc{;M<857}%mE}q+r_Y*R`%Mdwk5?g zx;$_tWzk7~?@&#NKo@2a7z|Syh%*x#j_~*;)l8@$VTg)m6B9kP>fZX_YDb7W6=W6g z3RNmf1iCN>L7b0DaH10j8t__OnJM2dmfh;tPYs=B!^e2_W`jdPm7lbbm2Xk;*?P9O+2ck z6|a*&%!CROKJJ#xwsrNKX|?ooclYLJ@pI0uyn!)VBG4t@&)IhJHQqAr1H1ZlfC&{O zj!Y2=yy=Z|o^;f+EW!gH^PRWKa=&4HB?4Wo7CEt-pE7gWGM#Yl@smF-yvRJx_B5e_ zgze%+Ow9|(**sRy1k74*pw#hZJn&1nM4)TX)<&#d_P(5b19f6_t>QGGS1z-h)YXIv z67#$Rm{zrOPS?x&J8wC-1fA|<#Y=taED`9ETS)_NdkU>5Zl2yDvOl5yAmRTZlC?M) z_kU!acU+DC|Nl!8%5LwSgr+pE*XtQ2(jb+Uj3}fjN*N7OiG(sEyNG1Jb*^(x_70J~ zSN6(y+rQU!^!|LG*N=bR-QJJK{XDPvx?c17s_{@0-a+rfh7jYYN*y-#7ZKQnpJ~>! z{gP#Tci&934YYK=kb={k=xHB~T=-36d#rDAfX(oM ztgUkuy@Mj6GL8H$j+Jy@+KI*JQ|kgl^_}T~N_!D;8@WdLq>;StO1yVuM@B4oMu4x- zrHx~3(8{o=Ol4)!`iAt2!*t#VhB zV+9j%=OaWKn~@plQ-7kT!z{<;&sxJ%q0JM_Oz>JC3X1BMbuc$861vw1*~8~ zE60kQ-!R>?MEVaSVz?c2$--V>x6W8ZV3*@-PZAk%*khXPAS1r#?V}HOyMafME?@-{ zm!~?C&jZ6eLeKGxxO(ga)k$)Pnrodz1a>7|cN8y!EJHQGi zrhIiGm80z>@zUdr&`3N>^G@^ulS?f{1a|39r{q@8eUe{Z!U)!**T?C)iTxq5{s+Yh zCM?`~k;f&6Bzn8+7%?#73Vm)d5cr%%5rJI~Z+j8z3vKvY3xruO-CEqDvswm0a!ozO z3MS?Z>q}zJusw3S3AtW25ByBWM+ZXjGj^5HZ(-M@S%GA;sXw0=B8-x4k++29ae=Vf zZUw~(Ch(3AEQe5bCrG$C01lST77^GrNohFQ|2>rtS|^NV802e%$%_8)C}R}G3MTN5 z80>p)WCWJ>KJX;IuZX}dkJ}@N-|M-2NTHBbrQw7TOpfgbegiEiRxpA0>0ov0wiYn_ zY+pF5@rz&ryEZ-!Co@VG@XCq8TxXs87T_1;4Lbu55v*VW?>EBc@0!~}ay7u%V_j{)nBn&ST5!hwt8AF^5i}{V~gn7t;*CI@!U)iSJL0`HH+Ml+`L z0XwI*uth~CBCsoDb1Ydip@^@`6Xt9W`N`5bRknf^A?IaS!35stiQRMEzTm$9C++*= zx`@E8cOT+Ol1l;KlC8R7@1P%r+QGl+bN|OOtYAW11E@0bg08dQQRlXALY@OPfo;T8tM+Kk1t-Og4b0=wcfbBO=4x%}~Gomq^pe*Q4Z zD~*m_+Fp(oOyKXllG4y!0q}+lrLiU*MFe(T?3hbTg9q{F25YexCYt@=!Q)WsnXWI# z3MRyLhW*vP@V&DW4e4eeBCuTZhHCTj2vMOEu}F^(JzxU_xA{Uch$8 z8^4GrzHhWd1a`$IEF}@W3M8&3CM<^OhhT_|9!=zzJIS$viEYtK$-sa2)+`AT2;;jW zVM+ZVE@N9u5rJK^+N@z^2hpzOq?85VDpRaAa%EM8FBhq0XKa^I1Eizf$foO3@ULGN$dND<0cf?Y+YYQqT*CY z_2UfB!9UlLae1oj=;)0C?qA0+h}zl?u!4!Ar~;c^(WPW>Lpw&uRZ6(Y=1~x4@tFP^ zS775(zL{*g^^n8yZhy-1O!MAMx}1B$j;d~HM^djk7QUN)p;*BLj?L!j7cU{l`;LWm z9v?*ncC{Maf}7>AiCD~d#$wD~wThD!#>0)QL$r2GflcY&3bOM8&*3ASeQK`f$&nRg z;(Qq+mQU6p8-ruu$I$Z>E11AX%SJ7eR}g0s2kkcSA_BW)rY*UpDdnWlx0c1YFtmn* z6;A@S3l}L?Fd;qFc*fk=>mwVf3D{-WW zVDs;UN^<{sF;~W}!oD{ZWXR?kj?ByPH11nTs=k*n;*zBv`EYm|z|~@k6-?kOqNKFe zY9+B7$JQ?KIU)kP#+^~+tkbuXZEaSt7~gkE$vW3$NL{g#Vg(cUim+@}|ESRWnbTlq zWuAz@u9de3aHQ8ZGMKDnG3a|O>i#7WTAx@$v4RQlwQAqagZ?_51oy2MiU{l)csGZu zNG>N+m#<)!&Cd$)cK=%<8EANAIIm2b!$O`w-9FDD|l*jd^Su0XO=eCHuYWPc0pKUT_p$D@@=LgRSSJ60-D6 z8f0$w7ZKQnp9Li)%giz4fZ0s&sm#&KWW9Tm2aOyZdA_<@H$>b zu!0F(y0X64TcPCW)j43`v`Iu@*YZoPIoJH1WMruti;-!>}#p7^U3Sz*0_obsID$@<&3?xp^*32>~V7r_c9?o^!P>PDfnE4$*|&B_9_??M0;^@Y1S^=3kI(0{(<{l0(_t*e1@Ec! zOk*m%Fx)62unS*9RwiEXqqS^S*v;+zL{}FR1$VNzU1~cNSAosBTjfDDTxP;&yG#** zUHIu?vv*q9(8>w3;H{~y=qbU(;UhuZqRu;;V|4x6iQade4bPOdLhY0qL-jkw3MLx1XLDJ(Wu)lKYet;i;7jk{jfC=v*F*$%eHt>4^XajfOg1{ki0=cZ zP(F78e3*TLVg(acZd6^#DJzE zTBaQXh33T+E0~afJIU40*+?E9EM>%=qbu2nNgR0hnIa;vYwXX{+|PTPiRaEpMx2^h zK{GE*ftwa#6f2ncTK$6CdVK>~9~i|5>DVfI!!8cqSy+k)?7Cao)I~1 zq*S~06o}p2g<=I0z2jSv0@L+ma(YKbyte&K_Kg_;oec~DKN(%06K>+0Vq%_cK=9pU z^^*SP^vX1Upg*(#E0_qqoXI`OTt#N6s6y}u{zyD}8M>~AF^unXT!maRv9EdAv& z43@AA6e)KNfl~Jx#HK ziLPglbN@bDM=r#jVlnogSV`w>j{?urTSWwR;k(J!#7*8txjs=aF?=P(3MRa!JmYc( zml5NPbu30j*WL7r=Oi$+pDrS>3*Sv8rSXGmsaa7pL|qy~v4V;0$*Lr0>^gGSeiDl@ zz55BO_F*E}dD@Ez>=HjE$x&CRZC(`I++s|zf{6?-Z8B1BjCAW~Nj}H0cFlzXa_O!U>1fsD*;kTFQr+FzQ=+^4JeREA6I9lF0#-0_ zWlDif@2`1e@q9N%Jm7|teKEaYq>+m#2Byc|`Qo{L+hQWEvt`8X19jwjQBNqG?haVN zM97h8oa*f?a;rNqB1Wwxji2WLgOgoF1a{RprEyIo7m(SS_KZkf*OyYu*G12&zj)SO-x|d(^&;JPd90j-;WCz(J9}NE=)3kcY)rpYVASp z)S7AJZrgsOFd>o4HJC~+4-6vq)w@~!Y7iOyU_2uZ-0Vz43k~6rV}HO3CN@XLa(32Z ziCfhuM(n+yNB^0n2Qk!7L}1tJr#m?Qhb^fdoXH3c*7%wct_%0w`~fSNh*%TF?Y!+t zQrgd8gq^txjk%};uQJ61cBwzv#@+6rO5*w!GGfH(>%?S(4%^E;0I-4y+acq)S?6>} z1kGne!sH`FqN4|%yuXORt}#Q$a?YO5xrHN_Gh&x>7IARUh1tCW0V|l$4ZGvnxk!~9 z{a7TNN4-7CGSr8?#sMM%yOzY<_mmwv$r%=}Wkhh)MsAO;9@rWM0#-25KeNDQ!=}%i z?~h_e80)p>W*^dnwtE6Z1a?Jc71+E^OkqKnB^#y#N@q3Q%4eN*N zzk}TSYz%X<`U6%lA%4#Xnj9r>v-M%c)`21dyYRhHQhL6pn8Y;cLbs#Z1+zXT=0|;d`T` zbZ<=qXD8EwrMZIuE0_?!weD6NH+7pfcr*ox2<*allg<55?M^iZ^@G<#jR4nPzAm24 z<%KOJ8ns3Q*Era>)_4&0G#LPXEp-4ZnDG0!p8Hk3oD8|CAv{-(F;uf@FsNQu6A{>j zYaDDgReUZjaR`AMHNPoVFafbgx!?z@NEF}1zO_rDis{1Yk#PUxZ4rT8xW>Wum9f}L z`{sm$ddxYB6--Qe^@Mv;xP}}$c80|$tEr~4^;1(Gh!8%h-7UztF!nrCU0=sZ;B-=yb{#RmlF#-Cn zU&Ygf1LI+pYLTd~4->dW#@3iTnnP{klVJ0OaUue{#JwMHw=bsIv58Q7cOb9t+lA!g7Uud!7JBO|36TbkI)gLroiK6mqk4+n83AjmRBwKI-PMZ8k9R95)s(t6=F@y@>dZTrFhoE zVrcz@T8EwtD>cJ{h?R#iPj-zZFo+aEroP3flVp0J+SiU{n&-zzq! z$cv+&j<|!8+!nBci7zSZI1Qi0q~MzgyH*pv45g1-^aUpiV-bN}_+7ye!;DNQQ4MkV(~z_6|BDOND?Q`&{xTD5{)P2I?1T=u_5 zV@gMXa`ikBfnDM^Dlg_WJsB|)H2kMitYE@smL=I`yPOQz8_!}yIyOQ!t_q&ji1Ix&k0v#5^^g#=_pD+TJgtQV7*!3l{7a4C| zLfWS%v+`;|W*hKrH5BGfe?qW=i4{M+iE304sSitIMC4En7#7M#Uk@)45!lt#;7yh{ z32hJI-(> zUEQ1!?I3pY5ZF4P1H}p^@O5MTaBJIw)m=8Sf1ip7?2<+~lh0F^kfz|NEXE?smayR8 zP}n_xFvSWc@cm~yxb#wn@Wmkzv?@bHU{}KjbMjnw8JS$MnZ>wz=_A!_KNLbr@+np@ zfuCbxtmrkpJ3Ryv@;8eJ>~ikenYgDfBbk>juo%~F-k~c#hr-OcyD3&Mf!{~g>-?mi zn#~^!b>^2u1a?*QQYQC9mXc*xzOopLs}9qoB1Wh_pjg2KE?3x-Shkl&|Mr7iJ!QZI zc0KEPpS!$yF`2NqBYWoThHjw$tQY`t%{G7)OyKg7<$KjwO1*b`!TTpVA_BYA?n=3R zd;z)QY|dhIcFm+gITW7HGX|_+0+;iw&DoGZYwLP}{bySdfn8gV)^Pj0=aTZiE-c1n zr$Kc7ZfB^h?+IAJ1pZ#Jr` z9t1Y?EXRl3li0!#0Kf_+#678I<0YJuOIMISVdsJRDX|OpOtLy$+iu{plY&esn<#CG zCCi@*eN?OsS2Bh;FQ2dYTe&)xglc4xABFQ-3HRu`H8kAtf(i0Uf)z~c*)fK+zLG=! z)tt+S?>%fF@iB!pX=)S`*d;qXnv8xmmwf7J%HF6ct;|6GXJ4orY(lYuiCBM@CpABx zd^9&=#58qdFihBF6f2mRdeD(n*%y-F z?^_w6oYNLw&F%;1Csm3F?7Df$o@nmKC&x!OFyi+_6{z3RAKWG$q*%d3dv`N(iR~%> zF1MZ$y63;sQ$M_+Ec}Xyz^>9z6VmWKkG!)|V$Xo;)R$Ct+Xudkd_=K=iD5I?Or^Vv z$ZnONEJn$_+jK}0KwAf8zyx;9Th^X5o|;eeA~acynK#bRcb_R7RBr=V!NePt-<(E5 z0ZE_QnGsp#SI|U?0_qVgkE*wU|M+rzen6N37YkDtqe$-M=_O$X&LtB~mcaecu!^>ED@T z>I4f$%wB5`rCS`KMeDI50=o{}olNo{PbUu-WijI2DO4eIv7!jLi3ZuXEhPF3WQLJFXP98|0_gqrd zij90IZCz^!+3v0oUtTRDux_85q9Z(VbcH3i8brh)2^VP(5?no( zSY1QY)MbR)s`vC@e-}7+UJbBF{m^(RQLQ8-Az?LpcFU>;LscNl>)hio!3rky=pwTGhd*(*Ue1UYHwHm{ zT1RNSt4lF~T?=O~B$j)8NmH#OyC23g2EvZJT2MXHm0|@GvanndeLj?Uf9S!8*ZX`S z$X*+!&5aci*frI5K3TaUkbL}+#|TM4AE>{o59bzTQLJF1p*E8oEea=zljbvmZTAYD z6ZN4T+Zh@Y*p)1sL;5TkLbSFXWJH~(8?-7khGjd~Q>Im?(G#{2Gx%~uMzMm4#w#qtpw4*mLHQvgjACu! z7dMO}&`m&gC9 zap2O9-N6h8INHSxRyXV+SiuCYOR%rAs{?Edb%i&NH7F*q3zv3m#}J2ZFnEUt{G(${ zv4RO)`(SMY4I5bE?g0z^M~DdQ!lfNsk*j3}Y*TCqxD-pVf(cyvV0|(VjiB@}2k*@m zi3se%r5#(N$m@XYE5Pcw?&eQHhLQxU^%dYu;->Ly8wX zICY3(1rxaT!FoBTs=+8iAZREncTri3UAVMk{cugcsCof~e{VdZSiuCYOR&0V&^y|x z)*ZTDRsu|57cL*!Jzsd2PLsQX!P3@%6-?l|1e=jkcbQ(C;RG5_v_u4UiOb!v-G`|| zxg$KgVhC8lgt%T(bDO9As%@d9&RRrZS6;C$Y3x3hJgcPa-T4?>N!9Olg`hs&0V|kD z5B|a(c|VQ(iWlZ(JleREYOFVdv-wUU0=tZRYLf+D0?6c#uCE3%VzKR7`umvy%yRb>5!khVZzmFR%!;f$J(Up=Q#4_*n=>4VZIF#< z>`%BE_Pob?C5qSZ#;5y|_Em0t>IY#Z(ngs!WNNyC!{TEytY8AKA7*XN51rxIZ2~j) z?iLZ)6?@Nz*!TjUdtJzmAH{0=Ux#}^^{X-&Rxr`;vL6}rA&Bq4L?G5p?+7ys`@;{H z0ug~-`;5Fv8((i8ivMNAgHxSY9wa{qQA(0w1rsA5^(Q53g86D=fq3~u17eg1LqMgE zh`_GJqz_rW&4+JcEv!CE-rEl9=LSPZWn&puFmd;GKVrWkn9s`m$OyHF)-dDRP_R|G zFU16QmG%enWQsTcsZdx&x1+i>MC}>|EB7yvVg(bfr@e{I-5@^d&^t!#Q&xd4*TUhm z=Vcxf*!9ha5T!ie^Dez+M89t>Am?p39R1pd!wM#L@9sm|#{2PG&I#)WKl*>8r*Dsj z+sC2^Ca`NS^(5VYy75QfJ!eGV)vr{$*Jv=x<_T6X5nKi&DX0y~;u@>RkNhTNJ$+etni{+g zhq|I$CcOs$J{c0YzJI#oC-`RA}@jz&o-4?Kd312@$^10jQLq`&X71B1p zC()=jesC+gi-^Fk-P#?9%P=j^59)^*@oPy6&DZmRhGJd73MK}R(kB=G@%FSZk}~3S zzi2w;Ab@*`iHN|i>>=$)Q+AE#YL!Eb=zcw$F6+-h`z@w`6-?ljh>I^DPa)Y=a zYY~B6$1OBSFDrd+fYNRj;~hVXS}b>l8P;}y6-?k2@@y3Ofj`yy+#PcM=_MkttIY2K zH`Z}AXEH*VAs@Ign08#>6;6(D2drQMuiXkalpR$)Tbrn{+dKChASvllsMqK$dm3|(;=Bi!s77^H$d+8;2jb#y- z={AKCAFlR;ig{*m*lQtasg_5!z6odlm(4tVpFYNckT|i<}DKu*tI-+B1zjHMmVOr?F7ZG9O25OM-(fVz`Y`D-|$Us!6Cl~v?%%|BCt!##+{g6jwP=` z^;wLZ3S4t1nx&+^{cjD>EjJuVHvCaVFJ5MX1J2q19e%lkc{{}h&fp6Ow=2tGT$FE;`HFr zE;+#pCU6EK+VljAYNQB6%ipSuU;-RgZxAr z=v2r`AJnsj%P!o{#AXge=|kt2ws0onA;k(NaH+)lsXesea~mu8-0)3AV3)Z6O66-i zIJ?Rk!Vb3ttY89{F)Z`fRCU;W!~|rMJBSGEnkXGabQbg>BX_v4XBoD&fb)%}5Jt5D zE11Bg5*xLA*8&>Y+;hzmBN2gJ-3tOpm$5xbb%7s?kvi-n4P2`aQ85;P6-?kVhV@@{ z{Y?FaXo2-=8xetBJ;(ZyFH7~wvd{M0_yOKp)i=`s2VH*Uu16DABOC^>mgpKOEt=EQ*rtG_peha&5 zzER?HWChncO{l{)9IBIY@x!D-HZtN){uPMHD@&?a47auSY2!m%7;bDJBCyLeaWDxsDXa;*v!4;$ zT<_DA%{}4xV=cf6CU9OX)@!i;IbD0r0csX?5E0n5YMn2+{m;#sZB-H$vvDb3)>`QI`Ou{&d|*3z7T(pMSi!{f`thXQ*;V{u zYoY(j=}a$h-{k}eEJGzGuxs+7N#w(+&HS8SZyE7(v^#{EJHQPGAA%K3^!XA+_LP?K ze!V_0Vm`~bSiR8>t`v;sFo9itYh%d19^3gQ3!!)L;9d&j_I868A-j02V4~iK?ZVe$ zGw;$<$YJ{aQ(rhf&0-yWPh+J)rUj(tYlchL>7r7 zPy1Bxv5~?quEiGq&|+5?xEbXuBCxARuc>5Q_-@|(tB{+@SkoUu5<9}15iv5XVB*o$ z1oB0-g72|i$a*^Pc_0|JX#*cx%@YyW)#lzb61udSf9)saFx@yM5MZ1tSbQy(VFeRr zDO1Ty$E|$a4S`5}IT$8Xe5X$~t`QN~6(&g|@5~SJMsI}NRNem_0&5?&#hXmDK_MNDm>K?vlFUFw6TQ+c9mIh`=ssV>Y>Gd4k`yOvu#kS%k!^%LkZ1hIL79Fo{bhDW zh80XK+m}c7>0aPl4-~RG@py*WF(z8XA;=m=}aFC zJuSluCXT#aLN<(lz&9S$XGGsyu`tJW0deXs7ZKR?%xfiC>iC0q^e|_{;n;X+|M(u) z=J_ERRxlBBXBF9U;uW7a&XN&Zt|q}MpZk3G;pHL%yX1B2$nOy?q@kAG8DSKd3?`jN zN(&oHWmv(4Tg-a0px1kTiDOSjD0NN&zgk}UPB%wHU{~Ldo5*H86=|5QDx7*=f~ulOdu>l8mm@ap|NP4>?LF6lg>D++9$TQ8K5^amuL{oQ-= zV#&sf4+-8qgzY}$|Iss`CIcRh@enDPa7@Ve+|+J~q_?{8jWXDq%e{Y>0aedObNIKg z%X3^C&f?HANlBnU{AzogYuJ&&RuA-&Vg(Zi=C$D_TwE#%jT82dQmZr~+}kKIb4=T{I1rIu^;Wf{C5e^SK%RMG_xhVdN(?`Von9Pk^J& zJ4FO`C8n(AMy*;RxezCOol8A_ljHX%!OyE_WLUw3WWj1~-}eQQZA0EL!o<8Y^}P`Z zDYXwo1a=vxR&p&&7fNO?5WeR}2bu!oBNx?o?W&Br8Q2Q5>K* zhi>+>gKJ^VA_BWYYVUBteI`goJrwFCCJEWpXrC#(58&ij!Gx{ddCvHzpJa%UK&Ty9 zNL@e&j2-)m2<$rL`i2{+6)0(?ER3Z#*c8*Y{%v8q|3EobFyZU;hI<+4DA8Li5cbX+ z>7J86=>*k5A_BYmXa3@rwsn@MnhSNGqxM^<+L6a}@7gdqRxsgW`-V$7*jciw{Z}Ez z$0|Dc{3RMVZ@7rSuF3#4vayA>wn;N0oJx-1lOyJz{N=hv^Jfp=X<7vpDLrM4I1v zpd2fhzx3qztyFzJGiH963m=I^KZ(C>wFf)d(lDUWo?7}-@uq@_#oS<=6 z1brsyDaQ&XaQ;j-QtjdbpQ`d`%Z#of0=q;zVkiwMcZ2k)i|F{3=5nlH0_P4_QhFBT z3fuaZ)1uBMB0}U6?X>Z5L2n4@v7d$>(UardH86qqDQ91`ItSQpd5wne)D{ugCElCk z9p3{ksDGrk>K)`*!35r+osFxR*?`LeRk*rFLquTLx^qLxF+T@BJ3wfEwC!L8r&HR& zE@w44Rxr^%Ba94qLV1_>LdM>C4@{u2cW0;_)mlVgmrLuxt`}JFTS5h*s)H7s+HC`O z^FPb5f(bmIiOs+2(*d?8bq6)4FCqfFR%`YpBL*1p`cH*2QTL5HY0OEX7HvL#o={JmV6=~JX^4jp`%9&mz^)0JX5`}m4gSPUp}sq3{{edTeLTF{ zVJO84CjM=*CZ@?+{2CC5V$B`&ADtxFNqcgbz^?F86VjV&%R3dnU_?_`6?Bfi) zwtIFQC1)|Nw+|eYlfULDMzaI)4t;8iXsBCt#MQ=_NBlw2+{XFDVI?P^7o%eunz1TVk}CML&3 zbJ0rkIc;BoxIgs;Cu?s3i+cAH5!i+ENwIqSKV3=FPcx|c&`*>%3KRMve?Kz)vJq(7`H2YZ!g;aSx7KPMNl-C?fm{2F@?T-%2HnQZ&pyiOnwPQ|7fS0% zKPN+oHuMt_*oE_ZvFsOXI?y6pBk;ZBE6U@A2|Oc>&E;}4rfppHp)zfNh`=tKr;L4Z z#<|gP_w}GfSbtFlGfdzaX{-jI*PBMJ(FKih14ION;e2bXCetdEHW=wacPC#_UNubM zF;CXZIVp@zyTe*7*4`olyTt2+`{<`q|L4ZAlC3(#3MTNVEE~boprRq>d>t3lZs6ZLEK_5Fb`a?(T5%6sg>tNvMD zoEweQbjm!YVY&|_KAZWc04Cpjdl*I!Rc=bA) zW$`=}hP4_e8$12Iv~7WS6{K~Esq|x`86%b+ zNP!kJlB7BPb7WY-MA3&5(zw@3`u&A5BW}h_hisSYp8i{xhzRUjl(>YrKk6dAa7)<7 zp`8 zbP@V}64heBx4wpc-s>X63MS4cW|LllA9&v&p@-$&?g{Yd!A*Mpayt=$UE8%*hhzs87*V)DL||9`i8Ml0 zF7YuNzca$qb~r?zXbs25nM<*P2`EY>F}Kh1b?QPt!+eiW*wU^8xMuI>F@aryMaiV& z=vw}WqtI)RA2A5leb9nZn7@h+k7Kw9lgl_`zfkBT%hgKrn$_BWA~u z6D2$OuvbF+d_$cNNQz9M>A-J-6-=z198bb;l=CaHg?6o5FM!fSmQ(GMJ;ele#YMyr zlh8H%oUcMFwNHa581Axw%!nxzE0|bj7faM%E#c*(uQB4oJXhGi)(VECFAx#fwY}#g zGNWN0e@?A|5fU{QsK0H_vdXi)s*!>T*M~7=&9+27E=Xt(T3+Z0U$v~^#+OPFfn6D` zCXiRl68Mk%>lsnhljTV9wFb8@JjDto4C^CF(Hsx{o!Tizn7Nz6P<1<)_3ONdz^*E- zk>v2Xmi(k*8KFm`H;F%6IkkPB_gm3&+%kWd*nx|GEg7X z_FIVNa$@4{-4G&G^Wx-JRPU3lgxn>D%d2X%ei8JvdMh~}hX zf;<{ddfwT=jVjAwG0wjDmwx}$5lY5)6A{>j=iIV&6TMqO>zD1|!3-KEp zO#8tdzB8W1Xk)DkcDp)2$OTIgfn9j+Fl*7zYX?3N?V#T=6VV)DOk8{%N#^KuCOLhD zdHd%<1ExOj1jCLQiU{n&bD&u(^`Iu0{L=wy?~7+gW8z3gG)alEBE5IIvltVICR93W zgV&3WqS?{dh39g!ydOn|;H;tv>-x48&Dq9;XWJN}R@9rMyftSrOs^P2noJMA8!L+l z?7}$}l$12Htzmc{_LM|_6y;99#Nf$s#Na4f`D>xhVmuwy4c=-Rz+#_!A_BW`ZU~n5 zMy@y z>xxe70XST#0_7@KDONBM$}J#CChA1Fq6>?W7tjy#w0_h431>wFcHQ=0ND5Es5%+B$ zS&VSo0G2`EDGh#oo?-%oS!a>(PR+}M_J~f$)Apj2<&QYSxoj%Y~n`$ z`-8>k5;_c4zdlM`s*X~uVB+Q173BNbrJRGE5sT4je>il{K16?-)rbh}YLUH~G{SD~ z{+$+#*h0p^(SY@|y3;|56-=zFC?z4`#@w_Z;ko*v9tB-a6jQUxogxCe+$WTg{pI1D zRjQDa8pT26!BKSEaJHK=`Yr5IKF{{& zaVqyr_SIm-X!|7a-fTn1o++VN!Nhca19|)7f#hsd4@SH=nhZ7t>U8_(0ug~-3G&Uv zYJITe44Lrvr>V94WE~A&a3y=4eU1pQBvZ9OK%% zS@P)(Mt>35B|fTAA7kW={$~}$j#0b$^XCE-M^)9UmVX-EPH|rNXjyrck|@vJw(GC+ zz=Yl8T0X0jhJt3b@WaV+uf)>72<*b=#IoZDgv;wXx0DOlYDY{ZuWvC{@mq5YcJm%t z0gAuz(X!|2@fbPZ_us$H0~0@|9pFnfJerS6b9J=5)3CdL5!i*#iOoov=qyiP=c+iW zlFf7ZGY?A@*UIeWLO!juSn<2U{}VLf&ayS`HAMdSuAPFw3MTaLm+~Dp&TT%bDPe)~ zlMi+OBCtz*=36HP%HN&(Ltq6H4>i~FPbdEuqiINp+-6S4KUWvsbL_%bosE(uD9MYH zBNRjzSpeTJXt&~c-R=kRyN*;V{uZ7bA^x8;H*{zt=PZUR2&`a2H5;<7+Yp_m1|19{vxmo-y7EB_4uu< zr){Kyz-Nxn$vMi3-#JRs93$VZK~{Zul7herCWLoic&q+gD|PuHS+B+Me-YTV`<^;~ zt7~m@i~}djWkc>HDG01!;&9zZ$&#d_&BT)N1+wL#DGCBBm=MY>p`7`1RO{MD%1m~p z{Y79`=aSWum&T`?WAyG)CB51?LqTxy+suV>QTVOft}P{f%>R^;m}ada(pg5v&Q=gu z!9;ZTLWzFCe=*9wxXQvG%>0YMF7Z*l@VBLA>9Z8X7L7trjpRSSm06bTsW<9& zR+xC7KD5`1dH==8iM!4FKKq-%E_~hCe7NFZy1O|2uQSI-I9c_kXI{+l<~vw^EQd-A zQWXSNM1+n8_kYiB@_>!><+-VU5$w78pKJPKbxo2($Pf(iC^asOBP#C>~4+kYPa7lB>=HNM;ct-Z}Lf-1Yf6Qf`S!O9Zu zzp~x%WjyCHa;w6HX_imlOAQu{9HAhvf{B0E25<*@|0yfkj#D#!()hU1e-YRvKB~UP z-mv?Sm4fIXFXi6n{VBu8WUl5OCd^kH6+2Sy|Gqe6nI{{u?5QBIf(aFs1>B**E1J*z zcW)>7exmnZ1a{#o!upno4S3Y|Q4mu+>K=uo6kepaR}@*@2nuOf(iD7aO_?+mv9MTBVpin)xQYrI$*q; zJJnp{VDpgO$3UBkZ;CntRxpwDb{}`_DKsC|cGGBR7jR!eU7EMezBvklm0}!wTNU-sj>X5hyXDsubwfl{Zz4fYH5xdm&_aU)|2 zYJ|Vp7lIq~Y@GR@GgqCS0TDqt|JAAgr(mMn~`7lB>)im=h} z*jZ4J*X^%sg^9A+r@2C{|LWAr8`EJ}$>6^T?84WL&8>aK)=UgP!3k%G&m5oa#lGh_ zvyZPm1P_}DXqExf7FMu!1>4^oDVS(J56?f>3esjnNtUpRNlaju&cf4Nc@H52t?+Mo z<4kai7si>`h%!RekT;ab!E1MJ6&g~xQ3W!<2Y;LAu;2Sg1`zUs!eOT{x{VX zG|RWtW-92M+4>iOUE-s1JL(IjL(M?ARwWxsxy!LaJ{Q){Xts%S-;%2MySZFxKJ$g) zgTTm)typLOu!4!Cq-t*M$3e|UH9aj1?)kU-i@+{?MOe>7a0Gma+}pLyMAA@QD3b;% z2&`bD`K#T0RDA1>puQ>OF9N&tEyi-JWz-x)ZTT)*otCH|)^*n445rj7lxVkhTtE8f z@8&v6bByP1M`-z-SOtLcz|c^m^x+e-YTVpjDygq{!3F=MfWRPV|d#Qmqip87^- zn~8%(b>!^sISK+Rm>Bfz!3Lom{!_x0zv)L3_h$S>U{~YK8}2KQpKFfM=u#tH{O(T- z_Pat0OYvI;US^X0b$^Zo(=6v%S}SSg?LRTFf(fO5V|)GH@L!C|7yCVb{ra20F7Z)a z|G7i<;{Bgzck6d`z9P8!c~w&5XNDhE96P%=LMyfT%(uj?km)a+rZ{t~Oh!a-#4gE} zcBh)pJnuxBY?jZAzX)tBOjHn9!B>I3X+rNu^R*hV>yzyL zsz2`_Ca`PZi~zo@(|_-vO@@j*cgvr55G$A%Hzk6%3fR$nRAp^C%9A$!DX*}C30B$( zy;RLdbxF-YZuXDA;yf^cT`kSBc)c&e?!&^rzDIh=@APh37u?xFEP z@jb_9j*rmFwuZmY3pwtDe{1L@`P2#56a-ciq!b86~M#rynrTjU2w9j%I_eKvRGZo09Z&dwJ}>omr3u~{Rf z7itzr|D8ULJt>dU$H_M(eUK%+;oWTFmP>c9bC7QC|9~^zvRvBvoW0`j%$SwZoeyoL zRR^~-VyE70`Nju}B&*BxsLuKA(#V$-Hm(rNr2@N;=Ivv*yXC4&2s=D(SU1UNx_eJ@NdfdzIAPwMudz^9j4c zJ3d*+byxeyceI=?8Rk4%8gw>KaW|vShf7EB`O^LSH&v-ehD$%HFOa@Ca)%K*r)}gg zqK`afTNe?5T|ahBk*+_Jt@tIj(mT^mzP$sL+qzAv!3riaRi;P>YR{F<9(|X^xNdGQ z?{v^ZzI#QqCnm7#&GvX{ht#a*7%Nnq@!G&u zUh>>ozS!xjh`_ElHR;k_CsLYYJgjw>H(5H!-PdbySi!^^yE)R3LCMWT8xJDan9yCG zrxwg%1rrV*=1QyUCraDo-D5|!BHT;9=}A}l9Y;42fn9Ei^Q7FtAR;Pbg+wwFI_s>=^E}V1g%|3%bV9FfK^#F{-F0%HU1{LI7^OW1;ScThsM}Oy&sc z`fidBX%jvE#n}Bk0G}<>#osfhD5*k;Y2Hg(e=cy58+y1_=pv|6=rcHVWVN{3A7AF-=JoO1M8Rf?PYx ze}ubP2!3z-MM~~jrlblbo+($rtpP?5woz`?u-Z^8%6cPx`aO*!s4L>=3dn!oy%WX#4A_>-oeelz2`&LsuOd= zG2+SvNi3Ys5!5xiPYI~5HTf4~L(vqBF+VOXt(c~y3MG#Dl!1Cy{eOi2m}zJ@1EtCJ zHz}z?37ySr0q=Yf@6^bxstt?4j6S=iU14)Lg1XjPtb;3YAOAh&{2e1Peqg0EASYT$ z6-xNFD~IZ__x=&ZI1~5uD3gY{R4b`M2@lN;(75Y)F?PTs)~c)-QTY0Cp_FTz&Joo0 zJZS?sMEw6}ukXj%c;@f|N!2@3NfkX1o8j%G@OyoA*hR+GU?rQiT#V;zpRd zbAwoSU2c`{vKS0~K1+&vzKkQNtEKBE2(0@5bC5$$#NvaAW2BGO%av52M8=j%*fuNs zU#q$tjl)-KyruaC@03)bMDOdB&}?*qSUTx3YgLDHbFqu9qtvwjc8;K~O(QmgxIOA$ zjMVM%IBu4arbM;le*+!>9xd)@&+O`!rWkg%UmesvsiCT#WrJx2j9K zMEp?m0VdSHtfT~W4Y^qbJ8caA#Sk_oV)*?N5F^}DQiT#i@fP?p@obHpAF;jkekS6i z7A25A&`L!WO7I!Lo9QfvtD6C3hQF1Rpsr+b3p8f98VA|C41Tr6-~5l@zg}BvM8HUrJOQ-U9nCRPEa^HH}@Xd8?CfiCGhv)yj$^ zsEcn^_1PqJ`Isx-@oTE03MF>k-vTGKChwC58M7E+x07((j$PvVjmMRgpsr`yTcPI1 z>c1oD3Wev(B(ys`zs9G_c_mdSajwZ$816D?@3+ghx3X0z-4n6p=#FBmRv%Tz^)`b+ zxmQhTUA{8((`Inl*0kok%M_*M-OcdB`9{q(RvX85@(fADyeU@V@h(qPRH4MahE;I& zq;}2c>(}~eV-$!>z=v_TCDiAzsbzujIjO{kFm|8Yoc=Wxy+Jglgo-X z!7H8On!0WK7!lzfj}7{2?R9Xm7WAH1fJ^q38j)qM)a8Dv0(2hr6sy_4voYj%@i^DB zQoKJFLJ1?! zO)$zSSkzCKGvwMw@mR4m4d!ib&Jom=b+iJ)7peZm_;W5Ejr&x=-E$2Es!(ED#|o&| zIa%EKw^i#_#N&i-S0Oaymx?NssMV=}d!tkT5nG4FV`2MxQjY0;6;&wF`#}Y)*Ip*h z4U_w^vqL<7nxG}UEO^Bc)K&a_1Ei;A{EP8bI~M0(7$vQLxIqC-XA zexKBPY<;fhv`;^`u7>*kn*6;YY%iqMQ}NHSgOah)ZzWYI@#gVL$hy!L;;+lss>7ct zi0_X`rs>x?g1RpMw+e0zX#o{~uT^~KFwA#)EfsuCb*1m*HpRtIyu}38GZ+7UetYP6 zT$uVuGXJH|DU^7AX*qbQh3xs^KM612zbaMN%vMr` z66bVQK&)W!FGj7_Wc=cNPU>2_jw7gx@A=2!A(*@3vs8J^poWf2(BAHySpXZGJ3-ms zepot;#`?~`CDVGtT&Y5d*^`&Rf^n{JvQWMsB}+$Q+>&~@?v%(RVd+8w*c&Y2g2wWxmCwk z`QfpT%`mulhe!$P3L2LSZtg>1_1_q+w|Jw6W=9+pS0n~*p9jYNQ{jx$CZ%?6CYZk- z%}!Q&prkb0jU>hw$4=A33+dNIs!(Eik6h5d`u}4X77xX`sV(s0LgWbQ;#>9lV;__X zy5h4bX7F%I5_}Dr2}P_Wv;31`%C#9#%s$iBvP{OkFV1x8iaG|}fGU)@8k-D7asNlN zs$Vwtx}(GpO|9B<1a;9qDHNaUIbceh9Ztg0Fie;Ly~{FS32VvbRS{tMX&x+PpF91T z29(JuHwZxPV; zn(9pepX&d+ZnS^w6s18uu;~#e+`4H2*KbrnilbEwXyGNuAL3)&Lxj zqeZGvqDK)M#ci+%^sMDk&Zi#?aD8!qtYteSQ-Zo?WDf*SqeYN1qY3NBTDHdW;??S! zjMgm$IzmgcewvrE-K^du;Nlrq#A%a%tEfT=`Ub#yekcL2tJ2}I;uS|w7tI;j{w2o~ z@OAT@Ff;eKiYk=IYrYu@_6g$0R`T1#(*5x$R@amImDX|ub zav2#VTvl%a(QLk`yKg*;F)BI^TRVD4x80U=1a;9|i{&MGu~@P`NZOT>%4L?6NX)E& zr);>Y^DATQvoiy1iYze>sNp$V6fQDV@XGC1!0M+_^KW9<1k6-VEw zmGG?&M^G2d4A{zk+bNizd_ocqYO1J0iQ4qlaHhH?H1(8YOy4~LhiBfA#`itV#tJK>qpChP?KB-xS+xAhI zfANp>pk9TNDwM!41@NP{BU~(!W89uO9Di(VgniuA96??58O*8yTMMY_Yk^ZM8*xug z`b?z1L<)sjqAMnNSYzFbV38`6XlN7za4iO2JB6}Vol5J4ofGZx;>)+nzg_{kpB|56Zq_|C42OzVC}~zqCTFMq@dJ5~bs^U}fkCc=}pyRog}0 z*jCvQBfGbDrPqYIXrB~{iMIW)YXc)pnI*YWg%ZVYQ{c?(a7ZnXW5lMoVK$oK?Y;#r zl%Otp6K{tZ~pTS1kL|L8J;L_&YeQ*bcp?IpC;4y<90lU33oC& zfUvzxizZN@Ey4x~PNI(FZt!y6Ef)o5%4Tf$OarV&cL>N~%zT{%x`v z_jRMuHteS~^z&(spe{NW!sa0Nhv2juAEjRfSCmwt1pT#BD85#V$F^r4NbwV|a|CtK znGH4@o-+|2J-Q*)zy4B56-v-wZG|H8+Y}7{endK!@`59%i_TN9=lRBIXtx-o(!%;G zs!)PHeb~7f^CB@=d!zKNRFfm9i_SW*Z0XxfeBP`?dR5y&MHNcWr>H`4&1w#6Sma1w zYT9xHbsEf`Bus4=VaTs>f zUGjf6Rz(#`(5!}icQ?mlSL2S-aIcXZL0xowpXIxb3Apfj|KjTP8NWx`LrHIUlONieX?hT~Wa{Z7~k{(a|z?bsFI zGt+_*7wV#M#?cAVjhokD_UHxht1uQu-fSw|c$Nz~x~Y)+uBA{rCJ&D4rNPw2@_7@% z9sDpMr#T8mP2j-k1UOc2Gd!HDR_ClZMD`3L?VEDDynGr1?CSiK!2eGVfyKAOH zE>w#nV8zBdRhn-uY)S}(N3O3_4?g9$=7X`a?@k|K&#*%18udy{FwRwZ z{V9U6$=Aguz0y?sDhuJ>o2D>ndlnwN;JUwHAbF z1I3p+O;p3@uZ0USIpU>MQ%2|Xaot7Ua2`21Rq^yHp{y4874*x}G09DZgBsTTcV{|7Y$44E$kuMUKeHY&J$ zF@q89$9BOZUh72X7*Dm|f4(5kwORP)2pM}v{{7tBIa|;w9tj?66r!VHHY2poS>Uo> z>%p?U(JAmG)64H=Y=)HO2wy5^wkTqGXJ`wF;y7*GW+l6vXT^`@I^Mv zy8g1JLwX7$R$uYM)v;^Do)yj1M{V-{x}Igv6Q(Qj|9;*Xmn^JhpRI2`t{FZ$nGvD7 z!T8N+m1tU{sUA6~;IFGwbfWNm$+Ewn!xQ6$L5r8csvUQ0TDiwFV)yJY+~U7n46Au5 zyt+{Q*A=xjR%o(j#oy2O?nMjFidR5w==GZXb?@FQq7< zM8D+k=e?a~36`x&z~S|UnyC+GGNR9g2y8!aiCFYvhmfeX_ODB)Dnj_)Xx-n>?#k&x z$@jJJcF3ukPa4x1VZ1L259=-z$7wASG^)z~x>DJ$=02=!PQL%g)Zv2Jpbd~%c(^8| zVK^h!9f-lPL$bvk>PR7S%f`R1l|9A_>Moo9em-D1P6%nV3HBa;tl=2J)qFF&yRxUI@zv3c*lnJO$Kn&k&P(2_`qfnZ zCDsQA2|<_t@3YC35yGJDRbX{Je<6D17Fcq*qGsO=e@3)9o`m)zXNac^4OG;n)n+T~+Bk0e_u+&8hgkd~37g$q zBJMU>p``y8CGOVW3VC4;HId%(@2=tfB)t6cw0I<~h$EraP{Xy!}y9dIjO;c;MH|GdC#|Og112?Qc?aUGA-==&PM0M#;H9PtC8EX- zgzRIkVnT`>V^jlutf^GOrd2#aUHly!SYU{KJNZbx52@A1%Ljm;V@K#)nk8)CHvmc+ zwuctmvILwu92^g|0aIJ~x4m?jAuiAEFID=xsi{JV=D!DkNtYH-{6xNk^*$Qoo_Kqy zJXp;U)J5+Ndvbp4j7^qwlXPbERa1o$mUF#e*hWpr^OW!4%PF1Fwxhn3KF6ISsEfbn z>4hd}^C43j^U_gGpOz-W`$NntS9lQjzfaBt2NN_AQ>7*Koz?W2N{MF&`h)E#TL`!# zU#tHrOtESHEU9F^6Gu=Ny@qTj&s9eFAS+BdIa0-4D@ttcH2_X-FohXz^40D6#SpiC z2#|g}5jcXn=$&PwoSVDhiA-L0$BUu-%i|o8k-mBB^wU9oKV8JfGkRColVg<>E{h zqb{l|hWqAAr~G?y1a;92hm8)-?v4Yd9h8PebX89q;sFIcW5K{DUHCoD1G26}L;LaR z!lxiVc=vf0Jb#$VVx-x3$7*MkKCUrUQ-u=S&U?VY5i?-vqjW~xtF^#8TlY%sZ+GPg z>Y`VK-49nYbepn6GU;H!T`Nl1j_C)x*NunMiSpGgf7K1=Wo(f&Cs}d?bC6$-)h@&x=G3G?pYC#uqF)x6-v6bP-LbXWL8mX|PFV<}C#DGBhV}&= zrv+mEch1$IimDNX*=QB4&}OtE!`g}pLhPMsV>aahgY~V&V7@Sk z5&J4F(L&>!G}V?Ts4K;-5BT~mh4+82ZeW@fYUnk>nL3*4fGRgA4l98eKl1mVY;F>)NimHt_H{%^2@z87_Fs= z+m%`zL0zf z3O}O+xX4x+CZC%vTyCU> zvClR^gRjv-^Hbh1?!^W;SARAm&cCt3*R9*&gclDug%Xn!)u7X^0;1VlhC*Sb?18Iy zwM6r^k2r$5XbTmJKhIgK{9EGo)vpAqP~u&(8g@3UfNp!`7&mWQ;jXjI@j`qZM^G2v z^W~SU@XBCA9Dci2$n2|vnO?hL=iM1XwmNeZCn?BECM6huW47BfvSvIFRg1Y#toBY!XC-&}$fdeja*NPHT zf(6k1y#<6R^8Fb4-3p_uJK*hzs~kaH^v<$zxO434s*G^qG2nVmd)uJC3gXK5z|#W} zEJnX8HrV{4A@f_uJF^S76x9MAT;db3Ng14rgfVr6zX|GaHa_Rb;mJ6`PdRYH(KNO zkqbG65-CZp5W7`^$OO4nQ(stPq^Tvo+?vl3)J0p!a%x*EJi6EdH@d78s6q)tJtchJ zTm!GhOkpuB23X-^TXVcBm2w1i@jY)-Yl&z4dSJ7vOs?m&w^IvUU{~iuFk)sHixD!y z8h@|sfnPl43RI!QP~CoDGO!jbW{hFPw@H>5^~V-xt)9&h)TKYp1?+VXgQImQBaAv& z;?Gk0+E++juEqwwrafbdD>1dlw=!1H!Pg_u50Fw^l23>Yw!#pn`aflb&Nmf|Mu zIi>k+C%Ae3B-}|H#{ExhPB_~FSB!T?zx}41!V#aG04JY>DZ#^8jLvx$*g$YbFI9Jr zC?GC+)!CV0pUkm9TZJ`+$c^>U@x93vj<9FaIY_(W&0>V?Gsok71r+y(AE)|e0RYfT@JZY zg%Y%dY)-hDCAuw8;Yja|HI$&P!VL}pii_}Un%!T0 zcji7ehMc(_hBa^mn~P^*R74lStHcX#86SnpJBGp}4@X$G{tWE!&}T9F+F2vEbHTKR z092twi+f)1HTMu$>&ZLUTa2;5&0$I$Y<-?1sLOVqBdnNz8p8Z!;_3L)R3)$`|TP!f_z7pF9tOD8+N;E&?02^AL2lWtB7NhqhYg||Ef_Vqh zIfAf*mw68o!F zfGaLjHI#0n6O5X13|=kO5u`kC_};x1It4WqjoelrQubFH66*v$f$J1FtN^~XRJN+g0Km}i}W!r0a<#+^PEXzs1qo zSTEEC10yV@>CJ}1Ei*RS>~db!(?$jH`g_6P;1$*Nwknu2b}!6?t16aLCs^T#ZH|ch zO*n$Oyo`OoAhjBT9ONDNo%GD{?jsjGu4y7s*YD#lkn#&*S-X!ao*1Au$EQtP(ayj? zq6#G%*t>vP%Y(4^t9-`cv3XXQ65)g%v)gb4bi7J$6tnC6< zDi1=7`F~gp-C1ltYK$vt_1EJF>f*mwLpPb@_IfUOThClN`=K`+Xs`+HMwF?#^z98* zY;|7oosFsv9|PfN%QEm-AfKF-vC16p{c^^(o)!{SDDjxBrPi5L1$%3^Fv6j+HEMiy zz==Qu&-X`CBr7j0-w0=Lzbf-x&6c zI%I+C6I`)!!W*cW(;rIv7lYW@S#`f_fB2-k9Olk;Qz;LPg&&s|z~fUY7UKn4V2+-Y2hcY5N+yXzBxnON@3n}zeKjsqq-340k@x(z--M# zRaR&)_<0mU+ec}P*c4=eL&9C~{ns`URVd+c#U19cO4GG3Wg^Yb0`&u2aA1S>96?=W zi`*fi!CLseF_RHf9$H{KV|awT1$=(Otz6)J0cgv(Z|y4<^s-iq@$y zVDu&dR41e1`i0giy7ru3<$YnP8nf$lN6o+#Zj~Ng7f$~tHj>)H75_Z7LW{_3E(Rs& zDrQzW$uifIb8OJbW(7x37rhD!#qXK+*mJ2pK3ZMG-49C8)!1yl_OLCka&*Ay%~x;) zbsvo_VZkHH{v{r^zkF1O-faTwuAlj=Xi}A-k1TW}( zk)ls~id3NltqWl%xO@!2x$%XFz%EgP=yk->Voa2Yv+p(^Yk#m)0!iwi@#Rk?vt=exF)@8r>CSfIJAOi{Qe@i z{-PUrjh6RT&xoCfb2i+Rh99}-N)<}b8Y8xzA!#~3nzT>KU-(r?YsqM>RL|KfVR0~< zkBV&0V*LIv4HtQcQrOJrN~%zTuM!$@Y8HAzu{3G;C>5>kqLpD^)~tcYqv}K7H2JiG z^69hiy5&kqFbGspg%Y%OjlC7UXZyDgkCgH<)^e44vya2$)Re^-u_qcs zYGzCAI+v)ZLJ7Y5Ed690`c_#{fg_Kq(25z2< zt&YZsgD<;qRlk&=Ykyc4?mUot4oP*-PS>DdS9_^W*63T&6GG?GFeNRb9N|4P#0a#q)=Gq&BaAt zZD4_`i$GUR(bZHNJFbFl^Ph-~ZAP;g7XxCkw$~wL-i-;u)}||=_pIIGj#g7t1us^@ z*A11T;e$|B`m0qCx$S_sV?hujU}!9w9@wkw)^nmj6-v0ctcI@ttrD+44`jrbK5@8f zN9P)crNcOay681zbK9$8(c(phGNCM#ySkJ(p)7@ytrEm z)J0c|vF}y+T--6djjF`PN$}6lhe@ap&bz8qaAOIycF+Y|lQpW;+9eQ?-2qPQDq%6~ z?dIabGi_AA_xBd4LWyQ9?=jq_4IY}S81dUQ9#{J|6}PYN!4cF&?-LvG66RuZ>mkZ- zn(o{kq(tSYWze|MSJ5OYpT+p}A`V}ia8*7yk5#`S{|*&g{Y?y&)EDcs6hb**(gK55cgr90c2BdCjBb@p~= zm4rfVTXDS3TGc?C1(3LEFzjx4RrP)20vOQE4W4+MS3L^OgWIF}!q{=gSqzKXM7-%- zs9c?Plv5~i>iYt?=&gj1#-|zaXmuhwj9;(JR-ac=BaQJB}uwO!>Sj-W1j)!E(&2NLjA^lRm`X7#!I zL5b*53t_@;YX}}Au^2^p33&U=7p3(!ZH}NWy8e>QV5KBsTdyImit2dPn6tT1&Q{b^ zl-^M_`<)A#JNtv)@f+M#XY;kwlF;zZPSK^s-(Vb{Z&e9 z<-xYgIfAhQvVljR_O2S?z7K?^1z!B6%*Qc^wXxT0vOGEXciT&#ux{8&qTn%u|h5bomz;=&( zHsIqwiI_jG0K9Jbz{SE`xG;PoY%HoL=%wUBRnY_(FKP-)zvaNE;%U&Yr-F@sO!r8_ z&|0?g*53rELWwG6F3i^-3-g5^EXLmCBn%203s-y9iIkwOEY_;CFa~zC{lys0OP()hC5P2A$dkFq%Dbp?QsoRs|Ncf;_8t7V6-w1 zs6vU(n{r{%_lcl4R35)_Uz~_DeXF3V{ydJLE_y}SDd4l>afm`o3S+s+f$}`qF@6Rp z%UcLh`xih$|LGtd)fMQ9W;Q>__RCm$^DAu0J<6?hro{Wr3*ey6bkGmiWv%);EDjGw zn@ibqHKf+ri(s!^BwNSOUKm-s5Do@Jg8isA!sEkv5b7TfXFcUz`gRf_ZbjXAfFoQZZj8c_4TEitoIy2U8eivFY0lH<*91L`uAqB11 zmL`T5z|;X#q1j0j;r{C-@NL*MShdJl_`ZBGq-v%>X?1r-%)iV|^2nbo1^(Aaq6#G% zpI!`u%_3lXco#+}CeOz0vr?tXIX{3B)U~<)B6xE$6`t7`F=AGDG>&>aM!Kw_BT z2sXRJU}nChpyO5u<-&NFnr9)L^I8fSrU}rzMNdW?`92$S4dSFrceNz*iXv!OZ!-L` zvlCv;FM_v5W8ruowg(LPpV*Aa`q^k?lPujnTu-9^uUY+N&}!i%aNB40KQaEhH5*$j ziI=KR)t6{=N+jkih3=QaLCwyxVzqt$&BnPs=1QUL`%4Mx8XC70qQ8bigIJmPaeg+= zj8B$+Ui%J>Ca!?B`vbx8rJZodbp_zeVbF7>ok07?R?1$Uja3os%vV!|L|q2+i{aGq zQE<(t$Nvz@o3qhzWrB2AqaJsyDAB>G7^>foh9x^~SgYKtYg`0D zwFcB)9?*Wdi!h?k8W`fpcB|Z}X2igl+3cZL0}o;Hnli}tw1plI)WSQR}1sw-_{@Y%IU>DRb?E(Rse?=OR(^*!OFjvI?{q+tv`&YvljhArU;>Y{g( zjcmuVcbq+gB|oJRgk*1k_d!h|d2c^~UbhZ*74XNi5v*V6$zuFi5{Dl*_)4b^m5NlM zL`r-G9BAJNZUqfu#2%A4oZd4)`gW@)7sIBg9FFU^f&S4RTs$_CdLtGG-5()+_i^Ly zASG%WmqY)R9Y71@+1FJ&V{uB?V9E4}Cr3~hy_>9#J}C)v?!8B|-eS{(euCM~Ef9KDLp-7(uU7A$m4xdu`oW#wEmTyY1YIewP~19^gbfa~ zhB>41m6V{a_!C>;QrVT7r>*4}&8{Tj^sWl9>$p@&6-w}H=np?1g=3BWNZ-wKxP4gY z2pb)rW9Oec2H}KCEzF8|z>VBdf{vZBRo;(-(cDo3M+aQv2{zyR zpyw#;lc+%JYX*?ww*dA&91iwnQ7Y=PUNj%9BSXQyog*W*J{*QmEVR*msyR>>jlmQ9 z=M2K4&u#HuLL^Xy5_F7Ip|JDlkDEda@awDsj-W2%>Nq&pG#Pppy0BKIvvKgi&gQsk zO9fDc68sqQ84G9B?`VS)3J-7ubte$eZ7$~O(#B}GGS%Xrpvqp(5vG^Z`L?Xn7}LJ4|B z*t(@Ro@n;76ZUw2m?NlbZ`CY#S3etW70qKYo*h-;Pq91J>R$n>P=dc!?kk<}&T?y9 z@bW81P#2xwVPnW!ZSY)(BU;;QaPv5n;AfY7=2&1oHfyQXwJ}Ff7oBxtJB7R-h&BD& zVTZaU@JTNcMilMD_V?~Z_xVcVhWB{}QMy)XoWJGa0u^)>-j zDACS75z18Sp_6%gMtprb2!kfK!R@8HIfAj-aj!#u1Rs_C1`us0kwqM1Qnvpo>~F&H+^@ zv1?-j7&@&1$DQ(9QT|F_JbI%AZuGm!5!7|?O$6+5u7Jf^@>@~E;6S_)s*PoSSAZ&% z=v|OnUBdBXmXe4adw-&N(zc8ZbqhZ+iTLVn@xdK$7 zM7~inTSN81^FS3! zWDK4MN8c}k);_lxQGbI!zNl@C-G1KV2*CC16!@kP!!72jPpEnh5a+fhv^f zn~?@Fj_FWfSHp9`g9~+^Kxty2$8smkd+jPYL?p3R( zLWwK>v!Gqc7C2)ugb|aq2BMd5Tl9YSnX=*;i zZkP`F1I9CA5j!1kMAA9Qa7jK#P}j|CIq>m)GTd!2kr8oE#^6=Q3)0kG`BIj^JGDvf;dCCa53CYdK&48I7va+fx7DY#lREDADd= z9wgMJ!oc40TF%95gYnbJr_!!BY;7(fsB8T6EHM9&3k4Y=jPU(A3iZ97NuE~&1*%Zu zd(i?I>yrhi-i~C%`h_ELx#v4cd(Tjgpss_?^I?Q~F)aHY%!rD6!RTT5PV#Y63RIzl z<&az$9LB~lr^;&}mxcwQ-iz;2WuzlVP}j0XnPAeS5dP~uf)VGojKttB-=%u{3x|(%HKq@$RM;a&_Ml^h5}V6 zp*Wuf{(6Nl<&7^R_HG@GCks}JEyn!hDt&1^FJJY0*K{m~m%bHU>_2ezz?9&teygvH z!Cz}8z^@aZIfA;1J1&E&j!B|4Pp%%Y=pTw#vX(;2(9l(=uc9J=*8DB32@W<=JE z5FFp5yAwehE$J@c3F@N1$82|FZ68d#St5?S*;Y+!=V^sJUq^qn!4N!g=cCx8xRshJ zl;G>=zZ@Hkf^9fdUe@CX>Uxlz4bKA8#l@y6tRFis48@jbm%)cW&D2z(#Gw2|&@Mhj zT=g@F5vM2l;&Y#SuuQ8ZM^M*Zb`D5L;5pHFu3Upg%T;!LRi}N zl=z_}kr5jQ48ghpb1BoL2}e*@hqCz))=U>pM12vM-9|ep~T=g1WkINriEakuafHZq?Rt0q8dSfb`bytUwh?9J0xRoVqDc zW+(rhKda}5moA=`0*uda1a*m9Q{Zf?WT<`ccYlUf0XW?JyrloQR-g(cjP>V3{ERrz zNR;Hw_Pewg%T?cq`}UN zMUeA*93%XO`Qn{g4OFM+a|Ct8v`>JIwZ)LPL(UV2d>evyJv34CY`Q=dN~D*jf{*qx zxG`xgBeGP3aruIVc=6mkj-akrI&-1R7q;HukxW#d@x_jZ8lu+KsRC6fk)FoZ{54(y z>(-58L}@)Ad~#D4zp|xFeqmY z)a{Y;tCC#`e3%{5hmzw0mf>(0ho}V)aTg1JWJ`LX|P=ylo z*~Qi;KJmgt&EL|2?A;teUEa@U!HSqd$cbZb|d7 zc0n!7)LG9F)OAa9Cd7iT3f1Kyl11G}&CbMX3EFHDKm#iX6{1*%YjK8e_w7N0$F&-NDhGBuSWsB6Z+>0q#Z z1HAd~?{lzt0Is{;0uL;mAy9=9^x4IJOZN9e*9&d1_pb3AL0u&&Q^B+GW(YheKLmN?1xXEb-)di zdI(gZ1bud~-zy_`?A5z7s?54_1a;Gctc zGu`p)I76&#{Ypg%>YDN)0-|DfLYhN=7UOn>C)PeR!2M&_tEfT=I_{@XEbQGM_ZxP` z>AlT3g1Xk8oeeFAZwE0zK523yJ4wK~aYt-dK1@j!O3?93Ha}R$@{$qlv1U%bND1mP z_{2^uY+40RbF5j6o{xO7RYfa|+|U`QLJ5A~!I!L_bF!Zb^KNhA>N#m0EUnaJyOBg$ z;UWVi&W-!3qzWZyO)UEreQk~Ith#3H&ygxhP#3M|Wvf`bv)b3~O1$GgUquy4(0X20 zA^qMQPmffg^V3ZnL0x>E@a=3@yklaH5v(%I8m7W~&!y09`FgJI>Q3o*P}gV85V#w-4MvVouy09S%U*bDN>6N;+f3U@(qr8bN4^_4wV+1cWpC=H1!l%VyItb*sM z6VA%9Mx&xPKnd#7)*TJsZT7-{En2Y{k>~BvzJVPsa(n<(p#-guWGe?&JE23C4gPXD z$r04mpl%dA|Fa+bv*guOGi&TI@TMI$@u&u>P=eOovTHTY39I6IU@ODb96?>jr;mog z&qT;-B3I<*ZL`M)#rAmePAX7^6147?%{2Hpp|M?0+|y_U!)n3<`=5g4+lsi{b2PhZZ#s*sqz6 zk}8y-fB&o^7wk}@z5|*K>a3y!b%plufvSun(8gi_i&3z*2mYDmgu~M^R8*k^{l#E4 z4ZCcxTPG*B%JdFLP#4`HfsF|7vcz?1E?9r}dlgkELH8PEyA+IKb@Z;T*eFVi+t+}) z=*|nQ+9}TpU-o6^*9N(A`%KWiC1`B6n(9suw76x5k2hI!F(?t<#TROKAAokJf@3|?S^n{u>8`hQUu z{f4r-qS=h_St|wv+NkMns&vm(erMIguT*&E@fUH#TnjZ-C_&$l+3L@WO6)ah5{&6> z$r02QbUYUFFJ_B+HW{oRZzs6nz=KO6?{YUaRVYEGnvj`PEmtPx)F_wA1^iKov^RH)K{TlkSeL$(JS1dfz#M zx(;2L3dyU|+5M2`)eahXqW_KSQp?&m0#ztM-;mi}7RBy(t<@9hzx6LUg1WkNp91H* zEP!6!*V0e1zeP=dZ8vv;*fcMR?DNm5L?$r040H76WG91EcSYx!+^ z=H7mIFygB;s>NA>DwLpa$m|X_aYqLmP3)0;f+MJ_tac&{xwahaqU5pgj#mBf(4u;H zLkR*^C_&$l**;zoeeuF*ZT#JAFGo;U^ClCZ(bp1~a!7vLHk;~!qa$?CN3mI;3MJ?p zvO*ECrVqwxHOKaTrensz@+IX^bXR`cZW`~74URU)l&s|fRVYEl85^97#R~o3OLJ9i5t596I z+z-dO8RC+wz4lXrx{eslf~c|`(AUnE#dx&V3-=7w$KM9EB2_3s-;h})QiTl`+*vE$ z>E@!Qd$!Y^+4=q3odQ`lHsGt6lJ20U3MFVR!RogCZE@rC32>*qBS%oz#uJkvFlvF= zyYYP1k5k* zv3`GrRI<%RO%+PeT!Lj}U0Bu^*-hG_=)n=x_20XRP-CM9OQ*`Y&wN{FTzF0?tsZKw zrV1r!F2UX)dplz5gA*mE4&6C|y3X7k4^K`z!*p#q_vz*4iqjJlrI&d|YN}9z<`OL5 zjd4aJ_hpjZ#?Bl;U1`(9;Bw2+pzbN>CHI|Gn0lvFnyGH5rV1r!F2UB;HgH8hX{WTe zt~Ezcms9&t7?2(Tn_J5>4T}W<&$#T9`gCZnrV1r!F2QSreu>h=KDViTdj2)w$khH__l#y#6mjYBINU}?&Efhv@sxdf{Wo2o>+ zwYqpH^(047SImGBY?f>t%t)5=k_pQN)cDv0FAS9gs!)RF5^Sy7b+#kdrdD|PL^VfH zSCb3F;IRigb30$oOUmx4(07v__Pt&yP=yjSmtgfDtzEI8MF%|gbR9=fSDVm4u*lpB zcOvDyMDM2(lc58;`W6dRp#;q(SZzj67wmbWGlq9u%n{U;`o|wuxbA|wZgO5y@xvA0 znsmYC|78eNp#;q(SZ2w_$TH8EV7NmPM^M-AN0N34QF(EXoep@_7kW=37Si=I^hRS zxV@bv#?+c}1a+OBF%m4A15AvPt5Uu-QsR;I=4jSgQ=keZXfDCtyw)l)@`wc*{;p6_ zg1W|she35k4Y)1q!(z02sK!Na%&^|6KowOeK{EsPtbO2yX&z?SPLZLc1a%F|nhfJx z?*+e_UM$AlRCm;9YJwK~f7DQg5;T`!Ge150p>)y^>&7<&N>CSF@z3__^Yuc_NPRqU z)q$%8pah?n487rlhZ?rQ&uwEkg1Ts309*B<@Iy1h<`~`~2B<;_eip#o)dZhvtrIf_ zyQ}F5H}o7EdbR?ao9JkUaf+|vwij;PsSA{#IT3qHb?Sz0N5;XC!M!U7jN@1xyL0$Z51$)m}njv$RWG#3+b`)q=)j#MKna=?u_xyhTXY?r6_`8EhQzmF5}g#gSIr&h?a_Igvsk9Y_WS zvzmsTjyNq+8#T=yaXY0`g62eQ4pOfd+AnN|x&gO2g1Y!!%(u;UM9WSsP^0mAZclPb z(42_vb9crb57)K9*mcJ_g1YE#<80)~fll-Q>zT;R9(G zM^G2tZJfQUg*agRd;=U=Z=*mJO3<8$Wf|4%WYQvIJn_1OBdF^)w~KjZNiY0nVSb-$ivdAJ6 zfgph{>8nuj*1CBogx1l3Cd<{J`!O zyzS(X5`ix4F%^AYBkg&{;KqDFwP>kl6bYPBDcZverul^#W< zyf{c;HX@yF>;oU(qdo?<4Qtz!~td*47>sW4Ht_EFLRs4>DLUF@~ZQOcnqsaXj3?*bsoC3$mwJ}S#wT)$3KAGw%zR1n;!#HunX_xE zM4&6jCz*!rbfaJM6tP#C0iL|i*i@!wccrKxAs4bvlmuD4mM=>pvd z+WWdTA|>F+3|?Ww9_G0*GB4gckv`uRL|+f>t{^eyv*`7&Jdf7BYbS^@ku!Offw^o+ z%`JLVkiau7zL3Ap;7=FrVof*Hr%0gdlIJoy$YnkayrQ*bEZ^tB_or=Q+j%ra1qnRU zB8$iRSv+tX(^c&IaV&q#X{}mE)hNk_keR%XKZ+1Dpl$2u& zU6`#)w4R?C%=dVe*Q782|jU1Yh{0tSu@?;JVK`-Hltr`Go$(`T3lkdL+;_E^z@}QG6ZU6RnM=8a&07 zzx(u;Il5R;RFII@kgl(e=Hq&PWAn!@ln8V++8IuL#j3Z}OEnfT?j%p)^{bv{=3<4& z7lDhZ`S2Jz{B=9Uo-CmwZp6@Y-BiV<=2E)4egu88M9a`Lr^XbnbU4SF%*)P01qoau zTdZ>2cNE`#_&0m?(@&4sqK z9l@tL73J|^y$BNMa!8J#wYRLKXTJ9qG1jyh%D*O-;tB5}2`Wh7y&&d6b{xV_HY&}x z9$^xJu1$NxXx*kMbmOT0B1V~QfxNR@XQqxhqwkQJN!hZG`m^JDDJ33dQ2*zJs5;9* zk@FP!`Udi-V}x~Y_CSvc68*C?=%W`!sHLeks#qBq$Oq5u!q}`g5`iwvktAlBHVfui zRcf$oCis)Sl> z1Zk{C1qu3n6Yan3ieC5CQ4n9p1o8E2%viOjIo3#^3y)9K4MgVQ>hH~1*YHH?IFPvI zyooArAM5v9Xff^-3gWGgwPP(NY?lah;aL|WIr@k2pXM*<*W-O`I%Q|m;rrL>Cruil z*t`*|A?!=mGmAdTU(ak>>rS?QRl0VU6xuKHa*iv`>=s1WB7rVEJ~5IbBbf6lrP=Z8 zbMsI^BCJj}?UcGpAJbinv2;=}ujy2YrDR-^2z23f60Uphky75M^txN< zeeVJK>=|+nDY0g8w^07BLlP~2qK_@+ibA6ErOkBRqUn0OhR$NIvhIZNSN^-H$A#w- zfi65FqE>V`g#YbzoR<9bUOKx-gu85}DQ+?PQycq;7;7U#cteqcg$Hhy2z24K5hIuN zA$+V=u>Shx;{?~H#ucdLb*jyqh4M<3_4?mc))G{Zz|2-+oMmDNZ`Vnz+`DbRM4&6Y z_-1-3a)5s3M{Uf+OL4B!AA8a-1D6w2kifGp+C~2a^Bs@(i1E4GBm!N_PG!*++c)YP zh@8n{PIb)?e)h{H+9zusK?MoSf+0gf&{vz|J^`$&1gpJbM4+87A`WeQ8%{7`l$^nNMNowaXnu8 z@=vCrYT*>7GPv-7Nof&{vzCuWF@y-)NDl17La9lZnjRegPy9DIeKf&@Oz;>~%> zpKo@tW6M6>kqC5s9hF91##W?NGqlp@>^pzndueZGlbcCUK?0vmoi3!UAGa+(jolf( zNg~kImaeCv-e&aZy@4V|>sEd|p^GqdzYIU8-x%W{DM-j=$-Ke=Ja3va{Z?&=M4+qX1-aI`+Zvlb)bQ2;M4G8f%w z-$g+M2`n+hh^@u`{Flo~YUS5kBGA>YYX-d+xK&^Csy1HK(jkEFrq5}uJslKOkih3( z^u+D+;}t^1cY9x3i9pxIgf!|H^jbe5N6Thq*3F-H>(HFdzSu}X1qm!Mv>friyqoIC z$cd&Bfv$R98|c*&L4|C+-lSluS5Ab}-@s17xu~wFI zY*9f1+knJ)xQjFS(R(}Co|y>}fvyriS5Wi5-qd1?R_82jKa+1Ry^C$NdtieK64**5 zMhMlP$s6{`VYg4m5!@@Qr%CkVhDr44je!cD5iz^}zzp91({}dG?WlC*NCb>ZrbjGX zs4i!S*sH7&9z1PfCi6SBUn0OD|;V z&xR6#E_~9&+qtS2AKYs$tLLf6PZVso?Wc9LY;+C!?X*_Mt=ZJIuvCKHSIOg00FOAra`pl2442@tn)hnI>TO#MnlNN*e@TJ%Y$ zA&H0c=9SP!8y;RD>L2OX^f$iEl?Zgr+LCE_C$4IvjU8+$%EXXaar%UB(F!U^IFCs; z5XV$4#_fjFc%|71dXuOl%Gx?>4a%OnUP?%@^@iW2H_ueetE{D#uP)?G%h$3e6)81? zyMKG6cfXe>DM+mSv7Wx^e=6^Dp&5c$cw`#Su^vM^rSF#rbk&bZp(8$c>f^-iD#qL; z&EVTsE}=c&?^IAhqVCl7^m^treMwat{pq8h##f24=RGUuNd&qY#;&15c2fQAy;^1p zQ?D7^>CkT)X}(oK1&LRpy}v`*z501KvoWD zyhFtqy!Kg3HYaI=f(jC@*VfXa-G1n=?AESFcFAdc>rhuV(MKlG)u&4`eIL|-Ud__> z%6-gq?sjWB>*boDpn}BH{55oZOdZ^zkZI~K{#99t?8=o(WliFU87()#zc zyqwmWA9m;x+gM5_(Dh2R?>9?Y zKpWd?wY$AvC-TFEFEP@ju!0H_y+$shpDxd(HNCV}9Jl9g-2V41*8PM|BG5JX(IQ&H zCyJ&W)@pZ^-cH~j7TsiK_SXn1NI1QZr_~V~i9lD@-8gC$zJxY;)=k9N zIdPK6Pkod9%?`3f1qtkL5zj~1M4pm)mpN5ApN9mx25pU_zCKH6)qqYSM&mE;d`9Rc zF}tP`MFk1$5fUvdpC|L4^UtvSmA(>zt`in8tTqB?4WTGgaiQdFakZ9@8<8RVNix zkia*QPDk!eWVdCh{*qo7lndSOpa%@J%FUb2yLXX+!of zGe0?NHqw|6TePI^apRSj<+4ZaaZ+w=B;*(wqV(zfSTslagi8dvFdw#Lu5WkIO#6oJYDUs33uFJF(7B>^Oef z?-E;K>LL;7!hF~|-L!+_`M{r-*bS5J3Mxq8+fK}Bh#SjWY`DYvSM4Sd=)!#1;$53J zjz12&!;VLqE2toWZ#yxDC14CcSnMe)d9|fPpbPV1>vXXj#&S-cux>x9D5xNTZ#yy8 zV902GbIDtFGP|Ngpi9b!tvfJx46oee4eM|Dm7szIzU{>9n&zW;W{ zIR3luD`q;;jG%%9zPm*0VA*l}PmydoDxGX4OvDNFKt}LfkEzk;IYfBVumk81qt~* zc<1?K-n__ZR;t+o9`84 zyqcxxU)=Abpn?Rh)hgPrMBm+BF^}@xqjnO3uCK>Z>Abvc`lJ0?5HTWUKp=O%+nw46 z+bXCaA+O>(cvm2w=(Uo1J#8rw=)#qW#X1d#0(py4ZZs*fjkIPl67s6LYelb2v)`%I z;QEu|8*WD^|Ms;jo%pAYEv`n1E?j?7r+Y1Wkzf1nrz_XZ+=mJh z7*Dj&UkT=a8x>&-Ot%~AR({& zdi!h$-x;uxW_1}V5$KvRHRg&0xOq-e+3J)m|ddg;!Ser9KYgrw`U;m#-z; zqJqTK7SZ&3#ToR($_FBbWkN9jl2@8}Y}zOh=)yZxe91Hq;&0csVMo7~(4&GxVXr9q zYoZ@r9QsbgxGGjZ9sRH#3!73_BG83TuvpXkLjbq2?8(BmRivmO5#2J19@;yHK3(-! z#Mr$%kRQ&nWF59tlL&OlB}3Of{ycv480P)LhoXYS@BvY@O=uXk@+~3WQG4w@`IirC zSnpZ8X_Li~)cjs7tyiXsg08xcBB7zpaXh7{S55{FXx~bINk3s33voO^gH#@)5H+7P1}{$4dmd zjy{c`t9<9vE=RtIvs=c(pZoN6XEi^SqNpH&*Iy83e!Oc@fA%rAq(q>rj5vo~O9#`j z{NXpTU3z1=TXeGunOR}J`H8xn1e*1YktWX>Re+YE$X1jN!%E@aMBT;d9G<`B8ke0Zr z-6eryMEu=O*375$8fm@(x^S+8=(RNU;m!>s*noY}9^A`|xY67O-Q{iwP=7c#YaXUwpc(-(n!XKlJCmDLvTC zLdVIY`Dt|4&CU94LYaAN18p00#^5?>wt@CbW%}V;%89-DTiT!B{Wy$m@52cyNMJni z?eo~5H!snJ^~=8}5$LKgYaLD7b47ouk*SDbU(uh}IXs9p+i{Mdf&`v7ovxip0FT^n z#oCm4DG}(}emI#{jx9>N-Wn@n*!lYNW&?V&Z`&>sRFJ^yFGg}a^5$}DJ5*$#xi^cKs-MO}JUSDv1?y<~m7n@7 zaXpqlTtg?dDoZoPZ@hcNcj9~xp5I~%iv zM@CHGZ#^Ee39ZwuTPG#aq%BS8Msc+DHYU)@r(4qv;`fAoE9mv-&8g$4N+QO$hvWHC zVB>y4VooA$lOTAXX%83}aN?kD;`p0=ew7qt~J8k)QDCAFTh?-^C} zs33vskBXUk*Cz57PIuVa9VH|JUF+K}p{`dP=!n}MB1Xu1Hy%~w2|N31uO1a7a8*>% z8@|nrH+6Z;+P$K(R{BE%*Xn49{X7$(1kPK#B+Y#mKTp~$S_~B=QWx9PnZ?)BKbZ@~70f?t z%8#|S=D)T!kqC61{b)xI6yHSe&P)|ViP^Jw>86=%zf>5=7=c zAO2uU1PgJsvPA`nAMYdSmBq8^)2GAb$V2gz<6S`VeeU-Y~RE_9bYdI=sNT(ik7Q0jjmah zBVy3}S$xXIbT+-}oIF&J!1E@0ux^PNBNGd=rNs*=Nk7u*g0OIXjwsch9ZsX2N~G(z zi{Ek!OOBW^Qplt#W0^k)DoEfvSlo#*fjqYDH(L5{1*wGvUDzI^(~YVZ$m{cpj4dxI zwfi7}?_ixS%rlUi)O$|9KdvDW=)!g_F=Jf`5 ze{MC2Ko{1K#c0Fnf&7|Nbyj1|8>#M$1m4r)Yw1NGHy>A(eGEM>5$KY?cPnKD@S{`g znTJCJK?MoCr$s$#M*!bc%aJ9;be0Ho;kUL}Y5c1%?`appMwz#^MFk1Gk45&qF~0oc zj`{4+v9fw3(1mpdQI;(A;*IvKVzu)MQB;t?Cr!N1mwNNfwG!CIawZaiF0A{A*1-lI zd~Ut1Y{T=36cr?V+by7;bz&*M|3N%a2|qkJJ+Ow=Xg5Y8(1mq4aVOf(;GZ_`W@kSw zk?Lwld=aaqxo=!Tdn6YUwTWxGS$yg447TWAyhNZ2>!RX%)S1TnH4`HTlCz{bClYVw zgwe!+<#guVQXRLB3td4= zT2>Y@tmjYTk+&&}Njo4B=)#)5$eEcliTgLY%)Fl+lG*@}NQ_=UPb^PtkjJY;ACK2d*z9ov@_gX~1mai>{p@k>%O-FArpPhP&3KH_HMz_+F`TNMTtkyFs z5$KZJ+w1*t^ZQMf(Q}1FpbL8kL|&ZF^VEtjSeMduB?4X8XCeAne8=#aHNP<5RStSokihwoV*J(Z(PB2o zH#Yrcx-Amu!oC-g_0-Chv+6po|2R_W$3X&TREn8lt6X@cKY!V~O4}qtazP)GPUqBW zI3K*HD4&ylOX^)hLY`}>yEBweW5u||Zt+CIw$O!Z&WdL+X%>IBEnYvWOs4XqmR@}6@w@uzZBir!2^@c?)AcIm$>({Gq%)H@NCdiY z6q*><7vaTY7sSz|LrDrMNZ>d^F(&oOEFM+kD)s4@A`$4qQE1`{cJSiiN#E$BE=v_u zkihYfB9HJGQNmqm$jUWKkO*|)C^WGelo;#mwy_=CQYTVD1qmG2DSG>oJ^1@Z!&nhN znLrngLK9h_R?gzqzLQvF8D9kzByfDHc%RRm$;;eaz|zFHMp1DMz3rC@e_VxwSx$EYwEarJt1r;Q4+_U(m=2Lm~eH-z|F`Z0~0ED_0cW{;N$ zbm5pXosLhLDKh+RWA?pMr7Q(V$XO%GRGz_0+U{oeW@k$Ty0G_MWGQ&+!ROmG!-8C}H6z40^nx#v4XPQarQfiC=((CN}&&EjhstYL|*ZcE<`NMH^aF*khcOkVkC z7Hc!-qC}tzzllU!hL;yN+q;apPq-m{`yhdNctmT|&{@38-c%N@oRbK2$zOeb!)9|j zA(Hur%inNF$gSr}?b+NqB!-o;ko$_zg}p$c#p|3OFH>|p>*%*mjK2K8ekUZbwO))? zuM@x@p6tiMTFj9MbYahyh_NDwJAJCl!kzm|eO^c`{~k?0Crzh4+Umr&=+_b<{GsV5 z8alqDM4$_M;>8^I&Y`@Mc>&d@C}e7)oZ%uz=6S!VcM*EdAL)w)H^D`+@x z)bfM=(52!kDoFH+PoS%J+|8?EA0&?4qxCTE?BY(R4=pJX=)%>yb-G_~M(}Nc3AFyu zA}T6KB-Ku!n`?*a+1x-8lPz93b}Ce_gmO!c2GeD3D$cNbw4qb+Si{cV$3=)oVUHdmmQ!ofi7IFTf9Fu zjpY5>Qr3IfE(H}NO16%pXQC$3(DZ2{#-UNedF}egnfI%m5`ivUty{d+%t!JrZ%;B0 zo~fWB5hY^j<(1yF`zLKS$CL}hc$te=SgU{xiD(QiT&-KoN(mdmqibDf--fSJP(kA6 zwP^b3!yJ0IxHdPVO^spP<8eMaGJmB+pbJ;)*6BXx4Ch4?9tF-=bFr@>y18cznGI3Mxoo ztyqk#$?eBoZ&u`EBYzPj(Di&v5RLqqNvoM^nOiR8_UE$?ROBU&A10_Efq9X{+L_J8 zs_b=4c*8^UB?4WptL9M4fK0m4Mau$ppzA=MIkY1GTckKa1qsZgCCc_ngZQ}#6?oII z^nFO6YqRe>`XD}yI>omaF(Q+P@`blbao7ASdQ_0W+*@MJ`&vVJRj1PYY_LL+K$o2N zJZN!u)CV@Cqp%ft-Oh!Nb&vj~6vafd{pt44{y7B0NW5FP(r`k+LhYwLnwIw3ukmYP^m#CX4WEZ=7Knk{;8kfMSFwqNRW zm+Oz>zc+tp;rEY71iErFgK0yn6xu0A8@JSV$9Uec!(;Yvzn-Fk1h&KKbfxNy;Wc-D zVASP+M4+qwiV%9eY%;BC{zrU~71=+5kBYg&BD!y-s33vu$>Lmn8q4oHzG6!LE{QJkR4c+jD!EM4$`%qs6TF{Zn}llVhyu&pUclkdXV; zW+YDLrJG$~xlgD>pbLA+MT_wJ={*0oo?QAhgz5QNpX*|CaSSq1XQZ@JmM}V#*Q2??2HFN^Gf2s{MQWNGtK27yK0vA%)`d zwEzAU?yi_jp@!d`?A?{9OY04EVdr=w;&$ClWPiev+yIe{WMjGGVxPranrnlUGVz(j zd-?L*UGCZ}?1I077^ol-IP!pjZgX0jYl+13nrq4Et#fi}iq^;pqNGhLTQt|Yq=)jk zU7Xn?I?`<^PiJb>(Ul|2|1$W7Tk+%$Y-x}wo$`UJo!|#q$mMSNmYz@E1 zoz!v;Ab|=J|LZ#R*_gn)8t?XA9_I|laeKuQqZp_lF}G4#1K~VbtAF5LA%U)_G1m=* z{S@OEcuw$K#r91#oU6t$t&C!zf`mwGV2H72NB93ipo>;3i19@=j*(JnyRCLyTN=A4 zVQZ6#*YzbkI^6gD|M?6e(Q)`1via@G9rapj_49(if@_XXExPdemx-pmvkiN7ubr!M zCn15{o}QUw7aFAC-pT|jNEF?fMABzO?}$I?Z?soPpbL*lj`5ltGd1D~jGWjyp6 z;c_ir!S{;xZ`$8~zHyKUJUPNZH+f_H#=&i&3!ndj2>%-c6(m{&RyV}xZn@OxIFLXW zmP&FAe4g<+AKK`LAx7VQi;ZHSg2a=FG4OfzTO2?v z{X=u-uMbzSRFVl)kchq#O1^(voLlbe0;9b`0$nQ(uPQjZXN=D-DoFGn97c-duFO5O zMO)3h;IH6%Ab~EtPBMWC64`?nlE3}d3KF;`@4pFjRY;w0h++Os%cO%b zP(cD$4gNQQt|yZVVjTHn9OKE_Rfg!tPK;K92KqS+P0sHaz&1T-_%25 zvJ5V-Yec~snM|O9#F8%sbhUEYYRv_I1!ortbkz($Y1rGWSSKR_6(lB4+HBavR$aRN z7Xn=ix12V_I346{M4*Dir@>ncF^VtkX++?c1>X5iGujdDcvt4e8WE@<5uDQ7RwLZz z8P_?HKv(Yp^$jsh-ozQjKn02WdQ(FT=XJ(!P9)G3(!ZV|M&uvk7a?P@_1yP^kF!FRh%pn}B4Wh)HyuqjQ9VjzL8e}6OV>gaFS z7I|DrIp-N%uvhOYD|`DT8us=?ZN(@CDo7OivA{qt|5fe35a`NUUr@&Ud~F;96(ln2 zL>OXR8dAe31`_D%Fe1%x9KO@FeuIL)f@_Wn68rYV7-Dqms*N!H7lAIkvNC}R5*-H= zT>q85>l?*D0$q6h>01Lyio;z1!wnA+kS>^Rrp*|*;m-!@Z0l7aRv8QCeZcORxuFA zZxs741a1q7{z2M|Nzq?fOq-`NT3VPf=mpb``1SMmnT~$DRbsMHymxxYD*Ni zCuI!3cmGF?1r;QI)-7(>t9!kSYb;2h3rkdauTVi^+L2O*7&qz}$3OyI|1PPURa$B| z!u*Bt%KiT94ZqJi#w+GE(hO%LeY$bm5-LaxN@fPS+au$4A0*I)XI(yWRFFs>aorFj z&D}T#66nHfBgeopeD$`@R8zg%#wu9m%LFP&3|ZUBKsygMexD_t+Kn029UiA$zGG7|UKmuL=t~+l%xXo~c=8i7XC?x#K zl=li19EF7Anf^_n>)&6m=@xN@yE@I(QW@ryWcWSM(o#8|5ox%uN|yOZt~7G?ZIA%U)ZCuc*9Or3En4k}0_TGuih)1K?bF_1vlBli~u zqC;Qf7yu-A^_yk53)Xz7ptw3}v%19yqJd?V3y)$A*JJV%Tcc+X6(kBB8*QN7OO*XD z1iCIwD`-{ya!ku+Rq$8vRzn2|dckU*DT_iXZ}mT&H| z62@&Zs33v8a`JH?fiC4|7J2+(elGiD90L_3u-{OQfqge|4$V7iYCVttd+z?TALoC0 zO+mt{{!MF5%k}&}y5KHB0$upb|F5TjKm`dK&s&C)p~V2>7)YS&-(^X6=Ym>M=@u@^ z%L_?{C)Inazk+WGd9P4G;>Xei13fuJ8F5Y9J}_X-Jg;oiyw*6y(0*7nVG!?`+Jw}R2R zLIsKZnc;@xt6SE%ghK*dANP+o#CTcKxP-%ZY9-$;hG)BDkM{)M!SZpSA`vZ18|cC@ z@5sN2bZ|BN^xE)zoV(P~=*Uq)qIk+B!`*ID*Ej|e=u!sN-l^?P#%bdiSa(XUTEei; z(H(!2f7hc>K_bJcsDVD1@XP4Pkw90^n*}wND#MKHYN#NQb?lzu?A|=7jU+GlD|n)i zKv#{wZw=?FbiQ%_Io_j~VIH3@IR+|7V7}jf6X?P+MkY`}0y7f-n?M(qL^AQRUcrcz zi){u;Yu8|jArq+J+BLWej!d9}8UJxhGJy&b^11*8Ou;or0$o^k$uY3~bJ@~@w$LBj z929IXl?hakXkK9})tvROYa>hx{tEUA33R;(D`>6#II^!1feI4Es%;e`_}sSt81~-? zblEj3h*5NUf1?)wdxwz2a!M*zU|}~csJmh zlX&;Y1S&}2dYAtu&{ZqCpj3)EWBg5x3KF=!o*V-SbYaOS6R05Zy=S)JE;;re-|a}C z3(H42#$wabhI@2f>^m}HalvS+q7^Ka5mTb~X->c6#&2hQhu40(*YKT?y8bQs_xl_b zB%UNkH}7}3a`Ocu%d)&zNTBQAdxZ)TVTHEjY1{VtWE=wtbm1A1_iF6h)rPzJcm-8) ziq$d?&`^9xmso^vG7g*9Y(uTVkaL@R$ojAKtK z8O1;XU083IW1KphWZ2feu%=4kzFHO|F%#oL1LcrO!Pu{;Wya$&P(dPlN|xaqejRRS zv{x7d>7Y`{hIr@o#v?gUL1O6pU4|GHZyNVnB7v^hoHd3Rbw`^T?G-9WbXN*Sf3A<{ z@m~mZS@zO0Oot093deCFjC_@>7%fTG2$spibL zC}wmVs339tf7-$aSQ+~P-F;GF`@DtT=&25;~e<9G7Kc%3(z13jj z7^onTu(OI`uXcU>YdFi=Stz)7Q9)wik!ps$%84_st05t|%9k+2IH&wJih=iQHT!JC zc1!>HME-s6qJqTI2L<1|^#*@6ih%^Wdb}@Vi1&Vw@o}Jn#H2b`4Mh4M;}}SwOF9eM zsTF_!Q#XLKh(t%zzlIoD8-E%d2X0Gp{qyXed3MxRi|F00m-6mux?y`BV)S_JsRgCz z-<8ItC@M&NPfIh{z zu_nEh@_CyL`(E7NUU45+&|3Rh%)pTM3Kb*@m(DiOCe@9{`yhcXJnM1{RFJ5-CDRb& z+F|3e1POHEwUJ|B%XSRgLhdvfnp5TeAgPsGCa^UdiI)er5PhvaIYa-WK8OUm{;n&i zA-(^PdMzqQi25h_|E|{}fvy!t3S!v4bvC+!s36glZ!w(RwU2uJ7Xn>)_sHi86(nBt zEr`+KKSom_fiAqq#H>bZSJkujZ$`WAr&nr(klw{M(uzH5C^4bI4b(6 zUTZm>@I$K!_pLKYRsN>3Q6|fj>H8DOyG&>Lef9+9`qvd?OM@=7>E207si(^byKhhZ z7ihD|FXT^Dw^qB(w)fT3-U;EvCoY+`a%iL+@m@fx&sa&b&el}&0wRgUrdax{r0-W3=Oi(LU*xUTGAMtzw375|U!Q7O9iy8iku4pX(X%dP#C36V4N}+tG^NAi znkn%|Gf4F%M9+lF?|263aL>x{yD>{6Men=lO&@8a6e2tV)W4-~+mPmil(XemkyOu} z`qx#al5UfdNYv{~dK;&C=gz7W1XR1MqyW}n_|IJx~ZhGgw^pb1BB zkRSJA$g{PMv}euR#LP2>{K^RmmK#P^#?=UpkUlw2D} z4mI+iKSxzk+*0F6-*!Rtc1Bfktn%1w&Xr@+qy?a^Gol_3nz+Jl`~0$+oj0ZSHYew8bQ)Ry7+kB6mM^?Kn~C^|lAOTZPgU z)5Z&8)?+i(q=qe5`yQchoAe_6wjGQ}uHnYkn)*LL$(0!iSKVeRk6$KQ0Pl?;;Cz{mxE& zcf-akexx(`b8i>e3Yo6wB%1}Y#%|Jpr>UYyy zD=v!|VNIfJZu_owC(fi9!H3b#;yyIJwx&#JNC7kiVpi}Gkha1mu)A#0Mf_aI&4 z^_Sq@igLHFsan3W4X?hdj&vMIIF7O=B?Au7#p8a6y;@~%sy6v*&67(sln8X;F^O{b zfw)U9*zna|3bV*sR;04-B(<$kN$IrDiaZHEMrSQ6t-RahL=ty#I<{RoQNkUirs~Z+ z8y;P(1VaUh2B)mZgU-k3sfVQm(O|EIy8ERS|6yNJBG83rM5n8sW~z1zwBbFS%S-19 ziTwJV$*{jiXk^_IBF1VzQ#E^x4PSDqibS9b&zs00RN73P`pSkUZ1_g;$nlu!Jnlr^ zT|G&=_Rw0qE_}97_xg9{^9H@5s30-nwIdnV;ShEDu8oxa+R{wz(B786FZEa=&^1Qi ziRhzGQN>?-50>3!re^2c@@8vS(wXZVNyO75w8i-b%Gyhoq~z0cw1RC@<=hQR(t@3% zdj@M`gdb#>saa=jd99ioC@Pi9bRta;ouv*Q4HVpx81EQmrXJd6%cq{mkzybb)3p-` z$T&kwm(yA%Mz(3C4lN_@t55qS0$q4aVs+rjW@_Duwp{OjhN6PRf`MWWUC&UzM%rlH zmd<8sb7w(}yDkyvlF!wllV+;NUt7LmP&CE!gGYNN!;%y&e1T^8n28v>y;`YXw_5Yg z&4MW^Nc1`FNRDS8qmemUtJ?RwW@^PAg#V)bB?4XV*ISahjV{oIX6AypT+Up*6ixVE z=NfwFTubuq(*=5TQDk;zx=l8R&I^ zE*+=UAVbBM%&viiFYKyH1iIuS|Bz*>_KH{dhv@2LjgK8^dFV84J;F{2`E5x)&bmNH zt+rD}{;(tu0xr-OleCu96XnfS(FDd<4W68b=L*k4)xDNP`F??x+N||Qt-9DsH7jhx z?~>^@s3381L2t7B;x)JUWJI)pfbY&m4ByaCtp!=$5BOsDKo2nzf zh&$2wFzJ)nmE4LuNv(%CDeEqGA{l4S(u8Y$6ie~czN~+aUPM+s(ij}MLM23Nvnqp6*1m> ziLbsU;!DQ6mZV&sY(;9OoTh8`4wSYeGUJUlQ}3U*=8MLbmlP!Wb+IDZ)@SJ2>H|cK z_1n$W&7-V&|A9XU?iIS^>#?q+nOc9YE#F@JmUMQJsCBgy*>U_V?eIeDsXqM0RDE~P zmaiLoLL$(GcZ|q1)zn-au(Tr|zHFFs>TGASksYP&!$&Ebh zPVT3=Bcnu&YRfIuW+yuG0S;Xy1qnPpvF1ybnYtjvid)p`Ae}2D-d65RZoEA~yLKHe zVl<32Q>P8-%sn17mk4y>)f8vf&0O^|Z_i!#dnu!mt;y}Ohv?zR@k*Nb7Kv|qn4T#+ zPTE`Xb{;H_d`EjeuC2(k3`dAWF9&P#DdsQ@oikSK)mp_|&4}v24_$PV2z22&)amq! zg<3kpRID$XqO|R7ORl`xN8i?-rlfqfA+MeE^xKIkO3RWC#N*r^`skB37kN=r3-wP` zbM9)fQc{o@=3_&G?l3yGk2bb;#~KUu-qj|2%AlRf&8~!O?Z1=0y6>S>d2CB|_S;SC zTFq28x9LSj{>Y(chia_`PogYTr|f22e`brMATeo_ElFy%kCwiw5x;I*sEIx5anqQS z${c5f(1BZNnAL1W$tUFFf$icu!AluC(UH_%wuP2ka@S?iVheqhkTfS!aZLtw zUgj-`wO=gM{bOtL^M|fW3KAlf0x3~wD{VS$wnm(^P+gi<;Ew4Zl@VjQkiwHw>3SNZ z?E0aSuU&mGA2TQz>6eR5Cs>J?pI_;M0FNntO z7V53|;=Cv;q9%IUk-SF9bb0kTN?rv!Qs&@l>h?ZFd1B>Ef~qIe*&hN0@i)dootRmY zpBh_8MFojzo4b%y*R^!)&R{`Y-fyn1`t*bO*p^d=MRp}M9hTC4JLf7*n{_2?t0d52 zjpi!N!}<~>aVfRy8Y&3ax8|zpr9UjezKn_r60>jHk%rAz(7UJ<=v@%#34PJwrH-+&OBMxTpj2BlFeLUqN0LC zgVNoI|Kvq9cj7#a$TU^Yw7AULtg5FnYERDXnoGN^4O0&EvL}x`MXvs`VakQF1IYP- z^XaxIjTrmHRDB(DjpcQytD=HL?{@aYwnI4m`bKLnIpEMzU0ZTLyVAFr)WU+TDx0o# zC*7{kq@gdhS=g>so2%6wH?XTYt<~`pdlLJL{iw~7g-Y0)9%RX}5tP+jsI-_qh?JW$ zp3Z%t&8dEr-dsJ_Ig4ElvQSY$B4m6IQrlqyEk8e85as?hSIs=OGG5bMBG5IePY?3< z<3w6zszx}OG*J&WoX4h2?X2!7){E>uX-1pZj8qN{bs&dd*ig5C2*q*H5aMsC&^1Rj zVogR9^+Q$!JGZBkiV6~$^&Lp(dUmvR&j>*{+;5_CC7L}dEfeUn``eQYsBceKw$zB6 z?G03`37wgG!A_0a;YbFWebo>5h*Hk~?M0%RRH8+nMJl_-4I?GDRi~xQG~xhhsJeyq zU~i+lsOWNe)Qhz6HlZe$jEPm=4b^)SoLHZ-T~yo_5)ZfbBK1Dir1t4rtJ;>24b|bt z2eZE~6^TICV#{7+W>z!$#ZDta3)fYzckdP_&-vRQ)Zj)vBk|)`#tTGO_4$ZMD*b)--&Vqq;h*H#uig zPVccSTIoNhH*u|8O+O<(S{b@xB>5a)NdK@wl!$SM)KPoJjin9yII5^1F{5N}()fOa zzF~iDuNLIjS1T3Ws86`lQzCHwInG|!=~}<5t+qC4NlWaP_X^|vi0DnWeJG+2NYG+j zb*-b8Tlh`?HQG@{1qnHZ&9)k}NMJq)k^MV|s87dz*WcS?rlNv`}%dXd-FWf{$1qsXtq0`OG>#2_I{!Q=np}vX= z66ARlDYx!b9u3pp2FH#$s(0$7>eI~YNCdj%JQJnMIIBL%>-6T=tE;FWftg7}HrwjgWu?>APE2y|g)67jCRHbnK@o}xce zuZ)Tc5}27ptSuWqT&=L>qkjF?;wmagJYSMPBBtEW8`v#K?A5}CE^5rf)%xCvg(U)A za>kR8b)(d$F01wX7yptnKOuqHnshpwnq$@aZQkjdPxz>yf<$1F7=={%X5RVrzGAQZ z+{dey^^)~wZ(c|Qy5uZS>FXw_<(I6~FRPm`WywMUGh2y#N|z?7?XSGlAK!dkK?R9D zmDiHQ_)B@&4?M+Qsri%DYxffMXFi{k2y{J%jCtY<;P+H@fqkOBW=FANBPd81B@rPdm9Uw=I>ML`9L)ZXbN-t1`JiQ<#RUOBAyR>xdhq<<5i zAQ9-oEO}y7bu%9|$ZC<^b8L))3KDWIz1_aP>JhUWdb6?fq^yTXTqv=LOzq9{_I}a& zyfSkA)Z$g6^=GSiN(8#(`B7D#`>X4{qV)HNx+hkBjeqO^~3Mxo! zY?)1(4&9SC`ifR}Zjc|SS{z%T-`>blBG85NzeIcc(I7Rs*#iB777Z0tkic1K;>d%8 z)!;+N^aC!ImFB)7v18k2a;pFKyo%{sZQH9wi2C|&s6M92M}pfz7mh&?&xbxlJ+eGR zf8yM6f(jBi?m(w2+$>aGKY{AA%B&@*AaNsk3t7~4Q(i+4ZM1r^@KAN+dr!Tmlcz+W z3&$OZ6)Fyfs>^S#*IV1xC8!_~^=%6oet1q^Cp&G_{fjrD>eB}fdWYkyZIM71jyn)* z%X<5(7tW1lB{~kK?EVI_&aN>n*RY#nvtuK>7y$6nlvnh4=fb ze8NaJWpQ_k3KH`cq><>`)##-$-377sg}-|H;xP8|gRMlMtN+S0(#NzKEgYl~U)lw# zji)jX#cf2H>9o|!U*D-_48eEcAT&}g;-7n&&j^~~% z>()|QAuyGUsN9~$XQ+zbt5mXQdK=nyP#2|+Sjlrw^Uk#C1$#lfs^O>ZIyH;gsG^S% z6eOlsSWiyRZ%wC!YuPVsCitn%>&#%|d4xouYw+O>r!&E~M`Cr?VpfrM>^6yj{#gBI?mwK~t(>Z8ut9?JF%J|q$7!gHw8-F-G&H8~W> zR$nX1>iDf7o?E8Sd#BqeF2hz3r~PAThdUO^%ce<0X*-%8h|}8J2i%;kmURned#4s* zsPu_QBJ+;8(h1IO6x@YGn-Tj;{GF7EaZv(*>3=KMdl{yMCxCT!z|myO+tg`Efz2F$t)ENsO96%|DgK}1Cw z15`jzQ4kBTMX|BjGs~{q78ASUw!6RC_xpUubI$X=|9N*P1nTU6-(K^;WsM zNVxi}VAXR5^YSmuZEW}yOj!kHiaKGh6#`v&FUS?)`@z(;Or+RnS40f)PGw)M{dl|X zjrFocmawCR@c^{|YhiOzL(^rgmWg+ksidesx)yogyv6t)p zpA#t#anoo=i9pfiOmTr{RglQ{OJSDGpZ7X#-n+BiIF&i1P6!<<5<#2K*A}(t3&*oV zNc`!)fQ>C1#3`kcY@>UvFgjDHr)b^nokF1NyVHDDyksmN`nI|x0(_!qQ@O`HedTWc zqID7*U(KJVb}g>g7?i~JFZSnQmL+sN$)#yO8b(p`nQ!>8Yg{?wg~W%PB$oRkfPWib zO1ANPXEc>wy@4P2JcVD6OJqa$kK^@T71T#0C$jGSefXouLVEd8iEQQXDSYS2qLR3> zGMYS!X7kd!qBtr@BxfbEPns{!>0j8~Mu%vcI+XLI8OaKPF8qFSZRuw;U0Ah*SDD{i z`Bd0mV24D;*Nx^io0{WN*QHCM5$D0toj58;l>9W0J^9C61!vM2%z3bZhhya z2?=yfbWUW8B1ZC~|5Z3T=N133=h8Z(>sQ= zrY+h&or)IG`Ln9?O{gH@$D4_a8SEEjHd66(r8NCo)T)L443ra~s1RO{aUyUzzq7 zy6=Ppy70Qmt2;279v(5A=UjQrj+a=#Ufi+z0! zOwI|}hI3jpnVw}i|M9-8C`gq1oWz#JJ9Fn=XC)C)dOCG_b2qnM*mi|LS9G5wmT%XG zcOGj#i!G%dOq=$xIihoOQ*;ZsS>d9Thd>^Lup&uyp6w_1JYoE8}hfv)R?l2`}p z?mVF8O-bCD9Yxv2emF<2DxtT@TEMFHZo&PmOzil;1*~kTRy;UIu;$ekvbY8Ie5lg_ zNj%;gNjZTf*`MQe^y!O|Sq87kAMD=BPCF#ak{WgR_+mT$5Aow^B&{!3oZYHuspH>5 z;zZ^`Hnc+n?y+>YY~w16qFW6Lu|}>H6aroNX*F$YW(3`vUWFCnZS{WTQ`pexYJBC* z4EB~UW*5Ge;uZeMWcX?2PW9Gs>U6)hv+tC?I-U_d;+V$fmw#=VelhX?oEJUyB%E%p zZtomfwWp3JNs*X4VhKBC@y+yMO0xVOgYQJplQ%U@PfN8?2z246)wEGp!pYsLB0D~- zhw?p;n7TNHwMr?*Upbj$u`XLh(C*b$*u(~%6#`v&6=bHyX5myg)Y>_;vb&ySyN-EX z?PQ8?T9+NIvyPQ->|*+GwJviiwvIh{Hplehw3Tclv`{!T_};;J!{uQ*Do6yhTEmu) z^E0_0YAuQP=fbGmKc3ERks}oXUHu$ZvyEG#Opzy@B=Pu0IJF8m?qoHvmu^SvncFpM z)ANs&8J_ZOn!bT;d05GGH^)K}OG`wM`{A`tJ7#p(Q9)u&{svajr<}>Qf%%N^?#mGr zaKETi6UVlCuYa;w=|{FEE>DK{aevnl1#|>8K!qrkvt4JC>VnOtV%9bm6C!`yb;Ys6}E` zVS4+9eLA**bttyclq)}bR>2MI-sTijP-Za}n6-iNBAfsFe|ZwHZv>5BUR7A`|EwrT zoZYyN^~yYGiWqLby6rcI(})tSMc~J43W2V7F&kLwt*xemvTZqryB|TfPZtz#N@_ZO zsx?10viq@fOy;YL?a3uT2M#Anl9^S#t?4SU(|bgqm6mtn^&oO| z-5~DQY0pqW;?dKUtV(JnerH7qd9B)(n?ze~>=5NzR#pgft$LKff~-sN-Tz&yB<4$n zhF=#xnU$3|hMOf;uvl3c=KmejVDWxD{W^U?tQk38iFQEZ?z?pMR91<}`LB&ZrTl4q z{&5l0VuwPY3qPS8m%I+3zrH4MZu~Q6RFEjPBZHOcTKa#!$H&l#Zv209EdyMA52#zM}m$15LTk&oGeUIF0W9a?l7owOxDHjzayzZv3+JoEh zr!~!|?*ADunkM}CAhh+>O-P{2Hed-eGHm{*jfS@UXkKb1<6vlWZkafjRr=SHuam8> zwn=2ouJz{|<-h;jOx=y8lfR{w;LjRglpG4@Xd+c7H|UmN*kCNSvCS!q%2+%eVa3#!Kr_^vLR~sB*EB zLZC~%y8rg+N#T_&4d1q1l&g!M@J84SwkmuQ&-|~Ac_X^h@13=c%#q$46(p*MN3%}j zrtzmg%E;fNQR&WPXW7swQG1F)pexvI2AgvI|KG-%V0)^!!rpjWb_vJ0lEL~o=CbDh zE5_u3r6axm-rCp~zL;YK2ND_Sfz0vqOup>D?@|6wdm4GWr4jX4CD4VRQ0|7O5p}R= zYCP*PgQJ4P>j~4@*HM%I=UOf1ov3z5L!;S*sS1HE^_!1)(v8|buVvi0d4{`giDeto zgZU))Y0RtZRJO2AJg?C_in-*6u#k^2d=4KfudZ7xqxw^t8apn&_75pP~83bh?f zrbERIkGzW<6(n*GMzKbxGPuir^GeYxi+=RrWd-B@^a~1sE*pzLcJ{$Gp1$22Z;-dh zjnv-?o3c9o5t2TTfqF58uX%+g^eFZ!gmY~xa)f%LFqSz~GF z0geh17_}+qYO%fPX8)?j_zJ5O0$qDvO=1n^?BZ?eH<4|Gc(l+bRtu@%W-WC0?~R7Vl;p6+B6fC*@`3pJ{Dr!%`a~;LZYt zK-ZR+BbXgO$QQ+$V;a6)u_qfldqaD;l%s+K#vW+eqn&N3_@-9I&3K^@==xF3leN9H zk5AIfQKmhf+f(tec80b0DUJ#f7=a;o;=Z>f*G<+&eEr7?fv$1)JXz1$yZN6a3)#k1 z&4I2ZwKjHseZx^f0;6CwZC>|w)Nn^jW63j3Ac3xv_M=$+W7~P{QRdab)3qIF;vrkZ z_k2--3KD9R(2MkT7Yc)J{#|@-WG{NH3$2-5*Lbz}ltQ2j`$`#wJ+&hhU)|97K1uCGk-+Ch?qHqlN;huQ zHWoj)uk@nm!aiS~*>2H^9<*y&>D!UOr$8QCI?#UHI;j=k%X; zqP{Qc8DF~nQQlEV;BzBK;Thd2%SEOUHA@`Z?$EeDKgi}_IF`^f>+>$uvU*)($_ER93KIC-$hhrxJ*n;NYDVL^-<44Yx^RS} zX~`|SlHZQnhM#XCfeI4%+{pV%o+b_~)WjH*w@JtI_!vo`p6ow5q7{w0(%5j_xkfqJ zkAxa;PwX597=u~B?LZGYMWjAJdVK=XtI#%|(72n!Za{VU8!qhoBDo7lN9>`X| z+|T1JN0|vZ7Il8y$mqCzqC%i6YwSo?XzOlnw|KZDj#;#)lm<HE! z+0S>CH0Q=Gn#rg~^G3$5iM9%XuEI}!*@hK4JZ`l4e2KBlna+1?YTR@vucLxQV;aV$ z`EXwGpgA+e@^g%icWr8PsP>W}fvz7nz1hXJ`?-~UPf1K%+ny>tZfPVB+QLvlV#)iV zEa~ncUZI8gB!}e}C(5hY(wJ2zL?O_%&S4CDayyq7JZFwqE7!gqHJ)x`ut_BuDoEH@ z9K!y|Il^B>m~%A#J1iIRm7|o)hIPcfRoTn%>t0fhlQNpMn_eaM_ z1dO4;$OU;?q@E4!*-+9rSM;+I?SO%rPcwn>*9NlVy$cupm}VOb8BTIr0)f@ghg8}ch|X%s(lR*B$2LX9i>yvUw%3f3@2 zyfqX8T?f|ck^ch7H{Ew?99L5A*YVC&83d<`MjHs3KGMU{McXj9en5wbDwzeiVGcc zsAY@~a8w9%op?Hx<-W`2U*4Mg#654i(4T9yj6xNv>8K!au;LWOcFd>01i`SFcmTkLupV79G*qzgY!gksiMGMYR^1EP!qnhjGsH==7 z|0L&wg=NnGSzwUBXh%)EamSVdtF>r~L=&H>IuuTyrek^8~{8X;4wv;`jwUKt1 zbX1T~BR~tRX-(F5TN{5ftP}!WnP2)ciwZ~h$1>(<*@Z=HsCwHr#*eE%7%E7p(XuIn zZRyr0N5hX!Cws&16oqSx-uWY&_WCqB-HrxdTm?K+P=(~bN!ez66jK6!`&m=QlPJ`QSfWF z31>q14#yP)xoU94k?cCz8A)PkE-FaiXh4pZ+S}3g(~d^xIcZKvpbI~(j7uHuK&dnA zjT+nEDBlAK9HVI3pzn56eT9SZ#;vz0{kF7Zw6)QAe@Pt`Byh|qcd#Bfl0{W(5xQ81;|)CXA{PmDl#%_xp1R$uU^KsXMIq3I<2l(=S7}4G>#7(z zH4f{jAc12EP2aCDWl6F)r}U@({)skz_EnPGTERb<*le@ zv{{j;5a`13oIE)Y(usa8uVKuq8KR?t1db)-Im>!o>C4+{#+Yw|6#`v20+iXsI(DP( zO(2Ljqmt6J{~HmFxMS@#eR|KZW{GiO*GxpHJs8RFJ@tf&2v>`jX$X$_9Vq zpb+RP5;}wV=5FGC+svoc-3#`jCJ8l+p^pwYqk;sE4CFrNjNY_0tC~^Zmz5I|=qiyA z#R@jr!tIZmvjW#PT!~Rly4V^zM)70*0UTe;{lSZ^sNh*Eqv7R!N;%w0_<^8Hxf@QDu6 zQ9%M%EM%tE^EwUcSIoGq|dg~Q9%ONA2h9bd}kVaM_#MX zRTKhUIKGyd3deP#u@~wa>q6c$RFJ?G3r(w>(wPRu)HjNZ%vA_<;rLpf((BoQ=GZnd zOl@KqDoEh^gS^`}b);rh8yk1JG*t+6;rLp_B6# zH8Cpg$~lMxx^P4;vs217fPPb&8*lz@HKBq8j=MB1zd|RnINHdlcKWA6pbMWaxq9Br zg+i+|FvJH(jtUaEMy_eWeO;;ZxSGa~1|1awUFuV7|7-|(|1Ks+;p^F+=5yHQBdhq& zrY?HIlsJ}NYX$!}xtDI463f0U&*WRLnrC+xdk>*4eTo^09siZNJ^oigLf=1|O}e#$ zAA4w?L3XO|Mpi>h81pZ2D&0%hQ9+{A z?kQ}p)l$B(nt5fyeOVXEzGq>~t-nJd&~-4`huxdKf`^nhuU}0%+nH?KiWt`QkLai% zv9HH?cI9~rH~!0!ve}L(<3?fQ=Yu?jKv%xiaCWlTQr>iwIpay-U1tgk)Ql*4rlW#{ z#kvu!lW8IEoo&uvlC!D}%^UPb@TNZ$0$rGML_UL??WyXMk79YpqDnRrBrt=B+!<}! zimu%FCpqhwkESo?LwdXE^B&J(Ez{EYvUBDY7LU8`wB*X@d!tejLQuKJ|Aab7gS7fi9sH1|!$~Cd9a)V?Z zlwn?>|J8l~Wjxl5!cp-Gfv#zvqS?;u6rT3ZyyE5dtRMCA`6W)wTCSslMAn=c%r<;J z5B2t!L=~+!_4@Wpv~=I95a_y}9?Y&ENahbyCP|`a=bm)t+-Gs-gV0eyqS@>a_V;E2 zFMMr^ByODRO5b*U5=~lORtR)m`Rm7yTu$Nz^UcxZI}%;U`sOQfz3^il6(r7V_h;*S z&*6>_!X;5Nh^T#o7ox|AuL^-KSF4e1c!78xw>w%APDcd^^@(aTZ4d=DDQd)}+bRUQu-BGj(Qr44zE{{7Q@g*83KIC-$hULl z{^Dj;B%vC zx8(CN_R@FJZpKrEKo|Dfa$WSMGr2T*Cw66i(@{YJpBvfx^ld}+j{hs_-!4K(pbL9# znaiTAJ$+mAK=6}gluT1ds87_t-K=Tgt^1-$#VQJcF3fVJY1NuHr!wjJB4@g#lK%<` zHPe)LK~MV7=$ja|{sqH3yrIv0R%Xxw{%u!ZMEK^;>BeO%47mc=>KRDo9xOj%RBVl6XL4^WMa> zS3_uX_BZjY#sq~x7rq%}eAJo2bi?73aI=`Bqk@F}@!4!e(|LStN%I@$w$nfwocdYZ zxwKRv(1mXXIZiy>pGNk2E0%uSq@#jFdh$%>b!jedu{uz;v2}ZIYV+}p*xiXM1iJ9e zplO>$Pulh2sR%oDUPlFq{@!6MXkH9|cVn7t<3_n|RPWp=VMPKls>l@$VA_-4?wY0X-bhn-3Md|8W7K>~B3X`1(W znYVVz0g;l{P$AHzW@4++qY2G#m?Mn*W`qh7YL+yo(!u07cb<6m;{?Y#23X%<_re4g zF>C?1A5uep^UUN)bbI1Pk&=Fvqk=@=Dv4}Y{sLahubw216dq5bZ7+zN?>P#AuJGD% ztlX3pyo_Pa*gLGDAN^W*PE5D$#GA#;XTfq*bmY0C{?q~OQ9&ZVa|(;z9K-){caTK;n2FTYdcSCKrH?|O%fEFR8_gnl zOq#PK%B6=1#NyIy-WPsuZX^955!P|@O= zkv^d=M+J$HUUOMqk4%2b$DGR|=5QoE`th6JJ$;5_)Hv4AP~*@0kBFe3*XoMLk8ddP z=SX0*yry*+5Jv4b^cHozRRUf3JZjoVS(_uL^+aLHe8^Ej0`E{cW9d4D8g^PD)>OHw z5a_}uSiW&O1k%v9+r?yylN=Q!@DA0qpYp!CS>TGOQz1(s(1pK~{8VGc(XiIHh3nQu z$}fln-l3Xi|JI9)(ywGyl0bz(7yg=Zz5T;j`n>azSZ{Ras34)-W|K@Zl_XNpU7D}Kd7U;Oa2V?qplUti!{HcPN*O; zxm+@{a!BF}kD7Pff9&_7gctvcf|u&DiA5H&ea3uVpmR6wjM_@$fPD`!62 z{ydpyd7F3jHGLG7obyGj+wjpD6(sIXif2DAui)=5nb+GtHT9 z#ytMEU{8JVsYR^Vw>dm+RUh4-FJNvz6Zq5-10_*6Vl3ULcTa5k^IB%a_+JHyoN6-L zTZ1{gz`enenDu%zdDVL?jE~iozlE+H!Ab1)y?DN6p?UwjRo&6lNRD2sg|^jELE^}v z`Rx6mSU&2trzCtjdeZzIkHt=(5ek8>jj;)=_^G)(HPM{^YIEBWG_c!!F>y?wN{0$rI)XEE!8Gx*$9=1gp(9}FPJ$CpKykdrzp zNH{HvVGE)r^8=&JIex1J^r4|=FN)#)^A!SJ7u!X!Jv&4A_Z4B12rk`=bpMm$beDg1 zRFG)@Cz91$;ll^lj+8{zr(G%V;Zf22_g{rT*Y$q`S>JB{yhbJS8i3{7&XnHqfH=_6 zf>1%C{p27vpv5qrU~e9gJ(H`>{bP2E-FM5Y1h}#Xk736KkL1N`$4Fw9O?z5ceXaPE zX-TNy-witF%{-sA=QV%FO2Q~^N4s3o#K!bS3V|-n94lwrG9Pl>%V^z@~;U&bi}y1M+E$U?3J^W{0_mF>`cPkK=7lxS|ZOh*NYZB^#8!NP}^ zpJZMgEZ2V+l^%CeOl-PUA<$K&dOQnh5x~p+GOrE}$Z)4~TMS`r<~k}!ENYm*4!s}2 zL!!*9gE>Ki$TEV9xhF3v1iA_*$FeGUUi|nY^XlNy_5-Q$klkWW(}y}LNF0os&DJLk z;P)GuR|ikI_o2pTcZdqrzbFK{!nZ}UB`*f^X`{@mgR3KYQjbEb#lxG02^AzxJ($59 zO4;)hmCVoitc6{uS>h70#iN`;pzBP#sjPEs8$P*;`8m(29Yh`PWQz=cZ|7b8m$SP5 z0etbO&brm?bhh=22aibZp?4awoR!l2`Tcq3bI2ln8hKTU6M0=KbDzA`Y;$Acp6`1o zxzsSHn>=4qUglNnHd6%Ep0DI?!>na$UbSVXLud*Gi(x4%6arnCX-;NJca0!V>y9Gl z(t8tTr@Nh+#oDYd%-@#ku46Vkxl6V(f|`72FV?)wQ}Wy)QFGfS_OI!qsmTO$_PxBO zk<@rxEAi^UdWAsO(_fp}&2?8z*M7Q6;;Lsby*fEdY`RiFVD>G{lBVXry0ddCE$Epb zPT9WZs33uv&E&~t*C`ZwEKM}KdRQUQHKFQKwk~7}FS^G(3eRjZmCBD?Br?YejtUZL zmb8@ZQz+G8sTfmssY0Nuyz2_~Pm(vEI@UZQJA7#>O=_GhuAY<`nm|DUe}5TEmNk{~ z6H-KK%bp5>E}oLX##p%V=d)a78$UM%lUu_DBCXhO6DmmH9V+*P8wS&W$&1CU&4rzj zK-ZD%RqS;AE__u~B3 z$=D@}AnHGCy=WAAOd-&Pvq?>>6*7rDVm65rpZ9T8kife~=H+wtl-@m4A<(6+8u%8OOtYJ<6RQ&gIVwot z-6P|1<^|D=nOVYWeGP>`7xrWF)P3nG)cjqhn0mD!M+FJI7vu@-tCMM4p*5oJ&C(_$ z(1rb@rgi&1g}!`PF4j!w>x>E#>U}lp!ekoiyGqnPB`j;gP6(nwd%3!ss_T&$1n)lE9-&ZR-($r1AeuiSOFWs>kD-DD-fx;#;A0?7%-PXsg^C*8B+I%$j~Gm z6(s5(Ud;CA59C=L{Ui}Rbu@Lkyjv7rw^||4RkY0lR{GOW9`tUaxsBH&sk+Nn;k#<5 zjtUYhT^F){<9hHQd-M4ciweVOK#^>rzdEiE=&IIe9;;QY4{vkWJloE&^q`tW(uJkV zO&t{^s{cr2%Wt*d^%k3F+n@Xg(XC1;!t?e!g+SNZmUCG^v<=_;$-MtD+u4`e^gAUE z#@ANv61+2Tz9St;PGXwCKhO5w>uQLZA!hJMvW6`!Uoj z`>@!tYNn0~68Ou?oM$&jQH`^Q#e~_Z3V|-1@5o%N(?-&aHwVRsJ?nK;kicJ7UaRB7 z$Uf+RXz}ELLZA!hJ2LCgb9Xvcd8b%g>x_;H68Ou?ytN5~=xNJs;zO6a3V|-1@5r^K z`U9zpOQzU;`n`?{66$Y$@mg=%HZN6-SyY&iKo`!CWL%N8AL(B+g_UKDQZXAVX`c>X z$#Pwt`0p#`r`E061d4gGUIeH6DD}3nk5Y+GF#%M}dc6pHL^>)+U~i{sWjY4Z&HNSO zR;05+psUryOy)V-kq^6NUIW;cKZ#B?&JYWd%IK&dfujNWjtZDe?j2HvMb8onfv$F! zR#Y3Rcwv2oK5g+SNTwQE@^FZrCy zYI!n;X>KsJ{wGO{FKfq8K?29{azyrK8d+?eE!r2gR0wokd%TXl9oU$!UTS_1e(w`P zA6#PPc^{8lRFL>T^V;5_w6t zMxM>RMB93v3V|-n9WU?1C@)&Pae-*INa(XVE|S&WoAPzVgOzIUsehNScKsXj(j(04 zCH230Q4&T|AI3M9mkjiQ{xs zkie%v)548OH1=k!XjfpgLZIuz!_~}nVs&ntGg`K>Ct)&~`o)VTJ6h|gAc0SToO4#2 zN@ssh7k<7i6arm!N3UZ;hF0baH=57&*^dsUc@twq>apJp6(sN}(6pCFrqPD{siMfX zw+ex-9=$d&uQuiR(D_4T8wuHsy57f$In2aB){ z$CWi1B-Hu_-ZFb@$uZqUy{n}-{w;K2tpi!d~OC<(WIn3AA_U8F6dEN`*id?zd@L1s*`&9k{r(@s|k|Byip?cN&IHqyw7{iaTM^ z3V|+MRhKi!J%KcQMvkbkY=H?CBybik*8o}tl5_Z8G5^vAWk(TRxb`mBUU?v$@W>JI z<>Q=DK>}w>nl|4$fWANGqFKN!h6K8BmLcCby94OCK{dvouX0pBF(}AKo66nIYh^(8@$Dca= z+$AdYYoMco1ddTO&A);l9o)HFG#}7YA<%_$5lu^Eydg65B2=)loqL-*9rIFLz%fdT$gB8gEqybm3e?o`>@q zMM7UL8n8n;DoEfvSgt4b8%}lWE)rQ^t}6t(aP}hS=M}8!?xeAj*qUHeSp^2-v03KH*Q=d+5XOYmCL&HJ^@in!4g z-{vCem4!l}>(+q}V|NWgk@tbVbk2V831p)6JdcvFIXCe{y@)R#?Yx)lorW!`W4A>zSXXVOi!K z#exnKsn*j5!e>gBLZIu%kTvW~`-7&?OXjg?M!g_<|J7c+v{|I1g2a>0YgwJ~pH2O? zo1-8y&P}E`XDg9&IZ+|dm6o!eWl!B>3cqO{i~gw-OnDYI;%B7*9Tg<1&D+4#K%iN7%E8I|GbG+ z{O5rw*xS6fJ^5|~edt+EEIR){A<(tzST>t~WP_=3l6fq8KRlA+ht&{Y4kj>Ekihk1 zng7ZyipmbR5KI0Yr4Z=CwPpE4ZIi@e3sGa~EN4`Zz!h&z>(?oou6VuSF>dvhb!v3s znzcMr6g!=|UFgjt8kc9dB8+RjxEd{I6Gf)epWSWvN&jUG6(q2#ncVH06ixXqA>8ey zNg>d+s?b(e{m(#C|99s3d3I0~IYo8ii{&8@RFJ@WZn8>DS|qLPFpGceR$U>`l{+(= ztIXi zuLrkovO-4%39McyW68b+QT)J#e0`g>3W2V5zH3<{mx-p+PUc8G-xU+7>4TB{;;4N( zDo9}6MwtWRs6UP9E30qY8w!E0Q}LPXO6pWoUrX~zr`;EPX+_(y{7%6uIx0wD#Y*`; z=dy2)OXdBR-cks36|KI4Z9N`t+HuExT77_n7tNUA!`pp%t)qej*6P%>u`lJB)RJku zM~}}6fv&jfOW0K38K#72b2Q+}OCGf4#CSfmTwyso`dyXC#sofMPdP#b39QemX*M7G(wrJgd1lp03W2Wj(-YXQ zc5_UH8k)yGbx!o4BMB4u*gG`|6(q1St=#R)?@B#H8t+rRu0o)z(VG|+TqNG~$H6>? zyV;@xwQf9t_ljyls33tgd1d5Fc}Bf%E#VIrG*<|8IUEmTJNP`)qLy=H8|lv+Xr$)H z-^SSyDo9{8Vwp7}y*14UPvyar92Ejxhfnyifn(;IP8N@oZ8-dGMrRxQ@(y1Zp@Ia~ zVV0{nagFKsmc@M4_6`bxF08{X-?dhC>Di1V9{aJYQlT3OwH9`t+chb>{T6Q9tcOCN z3+sE!cde{VK5AJ$zw*|Fuy!|&;nh#oxoA_G*!mA&FY^zgf&`A|qq_f6%v(F%PG$w5;&fh;}YkAG6UuV9+6*KA<%_=jLf!hbto;} zUr1alQCR6qkihZ0rWI>9jM6UO=WVPDCnkDt~h!RUy!YV+naS>P0Xu_WI0&d}b(P1|)DiFW=`wLg>cI3;g@($qIok z923dijDBHsJ>oTwztK$@`yheidATbyC!GF{JH@B>Yo`$C!m*v);e8%KfA2lw1p~?` zV>l#mJTK>i_akZTE`!^h_`~pTp$o^Ta@@W>iWZH(!6T<`VyGa2<9YdZ_Kl`PBlhqk z!{uxOM#AXAv9_j7-xp1{tdH}a9(R~NrxMYvjZ zW~d;6dtq`dBR_)L#@UH&6{{%(x^V48jsV;vsbb$2qGWh%dsL86Pe*4Li=v4wEya={ zjZH|POFcViSH6y{U|&fLsMm#>e|BY&1s|J6WF+YGce%2G&A*!5Cne}OT9$Pbqv}&< zxki@n(Lq@~M*?F(WCW;Fb9!~kN!0U~F(&!$Ol-VwTG%LFM;G?s@)r!Zp{72*LaSw? z^zBGsOp6RYE8doN{+TYqN;XmmbYVX)bA@F()7YA6;=w*kLInwo&5@bEns%no-PVY! zLFE(zT^Lm$W07Zer8iG^iIMAzD$xT-V2qJG@AI@LT`RLseBAt9$G?RxjE<1e0}*|w z;-^ERd&?I}6a*3&DY)`<#%E{wX7 zvs8T~wL5!LM9F+Ks33tccydPH)Qc*K>tg)L{tAIEj2@D?^a_rl=FRd&%dFN)ln@da zODNX>61=IX^L0_Udl`j57e+yu&z_H?%{e#3*Dep0_$VYWCQ{S<5*W29$0d)(Q{~wgM7Vnag+LcZoXQBdi{og*(A%Qb zLmP$)5*U3dV;WZa(2v_UMZ}p^&PbpO_wMC-$#!qr_~L<>c6y03Do9|ws-`WzF_r=& zo{0RV{o5jeE<8~n^9Zxi^t{(c@#Nz>CsdG7V_!GT^Q0QZev6ZrzvLo;E<70_-<)n? zG}&*rbCKFUdY|nX%xJO9RN&A6rr%%5MCmOin>J%uzE=j@_uFLJ)M2o!`BGqT7CpL4fsX^gB3V|-SlysK;{=O;bpt~gckBy)c zR${M zBo4}mDx0?z`Gm8hB;k8EivGTR!P`um!V(=9umU+Q{M$>;!nP!_p!oj$@w0!}&^JkJ z{@(F{@b$(o`h10e99^!@1Lnl;_$UKq2d{QRyl0&XZ;%7vN%;_{sSYJMoiv+rw zHA-MBeof&Q%9v|m?=K)vw+$I3?%Jj+88)7FPhf=_$8x{zMRmXa^VsXOaNfOAA-OtO z{Awum%^D}>6^-YpAW^bK0&CTE2CwwU0`>tdIA?1SrM{zk?C z$hmQf{gx>QJf9=V0TXr08ySM%qoU5o3O#i9JDM7Hwx6u$FhQTYotwTYlr&uoNWjU5~n zBrw~GJbyJhk`}zGDGI(zPzZFD{4|d}`NyA+e)UIw4+}%y?JHV}Rc~TBDoEhnBUjH) zMp21CP5c;KS0T`aHRLsIi$fIEd{bUT?W)RAK|;N+!uChgmrwuj&huaAB7v^vlM~sm zEO&lpz(e^xa^FT$%THaM-KN%3YOG`RbhU2y&yXlGeiz|k+e<1{z>#>_axojwttlTB zYp%7Ga6OVb*bnDtmsL>+bYb5m*Wr3b(wC5*+<($rr7}7anJ-h=-VfH?qf(M=WBloG zdVRxM^cs9aA<(7viDSy!P-eBZ#^*Z!@V5L#Jc%WxvhP65q9le-kl_YNc(NVT> zqjNj5>fOr7+_jyff&^CK)U*}Vb+Rbc%s8_~CD7HsUj&PYi{_h4*vmHZs5@;hEq|S0!HYBS0*ITHDcu=*6^PWJT9)KY@^%9F=YGaxhPcSX)Y>AU`<|4iyA+U z3e~+Q$~QY z6$*i_&109dxYM=y()!J08}HI4(T2TS#T;tLP(cD~Jt#eb zbFEpL2Lv^dZ4{j(D|CA%iSLOC3>74>s<_2Ceg;j1S+xW*J zf}Y>5C>;F?>Zl-rwbx~Aczgt{9`c0`s8?Pg(DlCCS{Bo1i^)HrzHH;l=LoXPTE#m} zsHdZX1lC@cV}{)k%fA<*SiY#n>@Y>w&0X)D>rBRRejO9q?z26fd@LBfvK zGq-Ejrsp3kOJbI5I7RiV|2By=wAKj~Bs!KzWrps^ z+x+p7#O?!AC|j%$V|Nx&{ua8hf0WgS8VA$A*2yB|Rd0q064k$?u|+NoxsTUa*~Z%| zA+&!+u(&N!6#`vqzZ-C;6|J4s#@N#I6W=hR8;gCnf}grRK#oiQx35)e{f;fwjz&DT zHf-kQaa54NzEYm#xX-BJ&ZdSOI4A_Vurje6@3!bpoAuhpxV&{r1!5$y=aWzE(BAZ6 zW>w>MiM0xWF07ZVX+`c2p@SbSjLNZtluF7-V9zJ#22DoL;qjVrc369bKo{OUa-{Dy zmbx{2CQe+5RqiV!u&os+0$q5I$qX9~6KGtSGorM8ZD&-Fz`jyu z<(d~jNA?TR)GJsa(1rJy9QD~josiT4f_LZ^?wQd?oK?+q|SuVg|l#(mvdw|IkwBpJrO)enQbG{ z&tWy&xFyOIdD2PtK79hh=;i(l=YzYv6#`wjHXz3g(bH(FQ-YXizqvim6c0a3VmCrP zc+94)3}=>dy`)A|5Qq3R)LRFK$JeIe^Q$d#wR-XuTOmbKxeP46vI%al_77P@eT zENdL@h#;+&t?>ObNttaUu`fTFy?N1&S9aVW+c;($MLA81$hE!&3V|-1>C5@~#%PL7 zn$PcFTBfW4T#1{{z8>$$$K;$))&t~TYVqkbWbH71(SDwyAQ9asiRIh%;ho3k$xrp~ z)o2-C4=c`_HMg@s6+4Govyf44A@VRUw(j|(PHLol> zZSr+O0$n&4)wHj#Bj}c$gD996ZbAhKmsttyjB5x#e)f%QIU|8Cd>-X`d(jX&xi?n)+S!Dmf&`ADG|g*WI2CB=BBpPZ z8Cs#wKo>s2GS5WaNcw!Hk~lcwu*|6NzdZmFI4k~tPU9}@c$x3Ia9knKrS=SaN=DO> zQ$f7e(K|}dfCSF&<;ZeDH0`R{oWE*&QX$ZVy@WiU=p0R#d!#rOd;XT8g2eHG3s~7w zt$1*bkiWTSL3uiQ=5^->jlL@cx{jAvz+T+4gmV}?Jzl`}YM7NR#&kc`fEjK6e z=iMqOnNC~YjANGX6ZpO^CFJu_>9jn>y7z+k6v#O$n9o$rVLD>mL^?fak2oB-T_MmF zx;2jV890|G4k;+x_%Ut_-HCcCW_ldt_;e;tk76$dtl>?jmDSbf+|OYobuITrw6Q*< zJm*N{9*km*PGxYH{pJ;~s$t&Lg5MRbJ+>(Xy72jzE88-wV}G}|;??c_O3#2q^5JMU zX4Y~ZX7x*6-Nu7_=m5Vi-f8IyfiCPNW?gJdd2otlKW+n`)X@AkX&oqa8EP zial!wDFnK(myl1?BX4R{_@3zJ7tK*YBJWHrn?E>~@5$dU+gLt-0Cr@M<8#SU3W2Va8^f8m-x9tjccvulURsmKZb#$Vk6Hp1B)nZZvDQsC@vOF)k_dEZ zP7fX18|8-9R0wpvy6?hHIj-S#$HYp)eq=)u!xoAO%N(fV-)?L`9T&d5X`DW0TsP)& zxgU2*o~vUHO1TratSM2Qm7+l7R!VkCBrw~!rX5VPq2ANi3je{46arnCeN*1*_-cQgVtypbN9?%8b^3hSIjE*W%#Q7$uu75?CEUt`yl1r??)k zgiENGLZAz?1#8+!*-6O?j09GBkZZ4nM$xuiFNJ-rItqa<%zCV8NoPmV zu1^07-M4^}-53e1Rw1)Sc#ok8ZJvrQ#SSt2Tj;{wce!I?Ihx7@z7|J7te3W-PN? z=!^;yBWlI6&-2&u;%Vl*232QzknUB)2>sSC7YTH!=Ky*g8A4IJiW{Fgu26C(AaT%b z7VEHc10Qm|wQOV4ICpw{yQtwixFW~Dg)YoCuW73)4WVCMOBh49bW`%sBY~On<=tNI z|3}$b$5qkvVgG=HfZZ*6V_+vBoY_G|0l`2J5XA1pZb4B|u`n<}Kui#@gPk3_yF0MO z?&h6y^uE33d5@pZ`})W8?9Fw3&u?aScXoDaL+RV$dH9D3BP9Y|^4{w4!C|z|x}Vx= zk63A^bR>M^rjt=~SFk!>l|?>$7WATD2Hw`%4@;8>bm2E5M0>Yge>!H$QEhM0ebToe zkieF+7!&S1jIJ9Kul+1?KqAnEW1gblN33v*9}}mIPTM1mxFdmWZ85g}Y$UBXC0g@J z+9VO^!qImz9`#^2eOW3_i@CI#p@M|m3O^q-iq={)T`P5Iu0)^<$LqzOfc+!rv5wr$ zIdLYrl4lNauj9oAmAgi6ew$5FcYCq8!`BG*QiyZDB!a#jmZh$^-(FIXkVjt=szy-P zQVA@g=mkCg7P_#PLX2&@Ori&my=I}Qr?OB%0!MqrtjSgr=(TM%wMsY6sz{&q_=duEe;PccAb)35kKk{i3%{_e)Ajc4Ku}1b%;1 zr`tQR4W-Qs@uHiYBm!N*hsTg^jZ;{i-iE!~Zics}yQ~UwyMciUDoEh>N5%5<+upR_ zwnE(7Zj3~r%lp|7Qfa_yHYviefBTl@UbNZ#0(|O^*$OI1;P*$xtgtN})V6Cuejy=2 zA|%(%UL-sziCK3rtanZ>(VRvGGw`kFQSOFA?b4kq|<9 zT}xo4FOLv0GLrT5MVGuhz5FEw6(sQcqoO}C)0sxhu;xKok0kF!y~HDoBhz=1Zm~&0}4whGmMY#HJD*f2SqyV)Izt>EcT|oSx6F z+jY}7oajqdlliO?vDaI74<#S%X0d1cZ;70{Z>~tKe|qx3{RdQ3kg$yQC6SKvS+BwQ zMLur7t3XqhdGVoc=@Nl1`z5|)Y~J~7QcXh)Po)MuaY*4VhrAh{j0AMF}tqprI zAcB1AI*hFnN<#b);`CuMTPBW?7JC)vaiY=V8uF36vy^ir0+rsxBl+JLAHy2ay5$=4 z?+293D*VNO>I@YmFn?lKmD8=MM}tzFq(-W(U(F%T?R;71F&p(s^=6YAm;Kl}k#qbd zv2LP^4{hUFmfJYws;D4Qc6Kx=_PjGoF_!KGpO$n}VkKUnc4;Y9=)(MoFa326q#d5y z@fk6Xvqtn^Napo)V`4{Tef8mU$?VZSY`yqhOs!~_#QRh2eL-%qY>Si+B)avSO@;qp^!XA$Iv1iG+9#CJ0mhtkmt^YGA|N-8Qy z9M)pVlhf`j)fmHZYcMUMu@=P?zP+%Vv};(A zZ8pX@rteL^rry!AE6>rRg2amlD@n|`l5E0N!?pV%pfA02_p+9fHButbb^`HZQ}UUnM5*QZ^=4;HN@yWZ7`kM zXtzeXSrAl^u+B^%1zP4e(&8N_VIVa>x?ihM`KR<-=)x3=ez@ELbpP8!T7_v>^{60m z`*l2d`%Y?oY6|`O_2z6$vJO!RD8!IX|1+mzN?gT%v04*Nu=uG55^J^ z>zx}6qZ3P}XxnQxC8!|rv{DKw)Z>BbUOrWnmE*bLH1zN?t*%Q4i9i>rBIf+Hd-prW zN1L&9*|{)narQd$I%+Lhe0`I;N91tgkrYBFoKkm-<0co^lKs<|8slz=ao1`LE%1J* z)?wcgf(jB2Nhu`T>8z0!d+!_`MW1|*(i$$GE)nR$6p9s9<44gK=F_#@>oW){NJMo` zA$Q(iRCgKAM}5bUv}UvU+L0c^Bm!M>&R2dIOOrl%X*;5KNjb+n4OzdIFw2cy+Ct+2n+YmNG`+W;th0$z$M-Ol)r9Zk=+GN=G}m`WB?4XV53VKd*6V)9$UQTG zPHVP_9Xn&KEI7QLl#C^+CZdliyPo8&7^$k_xRU2a($%GtT5g&lM#_o_wC|V8tZUaF z1QjHX+pZ_~J4YF5(H0GwK$n)zqs^>(S0d1bDHN^nG81U^K9(9^ltWNKBKhk&a(C+V z-!ZDM7*FRmDx*!;UzZ4U$vN*oXd=z2!?O;j7gAb!rIB(c^;w%g$LQNsN+qwyP0!kx zk*d$OOeN8m?bJ0XhMc!AJCV+NJUeUlh|&rwNPN1sk<6+!KT8SSDu|;t6KT_brev8l zFDnt~8h&OYS-LtlYqtM3LGb$%sCC>_HZZM_bUvh#KDwSXy5nLzPvU*B_C)G>VKVDl z%tjdl3KE!FF*oYo1Ug7_U_QB}B?4W(C)Shv_v@?7cqJ;|Cs6ZRo76US%POcKA?IUL zy9u<0*{t2kx{5tnPh4kR$}(JIA|K}_(c>F^)V+BQkOBI1aw@0$o>$K;^j-UG zB9Hdp-LpM^YkjTTY2;^T^b(yof;KNLr7op9X=kHWNCdj((v76j zmes#wL>v{*!HjTiL)RsGRFJS;zkxIulm44X3?EI0uA8EHTb|LQfa>Z)1!h!-;}lF^{%VGiQ##M z(;rI`wV}gz>QO<$Hf=RIaO;zLD=S;1>c^y^bkU9t+C1GDi9pw_x+&!HE6=WXu4XJANdH}r} zb67i>IY=VV^~xiWT)CG2cZ`$Q`_bjK&T4(y57wiCg!_&JvZh|~-^A0|edv)2*R`^x zQuL@G@mRlt-1e@_x^K8AQWZ0&7j>GJtvP%jAQ9-wIJ|=Rzq9`xqfV_JwCwX7@g2oM zdQ^~TdTJRlzghh^F>PsAY8CN8Yh;_OM+J$|b>hgdb&Z(MKZaB}gm$Lx@jtYD?FLB% zx~lGuBag>7{2imf)=-)ol7|o4Jy?$l5^i3L$jT>fzX|V$!PMrVHGjT)l^zu&PA;8K zM)q#Wip1X)smksZNZA!Tel~P~M4)R&rC745M~mMv!bbViAf*rw`PyHP3KCw9b4k8{ zHou8o6WY<7amBdz%B6Z#kmx4nauysL#Nvw?QZ;^CYZ?<=ipTcuA`$4?YZXI=t_=Jg zBVTkY`ZT5-H`^MjM+J#Pk2_JMeuKP2p3tUh zP2SedUylkBS8tCcWBQC{FF)KCsp{6rm9~zo%RjCyAQ9+F+%k^j=c9hdn3m;4gFGAZ z*p0bvs31`)Y$(xcMgAtt*ESU226W=nt7W^Pg2co;1Bh>lC^n(9Ayu)Wm(!xGE4Paq zE)nR8UORxSIyB{Xj1sSF(rz0G@7b-i8!AYAD%OoGSQ!1A`0=4SUDDp2FSz`A4=PAt zkDgdJvBrTOu=3zrignLI0$tcMDSEa)+tXe)p1itmQxz2?RV(O=SN5^XcJqH0Or5Nr?PdjhsNMZ5j;L|V1Q74_!w zZ&J$=32ZHkeOPppXw;Z!)_v+#i9pw!LTMy!x1zo)YG}QNO`k{?&(2^GUG5N6kib^I z7)uo`{i3;fw3|`RFJ@TT+tU^Wi(ycW{URqbRUU8 zSHaV3NOj+0W`$qSqwyBS_ z1HJd@Q9%Oxq6bp9L?X}?(|;ampW?;z%?&YjUGG5I=6t-Ge;qw4NXR|H3TJ2Nvm5`<{`s1i9pwq zms7~uk^NZIB14SPQ`~6`ugQZeMf0t>+nO zlne=cmWbBt${O_j1%+oucasQoVXZAzte>t$ZSLrK;>x%zRFJ@DqG5lZMzo!k6Ax+` zup0?<$)!7ajuU-1sv+;>b;Au6B(OCg-nOd~T6KIaUSefAJrd}`Gb?sCeoN`{U`M{r zcd#B6B(NPMo>3O!x@u6FpR6%WBG83bsCaU|^P-8??^ZM2Y(m9>%c*R-!Bm!MnV~BCJc^#?Q zAuImy=`pEhKmuF+VvjBF&h+!jAKIFk7bOB+So4XwgErl$>+W}2)R;?B4Tl82?}(L1 zLA~gCtNYr4mro=DU05IMba}4#p^f6NYExbAOEonT_@*cNcXth-b@Ct4KK3w|o(AZ` zCy}UkUk;)}TB};Y6`%E}Ac60=Vje*Ip>)cn4O+hV64EmYUHC*5Uu&*6oDTkwpbaRM zUwU#Pfp7O>jbgr0^x={itzMyq5`ivk8R&H7=8Bzk4n}Iv7gUj207ziJh8XQTJ(j*` z&{4}e7Az6y!WNGB(%*-1bc)VHyS|{M)RI90dvwGXZ)b{~Lb{jH)_;hS2y|gfO?+Xs z(?mMvs-<@2^$@8=h6MIyiMdgtk4(9?gFV}~N+QrDw?!X{HH!6u=P|S3`BKXg3GBra zv%(5Q(7?-P%#N;>2y|hete9C796_tq8KpMOKTqndMFMAB{CdOt^}mt4)fiuORpHIz zSts7%285|qeAA4_C%+OF@x!otfc!6#w=1=l?d*0(HT=D1zrE_@!ugEH>5ccQk9y}f z9wQ?YPa@Vary;-ktdN!oRFGKLWCM$+zTHF&B+xb7{fJtuKg+`3HylUuO#8ih&+B%2 z!+%|zn592<+QE4I);*bo6v|^F=gP8l_NmWl<8MW(=`6qda^vxlp(oViK6(=|P(k9c zO$N*QmaxYV8~;UeB+zy00gM^EW=+TR}FV7J^i>bRYU5B>VqsdvBSG)l1!k2 z#F~6_-SQ1TW~60eZZ&ffR&KR1#?xIl^_3Q`H69mRQbyl(9Wz0of&|}vRiA!qEi+s5 zy0RPt33QEoV5fJizSl$yRFJq;B1=EXYJ)L_attKU)z9*}+l>B)OvFG1iKdHJ>+Sn& zWXH{K|0Bmh0$qPET~v@bl@_Z%JUrDzK9E2co>@6nSj!A?s>#-_HLOn)J-SdU$pk7$ z9CfM69==;^fhP`E8Fk5d#Tyt^H=FuJ_w(A_gi* z)ct71CXY-q5d#Ty_0w6a<3snEh=B?c6QAc{5tR-5Ysvp2ITGmFQvZ(n=;<00#0a}& z^~3ma#^`rPMYE+d4f_m=xBhi2)sjP_Or#1GB)$%s!ko+WGZ6y`bd_7QKz(LC&qNGV zkQm%Nl35fRY$65{=;~@dmf36>X@Yp{w20*?>}pi%H(tQhyza*1={_0io)BNOPt zXUQMGAyqA(#Iq)erI_KbBby~Ma^=@Z%#RT})Rp;MP2>X=B#yL6W^}lP@t5QnNTBQQ z?GjXwSY0!PT^jfA2-cq{ksJwhVVmfW-;nc3WjCv?lYNajOzWSjmiecv@pzEWLe{4! zHIa|+83S12@n8MXFE+&R>!VfWTLEm_O#S{72j%9Mnx4TgNm;*68P+r zQ-ul=ubW$up-q#StNW3}zZ2-fXRu84y5UM}J1#b+HG+8bEDM4@e9j7;KS?;0P#Bhx5Qp11$`!ABCf`tFo=Is23`9}I*x8eU~0$und zk_o)G<15Z(wd?pAfA{bAIVwmvwx7c?TeLBeDkRW_wX2*eRFLRaa0V;=J=8=DB+!L* zup9%=6rRD)@xJ;U&YMk~K~#{iA6T7~k66y|_YKF990_#cHI0;bI>XhDgm<5cq)Em~ z=5+3T#lI8i!Yf}UY$u%5D**-3q+_b*%x$1$_h$)F?W-3-V0FOtujzm$|6 zYS>#)eC4C%X8obco1tWI3@>l|F)wT$&@R?V1pywhX?6(kn!k7GN#)HjiHB+!K|133oP`fv8cv56CZ zjk4oYLMBi_!sEeGHoIXhhHk^L{KP>QJ|B^a`}W`234a)wKo>se|M(55 z${#kJ1@G)`OmB9vc=b`gUo&=G!l$y=W&Rzh{=-CaRFEihccoe|`QQ0Ie_ITGl?w!|O5p{(ZU*Raz^9vW-1 z%umV8(J|L}oU?ep+HrEOiJBS}B;GVhW;bn2_4^=!u0f6Vsy!e5>OqoIg$fc4FD5YU zei0LO2@>e4;tJW~)NsfUE61`Ir*#7-RO~gO~U07GjF;GFm;q!84<5$^43?$Hn zHL4tA<%SJxhR3g7$EdsO*n@8e|3A(k5*};Uvh!aqnJ6nfgXqGmM@|*?y`9OQ!Gc{| z@A`7_X2#$9;ZQ+h){b=MGbP=`m52no#y>crE^#emg1}nT(Kd#aN(waAYFIzY`9KAU z)#c`}S1tUE^xp||;oFN$pn}9#hgdeX&%ZOa{xFdo33TD}@sHndpW|B*)}lcTJF_+? zW|+taDoDH<7^OZ+{8gjMF_1u4?^B_yqbgQVZ(p4*6R04O@4`rR`niASi~eCEITGla zbj+7c5$gxr#T66l2mkyN&%wKG)QtU^s^M?tJG-!?;&H~@BK^m2C@WNuI8?h83!5_E zL|Gw$uD_=Wd&#l)JW}j$I;E}!!4w&eBl(_6tMyIRj5gk#i~Z-2lU~2xg#O+_Mg@tV zWC8Ih_N%uA<3w^)s=r-8*4rt@l;AJP1S&{49*QHix|?eCA%QM@1CV2^DQK&vS57yk zB*wi`*7nmUjHNIvhN>+FY%)<+s30*R|JZ^gFKa zHGgatx(&zj+ueqD%gHUDU(Y^#(?cqfqk=^174gK*zLbe`js&{!?vi7mf<&RC3FOjM zQ>_dn(DnDb7JGheHl9?MwlnOCCU!vnf9iEcqUD(F>f*v1OynGY3tfI;8Ch%cA2o5c zqk_cDkF(T=3sOzQKmuKOugIl~3KFwpW~zOXO~pV0U4Op^@u{EToz7Z$eKJ1v|K0*X z1&JnGHZiLfbxf2M66m@#?3kKacCLw51}aEwHcw-H^Gq=j0||7!iaDy*Dz(-`3{;Sq zV3x*8mo^mx33OrGPCkREAo0EOM%GSUZ6Y5?pbOima*T$(s;HYfWvPb0=I>XL?af@t z)-}tMQdIL*TeLCNM}`U#!(LQjW)3SD{=VTjk|TjGY#AUWw;7Nqy~~+ZZ63!`tGa&j-7hr_Xw!g(uy7MNM@@VXRgK)kqK0gSa7!p+nxHW&-(8Ky0F}2V&Cca zS+PS87|+KOeoL)A>DQPrrdB3UK|)J6XG6??jV}M4Ko{moCU7)7rrsB~iKEhu=NZSj zWdao>>@M7JYaN@;x^!vsKO@yhpzC|5F0Rq(|M%JpN9g3-crsg$GU%-wgUS0=hV9rT)UeC}SO!8#Iw5j2>#@sfG#?dD0i^&pnu9 zq~#b$pzCnnu_SY+sc}wB)yOx~$WG^O#*|<@IR+|7SXj>>YhRign?M3x_|725Km~~l zS+hyU+_oml3JG-Kn}r;sM%-#OLd>Q(u*xra)9~%;&Yr(!Z(toG6R04uVaHYV%k{Oa z>gc11e<#p|HIYnUsxV&PA+yyRJ50^XKm~~+id?zZ2;C`$!!2OdM#ohS;3_-8&5P{p1)p6A+08H`kE5UGA93ITGl?Gb_hH1qt_? z>&TT4zj{3XPM`~~P?^9da+Yt^h9e4Ou=b0c6aW5nMg@uQp0%>NiC$0qeZz4iM*>}V zcOezYQ9+{SjT>1_m#4EvvA&i5PN3`WcP(BG?X5FNk<=Z=@md_mm1CfS1nwsAcLH6r z;!o;B`p1}<%W2nRioV;cc;od`U~w1HQ0&2K_|0RBqx6^0n;LyZ1qt1nfh6vcsS#cz z(1p)-IUkY&zuW8FAabFHsTfG0>+fxb-NmYr2Pc2c#;cp%gnaN>WX$=?vA+5P#eU5; zmQ#fa5@r7Bsu#V*ChkFuf%K@BRmpSRa$`I>1}aEIS8~w@z1d+R1`_C6xUne7*pgr( z1}aGOcFC`Ap_rNphy=PaUs;jagG|i?+)-h({^;*HMYz5iTeWh|Q9%M%PXC=i7q)$6 zV(6=F`h$|~Ya=B_`=HiGVqKqH{id&`W?&OetaP`j;r>KDi`QMyQ= z>+$t#O_m-q6$2F{o(zqtrYmNQks{{<33UCvEWd4>attKUh4q+B zV6Bh41L5;ZCQv~F_x<@hfv$Z`_Uc={u`||{GJy&bxKq&I33Oq7EEA|8fjb5Loj@1X z+A=ZAYOY(~?!U%NZ$-`2zg_-o>;`KLnLq`J5k1oMB-PXi782;fdPR!0oV zHAah9k4&I~#J>G)^mB@s8sS9(U05P=3{;SaxiwjzVV!2;u0;Y}SZ-oP?s{uFe_|ki z-pooX_t2TVzI>cDYgtt3syY)j<^)s57FVj+Rv~*{pJOw6l@xnNcg^!a>3yUWx4%!v1n|#)mu?ycP3*!3Ry0WQFjB%Cj#W8f7PzREzXpD2Sk{Q7oxa zJvDP=1dVn1HMZQi|3YP7=nZ2#G@;Ex#j){?tZ5@ks`*+Nh?zXEmQvJNy_GqURv%x| zcxSe7TBwXa9%4Lpc)37XvLZzN^s0n9EZdN(0e#wPt~SlpoV0QDvt78+)#=ItW!8mX zGf>RiEKqJVT&-G(e7rN}cB4}sCW1oBXM(StTL#?!(q8W9cCQ>!X z`>|H}SzaE0%87ny-<;XH%whA7Pf?s~o3q&i=CRIwrYIY2>oT{y^I7ngC_%U!`l4A} z4dxCdgOx=eTo~_voDJv{tQ5NG!mgh^&TdT#QubR{W!-O`W~lYj?Ks+O6hxUppAmi^uF=ss0&#`(6=8tzLUpWIJ2M zvsEdD^HXTJjDeinZ&3dm=knW|f+I>HRjgRY8_8^2zoLSuRduk|^XV8~sC$SAZCxQt|f&};6Kv#s{i%xx?fJje%S19A?m#3O)Tl6 zfw1+dte$xq!TXm#r2f})Q)p%)_7nweh-g4}X0W0YOA6v`{*mOs=m>s*9#sG9jhcU8 z6^<@-SaHK`N&O6VrM-c8-YZOTx;vIkAKmLjI^bH%$CJc8KVluLd#9L)p|KpQFByOkoa%jt9!iYBa5zPM=Kl)lpmc@IzH&fH`GX!N*7BMR}6`r zrcPuiv0cM?y^X2rpH;YbR{gh@$h~S(mnv2ySX}K}j8}V<-a|>OJD#uGrAk)`UK#Q# z(<|aTUX|`n`kOtrr;>8ffbuJ-!ItKBZ+rIs_OJKq?zT&jJr z#=#MOvExaqB@g!w;WviHsQ=CWv%j7AXY4=I{=*b!7A>y!V#cfe*`4#)@oZUv#4tLTEW`3cD%rxKpvS}PD+*eOkY;N%6!%|rI3_D zvCo8u9WN{D_A7JpGE4~);j?_1XXW{9N_c(|V@#|qFXI@*?{+w;B7rU}L!HidNI~B1 zvp=^F-y)SR67`mf6k5$^#p)Qo)6k-0L4K-80Drn8Od`-F&&;g2&5rM}@4$VX4zQYQ zTQM_b5i8i>lYT^QD|S|Vvtg{**Z1PJ#$xBBdDrAUcnk%Y%hohcPzR2{XpJ(O-YGB7nY$;=T+2>m$>84BgYofP(k8u z6)*N7-*Ps7q+t$kT^Bn(=es}8JK9bn(1mAKdS zU@4q_*OcwE+Q@DXG4!%*ZJUSZ6b|GUGFxh>AaQJLZ8m1#7G`N_c+a^PVZ&nz`12(x zPEw2(mps^Hu?Bhdv#C-%@qNy9Hhg7qf9~A0k#s(gIM=-eyZJbgjWnMmVp#sP;cpuH z^F2puO9Z;`+~{;yhgtD7)t^UMwASj^C2T^uU97_XOQePmVKR^V3Re4HYCFh;L2U_T9vG?KSlM9L_c4*)0S4s7>u80$p-h=@wY? zVb=b9;ay)16(sDNH)Wd&rLkqV4DZiT+?qGeZO`9K^^pj4;d#>O>Tk8;bDjin-{i)c zosBEIl)9f4o{>we8o9FSMfS4=pTCo^!qwPRk7F#ex0z_Sk6dlVFP#YBH;1}ts37t4 zs4JWDgR{6&??tK(b~EEXBZBymPt7C(U08o|x+?l@$_KOAS^jg+@a8d_e#k-P*3KB=YyRgiuhuMjcyn@KSXvRIp26M8s zhD4wX%TV04IaYij>A-g{tRha(z_#%K2SizH!SJROUil7Xlp*GRv_PGQCP|c5_!yAScL({S+G|Tk*bnCtog&A z9r){ZB_sk}Sn6W0Aa2gDbq(QG?QSr9Q^Yq&Os%L(j#%^j<$`!r#YYSkB>J{+W^rpy zu`MmiiBv7wYt8pu3FOhSA0+}^_%15Gc$;X=9hL?2Nn#J*$t4|F9`Rj>=+xTEo>V8+ z?bBKIdQ?s2%{C{NoOqV;C)GuaW&6x|%ivJ{DsH|+pbPUS-Ukm@^Cv}u`4a!tQqGYm zbjpdXD}I(yzp5g}(QDSc&e0%#xzP@ZKo`D+i!WimH{+uxcj8t0B&hi2j&JmsKk>!% zZ&v(%NJs8hE3cFfBo-`lV!_Ghn15tFk*b<~t@+7^!F*nEFNr`GmYdkYtb(XZ@`s4I z43}N8p8-=CsXDO@kI%7P(_IZ`u%;Pr_M;PT|7oNi6(sW3b6^krudrg{6hXwUu;f$P zh4ASXDlORRW`w;%@inRBc6A$+0b zVTnLj|MkvnN8dAS>LnjROxcl#KgDTSiVkk^7QJR8E- zyA2_j5+oX#IkWoR&aqo7n~E5=`E@*B`!GJ@lcz+W3(HNXyZ^v~N3Rqy&J`i3Ao2Q| z6AL|fj!l_rI3FYZEqP{m2>;OMq8*c{7Bjx`T?h}}dYfRGU|GdxIkVT5&#+s` zz9NQI@2}eH8eu#q|3`uf5~Xdbur6mVh+w?C!AyRQv(EXzd^1R)HZ}y-Ct26(Di}1u=}2; z*ppK21>t@EtyZg1D4({_PwJt=o;#$)yTRe_TKmf#MOis3s30+>nF|}{e2RH{8)7^m zKehDgAw2$3b%{WioT>vOzG$MJ=e=u$O8tr0hsecq@SM+ac4mICh!Jx2m6o=`A&lP?(#~Ds?(mk zd|amtT;j^MRXo5t4(p*b39H85&N{-%ZS1M6YUswkSKiBfuk;qg-e(WBX~o*}(I2-- z3K9dWR%at$>}OU7`Uzszk>}cu*=>2;p`8+eF6(A)Y|Ks0236}Li1jhAwZ8rR#doS# zNvSH=)0H*KcaS;P=`N*Er)&HEwbq0C^Vy#9l7hsk&aN!Y;UG)T*ImRITKSnaph_Um znZH~j(1qou(_L8cPMa#;Aj3D!QBXl*4{O3o+8trFigp$;TL1GwTa^~b1By?R2z1Hk zqtD_eT9d}!T+O~g#m$cn%a+5*I&L(e(KaQD&fW#mtdaTF+R&ErUgj7S>O- zHP)@TXXOi$f<&cadiF6bi{*3~Ac#tK+1lAtzI;lavl4+WJU5~ibvH#RmyV?!tQ6)}bdJlAIH+VWi|_DBS}_A-39AOfC0)D{+R&d*+bDG}(3Zcf;+ zR@>Ru+u?#}IrzRdqgN9iVQo#nk5Jh8A?Ymg%t&QGCxzwvna-2}BbC5MHJFFPX4d!9 zXhD40bYFAb>MHuFEh#EUR5nxC!UCJw#*c1pXG%pDo6}_T9Y+?v4K5OCI}*CZnjn@rykGtEg})< z>OYAx+fwV<=!~&~D7GP63vcbfC$zSw9X7eMWjzwvs9h74?=kMIyjK#N*Jh$p@?9NzEb!Tk0rnafdi#M%6Q9;7Klsiil-xDsk*YN#X=V#Y62lpC$Y^m}Rfi6s; zP8TsYTbnbrHt*B11VsgjH<6TWwO-Gv?K0%Ue?+$CIixOMUA~w^pi9m z45}>U9P@O%W>Z$mES}|U6(M3gS$199A76prSy`Q;f<$<3ZDz%nv8%>W%cAVQR&;k6 zp5Dk&BG6TJMN?*BwVYk~L_hbTHm_qU7oc=)Tex^9T)wVW8 z1&K*Fn=-A&QubuKAs-ecA84`STc$2yH6;RFa?T4)ysIsGXT}@cCKSgSaSRgkr_(j7 z^;GjbV$N;WyGl7nV%nbOtWb$rObs%OK|U<>MEmMu#kFF$dbnKND-uRXl*}4VAlprz4uLWCFe=Mue#xTM=@yrA5LG7p7 z!16MIE<8`-OJ@CFXvJ&fXcyi$mChg%Ymay^x9*c!o3yDShUM!VZPlr_T9BQ)M4$`D zqs3Romb}tl`)t>Sdbg$Nj~g)Cg8r;^?hNHgZ%=moVmnrAL9~M9rqflo|EzU&->HrB z_ob*H(d=SNW_hg>YxC1kx*oP4wO(0V+h^t@5$KZ72eB~YeBfN|P=FtOyw8g@2y4JP z+?t^{1beYDId1IUxEV?h){yYh-kN`{m|CsuF_hKm&*!?qGvtX7AG&}^xbeJ`hESTJ)gQ( z+rOiYRJ!QGa?|N*TbXlr^Js1CD>>(wr?kf2?6_!Ghr1hcUfJ!NmhxtGM!?OhO{%s!Ks^<`GUw(gyK-bZ=-pt>*ENh-*h*9rIu6FHnZ|z(8K#B?y zjtv_#Cf26T9vveHht8J#VAEjj@GgIeK-cEo-Yn6&G%K8Gh|xSQFMsh*C2f})Kv#Zk z#U3ooR_&8#DN&iN#GXYT)lq|HDSOT~W@YYuQ772U7DV?VdHI~U8d~QS0TdM^YK?Ej zf;O15xt@lcZ|h^uhmF%~tU-`OpbJx|(@jpW;+0Z8w7C@nC@M%4`svLa>{Q<%dUCrj`>=6f zmQ7lWvVFQQEBM)5y|O4q!Cw+*(8HGJ-mSqb>jp_NkSH1H%eoiJuP%x;l-1#Wwmi>l z%2F(40$rFwQC7#EYXR0z)e$$li>|zitk|T&>ccB@mEBfVnPH|=ndrIyld8v^K54e` zajIv@u2QOy2uyS~(rr4-5viJU+JbLOIH-Cb3XuqOVTtH;(_UEc?3_UL)4mX?tdNM$ zY+{TtqP`(U-U~K7X;ybN|2DaF(Pewom-X3qtTgTBwiNVFIyZo5!%8+OBZT)q85rIX7Iw?A{$_FwKr zntrXTepnPiQ9%Od$%$Eds~r{Y>ZX<%Hi1?xyikn!iYHz40%gSM5aaR4R|^zfe2D(f z?6zJViz{KRTvTg1k)nb`woe-)y+OB7^C|pL3O-RV$JrzwZL^^`XuelzARg)q$1zQB;r^c*w>` zU#noaNGhA8ZY;^r-KS%Ky+`xFee4F9geg4gynh#4* zS3V4-=t8>4rWQuxj;Em(9pavss-?cDm*d1Y<3T~<>kMC#`8JO_F3xbZKR=X@W;R-* zKHt|tBG6@a)R(-deK!50@%|`(&XzKdy=*$~KxdqEA}xQ{;YUySkn(R5)Wn)GN^Xu1 z+2pcNolOlfyyn`{Derr-sAGY2a9&^X&)penCBGQOFVdHU6)B+(UJ#>T3U#_$ezx>z zifBLE2T5gxMEq1=a;8{*HC)t>V!z-Pwsc7K#$?ZbEdbveR*vXb_FPXI*)iJBi;kqPDx)UX6Y zjKGN&bX$-7+S=N|5`iu}Phw_`wJp7J@FT0=T|R?Igb(l`rGM^I3%oYOIK9}Go{hZ3 zx-OOpbm93IrMujc1|8vGgW8kJn_?N*nSK>YRtR zZ!u2Wy-Oz0CFlIQ?@#6ayOrAe+ij(sW1f2S_9PzX+cCFTLrcF<*gNI!lN60D^`odD zvF&jKV)6U^N{ohA`l@vOyh$s~T1y1FroL=RVvmF{t+XM=`Pi4rtv0*0)tlQ;RFLpA zZ$Q$-oA4v!n{e5t9~H-Ynl{71Ms`cf0mj+5N$a=PBwU5$K9>ZB8sd%wfugDI!Ml&hjp}Md=}bO72wNzz!83t2CWViAU}_)_mJoW$e?Mq?+gpzhUePpENRCiMU^z7k*Kk zqJqSZuavBKpTfq68v3aZJiVs8N~*!Trwy1End zeqv4;GxX5UNy=8V`wo2O_KFgLE;;A>6S9@Hr|NTE!@^R|F;63(DP&txDzl6>j2kQ& zb6rWR+n67(T!^BAM5jkJh?^K=>0%sXIqZF3nOfL|^9Ok)0$u-fQi!!#2CFh~q=>O8 z<)M<+t{Kl*@kY7cjF1e!?d75cl$Pr6+?z`oRU>bUU@JuE0HNJO?# z2=mWiQ(X-CxDk0@8GoS(uie*5BG4u0JU8DXrF_@s-15*1Dd(8Nq7U_Cd%K;iyo+I6 z?cSN&%8t=3d6Qnx6jYG7W#&k#i809D#xcnJpB^g@AA9o24Q@&Vy83k1lVx@GFx$%m zMGU`g&lQ)#ZTZlldz7@MZlvBF&Md0;QG!RgkqNgn)~$74WmwhfWULrP&SM-!_UW6W zkb|xHzBc6Z z1&R7i^yJdZJ?vFkLp~m*JyEW8_vTkVUXloO$vJ=c@wrlYZ(Ck})eb4=nA|-4 z8s{3^Souy#J=lTw9x+E!knr|$CGTe+WD$|wM2yC*o++za1oEJyWfFldOrhwrto}xE zdhE}=?N=(OAhEWyD_KzGAUkCo)lZ!NTDdvEpF75{k_dFkIX{u`Q3>i4#KZfJmvWA| zeO06hx%TQ9Yu2oz$j6+dS4y*#j=b*IQ3@(Z9JQ`WdW)4|UyUony7l{_l-?7}BbJ6r z1iE@Xav|4KjLg3p?XMuM z(*@gqQ+m5~>7p}Pf9f=gyV6>*x2ZzJ zWiC6DEk{qYM$cM{RBe9#NeNriiJ!ACBN6Dr64B}G`sFGo0z!DXm*u6hLZY3!3rTZ5 z#S%*zX74n){zG|CJcLi$SxX|&h2i4{ zm^R~^Qnqmzf9HLdpn}AyjSl3CnB7*yIJ<57esg+X%%HpXb*n_6Yfw99k~Qrtn=7sh zoi4L>9(wD32rp*4nxKLNE$>VwmpsR=>}f8D3XOg$Bg4Y@+0+#T6(q)YcOVVLjJ+{p z#-3PdQQm?cJrTmsKJOzD=$iDyiM$(nj&+VV%!m7;SW%0w9eJk{Pxb_@b0Y3f&#_Ko z?PHs5PUQ9bbL{ZECQ9j|4#cnyGM{lB|J0u@B1|iWqelSkbckMJ@WRkwl;iuO6MwY>PF$A?Ae#H<>Ku z98;Kh!HML3e1;X&R}nE>&zaM7r%)a?bs0kiiKqb%q@P${%Z=-63tq9NkvD>P*t1ND zK-ZaTPNceahVAO$AYzQzZB6}l2XfnjKN+qdpXTpOs)U_lV=9;ZpVj2&4_Z?-Cy*yD ze8X^^ITEv*Ig@egPchs4pZ(NIC+pO;n0OtE^v*0_4$P-|;?`&tJ+Pb(u4=yKlULLN;#!iFxg z6){?6SW)d>0DsojNoytA26@NrWAnRzB}rzkWZCZhEMa&q=~1{E87J0eWEj_GB%HUR zsiivbc8lt1s34IoR&fRA9%3`gTZ@ouM++Fd&@T3;T{U{>9mdY`gVjI8%4;F);rmuujfhKFOFoeSo3qpxaOzXNGlq) z)1O~x)>=aaiI@I_G*)-A8%r;W7{`ZN(P5XeG(&9rJWM1(!?sdt+v#Anm;do zwY;`A%#%!gy@DOR(w>l7o@8jBl`Ly;5UKN`0kIY9)mj_ZtM!Ysr6b1r^RK<_HB^wW z+1-*{oe|Hf)G_QzTe-F+-7+MQ7mKPP5$KXrb?lQ3{o2T%Up23zp&}7ITaaq^64_x( z!>X<9oijmS>1sxij6s_{oFJG!E90DtM8S0d0=__P<|KRw_gWtHak?jj!cn>=tkO*|)c@i@RJnd*|d>}s%m{0WU_>xG+`K;IA z{Q8CyeaUJvpH(9EdR*x*`pDYb(ZMqU`LLt*3>74Hy7-a~r{}ZlcHKm(rVqBF;bS`T zCHed$0$o^!;tWRF(dVTDdDkn$rLsc8?12wyJ2{rcFJCHRoD}C{_3IA2&-iH)fi65Z zqQ9ii1EqMOUcCGCl`8JyfIBbX{sUrU^z$p_pjCGscJrZ%3KCc%I$cAn=Ss$@?z}|f zb_@x0UE5QERC<)a%-R}uj48e3lkzaS3qR6&976>OxvUc1pDVUD-Fc@yYcH)K1c+*25c)w-ssjapQxJR zj=JgkN%?jvjQf={*HA$M?=(@jKYFH2ck9Y~Jt-v-=(-YAmOS&`z}DCVix?ljd{8!i z@5KA;si2{P1lD$9Kbil-)p^I|{DuGjmc3F$_7);hA$q^h+lY*;GD3r>gj6&rWsi@& z_sWX0_qfkFRtaU5lARqQd-FZ-`}_TQyw2~x&*SrYJzcH)zTek%uIpT_@`-!AAKy9K zK_buF>@Gfi8TO5c_XGpCUe;$8pOJNk+UQ z18>!k@5?CuAdR&58pC}){WPM21pZBnQ-B|7@TkFi{DP$mER%$ z673&nk%f+@SviVd@C3O>Nb2EeZ4Zh0GA|t(m zc!TCQDJn?dt3ceXyE=`yx(4&4ab^q&bnX39RJGlaM2mE=6ERx0$s)st1@hZh%P>@s zz*m8I7oBmDRCXK1!5dnNdgC-0WB=A)rI!tp? z$co?~K5)5m(0+*7r3ps)c^6&y}YlqC@WFcGABfoZkrul?ZelIh&(I*4j-i;&zHx)WM$z zNQM7Gx&5;x6cr@!l_t9M_G~9ttA_I{32736t~D#OmE9MTX|`1n@f&QCd4SZ|I*wPE z{D7i@1io&>>%8T5l2ks7cX(8aA%QO6a<`OA?)&MgeJwo-&;9y?1G{1?cbhYn?^Ac3zmG4Ko?dM42Em{t|~1TjG*6VP0{d{z3kl{PFB?-jbA%1 zC*5A(ae0&zVSHRy?*z*6(3kl5ta$7w~K-Nr`0b)t2iyISK=8P=^|oJ64Og5i!!v{Q~z3Db#HJkyL8zpvkIIJk70vM0rZ zoeqo9P(k9yp>9r>x0=yMzjR{vnl9>sw-L;;^F)b2SKgu9F7=vLqn{h-#I>g9mBqDY zu+bx;HB^w;;oHS&e9vn1S0|lV64XIW=)RmeJ&uqFbh+o}xLC&7(;{wq*JS%ds!Wbs zFJ^@&Xs96JUAmLg^{w`_Mu1LqNo%iKzDi;vONC1Wx>}UUad{EZh32~H-MG=Ojw@#O z53%kUp&BYk*c~QL`!{x>e@E)X5$o3Kf~RNM{@r6G0$ujj*)HXZ4W+Fc>)p7wx*Spx z4qsx!UB+mrAkoy@#c8YkP#W4ZY!%I!q!ZMlzPkR0H9vN?mqef|Y1(xc>%h(Q;U>K+ zEPQf;a(!zJp3GD7`Ho_`H=wpzG(4bQkvG1Rb|o zp9cKdeuq-Jl?$J?u!V*S64#d3b+W5?lBS=~iNdEg>e1AWeDPNsi9i>9c*SK(xH#2M z(>rTCm+n#ymg>Uy4Q-&If}2 z>JtUgYw8}c3$-`@*wb1=1&Q)csyUt9ev#hmr4u8!w@}OV@6TthF_#E*wYzi4CE<1k z?c=O>yxFEMneUO3-hZunOj|@ug2&^%^wbG&(+>MYHSgSK-a9#X)Xmj zGwDPdea1bj*->STiywdH`-7l@#NgJIoX)+>q^*YN#HAi>)xUp7@HU5DNCdjpHcoSy zf9p1_@oJPH){j1^yzma>^-De^s34K|u!7T*TDkOMtzbb!4RKND#E<4d71JdGU1!2C zx(xEaPZQ_rT^7MTsZwIuSiZ^qJV6DCvGdD0H9UBqS{Zes^f#ieDjUYL`yP-8bUn*T zbxCy3qnk_WcMfFkIHN>lhVws56A3Cvm^qhrI+Tz{SGU)RE5$phrFTT|q+2T_0$nZp zrMlc(^^{H>tKUpq)GxvSd9CYGPA*+C-E z)n;Xi%gdqp)a|#sAe`Q(Dp@rr^Svcn5>$|AIQNg^h_m@L(@yVBNFU^;u6KyzH@BNh z1iG@kQ(O|ByrQoi^fP)_eo={k7sm&l_@knN#IgLZj_Z28ro;VpLVMz-rYwo)-ObNP z1iHQ{DK3YezNT-7>8HqxN~I~2YE0qN0=KECATglVd&fkNH`H;lPOQD;rdmv$!q=a# zBN6DD?waCKW8xdC9BM6yUK1`V>z+^HTN?W)s30-7`cubcZ{E-s_jST7x~popU<&X5 zrW{2AU0-*mxa=DCnocZXD~RlwDaxqXQ+PYG0E!9{1Kwpj-phSW1MGF8@<3O$;Jxo>Nqi=zQgp8?=6~g2h zEF>`Z5hsfCGSpMYMo^_syfn3iuDgAPC>E6?j8)h&@qN_wFp$d5d+1opI1Lpf;$93^ zoFjJ`Z%@*R?3o#AT;;1YJ1|Z|1qsZr#KgMCUv)*t(roLVScyPa>wv+^8cFgHOk5s33v)mBG;Bv6u`CC9K1uNfLpss+YZ#;HGBuNt~XsES;XF#=q># zN_bDwP(cFoE79r1zNpK;g|n?$Q4)c!R@Pq1mUC5U?~8iIGV%L)HSG5^wkIG;Lj?)U zuf$CC_(Iic^HMf-#RQ2!*Zf|Cl)>ffY3%|%W4XJRsZ(6nu^aEkYp5WB`IVSBT$ry8 zvfs_(b3-KpUEbpcD)oN4(rbl!#p0Rk2J**~7Ph;V+qcv2J!2C)~1G2m7(WlwW`m~tsgMSNMu2KCJ zujQdMf4QDV?XR;>O)CA6wGIlajQrlFkX%_rSe-8~6 zBrv}+7|wOOtd`zt%_EMuO9Z+mJnN$@EWMf5^VGAVV)GKzbE9kU_%S^+RFJ^@%3w$s zaY;2*0O8XCqbk2BFR@5m$jUYC>cS1)E6(lgfG8l|zm(?4c?Rd!9 z_7Z`v*|T~n2S*>E{l@EAQ5~nP>f_rj`L&;IHB^wm{7OvGRZmy9?`q4FrnQs^bS?FD zSBeIop!+=atms&e?P`mvE=WXf8Plh*=2y}Jo+*29ygwwb7 zdRFvkXremuwJXn6>T9SVf%%n~S9_YN^4dLl*#*@k0$q-6dngXqQ)#tn`h-IN8p*1A zm)<;}dKC>7Brv}cllL!ftDQ^q=ldR&lL&NeP`fK;jWcMYP2)w3jL!R2^~XT|zEf!p z6(lgf5}h0_4^-dA-n>M=zXS<%<#=^dYCpb73+9K27{68>R`2Ec@(Z`V5>$}D{7Sse zS3FS*gGTUEHcur2U3ccWDeZsf(8GQ7JgRoiadpy&qBcP#+N^xieR5)DGt%+75yW5}03!zmh8N)qM*maC&;FM4(GM(nU#|{e)J_ z);q9Y+MZL@evzD2nnzGU0`n_TNp15X_PxeQ1iChN@1j&~_?#YX;vr&Kgh-+Iy!`ENDk?}|ekCf9 z_rIyV%E$3X2Tn)?y3TKQRZ`Z!qFb{&h!_v1TvYFw#q+4xO)4r#V16ZP8DGAs7<~71ZGPjA6)lUUGgc8`}L_rkw8~` z=`KpmFZs0If~F!y#XTwNvk~#UM&u}p3KEztiJpnNpH=T~llh;?7bF5*_0M)u=0v=p zvp&}nF+NQ>ujaRivxln!bc@l4Mq@6^di&%G4BElcirGHC^7*!Iux~EzUUoyd! zp@IbFSE2%0pQ~o?Ci2q1he!mvYL`oQIT4>tvs&qSR75*X&8j?!&z%;;P(eb@yvBcL z%Aoj(T>TRv5$Kwe9_2VJ=?d*q^oWR|tQ|@gXS*81O2lZmGYapukoQL&P&<=S)eale z)mRM`B=C+4@!p=YnXP9m7w=zFFE`m^EVemby2V4v z8l@XHT38s!(zI5zJ(q9TKmxNqG5PYyf&9%|O1lQdN;hnvOa7{UesCbK&Rn5xDKQ!< zNMN2QKBIc~B(Xt-NKdF;4%^UoLM&tQuEiVGfftRFJ?tQJi2M z=|)mXduH4lB@yVle=9**xU2}R`$*5#R^MzvdcAjN$9_g>s33uPqQOvb-j!5eF_u|2 zi;xI(t?rYcY^Yk5?zYooj5jnRAL~zHbJ|2`s33uPqWC_ZX~bjcBIarnE)nSJbYhDV z+^+?-^wRUe6(lfE6jkTB?MWBIPBwpAh(w?()nbd%wv{W58>Z)j z^$ye{^Iz{{#4bcb1qsX(#VJ6^*5tDVWqFH(B?4W;hiq2bB@L!+-Sm8LPHs(N^*n_& z%^annf&^xL;%9Zpo?QBp$u8X)DG}(Jv1*fIxo;dDQ%=tZcXbxqzP8_LB&7{Z8GeyjnGldLGbEu-u)j$mePwSs%q$Lj?)U6AgwR7i>t= zr3Su3WOqoQE3aUKvUI_GTGvs}2dliWAZ-s9aL+S6Bm!MCnyy#u z!^8%cTly^p8|#)QCErx%Q%`o&P(cFoL~;Msow_8(qCU?n+esqO)!lWS(yeG}>7r&^2uMS|w-Se%ki)G!diQwDKfz zRZE`puC;~=5|}57Pv>*>Nj3krd~SiAM4-!J<{Bk?m6$Bvqu)rXwW&ZVJZ#U4bZMrc zf&}J?2E#YcM&!l7j(p0N`VxVz$@^C;|9xe&x}!c7Up&>44BqX^lP}fLP(cFoL~%FO z!6szd=^lLltSS!B-f4%gLAb~Fb zDJvD<^*89$`C~;4U%Q%QRBc~A-t7ZH1qsX(#cB8xC*sxHpNFlzFA?ZUf4V{`xhk7Z z>JublJkF{^qVh&^^;|Jz`Hy2-Mir;#w@J? zX?S=vKRNLojl%K#IWgVL)?~!@3QG86=K!OSqm?w%ZB!esY)hn7? zq_vU=bh&+5rj&GgPJ71o6fvrJG$&afC-UkQ8WB{Gz&ugRD7tqcd&LuSLOU~wK-cXn z%anJkU(n?zyNDR;I@*!tD`NPfyw@r!NMN2Q?kXf-?Uss1qsX(#l(82uB3O#SYD^7K_bv)dvckQfBPjZF~~{8xU|iV zBzBw3FVrfjpn?Qued3%ms0*<-#PW?|YbO%uI$^e4xv~BQH9y-##CRCpoY*~!<*kQ@ zQB;t?JW*`C-O`y1DIdcvpQK6zx;idcuF%rY=m2Lu9~^hgmTWM_@DJNwQdE$@tWV7R ztnNq-CQsz)9+emp=+gSFP+kS)(VFKhMT|cAO-OX-NqlqhdJGjLFi#Yx$mtsC?HJ9k zEp(O$bVazYRBC*@M;(3je6U$$V>0$~G&k$gnW2IN=82+e@WqBaN{r%$kiimxu3sTN zl}TT-=))zCM6PDJ=&hQ$Bbqym2xO=rfq9}hiCZG7Q4^y%DIOsa=(=oq-DO#$D>Ui$ zVG*O@>JDm(<3zr?Q4~W32|0s2<9tr3a&sc*D?%j#T@#OVa;%kphOV48Tf~T6yM!zV z8E9;~C{n}C#<;&&-f}!RX(p-tWENVOM4-zp`If?)S<_vE^vtWzq6s82C7MmY9;Ts!1ZI8W zv~SxC(y8e@c6MQiM4-zfFH0%j%Z|p*HJ!u_4+O=3}Aqcv2Jz^qT4rQVxJjMGmr_l1EHfv)l9 znMz)q7u`8i&%DkUhLOTYXIbrbff_1EVAf|a_BIP2JzPTt3C#LLO~1()vODX!_zikX1iIRNx~?=Ym`d3*p#1m)HHMctw(PS6(lh0GZ?Cd z`jRt$D)VRe+#~{BWuh~b!|OKEqc(bW*L78Q@~nP!UZqM`4HYCX>l3>NYl3fRXMyBL-5&f|jfxV1uJ#u%Dq9C#pyli8cWk+dyLJBb?#1JxD`==7 zfmxq;ZvQxjWUlhy4=Waz2z2$&NL3mIT&ADfg^3t+u@{-Yd;p*5Wu~Em1m~vmf=KhdQm^whj80`~E_Ff9( z6-_k+fX9Vl|1X5(kbEzjc(RM#Hcngf@E!s}zGeboM3C#LLpZ?-GWW}W@UL)v&f&{w8JDyWo z9(+b$HPLUmv3VRtW{jW69a`DDpn?SEaALB!#T+s&If~C7+ma%IE}NC-lwqDvY5tDJ zA_iL&Ny17_D>5X|HNoS8vi;kA$}%iOjIw{j$nC|EylI!Z z3>73W>k}3Flo{k;?FoF%`8E=Pt`Z3;%D#!Yv`t)b5u;rBP*S921P}J<$WTE7vp(?- zH)tH$SA7Bxemqbj&{Zd6welw9COtCip~#9Jtt2GkTLf?KJd&Y;1ZI7rzB{Hd8P+C} zf6WY+2y~5@&_~&|<`VT7tY>#mb`+{>&PMTOMK6yWhPu?QtYvJEQSD|ONOUkIz z^i>%@5o5FcWo6ys7+xi`FGB^1tZhvk_r5z#e-oYHoqMW^T`XVWs7VC6X4~9$8CdT) z-BhKOAT|w1S7zqM^0IeZGgOfHInUhDZ`W~Jv4c+ZHt(gn&zQ`MO{gmo=$d{Y*JbvK z!*ujxGeLYhpP^K0701KPD>GD(_;ux_gL{o5G^R*VK@4orTWyve$L~jerAVM_*!?>$ zYn~pU?O*H?6S=FWTve)u#PeR4?@?5cc<6t`A$#;enrWfm6ymtLx7zMrJh!vjCK2cw zu>P*g>Q?({j)%1%dhWTZTpu=t|NSKJw!TH4lzdE z57mCwDj|M)qNde-37I-QUwj4PNvFzEvgJ>4b&}YE(bHMaoo}^BB>Bk~jrLE%HB^wm z`h)oQDjpy&500npUxrEqy5biUS2GMdjCF75xpS*(+sXaHJ#@pIa19kCu>N2$EWWaz zoU8nsUh*0z5$HPEzPS3-@20U{s2;<&$u{DiRe`Pi9;%^&1lAwKOheXQlE1Dw8~<#q zM4)S2ZZWk<&|l*m({7HjFSiiyk{S!>F-}7T39LUD3@_4>NV!Kt*v9f>Bm!MsgNv!} ze^sVUyXrN7kW(AUr9UBTakH@+Do9}cL3HDO*-7q1&tx?(jFJd+J%3eHZEI*wTTjtz z088JjB|DlfV!11VHB^wm`h)0*-?x<<3|!CZdUbXocpRZkq~NDr;jYXCj3tRzm( zJD68kpoR((Sbq>dt9F}6vt@_azG?mvfv&5mW~#%Vfz)DwUIVzfaw+kgXk_m;`D>^k zf%OORd7izNFssY#L^ofFK$k}YGu1g~3_a$npYWcXyO2zIoylgE_SH~90_zW=dY-zH z^uC(Mnzb1$5$LKDRYVQ8no6C`^*Y1dNB@ztk*`_tO6(q3!Abz?t7L$(`O7XNN?h=8n*ToHL ze&}+#!A!3+*v^|teEOH?%U|@+P(cFg4`Nf(mW5=0k`?zibCn2mJy`Tdv7EPodbsHw zzx8U&AR|jxks0+eg6WIJ-9Ca!`n*)x_VmtR<^X-L0^s1JAOMan@+r^ zH{@SGJ8P&Qf%OMbjXJV`Jl)oeTZgoi2z0Gl`BV8lWG@{sO7HkB{5YLF{?DH0M6}RQ zK?3U!;)V^eP4{r0HvF+|BZ)wlQ^Oxh?$0Ci-Xgu@cW3LFWXAh;Jj}9zh6)l`e-J(N zGZ&Nb&K zgYy@K3`(O;*_Bq3K}7?3 zv9`MiDo9}cL7bB1Cy;uJf_O^oGKoM}>(CF%hM-*9s*iqm^!&8dq~f<=aVN(@f(jB? ze-N8{7j7pP*l6xqYP>|C>*}TV%AAJxsMC2*5rfuVNA6V$;gMfP5mb=C`h&qx^x{r3 z+BSq&ck3t-=*sT=UTM_l0i9{nTf`_{W&_z563S=yawe!Cf%OORoiEr$e!UvU*H~4O z2z2$lU#Q%A`;cCY>n38now<>uhz{(UZOaf;kicq!c*?lDo5a=#<9j`>sYsx!?5aW~ zu52E)&FCaz*e}{dHg+5@w&YP26(q3!Ah!0LNFuhk!nogp$r6FC2_c2b#l3kn#99?G z8noI>?i7sYA8m)Is33vW1kp+EmQ0M!;e5}HPz4Ee^^Yu6*6z%sUOQWf7#1@(lc0_h z`1y>rr%^!ys|jLGxK=W$`6Z0IH1A50K-c}Zh02%OkLU&$8xcb-+(g1t$MZ=QXH!&= zz-of1u+&N-Yb%9`KJKd$fvz%{@0G(|_i5RO)kTbmvm41<7S3M>y`iWefz zr&noP%LgI{`u=S?$u|@CEj=B^P(cFg58|DnNGMr)Fr2%3j*|#}GN|}ontDP@z^~R|m_F8#jC&Z%+a0JVeN{-jh}@=BD4$H57S+G=Bf*Yj(yUlM zv&S@vKo|bh#kq(y9iROhxYD$0YNHl-AMR`?th&IWv7cpkHXhqgEpUB%Za*zmg;j3AEo-gZ8dT);6 z{in5;UbRTfnYLM}-R?Lo8sZ~jEa_!Wn*503wmaP=0$up7B%Wk?xsl9ik^JZr59!?p ziOPRBDyyp*>F=OfB1ZTBT!~Lg1i!u7Un0TGAzpuCHb;V$}P^$+gm=Uvx+< zi9i=VONe{bnx~WEg+Y8y4@>DO1Br%XE2u52-KOKZR1+~a4?0VV+m7M4qTWhRGU&pm zC~=Q)cm`=wB$&@#dsBK^LL&Kzxq89uE`2$pp@>mDH3!m-8L~gsQ zX?)|;zU=snu%=*7$vBq(GWr?u-$EBYql!=GuNmZx?`Yoo z{sD zV#0oN)pq$kI{2DC+jqU(SyHC^SpIwCMu|Wd<_zLg=F%1N--BSjX;`w9O&~Gmj=9<< z@h%-0(N)B#wT+W2)5h?XS#Ko*U6?J2zg_do#Jp-S_nYxcMFoi_RV%1p)I0QEMRyUS z^+`&8cN)!azpO9iQRu>~Pu%Kw^CB5{JBY7NX)0xRNSqy2LACC4n||J@_Xvl2o)+)z zqjWYBtlK5F$ki9i=t6T}To zqZrv#br|o`c#~8$Kw`}m3-zJZH9GyP-h2LW-$6o$iJ5A%qY{BGtcr+x?zW#I8&Zez zRmmr$>IV|X0xi|Vw97QdLGPg-Z?=!rsW+H=mb)$y=)&rbc=x$^jGP}akT<-UDOGWh zcwMogYLS~lw{+KM0sKcMkuhl=+-vA-i9i?DoJ8f$<}mTN+lObgeQKEa>`BBH@@`xM-uRoNM4$_+(c+AL zQ4*-nyS`} zr(Hkjrx}yjZlb<=#&(bDFA?a%(;6{^6Uw@Z{ZtpLh${=xIMs@XCelWe)UO$y- zTW23Bwj+Zb-z%TvpbJl(MCZWbQ{<-8d1gOtuyneFM3rte)LnK1XemGabg4`JA#&;T zQTF<$k3^sgPtQaLo%rMo@=Rv&0Y1_x84^YR)==mF)@YKSeoFS})^QRva1)z8Zn#9C z3r_*X4Vdf#Y2IK38x%H7I_*QEWMWPA?^s*5>H7j^~*vldi#eSqw=3KWJD2v7STOWBG84WvZ6x&EQ5r+>CKGm zM@px!NE}Y7rB1*5%h=V_9o=NZ1=7y1HB0&#BoXMs(`8ZRbh|+!CN*GYr30l?WF(T> z*H(|Wyl%W&Nk8FrYj}~I8(W&K_Y9T@bm1wv=xz(kBm;VWpr4utNvGjR6xmo?HE+Ak z*e_gz?Xf=jFx)+I%vul)KvC z(OhG_e)EaEkN(7k;#!j*tLUEzgEdr;7!}f1-O#Us(Ol8bo&Ab_A*;ny{M|o(5`nIf zHg(jB@s`GCIr{f;WX1A@n#h~FDDoFGk=O8jJG3RtdkFjIfb8=$G0^@=?BP9Y| z?jChagwNTl`;twf!{?N>Z086M3y#>Gek-bs%Y1hKcTi1?eI9?9oh zuc4?Qfw#?z-Q<_!$*QGMJkKEZ@N5N^NGXQ3H-z{YlaFEc-y>qr*1fzTy~A%a~rmh2y|fuL1e;J z=8=nTg%t!*VYyL2+*bK=R=YVv1qs|ACvLwe_k<)g_2>8RRF?>J zVFf|-Qx|(jsMrkDXF&yq3KF=HPvnDLo{|O4NAMaA3Mmrk!U}@^RTYviGl%irx!DvI zBycaG=r5`8j2sc01n#A;l?ZfU1wq_R6;MdrVutgz)h1I^kibokqI2NxQ*j5xNPeXC z1tSvZ!U}@Hux!dZa<79wx5}$xLxbYTTS^vM)^OCo0b z^DCb}E2toW`$xqLR@=v9jBNm4J3LH90$o@^5ck6kd_xMR`}5>F(^XWEz>TFM#^6V! z*v*mL%hVgO^?FlMK$Qy_g z_vDb)R>S#%S0f|>U06X7PXG~*$kO$`+$L=lK?MnUzjNI;nPL{emzP*PPa@ET6$Ekq z5q^&ti+l5u)fW;}kiebQqL%UE8u2PMlw134mk4xW1wmxn9d45qv0i*o)kJ~{61cfr zY%{+hs%p~)@{;ykBG82u1kqVzl|>F`dh(04&k7Cu3H|_gHBG82u1aT9>(R6bAP*>h&%Xfkb z5@7{R)oCY>)BG^KL#S4#v&4UWN4_hgl!gSlu!107AKxyK=*EOMiz}m{f`s>TTh*oE zLF)HazuRzB6;5oMI`cu_D@z2ru!11Ywp*u>g#(;;@-}M?6(lC*H&YuI?51~#-m&%b z2POSh+3~ew>PrN=u!10Npjmy9-1KeAjXxV`s31}6V{_G})>gW|uHJcOUz(91ajVMe z7j_bXF03Gk9>|tyBq*vDcXhMZP(dQ{ubujht)-d2^m<9E8z;?fRpyu4IZFh(u!10R z=bx8IaJ~g!+N+(03KILv*sHA`EusAn>C=FIyU&s>ElcxgmyQyFF03GkZo}8?KJF$F=)wwuIGebCo!I>@V6U2W*HA&C zLxooA)8nyp^-jHBQgPfRGN8jl7UI}PBG82u1kwGu;}+@KF^jz`*+)YK2{$tbbu48xPV@K_Zwss^1NSw)$k6$o0r2p)RXfukJ%7 z0$o@^5Pcbr&&lYc^I28nU=0-{PEK=Dm#%C=2c+sX8H+U!$l~BBZ0al@i9i=t5DbO^ z6JC>gL&h+>6+<;tkZ9@HT0QlsB3%%z*JS1neL}95@6USL`bh-3u!10N%@)szC0sf( zkLTVRDoC8Y-de4k_uV+Tv|caq?(~9WIoYyqfx{#MU06Xd7)tc|L=JT+&%9guYN#NA znZBqeE_p>xN4}w+TZT&ny0GS8FiigXiX@!eP910ZYp5WBnZB63Ps$|4)5p`d>qbcg zy5w5M<#TCdbhB)uf6y3dLIH`fDWy#{fZW>p6omI^Bk}Au!RS$BoJ61t=P3+^<>!m@ zm7mtpsp1~5O7D8oN3P3^wBvj-CA|&pRwuz&B6|Vx3u#L?{i}Y=RKKv8IXkIWte=Jo z5(OJ-Q;UC9oVL4Ou>*4^(KCPiB?4XjZ0b;}fAx}aw=>zMcg`}hdi@aN*LPKn;~(oczV}aU!${*p#+=Mp4HYErI&L$Tu&QGGNOa=e3J12L zk`wj%{|IzN_a0)j6nEWQo9?>*__rs!v}PH-=n$i!g2epft;SGsjA6L+_r}zmHA5my;&3)~4^HOPl4SY3sYEXGK^W%XL{Uh@D9f>5OrEj3a{M zHB^wm?@v?*t7g!C_gm56i86t%dN1#s&il9fY*{k{+qrZk-M2DMLj?)^{zQyDDeU6d z#w;j!l(wpUar)x_W@1*iuT4+=U)8Z!ZZX>I-y91YdYv_2?Z7t83(!zOVoORbI{RN; zv{cABwsw~%>yRBN5$I|ZT#SDDH^&m2l+F&-@nx@mkI+y-B9qjj-~QEid$}{#t=Uwz zm8HuKg{L83&r8g$>kbAyGC_OtKvQdkFvp%Q^Erv_%UqnKkkVVYxU zQ|%-hXn%#Z{WVBK1&J*)s?%I?{_((c{_)KtnU&stpOJ0@B?4VVqKeQ^F~{O!nq!$4 zcZ8+ye8Os^duXU2vHWl~+Ebk4bT^&j?DR@x1;xHFI-svapzEf%=cS{VW9ej?V@X?Z zfLV_I#hy-f*HA&?U2avHAI~V;i)(~?n15I-*jseN6 z>xU}*y{)35g2Xf{Yicjf2Xjs5gRS>&VOz%4;fa&lN(8#BEPfl4#T?5!(;Q3PfF#x+ zzdnz!anMjfg0-kZzl(FuS*CMN^J!by+yYzfaJRWcpv!ONPh+W}d+A`)9LwNoNzA-! z3;witV+|D~diAVK6>(ncVLGq9Chn_=KGvEq?^I7B(DkRm591>-$MV=T$I|FfGP{4x zncIGT1i>KoeR>sMLpSO5U zP(k8;#fr3?=x5kw>SwUqw1+*gAH>I2&XovsRj>ZpxJ1mcRQJ*6STf!mXURTZ+#%sI zK?R9jftGZK=*zfc>dW}#c7TOn^X5l#s6?Rao%JW<0Wrt2)HKK9Ydp<<1^DonEB6yr zkeGMHf<6%aC9_TaB>{Pd*_mO(xqYo|5`nIJjvtMFVvZ%*G{<5d###Qz;e1-Rl>`+e zVmevS?xIiTkEu`QCOOVhe~sje#LcWopsPga2jdzs$Kqs~W2tfP9P^wsl27;+O;ACi zX?g`ZU-bJpnEHJlkyGsAnIImKG)yAUwfWL}<1{hH($+M`QvGQP8*x66^Yd;56(o*~ zsz5D7-_kcz-%^q5Mz-!!Fi#F>B@yUK?EKzXTgg@ z0(~p`uO6EEuVP;?ra6t_cb^xN2z1rHUue88=2$M7=2(6%xXgx62o<@VR47 z?L{A%m#L4e=Cm^`pw?LKv+I~dpzFcPLSu}WV`*-hWBF1io!zk-&67JUQBgr6aKAaV z5&dvOP5p3oo6oXAo5%9*%tIp3)h(pZm@4L2LjQM;#W{odiM~GbyX93>kjPqPPW8UN zk*2=BfZ^xZugtNWOt|8L1iG3>78=)!IhG-&IhL4mSJ}PZqq%Ftl}1#MsK4HvRu%n; zj;8*^(euu+wt z%h#qp%i!Z@nbp)W{O9?b5`nI#H{Tl*#T<*dX^!Q&SqAgoK8h#bDx|0&QFUwuT3_^w zhMW3DZ-<^?Ge(Z)H9aaaB+zAB{i88O%&}B5&9S5(zrrRj2;ym7YB5xhDACe_nu)&G zji$a=v6_=PcMj%-p$-y(uJqHNjOYH%v6#)c%x+H(~M#egc(>}*L z{t|(%8Tr4BTf}B-_viX%>&$Lfn3FhNIwtm1qk=@|q$;$!*e;)I+Acr!*jct*?85FR zc3~rdF1K|>=-+=k?{i;XWn65qUne%$qk_cP>}qte(?05HGhKXDmJL(bf)+vic0nhJ zKv()*Gurs=J{s&iL=YGD-e51^jpRL!J2O;}xHhN;ec63C-BsF45V1c}+3O!ce8**5 zi9pxRKSgPy9Z9rU2RlKW9GS_i&js+S=W8=mkO(|dlfE+SpnYaE6U3ulX{>VLC|;*o zd5J(*olnJR`?{iYz|0_snD{LA>S!R(oAsBXg2aD!YSE!n6X@^Y-=fzb?nfFkdmGFj zKfWaq=nB|hobHX^P8G4US4?LXWU;=xg7|dTlN1#svQE{eb)Rpd#rkX$#5=1??9G+Y zJfqG$i9pwoMkVOryIbjz;7Wp6laAW&UP!p z{qw!~w`&WHwS1jvLgiId?B=Um?L=E@(|Hw5F0rTX=jmpF#apM zQp1-|IsR56(A9Z{6Fm?lZhVhvD*krE4!mY1ZVuy{-WFr1Ac23!qB|kx3;Uw^@HcUl zB?4Vd3mj<416yg|*a0HOkKwOa);B+%^QIm{1qpmTiW8HRPi(|OZ>|)#mk4y#ZQhD5 z+LTDIuA3@iJdb1zCVgOb-TB0e+_RwB5aUEpv&faQyMjv(Ny;w5hFGukJW7E z$6w7K!caj1-{-|1_w#Sq*3v%Q5ZzlM(B)&@Up7kwx~5q- zq(#4H(>cj@B1W_CPubiFBY9%SXo?CF_&g_W(mDH%kxKqNq{dq#66mT}sUiJuO%AQ_ z$XUd&Cr??ZO#uJ+_3~*{kih3svEN|8TXuYwKOYjfRzU(?rCK(mPd#&}Rg8WIUCmNY z*k-o?-rz$86%{1#`C9a(X1rmBHU8YGiibp?Yl446+AJZP##p+F7{%lB*rx^o{NbZT zDk?}|o**XN_$yX^tUo_HbPhEsVZJD{t>EVmu%Fkc~Ywl3OOqllRjfvzu!HuT_(EA-(w zKM`YH&`ox1o)2%Gv5cUC1l9vYe|t0u{KR;WWhOF;=Epy@$Yk)6;1EY&D*3A zRFJ^>jF?L4af1a~_2vF?SrUP+oFYwWyt|3$Xd+>T#2uPYJgvi>N}K13(SQBxu$2*;DCK2cg`)fx_@U`@|sguJikg<1fYVmi=T4|^t zf%RnZ4mbD`b1zw$m$Ppp5$H-PV^3W~Cx@4*lVf3pGt6nWCBHDvqQO* zy*)fYLj?&uHxhS$K6$_*uP3ot6$VNKx<*h(`df5zIG8#)c4yyW6|e4KUpxnEs33vo zU*gufsZZHC@8zuRYcGjF*P&@nbcN{T=x^%eaCg1Sl20yT&&zvjs33voc;b`uQ9dix zFosq6F+?KJ)zq;yrT;oPa{V8%CNAOZYXx5o6(sOHQuGcUe#?iA z)&F&JTzUAEyp@IaStBUQXgFZ5U_ZsZYeIJQH7xo>9=S1^-c9L4M<7UG( zRFJ^)VUeFNdBq-y-j4v$`+)?yufeUV)&_)5`|;~+M~Gt@H{rTi4{AwWrBtZ5;MPN z8!g3dj%%jf9FF5+SbAX_R`iEVpv&`Cf^pHmJ&N1U&SmapyD+QM;TkGPRQ1g^4iRUz z|GS&x&$&qEQEU|RPm~FCRp^so-1u*g;;i4Z*r$e(Y~avP4HYDwB;7Ke`L~;6W_~E! z_HaJiaC@9Ypo<>gVjL~@C{{G>QS7{TIUz74A4+P!pc0;_$`@$R+M`$`JCqITpTl1G57SUVf|a^y%on>k&YE^}{4G0>J*xYXMPK)k2y{(L z-DrF(_9zZ8?NMa2f?1oOx6Jj$5DgV19(=rRY$bMcoH6a@sQtVzEC1~e%eyd0BG5Ie zV1sd`*rQnAv`5jp+eo(hlo{W@yuXGD5^Zi?GnN;-Io6wYb8LC#&Vrto;R(5YB?4W2 z%Wp7di#>|>OnVeRdk!OkT@KbVLZKVBRyf-&C$WUJM&pkk6*0QK_bwV z-Fcm{kJzI)-Lyy1wTch(HEYEGoORJqLE^D%y0M1X%@JtY%`w2eJF}SAoR{v^Mk3Jl zZrEDmeX&QeooSDvcGHKwd~MJDXSUK%L857uE5@#3H^*PoZjS%H_h1DT+wuu(nn?t@ z5@xJ1-Vu8g>zVc_j;J(@(Vp%3+)*|fDo8wkd&yW??B-}@+Rd?`uort#x+Ax?tSb@d zs<3~xQQxCj%d|)F&#n>dS4mesGrqcp3KHEi(~KX*ZjR@s-5fm&`mqr29z5`DC5b@S z+h?ncg<_B57SkR@|8}F;Ve?*m*{$*#DoDIey=dGlc5_rP?dB+0HjuS^=fN9aEFlr- zO0->Nv=e(2hnw~&rj80>MU?^k?`DIB3KAtUQjHD7ZjP^}-5i@&4Q0(Y4B-vWd>}}m z>sS0rqmS65IK#9@@!0e6>}rHJFXHf=pn}B57b(VLVmC)a({2v0{lnN{kKug%)EtRG zSMbvn#u8$WVytP8;_Q(VS>*%%yxWV*1QjH9RZB4z7rQxzn09mIt_onkD+KXlwnm9S z*OQ?ujGkhT;(OB`#VKpz*qZl2yyvm~1QjI0MqDuZiQOFIOuIP-S&U`}bH!Y(jn~B<#rXf-qu5{?`_*YIfBks{K?RA{sppNu#cmD@({7H3??c#zQ=xp$ve^=W zu9h>F8`H%e#Yv_;iU%9cU`G#!@-;6a2`Wg`>vZ1OSnTGAH0|a%(I}i9JU?F4$OcOU zy6QPDH=YuE6swx{C=N-T$<7TL&v(A)Oi)3>A?KViOYG*@W!lZrX7dE5m5JnsbDKy6 zy54?XW-KQ5DE2b#Q5;fqHcRLl!Iyej5mb;EHS3&F6}vemnRas=_KsxpcSi9d_dlsf zpljNdWyS)rM{%WTkK)n0v)P`tk^D;8Ybq*8>~ue8ED*anTur+*=k<*e zfv%Xt%Z&OS#fqjqicbd5`JbxJJglem{o|*|HptjXc3C4WG?ve&Qr2W?$PywHQi&F= zlRdJ_KB*{K%f5Wh^E{SP$TFA~J844pE$jH*r|Wmk_x=3my58?s=PIA&ocp=&_sv_* z2%!w2kiMuOF{{ftbrN3<-42HeRn@p*@OqD)uPOf3k#+ zniV3xG+)3_LE`0xbLx27%~4jdn9zWwADoSfzk_dEtU9nz0PJ0wRD)uNY$yv+? zj}8{CI=^73An|_4d37Z1=2%;?o8y;zb9gP|5aG3;9!COQ--mBdpVA&h^NKx+?(vJb zhcZuyaVB?4VNTocq5|LsvUj$O#z_63QQ zLI;it68TBl>XH9;b8H;#&sEyA@%hnci9px0yiMxs|2A!8d|trcQv&8iO29+~iLsw@ zRg3>JGaZZq_y$VATtf+%NT4h6`c}1s5->kiBw)5}xQM$_u9^eos-c3!vafmSQc7ZT ztw>@UGjT58MA>c5l--5|y59Wzr@HySe7LYjOL#HORKKB_YE+Pj>-m>@HS8qwS+$7H zyu3rg_^!ervGL0=i9nZ6><-nOa_%Zu z=^A5xkD}ADV3FRviA11lP?Z!loN@=(ROAl2`>x>ef6Wz{18Q`CyTq70ggU;!bp-YD8%Z-7C@- zE__rp|XxWO1T`CMb>mZMGASb3jidnc~rE-mIs1iGgEQ(&kY)r}bq(1_yt zuUX5DTeyi=kRBBz`nh_j<7#$e&0lK!KZ+h2*!tIdc!@`#M4;>Uss)D9c`mGIfJV5s zddlvWWb#Mz{q?9I(Uf+!w*KbKuD#KcLUMW>XLp~S;ojB#Bm!Mi>gOA3RUXfJwATo$ z=8xE}+#K#u`T+KPy+#~5ypQGPz2uJ%O_m6BRsMFC zxx18I*BBpcA|6&6t49S1OZ`aI*fgHiJE~0se(Al7{%SRaci!(3fv#Q|e;MYOZe%^Z zv>C;@4f0s^L3PBvvJrYzkXTlKgc^4`fgP!*5yM)iu)}8>i4|RjN(8#hW3C&TOy9vC zCTjDXam%bY-Er|c$)2Go=1C9ouRu#plieDJcB4b$pUt0 zv&ex5^H|Huy@k{3E_zguh@If7R+({^ci7a2EA9wbG-4guT-cbzHGvZ@OtjX@@;5&TfcUj7`^E~P{w&=u4!*RbO6 zLT2{dmx$u+PuSO;)5N8Bw{@r>Q5rWu?e(L89UZ0->kCh@b<_#?v)UzzKv!Boj=^Kf zJ(j-An~3q7pRx4avqbaZLWc?x#<%*bheGbMZ?C2hVYHsHGfM-6^SFZ&fv&;6(l^5xTx7nidoZqEiJUv^E?Yk2^C#d2TBCG_CLus zq&SzdOm!p?hfaQATbqQ5FS(vNRFF73&_!+7_8)eb zBo#krW!3|T=;`>Gb?O%>Iv0KDiwY9=xU>3a+B0UF+MkF;!*kg1qfw&OLW4x0t7GqM z!{H}o?3I@z5#L{aW{W+e#J>95`l5owr$lEpd)sriGv9%T?1&szvNc-#W7Ak7&~?Qr z+t4iR1?zLzj)=iIpIP-r(c+huUHYJc#Edj&^^{o|JJwAje3oBenaR=OUgEC|33QE5 z%{J`zDq~?)IuS9UWjTvH5+w$Ip2bi>BBz>*+T_zS)+W9q5s{m-Se=w8kvb+zBGC2Q zgbRjh&z`a(&niS%wGyoA>o9TS`#6a} z*UuVxhEvh`>{jO=dBuexb$r6FChTHBK{y9*d9NId>FPSti=BvA-@v6_y{p_{p4I&PG9LLuhhl_pHRJGH_ooWoFI-cJ#BE>f#UcGaC zA5$FildzgVx#t%hc@4V=VG>nWsv01H*Q1=GBd)xgd$`!tCq^RBg;f#y=A3TB&p1Vh zw$X`F^#cj~yHVcKTvxth_I$C-U7uIU%N%*HVKdTEDp@DCuDh?9(|4;YS+lTNO z{lkP=XdS6igf6U7QKCaNYd)>YeBo8gT&hMPfv;ogz^*@-yV0KNh__Y}fiA4JDaw%` zE1sDZDh{Ogma1w<;QNvC6JHMCjqeAG*Fi%h0$o@&q&tAAU3tr-5b;mF-=*px68O17 zlSpySd?IbAcu5;7@Mob5Ynim^Z(Aqc_y70&pn?Q`K2oAXKL=iqb_w~@E+Hh)g*91) zqIBBx$+Q=_^Q}2jwH68doTv1p1Ram0-ODz#dl`Qgy098ey_}yc`19Q%Vz1v=sp^ab zeqT|AWtN^#KN%uUzjl%cbYWGUDyd2b?%)t6a=QH{RnL*Y?_EW?RiECq9m9lu^Hvgp zF0A!amR?Fn{y@+-PP%*wfCSz@&|kMfKOV7__B$)jrIQA9;VB1wI|p~>?K(z?xWgBu z(+ni=K8Pw4pPcyy5iUA450MCT;n@qNKvlKmzqE=Jc59kRr!q+3{TzKJn)T|pbJmWXe;}2OMZ29 zgs?f9A)S&Tf%n&nGCjtH$E=($^utOd0$q5fM`^l`yYQkG;o_x{iF7`Q1U@HFZE37C zZ~t$ocrmz@M4$^#GpUArsxuEA7$%%**h#0BNZ|7hy{xu4@i5vhe{20ni9i>g%F-*b zawl$aGFUub<0GBEB7x6sG&j-Pfv-9jBnoRUln8X;=`!^vo^Q_wjtLU`eqAM0At>w4>#y7T~Dek{IDG}(x z(|(%GxYCN>E%6l@E3>3ieI&3RKu;4Tc6>X{%JiLfOCr#PT?2^-!)_LLI&;&{6bbZKUoUB(UyB`@BZ9 z;W272VLrH%M4$`1lc=gTu{QrFq^D3mc9pu2kihySZ8KlciWm4<3Ab8y5`ix4vZ88j z{aU=ZvZc5;?l-BMN+P8CZhC%8{%C(YVgE%Z5m>FoZZWD^Ua!gb*t8b*rA|^;7!p`d zrsu)&t@z87rXu;r0Es{scD>PFvMsf^UDrk;G;WC0-G&6##i@#8+J?UfH5Dm!hD!vx zuzOEY&iR@0qrcV^d!5{+Em1JFQ)>E3{i5i??pE5ULpvG` z4xBG`pDA^*B7x^$bTZoZH|}@x0Dm&lPa@ETUApw`e69@-*6rr+Lj9#~TqN)ukM>lr z)$yj$8+kwDK#4#Xb{i{7e0T@0URlixY6nSO#Yo_JBqi`~?#I<$QQW8NT!}yzc1_c6 zC$$To^4OopcMO*Lsgb~QRhoRcHh{;h8p7@F%LKZx`;Szx^ zIp;3lMdABvTxC1U@u=lx95`iwv*rP1(z(juZ;RLnRcdmZ9 zS7F7(fb-0?I*-<0EB-y~^co%Z?9-l~YWw);Te<3j9&_}lAR*@`&iH31kBbUrAF2gO z1iG+ipQf;TWO8r2gKYGq06i*5$Wsu%9^1*=y;u0(zJU^fF6`N-Z_ZH}JY#2V{^{;) zJt|1x)CE1!KT75uKXv10iu@%4UD&fvH+@wP@cp~{@E`sC^r#?#d4%-YZnA@KcsP-t ze;^a+!k&Faxq503|NF>HUTg47Jt|0G9wE&^&f3P^l9%wUK{A0Z?AfP!J5S}FcJaJR zk&hk~BruPVW~#k6@l%`rg=@o1XE}zkBFWK?3s#Y1--4 zQr@i6H?CX!yF{Q1d-iEpiqBd;`nV$EjYjBEK?3s#Y2MjmG5_jXUEEweR3gxYJ^NHo zEMCRCrq>j!w-3^zf&}If(iV)h3wc@X1|l}tMIz9JJ^Pdq@3N9F`lGRU(bQ3o3KEz{ zNc}#U3wTI!OA$Ask3^sgd-iF2_SSg*OXIe}Dzc{@6(lf^kZMaO=o&?x#p>495`ix4 z*{A%H(s=ILqnkL9-$joK5|~G*C>M7v6eTCd_+dwvs6gInoQ zK?3s#=?QYmV!msRgNSNmCK2euo_$3*-F*$8G_s#?|4?6#3KEz{s3@&-m-5w{2Z>X& zYfA*WuxFp1ydJFMhs|6?*88e@RFJ@QK{`d=zMSXW86h@V8%YGZuxFp<=szTI+o$fr zwdzM5Do9`+A#GhaypmUKK31$4UMdmj!k&G~{czmE>!pno2{}bNRFJ?tLi%>Tvxe(D zCW*Y7c@lvx?AfOrmW1v6?kF$uc|F&mf&}If(*0H0dcJ(+RB^gIQzFoXJ^NI@%HF}Z zRGuatQRe_ENMO1k-2sS=e8x3jal(6}M4$_M_Nn5vFNNo1`--IWI2|fTU>+gm(D&NH z+gtgGNW1wGfiCRXr)`_vQ+ZnEEV1>cmkt#qFprSBSlzbqUKjjD-0=YtfiCRXr@o9q zySc~x+2VfX?mASEz&t`lF}&Z-7w!!daYq_U1iG+ipK{M%r1P*D0iyBoN;*`Kz&t`a z;q8#fN0iSI5ygdlkw6#r?9)?Gjk5 zMRad>i9i?j?9-j)>NFlq+syN5n>i{-U>+f5ayV_{oHnNW)5dfp(1ktwwBzvcZtg&v z%#6)^IVwnCx*%1Apa02YX(b^3KBShLA!pd z=BibEf_c-BFo{4{>O>dYpdn4zcPH%{j+@Iy;cS)P8M+FI-z@R?;RHkm|w2!A+&yfgpSsu~Z zX8h^GeooaUEl%h3Vp|dq^GnGAdQ_0W2@Ki|`1FKY-s&8Wz3wLw=<4X%+cu@!coxu4 zo3yyt(2n&EzR1h!&C;WS1WsU3)?~lKYDi`w@A=S2BG5Ihvb}8;*FaX;NSn{Z*=qa_@0rl5guXv8v6p29Bw|%y@W^)&?F^SsT#HLG~*xj;^+-snh z9u*{T0)x&bmZz&5M;MDc13e`IT~*z?+cpS`XHU(vNsF9|7Oejr6S1qDb|Qg-1WsVk z(_NKRb#<3oqF3}Ni9lE87fajX&Kp_5d~I%G@ZW7%?&&(B=-Eg;DoEf22EDG5Qq(7v z8;je|hDrpwnkRL#ZL)X=)1B1jChF8|&FnXri3v4_=utreCori0YHqSxc&)X#808`n z=!)*&-gZcMIGEQ}i~omI!oRTi?>wvhFFCcT$_1 zc=xjn8`i0}uo>S~j|vhvfkEe-HmT~C%Z}oPReOm*mw9h<+xp38*z|AO+(hR`7R<=l zMf7OfMvn>-IDw%kt5&9~C&vvDvuBw}1iES!H?cjnD~H`3s!dvSUebvz^l=l{OdIJ@ zK>{Z*=$;{Zzxrg-?;@k1wnU&SYehrb+V!up=d-j)i;F2;S(c@TIPX|Pj|vhvfk8cr z7c$kzbWgEozmY_sYph*8+jCEEvhL%wNeh?H)=Z%+R^`qY9V$rR1csti>Ud0bYBW{s z?fz6E(Dmqnsco@&5z8^xG6Ay&_GHidPZzsm@9R)O0w*x&#NFqV+GYDpadu^%M4-!W zMNQkbhwicZsy1nHdQ5NjKG;tfa?j~dK>{Z*D6w}SQ-it%is0-_i9naJeRbQz$&c8k zUfQI^y-$=HMzhFDz1=!gkiZEHsv++>qi()BPfT`9kO*|8mYCSyeEWpmOw=YV>`k0l z;#cadIk!TG3KBShLEll+&a3&cVPfHlc@lxHQ5%eHo1~U9>sKS`8v41;Y`}#1V!*^H zI#iIr2@HDe{*kTbjEN9UavUTAU2T{BYvX{Z*6y-C^QP1T@ z3wxup5`nH!L*Lr$9{GaVtkxziu00+=+l`~eX~&els33t87>eTFB3HeBDn@L4*HR+T zwXEqAn{_WwKHL zMP+PSH*M0QW@vxrJ|sp=?LM8Mf&@-r(DQjrHqFjPi+?+umk4zAyL{1R*fK~W@%vw8}zR>HxbmtiPepX z6s?c9;;0~j6BslxVtiKZmKGsy`1g_sbj{wFVdEY2hz*O?CN0YB9hmX!aIyNeGe-pp zoWP*@s6e4M{XAc=^zjmbu3thEY&IJeu!BC@q{WM#dY0c{zKDwT;iw>i6Bvr(U(QvJ z=rA$x-+2;&uBCY)HeP!#GnYz7=^Bw69ay$anAp)SgrkB4&QmB#J^OQNqZ?s@ZwQbG zbcG#tvN6v)!xCb(xrvugoLL_I9#wkya8!`M2@I<5uFX*cI)@AIyB-pOu3I}h*c^Cm zU_W$|=o(8N4rB?V!^IWr;T#ntZ~{Y7?5r=T?!FO1@z+ZPy1p&1Z8ItT1gq=NovyLi zc?c^@j1W^3?Kmn(-~0#)zvfJ0${L9(!V}^(QhYJE0L>qsAsTcC&SiDB8J*p@IZXU{Ig_emAx* zCPqXiG?EB(b-r`Q;JEc5vt8@jN}HD5&WyXph=mQaR8)|tar=>>al%2STpvTk{{efd B1dadz diff --git a/data/kuka_iiwa/meshes/link_2.stl b/data/kuka_iiwa/meshes/link_2.stl index 47c7885fce165ee3f32b638b6cbdb4ff2221aca4..282aa787b4b158ee0936f84b1d414515d146e6f6 100644 GIT binary patch literal 72534 zcmb5XXIxdg5;r`Gy<)|JioIY#RN7w2+IFyE?*$dHD*|p69%~4m}xl^XSQDlmvC2gOtH{nC5 zRv;5`Ah-+2=se5(Po{{YSN_yYFV| ziXu{n?>jW=+qq0#Q5^y}l`;3vJriB;-;z@V^nPpe*nB(_4dB0JVEwV#sy6sHg6hY} zRY!|moRTRMK$c>)>c0)1`~UO@r80sG+rqw``#*?s6T2mBd0YR0LvmVToVb``-+Vli zN|ht1N65Y&TG#)_N@&}u#Q@ZL)c?R?vrT4y&|d3WbTors!YCY)6 zwB+;+f13H+oAb0E)6DcE%QX#u8@1+X88f6-7=H&wPGKQpFXYYkop>(6L2`I8wBJ zW~)x`>Zsr=4mx_!b|IgyQWtF%=}mwt z>zsWZt!jVVUE=)lX|6!Df&^#t?Ha#n}sR_{bVNu=f zW}qD5(nin{S}*lP0QVPr>yJLxm8}-GVH82Bf)4J~QYVC%eG2O+$K`ed^p9;GSW$!R zf|gJOof!aP;s@)M%3rXK9&j}&f>O;*Kcm_Eo=SP+H?}rFlej5*^W|lPbHCDzmQX|i zoTF0bth3z@t%H88$eYP}ZqMm#O~+_KODKZQZ~(_k4$x=2Jm3pEMl*__R1TS-&n)dp zhe^m|@aT?u&ji41kGK%zF|xo#wrKoheQz!o zp_CAWGQ&Y|fr}y*5l*>X7)4Mj`^k$bj(O0(l+%8ImK$bU{n=RkTk$r6mQVzpg8}^f z?^)%XLUh}LHjE-DmGReL6Rlm_7&8WWOuFeV|A}P!hVZh2mQaK`N2Q$emJe%q>XZAn z&?tgZ#V+1#qP1&hN)N?8-xv@g6XxFI@9Zs1T0#+YP6SwRWtbe_>o8wEyey*#O0@>p zCD16+#`IjsqjcJ2dAZ{%_En4&w1gt)9Q+@|sgA2eb894{2ukHZ8-?$uWIPSWKA%`+ zq#W?$fYm(uw@FJVg07qZ_S*Z&H&Jgadp1u-5tJ(K<}wq^ymf>Kcr4$wURMezsv_N1IHf|e)7}wP~Cva_6N* zsT6d@wOSbRa9%tMR~gx(+RKzECpIpukff`ybV5bZ0M32O$ijyP*=9WpP!P(xgrEUd zCKr)KtGbA*ciKu?FGaw~np!xv$|I+Vt#T^7(0V$+nO*2IMp7ze9i$)%1&p!czGS56 zF%gp1MG=O`Z*xe#{OdX7vElV4R(d0dZBr&oT0#+U@Ip!`BD!urj);;M+j3r^B^%dj zf>hROgi1j})TcYVT;0YZqj!j;by2htILNdk598}*rP#Ii5g{=a*BwL-fa$Z)cdlv zNzu3>+Z(Je?LUqA?SIHA6-BEn%gUu}`m+Q>%==MGrzQ551I_6U{dC!4(wYE9ttzP( zJ{iDj3~Z%SDvDNDmZ{%w@qj%3qSoaQT`75aF2z6|gL0oRX-xpTYaeBkjUwXLw#hn> z6{~%xt8FwQ+%MufnxJuaH)tqNjmXZvz<32gsTAH&tzL?O>Wovzi}E|1g3BO>n943nY( zitfK-NobC;% zpQmVmr!V@+j#smpU4Oh%5R{7Y2Dp8BvMkcKDLZu_p3!aA?zr*`sTV6Cr5%=eje1f`{u$r%u&brB~iMEujd=UPIVF z>D*qeKO#1MtRok`smS~GX`m}5UX6rtuMP)4taoK~0S{_(_!WkTA#HldfO4s9&h0F^ zQ72TSzVhWzr6@C|PY|i4t8=JOkQo*G2na?*gfAlc))*!$W_!W*SSEM75G{->4LDSk znt~uT0sNUfMLO3mAu4rzs{P|KQ)Jk%uI^*C_j_YR0n~!=E=$VJdox6Q)2bZuR6w72 zp+%%z_X$$Qj%%#&xO{q+DCf}INH3)(fC|~G$^IjX@c89S2P!SmkD@nd?AK6s_PfQ7 z?x?IFD3vOC<3b(fE!W&UH_xln5(S}1KG+D8>lgH4saw}6ayZXJy>%+jVb&c*ZvdX9 zTF8YLZ)#V6xT^g@tb|$*uG_Z-$#JpatX9kiPJ572WwbNI6^Gv7GHN$=^bq;3N}Tqx z=U)nfQqi6TaP2x)wy2t)g}TQma!>^A8-V&9rpRAEqRh0fv5fXPrK0^0kUqdg3>>u2 zx_WG+w2N7`xVARlDd!BaC+U&z@(1;Js;41RW1P(+qrLg&Qc(gRp`%Ua-%wZ&cNG@c zhKP&ta~UKCYlVjn7jYiZ%$Sr*J8~vUq`wYj@U{_3e)RVM5%poP?wR%L`b4m4Vv~o7?Pc!d~?*10$=Sv8akjy?u&7a8_)UJ*uB< zy6QEbzu8@s+`3Zq_~44sgEihzZG`~WnhefGXwP0Q5NW3anLTL+B9=^VB{qpTap@th zmh?G?3Jq?@Cv2Z1jK(?rz@stG_+z$!_a!l27QpvJ<8PST)WwRwdsrJ#c9K*|e#|q^ zp=G%3ogrvVI1gTOk_9>r_Wd5#LmDLuiVc4UaQoR|!kAQ1q@r&(W(Ns4`^40RyeT76SwZBbP!R21E+m$>m)V-CCAkVn5PZRCQIl|-TSF47<+=~3aL7V>~g*#xZ# zpjCyD@>${>^YQ#di&8;wq-Y!B&!O4_GyUOovBWW=4lOVNDp!~!UH0uU2RCrBmNc9# z;+i+&5WXaZT6k!m8NxmY{ruL!h!|XalC+QCWLj}0ELuVlDvzT{Q{*7KE-GGMt$0g{ zpu90M@#hrzAb%%u_rL}-+vI3r{|Fph&T9KgP7`0}W#jfO-!#?l7F;|<&RLLEyYu&8 zK@n#fp>^~$ z5p+iF9RhCNv_a5D93P_-r^qLsMHmB=2ZP&#y-J)NAvXI> zVUV8B3m{j*Z&76JaQ$-FevA60Yug|A&X|q<>eTJT+9h|Gqc?43kgFd?M9&WDCWn4$ zY@K=c!=l!{r%-Q^-UPj9Tz0W%>;!TBPah694x%MaJK0T688XV+HYdZPB@_YOLxmx0 zaJaS^5hFY!3#YH4)Qb<5-9Cxr*Cm&ye2^7Ad6g6%l#1E{z##h=x!J3h zwaj_AVkH!zO8%;N8R_i5-MUf2TgH{_B+@IPSKHJ`iwz4A5h3T95j8|Jh6M`a>N5uZ z{m`x+52z%&on2!M7=t@{QbG~emktmarCu^4H494aI-|U7#?M(by4Fw-lqz;(FA@4N z8;3AE?w!|Fx5*2EbFEPy%1MQaw(43q#a{QdVapjzj?*aGo<1CV za5IB8>k%>{5VIs7wIXpResO&9B*nVb&(a>Aak)uf8UOQ z*A#Vul;Y)1oEDGhCy8N@4Kyxn?M~`(pnH8S|++ zFVcCVMR_Rb4Uxit1O^cT<%rVy%Bix7@C<)%8Kgu(C_G-D=qznZuWJ`7<&_jc`=9a# zNR1dT55EuO$y1LCDlMgoeTRKMD44kwsE3lbYuQ%5PFrX_w6aJ#<0xaB_(y9`b5aBy|9G~&sDyT9^71IhnKxtQ+I+WCo;%G{{4T9mMY!z7=*RmbtXyn<#kW%`>gRE;T{l@C&VQUW zcPb@l2}R60Iv1l9^B9!qjjeLsJw_g#zJOP+vfiZjO8bEJ4M4-S!{p(M@x0t$O)QF_ zRCLS(RP!1mb6i-&!^LckBIt;sYde6eqbJClamBdlRh*~)TrVK~kp_he;lA^KD_Ldj z3(@-{BRPm!BXl&(Kr_zUN)3W8E8ykY9uNO}FdC%@d%rnHJ86fHo^$sD5SO)uH{tEV&$ zJo1GzpBZHMm=M0ogkrxL#1A)9SK;5!;l3npmWfs(KA5R}Y_e06+EOVY2x$7)7giPL z;8sBZbmeVDkwU(*cZi2nN+{x-mkI4la|rfC#4`7#)_`iCtp`aRB)n=U;Kvn=0bH}u zJvm(&0Q6uttubj%GG-u`(5{Jq)7d%L%bWJMHUT9*Fo>&{LRSU=4O(TD`^8YsAy5o_r@$)9ub->rrs)@ZXvK1p6+Q28# zG*+Etu;YjgvyjXKW|IzSat@AD0sH z#f#QTt0+H3K3F<5P~7rjxGKcYhqrq1^qML ze0L<7oywPPbI4S&Ln@1Dl!mRk(DC!Zfst9Qx}tMCJ`w&XJ-N5u0}VpJxN=toIxXxK^H;N(ZXd*&rF zL?4l%daf7>WpMd*VjS{XwE^_S&y z$ zsCX99HUAC-My<5>kqZRL>-4oOILdA$5gOX&;L_V%Ok&ZDBma zy+|%k?2m%czeL^MN3BkgLnNK`6@RWE9&`@1+N`u&-7AMnr7k+d5#9iCm6nUH8}i7& z-klX5iX0RTi|enj8jhXG{@OKKk;AxIQDl_d!HnKDRheMH@}jbTYB%ecZ-AsTJ&jDL zYli;M8^~G#K2}uu+RCnoB4|yRpBPnIdNt0@Tdwq%G&*44-9`9++Q#g=qm+06YB%2@ z>-UQy*5%bhC0&c89&avu{z+iQ<~|xl1EjrwY@K|RgYWd~CzX;X&BUIb8yWQNp&3e? zq4CgS@_>GqPv22TDkWacMEr_n3}%(r=!p>Kcv)+$Y_40ZDno;n)e`N0+FFbn+&yP) z&)dX`8#zFcLqQOkFqSc_ntZpjAz!fCPl>QlnUvPT+fYBbuGJl0w?Zx@!lF=-lPz2^ zrMHy9-{Nt{l11S`qb+KjVPu~!vP8KRyzBfY7A>Lsei{S9=wLu!xvBUTzF^B9i!Z8@Ufg$*?pyL%&6jjl zB1IHIEfk}JeRohHJmbP z$+{FE%6z~-vhr}@$>47}t@cq`L6MwU$ z?jsZ)3R>}SyK0R-`+>K-*;E1;ibLa(>l}yH&O2U8RN(PN$Y^od~zYkk3%bM#6O@CW-jYAQtC2rm@)q3`@ zoxUL4Nm&6NaAIhguO;dgt**^8#^4ROA=j;2{ zQc6hQsB&DevdhsM`e^$bc2_(#_3c#CxMRsBtrAV2@Kk~OLDEx74-$R=pEj13joVbv zgLZ$k6gj9LR1o3YN=j$9YI@+o=N3KtS7rdJ5x71+t32?kwZ5k1DuoBt0zIJv=x?ts zC+zmpXVf09@*wr9h||;Rh<-b#=oQ?rYIM&*_agKh4?w?L-WqdatiGgF4~wq)C|W)3 zbM8II3NJfGUmbQ-Pz0r-76UNGZM}6m?=bzt>;8%*QbfPqImDKh>lmyG#}mae`5#;N zcL(bq(mVvMi&D`OOuV%<=)4u;++RPN9HQ``R8-RdqLH%;xb$u;v^bHe^m3P4l)p(6{!2;&Hn#S8I+&I${ zqfspi#fwO*k{o!UQKt8Kkh3x$-J`28{1Cmf9LAZN2~gr!ZIiNz(UraA*1h#4rE>6i z^RPJovsqFs(ew{s!k%>Ys-jX zySuw}A{2Mqw1h@($bJW)+3ZGEWI!%4yKbb4AXLhn2)p<-D@WWbKJQ_3Wv->ZR`HK; z^hOVPBlW)MQw$`{NKwvcNp=cA@jPMjy4!T|VDJWup6b$5WHrAeU&J{1toX`<1&Tyl zG%8O|0qA)Go_U>*um-<#vi7^-&WmIlrFJN4`qZ=YQvovt#2hp)|J{VAO~kWExOicf z)vjeP%WY7oq$L!QdL`K`e#ei)%khZ#D<4J+(ymzLcWAQv@XBIYay=gRq_Kd0AcDGi zV4ikoyqi^7xP@2aFsKG1Zn;Lt`<=$|<9nJak!>2yR-@-#-;I!;p6=y4$|VaLJ*QOk zbO6tau62`J2gUQx+b&piRZOYWlZGxy{!&|YSv1`0s_eYz$r#;*VWys64(T;}g|#z# zD@F34J(Wez<(vnV=qQY-S;dnkI!|vn3?(n?A8iE$B#6UC_p10wRSI=ZL--jZo-Y}Aii1u&V@Q?FnGFqY_l=CRx zY2h+ywF`gR7A=vSxKXR5Cv-SFFNlx>j=S;`eKd=fPy{{y!ijEgg=w>TiItVA@U{=q z&|mGi-a&S^t+U>Idu`DYicoWLVq=-C;I_>wHLsYY2qk-GX(KVKc@1vQRurwI6!(?p zfK}Gdu(A?J2}RJ{7F=0gc9*jrY_=|qsG%Szl`=MAS=-9eze{iIc z29ovxrBXAU?v5!Xk4?*FxrGHN2uh`B8mif=i9&nAtyw)IB+Xo<*}rsV066w$gt+`+ zq1EqIxTGZtLdg*x^g7J44qvd+Cij&zd)RO(ZpN1P;OSmt1zborGb+^OM(e>iKFp5^ z*10K8@_8kHsg#t%6QxU)F$=AgI{Uy(@8eefQ@NziTDw%{C5qTyTtGHl&vh(?JevNT zDn6ccmZgmLlD34d8R?n`^LM>`t$yXI$N*1VEzx?(%89P+@UBeOj#gUX8nW?CZxun; zRLW{;aoy?G_Li=)fq|!etz3l>mxV*F022t65(xpn)+fcGf+eIiqLqSBs7MYp-bC^l zW*K>N$>gnV741?jDDuJgZ=B)@BCwh`{KzcT}{wchSGzlPc0A!F5a{XSs{vD(QI`^Cb+kz)-OjbbtoygB%4`e%W$navsZ4l(u)ee|ea$1UFSJWVLaHmpcCEB< ztMfZ2S$=za6+x*;MgitCL`=1IWqEAPUE4#+HK6wbXgnF<=B1MIYuHileHwRnMM-WQ ziJj1h4#3pqm#iE{dn-@L{>rRIEuYS)0CPefS+N!>eUqZO60 zUmM&zOhG7A)Q;irFXgQ)9oyljtIj4 z&N;(EKx{hNN&g;~PeCYDn zK~O3hHNtbwQ}yKZd(Qft%6F8zOO%S9>0q4U%~`9_gk;P2T^D8Mq+?JS!SJ>9T5!HQf5xN2c+vRfWwzO^qBz{Sv>RBQ-8TLdq2FXb1H}#`)V^g-WV|c8pvQuYi8fx z1mEFl%YjQITOcbCZV_aue({a1zx)+1-wb&8I?;X7np*y+jX|YSRbECLU zODI2D6ULSzJL)zMKhsDppeyx~mZaVp%hK@XB&^ASJob$3sdr8Iz)Cy)y;jMVG(Qd>PiVg{Hs6e4A)zwRba!GO0FPCuc@tiacYpBbZsiDzu+QQN(ch7MloY7 z-adu*C`X>BVS25l-!-@AaVmmPQH`MY8BvLiIbT`oCmSiTSH)9*tfU1U#OUWjyfq8` zyXN4pa)ere%f`y|Qe|1s3W;cSl{Gl7gw6!zltMH|f)1IQQ_!-7IxWZj*urI9B$gXC+-!@~vz zmf-!XOL!Wt+2GAzni2aL^Zgp90Nkjzo5%WdtM6GnAAE)J?z$#}UmZ1A+JprSJiuUH z2Tg6&yd)Rqxp%H8;e)Lrw+xj#gRRSH=`Q|!N9=5r{Q0(ue9xwFdPM60%Z&PAt2Ytv zR2u!gjh_{?N}KWbsUo)P74~UglQ9p-wKT@tQ_?2uEe?LsKAb(oy87>6_IiypnDn=n zdK_eWhV^`59t+pv`NjVsG3!g#frfk!(HD%D^VjkyNj zCg^3hW#LZ`mEx(-@rirH8BbC{7w zz|LW;ox?kKaS@?Crm?tPO}R03r-}J+NkjD8EiN5$4nAioB?LkF0eq<5PJa=xU)UZN zlF+O>i))MXhpegaP*Co?MSS{S8j&ot&4$s+sDDH3nSFegVICTr3cWskq zyERHeG_YlT+wr(Cj7LwC+N`qyJSaIzK;!Y+32c=|omt3ZnTX`&y;lp*UgM-vLJ`XN z`0?#B>u#&39a=tF0x3~Ol)__d>OkEozn7I5b6n|3;@ZP4~brf^Urg7N# z6??FAwqSj7LPu+Rp1&Pz6D$sD)yLzFmYqyX!77qxN8nmQaLhSJ6om^`;~53cuBF zl@Uc-NNWNpu&J4TcglXNDbImk6juPjc{pU8OmVJ&H+H(Bv}P9@{Ii<+ z{FzM-{y3>gT0#+U1lOWZHZXXz3lUcaHPtU>uP&lDRggyW2xc_EZ2oWY3J=N~?|*a{ zqtE#kEt2QVw`hB*9I3=&Fi+-~uU?_YW`3_pX+( zM&ipAE140$3|kd+Gf+Qx!;g3Rm|sEAwi`*)n9&SxBA&W{h^nVU^j-cDeBP`iD}LNu zHhs!myxILzvyYq2G7_iZO8m5@A{LDZ&_nNz;!Qr|_#kyD2+~^A)r1au>c|hg`Takw z46jA3>uy}lG@Gc!J;7D+m;Mag8*8ub#jw;3;S3gR$5!>&*jul6aV78Y`GnFcx2ubo z@c|L850w_;jrDh}^y2z8{(19Fi|U8AO65_sX)}Fwi{t$1aF7&1sf?15%svWN2YDu8 ztA?EFrN4XekbikO& z;@)n4#czvno41w)6?J7s)xR{#kJg0qNA7Ul>-%AIm)D;bwIu_4F!jn_Tnm+Cs$I>q z_0>ltP7v=qy|df~j>DbTU%0aTL!(qiL$s0y$qd@vN6BM1^w1yd`%CQj3X&oy6&(e5 zr}|z8ePqUV)Blfx%J@hhG6OT_)-z~;Hx9{o#BAKe$@;}M6`4yJQ&5lN?>UF1R)}Y* z+X5Mt5AWj~pRCvEWwG(EznZj!BB&Pd?Y6%o^aICrHo*fU+(bWA4ypxQS?2GppLkY* z_5JqKqEw0;Wc=eU_3T7_U%fKCP03=6wj^W2A_if@@THI-wz)?vdp3VIi=FL@e%JOf zLVq!T1otjCHN_r1ml=ULI;$5~sK(S-#%6uNStn~%MARBPMj!U25wB@>u_%I4(b0^v z!MawuTcatw(&xO2XQ1PQjsmV|N@|=!bwy=T<#@JmqWTl9WJX5lZh9WR_iQVrKPVN|I>3O7VY=7;C|3S5W=|3ur3l(L_#SfQ(fY&OU3jPI z!xddo{iuli-}~sD+U4agUte3agd(Wt!yU_^K6?4ceEi43HwuDMsn%Ym^f>)qgZezn z>86}o2Hm}=JC@)!5qgh#&AGd0F%>~}NN%|{qHn~RxnXg%k~A$s-&nFA&p-XDVoQ{t ziWrh5TrayhhW9Cy$D+MPsi=+NExOC0dd)dod94>qg~wUkCDuQnL6bQe^<63=%O_lm zK8WB?Qo1l&FGZ_}Bc&qsYu~)M`_I+No|7VIO}MZ9K0)vQXKwy@c@bsLNvTxrhCRw- zF39dJ^&g&6$(ka2awT^d20dD#O*LxDt@wDWQbG{wow!XwuUK*aV)D(c))Izc57l^% zd;O*<;O@l?Z@hz->!D4F4M4v_0leRtTh^>yebuM|L8vi+N`;s44z|PAs6@QAMX9Q` zVD@Ym8F=Q_ETlwPYta}73{TkYH?-S*>%?8m z1E4XI*l^9Q!D$BTcH5NfU)XzfjP_5h9P-VNZVG}@Dfj%KLGDJZ;-`n!m8Zd~c4^#) z@`m`>;>`4UVQmbN(PPkKfEitAL8+l2MUr{Ot zzyHRv(2M3Q&%!H}68G0kk@V)Aaq^f3i!BBnU)$_+R%@^;nUzR*fpQES8O!>P7OZsR z$qIr}(byTl$@{&uM`kj=b!Y^>W>rdSGHO3d{kccE)urwmvLHw7>fp}u>W5YHq#a7LznV&VkqUkH+FpBdp z9{;7Hch>+)QOJAK#icX1)>?YpM5yX}zlLCVcL}TD%>k2mg6dk=)Vt z|0}I>=9PP7e>SU28-3$V-06_lrKq%23;0^kjr#m|`3ZXUo*x8_<5EqhZcfo69^%YB ztPE=R*xp zFI5g&FOdm%!WA@rzSIidAZesbef?P*F>W_YeFz%mp|lX3s*U4LZL8_O4|+*T1p{Ad zZP&%)N-W++wSaGh%@o?N(i8M7WxFZ1ORZh)K`0-=F1E*=QOF5FODIC^k8?+7@$aeq z^|q_<#YHM1X_eX^OCE3MZ>}`apR~#=Y1@set_*&x!8OVpn~FG8ne%oP{^B2Y50J6- zfVmdHdr+Sq*r*m19YVn=$*k$F?;;_`BuPh(z2O%v_EZ8(j?Jy9+I6e5kwsnaW<75? zUYQ5!sSK?N*Cl<=^Re}=S~YuP-V#}hC~+9F`T*Eg!C8-NFw)wV(L!05Py}70V5aQR zS8P{kl=b}tzOzkceR^)BwyMYre_mqLbglKz35w(tLA8LdKy_Timju)nV~Zk>!5SNs zjwdl?T4@xaoC3j^<+FLWq0_97Gw|&Maz3OWloPBwlWXdu%D!R;uK7tNIz%Ej#`_Rv z{EBBrM_xKGSG` ztIVaF7+f2JJT^XZ*N2wN;4$|LD=`@whq0gO%8J&;GoC!bh?xDTwC*{3CNDlzm$WX* zLq)8KZpIgF_hF~fCn%?V#<8mS8Y%k0&eb%vKlJa@xou%X9^Nuc(h`bLt$ppG!hB30 zf8Mc2go2<{sCFRwV5BN%2qSQ-j0%$$< z9M^pX4?EpiX%$6KE#OIY!W2&F%$<*PjM z|4!hx{72bsUtA}WUZV)ALtM#3tmf-3JmS9jyQm1FAKEwAsy-|DAKC8mx(m9gvjIUU zo)4B?jODeD*U{gFyDO3_{Xw+=_rjm>$b~KSXW7#%r3ZW4n9o~`^}0>BDQGx*DVJWS zNFF`g(kg176U(so>B?GU`-4Ht0POP_9>4k9*U$O0Rhp!|M(s*PnC)}wZPpak{pXaG zw8U+HALf>CKCS?&XtcF>mKyV!cbQRv`^EQE{1qLKYJYgdzvaPurt@Cqx~g_Xya8^|mK2@Va;L_A-%>Qc*8~ueS!))|b3@)8+dF1udb7W78I} zVH;cG+l}6sIdFP0*Q-6Ls`so27HtWo`qgeYdzA}Mx7w`5msQ=fH`e1nyXo|q#q<~1Tj{Y)OIoyqA`CJf0m_FK z*I#F})Nej>wrB}OR5HC-PInxG{&!H0nd=|$w>5(G>@lYWMNlfAzPVWBF3fev_6O=} z;f|vEN8L+bQtgc585FBjT9xH$VcmU=pZ=|tR9Zz5R6c+%6qkPC@|XXF zYP5tRXxtCa)sBqU7f%V|@4c!kwo9q%cG=Bt{_UcHJuiL{u>1Lm`U}s}ymj6>jFwP@ znqMNSP0?!{oXBEtcUBOTO3ix7wXDDH(|I><`{zoF#@OlDrXv{Nli{`Xjek|qk4J7- zybrZwwFl+7QF@=e@qB8th8p!a)UVK(HGbJ4-)OyPtJ!>FNLA%rjUs3Z@yu)d4qm+C z8gbS)R9RmsbFH%KtJkfpzN_kJF>Nv4%^+u{be*WKsShs#{nR!o{wdT`J$)tXPrBj+ z==R{NHrM03RobVIgq8PfX$A4d;f6_>H(A|(c<}5G$188r<4d=vDzIWZippHo)LXwm zGQpG#F^IppjQvx&zFhXGzVd1vz0VukVvcsXS}DGya&>_(Z2V4QBSzPjXEJ;xEujd? z5AS)MD9?LUswR6M))a(7wKPRb-BXdn+os6lOztndL&jCh?_3iJTPiX8yy_f0>k7E~ zK}*%#IqVM<_8uQJkCF{|TK@rv2spfh?;H8ldfN|kooNY0yo%A>j@9LEBSs_QP~`!7 zo~pU5xesqBIV?0gMa>Wz(y)zwd{Z4OrcxnEODF=O0$FMU8#hY0BabJA+vxKGYg_(? zicqLXwh+F4@!eOy{Jp&Ot**P8w?yhyGlUW!dgy)2a4X`5r&LNPBDy-O(Yql}_wItN zYVML<52^K0)SuH;rjnA>ejl{t-gt*I67@rKjo`Y=U4C)tOHtxPu#$zOAZUIOL}euK zs)g%Y+-s<$xk?HmAVz!9pYcjA(b%ee<`jPBpO3=xC+-JnU6hJsC*iKBLw5a56lP>Z2j%UPu)qeS|7k0>!d_M5U+%<4n42P z8-(n)G(Jp0P~S!G$6=gdKr>eL@8i~Y%>GnLNWJvd4My(VD(RPYrC2@xtf_bgs%e^8 zg)e^FcD_gX3+$*9Z99LWO0i7`)rJ&xyg*GMFpxCV+Zp;!*LN7Ikj( zHM{c2yAOO+1f`-L98!WO@R_S>$@xR-sflPN&R2W9nChQwt)9>3YO8G=DoDmwyC7_IYof8JDwAk;*j>s1Sq(! zj9wteD{JzyiV8xZQY24Wo5o*{D=zQ7@|2XyNG*eLY0R?=4L237L&1klc+1qXvdw`; zY7d@zt-&k26WMi&shqKb^NcEblSkXE0`aw#92OcWr1^LFs!FqJx@WEgtK^0nQYj&^ zMdid4?msD_AE@;hGtX)(2uh{s4H`b)#n{0ja^sso^$e1nBCB#d{5+O>tScdZ=EM~M zJw>LHE9bS{KXv2#DwLCVf8gC$T0#(trXg4M6kexp30b9|w{j+|P$_*L@uh_B`{=#Z zZE|G=L3>k`-1|s>J!UUC%>CL;k1}%G_W((A{wYGu960yeVo%fDWTLs&E^l+p^ zK`6eYAkWI5UaTY2J@IxX)d{7do(NV|jo~rHt4h!ss0d0$eI=Y~caNWFmRHW3j6A6Q zP%6bUf=7^CB}ct(V?|#f+`>-?W~szgrjUs5=%)Wviq3 zM4HP-&q6RJ6XLD!e_P(nz6{?BC;59c(~0i-Fgx1WLoanbCx4TOCvnP-?tdAr^mG6q z$1Nwl@a*xdXL@%PLCz4A*dh#SkzMx;ug!Y2_!ol26Y04Kp8UAp;2-Xu;XlT=RU*PP zMoMGk0POowzV4*1$Asijqvzz5OpOS;jsL)7J9pA|G>)}s9GAv`)VR<79Xt7kWh3=G z;YS2TP%8B#&h~2^52!st-!+F>w1gt)$uH&_1hwX#o_DNnCHhJwcZg&Qsk`lRlUMMm z%RgKBF0@y3iilsKSv>%!st5BHJM+mb727E1YSa@cGZCCUex3haCx@I~9oJW6j-sBL z&Z3w**n{h#KLV}w#VRUU-gG{va|ysf&p8LruZr^h{dZ(8GTocepMUb zZl#%riA#8odGyy@a@XJ{hr^nT|-CBvUFGJFA z#W(LUkL9Y~Nq}*~lcE8p7den5E0xKVgO*T)%42Hz0AX%`*{HC-l`is%eZN8*Tj(3TN|k^as@m)fGkKea1cd>lkGJBAgP=v~(`|ENnQgIXokI%b7sZF#8CrlN-& z{Xr2_T8hT6B3@qOH|uzs?|Vd0+x5Lxkhw;!6JQT*K#=hamkj~Ng2ZRKUR{fjuy8#Mf2ak(vwE$ zX-#-HV@ZI|kzbQCTV)UgrBZpk?bFonxqqbh50spG9O|iQP59Mmt&Go>!lg1>Mg0dw ztB6jeyllBf-b#|lgCeLWqMi>=0o*+O@~%JU_Z$)Qiz?K1=_tTgJwGOir!@ohO~L^>+n9bgd!+!fEE6`la|iM!bG2v2Xa&%yCW; z^xKIPjXU~%Z@t1^oKAG`pgrXrxYHaoc$?DKQ^PbW?|us*W~sbx@pv?hSQ}a}yFAV~`@Kb}1Ttdx4Wlhm+DX zdytM)I_7!uTH$ptKYmg4JZfmxvXmr0e=V~=D1uT^jo^2YBR(a)7**2C(JER(5maw@ zs{i3nhhNt_7V7P-+`^?VyeVI0zf>sE(HDB3!F7^g-Bt z9t$F-IlO{ixPBJ}0hEe-fgHbo-ZnZ@jyd-?CYBg`)Ewn#Z?|(c`h8~w4S%hj?&u4> z`SO^g_~_l{Fhr!jY;DrlNqfIOWrjQcp5dB;FP==y^dow`iuZkJ2}P(clDbCyohiqu z0{+SNmIKY{j#hQqV$#?5=y!(k4p#N)nFx2+_CE9$HtkLI3-(ziH_DVe?00t`Dxo5| zqN}qZklBNChdff{AYTNg-{i$J;V$bkb+xGY3vVh1{pv8)A>O>NTQaj%?e6sOQ4r+Y z%M^|8S>$-)7~^`)?A?8+gj8}+Y`4mRMm{(;^!|s8#PsmfTBJj}Z*JS@s{!=O_PBSR znJ-iFU$0yaQY)d~^j7o+zyHjViKrLXH;MK+)el8u9>A9OnUX*7+~Q3Ul#22OIPq#= zvO|veLX&)`7O8%yjp6rLURL&X=<06Qd&!DU=r~v2f$Y57$;*KV-!v{sK@ck1Pxu|) z9yK#Z?FqMOUTv4hY2#75ai?aO^vwa|SRHKw{@uAJekTihEM9aFXJ)<7`J{uigd*sP z8NSx@tYBsj{*27$L#Ze~P4aNUfd-qa7m5g)T2N*l2d^J893@Ed}^*9OjE_zG>^%(-0uE3KZFf*@3e z$Zrcn#PY9>H)~SsS54W3x>{N?R|?gYq91xT2{$kN&XnWSo((?f71wHxx||o!(&*bV zR6e{p8Dh^IwSh-x_|g)JpjrTURZ-8Be0=Nas^oNLpjv<$5my|mW4%m;mcGhaDtY%o zkq^2>t;%dw$mJ8>N(n*G@sIJ6hOwCl>s8@o+UH6?lNUYE`($&x`)=qvUS2yu5!99x z8-uZZv;GI+dd7=t7f#mH95aANP7~i^d8Kv7-|4?5W1mkSG1IXQ)uRIE9Ha>Pz7y3n zo+#!VlqtuO#97|3xV_d4>vF4$wnXct{9ujuGW<@rp}%<)?XB1kMJtG%aXiyXmVOEM zQV_%v72Z(u*5`v&w0Eo;HF3YqmDK;-$ z!6ALIfY7)UsDU?r2d)q>!(W5%(-@pzE}&)!6N09qcHd1dFGp5wCOa+d$>Kih;#}j! zVo-@^T2QTqB6(M=fUk9!F{i)SGjWRIF;kX>UZl zT0cfM$>G9ZCXC@mEtLF09(+LnUnlr`o`9Zsqu(!z1&vxGz&}MZ3im|Bqe6Y9bMvnJ z=kA+4wFJhf7Or8bU*|B7Ia37`#oPUpw=ifsO28<=Qte9+vG`;&*{i^O?tRr+hZ`*f zG)!m4;?)Wj){Sq!AoY_(M4Z~`C*Q{`;Wf9ERS=Xaqi#I`!OIx@iTB^(Mn@kx^X@WU zcZHjRpj7F1>!8MuF>uD$9-!4rPuWv$;FXS7R1lOZHE&H}xPN9}M{PjFYy7IC_k{7B zC6?ENmev=rrvrnYcNyhDTL|FR!Y*@nD8b#fRMO#QcL9SEHRyhwL4ucne0Xxb;SK)o zBJgYM4AL$lk8`PZ+0d^zFJMCiEg^{1Q^;F$W-$91B5GG^B7<%%V?~Fc9E6JUv$yfV z7j;|P;?}=I#LK6RWyp^etk<@Rx>7=0*sKrk1%KI~-VH>o_|;5)UUJ-=|He(X<5z8< zr)I`w&tM9=3ChtZzX^-(AmZH-f4QnbJM+hR>_JkZAQT=U`Q>+v)kEagVPkIr?Y^0?>h?0r$h!{xG2fzRU%p zaiHw5WxwV6Gy`9&(=hUZ(T{e2s|ZpP-dKOj<+5g_;-k<<`g50LWY9I+2GIma>&g(Qmpah zl#22*o_7^N{?i3q){w`%9F^tD)^@ojw2*?JRMZmzT)(PIy-p|o@;Q!=8UqE)?Z$vf z#rmjC<7#O*lTkSXc;|#linUX#R4wtrj&|}!o;9pPOd%aS9o}H029r&EEri$-wK3>` zh!SJcS^t{o87P8K8Eqp4j4Q&7rYR_SwFj+a-J;GstzI!*DIo~jLVTHGSu5GQc{RS& zsi=yeql;<;>b&nLZ{_mgM@HsQbVWU!!W*`=?JT+AJXsu`3*QAC{=criJHE!{`G1rU zElTv72(B8v<(%E;AP9mWL`fn<1VIpzAmkvTNAE3My%Rm>*^S<=-rXSDy?VWR@SVI~ zzu)K1+`r^y=KX9rJF~O1GqYo7nzr#yCM>{}NOl1GiV5b3n;4;YawZ~9;*05j?VG16 zp4yI)g}7%tIO>4*GXzD$2b|ps1x>hs_1s`!qc9y)e3Du@=P*Z5uBwwwTfIgN%~#JReO+GXH`eM zm05@*Uyp%Ha}p9%tB$uM&^e(!VY=k%;%?gO>{ivWNV;V69@-0E@o0?xR^0m-;!KdA z_L{vy7=Z;eaBD9>d7~_09D7+m&?u-_HddIkPf|^???^7GFL5mx~5VUr9$x z=Zb0~thiXCy?%^!w%flO&Jc`?%~kB`ZhGwc8|p>K9yYr`x#+w>h5p?&^t+~7gl*$< zMGrEZ>?>+hQT+&THKD0q@uRxFGzQ-gB6GsHh|b3<|95=!!?ee$ zUs?PGN$WNj+zp=N{$3q5D*HWBK3CIDxumW${}8k8sCH)U!P#albjz|ub-AzeC7U18 z6TagNo!DB(Z_c56wmiTPjEnRZD?0S@)$NyM*SG)vosEMc*qC4|#OQXLTZ@K`5+t>X zscmR8(6US$W=YG|8s%eW`v4tuEWo^Z9e3wCBTV~je+O(kg|#J#oj~;?j5rvi2Lwi% zXFY%78vq1Bxe87}YoL89?7-||*pxF&zpYTvS}5(Y1WKU@y01Wvlsj$?rIV zaM^v5Owe_$P--2v(duFsy}#HMN9#2O4W`3s8+1%C`kJ49oZ_m+g&~4c$e3(4%m1tz zth4PoTo*Wg$PwOpt7NUy^9MbbK+iUV_4Y6R=F!H-ID&G~8G-5rL$%kTTx!zxhkWEz zcaa`qwa{Wgdd26qDk9(&|2-&zY9%O?*-;lL=A-T==VulfwZizwFPWY6#y=XXa^d+H zf^o54{c;+q@A;N84=up68krxq`q)`5Bz2U&G<2cqv3$Cur#On>r=oXrqx7p(S7mK7 zLsAMoN6{}~)rk4SG`J=xr``PI6*7E<3FH28qe z#u1kuu78_%Om+6MO8Q-THl)@7-mCdV=$W3&Rn$Q{Lr^Z(HVm>v=!$Z=THI^`>lH;X z`vD?yMd%iVW~jhh^BID1(J{fZQ4!ibv5Lyf*w20sW~0z`3@K9w>my|iPVJM7LcU9V0{{sD!?al9DWBC| z%6tISYe3t>^I+Q%y3eihGU($RNhuV;+jtl{Qhz+LUaZ(N57+Lhe?1UH<~d^QuSnh1 zW2T5p*};4nR7)`J3O7y<)hm}Q5nGq;WeCc}W&|!o_SdeSGsRU~I-4tsU?&;q`lGjQ zcm9d^r|LU~pj`Yk@wjM+uGZUCmh1JBAt)DJ3jiBic<7EbTk1H=I}5#Qq<4_i4nl9# z{2{u`5HIN+wn4%TTtAQFL|Wh^Vc!{N+CSl2*w<%^w@!G53rxq?R(s(p8DA(`8#k|r z_yUvUmtAYnQ&iIG)~G$^hc3obX>qJB6@i{3{D0?@SQEPmBH~Ys)@MI%7iGV8;0VHH zPuXbN+vK)F-eQP&dkt&*CN_|+!Hrn2=u2j-J-8S;P9IpeLv-5kOyqBd-lz%aMLF9} z>?xICewme1+BSZ*o^76J+WVXlu)Gnrk?}KLe~4ITNjlitQZjRrX*+6|VSp3V`hJt*D=^H*-olO3jcas=%a9UpiP ztE1bNUL^gg(pnrGi zD1Ys|E03P7O31fc=iskqm{5L?m7culPK}viqZ;V2!437Fu5YZ+W`Y@;G1!Dbp;juv zTxtu%w$l%KmC-x@oN$OD=&e3QW9`pgq55fs7b>a$a;w|s}?j7o^XOtSoPA{6|tbuumRirj@}g z%8CWC3V#sFM=`WjgK@PV6rJ^;kzq2wKkny*LJ^yb3^HS*on^&!A&4mTqo4jdv4bqr z{trp@AhiZyI{N?m<&dzcGa^L3U|l?Jpd1yCHZ`RX`+>J{!fd6Ne4QoJo)$6~g&?RD zU=6yq_<~tnn7o0nVKW4g6*@lj0mKWPYi3{BYI;RBaw_L^4zb?rLG(HY4v@!dm1hz~ z5xk9{jD|WXZG{YLT#+NlO!IN<6=U?kj$<7C1_m%0q;ki1gVd^{_3OdKl+WyjnBn=a zq*4i{@`#yX{i1cUU$}akv$UkrNxA9_+GN7IaSqsf7NvH2!O^;VL{ZgaauZ1@6hYg= z?B$R+efaWmGjV%e+h;AVnKCzWlgG4M6oJwx>0&Zg=x-d#`%)gQDyJZ;Yo*8A#Zs^3q#3re9nifUJk z{b=o{%PuXdlWOG^ltK|yS7t>Udgvb>E%mI1uPs!+QfrCc=>Z%F5xV>|e53Q|SnkCk zcXzxE|KHl{(8eWo=#a^RQrK?5X17P)NS$KYt+w_#%tlUsO*)5I@qKiRZvJtEavgn~ z%`QdIH4Wf*Wwd^h)J5$~#|p+ow^J_q%VNI4`#8O5#}D&l^;GtoQv_Ypcn28~qu)Pp zmlG;=l+=P`HWjfrv3|QTPJ18tAg;XKE~qU^5!{Bm`XyEu-CS8_Yl}Ja} zc(g8aBZr*wN0g-Br9I>p+4;@m^{Yt_tQWk`FsqLu3eB2i+Pk_-n0gmwFk-}5UC`kn zeoMDV`Yp;utwGFCXdI`{HNS3^U1~{6p$NCj*haR75j$9 zx<@fCf=18X>Kl$R594+9r;%0~#b}S|WeMJ~!%R4E)|$~iyCbT|4l^V09F9D!#$RG? zkMX+Jj1dfR>DCIXnQg1NZQTVcMWZESUnU1RkJL%sCRk~NX$ClpCU@4D_SjoiiU!!c z^nrBRAEqxS->_0HiY^)2LikplZ_cdy6nj;~{7Y7k?WceGZn9DeMbJojtfzl*KK|CD zbd>*H3vHdoy;3yhA`i_ei`^cl+k8x52s&>R4X~)eIrH(Z@p@?7G6&_NGs@#deP`BI z?p5RT*RSiXltK|1@04TA+)d`w7MF44&)+$e=ZhiwjIE@DYEFh8Th??gz0xc>D@#7S zf2OGZnjv7S|8K>c(fSR3p>&=$EjbOsc=p<56Dy>Fsyn)^dUf znK{t>(l@6#ynG@UA)j>#`!o*!Wj{8J}ul?-kL?+%OYw;7(yJq=W=SSTg*L4V5D0 zn4H;+!ySeSe3S>P3yl`A1z&#ac?lySmWs65cC6C8RfO1QBjVi$PorVg>#>INLe zQ+B-~65{ZTKBkVyIPi~1cKIFOdTKB1r7}d?RE(v7s3WzE{GKyp=?!=u{8bBYzELj~ zm?-8<#=rfGN?3qBB3}X+Ril;>oOhM1TDt~ogCbaa@M(TSBd3?Id{?X%f5VNwUPs!- zXpwdCM(WUf=I~pU1bw@NzO}Su+hmcpv7m&PA90o3Ssia26Ys3W+`I&(&{qZMmjItg zz!%vtYkbGJ4_M#q-+8CC?kO7J>+%?5$;ZF?#!eCROBfH=GuFsE_MI3}xCdJ$ zwBkEmF?i#Su~%P@=Sa=DZopxhV?Zkn@eG~@E@O>}t$ftU)!8iG<+h2CKc+fhSywB~ zh~Nk@Ajp_F5%jQ13%%$Hrx`UgBLZ*rrJvDud{Nyov9>5wFHwA`6K2BrURH{rUjq0B z!dSGqrtaG_DV64oQ3U-G)?t}m-Wc|ekNz4pmFYyP2kDnk!^O2X22M?s%M0OM5s?Wd zD{SpPDPT2ry3LVW@?m@ll>>t2t3Ayx#+aY<#LQ>2u612K&6Xi3g(7HgvD(7WSmVQ-u4-Gx7dE4mi>_&a#zn>% z=j%Q-e>u)E1m&W#f)W*hufBQqHdkMCl5~D37oBO01gu)wXg$1zE?Mk5TZwe_xfKr; z!&Xf;3$6Wx+NYgYL!gg0J?&E(48RLocg&aq(=Ip>juO0kawhMH+AF z?o|t3loymj5me>@Iu;ynq|AI|o`wKH=Z9(oItu_BRzw?q9}`u?^7aft+v9CG&*)$@ ztyf&{k4j?Wpt~p^`8cPhM$7Ozdd$2YOqWmuokPrtTM=&*I{)4gl^~dIr@H}tQxjjp z%rVx8x7QUvs(MSh8&EF(g5*A*cq6e(VR7+5qDWVG`tryS_!y<2I{^I>=5rQ|HNNJ1 zDW2TwEh&O>ZL&=ea4Wk6Pk|CuU~-({Ik~uq&rwNI3PtcV>G=y&N`ov`BaD^c#7u!o9I=zZ9 z=-dSP=vyOZ$xzFQ?;n+WwKAkVOup}2f+NVj#OJExSDO+1AXYAHQ`TS%SCg$P zI=l3@!P?QD&!k`SVOjTeM}yjiP`#)~JNrxQ%C&*pr7&V;nhb7vL1r%LYJkgqYjQs) z>Go|CzM1kbf_(|D>OI1H@d5ewt04yb47D~Hm{+E6!3Z;FSBxPnEA3lW2`JpwQvX*z z`8shMu9DTi6&Cwuq{$P`h@cdLu&pkaYF|?pZyZ-6VtkF$js@!u$dHFa4Ms`MNIkhY zAHLR$-=$vywe_6Y($q2r1{*-Q7`j0phuu<6+M`xr8@)GdQH7J!WG%lSBTc8{-2mF{ zw~^wU-?SCWCT*KA&hE-t$EA>5(r-Lk9#Ck~Q?(=Mv<$rCYtS1Eir}{y74Br$C9dp} zkK@`Hj6&M5uP$Z6pRN*4%*8fJy*aH8Y&b2Shgf~GUaDShM>1S ztZhiHl1F>om?FH#2N*Pq4xFl+wvUFiRSgvoQOGP=p*i*{>ptqjoztrEu`8C!qazHO zoyWMwoN`nR_K~)$c$R`br5CG;-#3aYyQA>LLb6?G{s%*(f1hPWHm)biREp<_LzNx& zidfry25KCddjQWzwKmU|UTE#J5fPL^5y{;xAs#-m>cbh>tI^ioBIRfgQF8luj-XsL zBLWtAVLHH<7S@5E#~JolGp!koT1z*-se)xbP&5?&I!F2y-z+w)7-_I92=ZO_B{;Zs zmwcYs%rddnFos}UC%;(Jrr;~JXX0=iLmFo@Hr;d;gU<&t1Q0IvhB$~fU>pt2BYOPg z2*yRSE-=#~>60uFY?pmAyBX{q?^Ag&GOUKQMI{QRgCP^+I0Mfni1D=p*eYRbjIFB< z_b00HyXRXUM8)vmoURP|Yr^^abJekoQ}RW*5H7V;Qkk50+Zw3)ojfexJ`6X2QYfPB zV25*syz=xU)MIcX_>CFZ$srxpQI}8zHPz6H2d0J<|Y!F!LR zSjTVbQXKj55q)HVi5S1K4#z<$6hU_)=v@1ES$?0Af4lYO2+Bpq1P~efQ0@ucBJ(xC zU5!!*f{h724s+4hA6n(i@Qw!4gY=f2t=;F7o~Q|TO3M4I`xs0QQpCd>j*tTlq|JW{ zj{M!x!!oEvwEVkef81;LS#6*3J>grZ)#z`t(N&}!_ma>l77^d>7BDKGXeujw#a>Yg zK`_~brH}ts#kUoe59(mAs1(t@vtE_FWLLQlRo z0oETPWOgjy4G4n$vXFXnqf8lIUfLH8wiPs-+`-yQYeD11?VGw zNRj3uGghE3p$Njo^gL`Sl+PIBc39gg5c|__0SK>oHR@JyND7+RyfsmK!1Oz z-1~`Iac6?u5Syjp{*?ocpgJ*o_!MRPoG2fTMLUrosD1>xV!-YBOqE!3hIB82nwnCG zMr9ft%GS>?zZaY>{p;iIOc7Lb(iH<^JKZz?xSb?Dnj?Zz2!dIeaN}et;oWn#+&2#; ziXa#lT`_RNrLYLPGh6yhMg*ZS1hJL@jO#7rPWvo*rp$1LU^VhUSQR_SVMc;Ou(V=ffB?fu4s1e-nBi6CpjNfH{#S z)ZZy!w+_HK$9CxLSh-R_or_l6;b6hO1YH7R4Cfic#l~qEt46r!+MVi(w?9i(TWkS7 z*v6BzzQ*1;-DHCT*I2LEm`D$?veDBnM#IbbWpp!)y5Bz-V>j`JbqlVH&gkW;RRG_- z-zQ*0gn$(_1x!4KZJhYo&1l-VwygCihe0V6!ACx}YZs%+20y7&G5(5ti*d1Eu;ar( zqt2Gjj+sH(3|Ko!*yi-NLf9d``g-8(`gcx+RtKp_Leld0u(Ze--0t+W)|{ zM0Av$A=1xuGM4mgs+=0+Gtv@KFV#8du-Tt8eFdeX1o)12z=9Ll#+_AuhDyjVAMPs5 z5tNJRE9=2-h8a*@^!$;RX&?iOvJaMT54sODckGvFQ*s=$z(y4z*Mxi|+ zdLE!&2R|b)aJM=O=uad)p*>`~1gsD0V8j}!>RO%G3_-bU^Kg|P#*DXY7qM3%Nj;56 z6ZVVWyW(6Csim5M>KK51E?td$RqKks#uZ=)#zkiu#@F&QCa3zSGd}qZwtJD$veg4E zo&1am4{n=JQi>RKCu3Z!jb;~G8Ye?_RY3*d#X56w+JTw~X236!fRo~+N>Q=v2ZVHo1(yCH__ z*(a&5Z#bA04g_J}fww+&o_Rr$EMLZz{)3Etp7qQe$$#*15Cm%*<{TejwD)^vrhn%M zrXML9{F{t2^8G4djeIjtvKb{k;r3PCjiZb=XGWX1x6G83!ulSG7Flv`2Rufr8T^Wl zG=?lbWRCU0oH+7b*omXXaX1d=4wFGE*_Pk5UMN{hH8oMuc(SwX@29a|=T- zE;2r>XW6r*@$_b*>=skhpn8zn?ex@#RXo;Mjo+Kil}aBuOb0!P}_)F5IYjI!dKhO_9uEAv4Nm8l-QivGs?uIuPo`vIzS4>z2Cy%M%;S0$qm1f4^G!Z*7Zc|~_Q*3-#g6nYY(zburR z>~}b$bAlYzK1S187Bo7Z#&6^9{IG>1@^`!Ze4HaF7p=m8*_j(_IPRRBB%=ajG|g$C z`35xO7|#YyPN})tCCGjqVl?Xs$tgVZ036XfdVybbzYnstE@Tc>6ot}-q` zo^BnZDTN|vwlu)~!p@d>?*!SbV~nQxF*FXD<*33UkF#F2L$FuvVl<^t1dZj!`aTzb zq_&L2*Ly2-1m&XnqgZWvlybbgJz2)*;^UxwXSt+MAbfu6x<3J(E}G#8pK3o( zUD9!~yig5)b5bRX_KN2y28Azk42emU;h&>9f_#^?2Ym)#utY9QRL(!64H`{DPmt7d z!c3%AQ!N|cCo0$X96`CL6@_o!_qAH1I!{+~qoWP#v!YSV9I-QafHi;nDJuGYv_a3# ztXC}ZEL-dot1ZV=wRjIl(3mnBw+7(I*4g@J=43V9C5E*@x!8UM7yLh3I$lmtzk6YX z4cQ?ng6*gfeKWuK+;Xzon-lK`$u3M0G~N%r1_zzQ`fQU_lWs8vrO=2^Y8e1L@ba`g zxjacl2V)yFCXwtP%s&G)P8(v-#gS@8n^=aRTr?U6HA9`VUMm6-KI@ z)vftgB&ZxVK5{xHK91Pwmo2_2lT>IQ-Uj_HjT}Mk^T@PJx;;tF3XCzBl}e(8C>rDX zFqkuA^CUGctBo4yN7$cR*gJ(Y9~qr#d?By(6w8cq2`Z0&j6o^1JwA@8_;Z$9XD2Ct z{5@!YSx-n0(UV$bt>yLGNh-Am9|!Frjb}ogxP7Q)Tfhamx6L2}++L=_bMz&yeumNA z?JeMoeyc%m(T{P>0?FIa=DmkD+=36DDyejwey}~epwaa#>V8LAi~`*uYMxRbsDeBEH+tw1kF9*h`ae*jK>ppi+Y#4 zFpn@h72k3faQcM>I()%4Lc(9kfP^D*d8PJPG3(zLA8H{{PdcuW%(XIj_-@(aVIStL zWxihKZ=d=#Q%cnBH@*GYNtpS1XXh8NtAc=q@3B{wH`$B{$9$xDrW->5;bLQgvyr=X$Y*q4=Vi8!#x^K|c+VLcZo3yY=Krdz3V3v2 zo(YDgo-hctx)@E3Bo(vLhj~AkFJpQc%qsZefYP|eVD7aX#?h2eCEj!~fKV8M^cL$5 z4$EcaKbEF;g|sl>o2!6NRj{VSQ+`)KzJxE!Eh}K$8F5WDdeej+cJ&2-OvDGWiq6ugbH^MA^mvWwp0 zJx%T^S4<3hxzGg1Bta3hZM>V|0A5*SoJ2)Uu!!2mKP>R3F@<4xNnD&A)!IQk|H#?2IGi*aj0)$_SqG z^W(usb)ZX#Zkn%xa695=mdv)?gyfQ}E-Ocb?FGGHXP{nKYZ61ys$4YR2v=gzN7dc6 zw|@QehOiZ=VBTuJ7;Cl#3yPp^4^K55n z`&hxe)O?m{AGTOf1pN}g&#;18=WnBjy-8#UTAh-j(f5k4G&R4`O4q%-haqU?FN(&s zTfBf?zqG#Y(e`giYl2Y(v@DOaG0cQxM^K_>cslF6|5VXOTI9uQq39?6|CP}wSMzfC z|9G2`cnJ~r#ue0-N@aAwIIIInDWsMf`x3Nra@M6D6w=@NxErkE8bvoRYeL7yrad=C zfWt|b!g}~k(9d(=4KJavYN4b(%sBLL(#OkRRx+^v;R~y`^XsK;rl_x{ z+ZwEb6|F*=QN=9UW2*xWW$jTDKDg@WDwWjzTfV%qDyiQhs0n+ct@em- ztZpquWBuA^nX2TJZsN9QFhejd(l)+o)iIlXw5x#ZRjj80w$fO0`GM6Q{|{?}wGG?r z<Lws=)>eLtT{3XuSzST}TF>Rdu z^R1sjDYPmR`x3m|^+UyuNs@Wjcjk3c>32`!9Nvl+@bdw-k+an+6?Si@>{zao0sWj! zD6|=E#4D_hFfhcFemV8o^kvfc;)}63|9*>B9;Q9S?18ku)Jm*Jb<85qT{z1LibVy$E zKs%8jC>I?QKul(3Gu&gZ>@Xk_Yitoan%dU`j8w?9VlL!QoZTKS_st`%%E`+SV+}|e z?f`cW>#YPQ3C`ZB5LwuIJXdafUpCSK6<=6wQ?pCdy9eLleLx9WA_x(bLJ;=x%~HYd zk=3tUPDCu-f6JV$tfM+N-aJlzG^SqHDja`T!6oz2q=(yyf zIrYPKxgi)wP7px3y!+t`V|Yhc=@qt7xAY0~ao3%4Tr)&a3PsR)gGF&kj_Jj2$tig; zYLZguDTPJE_nh&UnQ!VZtP6z^bh}EXLe<5Nr=M|lCl+>q+xb+#)A$y1V3Y$g><-(X zS#u>KGtIfV8mT^SM{@+_%I@j_ziW=P133`!p-zTl^rCpZaB@45K~6vPyu(i{)9T-M zggzdxoj>hk2*!2GC)GZ6Ggc)YgmbmXW0PY~pTRn;&2b3goAF&VAbEJW9%mCY8Nn(Lkc z7+FIRlxs&(2lT|<**8o3wCG>O9M+?`uGt)h3J(W8a|ltK|c#VydfqX{nW5Mkdn)hs;4MNj^W zx}72@R|t+{Vm;G-C+o}^IkcRki^n&WGwZBIDHH+zjqS~fn6`Y`a9vHPx5P}(nXcCM z?#~gFs~@h!It5MG0Elp3In|u8Gg+038G-tWQpk7N+Wj_bxTA2t>8jrFXag99AgJ8H zwwT;zfkB(if!{HEfJzbNI%%;$leMWu+M(`(kCi>mV6&Uo{^Ri+LAi+T0;o9ui#cmt zHZl4eMzPX1C>Pb05P$qnGyF`PF4_Zs&k|!DZjaFN-a3Fu7chzXaOSRgW_PUaR-(J4 z2+Ea=^?$+(t}$a9Vyq5a8gRt?;vcJbd4@?wq2HzQ2zlQ>F`pkAscYSs&JmQ0N;9}j zGgM5~v0A$O3U-1Zbq1)80Vw*)P$eVA=$Z`XWUX4*PYUA*d#@=iA`0S!bH|ks9Ypy>6uH-tMdOzP}?Gg?^Xn z82IUIQCqfj)>97WF&Kh!QH=q%qv2{w#WwnEs4GWMuDlB!_J^oTJkqgOu7|6u__>B2 z7KE=APzps*jR9plH&+Qs)%B0n=ry1S%0=ZLPJHa5hTh1g!)l`S+86ES>eWp9wvQN< zM>GzVf2ee-wYs*Dnn4N{Mg3cqYhhImiAfQ-(U6ay;42YLkyr4ieMUJQf(i#D?V6Nx`Hvn z6hXP@E()KQ1*nzhMw^9C;$FK=J0NywY9WPtD&?Z`4|z}es(^k)Ek&<*VGP#= z+w_$b!MIYMICiy0No$932k>a!3{`Q%F#Y&oC#+mgC`5NLc?8FrcoqE;>wnfrU;;T>@=Uj4|&%(S+?M1(U8!%=zmu#DquJu~&0D%u?^ix6}iV6)}KN z7=lUx94NF>y}DIdJM8rsg2_tepAInEns%SRu#LEw$ttCyo4#zbB7#upcd4wvz~)oc z#R2*B>Xq#{f^t#00gs|{l>5Zes>f2?2fM#<*!`zE>IC2pNmnIZV=(5%Ts7|6OS8|i zD2||9biF~hJu_9zwr--sDYTIL-f+NiU#nYgw9hFQTZz3VjaT=Y{3g#1LiwNw$`y_E z8N2_mrX9+X^CNGkt5Ks%$$(Jo6{S!FvFGuf>ItJ&+vDh6`8<>(DA%B?XzyYqZr2ak z#*Y>Ws;2KmX`PP1i5b4jkgh%xjOLAmG&09;UX$BY*c~IS7|4|*ifT!)pInmNCiEq2S!Ki2=T}(a} z-P@*a*;7^h@0b%u5tQp?4t!DPrNbWe8OQN`;X#!)=7c&vum|Rh5(-7ood|{;+pNOn zM74h&p4BLVa#7iYI}6j4uj?%39E-aerBDQwU?}||Rjo)Fq9>dUWqwiWJ*8F@){gG# zP}hbJ*8Lu*GX&-0KFhHij;S1h5xQoOW}Z}vU^*X89yq1yLztd4r8o1WQZDK*#Vpee zS5%$3q1wlz1M_lH1luKG?Ar^faj)+BOqmphU|eh^cKUKlmEYMyFF5x_GXE##V(UtJ zT~~u&)z{V5x*7~Yxv2jVR!+aK3i~zEtyA#?NhuUT_7#9*A8x3+H_GVJ-D+|Kg0GYMr&-&D2kr&uE-$_J%T1l=VdVexVGW@|NBVfud% zl#6-_!D;>(6|%=oKD>vv52a89-B-Zt%taM9s=q9H9A%IqC>Qk zZrL>y{k!yAl#6)uu<}=_C2B|dMLEVmok%GZLH&$yaoS+j|H?JFu0Cd&QVK=TeFf$` z$yBkkeRNvsBa+@nFl|8P5h~sLq3ZtCT)%p9ogvs>LhmVHP{r(e*T)M=Zf?$Q0hp|? z)t>n1vwG4bSv{+T{$1+%r(D!q4-so}>X+9ys?D;k!Tk6XL3KX-KKZ^nnjWa4m*Q_u zzeTyIbiw`-?^V#_w`S9%{~#zAl}#9*=e~5g5~d42AaEzgblSgY{GDS^A% z<`U23mWO@y{b@S{rBDRF?US!x%4M-3de}@SNfDHb-zYwBeMRQ~5U9V~7qOdB=>3N^ z&3&n9FST57gn21R_}3VsJM}j)?v?oW3iw-XDXUC--jxDAcgEX?1tzT8kK=e>`=cm# zrl)oUU?vjvy%Da{XJf6fe5wg6&mdxC-fP0IbAVp^H{Nj*1mmI}HW=tyP&z$ot-n4h zgD;=_>(gV14Xv$kZz%RK%MaHxz#-h$G}9~psLT*Rxu}N?>Qvh!7QCpUw_m~=EJ~pW z<}dpY@@+3-BEF@|pbbY=u?Un}=NuTH{n7zW=xLj1? zZ8|6WPejiIsQ~~on}CBD5B?9H0ZB9ro*dz6B>*X&iq(uox`Wr{S`|V4aEo6hNTd5025H1!o18MD_%Uv!DWL+bG#o_=#(3ly3 z@DiV7QcNQmbpf-mNi+>S1iZgHYPEOD6g;wKj`&9|c%DNh%?ak&H3R`HvS!=QyYfoJ z4G~@e&mWXR5kIlLc>^pVbF;j)n=GH@x^;IQdkf>PMiG>YMZKJv_DW7{R?*Cvgu64P zP{iBpSgW%eM%Mho*=@D+fgD}ZTaAdvHYkE}(bWT?t-r~6Nqv=PZoF5c2+GCQ)sb_r zWb{aUQ!jr*7FomAF_XS3pcN-P>F zU$40;Prt+2rIkCZbFC0P2lIDvg;Pm`&4cqxpG8B=QI*lN&HUeGt?=7y$FL=MH}znV z6}pc|eOnd(h8$LB8GSc2)#=cG5R|KGAuBX0X$_fzw^^`d>kqNJ;a>S-B6{xV9i+dD z75Yi6;g>0Z_7Iv@x+7*>J0WjQ!$?4ipj`Bh4GPscE&{#o$mOl^>`c99l#9*?yvpVw z?-z>G14_&n^qz~x_4%ydVI2^($%H&*advkV_K@%Aj@7l)5r&{#w!$T>!`35W#Xv;t zZ`w%C8ahVjZF5IZ3Pn`SxzlQw>r4m^N5sCHjb)$S(ORDLlN76#DgFa%qD>9`W#b~mBb z6CB6YWm3*vT}F##xDS#xfN=4B(05fQ892F^PArO5x#$i_5HNbH6|#Hb>$GpNjklhy zWOC7u>VmZwM-VQ%#QJA0?xsB`%YT(Vptr1_{gIkEJJ?_pf&e#cqhM~+o{@#f_oIP) zRMw$39T~_GluNCHOC^+k&iKUH5AxZK)My$r~6QO(_&{W4#rc z{DUhcYsazs*OztjB}m)}If8OgEdfyzEz-IrQ8tUmxuO(`$hE-=>D~gyWqFFiQfkUQ zL$}Io{-}K@f^t#40(0AzmBlJvmmQ;V=cM|BaxqOQo0nXc&$iN>XbV7}*3_-b=%){YsyX2(}gVCq|o1_$q;Ff-+ zwHxH_MT7M{?aL61i|LX+JC4dz&6?_QBk<0P=nT3?v3(cnFWw-lU$3U0jIYTMjEl-V zOpn?ttA)7epzUadQwp_9sRUy|W-YxdJL?|P@ytmn6hZA$_!WOp);M`fg`dIbXo{d* zR34$Lr$g4NdsTV#?TTxc=nRUWHVXVYuwIt(8KG(>X2rJ?1m&U<41N<1%AGIUsiE!A zPfaNlK`kfPQ-70;bz5eha2n1Ll#9wdJX)|@hOM=lyD#HS9HmeMwddgQ@l~>M)#uhW zEm3MIf^t!rhqCPs$lGu3ip)VMgOoxM)Gmdy>8s@O>xia_5 zZL*!?KM2Z2^$LhXE2R5Bhh=;b^x{woMbOg=#H7!ZHGW=@Bio~Af+8pvv-(b*cNJZn z$LmQ0-eXl>pZ~@6P&&a|E?4=spkGz1LYARh+82q+$#UX@gkf>HZDfGK^pNG{(MRBG4LvyYLqh2V2a#4F8_C|S#?j4GV_iN(OW+1VAl#5yh z@II=r_-$ZG>6MAGY7{}ZSo|Hd^l}&9?v$2K@5C95LJ-U{fW)gV;#qov++P^8glLQ) vwI68w9h`ktM(n*gS-$!kXO~hag6{LMV^Tqp>(eG#a6IZnilAKdlmY(-Na)LK literal 529884 zcmb@vbzBwC`}e;VA=m{riX6f~Kn2duu7HZ77+@=6p@N8tD9sTi1QW2ZFesG}TiMw$ zQNeDpySoFuXAkhbukrhNe}3=#@%Z`IJiK1dy{2b&=Gw!o>HfYGTl@P4O!c;D{r|(i zi548^)BS6m*(<}dIBqVMLuT8T=P`7xV zs6lz~@3@;oIH(nbZBWG)q9sr5eY0-zJ9t4?ZAa?sA6T)_sXuDHH1h z<_fB|d!Og?FIu$w-vqQ&5QTr&+yAEzEm4s}>3{oxxq_;S8u@2JTR)BONfNCqt*W90 zwg1oN3R)mBwMCIc>q?u$e5ugRdqc&DlKy>9gha(?*3zsGm@BAC{NTyc+Wij%w3wj=Je^nmA94kWijw~a zA23%?RZ(yMfq<5Z_V|Cu6(lP9!hi4qa|Klu{p~*xux%?!&j0%sghWNHYw3S(L8yW= zI7`6sTrtkIGbfxeSOQugQ8BvyL#`kJRTX2tf|$MXr?NhY$~v_w>#$VS%2jYYa7*2D zxui|IJ~ZH?*J=ut|M#AEisv{;yiVDqRpmPdN^Jr*@`~#9hWY#~!#r);;P?2y2x#e+ zw_B?^qUp!OC;hVzNDS~lprzmW@_+e&&w{Eyua0PmO+V`WML^5O`$x4Z7tZis<_Z$s zi%)6k*Y(e;|G6Acm0jhGmZ)yH0j+!|EeoUK-IXcTrJUZQ@_86j3Z;U{ipBHV%|Vuk!bEvYJW~f$(XC8kO(DGyMI<3lT&8dHxD@d%Ywna;?@%eA# z1FGtpf7cQ*cE|oI2W)d#)A611w6(j%zpuphtGs%rw3f1*xsIPN6lv3+W`wCB%@WW8 ziPUGu%jx=m_e4lQ6`V0xAFww#9p0>c?vtMZ|FS1S!mfU*mR=P&|F61&xq_;bam9s7 zn{U?~|BHYYNDM8huJw`SaOf`rwp4zV2E6iIGm}IAvX?;OWpxWJ-O@z*%LnYcP<8FS zrP<&$Df=?Aw+4 zd7p2Rxv0}QZQ6B&bs>BbOF#=GykDQz(#E<=3jdjas@{BwmiX+o_b&ok#?3gURpp)1 zm!R)|_5q3apUYQ<=lX`yKNC>3w@!KAT{C_DUj&>JVNPJ5W_>^lB<>$7pLgvJ_xsBS zB%tb_=Mt4(`TVh|%aX!pnI|QsH49dMJ_w)m&$)ucpI7Cy>#9y&{+WO(IFGRe90y&S z4A!>b8jpg1+1nwZn-;F6H+iK0m);IlaHO%hg6sCzerL7My^u6T4cmq#pal{mdX$fw z=_Z36|CxX)IMP@m{P!qrPG+1&pQ_{l#C+*tT!gEjmY^pyT;KB-0WFI> zdTLdXjs9&5LSpMxFD;#RcI#h0U|m6#(Ql2Ga4%l>7XkO5+lCy{s#1&J6#l!J0TQ|A z%Xb+WkCy*6Q^RLL6`YmWz6;mz*`+DkTjByoP59XlePZytJF8bv%3$ zOF#=G+Kw5g^&zdv{>uj>pz8hD^49Fo_V4u^TC5s6YM`m+$~>A9PaA<7Xf`7 zI-0Ci)%H(j{ITr;p9_i0HR84OldXUET}VLH>KcVwBBxo`zj6gFkbvWc%@wpj!qY5T z>!aVPO@H}-1XRHpob>_cSLv{x_PL#1kNnH|3KFZ@9nj9fdi_rRms~*=oWa>#!TI&x zw9eWYwR(qtJGVn3+_(Ik!D{5G|B@@Hf-^XqD>##_DUFtt{(9bf?Z2!mNUYwStfd#W zUHD&e1y$^>Z^EN#*gHu>iZ_L+Do?o#7yGt@=Vg`YnGL75<2Xtng=jG@Tm>zaY32M1 zp2>0C#7D2um>yB2g!-sdDbIqc%CzE}<4!g57v?k#CG#82RzXW;TJZr-3OTOry<}k- znoWi#&R__rs!SiN>O+0hI$A8etT&Z>>pocpEtP4-2RzHi>=C=n3|cDFiVt|F!*R41inKS%3y=FU1XNX~!(TR0>Z(VSNP9e9 z@BX?Sv{a@QAMg%|j`1wH381tVv(W5EZqnRaK_z);dXjC@rXr z!=HLZnb1<1R(w>ne}#{VULqXvxX%z!Rhe$>ludn9^h9yAkA4=kRHhXl75%uvM@4TJ zyX7`w2&k$|f1AIM`luLD;*b4KOgF&VrCG> zy7bM0mddo^qhemE@KG`Qh>Ko$Fa%Uprn^`n>Z4+Y6Af#R%Yv55wBn;;eys38$DcBb zipv&GVhE_JOrMzFiu$OSsl}{5Gqa$jGOhTinCB~eRICPK{*u`Y0acah%#pRIkBSvX zEHw_xf|km(;-g|Es_;>$N}!BGx(;SROJ!Q|QE_`#(H_cbql`nk4l)E(Ri?|w zhq9t6|P^F|J zS~+F>&pN0On688Epal{Y{wm@bDsrV=ogo2LmFe>JT-k>zGJ(mMNcGj z9aKR}Wm@r3(T^*9RP=U2*FlDWs>*cvK2h0+D&vr@gDPmLOe;Pr#$$z#icw4GI>-=E zRhcf|?^etVgsy`sXsJvqJ}Tyw3Lh1-525QILqJt!x_sZR>_e3rrt6>zS}N0ukBa%R z!iTaCRa%j*gA4&xmFe>L52c4Fr+%poEN-<=D0yKgGok#e)g@N z^JQp(1na}~S{PY*Pd7U)u^&S~6+9#7xJAhk|~XCQ=;fN z&cncsG`_B%-JnYg0&l~Vy{Mv6BK2UL1IG=y;Xw>18D#r(sz;y&60DDcHzUcC&W71L z@~SfgRKaKnj@yvtO*UE>X18?wE<+0>V3|11iZ>_jNmaAGKX)haoZE&nHV+sWavfXn_QbhTyn!hXUl$({^Vadmq9OP^G+CDD|d9>d`rI z=0VBNVt$tHTY63gqC%9pR#7PtfH1;?`$`sk=zTeg^*mX#D2 z$q-Nl<3Kp>K#ZN7zBnr@tt^~C3nXBf=#H#zIKM~;%R z_SX<-fdsr==D6JAdq}<5IZH1niXos%S+D+Y?P~Nl3vRp8GN)Y&B=CMfSvf2FE{vt% zxT!I*LUh61OkdMr0xghWeJp4&NZ2aW%L-T<#t={iZ-h9`+`~%nYu+x)bz%g87D&J{ zaa{A6tb5PiM*j?>}G;Ij*>Uv0!wldS(xssoI$B%F;pt-nVdEk6ZVIMeVZE zL&|&@0;-f<4#2PO$ zRk!9om!Sm`FvgGL&gT1yTby>PJnCFv2&hutkd%5;_KX}iGB!-q-*;2h`+$cGBf*q+ zHASWDKiQ}-W4&OpdDI1!&yYA7S|Gvt=(;CRbSNrP8C>1W5Ksjp9XW1>*L1N}N1{q! zyhnx>NWe02+)cj-(c1ih>cn14rW`OH4(5>KJR3!cb?dxPEi(Oqp#>6b49mF@8u9tC z4=Up$Nels1${Vs$Z+-7r(w%;bz({e$v>N7_ZgmBC>ka%daXB0p*g_+2PpoQw&U71s z@i&lQeI&fph-a_=R=wGGnui2b!MGfb8}~yadMx{)(rg(jK?@{cnK-Uy!$9$EtbzHX z#7qH34uJNMU`znV+0C0HK5bpoJfT&h041XO{!i{{F9SO@XVvTEiT<9QL@pMrT_g14j`cW-bvanq+7 z=3corBD6q)^|5BMlbEQZXI`>j#Sl=%-o7@>znrzT8q#E30Nk&d+paw4Bt`3 zd|a3dQx15e40FhF9oMuF_vHUpMM-@`Xn_QbvY|d!*Ax3Ee^CW5^I!<50_!fV-5HCH z3-%FLR3ke0i!hD|>|P`oImB_Qi+6;)k~^v~5tBq{fduPgx8rxA{;X%JpfqoWfGQYY z#BtA>)eskrdZQYdGg5>WNWe02T)V~v!lIJXDz)tlrW`Pu3g(dG?wf89+;<&Q%?_U> zLJK6=IDk8e(Lx=M1FG!p!3+UaV9!Wv*VlnZI%Wx~V+S=NjAsD*YY9dw&^O3;r_qr8 zD^<1jMTyV?3D$@4Tod7|bGoXeB!VHJ3dS~YT%=(i;dy$FYG(Ct5n3Pt%fxZh?B=Pf zcaBg+{9(%hMuZkf!1z15zuHrXJBRmEnZ1f)2&e+@JG6H5 z_~kNsjm=u<&lX`63V1h^V5|wp9e)}u-#q`(EM$C$2rZCceGET_WU+NK)wyNi3;|Va z49kXJM)Junom3&MBSmO|1S}KB^*Ovv7FRDcdpm3@}KUjnoNU%O~^Q(|{RqJK??jOw%Pz7U0InF5agSpuWJSJ zD5QVZ!AF)Nj0ywiJ`#-g;<($x?1(Yylr^cKiwG@{fMw#ipCJ}x*ycJ}Bkzg~0aY-1 zi{rK!wjnXCzGlXE>?J}ABw(#`+}a;KNSf35tO@hlGUb4=aWIFp9D#jFmvwWpa>h3k zp#>6b1YMKyo@Dm%1zBa2>oNpXfpb6FOOo17BmR>QW`#dEB*4fsa7HS@s5g#l)Os>$ z)HOGYsBQ_+0twc~n;~P#w(1+RMr3_q2&jUwc=Ua6>L~K|(#ouD_o|7|0tr|qjvFt{ zAa}x!WPLQtW6A;J^kEJ;uC8eiDIHLpHA{Dm04~e_j)^uO!)XF>vhZ_ z1PQ2uw*wrv^NNPti2j=8)2;!6mcI!lHct6wgX22=(h&5ZENfedwKjrAc{5S&AQZY% z1@A04u4lG}L=3US#=m~@Gd?fCW9~W#m)6WzZ(p|nCvEB~kfGV?Z+GMI`Sh-W(EUU4>E*qJlPhfy$6ad`MRc>@ zAAB|KD|+;80iHn#WZ8-zH7Nnlr0E0IeyfwFCSZMicR|dnLVXNA8bvhsY7}-gIEA3< z0+*;IrZ{i;i^z-BkpAY)3+H|aMetdW*fu5+D>b5jq*_cVVqwLkEt_`5i&_T|Ia3Q$TY8mIL~m*E=3hr#@WoPo?D;c`lqdwB3GS(mZiX7D0(K1wrHuTBo)NS}7cz zFb_Yj<1W-$An}uZ=HY2HCyCyLJf!KlPs=%^>V$`m5AH4!pal|#-^SnoN^|GeQXgxR zL&&Og#~n*=2QdUxvAL4P5v1nZf&9U7y5a{tU;JoEZ{gTcBh+D-FZQF)E&S9Nm8JM; z)5VP&(OweGjUk8U@8DPN|1CfQs@9DS!5az6W%4MRXxR@<+36yNl2QiFiuX*xXx~KT{!k ze^rrA1FNEOHJlh9pJ!QWXPm-PFUB9;Sz5Fwx9nE)@sp7Vp9=|FTLZ6%~ zEtzv}1<$?c$`DY+mfTOrlJM3?QNN2wTyW457v_pW@YD&&o2Je7h(g@t34i5ESY$!^ zw#`LHmJ5szNNinii7lS@5XhFXG*?55%t=5=9GXf*hJY%zuEw9YBvMFKVZt4?nE1{T zuNh!3Y}_;jjVG3P^=UycdN=_Y_He>p>7rm5(x3X!#9NWGhfIa@F%IH@L)~#{aaZAu z%Mf&@%o6Xq*i~5e#}{p;>3%o53en$vDG_?xl3aD_C*W<}L@zrYhd1mfn64g=Y7Ml~ zrl({FBDtLvZsctvBsLD9#PTy%q%696wSIW!bHApE(^}@l# z)Uu}FWl@tMpo%Sdgz*eg@5FL6zaUpg9WYm0@&RK$@@p;2(`9u&^Mh;Cb#P}_q1vU} zbRF~$oleG#O+`O%?+~B`6616=+9zG!{fiQd-%cgt(>9=uyN)mfRKYsrxQvNY$fr4n z&_uTjOkF|ZL4L5-M~y{wXvu3QO(YjqUqM|w?=b{a!ItH?ts6s$o%o$U`gE+&gv4l{ zb-da>-Y%&;J*MaY?=dfEGw(29(n?OA9G6|3@&X zoob3ozlSjdRN05l)B3(%t&|dVCTU3gpBmUGW)4csipL?eC#DZI;^%pmr&o3M=GmQo zqlFr>^xQ1`JZE*GZDzTu@2;9Wq|;k1z{t@?uui)}&pJ+&Mw0k2>iZ($>NTSDpBkhZab{w-=7Hxfw-XeqSxA zmtq7+PQ_bV>uTW8Fyng9ly(FMlB=NCGEUfo|ZF5M#I^?)*ZW>Z!`EAMb++wC*K^1%p z=eQ=@HDp+E8$72&RRk@NU~6~lR4cNlW*cGeF$WRuir`+0-7{Q2Voe&1sVOAB?858- zAi?g)W-V5e&G&wzQ|?v_0ab7nrRSpFPULd+%jjKZJ7ztHgz#kuZm>=i7Pjt2=UvaT zzNAgWO?2Jfh#{Z~u3a40`Pd*b{=jZ@|94$xje-Q}r~8;$)gV!JG#dYyCkieLOX&DeV-2~G_C``$*Fx>CCEyuPU4)KL_dCKd zZ&@_~N56Iv`mAb5iCKL#q-V?yX*Nnm&;kkA$LLo=d?aZanN)c1Ln8qaP$f)>!z(_! z2+3{>sE_X(!pZpLB=wI4yZ|kbfMbQ@K3D{k9Vxr`VGm*$0;<@OFK-%5a@}t5Li1Pw zS|GvByAF+lNbzZNl>A{eLqHYV9?t67WW~WAh`YUvX%9%SYpvm}ndIfyIJ9kCIzvDe z+!N7nmj;X@;d<@)UR6H|@Wcb2Yp|yuBS-iUs}0lnVZ$B@&;ki~#=&uKQvAq~fNb9W z$Z3Xvs%cL1@U?lph2m|5wqQTc03zl2^IcCL6rcqX?CD3Fj39EQZ7*JL`$~p@suP>y z@cM|}!k!!RsE^pe!DOQ0U3F;v7y()!0Z*yumlmtS$)4W59T#^+3;|Vem7x8qV9_Bh6JkYck^49uzXuUW67%z|#bdvwW>49oJq)!Y3S}yGZ9)K0ncY>jIgsi8T>OANp+1F0;=Hr$Z>D0coNr=-blx{t_UrV zV9&3NN=B1e&ApNBIgTNq3eJzTJuZwRI?YT`8~1ktv_Jxm8;-lG=STY4S)zH9&oTs5 z!8wMm=LP}fTKX$K^kgA3mp}rJ8;&EPLF7y~ncwHXiXos1&XpWjSoMRrbv z1ROW?reSS3xiGb<`ruV|-i0bSgVWy+>=H@*yy6R&NR64f9TITda9m%yesoP+CABbE z&a59$1y>@v-#xA&WBrI^{JSo*MnQtzk?mh&NJ^(xA=`#ol7_8%;YS^62nOj5q#9#; z;P18S2w&aeCA(MFc(-3Y;ph$JcUVkx_3?UxqjGMdzcy0Vz0^Ud`#AXqjX5S#>bbAgu7Su6;DV&d_g;^M-vk%DmhNgO3sT(Kq_ z6Pt)G>n_Xgk9~2;=0tSf)Pw(8=!Zu=iANbr9r={9IXGouG%8*1Lgz$hJzLV9*A<^E z_#)djnuBxIF=%$U7eD`X5FXz*9-S|k#kaaR1+Un@7^Qvlp~Sd%jmh$HUBv@ekH}&> zH*BPzjQ+fRt{&ND5avcMMXnv+sN3Bch)q0_P!*f{l!$w*L-6N;;=|BDdBR{jT*9qF zMFsKdkZyK3XT(a>#lDZa`3+~RmzIRaKOR8$?O)Sx$O{r534Sa3kggH7*yC#&>Ur9P zk2JT%9p`UC&lZ~VxqGef1HE)~b*IB7m$bY+jrpy^|Z#HZf-|g2O&P} zcSk%jGao(ALX>Ee6)hV?t&)$Ono7#Ty5e^Y3Q@JUYThs14$E^1y0xSeuWqfv2mFqq z)9DQ;aV?;sELV#ac25Z+!3VRXwXu89yZ$fKyEw|J@kHa14esCyW3cS|WT=*u&_vRa6U=8Thr23C`j&gY>p z-5ToTzSX2{3-VC^=fv?`*WS|i*||tR`Uri;(aZjg&1$z2Yt-sRLTq|V%L{j+tp|6j z)lR*oKaUE~vgO;{(6PVx5n?Uz$^*uVHn(tYwfG;F_u>+P=?6>L)F;_E(6wiW z)vu4p9q&0+FVCl^(Duh-gBkVN$1hT!kLuFcsx$tnXyN{ zymAVGeH8ZH?|$vD+o6+antwH#E3ZE1fbv`nU|9Ph`PRKcc zvY&YI>Z<*5^taup-B({q{QP_XuT0Y+KQ+V2#Y?*QExv*-j~%0~pYTC?y6*<6HT99> z`P8qHb zX|9CReCvJ-uwzOrI%#=cwILYs@7MLs=C40b=X=osBbJ}PUlmCg7EhER5b5g1|?pE`jVjjU1j}FSZ?rk4qoxK65-Wy8lEUk&aZ2r9Sa0?Myy&2#knp5Np@Av^_w;ZU)|)ISyf!Qz zzx?bhtlMZUaa^?=C*oq)QeKnOhCJ9Z6qgcF=-$089`SZ4b}Q~F*!o!DtiwI<>h8US zN$Ul=a*he4E!fRoSXHN{&|+p1wu<&f2YjZWR^69jeTQkNSI%TqvT!Mm=`#;quA#Kx zhN&9jaxfNYzRc&FJc-5iMx90LID2$wO)PdPxrFq;+Ms^cvAEB%QgrvJ5hcDf(GbT6 zsaQ9vbbp1D{A6&e)LRPrYyiy`64a-wF3=(gV+->HW7{ zaO=z-xM$;jLVMAfmfU5i0sa|33_EK6?^i-@E(^803}Jq6!8<1ryN@_s7}>hFF!gx? zC9)enz)K&xN{juXh|haNDSNGB0zxSc7SN7MH667iqLX9}m#(>B|{L`qzkxCc8d z?Io@G9z~!966fy37lu>1*$0J)8to=8dOSfgejP>(HxH4PQ;TZu0vsOWsZGZ&T!7Cm z^pwiJ_Y+JeETBZLnVme{aJ&@xGn_yRBw%jot$w2<`HMrGv@~Qku^Eykt$IxBJ?uIgRU`s?kk>?~d0)giviN+kQWp2Rbw86HlbJN1YU z-gDL%kEChSHiT8?;{(!5=)LM-N_7gmr);A zcH2-NIWN1D(hPSTcuGZ}1rj^o4aN0K`wA^$I#A-dZ7&+n@Lc+I(}W?QDs|dWt&i*p zohY#@bUfMm=DM_E&>NZT3ewID39G8$*Uih*AthCD($gUPX;5FGaLaExiyoQdO=`3% zm4s>EWoUuKhhRUfjDOqc2Gqy<&{1Tcttj6+xV6?&UAp+u`6JlQ-6FQPuybT+2MYllJPQ@lHF`KdlbKozV7j$<)X7=(g0yrTcw|iS2W#t=NJgpo*>C+YNk(=dEi}fAdF7?ZR3p91wwnsE;kp zAJN*?&7MM@Epfmm!!OIw0tp?9xwx@zU*TisX-cfA>rY~P7fB;_9%l%sy4rBAHV(u` zxIl@OJp)MCwPVuTa|dN;frRbxXdFm$^{qhpE!O&`GszP>Gkj_DHW^wVVZA;ENA7nM zPM=&&iSZ9+k$D!mQk9--83L-BZI98;d~br*Q(`v?B>~}vIM`^iY<)5wpPS?+{Hf(C zO`z+b64BQFtFHuUde1o~nDi;xDs7)QUxpS)yuVTIW43xN_38LE{`2FoLN-JuC@E(qX^0Klu8%gz|aDT{lCkj z5H}b%r@4AHJ(4`Qa9g@{y_O6KsDd>@?}|D{5Q91kr9%xnF?9urCfCaAt+mcT>chWL zII+0CNNVxE7ehc5tT*~S&T9=>wrppiVQnJ8m_%3$?0MqnH5y{qI7YHtIs!urBw+by zFQE~ppC+YCD!|+c!Z&cD)M1M?2NR z&;oBQSsx##Ye-t0FJ3vUCgTGV@RpS0MsOOk`co8sYc!W3pbFLqjqzHlA^AG4xGZ0X zsVhjp8yfnqwpv5Rc&Ksy{^|??Rj{V%>|>@O2`Su_?(_hj+(yY228;`Js0KeTLsp(UkB9PaDXT9{lln1@fI5fHQ-1xd^C zFsCMr4@e{rkHe`+ZG`xG6RD3YCK}RX@=Dy}F-t&I!HhT@IIXRK^}Q(3_>zWPvw0wy zygwzmjf=r;Z|Vp}^t#ks01XRI#qu;S4Ye=8jz44ZWUlO!H;&zi*yr*6x zVQ)?j^>HykL&R58@zD`_7!ptgYn}dz$9D}mFfK`L@^FNNTEyU|_r9RLPrmXuhQ#1& z&wn6(mI0dBHwM2BD?=N1>miQ2bwfj%%(murmsiK5V`H%AlV_;QrJ862je5Dz{}mco zuNi_*;yC%EhUA(g^A5*96+#Onen-+;uk#)q_@%tjul}YXi=x`|-A;63as^c|haA^+ zv4(t^G!4xf;>^Q$z}l^1@pAbVT9;$_*ZW}JRt-6SXaKS~U#5m{ija8wE(Q-dcON;e zR-(dYmS{-Xa6J^(S4@}JhVXK!>~B4*XATTE+9%ARz(q~-4BpanHuGm#p9_p zccam|?#Sv!JRZDt4|;UAFM91Ak7s_u=*0~s=I(BV`TBfUH3GQH?Kw?vRA`WZ24&B>0iV_F!hLMM#tc1jtH&Mqui}7Vu9GbRxA|jg?<4YNFsKvO6 zXcV^?pPrC}dZhQIL|p4|GOLA!P`%Ry#sZ1kCW~<0SIbb{V@mvPcxosS^12Ck`|Aks zRHakrWw`d^X{hs-zfV~1>uBVakdxqyYs?w z&sDgG+7vw-GXZ_@UWw~=?|{Z$n)ui0U{Gi2 zaXCJiOpZ_s+`}#m0ac$ztiablbVV;GD8vR!dUov8MTlGLB4m23!nK_o(D*_9QNwzx zv1LjN^!>;<1ar%ACk%s0iKVr$G15(_IdnDFRW(EPI*dbB4N~zejU_?@`XaG!Dz1`P z9~l@a(dyl51rwcl9fV`Jp8ze8&_A1sADY)j&9c2H@s&nd=ww<5j<5R*&;kiBel0%q zs0v!VX#^!!ObjNC;_ZaaTSWm{Akm+m)>`~-hOnrNbG^2~Tbsb@=1eT4-P+XQVM*k7qSN^XU~(|4mJmL2hyX2+=tYS!e&_gc zbKNOX|9vpIvE4-IS-&SkKozVJ`nA(?+IOop5^kgpVd@GJ?Z&LfQ$FA0?VEZ~AFXEv zlf*tof``NsPzCFa<8E{aA^r_@h3Q82UR5($Z$ut$qc{J;o-5@q#6$@Vt}LgZmVfEGw(RN0Kb4?M&B?X{wWmnxLpsP_W( ztJRMopsGpiX57CdnYa04Pl+yNq2zs^pXkJ(F2e5IE!f*?FMqju8#Krw9rrN{=2Iti zM3AP@J2a~JSX?OztmY~}3nX@AZN?w&FXQjGQhe+f97+oDLu4`5jUk|l&DGRDVI-#U zPV{q!oiP7V2EKmRmH*{sf)4M^ptmRe_&Sf;pexQ9Sh&5Bf7iDO^>Jx`7)kIth%)l+ z1!#f9sGxM5+j2VJ!?8Uj*2dA*VA3lTGqfW^KozVJda`X7M%vT+Ec{($>IxDTgVJ%y zgFxO!>_B}yZ5Kwi4k<=Uk921UsDkxIPlQ`XkX=odBMzAeHqqI*B)J;D%0nN?qqDGS z6%*b)r6DqxGI7e{#eDtE2Gqy&E8%3s=Cx?*0W$$wAaTPY3-@nr#;;${m=Y^bgp)hX z)+0Gj#Sl<6qIniR5U1j||5S)eS0c!SiSy9M-1*ZElf7c;(*0}eSxUwOV{FyNZ zP4)kSpal}X7q{Wmd&||+pI)a#^0r7a?(_yUGVMNs7D&7vu?-(EaN>>Yo}>iQjUpZc z`=T||pD_efCH~xoCkNMi{mr(defB8h=4pn2sud@;csZ;4#VIkfza}$D_#kK^AC4;T{AnkVt>D z9T&RyR8RQ5oBAlA@$K`IJEO;mM;QXD*j%YXHKft}nrK&Rx`Rl`#iKX6IM(>!$UjB7 zxcb~w$3c_*`K2_6-K=Z#yQ_OsA1O3K=&K9;a=9oLK?@}2War?+*Zw$~)u-RJaTA|J zkwwO_XkXKKhJY$qBOLds4$al{=4jB4bxd7BqBJ81UpddId#qD@oHo#q!@4cdWQPq5 z0adWx=sPEU+g|;=2I{6uzgPq%hh=JAn2RHu*KvHGrbNAL8KNPlW{0B2atj14kT}sl z7mqUfqc%Qyg5D^a9;R{n=D&F-(=r|sP}S~RE_U!=;P7J7B}&wz@6MA`7xGPqsrWzN zbMfTKi`2EehuF5Y$;0Q`ICLwqnz5s#ULJnbxv_(=a5*LBpNS$LvW}r~N$vTot#a|K zi%t0lqdVE%n3jvbw)(ElJ6O#Q`lGSuqK5p8T8lPF9eHSh1oTZ~Cg`^Sr{4)^gn2ZR zE0`1bBs$J7YRJ_UUwKW#os17iBpBvl`-ANrM(@a>hHF$7exbv5R9 z2+_GZO)xRPs`jjxg*Q(*&P$$c>~2MG#fR%`;-d^g>^}b3hO4ca&rkSukotIbHjHeb z-%;zWy03;7NZ8ijj-zMIo8;X6tY$6aQ>o%r~-WV)w3U7H-|Eh#wu8M{{+{&yP%B zc}58KiI>bqZ^9=#Rzu(G{IVV!un8Bhs)iihHmhOO0)0Q9>_d|Ihr*Z(YYrM)reRmE zHsUvMyWVwQg9nUmgG%Qda%?_~#!S>`gKm1w-%aQChvUi5)~|)91&0qp3nZr7uEFhM z+Mu5fF_gGBdMwFW{6*MO@Z=!0KqBb#a-3+{1=%L2Q{pQ>n&@h(iZy+A6haFm7R4vw zOO3lDt3TQF1k$j081XFB7k^|&Fa%Wj)3}UbR^1W5=i*NK8^5nyiSV$MXtwo2A@PdG z&VNRslG-Vbm&JJOQg<}!(ssSw^$QE|zW&3}8o%ANJ?gb`Cps!)@%h)r5+tAs`lH|D z+#5(_uAvwdnp6lakSKIqiswA(g*rTLNqwCAHkfD(Ym4ue$1wy{vE^u-+Jks~ZY!?$ zxLyeJ4s%%jaWwvOX9{wPZAN{pZ!40F9+u*e0Rtsyfke!{U_9dNY;<^0B(2?xV;x9~ zL~GHjxdB5!RnMitxX-iMsAto|o#|g{>eZfH9f-s~#`C4e_G55KS{zz5Z@8mD)ydfK z(mb@YO_SY_rf**TY{-!OZsLIIwIyhQ#1Q*n{H4bnRJG1~Yx=vj&RvPa5nFLlnIS_! z6`QLA^%@etqJiRk&ka(F#u?|;OhRu=x;gs)=!M6HFGYnNt@cbz8;CD(i%{25uC(M^ zER4yMX6|C0h)xo;K*Dq6F#LQ%0veKWm-gMZ7h95f2YQR+Q8u zP4NYbHK@_1FT1DgH^sdT)}Xh&zVDuX-V~eAbd>~STJp0Wf67Hy$B6WRQGymo$e+4k z-3BXA!!x#f=obp^HOPR-k)mnPHim#ISnKrHNTwN*dAdWzwH~%idq5&)kTbmzNJ4uP zJ5V37OY4%B&Yt4)M_m~Ls$kpD_rWjE<$@g(#N)R1Ovz!Hwok2xhdl@_D z`nX;7h@A4!UqowrO3(s{8>fFtmuhW6uiQ4!`Kn3JopScm>0)upVF_9wp;>iG3ZIdM zgviS@S5|G(<%Pk4;-1wW3;|UKdR&lfE@dK}^UB;lwD~P z+JgG{UTdW6We_IjC!J#msCwHfTgofiiVm0@p*~vs`N~_>p`s*Clb{6>U*rtQ^Z8b^ z+qE|Jk<%ttPH7%2uDn&k5Kskcn*K7L^J3Yc<{Z&7%UgmLNOTN7C6$iNLK!w`v^_SQ zStX0XLE?-a!x;jq*cP0e5HBUy*NCd?+q98jQ%2^aeGxkxm1taIl8+|#PjpaC2r1M& z$wU50%V^1~ImAm>>2JfmFnJ|G3nY|ucC&ocE~P0YhWCn>mOR&pc6~Fo5tx-0MU~Yw zAN~2X%>q7&{vwdIG2VDeBc7sn&(H#iA$pq%*B!}2rehY-lKbl{!@0dRqQk6n3;|WJ zhteHcMggA9X~d#C^O?R2iBne9q;Vbc(1h-vs1H;14cs6uO8n#%%@9xp`!UA_Z|F-N zwd*LKd)<)0m_!(>SS?@@?p;F^oG%$*`hI?K04aIfS60Uw5@>S;|Wfopk(oMJ(eo3My+s8(c-CZZhRmdwDS|Fj*DiC}5b{4wS z!IXH~Yyug+(MvANKhF?Q)jcx;FEF-bXQ_peFKW|rWM2;_gDel? z4ij3+&;kiIigk8g2=x-$6Xc}Sa;J5|{J~GBIsubS7 zvk|7JHBrRDbO)Z?ISxY$B-pw-7#%@8Pu|9zzLqfrRJHmNi|sUa!XN#Uv^_!wh7)C&1KJFNXlq3LLO($_6Av_Jy(V;a#I=tF{Xg5>%A2tz=XUGJG# zubGvweexFSV|VxQAG|QtMtFMV z9rcmnI*jBR%$AKc-(+ZE2xj*Ae6ByKnmb!=bY7o80?s8J9fsmM2ONaFw$12#m3hUD z)bSi6JAJ7~pal|ew&S>WrcPv%&S1Ib%vKBmRnyk?z)k(T3pb1%sE=e@o=n@*S-x;s zMW6)|Y+ShUJ8SZ}tc83*wqppWS{84O&u#A|B!8!0Kyg!=YshWC)%evnBMf6aV8k~Y zUov1;6xn-YH{Nz5mWeNc1RR^Rw~vS*NyRVl9Q2DJpz2lUSUfwdgJ2WxO2^=gFJYvE zx(qi+ZXrVpB;eSjH`SAZ$s51=@`pVm83L*X)SQol)4K?d&JLozByja?a=UL`x##FG z8CoC#$0q%|eYaB~c3ZI_`166~lQ zwr2`y@=-^g6j00%P<4565Pm~?2vOt{^^v?kf^4$N#2vR8%Gr1xKG~oQ9aGCp{LSwT z^RUZV17U@)hNowJVx72)JW!gH){(MW~_R9$zbt5G9k zVZx3-^h{>-nh25;a34F*`h=kc5^TRJco{}=`c#+g-x_+CY{6D z$P-h7WoUr}>^<}w#db4DtNhOL(fCw`fGW$PNIXUEDqMZEf%+JDY#O;3YbhHfY?Yw} z60rBsTV#1Md9uEvY$2Xt2&gi)@WRgw0aZ@VC*i|=dI}NC>eIQz;>JvJYtC8x2&c*L`DXTwwnI1@`_% zb9KDEhCDB_;Oo8GjG+Y*Fgl6;?uStnx$b{nYF+w~A)pG5W*R|P97S3gU6d>y5)3Vn zfYD;~m%qHC$nvK>an#N83;|Ve%+tu40vg@cBTK4!p$ijp2MIR1?fPR4d9ZkuH2Z!Y z6W0e-FhY>V(9ez{x946!R=Zjw7|{e{vDnzC9r_ybEOQ6q)2r~%0twho9Jk3@Lnc(6 zivA28hamw~E(I~T$J)!tX1G40-+$ysk+7D#`93p>F| z1XL~QAB}s@evbNk5ZX)Hc!rZ}@uTspYmPFsKmxWb{dyoigt)Ggu~WbC3;|W8edgj( z2~~tfFJh>VlM6#h_u}h#T$?^Jv_JyR;Pe~ClsP1NOKo{V&{T$isud=4@gL{f!gope zTPa(rg^*dz>d6PJ2g=X_2{?n(zH2v|ENNgRPntZPA)pHGQRy!T(5RQOL)*x28VqK3 zuaJOqK8<>zzxR5%yN$dvE|4Lh3hrd-`R=hG@+GQ+EbR-Dp#>6f&Zlv&8Pm!B1ZTNw z;wpxKD)^pABhTtiBi+oLvlr{5KQ>2MkuYWG)t!W)wz<44K|i(H9axDW3Bbsq|?zL=l6)d%Yg zAjtSeEI+#DINa>@VU#^AnC9xu?B=BBv#IpkJ0}7ykbwSZblXuQQm`>bt~$+`A)qS1 znHOGrqy$ZWJAnGoAJ&?@byy;=4t6Ba0tr|?j{7mWDX|%vA)nd95>QokU?|=&?JnBw z`HJrP=1gisqQiH{`%O9%Xn{mt@JPI3-CLC2EQ%7JlUtC)Wk=+o!`2J|RT0J>_-fye zC@6O(J)zf8wId--Ps!^}s0g$`B9{~7WE0 zJh{u&TIBSj3Ap2DeZl=rY@x~ZG5Fb1P6%sx(0=rJAME?Q3|*)`l=iDL#fWHdww#mI zh(HS@3ObL+m#@7<4SGJH#FzkQ5@onr?qb=HA)snoFJIjJ&r@_y`zs!sI}2n<+eLD` zcXI+QkO<)?*dQ|9{9j^SBzHu>T*DEh2le6on8XQRmDYManL+ zi_jw4_eCj6_O+y>kR?UYM$SDm)>8H*WZ#!8k*%-wH@Dx*>$&E6{`2zryt~gi_w3iq zHT3ZHl4^8 z?`cBY|73^$K~&lH-TyQ_E#<4*_J^CmOl7wp3~{Z1ZGnifDRY55uO1F zSdRJpqlpt+=y(Cqp3MaUy5Mi9P$c9|X4a)madC-`@LNFw)+u*Kl}85Y~HLF*S_^{LLR-^yq*rNtJsyLq9IZNWJ) zoNRa8icDY1r)!e^5qmdiBt|cc8B}0?2AH>j$AnF+Sk<{v*ek$PAfQXk&(JJ&02_R2 z7fwIXgTeeaFfY!GfR>cO--ijNQ7%-?n z0_M)(d81AbWjb1^_}JF20s&p{SLZp;o?EbP>1*&0lb*t_3kjI3gYSAdI)GUzHsCir zn>qYj&;`o^&%YaE$KEZSizoi>Ae7y}i7_PZRU$gFSrW=IFNsg>SYw}IIIW8TgXI+x zBcDZ)9sN_0ySBvN$F(;$EW)Ha9?17KKmxkNY$Tuh*|J6p8sOJ4-5FFMQP(|^JWt3# z!;0iRkT)()VGk#+!xJ}sqA(W<%#m_1X&HIUb5ohjJi`h1&NEo-*40>d&}#}6NR-}N zK~B6|jm%oz;6!&5C#DEkjPLKR&maL^V#}agFpaewvkn0@knIt3w~oj2&ASS1 z2_#@S=Id7mHZ0v{8UFOXqd-6xZ29=^gd~0^Quqe!7}8oOSCD`;O`#x8W7yS4Td|>b zV}XFK%?|No``iRH@TfdmN(!CGGREcLGuLY=R3IT{(y6zH_ncpfao~na0s&nqiZvvr zMJS4$DEFKri^sFcCO`1Kvi)@J#&~jgX&_SSu2elvUQNDEaziWUY*5*j#*vdw5oo}@ zEu6Sh?8thy_>3b)W>Tm?V&2JBq{iF}jb50>iIp$Lvr)_6;5<7?AfT)F{pDothZywj z;|@*)d~;-H70+>(J;f9%kZ5zBXIZ%(h%7YnY1s#-#d|b-K_eVx+g>1`3)VEgTfM<(cG3>xnul$L8U+d1 zcJb3^0pr-d^65CQLRTQ53)X)g%?KUMZrAzXZ`WE1EdwOP`ca!Wj@@)yj`ebz2n2M& zc8t%Xs>idb0bB6Q2rUK`NWfaa_g{UT%6|3A#KlIBg*FkoU_L263QwKM=8nq8f%Qs- zOjD2$>qj#`dv=Rn!4~&E38e(~$gqU+lSuD}vqw{I;wxjn3ndW}uy0o=T3b1=GmT&1 z^?LUO0=i&L<9+S*5p4OCxA^+{Cqj*a1RQzt1rlK=SCAg&3y~&sDko0sOkv}mHB@^Q4G;+E zde(LmIpS%Lnr$7y3FVUs?91Ke>e65(g$g9TnIw>zH4D&{%NCqCGQo+3G}2M;U)E3{ zpi9h>)-QNGOGvA)KKgr`(C)(T0b5kQgYN!hHiP}fL5<@nR3IV#y6Trx*$`5TgX$6l z0=i&}s!+5^o53m)-{3misx59L~N>Zv#SvsfO({c&++A!ASAK`AlxdgW$f_IL&gTkt@YqrZV1$ykU=FI-iL zgz*h`ri?AdG&_Pq7o@k9tRoN81JIN=Rs0$GFBdZHm?L--@uX0J#819w`&3(3G^F?? zCnD@T*xF~=IOOUofq~KIBB%^M!0iaBsZ-=qb8eJD$XB-GO#Ic%jnz zFM+hF-GpXdf2Zodn~(a!QqhXB@=2tAyB4v91tam`HU$(akZ|6;iuB*V9xZj3?+n}3 z$%l2>HyIE1+Aa{#HL!3knfWCF9iOeuV=Q}~`m!e;QTT=B5(*Va^!c=bjM*ECG6yx_ z#Dv8G%@dz!AfT&R>1N_O*%Q5g+l&)gcl_D=)XkWBcc)N+#Mv#Ih<5p66x*#n zC*G3))^1KB{%WZ$5YROL)J4j%ChS?Bdi@{IP4d+?R z>wmy|jnWBJAn|*B3h6b)6n*V8h5x$mOPtyH!T;gyH(m(@bitNSp;-HS9{Z7BjXhki z5vV}oM}rjd!rcsMw#fScRxX{xx=pFY{_k4}Z6b8R_L%okXXdlEY0vPZ(0W2k4T;@O z+sKbq1JSP?@;I?*{9LxCtQuc_U?vdI1=|%KY1p)Y)ob_wcW>IBLIn~z(aGe^zM*JW zt=#&=cXr|HiBE9HZzBZ)x?sD)*N~lES>i@TsOlsH&HF-6de=4)t3)!N} zmDt(6FM$Mf!E(&s$A!hLG`SStu4_u50*UQ$JISrDO;Cr~?)(}1J}zV@ZLZ-p@4W>A zx?nlxBbiBF?3deV{44dd=X#^^eXy0cC zX|To+IVZ~NySKM5W(Nux9_;y2AfOADW8ORO@?nYX3vu`Tc?2qum|3@-OwI0v2KSQp zm-HLy#q5obN@mfff0Iqm*2fx znTpyy=!DAB){uNPzQ|*d&B0v9@oOtpkly&^t z8&8f#0s&o4vsMwGPN`^zmOS%5GFbU20xe#8mn=fyT# zK2cSkJ1r2<)$>F&xig#~i=Z-2Bn@52#ygymYK?DEs6gVUQ6xE0bq?LDE8s*1bzupy zDP(x}T7iJBdM3fdX5B?}^|Bmkcn~&=H9ho)v@iNYp#ll#egP!s;%ziwVjL%2pYuCk zensLd5q-$;H(N+hYj-s1eK!=5vXK-x#h{bv-BIMNO{8*65E}kV&eE*+DwM@P4a9>! zB@?JX!hGv`V%{w+kYqO-1!&(t!BCUvhUONaK(^)0s&oJUMweFjQ638RWCSE)!d8ynOKY> zubrS!fyC{IShBI`2wJe*a}Z5_TPzUJ1%GLN_ZeQqPQLlBy7&1ag$g8KZRVLHKhI}*BZ{PYX>SDry2NOB zK&mrKuHH_{X8)p4fds70e0;^%eLfx5rt{k9Fi1cbjNS8m`WGg#ITuXm_MtjLj2;qV z%aAl@9P77pGF`Hug+M?T+=IZ!yJ;cJ-fAVzjngG?Cj87TnKXYm2Ay5m1vT84MEo94 zM~{&auY)%Rda$;)E}{TZNnxpmD+sXO@F?wWeWRywVtVyVrXMtp+De}V0=k0Y zg30}MkI?gmD>y-NX0zgxy=ZU$FBB?}XrLEH6rnfJDgAU#(Dts({qrY69Uln#tD3aRg3GMm8JpX)uwA6N^KtNZ( z;W)B|-_tU^TEXk!&jF$AXVeB%X&pnM0*Qq=eC00k5DJNqcP{Vd*{mLK--dcl;&(5B zzXe@Bp({u;T!gArx}3;!jbKMdm7`6MloTqE*tm2hvD3*yHJ)<5r6D7hu!og3=-kbp z1QO6SX6zbL`#cTpVgoqwBVq|#ch~^8NRA^=fdoCZj*K|F9wqj%*q`1NfwcYYTL=z{lY@Ql{m!q~B< z2$!}r5N_IlgqS~3Z-Ecfq-`VJ4i{6ns}zpz#T}+S*9EYcEh9+m>s=Hokbv_9zVB5# zn0=V%QS36l=STKmxkN9HvG#(QMb+ zx2WN|SP3eSfU`-3qIgCW%ly(5PwJ)?a+pFF%%948=TLrH_G(*v??t+hSrrmuM$#=i zLRmqY4gR&*OvsrDvth!lmHhO8Zy2ksb;5H~zaywX0^Y~N`@w)PmXI+AyJc1i1a#?l zNhYq>9Z+Ng`KH){nXv%1zrA!lgTyHkw{Zoj}z~g1+jj~Nx0o{djb_moNK?8lz2L#nxuxD`1#6@#Wc^r z6Ph)lkbo}3R~v}g10OWw<9ps4wA6$$FPA9%{k5HNBNM!-3I2wBmqp(&ri}5ym%r^m zP=Um^h&0l|#1QSVl`}5RrJ+poGzwqKu@ngCf@Oi9!fqGFW`6R+b|;b%R3PyrFO}pw zn;{zqxoub7;@Lvoqj1w6T?7KU;24FM_D*4J+~@$@%WkbO=7faDvu$MJH)~YVPtIq# zsaY6XIWrRHlzvgczXe_5*eBLLjD33LkLQ&HBd9<^tRE9H!`Q)qKS)<>SjqcEIps&v7Zx~EF;Z$THF>G2WS;0ShN<#fE{#$hE? zAOUaf;-%zK1e>vUIQDdL6;_I%3$6k2RkgcwSzUO6w6A-eFvp1~SVI2vI*NAvJfVW~ zD}L*OavrnWze(jX@RKl)g2b-87-CYFgO*Od!b|(uXA4;V89TJ8=A}SD7o27AU99Kk zv2U7WlsVzOF#mwWdA@QtBxfhGj=#sBansM0P5*WqVhtLB)^Rf=YU2?N1R3P!GY%MXnwG7b? z@*1)}U!gy36NmSt4pZPQPbn#_6 zTa&Q!s7V3=T`;byP%Iwp&FXbY!ZD`>~9H+i`MbUx9!w*!%D`%U=G> z>ehBVKC>l-3M62w&38aN4PttZn{o5LiwGp3OYGIq*I<@)avh%8H%x*GBw$~{cej;= zvX~J|@R=`Th28+V;C+5Pw!JZoh3GBBk9BtlH~m2Z_KAGuF35+Kk35bKwu#cf%y=-b z9*oNIJS?I9Y<`n$JpI;M4OAc@X5V{N>&MPNKZxzy8A_0VE*O>LQGF7~8m&vipI>!8 z4i!jD^V>&4dtOu-1P$lq%GBGR8K|;x``QK)B%ljMs6e7_*k0l}>#l0F zcM^Ywi9rAhGu($)8g7vw0bMXEr%)V=4Pr%k$@rN;V+~Xw(a3ub*?#7^>c5IZ{23l0 z0qpp@Oq`aPD?tLfU{sEu5|V=0#sOQgOUKq4s6ZmaKa<#wuT}kidWJva_N4%(JhKbe zmYkI!0bMXE$Jg|0`TMw(h?o6nr-2G222I>eN`e)r=SDepcgi@BrESl^)o&k2kbo{2 zmE)Q5OoG{g*e$r%0Ba3YAkj=`7dczn812oJM`X$2fvkn=4t%ZVmjnsuf>AmCKBfdS z59`f%_u^F=s6fJVZw6Vf+X`(AlV|j!E(fwVjkn{(m8}RQpbN(Fc&unuFx&HFBeuKL zTnV#Y!W^BjuJALwUqV?)Vl*bN3zSfS1kBgTXY_nTwzcyT9JipU3KGx->k3~B{~gZu zrq05xccrVK0tuyKHhHmswQBhgNB--+7!t;UPK9H)k_>@>E?8H1ZmR#nnf-;Cc<=05 z6;vSc`Q!m2UE8SYR29dc@n%FAb59M!i;S5-Ko_hld~ekIaAvV;CVnxlHG&Ex%$gn` z89h@}dtBv+yWaRPb|olQij3Q@YP1QIA6-Zn%+D}@~JFIHrDevsRY8%F8 zy$!+kqxA&>x?o-5^?VhNjDDDnU4AV>P=Un4PkV`nlBpiYyyedr*guTXd7*f5tG)sO zU9hh3TVfo;+1e&^an$8y2r7{1uxk(T8+b*vCqbU8MewzZtqx)M(;=lmKo_iCe3ZfS z$pkg;h`T?kkKvpX<|l_)+Igmsb&;&slPk!Pb`i3%Lqg0+?lC%&C0k@8Rf7Qn0bMY6 zyh7n%8o@?vu*54J-U>5e_({b6e4|qYOZaGni(Q&ws6ax@5x+MxoEg|5yspD{VTKJ| z;wU4Y&seUw^v3HIZ7@_I0rTwhu_%w97uk=%*M8L#27=$Nz>0_us z0^TaXXOIP9ENAQ(Y?a$UAfOA*Sos=2S{O^wDDfYKRwkz zAfOA*SQQF$-onj)JREC}?}VWO3Gu#(AKmzzvv?Y=_oJRbKo^{`@;T0bq0ENgsu+m$ zF;pM{@9f~8iqGiNTFu5ahII%M&;@6#e5cdfP}XzXMEsiGP3CkJR3IT{=6?KP33Kk)30n<2E)dWK`zyW= z;8PSc>|cjMH@8GkfdtHfu2A4pOIY@s~SxxGJr#v|#5YPqtD}}<|cnN!&+YGlHcnd)V67cQ`-d^>MWKJJ?<9eIQ z1OmEX56Aae>Ku}^%q`f|(}UUIJ5MzkrJs=FAVX=k{sO7@yPrsH<|@HEOPYzny13WfADl>t zm`04Ntk~t%{TWmsvH#svDL1wmkM+p8sYXtmM1GoBvu$dTfG*wh6`EI$ZSf&{Is0D9 z(*LBYefsQn+E`|k5F))k^$_Ks+hDJXum6sJ0-G6)smZC0^qJQy z8a{D4g9;?{u3C`;2^Y`^rzV`(KP-*@s=i4huFn(*=o)gsj+h-RL$=@gaKh!X9lbfO zKC_divNhd%ld~07=w2Hy3DCi1({>e4Us6FgVjDCy%qb=2|u zOa>K5gdgipZnwUOlB}O_BB-7t4S)BHuKhSiAfU_o(*V-c{TwQfX~92L7jI{J^wecK zf64*|6-bP%7)XpipGMC6OA!Oc!1vjq7WLuxP3Ee;#0xAj~G6-cz#nM|(TCFn!jd7P+zRYLpi$e~>~%n=Ca z65n8x=z6RscqldhHjP!Eb0!TUj-h#@m#HjEXA<`b#i*_#Mm598g8* zRFAdYZ9or?n8Ba|iJcvt$vF2TXjan%PH0VP$aW-tp%-*4SevdR$ul!;th1-JbS6km zvKD+tYgTO6)U_W)nmzl9Mj0r0X)kP1M-AJ3qP87W3@VVAx@R~UcI+j}J@|%aZYjjS zX&2RVI@cKs1a#eu8AnvRpQ4%xn|Zm~()$%HZTXOXX=cx$0tpM(QDiEvL`j+7IdL|t zhK5ePNIjEA2?TU`ZJtabw_HIFoAlt{yg>gRZ5Lfe+bx^OpaO~YZ^x2Xzt5vzYkG0w z^|DvA*sYjqnmY;vba{=RM*cJ{L$^HS+&dxn?oh*+JX+dgDuW6n(qB#_)#;~@ceYHZ z6mMus?-bh1R3xD5Tih)2ZXQ8oZV)GO?$yx7sqxgV&2$D8NWjv=BfRapNUQ2wus!uG zg|=PJPyNxd4)y6eLW2DY&&;hKrzx2^kgeJ?MCfrKA^*F@y|1XVmX*ZU$jlyT+TQNV ztSfmY0nkT5*R9z18rzA_QQYALyj&IZu+m)V*PC5HY6cZZ$p7|!{u&u|D&$1-l|wZh z*PF1Hw!{Aq@y{g_Nnc)|w6?1_5%p$-G+Va=Yw~U!+g27Str>V59cUt1!{_yQ_es;| z_I(up)QI;6@jjUvg|Q*)USiLn0txXMc(<-*ie6WyNOBMe=#u|!?(qaA<{9!&HDG>I z&GZ}fSl;g0Oja)B-a*B0KUm5CUNYwzO7XQ(R-FB%sTg$$IU282@;HuakfwU_U1~hZ z<1ewM^<@;+B33CACwg2$tz#0D!8iVBT&yaPUE_V6c;z!lbNK89s=a#=g9;?%e{Vii zjud-k;%mJYnqvm~>|F10f1mO1^U5x}Z+FmC-!oS57vX#ER>x>Ar0TKl>nHu6Z~l+C z*6}~h>Has-Eo%jThPC}5sgY|7)`hmYtHz%b0rz7__UgNIPmw#@V?d?PVONoQ zTd-2U@T636rX2NcT%t5P@lfhhQI2lCI?0LS`1$eJ$`$@mhQ=I_Ix0*Tg7Go@RH&Z0dp z&vPQ;@hoywv!A*|`U?bft-O0iO6+|KRquSxiNb+DrGl$pXeVzM=G7xzdRlh_U8g;j z@H_1sxJ$BgyoiijY~w`g??&WapNBLKyECXj0)AS4D#g;491AU@zk(MF1ax(raauC` zd={;fuJUJ?n+1_YeX{9=uYL?FkPyGeo2OaiY3XWuW?8U6K-arD&!s+7D5`Pi-HqaE zQVMC<|1@=dx|qRI4NLpG(~qT^H)oM)(Ov$jJO}P2-#_NkF@?SiDv)@-_o?(m{}jI~ zOKjL>8;$QMg&ZeHy7IO)}y)n#rv}{tJShx4xlloE)O*a6v*pR#g6_wX7(Lu)4ts zr)g~@8mv#oUH<>XKLrvGe+O&S9T-|N|KEM`3AEbw z3Mcj$FVnnR(2(vr7xkC;r~Gf?SIbjq_kR~Sv43cRWU5(41NgnEAF4-4{m5z5OL0ND z?}kD;qF0LMZlcOQv3zz?a1v>*T<65B@w+9H3?I7gMHqt$B;KdjllEObiEtnJQ}ytA zBsJ?Ygr=273Iuc=X*yE6zn7ukyQ?_yy^xo(nT@G+aukCKB-$s8l=71ZGVXPs6A^}; z$p&{0m@oca%x&^72=Jt_16LzV|BIS~-@MAA6bqqS903@VU-&*N=L z?s6&4*P1px94Qdc1+J*-^AOpzLqy+e(VjU7eH4nirv(Q5}oXi?5V_^NI5frShap zxTV!11{Jw1{UhXmA6{LI+J9u6aBG_-)pdG;eKXwt5An~nQYTEasZ9~u5n9ZNZl@oHm<51rqYVQ*sK?1DeO5VT6uK z=6X76x4TpS5An~1dxvR?4GK|ZgnSF1#RDuE7qn2{xb^=>0RLR_-`$^Fh#r;YDn-KY zJ(gNdZm;eeI-WrV67s*V?JPj;ZtdpJX#TPTxtwC89^*Lj{}BIN)Lu)9o1KqFAI{*! zl5d|RJa?A5N~6WBrf5l8Lk^>_#~1&7gZ5TO(78yTzyD4>eHcv`IGq#ortTx{q%d{K z(gk$$7%eG#WiA^3npp=;)RHz`$wd*3w3S-|!!!kEd1%jk%4c`8+u0M-pip(%r5Fko zNXXyA=y)EQ8qt71gM5#d2F(puH-F(S5YQ$6``E%fWPFtHXH3`R5RZxN)k9szv7T5< zdOx@T>9x#JDs3F3KhKV!jfvUH5_2u7W#>Y4qJ0s6#;P@^$ey-s)NkA;FsMKxY@mab zsL4kMj>|3eZ_k|s+iI(uADAH!&^5oCmh`+u5eh6LoT%PnO%2sH>ew+xY;$OqTg{{d@{s~zjHIZ_WQJp-my|PN5?$@(c`y};YP=Q3*7zZi2;}N8= zl;5DK_D?dXw@RIm-&-J{D|5V-^knl9l=4e{#@JsH@$71$uE+D;K?M?GDcQJeI?>D+ zsP^wML?EC`ejmdI6rkU(@;Fh`<(ic5Z>rWVSO2Yp|CIkt{416Gw~DPtw9I_foo^IT z`EQYqhtbc)rhiLc_m6o<`J%J(1T15G zm)@c0L?<{vedlY6KtNYxTL;NfI)ru@HRR9O7u$d~`xdNT*(#Dk1rnDn9i;z)51}Tp zr+7)+-m3?FA0MLL<2_p-pljo_71Hf5IY`r~loQqmThQoR9_rL*7ihlk3Mo+Q5E|WL zoN@uLkBhSMki+mX%A2Ddq(J>#bpE(0|5Uy34YHBiV*j_{Ebc|TG|%cNYQ!EX+1>rp z$kalV^5%u|e0jWd&-@rtT0G^1j^k^xD#QVoPY-8Mfkf!>{nGaMBJ^Q=H78~ooh6Um zb@A&7{PZvQThLXU9WV9mTY{S3d&UWKuPSn8P+M$uDUv}25@_pwDLk+keS0fs1s-Er zK*rroL$inTn?u0gg057zc*)gRgUDBT6#nA-Nm7x&9?h|eW>A5If!%)TqSG-{t1XW# zhb>Me{!?2>?|JTiNI;iw`*_K(3qj+8& za_UPjRmYKs`%O-y?pKqpC%>V&H~Fb@@VB7rORT+=;eQN0njnwi8mtc>SMFQlOz%hr z6-YQ9u$LbA9z~7c$Ro0;?pfrQM<6yl8!8acmD6E`G{&(Ar7PuUL{6w6QQNlRQ_TYz zR3P!6*$V04flia z3@VT?u+5VCv_FDg)yU&rOBZYUqx2JgfoBT@boGB!E}4wWMQc9GpDM`TkzPF2NNuxo z5`zjPa%;;a-PMPX)<${Uo)$Hq4s|k82d%^`RHs53ZEz6X9$um}s#hW9Tsnx3OgXJA zo|h#hN9G~D=o6fXA3Bys&uFW@zit$R3MA4eXG!sPhmlvma!!~Un9@0S8mn)bISB-G z6-`_rO-#*4`^rl>ald05x^(at{4>j$K?M@I!&XQKA`6f~?L|(E4tPzrZV<@D9{067`c#yz?Fnr~8D1!ua3YmeQL>=kLagKl`w2zU9)}lq2ZQ(Dy?B5xuEgIz$hn>dvn@ z@h7h{{ga=8&9wX&RAB$n@cVvAnO}egmdKHx+zA%EHzPPD-cul;D<-d88u}^^bsZ}A zQ3J6ywR}{DMkX&|cC*h(d%p7%*)M)6TeUtW-6=0d4zXX9*Us|)?^%Qv+W+9h8u!Lj z`q&bibctk8fduh9CXM@4h@QKB>OU zmE3%<41HcEwYYW+^&Rz_6Z1ygA&t!zOP`lVGpIlU{vv!=*aK~Q5@smf~s%v^)G&64=Rv=zoA0Wwxknn7odZiY>p5J=&GDiC5`ndK=wKE zN>Np9S6cmk2p+sAj6nqw@Hgc5dCloZKhIx)E6xTB1a!SPUL`d+cm$aYkl%Sk-~RMh z;4&PyH;_RE65{*#nu%%H{1mLa)>j~)>us|;QudcTlx{D-!S=@{(ka7k;U3fGGgwA_ zCft$6Ow2`!c`uZ(7AO=?-%q0UkIv&eH(Z6%4hiuYel3Pm-y?;%YS|)zfG$`!6$&Xq zMaOT+#2>!!TcJR$g#`RgJUf0fBYJrMN_^KNP#~ZSj?Q?bdVMR}^yPe9@jiq>1ro62 z^ZwjSLAQ6d!g^A;KtLB9o$;}c>u+*$NIP6*70I9i30Q*_iVg3dlY$O6kzL&qfq*VJ zI^#L$zPuyrz9*t_Nl|>4+y9IQApuK1-*eaEHc3othI|)C3j}n*@ti_2Jn9^Aj1G}b zlV}DNNWdD*&&uE}Wc|S$(!*CIpi3Ml9@?>x6c@Fl^Up6~P=Q39OPsW~M?c!!tW z)K-RM%n?Vb;}XH30$14JU*a*Z&&^0*El0XLC_;D!B;aZrFC`AvB)X30{HPx#5YPoj z&ipKyK@W1WXDhm{H$MpqM%$2pt8M(OOv+3$_+lFQ`dA!OLl+#+^Am12Mv#q$n@P*& z;z%D7aD|OWe#&CVSxaYSO_WGL7o3;yHGuJp$c5;Uss|gE3Nsc+z%@XH;*9k zid-Ykai9y%uXrB%;1#5~r3R(XjTUBJka#@RUYZe7f>xZk%isAgWhT+t-xeo%i*q&T zg7ZY)UiCXf;+I?FALk;386+fbC{{=b!;6uzpS;Sc+lpr)xg3t;GC~9bx?ta~P^c5N z>0pcPI6ljtK?M?4e09(BQa*ZSdX@77htGhvQlPx7w4elWWnRb|L{?uvGGy*LY_#cW@nwkfIn= zAOUB6{8lUd?PN@Iew$C*NP&PZSStBG%Xu1NJ3R0Vo-quob~Y)uk)_7?+bom_l8LV0bOEgzxihojf~e--<>y>K?M@x46@{PI9;*5 zgF5lbaDjlXewlZqla4uPUI#gMw8gIt#O910y|Xfc!HC<8&3mQmpBM^Deg40qeLAU! z$x`nEsK{ zeu*(iNYpI8EzNFx6rERU@e%Uuz!tRFewoU}UnHQ*_sT12QLiF&DXbAE6s?Tt=9}A4 z*Y-;oR3M?5@>;qxw*bAhXvm4ct3&9iBn8$x7cLOcRlNN_Da-E&s?=%9iFzfrbkJZ6 z+{`wVK?M@Y=U+>ocN{@sH|6hP*=7>Gc4am`?-nEw(3RN!yF`lfkcYASJxUFy&>lCI zM46qe$LF$)9&y70a45_LO>`kBe|k6No} zx^4O++^x4Wg9;={FH}p7cOFE$D&)EIGw%fYaXDX^7&uiRplg8f4=MFlHu4L6$BCH} zR?$t*8mXIJ8pogli9*F2seacSH1M;$8s+4&iPo>wQ^y6^2?TWI&G;eRoPPj?T$1}i zgSgE!%(;s?X_Asb1rp1;y^(@62hgC_Wt@n(nnF`5d#Ei(4-^RKdJ*|U`pUDzTpl5> z;@lkgR@3)MC%l=D+vT3jteXaTUAgvmO@9Z^Y~y5iMR|E@sHTBS33~rbj&1Ah2$!nY zIpOO(6Ae^k`XAx8HdHg#_84lBF7M>9DAOkI;^MK9B2*xttJ9DA(({%_QCpQvOrB^- z?jPEV$9?fLn1+)u^$9WS3Bgl-@Ftvh)Cn z34V;d@4GUnK*F`FgLE~m0IklEV?{5_o)G&5Ke1lTY=MBTZ_X>EqbH7_CdqOvbwQg3 zbY*EXb>*Fy5dD(6uG0bNdBSyF@Jxyb#l97{DD zW<}dIG*R31#0)Bs@DI$Arq#i4Y%2?TUy>s3f?{c;eQlFJD_ zXMehF@KE)wAw3yXAaT8Qg*5$QHu@PO$2nhb(vv)vq~eFVL4V8DsElK%UCjBvF!Iai1|t^H4fjT zdht(n;=x$@&1RmuWZyjs6-XTN$da};%R#kcCUC;&cMNS%;GtgPkw?2#mrECiXQ5x| z1C-De;+!RQ+?|bnrI~TUZh#BzGS6LoqRmMP6-dD6@pDCCj&#B>PxXf0M+E}9rh2ZB zLJ|+6x#RorXXHE|K&`qgQa2l=p-_Q@7=4`)pd}r1kHImQL;tou>spi`ow5smTc3X| z5$sENY$ATOGbt%>&LY&>C*zd%42>`Qq55+{2y)Z{!i z%v!{t0twhE@za_0l1S^{&v`$%Kp>zC_9Z+^LEB<7FS@=uspTvN6-a~$dnUpYKaeZe zbk!{#CkX^}!M=pwYq?a19$MW=ZMe#wK?M@9HuDjgVPBg3qK7)$f#2%|`a9@?eThQh zdwv+b(r2K0wyQaV3M61{=2@V|E}*}gSgSjG^$-Z?68osEkzq6>(^lQbt|NmAB*c2| zJz}5c_qA3yjN|eBaBFmE zfA^a>A3yj7Rdd*GOn*>?Yjku+*z4|R>nPzDu9z{oGJ zwR$UQpJRR1N{0ag0bO(YzL9X-1IRW`;_YtsrS){MvxVBOc~1rvNGvgbBW(%ELf_4g zaKg~-nkFmZ0m_Jo{@d>Us}pi*|2MOMrIO#eFk-HBwv3-vw~b;@fdrgo@QC}ikJ5+> zBd}fPNP&PZ7-Qw@q7O}o$B|gv)K`qxLITb*_!_ca6mfM)$DQ5>2=Q9zg3)DuQtw9^ z8Kb6H=bo1kMTP{NW$^u1$=8YR{X5vc+D#y!3r5L#&-t#746^+X`}v9Sb4b8h29F6Z z>_qY9ChFdOoP_u}biru9Lb21?obDLXUft$|xDNmlaF)T(jLvkTznwPJjfQW$^kjG=UzTH&|_+&{H6wODu^ygH}%w zkbrGIKcmx(}exVp}Bl|pwXdqH1VmudWKsI1{Fw%{m08Q z8|dt75h7ZQw|?KEE>_Dv*FX9r>uQTQxahI!b*r)j%Mis~O*IsC)M? zlC~Qt_9PypsyQfVSx7&-(T_{w-^2T=?e%?bTF0)b}tu+wJ6(qzpnYJHO z>AT++>M^^z3j}n*_L$%FcWN6osOhI(xV5*?QbPi+0r54N{0-E)O<(m^*Zu+lU9ex_ zql~v}Xw^F-^}`ibLjM5?xH83a%5I6HcE>uX?ZRvY0=nR8G+zsEx15#?(ov_TitE&n zfGcdgR~r;Un`9`|RcTJbIyH2`h>${Y`IA4dQO_|sK3j+tK?1H6@@%2S^XOvLWxRU8 z0)c=o7~$vZa08ublYl~ey`v|C3MAl)CtojVH;($~r{lwod;|iz;9d&(bd3YO?i!Dq zC<25%6Oe!_w|w``1}oZe-&`CQ9xM>h1^0v~6c?Q>>77S|aNxaAVebbd;0iQ<=l}Jj zsXcY@qplGG0bOu!3*Q@6*qL^@o{N6}i4^v*Kmx9$^D*`H#?;xqB^tFRN+6&M?$P17 zMM6H3U3ZR29eaqocOU^H0(^ga@oCb_b2mBKKqR0G?i}L#EO%s(uX9?`##u{*Jw=d! zkqw2S=Ls)jWv8M}gCYe2y5Rl*o(FQJip**0Pxr3~6LtKu2Nx;pqVs6YaqaOJ&0J8g-E=F!(nL;|}0*U6V&37RQd8mgM$ z!=M5Qxo!WS)3SQgijHTVJ3`G{`3VGc$^ZTrE9N(!R5zv{EA#2q#oo*z<)^f7PdUn7 zeo0w)MweKRI*H!IH&MCxH78FeoJG4#!#dt} z5(wyOwW?Nnd9(^OU;K=pY0x;HAeSe#V&=IM8B`##e&0LkVAf+)dTHZvzN4|xN>Z-Z zk##0x1OmF=9mtmkZ+L}*Cau@-8$&*>BxMnXtnIOp3@VVgWAs|G2zrf%wUbZxpBoWQ zvQSU9+1y4TplhMtLFt(1H&i`%pu|sMJ4Dj)$@fWbzUyVnBtueMScnc!@1r_5rw5s5 zRE$>V4Nyfj?n(xw9z*`ga@L3|zd~s9C;Ifce=vgzBo4eWCYF7UqX~MwIWf}4jqYq_ zLp$V zB?k&{dyYoDyI`CG`%t1?4qL6^hE-?k{Y!ntELcS{=O9_ zlE0-B+kl3wY3+2O)_%3Dl1vjT(a|hRp)cXlSLf~I^r-LDIC73qb|Eog_kC$v{zWvV zFq5}Fz7LBC4tY-799tj|&;`q}LUGWgl&?Tur00it3Oy$z9{l_*1?HYbb-U#l{ocX9 zNrihpeRE6fYoQDFqI{&U*N)bBZ=sFt0vJ>vA^ujz2A1@^%@X?Td7wZ*7c9qej^7b< zlJ|64Iz5;{1rqSx@EQHXX|$+7O{eY<3Fv}t4Btn#WES=>}d^(>>E0&MPWzjxt)Hwt4eb7NP zwZcdhh8QG7WGP}Pq#YY2wNWp6-aFS(~a1#%t1_F zZg*=fx6tk%TVY+V0D*umoA({bf}?rpReuvsJSo~ry_|LNAl(246-bn<>_*y-J%oDI z$T_wy9Ns|Zr{|%p<3R!eUDuie(Xg)_~fFz zzH)oz-zbqL-@m6CSr;S_(3N?#Cplo5kG#DsI8ji%oz`zHsbVe$GN?cz;&(qXb6*~M zy&rMn=BI76_S_{Y(ke(GpzFp~GjeHb0jjOF=0uIV4V(0-1HC`KJIk#ICJmNKC`l_@ zbvASn`D%6nHS=7mdN|aFgchGf8y_mq;$dEd2BdD~M0uV8tJlDS_UJp3K?M>Pk#1zzx1%V$!8%S% zvg^cNFVdpT+dBvZbnTnIh)lk82(5mU$_c+U?OAT@C*rC%mO%v)!za0s#)l81S#39S zLa(F)D;&me(%38#&^5i>gY4UtgSI3kb0WKEYgSURlMGxwkwFC#{SxLA$JgBWEOks=_8i*@B0q#MNQ|Q?3diU6ezc70tvlyKID;0KH4^BCntO#3}g?N zjUnd?ECm9(ZaxbngJ11OW9UInq>t>!oGf~f1f`Ne1rjzEzU0fJY;@yvCMVWt^=G<^ z`X~?FuoejD8hX*6v^%&L?TyUh#Fi9Ob~o?Balcb)1{Fx0d*nrK9n3<-zcM({{Jbfv zIP^*N%U2|zE5gT@>{^$J>@(y~Wsq&mo^*eqdi;1eg9;=L+btqmN&ApR=5|i}9$~^V zmc=65N?U<|t`^jbTu<7C5?aZ(z8&;1WM8Y6p*OciGN?eJV!8)0-@ONoPnYZ9bt@xw zBL51q>}Dqr(6uGslV~nxpf*?J(r&rD6T35`5D_FNuZE5k2A;zT z7*rqu+c6%;!Dh^%mk#};v=RvDf@O^FvmDfumE6#wYYt%s6-dB#jGu!n>&Yg4C?c6! z!vq4lU>W1LvbXKd3hH(fZTk@nDv*Hf7~d(|(wJ=;t4DIjiv)DRGRDUx30;_~up8-f z!ht~r60jZPSouqqkEQ1OpU^~Xw6L)lEPGo}r|I?|UuzCEtr&*3_Pr?z*6IxNj&B&{cDK3E5G(3$^${IZ=1pmYG~`idtVa zVNijD$)Yea_1PX&|8fy0l#PZnhYiW7iW&<9bk%i_B+nBv(6FKsPE759*=>i7$aZ;e z1{FxmT^~XYW$Z?wx<@$C`T}B;4ppG>)usXgU2SkU$(XqV* zpaKaUuOQMgVki2Lo5P98I#%r7mj*ccgqc7J&*%oZN#uRs)Hb5YtYfDfN$w^2-%Pz}AMZWxuw1oF@UX~KM5-<%>@FwZb$i($)A(ap1d8LDCpdmsisZCVflj@ zR3I_)>tf>Gbvt^A%=y4(^nzZc2CJkGL_njZi zpaO|jGZqrN3n}P|jyz^qr0&Hg^P5i^N#_5LtTzv*`uYF=Pelu*MN&%0R`xB~W}em% zEwo4pp-l^Il%oWcR%kyoi8PF;;WA; zoAl2Bhg=L42~EkrpvivL4X=t{>0oY33U zm7V{!5XY(e3IueO7>AP6S2m-OeN#EH!mS%?yK)UqIN`~l0*Sb}!NlxyJ|drEIkB#z zCaZi}g4qZp5YRR2av0hDd;_Zgq4))F`D-%En^pMut3eDZkjT70jN0WJHj04Y_C;4&%giH%m5V*KMrwNt3Npok27U@{ogRhD-D2nWV$} z95lpdk;{=cv&pN-mFVWpEKV$qvSGQ?p5duyJ2R+2qSx}dME5`z+G?x#&8`1Autg7F z;FkT$0s&oFPZp8N_UWiDjpuvw6&tN+jFE;E| z3pUEH6$t3c&Rt3lES`&;)s}H$;7Bhv*tM->Gw?Wt3M4*WN+GMw647ddX`Dc_eb}5k z?WA4iI|Tx|)SNO%?97>HbI`VFR8=&F6aIQ$Y|m{CDf&w)g$g9b>`Eo)GG?O*Lln`Eg-^WM z_NyAw0kv>}fUfU`nPl9DNObjzB9`H-S4captfof{LmAAD4fCGE{M&paW3Z9dM4X~| zi^GLH+mKK#Lgf0QGibwW3*LtNUUnRnHcjAdIIg@vUvyqfGctG^Aj3Fx!QA0|wjFkZF4PaD*Bv4lR3HI+BEEu^ z{)DQ=deIvDaDjlX+37(fZ{QKs=UOuVR*w^((UX7m>Cs6O8B`zv`!0S~f9*%=fA%k_ zBw+#pUB@m4leS^|(HwKdyZ!s9FVySOL4pm!8B`zv`!1fxtD=SOS>Z+c&z>L<(DhF( zgv71cgR(v)Q%NXax%dbe;1GCHo$fAdMc1 zx6ivv?OBcE2DCFLh(QGsu6C<+T>{ehlUg#|e1axink0MpaHzE_S4Bp1(@ZQYs+IGCB%!xq-60q;$QJl*< ztoxorxcdhifq<^WR+CBcg|)~bN72`QJ*~s~2As#QV$2y-AOZU>nQZq?eRj?D7WNrn zC=k%~J$(wf*e4HtagF0`jCRv!o0VSUx?_ELZuS3DAR+c@iMx&1*MHw|L)#t#0bM%R zrjm8Xa!}!qNxY3$PG)S+>tpzhzafKTPS_{LX~mMbiK~%1QN$VAJ+x#>CDnNT5N!q( zNWlJ4CVTtHmfb&c3aj$n>X3l0xu@onuDYwxosNnK%iKKxU&|+Sl-`rcu>o83KdA4J(@{2 znkFHo!HW6dyjcOv?&3*IvmXcqbbZOnAi3+7pz5#3IFa)rh6i&uykqfyBn+ zIpkr%95njP9ZsZ~hBND|-MHoFVS#`yUH@goY0XkpW1{$0_*?`V8&iTE)AvxQK;o=- zHu*gu8KFN9IkD?i7;A{zi1Tiq5eVq2zL!BxzRN=9-EMGVbx8y}Ic6R17IBrEJp*HpK~H%Vklcz5{XCdej*UiHS&ELv1(a|+!}bRG>Q%MJFR75`#*8@rZ$q2r=;kp1^?fq*VJo8)=CmVBd@ zJ@=yBLVJdIq=lxF1e)tAlVec&v&;@6c{OvPUjcG63hf~_RGpInqX!t0y(KjFcI33E{ z7}#E&RTrPco%%Wn1a!gKBtKIvsk7Om8}Qn#whSteUOv$H5^()fCd>BmXSO`A)0$1a1OmEXR8=MmH5$xw{wv)BfWkzvCei&;_Ha zJd*m>fzhi*RVnSP8B`zv*TQ&i+(<`e`bQUKyIBbYbit@9&pKpo$KK!Qf4BH-&r7_3r1D>E~I=THnn{x+|E#9 zP=N$o3*!+ldt+w2%nn~mcM%Baf>Bjocj zKtLCa!}4{`j_c{rFmIZ%J%;^FuqPkYt5BN{&Ms`WHR(S5IC|05(Z$)@f$XiUMEh2G z@i#+i)kfO!x(>Beo6VpCiK^bVz;4JIZ^xgFb&!`#znt0hCu}qX@>Tst5P}o)xnz+ANw#GRu_$QRA&kVbQzi=qA_9* znwK|%6A^z-(JJM;Xim^{1{FxKg@Z`4{cbcMU-5rT_PIpA9PN$kJf{c*bUn((A5IZK)%`aS zm+Zmr&9uq&74B{|Mj)WeHLVjVi!Vj)%N3bC)1|HSqp3`)wj9o&0tu7d%EaV*DY_f1 z*oVArZwVd0vV$~tqPIXm*WcZp$oqdg(b%MBPFO$NNuPDoklK`D1{FvgJImWxxeIlC z`j8V*jr*u!zP7aO@<4%rt|`@>$e`^dXqlBF-)nF4{d6VnFP(jB%Af)X^;^m$&SNKf zxL1+6<*ijE9b<1P-G9+fAfT)3?M}opq8Rn`zRU@yUgzlXCLO8uCvz5eK!c3gQiO^s znw<3`wMjzF4x}6V&$;g!4T3)uqwG6BInkl)EbaDFL(1Q8&!7T{$&T7&qj@np-mKWI zu8}3Ds((63=anUafUY;u8l-u`PE=^6%!ygMtLWg%ZKU2&gBesHu}evteBNDxzD)1T z39F8Wsk-qu>~m+RKtPw1g9iEfWEXNX=*Wp>1!XiS;T~QbIEFz562pIYC(9S^Mz3#n zcsX*> zQ|uSjOHZe{Mp^j5teFAeQ@p$02Q;gi4SFsMKxb+r<4Hadu+ z!@F?8IczMoQP;&sTjB%)x<+^YDIaZf8125R%87GrJ?V}S)o6f90)q-98t43w`~EtD z-1aK2ZWb}4TRlCHO@}0bfUce{FXdL>D$zZnxJ!(0>CnIp*Fo)Uh5}E zUFIvkRbHo`1lbtTp8FC60=mR%P(i4UhTl_{Zj7>L@R{&7J~{TerI$fo=W?X zeh0<>ao-@GZciM7$2rUu2QauUv+0Ok_}jgi=}?f>J7x( zLXXy1(KUGs8B`!4)+JkCETiMc`_jhu3j_kX#3yQi-D`5=cnn?KKb}Da60i;$k2NYH8{Qxxqcn-qvdpMcdWmaJ@PN>2M z30S$A@0rN%K+0-W*y4}8UMi^D2VG(X$%67P^7*H`vg8qgLOn=Gz}nLM-99s0uElz? z?~!8FQ0Rj7K>2=#)~n^kvvt{mS>8frQb@pR)ckDt^jY%ZuZ`I(TQ`A#E?7sEXJ~3D zmTR6fVb(jbP+=7kVx8(YN6*N;ds(r?6^;S{U9ciJpFsvKp<9RM;*|OsLSG9<%Wz~M zll9YIN%P_k;)JkC!UzBoaOBLN+Cf{WhUG=vrC@?UKo=b0@KMIS9W;4V6MkDXS{TVd z0*;*d{A0~tTGRO_cE}wj5YPojYJ84!qm0&0YA4CZcnc#kNWhV^BD-+~ec!8#w9Ziy z2zaQF>;R3>zn#X8yA`jV^QdW<6wSucN1zJVkWJ; zsxOR?At8>b+obHK$#;IDCCg)2fR`2d+Q?(10mucO9@yE|gy`{neLnRziazSpb~-Jl z4W_&J`C6br0-kT+&-wFGdOOn*Cz#I^2j}$&>cQ=;k#AF@M8lS~cn-UaCBjK_$7rEwM=3j$ZO=*061v ztjFhiI`l_1KIlABXaf?zYHUdRzC|d=!-BWbaIu;mT3n9XM2g=Ey5KeBwE-vAQtywu zagoP(;aWlB?F1X*T3w7Dw6W!F1llsXcX}@F?;>7Z=z{kG&*Sx$*KtqE!Co&W3cood zieFfh(+N9KWTQQAqx|Giddqk!ZeKe^AfOB0(|i@6po%_Cjl|Q2P7&^1NF-0TCik35 zk^fCaoI$?$2xSv2@aEj<0s&p{N#hlcCOoDNrmdtb1I*r>u_f)33y{l~UM}`Ywj}U- zA@ZuzbJ1vLM&`xuK<+!Vc^g|6-J*B*yuy8(eHc_A0q+GqdL3Lt+kLr#kDCSx1ax&V zHXuFuwc0vJhqqC8S5AL@J&qr@8_%Eu33ylX2#ec3x|CO<(O(%M5YTnXs1IqIvInW1 z?91CYdtnFFNX@`=?WZxQKmwi^Q)E3|OD8`bkN2GBC%wUEL6>ER?!~%vry>|UO+8i)nAfOAL4CQ;Hyq3}=k8{Z9(|qB~C?wz+ zGrphUcM=^NY=zF%#|s2>iKpmlqLxcCwEPY7YOJQ z&-Sgju$*d?=F5985l=`%0-iDByA651r6D6T$(~Un0bSzx+L;wA>GlEHq|RwRg9;?X z(`S#|vgz_^&q=3c^8^CA;Mratzj|Ozr%Z67UCzccc)s#eat9Jit5CUSR~LASmakL~ z9!PsHQKOAB77FKUA+czQ3TgG{C`#+9m=BKK=tT`=)nw9lk$^6E8ko=MR}7&(-V(v3 z3BoyHNZgyIN@@d+pl0o!yp2I6AvE`LfK%EZ@tiPpiFYEe;Yy$5c}Pn~JiQEwQmc++ z^{E4B>{rGAasO33J%6qVbvY6z+=NKFxf8NzE3j_h2QCYnduM=aA4%>_ZmbDn(tZw0Ik@T=&up zzg^gQNQ6K@7krQL==sx1`t|V{T%b2jcwa#R&odzBo)n|8>lFXT^daYHliOXKkrp5j z&;{SeJbUYot90G3uXu%yxA5MD#AiPNp&Ax1OmEXFTt}- zS3ISI($u821-3%}0SWb`W+XDJ5RJIiiML^v`i5HTXh>PBOa%hErncCU!9BO4sE>*` zoVnf`y31c%y5?lSpaKcILuSN$Pytfvr^JbnfX}o{Q(v0JdJ6<}&9JZ|5tlZjv8*j8 zYJ2{nkxvbzy!#pqDvwq;lYc`uq4Ky6F0gGL*>2xL)k^fFCjFj58<4m$&YAqm%|{ar zyYn{YTyLiCb(+$uBtwCKF7fJiKm3DEFX%3P^EDQ(6(kz^IFlXkH=}puir%@t`aSiy z-$5$cCH@}J1$$~fZolz~-e_qn#ay;yP=SQ$H79aBVk_F*&4{<5lJ$aqnfo1UHAw;i zU2r_dvtQhNO%Er3#_tnc8B`#ll;}i8zbZiOBNQX#gu##KZJS2?Z2S;`fG#+m;~ARH zJ*Btb-@*qnhA^l=VvD8|X!~0aBfTpg9;?zN)sRH+ttv_bBl2J z?FfN@E;s_@BY;EaY5ngY{BPbQ1{Fxa6*Hbkc#WK*jmCJQZ?r%_mpHQAvxV>#=~7>5zacvHZPzc?}(1`;xq!FjpX;OB^!{ zLV5JWguc{{=YW6;B;blNAGgoVq&cm;=Onj3-r_v#7KxjDApx6*8Vc0n9?ze1p5ZGg^cva}z+Q2G3k zXXvjjGZ<7L0W+q_WJ?AX%k2lAqDz!!3Iueeu3aKu{-6f^IDDA5@%%@FT=i8s4c;Hi zpaKb)`Hfc+Xsu4VIqjhxJZ1|7bg4frk~fs|N|rAaYr+@(9LcSswKV+jJO&j=z=}aK z+2RhdB+Ppi^&Bx@AfRhm<5~Gylhf$+w&%Q!{gtc9g*mgRFV9~B6-Xoutd{?oLeT~5 zubj~FJW9$u!)a`lNI(~i_48Vdc6H><I)hmyh&ApUX{0Q}ki7%moq!g}3B1hv#m~ zZQ*U)!7oV5C>^?(*HMH7biq|Xnap?gC!!vEncQqj5?1>lAyzoD9Ndl`nHxxkM<)ve zbivh3zO&y%oeot0?tFf9varqx30TL7$HH^_(|=o{&?GH!ofEp?sw~fCQQ%Bx)x1Go z9~KI$uaJOsjAXK8?NN07d=tFsVw^xg7hGND`F)m#(Zky(;D-FULS!2fuqqLcWmLq_ zmrs^p6}?!2fG!y2=5e@1bLh{i4S3r98N&V&NWeNqd^S;*N~`CV;VJ#63Iue)y(T<= zNm3demVO4i`9w0PKmyh=;!#eGZ0a3#8$Y+4AP~?6_nPoI=hqy%ruHK~n>dC+1ro51 z5kIdMzMck6Yc0*|GF%{_3+^@H8U8+Rpht+BG=pbbfC?mF9V1@dvGq23`>&=HbR7u< zbiutQe1-SqHrl*OUmAJAmO%v)FzYSfo$zTF-S2HG4Lo5Y5YPp8r^sY&G|Ff%ZF}i) z>%I&skbv2HWisUv6?Ck>gVf9`hCl+k#0dSzEtIwlbduVvQD;zrgxE*9$DXC(8*HRS zOJv`0yrrWfd{BO1hcRv`+>OA(03 zI%Pt;6rql8iJYiebDEOA0g{2~0}2(`25g(}x!ZS`UP&1(nekm9kbtgly?Azf|DEU{ zj^l0UMqi~APml~kHc+1}8l?ZB0z`9>GyH~$N0mv3Av@5!LI+NGbUshB#*CL1%r2); zfdp)u$9+~Dqk}TSCCe>41OmFQet#`@Oe{g&hT8Eq=6>8qoo-B!9{Zo5P=SQ_f7s36 zMxW_NO8tGx1p>NY^%$AVO}?I5ZV!{1=Tr-IWguazR4cF5*^RCn&f(uGJt31u%Oj+7 zeEb7H3%X#98D2qBCy}aXg-RzE-=|Q4#JZSLc_q&-X4Wc(w-IhUp8mBDm2x7V3j}n* zx;gxm>4-n_sXmd?Z;dxXogc-h&wBF#v|cvU8CLL-$-2KK%MxmqGgDf6 zJxd^<3*J3^JxV>BChU!oLY__(?kh;-pSvJ8Jg^JZTV3UC*jj9+J~yMK7MpZ|fG+sl z@JfGDF+CGAL#k*KBs?FGn0eu~yy#sq`myd7ZzJ30Fs;d$B0c9-H{oYN7kvKtnpb~0 z?Y?=cbico!@SH(+hVMu*R})Nga79cxj2qhdC(YFIl~hTNnvjnxz?+s`=@L*otT?&rtO@RN8YvtDhOb%vW%a{j8& z1|*Uu*%9k?n~0Z0`<;ok$wu^ck|GE8P}A0I zT8g=}{%1RZfG!y8<@x$fw`I%LTSx`JS}~|VqW=YV5_Wt&3iej){ybx^%oYwbmM&lG zC=k#EW4(N?M%uCx9Rq3CZ#4!LNW5IfkHlegMJ>JIms(&=^h?*ofFcApog0Wuy3^vQyh%c(r zJ$}{%Dv(HO=T4MPbUcPSd{yiOf;3Cc#G=xC~63O+hL^rk&-O!SF8z*yL zQmu+ZIR0jUKtLBfxxn{q4=ks;zkF%;mD8EiRyXoI_yigo?C-L(HzGOnaeOy@iOVQYklQ>cJu#qnNbQ1Z!pTwX7i4UDT$?>dR$Pg*o=sfiW)qdF#@7p#}AfT(R zZU~ulq!`txMsXth=PUYc7RDiEp$saJ7@X`yLMn<-WZoD~eDB^&FHDcd$N!EM2rdkDZbSEw;`b;q`%d@HUWt3J9mSvm376A@$vE|G=*AAkxuUO^Wb9gQ5iZIdDiF}6 zvUw=68nhK98Yu3ow>w%f+Ku3pL~jNaNJQQCCR<9kAiF@tDIt}_w(Qu;t9Y-mBoNSb zt!fylxV#DFm-umFpLIJn<=|_)s>Pl`1rkwmA5xsK37JI<;>56>s?7cIA3Pw)TqJ<2 zrgS(d*|{ENWVvvnU$82hUEEIEpKQdS0zdbXmM>ZVcLOr|q}b^czP>Xnf74m2TiaV8 zpereC1PQNQgCdg#aH4sQ8k=9MA-#OwgF#orbYJpd?Rw-k*U&{Iy6bmg;ZOTW0UtXt zs6b-aeqS=olb;R0uUOmO_DG$Lzosu8t!gC@&}H~w1knr3L#=ESyYAaHbYp||50Ey@ z_(q`uiI2~G$=l9r(S9q%sg(9U-I>xyYl(KcD-h5n84e*mJFG@69~61EM@95yP4hLS z_>oHN#+?adnT}>yr$o)qRIHCOjNSU$z|yCY2@OLEOgZ%&;_>5 zGdegKF;%&`G$a2ng$g9>awADK$w8a)6=(b6?(4C>kGn}D2P+Hz2Xw)2$or_Mfvmn< zPug#|oxUxOCl1>dq4lapE^GeAku@t)(cP^cE+M0)leA4s(W+jG-Bk5O)=VQ;M|zuo zj6wwx@c-lc$fyZJF@}=vVpa(l@U_PZuh7iv$H5vGterqz9(ADO4Z4BKamq@xV~FB}!g}kzthiG@sVjX?p#ll`%kq5yQ#6@w%U`^J z^keX>HvFB%bK4jD_GT}f+Dg90y%-3dCc#b!8bz-ctLr41s{I7Xt!F&cz&*+oY&Dd2p=; zGc@y&(r1TKs6gV-uMuSX@@#~(gE%o~aUWK4+)Z*ankf*_mCZtl<&b5_`MaXRQS(4+ zcK?@^^sCb-daeHg^1f^VYB%Ma^S}-Z$WfO>L}n`Bw}oOYwMt!sk-4r? z;`9Ov6-dBq$akyX=);^1oTZw^O#%U3FAs(i8@e2o8+_+&^fuOIzp|XAcB7V4s6axz zR{9%^Szhx%spFY6fq<@IWz)&F>uIRnc*Tj_PvI7<@`tsgtvQ`S1rqSL;bVq}OXa<+ z6Qvo~JpYT_9hKw<=HBR6p0hwd6|;%!uXcukbfBuZ~s6*;$-iFiqwlwx) zk`%l95P=FLQhWKxldQ_o?%-nH#?s}+R9hoKn*F#Vg#>iLm>fSPblia+x|JXuc(9*9 z1rkf840-**z36$TL%fZKkYM`$QoMBAtOJDvbitS$kFX>~Q&X=6QpN4P1S*jDpi?T} zSG^k@*E`MI$RD+ontYfiO~_ZGkbo{2ljHBJx*Xa?Yrdp>bSHrdBo=SDAWw|lg>do> z-bV3`tyDi@w)83QpFlttjLGrnhtfW3^e#raV784w1ri<$l}Xt0?Wp_V7T!j5CZWq7 zPnVu*eHIAlf-yNh|8TuYuYH>$RqxzDpaO}Qs|G|*H6OKF-izNQ{k)#hn+qbPaiRAG z0=mRlpP^+dRuC2bo6B%%sOka}4*vLElw+qgWV2OH64m}LH~R3M;B?7rY)tsjsDdE%&J#6>Db_L0s&nr zTk=RosVkaOxPrIw_|`b)SFR+jth*wI3M4+d=9A$e{m|XGle`U^jYC;;Ru9Q)^;rUm zBa<^p(1ma`VQd!{_-*-WhMouO*rT7M|EvRr3M61Z&&LdhT-dxT10-)hC4qo0c-46Z zvz=D#euAx3+QorF1ro5o;(LUzHUa@%@b2NK=z8d~HCx>z?;D;JDv*Gq z8ktPYM<(1Z_CS)s~Ldh~s;lpEtq zp#llGX2GiuJ$pqr4V@rmTpJ@0&?T;zw0ZP`n)n7wx2jeMD<+VDs~mhj`1k?+)OV~@ z-+P-tKo?x?60BQTjqr%!YB;XjHS48k@qzms4m-@HAC=k#E*SYzquk7u-mp0tvVR!FLr$+@|$b-qP(4?*sz6#5MZL(GO|e95+eJ_!or=B*e7|tvEF@ z*0zP9JIVj;(pzNegJaic5ygnic9aL+AHJNFExB0r-N^$t)-EGFZ&Y)md~iv+8N@x_Q1^r{fOGd z+NzfU8o1oMHz(q5rpU{tI%@-D<@II2 zXF*qa+sjoW=BwfUjlbo5^)=N^zHx{%`?$!0K?M?uztbGL;32wgc^l^ESIUdGIk5|7 zmj4g&KbPgQyH&mJ$#76{CU2v!&9SOwmQL*NK}!Y|__>O|bDfp2{=Q;Pqz^w{ zxwXOS{~`Y8QV_%6w#HGPHgUpsN{#&Rr+)0+Sg-%C?)CY`*!y(&e^>W^zfJAEnyMp@ z^|9BUk^KM2c|DNay+45ETS^QniqHKYA^w6Ei}sQq78Yz*xRXFY*Zr3P^0{BN@F6uz z-bUlX{xu?feb2; zfX_d#<8HW|3`w_V;RkF40=nQGBa?OOnMZWx4s3^?6@v;ScD)-T-q29aQQg#ofi2-^qFS1r%>@05;rDS%CkN{LPc8p zPw)&hxlttEQHy2V@Dm8=f)#yvjuh1?#P(P>7UCNq)BuG9%$>oXk1MGp^`_Q^=*2A{zB;vMN2gnj;X<1<$MUoi$t4>9gzcRJLQjaFP`gFt-dpIT@u( zt4&7II8X8HD|EqAtuk5lbuGH0(2m~vw}3$f5->*&KZTt;fCimXq3+!h1OmF?saF1m z`)N*}H60|^{Sp~eAOUmz@coHfF!k+dMA&eVfG&8dmG^2Ry=cqKT$jKBi3}=`fH{l! zo}wXR>F*z_P{Nvp0s&p{R4dQ+c4sne^G6vc8^trIKmz7o;%oFrQs~c14%jGWu0TK+ zJk`oqk*}|yw{z#=Yb$3ls6YbdkmBc9{%oSr`D^f#<5L9!y5Ol+KC&z?p}H#%VvVqg z3@VU-xv=<*Uh@d`iM)VQ=LZV}biq@t{9ST^QK$Az*nP)v1{FxaoL+oI@x>*2cF=FE z{nSe!pbMUA<(Z}muG5|M?InM?3xf(I#67|Rry6N5<1P}du@eaBf~Q(}^!#!oJ^!<( zB%ff;paKcFCz-#m#y_Q#7U@V9cMJpqy5OEE9!af#L9?#+m!=l<5_VHT0-l26=bguV zp?>czq{b(m1OmF?&MKZ6uTGntksTp(1ASQZ5H0d3$sfPEKZ)dKT9GSz2jkU01IWS& zR;0w=AM5oR%}16cr%c#On#wqa0##EqPJD)-60tub!#pJcQCmv^fniIb^Ok>Alc9H(BmjnX3 z+73t|J=*!w&M_&f&z1!Z~ccY%RI2Q7915 zWwkY(Bp(}s>uNS~LXjQKSARPx3|d5?0*Qv8O!B7L9dFrY#R;9Lh3uL~JV`ngDiF|R zRg+1sOdf(;I(c)#bygBv@OCjNey>fT0tr>)<-{w{9dFfJ#^(lWE+;cDJ4{9@|00lp zuIi%Y>P5pAsxBgi$WF^Ipl_M2AY`@g)XjG zMbdqjpc~2~kWAL4Z6X^TX^ndwl?w_a#>;X@U1T2eEcW9>m0c1WdD;{YeA7)Jpv%vH z1^N7Z3);@CI1%WQ%sTmN;HabXvYMWF%-FP2VzPdSYyrYdnl|MNnY+&c_4yNnSC=$dmN zovd-^JL_J{II$pa0Xv}o&E>OfE`rl;Jw<%O0q5dI`tb6+f*{Cb_k)AIYVHH~6R>;tJ=t1A>Lkk~YBA#sgW!t0kQcD)=t8P3YL#L!cX zHw6N^Vjss4JEWN*kv`ok|pG40i{)VAmhg$g7J|1BWbw{^kBNAK`w@NZTa%QRj_ z+w`m#2OE zX44&ZmjnX3x_yixJummgxBCRj`FWh&a5f=iIbDD6B83VhI%LI?5lsd-(O40O``39a z3yoY)YtB6v2=d`9~=C$c8{ zu|qXm>CcbK3=+_FJz_M;IBSkyyDAfY&g+&pOIyrO1b*nqpaO|67eL$Kv$m$*X4UI_~W*NQaEvL;Vp{$^dOTwr!uHO;#T{c@?}#4u+LBh zVKuFqwo56HpZ+vmAfRi_!)yN$LzXCr*S=BYY_69)WZhzR>w~AiTF!}&Dk{{W zd>IMskt`6b9W3@VT~QWPjZrRIUZ=4EhV!>ze= z@Fs67Oyo$R8g=xN)!IT1}l) zMnkWMQ#>_VAfRiM^>w+UC&G`m#c?8ha21`nJDZ*^j$}}QL@V9v@=IzCIQm2kCkjs9 zrn?U1)A2jU2?TUK+1;8P2pxoPY?;Uj)yk*z@{l96;aVVr3M9Puv?hPL+F%=%v7ESB z@t3k~gkIG16$t2Z;&UIJe%AP8nc}G(vyY!KDXFKYR=Y8%K*G~Ui|ns6#jo}{apL?c zHRfG^gW7632n2MEYG*}mZ!*DsB8@n4V@DFJx6MRnl{9fuMJd_${*Uw0Uu}_1YALz6 zx{b?*zz)b;qm=ZlSm4sm{hteu?~Y7jIW+_&rggzkfkc1#PO>H^$EDj2Rm4xetWIR} z-*m&b4t)?l3%Yu4FD9`zS6zxTTXCYXJb|T8vcglm8WB_=;cQVvI#@q-+4)h?Mnt!T z%xM2aJl1NZKtR{Dl0vdltsBZ+pcr3S{ETNqQWoO7O@k3sATd?HfYdtoL76+-b0Ri# zKKt`57a#v|y9yG}RcF76jLmUIyUu^-*J`BkJhqhA44b{zgg^xnvkz<_*9HtmRn?0B zeCW7XcF(*7%l|bC1a$qGl1EN!M4>^IiZR?FgIO$hQ3+ml%bG$361p!}5%UMLQ1GYs zoG^@-#-`-$`_0s&pHMj4+QY?{XQB^2ULXEP~OAhB}%N`m_&pjfr9yp6>hrm#x8 zeEfV|zCb`1tWn0F^E=a+#evn>@534j6-azJpH0jgmLS?wadq1lPGK{*ufXbyb_oP@ z!K!9_Ep_P>mKTF0oo#`Q32l zx6c>9S9(aH0*M!n8DyI6I^;Cs8E>O=VJO>ibRe#I{zf36>wQ!@kxk!-e%-&zi4M|4 z=Ha7_*SI!Os6gW4$TTu&?>6ML^d2W3hKI7yjIZd9$v1(3uFULIa;mZj*}5r4`tx%_ znbGZSNVoncg$g9L?@u9yKlY-D8GGaWNc-J1q#X7_sV0(dpE?5(b$3=$+voEJc5XXaU8B`z< zShRo?j5&?Qb>Gk1h>IM>hQ+QWXDd4i1a!fgSo}=Gpa8ab=oPZur7MF9B%&VACWnWg zM?H-<@HPx;1~aCrPGh=i3j}nXi;pJX%?BDk+*|2^m>4D)o0s&o1U4lqczt;Fjo56g>^5&rcfdp6FXhCTN_#e=4bK~OLnNR}BXTsEl-m)n@H3V3wTVft%=|f{cYmlbs6b+p zTO`rzrGbY%aplDP7$-I^@*-XORZSqEtM%SdLV?z(?1Cw6xAWNUuPY5((W8B`!) zwjq*8Il9>7eE}zSWlC&z{3+T{s45W96?1+R*<{}j&o8;g38f-;HvDoWz4=;&K?M?C zDx-<*TVvdE;sYltyE?GWD;RypcU3_Gy6%>Hkn&*z@V?ev2#+Ujv}0||j?-9`J`5_5 znD)SfO!;Mj{eSe~gwFE;?0r}j)mAbV2d)%Y&g+4f}b(b+DGShwqQ_! z#PNYvWE_9fYHmfGpv_v${_}47aiF6>K-Z!GEt0?99$Q`?!HL$>da&?g>*2chg6gWYqFv2q2n2NPb}f{TyXTER@)#`7f!%gDz1y^l{HTg$ zP=SQa=tB91=RDs2T|xX?n@Ni&&mse-#R&v-U0yL#{`V(e1&CDajXFLcl|H$3U!GDJ z&!7T{FAXc@8~L1S?gYh*W!k`rG>%P{pE$BmAfT(`j?wb9oG?yNv{88|o*f`A_|F3? z+#I})-2QBj-b7ADYa`YW|ARwNb&siNec?J1Y~h1Cj#WfCeWos8(Mvq>+hsj4R3I^H z=4#S+#AFmA58y<|!iCJ@!7!|P=e+P)(B+nwOJs$-Ms9#3C;rG2*s}dTIC;7Uf(j() z=^WyDZY5f4YR`$<1&QqQ0EEZB_$7w~bUkj&BJFPGqaF|XaH7kFM0RkB4xatBia-St zxr>((FV#}?VOkGPypBv@b8dIV1}VKMB%tfbk7cAs#WoZ>y9+0_?_bDr%)g-xkPkduk!C@!G`CuZ}!)N96kL1iWp0s&obYBI=vo-h1>g%T(JhQ_hO0R(woT0)@$ zi3uyxNy^PbNNvVX7ry#xGndI9XCvJ&n*{>87HBUaaXpVAf**0h&n%X0bt!ZC^Wp%7 z3MAB}6mqM}S!9rNi4&SjqM7-yD{}XbbpiohfAkW`$vZXZ-jBnaQ0q6Doygum`ggid zp#lk|t_z4P{subTtAG=>d}OKI@{7!R^i?3BYl6ibviH($WHln46Voz+S+b!SopQg0 zLIo20Dr3kM^=HUzks^|6-Y|l#atNVOvpewQ^8fc)(6wjqG}5Q#1$y*fU4YVg!`Wc- zMZ6wMI|da<3^1HQwiW$C`D!=$m|@E4Ax!o?moA&HA`s9Oa&;1!_UbRHR~o|!z0m<| z&%4!hZ*mKT3M62Jm7gCxK9p&{DWtCtv|^BeF4(v8+BG}^Y1eiOoge*yLIn~q!phgY zGKR5e^*waVz+VCZU9fNG*~OAZvvNg-vBxhdR3HH(tbDxtYy@i=xr=)A`zjF71^afs zXX0oe8^38A^$hz=p#ljQFXd4+HD5Mu`(EnrsLUV%U9fNG8DeL6F{5pzbVIxI zgq5GdPI6{PBg*L-M@@l%F4(v8y#`H#*tH!+G{>?pg9;>Igq5$cM4Gd%eRj~7txN<0 zx?tbV_qQ7iV1WUv>HLG%3@VU-5mp{AS)|P(IEJt}JO&aIL zpaKaPVdb;CVimS=(P)~VI6@$x3-;}Nr6H~jJJ4)I{q_Vgs6YZnSo!YHF0bf?Pb&1( z;E4hOU9fNGgvV`~Lr##<_a`%`KmtZs`L282WAqEp+27(dOCX>N_U*i8aY`ATS=)-t zejdx90tvMthyLr&D~F{LpZTxQut3I%jnC#Wvib-i7Apk;x=f=J$*QD}NYy5j6B%i9nP%l@ zl6)hNLIo0ceN)Kz<*l&BYegS*?%yot^hBRtHZK+k=z=R|ydN~4&F1toqm4(`Qm8;; zon8uQaaY4X<%--pUtiB)j&Fz32NA^r0bOv#jL!!PW0+^$5ZXs=9fb-c%F9y7$*#Sz z#qaTa?e5&?=}d!8q^su@2?TV(6*JxsexJ?`UW=g5e(s=9fkdBe3B<-rAIA;UmCIyT zuSGE%;}oj1kO~BJ!4)$_&diBycR(6VbFZUNfrOpUY|_5BDc(D!h_|sjHkd6rkxhFa zY!V3Qf-7eHPW(HX<+J6q=hv?kDv+4pe-c@-$p*i;`H{ELBXlSW56GdnGukmoKo?vw z`=i`oepT6QuLqiW&c1U9ho#fO#F0Z$}0d zNWfiBydRv?mvtVhMbC`!5(wymD`x!c(o9X3yuFd6t?_42fdt%_#WU%6cVNpCb`gUv zK>`6?aK((D?ekV*tsP9ri`U~AR3Kq^SCvfW@7-zjid7lEke^h?=%_p>ElePw>(!vv zB$gBT-RE<{^k!!gPL|Ns!SVm?R&SewaZ7sUem(*zEc)_7Ifu543MW9 zIO3_RQ#o;LjTt>mD(OG_=?p56@Z1|9zd6JXr+--RbDVH`JSWWl7Sr+VS~0o)PzDu9w6VA@@85j@p6W216N}0S)k7wMpE)1o{i{1N(*vXbyAzX3_*I-X=f6AgeYKTWaI${Cz6 zshdR1Uv^_%2Lv#vDDK4n5#l*7-OUfkoAa9Nxre_%K-Ur90Qs=1M%djcn75IT+M2o# z(qVUNy%@ik(t#v|H_#7iwW zv0+bN<)BV$HfFSsKwwwf=&PEKt1U^uA#+ZoDZP|^+niWoh$q7eCh7)V*Ho;kL%iO< z;m;2{?Y;#Y!_dayY&?g9)en0UOimi)o$ zC#=tC$%&uM(v_+fjoI@v?F9n6-c7ZYPr6pZ+@}Zm$acWSP^FPo6Lz6bCx#VF{By`u zUS{zcW-K1biQ0vImH65g?EI4;fxs?F-AaDc`7yXYa^`O`_8kJ0z5#Vvhs|LOE11Y> z;V2(Ja|`a8kKz6EQr+6J|Iziz@`Dqr{~!O|YqeK<*lk}@_e+M1?~lB$!O|T0$FUM6 z{^2-=6-~?* zfwUf)wB@eEGi(Bnv2^Z0<bOmE-qIddDdZTjs-BRU?MZ1T=RIc9r>Nnfyc<; zt3})l>M|F{_5y)j`2NVVUbgL1niiU~8$HzwE0|z!YRF%vHzj>%+42~*T3=B7mYcB- z7rg`myYL;AkC8pTs5FkWVD&9L7*;T`*1NGhcw>Ds?C?YW|HvQqOzC#DF5B zGi&oqk#J?$>v(~{u4LDq8opSTtem5L%Q$)5P3b*9OPQdV$gqM5{4T*qSP~{FpZu3A z>Um=X0=rI>uF=32A5vMF$YadgI7|7Qv0n*x9LBJM3H)ZDQf+U)SqbZZTnP(_76|NW z+_YTt?xj1)+8@hfT&Y{E9R7V@>EhIjVFeTTU4mz3+MQPJ$MO1xHNpe}yG|F?kb6FN zBKC7bd5p8=7nKp-Kb0kW0vJ{>f!`%~>%M!T1o!`?6gd%rz%Hw>MzYh!mSl4~XCC9+ z*b2q?sV-|X(}!UN6Zl<%S0i!JVLBly7RT4vVgkEzW9?<>t3BCct9=d{tyD3c7(Lb~ zwk^X7Cd6yk|FNMwIqtf0I&4JswcDeoC$Z@>qxvnw?@2o{rrmTI-@Evme(jm^z>d$9 z?;%4OR9VMJSC)}l?DGB|0)bul-o@t!)q@pdwHe#}53hQP?v|Kn zzj=-3`A&QC_GVWeqi;r*k}<)Y=~x5^1a{$j7th`qKTkQ-xDo5OiZZMS#FTPPo8G z>=duzh6(Jd%5;~%)HNhmUXJI)$nwidRa{+`nBdK@f{AUOp0e5L-|*_McD-}0a3kiu zQja+uY0W&|y2&M@>XD%@&8?$ zDn5t(WNP)l_P>4t{;%+-+WQ1~!!rZ6dT1Yp6)pWAf%^<9)x$F%jGCf(Qh5;r|MM_vw+UjM&wJ4RZ5iSiuDDGw`~c(Yea+=oYNZ z!&@M*3;$Pm?VaQEl)9(vncZwph80ZU9snN~HQu0n{n?zYy(ALYh5swO|KYq|DX?kE z{v`V_tY8B78Tg(rr3aOa-R8_^uAe|)m-ruiuzS0*lh9 z(RX3jjU_~Gd-xWR;sV~A7(6RoX*5HRwSV88VFeRn|HI%`wz6p9Z>4HtxIkc6MK>?` z!k}w#dZ~uTXfb%WQtSO6B|5S;X z?I<3jFmSJOJ0n<`uNuX$f(cxCoM$JjJfvJ{ZLgeII8q?6>&5#n@)?UgaKu7enfr`# zR2lj6r#ybjD25eG;L77FRaD$X<>a;Pa!kFE0)bsCK8DDV^NJv>=@=g4@BS;wkbu_m zN3)R(E11BQ$N6(``+a3y|5x5-nXv+aUCkbb$=P<>A?MF{9wY7aBgN3d8~P*;V_3li zt~{<%?VMAgJk;L}4#k570=pbby2-O1Z3f--|L_>sgFYyYCK-~C@dFuFFo7$N^V)`m zRZ7mzcH~e0egc7A2V#53Y3J8N!(U^0jPq}QE067m68}5B8CEcXE06OT#a?=By1^{+ zh0ly)0=t%e>?tpKw;G~rjo>jh+v&6Pu(jmrx)6pHOyJ7ne66LW5%Z|Ahd4FrBoNru zvRj0_tjh}ceq;cTv1g4D)3ZBEIx}Ec!33^6&g)b2YQRnW?~&RqJOu)~a1CR=9w)gD zdlvYG)c)WkR5!*1t~}1qd|`cd?sN@W(4mDuU>B}*%=5zU)o1C4Yg5}b4H;H2f$NC# zxuOM@?Cx_5I_Qw8Kwy_xrTIjeC2N>&LytSEgv#8Qz;(p=n(EJuSbV=$^xmwO3jQwa z!WE+Vn@nsYRuGy5QPRnjoV{u3zunSkZ=5zF`nzI|<+tK35 z1wsvMOyF9x{MtR#is`&{rjzS$6A0|W6}wfcn-kiwTXS6L_>Z|lWo}I1TC*yZr`nxG zc(XD*Z9x#m!`)H!c=JPct zYR(o`IN|I)mCE9;qp~t1Ty9b)S;*4EE1&QRC0?U3d%Uu@-xB$XYl1*v7tTWDYk0q9 zEB8meliwYP6S564fmbN;x4!rSp66_?RP-7r5ZHyYDf#GN7maf4a*$F{!uLx>8JL*B zE0p-27JhdW<9o5n7K1?ofn7K&l&`fcf2sVFI9J)m`Uu&dn7}KPc*XZ-HCRg0az)wE zRUohnXSebkNHYU=N^hsq|88d?ixm@ig%V$nL+i7T=k_UXqa=aAE}W&y`0z?8;R(F&wvfNKf6cGU{O_Mt@_zXU1a|#C*jrvR_5qZHzvaZC=QWu_&QaxjbVr62 zOpI9=E+^$(f(Nx)@;89DH;h@8b+PhX<1Y}{RopmQUU}p!jDO#a6A>?KFrR(-%Bh$T zh80YV=^82jH9845hHHttjcc+gvsWlnU;Ph(Twxvh%g!^7fe+E{c0<1ZQDj~PYW<8J z3@iA1zhy+p6@z7v2gY%t6Cba<`hL1HdZb8TSL?-tWT)MwFf=Ef6AdbBuxnjom1kiQ z3@ey;eJWbkOFRIBgVQ+ir?C->8|10zm-ZA0?DFq9Og7xP6QV2@a$<5=Emom!s%#t? z!LWjfzBYs8OEdRC+n8)l>~S+?C)&Q0Z5Mt>_LMt0G-sAUfeb5{z!fF=T7aQv<;q-JW@X(;Ag~M1 z-SRuN-ZL5as9ntj{`QJyi!p)gL-LBGkqwkhc~0zOH(!CkEQV+N&89r|8c#;Rh3MOzxN#2ht4N=lE+A!~i z-U5MLcR<&f;CQAZ=U3l)6SHR>Ip!ZH_ z#X{y1h80ZUijus?GN7)q+02&l+Qb5ZU3l)6*D9`8CEsb*lpVa+nPCMJxS}M_TN-Vz z!0`HPv2&O}U>6=c;rEgb%@n=Cwb}JQ-5FLeAy%jCpA(zU*(#BIb}46Nlt5tD)B`Q# zoAuAbVn6MgI1gthWoz#jimJ;Xh80Zw7-cU9A36nN$LR9^x%y^z<)!&0<)&(=Kwwwr zGw!n8=c5q4MO%$z?apyZ#O}SyqLafJRxmMYlZUKKXK;6(D<`sc%~yi&ELCO{j}!>( z!eb}=-KXYKWnup`<=atl*EdZ3PV|yL)Gq_w_i7$P_vt!ihv5*#VBi>GpE&HoJHYW7 z-c_p=%g7+5S@bxD6-=lDedL0D`=Drk0FPniwpIBy-d6b-B@)<$cYxzn(pnZM_3wU? z-J`}ctY9LdhM!z9VKGg@0)bt42RQz8j@4o8%op-#wl~8HCh%^O{266jlNn~|Q5|n* zfxs@j8ysIpAEL+JJ*Y_+A951*iNgfm6_dBsAw#CCUzhI6vJnXE!h6Q?_Y!LZwrGbL zwVBCBLGb=_XctesyC=`4iZ*7I(3mzEz;jFxfn9jdI6lX6sTK>dZ%WU|W(+Hsz`K<4 zG30}$Ec2E+)%XZZi)x)-hd^;f|PCU8wi{!ZQho3iYP zFAe7ZEKFb*-uIW!BAZtz&Bl7t^_>hERxn}bV=sq>t_69pcK;~P6R(stIX-k)qP{?2 zmsqnuTko!-`_79F>tV{Uf{Dx{7IMmn4G?K@naB7z?wWGGH_+Gs1A)LUyk7ucM?deF za^WMPZ~7QBtYG5qU440UgUxX2TnUd+XQZO6stlktlXL|FyFza1%R}`xf#07MoY=pn zNEvc5h`wE;$FPD4U6(hS%5M1(WV(zKFLrHHjEDB1=Z<|)Fo9iPt=?$zLbt#!GKCZ0 z8m>@&MupQ=eLpK$!Net#Gn&I2w*h&h-3#04dY+wPo;6Aj@P`=&(eHV5u9=}zyFRK8Y zbhJCswCK@G@hFR+e@*llRxojJN~Xrqst9IuoXLqZqXHGrE0MG)QY8@BfTY5F~5h80YhgzIW*-`NQoeQk{QeJbU2_ull#9YcY@F5h0d8eQ+5 z@U?U_Cu+AEFRvxt={Gxbh80X``-WCGcEL|qZCiD5{;YZME}Ys9t0NHDrTrY}y9-Vw zjpIb!&m-82u2)H=seh@J<61dTRU4!=sy!|Hua{4`=)#XWzud&#ZpzNavT5V)kzq|E zHCVxfQ{W2u<~>^o+_Z$p800sQX^ei7y$g(FOkfw@H;1nUD2!t7(rZwMcTiaHc9wLAh1gu(_hwrva0?~sGfS3Fs6@*%#ay!^25o{@|X4vx&I?ITRX8ay?JM) zKwy`+yJN&B!YZ1WQ`L{HeD3-Gb|b~ahx60rg-%JZ&~7A;(K12J20EM3dsVVPU>Dw5 zl2>%tNZ9;`M)afUNny`POpJD&E?-(d9Xdap&SM1K@ncc14d~8scLf5w(ktTRAtAHi z(ymFInAgFNowrcYdp$oWSiyu<_9VIa&e^cKop!|QzL7gSPyP_+&w30K*oF7h*gha;RiWek_kHpzv`_ER`v z?catil+z8YP!6S`49y+7YjsrgqFTxQHxj=_U}^wK{aDTy}67I0k5s z%JfGIrvA2^oPFxSu!0G*z9Zy-bIak9v3BI{PjoY8c_)kLhDri~T_eW~k;`AKf`^^7 zql42QHf0W5hm#`r_6#eS_~joff0fq2wL1$q!I%|WzNsU5b-A-ZVArDIgXHz0>%o2Y zY)-7W*N|mhwf(dbyQ-7TvTWS(08?Npr5ZHC#Y+t$Nz+#x_tX%86EY(CzDOm|2<%$gp_iOtau94*YI7zIS5zvsEP5(C z?)76>!2}+&=BpZAUMVznf}%baB@ozUX&f$Jxg)~|i@`j`>se2fG1s$|sIq;dg^ys`#=^FDyQ6={j2<*byV!XcSm@|q3FO{T(P$4S}6TLV2 z%k2-mfTA65`0Ub>sN>430tuTvGE*wyDv&BtD4NS zzlT6z7tZVD^UgJN*vn%z*|JbqA>$VlIIovKKQf*x(5o(U>(EvpunT7!^S8eI&&qwi zi@^B=7aJl-?85o`d^I`W19ZpS7s})!7a_AB6L=1qk5hY_Fi-yq)W?;|^+6Am-ediR zbrYDt)k*oC!RU^1BmI{0MG6%N?856pc-@cOD@xh4BT9VJ2x0vPCUBKio`GGyPdRaP zpHk;Xe}TX*yuO9E)%5L3DxVoGC>|=TW5EQj7Rz%#YUU`z9?e#64;>>A*oD{W@SM~K zla<}I`zh+l;tC#2;HtNL{-b_dW!FMqW&8DbVFeF%;q^wmvQedpQh7~RnKCj-SXYDz zT)mg~ah}eR>D4Rp0fQ8Qz%Fg??!SErc{UX_mM z#pJ3;R@<#y_%7_q2_&+8%p$p4<#0~)IBmjy9O=cv+vQ1E!Nl~>L|);zNS<7-B@PxF zv)`G$*{)Ap)q(m{?h?I7-uE}t3H~AS$vKPUmWH!hP5wgUG?ztk&k5QY_xBGB*r>`r z>?pI5u!4zm{HTWWqq0tm<%EvD32PG6o6SufClJ^r9#wN2L-yo&9|jvHNLazd0v^MW z$EbN-dmbg6i08zRF%ty>yKsx}xgt50dZoP6Ja1h=mv4EI_WGm#hw#m8L-UW=k*70#DgG`@)XsH*w&h;rj?pL{WAV;5^wcE> z(%DWVunV6b-=(r!Ynt^_hPSf`eP-tZ0gD64kre}>MSu&ee$}2VSvLgUT<-+YnWk}9H#oy_wfMQstT&q?r^Q9 z3ur5hm)?$sA!fYYoWn?(#{f=zA?>JxvRG=j--|vD2!Puwg2+J<3|;yMz&K8f+!zG- zn|Q_dcqeLd_?fiS1cVs)d+|5%(OMq|TDHs|mM?BE#K6Q58yC2{DTtK!9>|aC+7t(B zrHp}GxBnrKYb^gfe0>nv8L1^ocLmb?Ch^ib+ve0Gq#vAH#P>v5;tuO)^@Gv;JnFx8 zgUe0&{QKF`gA)xg(F^ z5$#Pg*DaFzFLoCQ?7}V0=W)7)&}&tbrI?wGDL!_5PA@8AU=)wBbAcU?G5>6L>Th&a z+WwISO81M(h`VzJJgXB%>SSr8k-<=m}uT@I*j41E01}?i3v?dP*=@Cb>*uY0)bs6 zt&^*XyH;O05$ZaHCd4gM{~S7pT%Ml=Q%u6h^LHsy`mN0Bf7HvGDT^ns;d{fV4rWfELvv=RkC$u{2<*b=#MhrYq)@X5pGplKzW}~F zw<(`peV3RS(^wMk)T7O((JSUxO09hw5v*Y1PwQ+L&)e!(s5a|fbvKFD?pS=V|5$H< zz%JY(JcI7rR2o^Z)34xLf1#}~v13kFb&QUql6j298xv^4`(u6+PEQgD?85EF^RM2e z(i!tNm0hh_Dp@(qslE?3Kcee}pI3jZ=79gaFp@F8zAvxblATJgnVu~B=T{tH1rxYM zcnAQ0Gf$$Snp;d?|(%ssV`2YQjhr?H1j{0!8+p{7&9e^^s6+K!e8XTa=ru9&?!!SvtQ-FXMX1^?xNk> zDSB%v{n^GrZcwBG-`LrZz21wE?pxJ=75plT%!Z~DD4FPK$6MFBAeA~E zwv`p98h~Bnj?9L+e|?FCOWOYsNjp>N#vhh)k4<`jzY7!IBnS4IQ*t=Tj`!%7?oFlB z)|$vJK?VYWU6q}3pyNnNYR_xN3HLiG^!$%ynvnT2Wbey@1paQ&=~J@wp-Fc2=VtB$ zrQzGM;nF5A;>c_xty=`-y}6JhrWy zN@M5`>GF#~1S@G-|GEtI_DlGi_{fB160M5bBwb1BEX2TskNv-`ZnZd%$LM}OneMNd zt3KJqMj)^Yw>qzp;+{eWZLgs*{rge)Juoq7^S?2=eAAA@HCvKGH6w>;N=>f`1a{$T zf$vuEGoJQbZU=@x6A5k~e6|}qW>mMEm7caT9#v1Kw@W*L<-G+2E0{RScPbdW+l%Oy z-{XYw-3j#Pw@fG*yh$Li%h)QdI!2oTm0BWqD1EZ*8gvYQNS1X=fT{f2txGLnSI4C4 z&n@TF0crD8_b+2j8vm4PwodR07ge1wKyhgZiqyhB?#a>m7O^i6L) zGW~2liWN+JT+j!eAM+x1{Rt<++l0`Mwhf7KElYvGu3wj;s{2vDHfY~PtFk)M9^Uq( zq@4}j{Vc3n88RarrcaNo{+xL)5HQUv>DUI)nBg{LV#lTwE10-b`Y(N9Ng$8Ww|i$g zY)dop`AHLjz%KEqW*l*)MVsA8w_P4We-QTpagU7e+&kZcez5Q+XI8ojeKkz@pYyLi zr%|EWKF+fUH9dR085w-DwLoAOK0lSJZ3{JZTJ1`vnYR|s0~1T${2Sw=qc+C5JfO9R z6N#GNQXsGkw>s|+nmE#W1y5nDH&EP*!+l)b>*G6Av~Z)#+I|NoM{l7&hzYT+qV*)Y zUVaE|;@SuVb~VZF3-wn~lGEIqpU1mF9q9DepCRbI9mNVJ#J1YCB$S$`ABN}OECm9) z8t)kmzw;=GVb(l`(~ust@#iZ5uj*2)U;&%AsUo zb`2h*Ub{imXGtOGcB>>!I_5@WXnA~@Kwy{e^I7m~DkTk8Yv=B2R8FC@M;L}ah*|^L4gT6^v!G!qkGwE0=ooszl^E*9fGCE!} zrD_pi1rzwqnP>cZPNVa(yvu4IYd|o8T}5rPVDT4!vM@MH` zbQY{m4kCMRX;;3S2#%-yM}x*IlCwxRDk_&TQA#-~GFI7;Q;4>eI=O3GQ3s zzBBH<@~p{(VU*4vFEzRKSm>o<0{7c_Z(`jjsyk?&l)d7dKwy{HOYPi#9E~5lN^-3y z_O>x0p2zvkaWu=tU3#@+iO@^MF0nuODm0#EY;7Ukh76&1hY8$ne6A=jiH3&gsJor&6i>U8m7K=Tv2h<1K|=Dkku+$@fI+l1lZrcF;8Yumo_A4!gv@+RoFd)Oyr% zO^$&%UXL}UL< zhfpStUtt#>HR5^5)*UIEw+zBB*b8H1n7~g7J}a|3jJo{k3rkN~3IulH@gN@KP*2+B zzzk?Ix~?$pg9-eU;7@0VXu2)f8`_Lh2?TcGtCH8tm^zqFYSSB5Recb~uP}k15 zXB0haR|n=jI4=;`g|AAUrFVKPUFqEvYHrdHtY88^CHS>FHIAP5R;2x7mI?%R;d>09 zeQh02cjfJoA|H$Q5=`Ky1kZI|oH`Z{;GxhN6tw`#;L9)-aXX^iI zypAduDE(i}Gq*SO=$Qfow^1wV^7);zqH`3aOrHm9gDoW82@zn^GZ+50HIt$~g~Pxzc`!J+H7AZNtt1z6 z!)WEP{mRPo4)ARFN;puFuD)>J0Y1Yj7_fMQde#qbFg?8#KDcVvM?vCsqOz+^)$hI8 zCrdYonY|XeUN@C&raQo==j-9t4I_zkaR8I3jWGSP8IRG~`WZ2ad`C(v@C7^2N+95AAscpItcfxNzt;*|*M%{Czou+12d={r7H!A-TOJ)~qA^w{}HOX%GLmR>ozB zLROXRFDu$OmW?s#48HRVV0=kGX|)f9iT{7q4&Sm5-ttvKW!0;MGF^6(WRFsLjWnKJ z>(dDmQwkq zn(JExE0%xdzelQ*D=~;mBWar_v9NzGNfuLg!}EEc)H4GwN#mpTz|2-()%ctE?CXuD zWKNIKRj`^usnXBy4|#TQXT6O&{*zO zug|V0Re0_J)4JN4P6zg0QO_+-1M{h=tiq0e*NjqV`s#{W8zX5-8NB}b@8@05Wq4Nq zDks{_NK=>8-XWi{{CB2W*H?i=->cO`i||8`)A5pe=#r&s(vZQZwpyb1ARP!V%T<~L zPGt`IzgOl(4XM5} z%;HCJhrH&BteoHfgk<(|zia;N~^u4XasoHVTEH^_K zeX_o6w(H+(_rGikZCm}fzjI~bEA{{F2;KdkBx)2qN3(q+Rr=)rJD0Lh>Z$p)>)+2& z&AMyW=4Qji*kJP4G*H7=pM8j@2ksk_daZkrwI|nsWAsUBQ%nf_{fT^;b&UVMH|x|g zb?WmXc(7oBuSl5tEP|#qm1^Lk1}m62lT}Z$>sSO`?UwTylMC1OLeb|Gx?@YaKwwwc z~2R$QeZV#nDbGS?Fr1FQxKALkOFXK1Q%{p+;iGBqR-H6h!Ni{ThTxa5 z9)`^h=P{1YJw#Tzj-^c+bruNh!Y#tz`g;8!l?w+_lN3ofb9_#hJ9xm(?Mt9Xv)24K z|EQ-&Pj!l-aVNHEu!4yRW}TtPC>J)^c=NVuY-mh9KJ=!i9=8<;>^dDA0554Sc=h$* zG2TD-pefBf>FpF#&5+q;WO`$Rr) zp|NlLXxh^>fxxb#X9vUCwV42EefUvXtY}T=%9L)bY^lL6gTKR|-PH`(`*&1{NOU`5 zNAJD%r@;=bG+4nz_~OA3y*d-}udLzMZe&7px^P4wopNfCKwy`@djwoo&4HKw0{Kym zUTRH`AM8S}k8i8N3MRt!dxK|44ve0o&)aItqXxA5p{_Kr*;1K~HvMAiBk;4*A1+-y_Oj?ZBA^`Yjg+tN1IjRgX`@HNJ(S@jO4kyn~f zo4V)9@Ui0~+&p4FL?(s6<)(A^c?6E{MuT)3&;yOlHCVw!Rrfq7Z_pn8{MpKX^SWLU z^oUCxdb}{J3=`Nj*ewtKwr&q2^QQCv`CRt_be{hoVtr^^*+8RJ(5=5M6ihkfM-Hrj zK3!YEJ;SvnnC4geqkc5vm>%_SG_njUnAkFEF>FZj1&6IO`L%n!X(Y8iVMJF9m@W|5 zB_36h_Xuj5euMm77F9aheIuOp(S=i8lwF!hYoYZba~O5z&>noWe9!xNL+Q*7&q;s% zt)*DOM7@tIVO)YObQzV#k4ob?gxc{4oosv2dn24#stYc`8`N9J=7V?ln^JA}8~iF+uxKLPy=Wsz8#Jp7E0`E~ZYwnF zd_w9zv53FvyB8){)=1EOctM`k7nymi`Vb0x!4PQlZ{J-kX>+BbBbIGz6=zy#XtjD2OTszp74t#-IE+k;-#e zI$YL+(aydCfn8g-6hpDsXnVF9_%+w7mf{y%uSi!{F(}ghaWh2RE-(2lcS*Fqm$HuVW)pCKru3!HYf%OoTdXdRuPAp7L zp=0-Z!R>=*U_kvs_&$A_I%(7yi4_*YjhO-J4nIqzqeg}B<6;}BJgk5duK6jnO_~d| zyPyD8F!AMXA-D|pP(K=7#EDw-ct(ou9605=MIf*XA0h7>d`zL!{A}TT*L=VVCLWG0 z0^>v-b(6)~^QfqkN?YYLf#@Bp1OmInGk+E~jV3yegI5O)NDG$&@F~8nHtPLH>b|D{ zqRbAf8-#z9T9_BW&w_qZ@hNS7VvQNoXq~$;(EB9cj|eH4Xw`TJe6uQ4e{g=mi6wKV zQH!+ou>Qykzyx+hx7Y#uj5|mT>Yn0+$=hl4sN5YA7rg_lVB+i19T2o=uG(x(IVUoV zQfSRuOX2&)GXjBK_;=#9al52Y$Z8MWo7@zB4@?{~Ed;w2sp{7Cw6m|Z`=-$RVf+=a z=~aQiE`0UyD&{Sw(G83E9Lr8)p>=U9*nHj&jczCCN=J9n;BcY`*k$fjm8{kd%koc3!W z5ZKkkejBuQwvpD()@I|neM+P@d3*Tt+LJVbd z?yZyFhgfn#-fx(?dnM40?pDO&hd;sNRCxTV$aDkLZ1i0E-c6gQ zKcG(nZM9XGG(F#wU{|xe4ParvLnksy zYnatOR3NYmUvK=KAv~VeNoqnK{D~m$(W@cL?T<8TVjp<*W(~~T@Km~9Cmb$KUIU-5 zn?iRBZI0KMiSaa{YeVv>tQWxwCYHBa3&CF>N`tL>aw6tRJpCGDN1m$#1OmJ8@5Hlr z_V5_T>yd$*dI`TECQA4Sr9nJB72S#?+w>3!>`Gp` z5*oIy4HNUDIWf3)Jhh_k#AbF7nQ?nLw9T`IV@C$V#AYj?d8@`y+j%goxVr)-raA(2 z3*p33lX&{f#f^+g3?^8?#8|VHaDBBIjJMXVN@?~ep6=HrWLZ=jvis8_Sll2ChBqGp z^&J;O@bO?cZaD(kaDI*#99u&5EZr zQq<(ueNTeF3lmB0mcpujUhpY6mdA*j8c(0b`H}Xmd;|i!2DDxV71SA$%7=1d)v^St zHUjd@xG_2DlLuE84TO+kBfuzm5tN$tgy-%f;J())uA3FR5wkT z4D}@KQ8nAeQ?Xim6R!?>1V_iNO+RzN=Gj=dzd=g`WhYVE#E#srbr|+J&4rn>mOvBt z0Z?<-T+nP-2+gVn!r9aF;9N{DblRl7uHuF#(e%6aq)6w4pkN~C^;{TOxd5IW8pMeu z#mUsVsvglvTLRbAIndQ-3%vc=3;KS@flZy)LC0==p~K=ipo(1w29=#Sq2_(HI~Od7 z^TRcQf(f&+bD%?;Rp7iTiWA>XOryp9zQWk7zR+WHHdyEHg_(y#;6_C@bW7R|Q=4`L zy?wJ`4c{@nM)i*AwbxIh--rAL%!ZkV3L)4-dzEC5o<_@h>XNCtQv?FL z7S_&z8+-G?%U-*-ul}SI8f9?>Oyg~U?#Y7F(jf@E?+>Al*vLt<78x_DrQ0^H)Ibz}*6YUB8FTg4?Idp~(k#PQ>J= zQs~*J|h0kZgi-%uf|8wnXr?uZx>EI_$(%y?M8bLvX zDv1BHYJY@`pW0k!)vZ(-^~O+&Fs~&G1ah72nhD|0UxHUTkFEOlB9-oz???;QPbw1> zM2w8dgb5~ZVB3HuoLJ6d>~lAPMpt|fVgkEHm1M&0jK`4pK)b?iO9^kQux4`7s%M&3 z_cFn|o(1W!d52^fkO`YE*CJ(Q4Y-!rmDvwB&t}ylTfxIe29jB-e2wTN)&& zC-T)UI^Elma$`q7yxxTGB+xjO4!yigHi>R1V+F5c!QaI50CB2=&6+u0~30t z*^qR|k+^2G;79djLJIXBwpU(oT0AQ3s(*17jQM0o#w@Gg<0UKS(GFCA0 zt0)WX7PTT1oV9gpU7PUpNLwa<{Mk?-u&cc~3vP~UL6&%GcQ`tm?AaJfLZgoD} zS2LByw3{k_^-qjCEn%sP9U4g(Z+|s;eCeO3{G55Zv?tz~goM(x1D?P{NK#5r}IWui<8J~|jkxG9} zd7(KQU!}ncCUCy6O4TqtmHIi^$=6@T%b36}{5$=-?(Wf$R&wXvI>IlA37pZ)N28Xf z(k~s<^5A`X0)bul*W@`9pHr!K{?4+ER!cN5Kjpwgz6w+Gdtw=0;fU8R@*c~s6q>uI zr^cb)dAWYmoa$Ad0VfSK$7cS!RzG3li86eCyzV)_+D$^bX=d2370w(JI5xi$`TD_* ztI{?5%mZYs;3E-Z4CnXVj$JotOk%zWzXv9S^^q#COZ-2`3kmid@l7DG3ttO-Bz0*V zZ9Q#=#_aGCNXtraV{s0`VXhJZ++#ry>9cJToT}Oj}TI}@sDOpP!c5Y7~7V9(@g#} z0~#2FkjgFRIMHF@D0y4!~HXhfszII3;ubjaven)0e2ckb`y;=RY550a?ctbCWn$&e5c_?D_cS@epGie2FdtndHpL* zGpfwHqgnqhP&f}v{2kPeuR!cU?v3uvkE-4TJF4=%t66K_Ng%KbpA(O9`x8m%u}{-7 zbTE5$Td(^5;eL3sJnE)?_1&O>%VfEcPfggeC6v7AAID>~oco)!FW9dsju^nOf{6^9 z1~8Bx)%nuVoH*92CQX>=C=c7#S0Jzpw+O$tJDSq3x@R>j<9i8hg$cJF))2*Ge7PRW zW0?7w(LS}#X}%cr6bS6X?WR(78}x$gzEq+~4jn3-IX za0A(C>2QV>Ox#MlEp0y?N@{vf=fvBn)5QGE8qJ0tqXh!HURT_bwEvHHleEO9&oUW1 zYPF`Ia4f?LCafnNl5#m=shiFTX>$>=tI&~0r~SjQf{71_TcoAW_&@4f1}AhHts#fs z&(g?~CJ6*~MLBJemhc!s)-yS=y~je5F*sARrORZ76->-CULh^x#4d|WPV5H`b z_K6ELj|)chPO64-^$sk&ko{8urn!-tpZY0ZPk=vUd*s|Wt8 zo~6x){4d9o*L$5foc224rwn;=Tsi7J1Lln4si+0JH5ogm!wAKTTz|SolfY-6=A88= zcazHb(^)?%hSo9Yt#~fGtY8HbPj^j*=#g!SXC0XnO9n^LQn&F+jL#c^z^?GJ5s_X!rCUT)n6Fvyv7xtm7@ERx>++z^;JY zcJP1uhR;&P(@vvol*ip86@_L(gT*aL?bW5e=hD*QLMsQ-cfz%@sH#kuoajv4k^*^e z;@$Z;+NZRQ@^0v41uK~7)hYv0Zn}_));9diEoeM_-?E`{ZGK;Yz^-|07I>t3kiWG~ z@faa)lc{fdQ>CSCf`S!Hu<{Iu-{eW2TY4MkeqzCXTQ)E>EPE(RxZ*R1*a&n84Q?-*sVRGVRZv$zPxS62@e(3y)Z+ zROyCEw9}sNa(JG#f)z~Q>y2kF?@s1D;Y;#^PQQh*4D1re0BXhY)w0uW%L8jSRj`5y ze7*6!SG#HS!|ww5@Xsn?3;?^t-u7|*WcsG_4te=iYXvKqz}FkEaD1rvB(0H4)g5laoidMouVA5ri#V}6tAkmcY;4#&;X;QKt!-iaSVJ?MDFY}Ew? zE10N%Ck_l7w;|hyZ{+_$C-;6db>~c_uKr7bz%G2B=NXOV5i~bDPgxgMsbB>Y?UoFO z?UP!PG4nM%#+1ZhnsRcZ@-ADSVFJ7GeV(t>`+sDed0bA<`~Pn$WGSH{YlyOzz3y|( z5Lu%=5ke|$iuOIEvSe?OEETe}YNhUT?0b}b-y=KOm-x-?_we{$^LhVwKOV2w^S;h9 zGiT1soNL_1QVaiL@mxbo2`iYGHq!~VjOa;%c3);OT=$NkjnyYbpDb;Tz%Kk`U^$nk z4W+F{)QFXRbtJ4{;t@DOgNZI_TdVt*sgCN>fe;TE^jV!ue!HR)yT)C0 z2mMakWa{J5jF>ls(7@yq;xOmd5>_yQ&AA~?QBQ;C2bdVXElhJz^>S!OZxY@&fyEep&50(F z4PwQ>XChWGf$u+?6J9%yJ_}nazS?zxBd|-eZw$2BZ$tv#&QM<6D{l0Qm$%q=&JhtS zn84+jokyq>h5F@Ur}^(htH1ylMw=7w5eD)P-a%ks^%VlWdk8Hm{9tGH57?%0jg2}F z?d(REJr5V*g~-MDIV2i}So9*n!+TWW^J8Bq6C&Dv83yB?tWlG|Me1BP~VRH$=S>L461I{ z^kloeVr$#a9D!Z9yeUT}9O#M(+r&-AuSKk20$)Srs{3j5)aE_n-KoDg0=sZ6V0rEm zZRjWaG;!>%pCVQ;!QT&;)XCI#^A6EDs~K0LuuJah2@78|!VOhNb_XY!&!mmh=Zo>d z4I;kJwz^?(Pv;>#YZm`M_k6&X>D1C;mT1wlQN;g?iKIyZaH;)M7!*BSV7Ye&S8EuE29bc*YFRIqEn9@S0p`r z#Sz#wvGodQs@;jW75-uOW3m`RO(Jwfa>-i6$BSL~{8+Z0uMup;{WZmGhj!eVV*sLs5p!2g9^+-#=o%C;E#?$whj;~%5Bc}`65vwg;2W2i%+UFEF&<=k8< zc5$<^vNLJXbZARkVc3eR3OvJmFr3ZTZoLXaoYY~*h80ja>M;aN{KoG2cE?D1dapy3 zx5fb07yUm46Y_7%K_}rZB=4H^K?IC`@X<44hXs zAv!OWyDoIO6izeQb{+|xsE8Fz;Mix=dXp(ph8#YF1B5!i*_?%67f`+;<-v9Y+m?_v=vn7}O`n@jEE zN9WtyicRMva|Cu}c}0Q7k1phs&nfmipRm@CYL1^OlElp-Rxp9cD5zP<+s@LqqF2s2fQC4R`u8{Vg(bp#bABWa$map$Y{~%cs5617k=8Y z@1yQ6p}wnHiS|7OP_T)FWIbS#wn316QwjBaB4?j;e4TTC(uSTCE zu*>z*OsMPGl;o?7XQgE5_6~HzoNl7t9!qJ(D_^j^mGh|cFDIb0KGRy zVc+x+7Nab+4Lvx2t+=w)Bnc~+Seri=(vO`7|98qv2>zyebcb=8crO#AJC-wHyYB-i zw|gzu*x(77)u&+Phj4)>?riEp^L!)40Rf{WtYE@Q@PuYo66oDp!D8&Q(5BySEft?^ zw%`ct!bi(y`hSy z(BrEN#8=@&!U`td&0GQx=N^Q#Daz-E$+}+jK=V%G%E4ne0=w{4U^5Nd`_tk+8H)BF z1qmydCtg~nvU5!i*V0=pk;hfu#CKEhnjkrGxgLG;5R zZ$}n{XcVy+R}UN0(#MAcyKbf&fnEI7J?&shEk3A<6BiGZa6SpWF2T@MUJm|xyM^aJ z7sJ`lhgkNTbQYsm-_cah;kx3RYF`PvFkPq>4sIbOpns%*5pPp1=%+6i75)c%NLaxH z&TGNeOiZ+-{kAPsY}(R^Bd}}v-6*)XzX&3h9%eBnwH{9&C+9-y$sUqN|5(VlmI<1l zMPcgtrO@0h19bh42`Y^d;P7-8s9Y*##N)B!=*?DD&@!*5gcVF&FN=n{gdH%ZRJpFN z|JrGE$I2m9+lJ{%IJ$n=Quto62VB~p5%Br3`|-k(>U9_<4_v~Z2PQ_giGf2!`(X1g z1&eVc&VthSRAJ!NlRI0jyX4g9 ze6E6258w#w;_vydbW@ttd7~m__FxGsn3#1mm}ML)fFrv5S&VAk2x`>Wsp^L11QEYM z1b0~hot9mK#1jny?q9RjBHE#J@#BY8cRNRjSi!_vPnKI>yaHKWZ?G8ewg=K%9hWOU z&Dg{d*oB{>GTD!ni)rM8EeZ{@-6B>nvCwBJ_`kXVr;jLe-KTf=r6w(F6sKwraRhep zPv`1K-c)Bmsp9-H%iGj|Y-$CI@j%^!?#{oen4@x?Be3g9b_B>m*tce# zlsnOMv2mlGXUY|c_4h@rVB&U3G#t5g2JU@R-t*u3E_Cv$y9%#cpEv@$9+Zc|=%i}6 zd`Vf)6$P`XnVzH=-R6&o6-=0nh=gs9$H2LRvYuZmw`Vb4Da@Q(NtnPcoXdvI0z9yz zefCu-e$}?&vfNRLXmoqdwUnAg;n>IA7P+8VUu2<*c3UnVQfa-@CVR|=XQt+j>Yv~~PSApYy% zNYiJGaA@U19}hJr7fwCrV&MPfiJp_@(}fM@!&P6YN8t* zo@Y&BC!Xa9>gS%RlfLrG+-V~Jv<`m4y6HL+Rxp8|MC|=MaT?tk_Zm(*b>Il>@-klrR#n>}Zm{y(SKpMebku|u zWUs!ig!571JXJ#9DA;O~0!Gi3y^KY@&FQxLZ9r0=t$p4}}8>TVUCx-Hdp|cI|0bwTpD@*GpQJzZlkLr9keZ%>vF~WosV> zT0Pdm&DP4ksO|5`w4#+Y32oC}ddxD^$JK9!qK#DozMEaxcioRz)9O>hM?aB7g<{W`txX#ODl`acu z&BR$`VL*k5Yt9Al)i5Y$EyTKi6>!~TEw!}=ozij5!i*VA={Ni%Y{y$vE zmo;73q&e+%D@eo&CZgHXz|Yqg(mDpQ7$b7+=-2l$YSt^3Bd`nS@nbo*f~L{LjHa~Y zcN&-B4->y;BtT(I0GMecvKT+t+0ZkV-^ujvTR8%|YFDj>wooH-C5$s42fu(xnF*tb`j5K{m(8blk8UN$3yV1dyVhy10@F<^ z;7q?-MkIEdOWQtT`9)(ZM66(9Y3OQ*^@)XB_nDEMs12s0oq&IdCi!nBRJiXTR7)dc|B4Gl%aE3>=5-@%&O|ZH|iVJ02 z=15H3o)ZhdP9#9Uw9PEWryp}^&Z`e(&7%ZGR^?XM?$!r}9yJtjyRyh>EA(|Rf`F{Ia5cs)Gna?t-d=8zm@jdCK)k(w( zCU6_W)@8_DsY8=T#IkD}j=(OxiCf_1o>8!)L0N0x#k9I ztYJyZzgbmMylLN?r-^Hm$5l&?Wr0nz=Ac?XT)?HW<+Log@kJfl&vIu+bv}9_?XG=| zRJI+dzzQaC31xG49ek+Ow-aP|mOe*d*W02@_}p9rI<8p7VnlTGq~5b@N&ed~1y(SD zODG$;%k-g+>yMIak{w52m-}1x6|-@B@Xl0@4!%`*QvdGNWS&EY0xOunC6r|(9qLQ9 zKPuRsOHmwwT|HHIf~`v@SnsTSuN~^?MME;qkYx$w3anrPmr%Cb&1qk{%j7UwId20; zU{}JY?V!542RLt5zD>kwd(+~p$H_UNR)G~v;1bHdYMi-bH8qcXv%I9h1a=9stuQ@F4tq|2WifiT_N8BrA0**p z+Or4H|0$RlyJIs9cr*h-T<rvPis5Kf7m8Y5j>nE;a z-;6f%2geo@1^l%&{#F~$n6i22q!?-^`a#p0cHHbMCh%9^GMN$kPI%1W?vPd(&#eQ% zE<8TR*0)R1w7K3;sF+x)zzQZ#A4mY5JEvf>r}De)+pi+&mfd-R$Mr7USRZ!bQ9L$^ zb3TI3JN8KEw10$%6-<<{J>!0O9E15wRauO7H$!Qf)9u4nUj7_`U3e6aJq=!l(4THw z&9p6JM66)q?u9tWR67l8&MLUl^up-K>lq0YUkK(b+kqTdWuE}sk-I^*9E0|c`Vi{a- zdjfhVRkIjjZ2o-I=|u|ZQY}Yd7aql9_1xWqcH3;InDFbCh!spMH(Cm}$0}f0;As|P z@x*!5VBI1`r|BPf0=e)go=kS|*&O<;NneG}yB{J}@c$0%6$^h1%OUI65f)>S)eQRb zsI|hhsF{Qb?82jXYz#otnZ7t;S~b^SRl*7;+J-HI-ro*DtX&O@p_V#>CKpdQ?EIh^ zM_?Bo#bf(a7tf|ozsv^J*xw>nFd^@{0!AL#31%zqvKSrxXVD(Xt3lBylQ4l@c-)VT z6#a;%r$6Mun*)ypoc94|ioo@e9hElwvUqjulMcoD*z3Q74A#z#549HA#U9 z?85bt?MjjrP1mhU2cJvq8+6nHVB&${N@(-F0&06JcgRzxQPlXJC%maw7cqfdxIVHv zIFjWft4e^a$Mi+4VB-GhL}*P);g+DxM>basqxD^Sf`jdBj=(NlA7!!^PeQ4t-7p|? zy+y2G;!#*UY&2(i?_bJT44vvAI(N_q`H<%8I0CzHePn%x&4F~M&0wKV=Ts3Zm^k4P z2k}ECIKNz(8EMHjfkINE#QnfIG+%od*?X&3gWSa37N+-(PIS@IPVWz_nI9+bu>qi*}f3FKgh zULq#2>v-?g;M*k~wyP-f$*7(Trgzp_lN~ODMXX?APph>c>`#KZ58E)JVnZMej2%a= zc5vqi>{{T)b|CJ#87xgy7~!fPK##c3CcW=^h*-fyX4G1k@i_qw&r)NA!52Tesc{Yo z6;^WucHxm*mLayoB6{;cI0>1vM#Ksx@CXvyC+>wOy?rT$9PY4-Bd`mP+_JvU4iD;^ zxtg?#&JnSK2|VV+)^aYKPq$RAB0(FDaRheZkz1D6;Dig^J!2DT<$OlO3MTNF6C3f0 zok7RtZX^{Ik2wOn@W`!9c66^Jb!oAU*rq%av4ROa=EO?-N-OG-lR;88{ox4g!t*Wc ztN1OJG;_yZGO|p@?J~xAOQE;ECcNCa39e2Fgt3hsA!6NTaJBPJ_=UHP9^f$op}U}tZ{jw&Q9islBjA@^Gxslo~- zDz%fKp)Lb5C1XaU-;boFC)G&w_IM*bWFQ?UBc;~6i{dwqR1RYV+fdq89tdJoE z6V|)eK(lMc6}PUH62G zSi!{1jfqeYz6S~iDc{x9mIctB{s-Z}+Ek9fu7vjSaMBbGA!968i z#0n8P?PvfImHuk%qR%^^xtwT=>SiuA? zp=>OCPc$t&c?MG7eXha;cHzD++lO~lG+nmm4mcZ3P+$cUxP-Fo_^cQHeew~w$5t<6 z0=sbEmwlr+A(CEte-q}mXdz++6S#!3oU$x`V&;;4AbcOk5!i+MzHFza#4vj6T`AnX zY9n$Asw=omvsJ9`g6ZNG&R}I4#}U|t`@U>t4ePhBQux7_N2^7wU;>wEnapqG5~|{% z0XEK!v-NP4t)U;&iM));0i5p7iyI|AnUx||FoD-=uu+_=Zq#g* z9{GLm3P)fU|IQh4egPdara!sT zF-(HQ#I_uPU3d*F>tzJl(7sJeLC;T1!U`tvDjW7Z*PBd*Gg{zxzY9lT7hVI)W~!S_ zqBkeH!HGLvC9GfqulHi>+sj5%$*rJbT$~|CU>Co(_CqeE#gB7^uUm~ItY8AKXl8v; z%~1MogCqH@*Nm)uo(8U0CPIYjNG_MNPM0mvdWd z>%hK`S~QaQ8xSrBHYRY+Z8lPLBZO*nwwK)R2Zsetd)mJk(G)S58eT-TtwMv{x zWHmB^6-?NKWkAvFfiPyG^4*~KFLtfM14uK=jerU4vK!2|CGO-&Y9_!VOQ&DNfDZMe_n9>=c6sARa+umDb8P>!l4$Awa#u`Xnj zUo~I_6Zjgk*^Ky5+Ha#jDPB9CBe08q+pcI8O7DshM9t&AfE7&OYskhKjtA2zJL5^p z%zg??U>APVXZes>CY=eUiR3_>1~&$P3I2WznHogbbX!Y$7AA27cAb-_K=r`c(AH8p z4wpSKm=5W-n!IdzsR}EY;OocuXMwbB`;DZ(kG}#F*fr`=DpYvdz}w_zEJjvc03Et^ zD_Oe5Uw+DTFNE~17IXr~3V3b9sInZGVQ@tl{a*PkS$+6o8vkw|q4R!JVg(a;odavH zy0Ov00qI09uF(t=*tM`_4lH!OBTVp3W-%sRT1>xu%^^V^HdR=`1YYOB-n?c7(otDy zWI~e>rkKF4kP&+z{Y0Jc^;{l{(cNeX^}f2BbUC%A3M-hv>m1nkQ7nh)bAwd!Sxs>W z6WFC8-wk7?H3+|+DA(_nE?q*a4`vg;k9(@Hf(g9NfxR1C2&9c?l1Y=Zj}Bo1yRtg% zf{Gv+7_3*WH88)yMh((4iR~t_3M-hv>l|2yzeaXH;y1HRdM6&n1a?JS&4LrBT0nO8 zTNYz`zX0kQvxAgJ-KxS0Ch$53R(1yjQ48x$WOn)6!1a|4$ZHKf`eZlaoCX3-^6i6%QrV;P>0Sc^Of?omA z?|2Y(AGMCKhO`P3*rlJ70VC^&z>q7-SpcgKVRWRAGx-_yR@kqX3w1fGgs71=0Ak0+tcP(!zzQaC-DGReuY}Q|cFv@@bO2xiyBt661C{)2!S%;s7Gnnu zr7v|u$n2;1S`tPVes?BTDw6>d*afflLc4i|LUT{$3hX-5P`c=N2$^$V z3$TI-TsLL1Zfq21`}Zgs7i30IXmF*G;yL z%sPyoo!~;;1DA3Hb|rZ2fki`VgzN<6%9`%<QV_P%?hmNWcmvaNT5U&$Ytn<6HB{ z*We_Mz^?sYcR_QLC&KRctym1V&mnX}br{iKYXMln1g@K`?{hJf_IR>@>@rB@2<%$E zFdMXWz6ma_%F;fT^;JV3n)mM>yh(agCP!cwsPBZ>MeU)yqjHCeaXBG0 zqtKTgm>vc1E0<{M2!!zjAr6x&bFZ7WA$7v2Yt?HDpJlIqUVCq3>aar@n20@r_*-$#n1 zH;S5(uCZktfn9i)IW{hOHGbie771&7!4cSncWPr}eILT9d)h#97I?NtQR2`mhyVPL;`a=Tjt-^a<DTE!C?o#NybGlxhkca4;=f(hmC_anZ6QTK5y#?5!j<&C*4OS<#${}BIN z_-NVuN0*MUaE!iGvt_)r|I#60__})Vw_RJgVU0pq+3*lH=@lHlurfy2Ab$=f;qfd} z$da=Sg4w;UQi$s$2`iYG=DAF$KlT8!k8VB8=AC!70-Nd)($*$JC45D%FIX%Xz4-+& zZ~=GS*bMLU8sYYaA<}D`krKY{nCR^vF7!)&3zv-Fu%r53vPsajGLb%|jp7LG!qX6^DM3nHJ@)6(-!*s0m}N>mahwmBkp*?x8$xhLNQGohPtMd3FEYS+=TpgWd|6O=iehWH#KQ)_j;gfJ+?;|L?xc+dFdnASS*G<8hrAK}V&`%t5feSkG~njaYUpLIVE5zh zfJ<=BRYkfya3)7!7p^yKEoaIJm|`iDDvf4wH3}0+(r>{yw-!WUHH$&rwvqGUZ^frR z_EM>lIhY*11!D>h$P=P0;O40s(7Do7IRDrbs^?yV3#nC%(9+2uF{uy4KDka3RxqI> zOoD;Ar(x{Z{;VX1@7h4(bsvb988bNoyWYD3>`k};7WV3laBQ1GD#xD@&pNnBSi!{0 z;bY)(^l{koau6dH*Iyw|1h0 z6->1MY6*_y8l+|aU}tWySR&Dx@5G3omK=dy_!_dl=$T{WPpjKvcwbxY>SDq-#v1B> zpNBuI4cU3D$todXeeQ{Kqxk!QUHD3~74eIXkTqA1i`})IB&=W}D%>7kZa)T#_AB#7 zIf*4iR(V`J%I*gyunS*l_N~mEax%9=vDj(bYzZrvNF-BWSnK03IDxPjnj^Bw&fyhe z)5y6TfnEF^obp+P&YGYmYF=@YV)EvKrF#*~YMCH(m@x<3tjgfqxmcl%o;%1_sSn{R5hBpPD6|hm@Z)j6QfF8;nIp?FmYYU2!*>QZJk!BXnw+$Bd}}aEN|G8c>p#g zr!t~NS1sD1zFOgKYa?L=6Fut|Li55xaMs?)h;cP~bl4^*#W24q9D!Xq0se43cQ2GR z?qI~KUj|gVzNl*SU2_TNJi;zMH`S8lE_8WNq+;cZNnCC!OyGEIr;Us4>2Aa3qK?Hh zj=(OQ&5V7QdcPH&RH-jkt+$o1f(d*T*a`^UX7tT6bMgCTdyc@aGtTosCAOalmIPVFeR77n)3V`hXg>cdZcL*IRG|c1;E{SCb{?%W zo6)kN#r$d0I0CySKbi@@Tb_oS9?Dv4AE3fkS*#JQ z^sObVU;^JKne4`48GZ6PUMv=EIRd+`>$J9&By+S_~%j*|JQF{652xkv!+gLIJV&LnXhht2|_iO%I6MhBb=Rd5$t;> z%9VuF=OXCDCa@ayU`>gztN`$ykgY z#gX#Z8^6Tk>2oBkU_yBwk#jCXrr#LlQO&G3OEgtyZ!At6fnCbq|H=aUsxcx~ZnH>B za?G>kN(sLII5rzKSRiB9rR+u1%R|+fdpMf96#Vkg0pNm4%=tE-4ibWiOUHHzjui^(K z$hW1P7DGhuzi0lhG?Wh45aybmgNZHn$h)^mk&BvV;8oT^7UQ6fns6wjKzteLFJT1} zJ$h&gMOvp=zCMu=V-o2+HLKB2>T41NPVBqlCXk_*-m?faW>V^M>CDZu*=tp=zFl6-@Bw5#Q1n_8HfUtLt1j0=w|tWY4Grra*_*il1hCN?5_fA#tD3Ip!>E zA|>qVrvGjZcltjNR}goOz%IU&=!AWOQjK`A*?=JF`cPFUJ9QMGiA*?Rt_EA)D_~cC z3nA+W1v(0p2b)kz8~rvE-Q|TQPRUbdBUWgRdD$FTY1i~JmFJI5u~oK)} zyeEiBRbaecnH~S)=Pu;Ln>xh^#|WvJSuj89c)0t#Ni;7pTBP6U~!pr2haDGb#SZB9lghjS0DHzvDw0sxN5!iJg?zPb0 zL4^12GDa9YYD$W~sEOfIh;Yv26T7-W zhmS(gur8oP_7sq`!TtCZ(t0 z$?TH1AfFLr;p2s1Nt##4hFU ze@|_hY|a)vdA!*Y@p@$_cU12lr^wr8ABTNi&ip;XgNKemR;P0;#s}9T`QXB7Vz0yD ze~EtzCc2DCm0z8E6h^GP#0cL*&*V{kWuo5CC}}}Ts+@F`z{}+7-~a7pcLY|O*T{Kd zYMY7j%7s0}{>LIEtSFEDAEEr+*p?mD_X{jWaPfHgux%hZZH)L2@z13s{v9n_x!iM^ zyxD4dg-Oo;-$zl!RD^KTtMdOn!lGvisB3?f#kerBgK%wIGsTNr|DX7$U?S{ss$BO% z75t1>?vLYHBnV&o^njITc>=rM^iGo(FFg$1UR-8GH}^21oq;b|(=<%#J3CEoXUY&3s zwueXmhxq4G5)r|b@bZh27*G@_JTJ%;_uOA1;l82w2s>e*;y4(|F352YP$tVCRV)}( zE)xR+LL{tUV)q3*!J+slRMlKzG3HIn67+T~64yQp?`zcBgJi}A|$L} zqQ9fPaBsH+f3j||7`sMY5>yxKiQO6_IRd-#&D#pW`y?2-PgzPXZEFsTnm<%*w2hXq zf{6{6?S-Ob1@tz&$B3Z?jY8j!X^Lh2V>kl4er#wf9E(ywl;2H8w9e`c&r%;&xgLy> zu!4z2V;qFaxJo$C^gbh2?QC zH^6UR_|CGoRNW!MFnU(}KG&PO=a|6nhHMtO_iDjQZ=YzDwwNQZ3*UeCl~B-2;YY?Q zvD7|T!U`rz<5vs2+a84`4{o#b_}HKVQ`{Da{k_6C0=w}2XYZVy`hanJDt4S4Az=j* z!=J4dMzNMJeBVPB!|=8qcvl*Vxz>>!fnE6ivmDqz#=y_%zZHpxqa>_gVgRfW{JSY& zTHsR_Re&tYEXLID zGvGth^;Lh;cmlg{iD6kbA5Mnr<8G3oA`j`Fua;1!Sqgrq6>^_dY4S;WW$^fmD9?7* z5<*&+L8ie;79%uF4_3sUASFY5B&=X!L{OUCu3tH9{i7sq7Ma2Y%Y)=@ksn83SIT%T z;c44)XeXR!MBb*>kYT=^s80)!u!0HP9gVlC*?|kA>va2!9DH_@&23G4P}5HUaCKg2&5E-~y)c(#hLIwy%_{R#R{pWz>&j4^3P1sl0jmi9SIRD=`m zu_XFZ$bX1`E+z4=|G;)W$r&sxYN}2}xzpdPo0D1scTVU3y}DZtl)!zlKwgoNCg0GZ z6t;wvu^8_qC+HaefjqI9$JO(pQCfm#*Al4GE&ZSSakP3c2phhU*p)8a)x`uKW74l2 zq3+Qe;-5L6Bd|+(9{330Oyf<@sDMr<4# z3MwY^sB6Lpv3RGJpfa)$UL5w8-)FzQ_7;HY*eQSG8E-9wc-d4&9R2lCn3wKCy{>%| zm1p=*QT|RpUIVEL+oISme z*ycaPKUe&AEkWZ>A(W}DU__qkOW_mC44m~+Tfz$dU*+#kH;UlL;CM#dpRoYa4veP@ zYkT~M_~+`Ht|dI)SOl9JH!`B`__yQ``YZSNCSlKUnYs;K814xcH#F#nM@Q`3SYE) zi6#g6H%Lt2zP3zuBFazr@bs6$MJ1YhgTyZWiL=KrS18?;t$5cxhI_BY1nz6IcV~l( z!Z*DXHUP#G*oB{Vtn3yV!K?DA@Hvow4q}4ug?B$Q5@y=eLXdkj_vFMb{M2S&9L}5% z@uM_Jp-vR{bjE~VwS%x@aRofEQoiHN_M8meDteI{u8|ypUAXtbc4TWA3K{-W$P=${ zu9ty{^Pe1qdw%86?3MDZC?|XlqEL1u`k?G65yd?1<6kc=6Xw*aOmhL z^jcB|E0)!=7#&Uqz`*(UhrkweCrF6MfDm}nU3D8#YRP^0F` zk%_Y(;~=hc8A-}t#1Ytqd$p{z_t^oE zUHD1O)=W4Zf|}heXoN6b!U`rDq8x?Il?P$hVdcoSefJz#nxRFt<7_wryE0d532%lM zLz}h-7!iN&B+N35nvl(&C8bmi6j*_r~iM8oTg11irELp82uB_}t^0myUM{<9Tz^VbPUYruKf(iclaV6rHFstQ4 znpJdzBd|;P`(J;B&83wKLS6m*ecd;3Gl)79>E0}1VswM1C%!h$5BsSYu^Y9h)ofJiDj7t@mz^Zb?FI(E)I3bCAU_ zv=~LUPYz$5b{s$g8}-- zSd0;*T$s4K6&)Ml__qh}uUCxw)VS}P8cK zP2>pd!aX(i%2`nc7mpfJzutV03=_CE%VgG#Rp8fs82vG47}tlxF5Kf}PiM7XFsh$G zV-EJ?dX|{r>v?`!9h_+xNA;WPa|Cwbo-@mBc%dCxVLpXUBWy<<)Z4~HFl$Ttv6dmi zT-ggBN!~#pUt8*RP=h0|3%>!d{G$Cjl6vdu)X6}N>*-_S^OhuG--!o4%LE?mflUOC!ivo9OdN29Ws7}GjQm}goJYLapU^3}U! zXl!Lb-hN{928h5e+&g2l;m-=eDPk&lUlS%_1rrEM4v2Qb? zF2d8H*+j)+v4j;&l-VT-xvnJ;sjZy(dD4%K)nCddF1~&ofnB(FCX;z|xeo!B$H~^F z-V#@XiAHvP1g5Gop#{lpo0?MOg*e|mnh8Ao6j z?$60&FT<|Dz)u#CZyzn)^vV}5*jGS<+I#t2jeH@>>@bMy-pgx7Ny4qOWiVmsXBK07 zULDl#C(yogw1gE*G+lN{*!80fBAzueB0zI22`MTeHXJx(+8c+sbUcZ)yuagAJk0tQb z?Sp*S!+c@uic)wx?Ij~duWd)VJ)cj`z73YJf{CgAHG+27L3p;dfe|Ac+mgXYLWy>6 z5JzAae^ig{r<2uh>dBM%+0uZZN5T~Ad}y5eOdj*DM)1)sfE7#c%Hdj#Fsi-)x{Ok` zyB#}>Auo*|ll_TvC9GgV)viF0-W9>OSg*L3oj` zY!h$)@glJ+H0X_amQq~KBO&%!E|fdmkb8Hm6*N}m!Jl;(_zb99AH#uqXu2L1!89+;%iMAEZJPr#o^4cHQ(S5c=sBLESs$+(hMB zLRKYhfxB0#<)%%7|}Xf8dyA zpQ?Aiq9m+fVpyw7g68E47%=HKyH-OdJc19aHHFiD(Gsqy*u~e{wJ&AFpk4U_rh(LVt6&I8H;gY;1JU5;w3n8BwWG@Ch+}d)Ri*ZL_a7k_o}=I~LU9V1loMg%3xN*zGUL#AkCj0=sa#!oK0{9!J`4t0QGv z&eGT3O(6Zoe(()=BOjOdK}a&qhx9F9j`WzeyCK1j`#b+GJQFOp!hfq1r9BHTNxJ>wpK92JpO5To zSqppOX^>C0)$mVFOyH})zGIo?O*|{FlFOF!xMwYPEpPZBv|#&GZ$I~f9aT*JGV=BV z+l4RINx}*y@O@(WedKFNdh?d_XyO!(z^*dd1g_8D2TLyAWik4#-Azj0_onJTCenw6 z>JT(`58OU*UXER<)77Eh+8k){+Y$IU>6S%ywqw2DWY&-gyRGZjy1a=kcsKY$A z64jBtKC-MsJrhX7tjlDUyNiSsOzRITx;sJ;Vr0{~5%mx*z>>Y6M4M*Pty0!t^HjK*uO&6xS^EA;l&p zba(5)5>_zbF|t4*86TzCD-R*f@g5c=zK7?0T3{AdIxlgYh{#8PRlC06DHD zP|cj45>_y=-n3S5s@@M@VzU@w{=tKIXOE%rx?MQ}yR5bq2)=o_@T}=(Mks!)5JtF! z(dTvUe`l8}78XF$a>d^nrGGP6c!Z73H0Vr#0f8ZO<;7SLE6TCHe*_-!WZ!K&?tzX~ zp>#uxD@R}#9${l+uZri;$upQXvx*e4f(d>MpxbLza&=n>oixLRBd`mPu(ADd*7qi= zb^-Lu;6xECn80HWY~9j};Y8IhkiPj6z!BJm$K==?ONZ&i^2ZXoZIr)=6->A-ED(;j z*bi3=&att+`ENbht`5Ppb$@k^z%G8Q&!BJx$s8O^S7skjURAwN6wg#)0=u4M)(9qUIiMS~vxGfyMx~N5YXj+=ET<~0V8Xt|bs<3|2XsP` z7-1NhMzprO(snP4#I;=;gi#T@q3P6N@&}r=!iBMW;q7)~`Fo>U;avB9EQk9NRuVr= zN+dt@-DuaLpqI5D-ee49#DalAq%OvRo=^NOmZTR5_8oGe!ZKdIc1W#o zGY4UrlEm=NvKeQ=NW-*35h#alb38dUX9ykfu^&fZ7jB7IFXQn#GUwPx zy02X?2`iYu=f`F<0#}l8-35Anad(cuF5Gspx$TnGBrMsSp8l>QVFeTXwNecTCmC!f zj7bZ$IRd-*Hc_Q?5jp)~3UxcKAz=j*xV*9XsJK|t{fHG^)}gtC6-?kV#_~X(SVvqg zPo-6Zn@L!~1it?)2i=b%F}^Z~Rv$Xf5!i)mvrM+nJCl4dmeVJ9^dx+rEB(~LOJ_G6zfdB__lC`F z*XI)5nz1y)r!`mFG11RQ9b8p+!LZ-y?5GyV_7L5j6X>Z<>KuVx_?+07<=Y}s^v9as z>GfK~3MR~5)c+q>Zyr|T_x=ALQz9B9DGe$Oq?9zDwRWUIQc8v?{J^}ar9|NiT`p3g`7ocrAOzV}{x?X^MDT?c=CCh;~N zjH|$934PhvpS1!(UGysOaiU@`cDoeA8b|Mys6vUzpeE2Hs1)uMd+;_w7H-Gup7HG1 z%nbrTUE%9)W*R*Hzra1^BOFD0(V@7_KP}c%H{LGx)*7207LJ2yD<0m3)o`*G) zbXfg*fdWBYbmYv5Q&Vx})B3DxTDUMmri3`VTT?p><#i8m=7oU*L0#h9pu(pgwy3&> ztT;g!=~IHngLuBrnI3q-|0FhCk|Yq+MI&r{|DcOIT5mszUB(TSsX_@cQsi4?g%0g@ z;P@#c1%kS0Opa$${q2m7acvGYXqF|@9Zoc&Lw6Y3 z)hIzDI(%d~`3wxQPE|b!5ee#|yX*ML)`2oqeKS+N-Zn+pcSi{tbK-kO>o-I9j7^eJ zqZFAn(1S;zCt#iRFYl%OTYy)OBk+1=6J;;G29Ub-1pF*j&r%=$YJ@#A)<|DW#>!No z1l=Xbb3a1wfz{;=(g43P0zq9BbuX0fUY!8@-Rivn&%a%U&dxTxm*TBYYo%x32Fp~Tgs-zN zTz@UW{Hy9}Ju`wA;<6tVQmisbAgIea)(zTyJ_ZBVx8+1l>;q8YD1a%qj>;U^m9ES^K`kZ*XbrgQ-TPjT$mMl|+5(Yy$ z!a(E0@Og>_Cv-DH(5$vXvRWV#)b&Vd2AQ?T;miy5O2f`Mff(dnB6-Q9WU5f2{D?VZ z?mi41j<)2)h(GqIb7ZqLXOc)z7wwOEEPRI%#_X9bRacFZXTD5wB~Z_{*X`c;#gZV;@T79@Bv(M|c*) zXZ813csB%_oE{3RdWi&e(Qy#3!@^?FrSm&D;WklNC8NY3YfbRBse%!Mba@*c2KK^x z^B%zi=L~_ME^)=g#w!FDeAmO{1`}nfP~yNK1#BEs1=qEj@;2UA`rxiqZA^b664XUk zYxurY+v&Ke&t-7xk|sAVG6avAJc}*FM7i-?D>$gV19Fy`DcepngT%et;6*2E-o~l? zRP>tjPPwR%@0=tGCC=S4fSNZ~V zi$aMlP`${^kf}n6`lnjL!-@OBy3&Xf#~otPD6mS^@W(`fpsvG-Cg9q3FFY7!$%!K0 zL|k6=QT5_jx;)aZ4b-c55b7#Sl&MdxVE3+Fuzi5NQY5C2pNwb9l&XeD(q*bpqDs#i ztax@puZ|A9jm;A?@oaA0p=#5K0zqB$`|+nXYc8I22#3IL6NK+UiGnsZ&@#9Z?B1zs z>ABeEq0RFpaPG25P#683c&5|lMOak+558oM6MjKTJp5<|q5Kr@cQ37Y8#!8exN}5P zv~M|HAgGJpJqpEvx$)SKpIrBDZ;DKN&b7@Qq5aK+aN&4ICG8*i^RZ?K-rYY=`uBRQ zOchGxPO$?w`vcHhuLJ*7clr##ZF5qkeaBJ-g1UNnSb%vEuNu+VoD&)Y#^8(QU8F%g z%bO~c*zln}46@k6D>ONABDcvXG;M4n1uvQ)5Y!dD$`V{w?t|0*)o^K!7>mLsZn z?rAbrC^0?A9yYn{fKem6aDq9N;%M#G5K)pUJKb`D&vzskJvLJ8U)&#nEr47(S`sk+V*3F_L>-We|B?}Seuy?7h?PiEoX zO@CF&r{iU+P=a1JKJ!{S8~glfF7>k$3F?}*z7sUtv==r9x$-vFCuHM`UA|KGhg6v= zl%T&q-!X#6a2mRzX}~afnWqw#FE0o8pFT=@-PSbohAg*D(0-*KZ{yGCojB0z6l_W# zEmMUO^cwQ2z+HCZmMJCBWSK}%SNuLt&}~==Kbr*bHfF6W$F2|Cdr$ICm8n7rdJXwl zbod6mzGd*CkI%*m1a&>`%128-x5KbO>hIBZ*b3bHZL6yNh;cGiC_%3wA6Z(g#2Lxw zRiP(R1%kR(ZgqnP2D_oI%7?cx_10YM9^XN_F+WwN3MItfBQ#|`)_3!e_G}+35Y)A% zp)2Tz?uQq8p1h68y4m>i!UXA%`52ihl%PEZUsrR^#piOGRA`VQ5Y%H}sO`=I@V9=wf_%~qpF zy$ngUBw3~kC5)W>;A!Lmh>Q&8L=)FaH2&E`YRSiVUqW`nCr;A05Tp z_?~wO*EAd_`Jadv27kH&eDdU5duM7;xEY4wAuWz z+L-mXz5MY~7OaU{4S|<;Dr>W*!cprLU|zFJS@$;`bTZe%`>hqcji*bzSb>o-o>JJ$ zRG~y|VI~ChUj<>#>NAn1@9WH7f4vKxI=hMlaYfb}2W#iAgMi|7obc)H%uFJ`fNbF= zQ-%It)43Bs%31^M3(Gk%;gB8kvRDDG%a}k=*TP$)puzI>&}H2!P8{xM%U1D`X>^*8 zOchGJ?L7vrEH8oF7Hc?h8O)eYsToxK2^0wGx-(-K)GgcuYYr~u#F9D_*7{I57~JY1 zQ-ujiD0zqBJ=l6%=&O5+VFM|``E5GBF9T_SM z?>Lz%lxQPI!tV4+DBG9K2^Y7g*eL0#s;^0+Kv0+Q@-Ue8eHYk#8_o$+@5g9TdRApz zZ?H@iN+j><18;h5hwmN7aiY&i7nXP+3Xgj@%BhVfLPc&NOutyJygxD%Ob;ysAEz>< z&Y@IjUsVLNPpR*c?#(+h$8W=MX@;Xr6-w;UodDsV3!rSg%X}~QXt8E6+8zuvHoyd<`Qa#2Yr17g1R)z zhC-uzrSPwA5hoPW&Dqf<4mdHxSEdRj?%Ws-UzBU$`W-bfepf42+~GTXD-0G0>RNXz z9xCsb^K*FeI1xA3fc4p{g%wwVWvWnO+|NW<8(adN^VG!V*k7O#9|=!nubQTMri@z_YJR6-p?+#6shcGC0^neYbD9SC1Wc4uDwS7=fU!`=|QC z_PrHwBvgIx?!2R5f1FW4)M(-Q=Ox+cyD zh5ie+LNBwCoM?9TH5RnHu5@^qAX9}Be^SF>cDv0m_iqX(5^HYb$zIP7ZCo%^AgHT( zn;!7FZxxI-jN`;h?OWI(sLvsV-Y}UelosVM&nh#qZE>lKSj)S!LC7`cbr2OzI8T_gX z;gXiRznZqSJ)pfQnXj!mom*wc4b#ZX{ zb1}@Huf7v|zc*yXnz^`bV>g*9l$dcK9*$mI1>t7XIHA2(haG0In7=q!AgJqdMI=87 zvlMjBPvQiQ(q@~+jmE>BgJr5vV(zGDn0#XmTxd3t6LAL`vBd+u@Ro01fuJtUfIg7> zupAncjNwFLm?vx6b~lEW7|I_0>7bvy6yy^tm5(k?ffkqNLfx=c%J7H`&}+L8ZZ%WC z)gE>N7T)s9O-W-bua6}4lZDBXOR9j^y%WO`n4|X;jSat)X!L^3MJ@O=i`!Vj!e1eAYM3QArRC> zpDv!)7vaDjL?6T5tu17#P=a1{g`&+h8@6L%6@J*>Q6Q*`K3)8zjRb49ylOv|zqgmE zLJ4}+`4iR0j2+ouj)kG_0zqB$>Ef}ak0$J@!&W>r+fAklCB)yuB*uU}F<61Grgaqv z>Y~phk3f#{VmrTN@R8*c2Ns!~hmF@e%2c5QeXsD79fsPlzF$Y+&k3FaL0xpjp-_bBTC*WM zKk8GWr%V+}&^Hl};wVhn?Crt0XN|8wP?s>`P$a3^Fs}_UST)yIrV1tKn}}C7>a5Q? z&$Gvs^?M0~;36XqzV2MV1$$iUjqSe$%XIWY3Hm1Db7#XQ>}_3RG|uTO5Y$CS912DB zkH!qMTI2g!ePyapg1(9P`e5N7jL19=UmM2?1a;97hx*ioU+8!BDMVVt%2c6*_>OAx z`~{9_GZI#2Ckh00(J>0I{@o`KS7Ik=s*4zJr;&8Jn#D7=?ENrcQd`OKce+d!O3?T| z-vx2s83)CBNqWacg1YEx7SCG>WjOkdLOPI~Ayb7Cbk%{+AXh1|wBmuPMu%5oBP(vy zMOU+UEu^k}ab|St3DQbTy0beEBjO$M-FOetbQO zDwGf-^p=N5;f%ItdG(fbfuJtBn#F&Q>Pfiwyd{o2HD0C)C2EXx!MEWyuxet!d$^2~ z$=JNJ30`ZOCJ@v`SF;p~fk6^pZSJ+No# z1c9I~y8gx22a^`yHT_7XU+n~$uH9(N=m_seZ-s3gU3m?9x{gzkxEkGB90tqeRGBK2 zm{I5e7Ca+9@N#GVsp{UW!gG2r;k>>`P#0Zq;Tb9GN^x2rdn|Z6TBZsmMlZ2}0G?GW z8>!bn{?sc(m}r4%AI1m-bs;blC#^&Z^hX57%Fa z_}v*D504cH>Y~3t-VB9G5laZG5U3j?4X%@t$+4Kv0)>C+_?(1OppQ#P+3Q zWvWnO;~E91_H2WscIxbe_>^EQecctGo2Cf_b%`syH@^hp%hsV-Q#?V~sYi*35AT(q zR#(Bq8x43Hm+Lv>g%hoDlQKgfsEh6^Y{R;?QR$vpxzngijA;; z?J4jt$Px(ZqI<3R>g$-TxX`36zK<9s(`P&8M;Ex`wGnz=_f*p7k)K%Txf`$D?u)AU z;WAYyk!9crVOpEOZG;p5=31T=Xq6m{ozL)90Mchr7kwUiX202H?Dlmqu39oerV1s( z|Ji`Ug-!5os4Z{f<(jotMP#1k3`L+6(j~QKNW9X+5GF2$y5zrbonO1;epgJ#OW61){ zv7Utic_Rgay6E%B&*$vC5cLih@ORX3nJScMP@xL}WfkzTo%;PTIXf4l+Z5n=jbwqK zF8Vz3jCj76Y=eIV#>5VlsX_^HFImOAEZkwe2A8%?76|I1&m+(5&&a?F&&tuf(FmC; zl%RXp_}$(-4wnw%<935F0zqB$dE}K4>cwDq$`YKflOj`v5_E4Tzq(JlA>15^nrys4 zP#1k3`Dn@82UpLTjAjwzWU5et?z`mA$2vO<)%L^R>(d2-y66+kYlTJFplh#wm{yY} zQ-u;U11>33qIbef+poN5m_JMxKi)RQU6GjrL0w|cU^ZMEOILNmrCa$pkyLJ=1g%)0 zP}t7@3?IDSL8qZv0zqB0HUzKZ)#?Mp-)w^A4<-p!BPc;@D)21tpP%uBr3x+I^^{8o z_(BPfF6*#BWw+#>P_(fKT*Cd7(Sy4~+cCv()tK?Sz15wcIC=kd40`1&Q-u}*^?6on|{F6DcA5tSb#uK7vGo(&!(=0cNH$2SdjJtgZ_14v(Gn`UGCdKyu%t8 z=6}<>{y94c4lag$@o&9v3~_=d^;Uz&EOkYP$6@y|^1UhZ(6p1MSJ=V7ytNQhTu*6{ zZ3iEpmB8(rO_ln7PT=6a2I^Zj^K5Vt=c`Uf;qPVUCQsly6* zKIE6TY{uYkuR^FuYr=_b@9MJy;m$0%Q+=5#lt_E*4!R{PA@-j7PE4!%hpi1AShLEe z0zqBkr|P8n9rvE-#GajMDpQ3L;?>Qb^Z_d$bzt+R>I(#Q(QC*nnBACa<9U?h%H3wq@yYCIUfS^q1vl@Mzw~#wATz{X3pA_OOFy(d!`latr0<`<-Cz z*R{|wqLq^VHVVbAUe8b?L7xRzJIYj{M8Fbv@Nc~u65i|b-y_xjJtoDQu|@qY1cJKg zHRP+W=07p#N?SIeQ5)e}QDWyCgrAF6LY%ca`?E=!g8i+tX5-hl5D4m`_X2;P$24RS z^Q~C(>w3a(PKlFt{!qhLuojIscwi@acCzFILOa^CI5@MuDx-D@Qvk=|6P5SY0m3&XfXE(rhe)xQ-u=qdUS$^nq_e9 ziWMjPb{@q}Z4cv|p#ubhy58=$h1Qwtp~zjG? zFIUe$K;Dn%hF(OSoBafWx-?ZbB$e&SuXo-$P^(Y?AY6gZT@ z-Y@F8fm6&LEDEm2vby#V2C9#%Uw;)KSPBWQg?hu!F@l&M0A`d`~Z#_3Wp z8KbUvGIE}bH|q4+l%1XeL0x~WjR4=3!JOMaIFW627Jq>STdcH~sX~cCEiK^r)Dkcr ztF8#NbKfa^7iY~n{IC@W>gwxj1bvIvLGf;N)uAqi)!6<)Czd~_jZ76v4DM?LlZTZ; zxPf}d$cDEnJXb#r8-T= zE@A`d+o-cY7o6LHQ#$A12vw3mP!}Cv^B(SX6)wtJgn2Iq%T%Gn>v&s8G1~}ptJTkk z#mbH7K72lQvl%K7)J4bFe6$p_5l6=q;m9+CWvWo(U-PznF1QhN4;u3}t9X&v(Ap{dEIQ8~xXfOUxt|CY2$vE-d8lV3v zmI_ykyBcYZINd|T*C1n+_;*;IH1o|^VRsEBX!bX+Su={E367C=yN(wK>Y{rD_-gor z{#dz_N&Qw&5Oxnxf@Xj79SYe=n6*z++O99Ie^3{VM)OGO<7udMv_v(qI!%aEQ-WrE z^AmNxFT|$<3lBcuEJn7ei^jEhrtGY>ICx(IJg7_+B3_iBnbQ1R8LjO&&r%E5-4$bG z)J5N@yk<@25xmqQ2*Z~Q72dU!pt;;UXQIn#Ty|m##@$K~2zdRT#Qy< z2Fg^S1RbL)6t}}pph~9zn_P_(2j+LoG2|B7(C^A^* zI3i|{Ku{Nb@A6S!!vnZ*(Kft&ELNrpCFrP@pKw&a3fEq%#2)YC1cJKgdzZg!wW{!f zrGzb3#K=^k1Rd4#XjI8Y>{F(~<^2Z=1a;B(F3;Wx+k{;mE}^AHluQ*$&{3^IQ9G}M zpSg4yhj>N{1a;B(E+1coZNv#FuQ0-)k4zOx&`~Yl)!1)6UMl^B_R27Upf38}Yv>>zA6d6~^5Jg1YE?SD`qna}a~$P1vkUE;3apK}WT` zjhp*W<6>KuGR{dLsEfXL`5R~AQLG!}z{*1{WU5d?93eNVlCe>5XJ&lOR3NB}zIXYo zXw4~ncsaLWxlU zM&LcV82T>G=574`eGI+ABiNRxO9DY%v_1!4D{62NFB?a(P2rm*s!+nFlM&eNSOZ%Z z0dGTd@@YKMX&^hBRwNMAMJsx6;^SHDwJMR>CXbM)LWyyXO`!H@34FbNk5_^EVt){K zw@YF-KBox;b%~Wi>UG5%i?50!m~?xpKu}lL=k9P$Q2=sPuKHTBuUKUh!OqNCB2k4B ztIpfO)1j+i-{J^vaPBK*}vEI86l&#N)nR!Znt*j!o*!Z%>ta7rAKv0)>b?5ediT2H> z92)rrJ=kHY49&J+_f5Wi+amc zp+ucS7&y7FhRk;TIgzuqA+z8k@nuQf1%kS&Lc(G9g+eGS@5zZ*J)1GOe+yrgd&pFw z#G2-j@aR!Kv}~!)Jx{T1!G2!)hRsj37YOP)*&qrW4=;t4)m=GZw5~O?t!v139Wjxq zLWvdY2f=|;i(sj304GlNHD!)V^;phVErFn}og?F6#qarW=B6_zPV1Yqy5BY|*5kgE z`z;=FR?UTn8LgEo{i9(@_5vslGEizBje;|;7lHK}b>wc|Gb7d_%YrrQ^h=@&C89s} zfw;3vAwH`;Cqlazu+mp8SuoR+DM4NI_vfca4AW&Z7wWSyQHC;AD6#u*Fx+334{V$@ zZ^OW-Ia}01hb<^F6A0=O@2iZmCM@uqKD%sVDpQ3LmM{F^RL??~mZQ%1sdCa_{%^F| z+TwNsL0z8!%fcJ6%4_ZdL0z;5=M^@-*sv4V ztl8xiXC&|EqhWgCOqge6uB3O2cwc$=wq@nlEZBmRbrMx5LGJ~grDtiv><+hLHOCsu zl%Ov96!15ve=GJcR)@{sWFXw_l%RJH&vg2x%RaTQ$I@@v2n2P}r&(RUqzN;>{RR); za}l0eO3>bpN1f+3V4v#F;j|gu1cJI~uf(6)#^10b?!d~Uy@cL}5_AQdKOb%{aIVEX zTxAg{5Y$EcO1=xi<1mhFwe8S#*HN;|a)8%kcfdivVCD4z-62!84URM%pd8uEA3PUU zK+3KtewPdycLj^InuCYyaG5HU@IDj_;|_0x0V~uyK&L!1%kTH8zn*1 z%|(!l>itpX-tCxH+GmX2X(UsH5`PDegys9@!|Lzq-y^J-9ZMh8h%E`#5(w(*IB^u5 zE6sxo?bPq615X@TH}l4<)~TLM6-p#zPlWiMxp1LMy+^TGh70?3T#FUleJN3by7V?? zK&AH#7{`N;ypqlbXSVdPB^z8*A)R%f1nz66z!EJRCGA&kgp7vhXSq)tD{Z(?TEw*M>MKdb$*L6%F8RB)&Idx8DB4xl7Dt1yLwL-|hT- zwQVig+4qmJG~H1ksH@SV{;;CQO89nkAa6s?Yt9BgzkrYDddXCw1RbOByIrR-)2pb& zK?wl@L0$XrhC*7+TDS}9JMrkYKd4>16ff@ylc_=pI@aQQ0ZQLu;;dKFkB$0YqbZ1 zRDNQ}=CA5;;?SZCc&~jPTqzhXQ-$_+v~8Xdf2S6&Jp2o9PKck160{%V*Q)wG4nH4+ zz3pOzPeony8uFgOrXHL5BO9-d=p$S!O3;3cuafoDWO`O*IC5d2Ku{OG7kCv96J6#| zdl31QQuxg&LHjX2S8LpgH5gxmefm2Igy16gG_T~j#e`Y3eS^U!?Sy-m60{%Vy=b@v zb8XvzIVBnh1a;A8lkZBoY{UF6Hes3uGL}%4B&Om43{G`84jo5UTAl6GN6XxdvL1HI-FLH(kyR03;bFk(M1dW%_Xab)b z@C>A|`XOw$eufY=pv13af6y#m3}H{zb+%u1l`rbMF{7#VWvWnu=9KZ-_RU|I=;X!v=!g+7>Jnp1J08_z zua>*BHS0bLks?aa+&CU#nck3@t@dKOW1k8HbsquC2{R&(^V6=~e`kpsw7vD(M?c=(YYP=yi} z8;ZdFMQ7-I)qoS)_0m{}#QEquZqXr1P?yKU0@yb^4Bjr+;Dqzc@hoE8avZw0r-~|+ zc$iTLm)rZp!ISkkF>3V~X4|(EmmaStQG&XXotMH9gTdgo=Q;1Gb2p7*eNI*2F_o1> z6-xLPFN2N`BOyKUJ|`@;4P*bN?Z#fG1_=apwRyY&4X) zRVZ;eZ!Wxb9tk~$6>-Ayc^I>N_7W!rZxaaW+OcpJ9FE9@PIs4b!ts0vn|$gkAB$E> zRH4N0$XwVybsTtU&*ntoyg)WS{U180R02U=HQ%SfrIKv$tIg(w`Sd_GaRt+1amPupu${U(%^KqRQ^OUoR{s+|B%^EGI5BH1L~*8Q0zq94ECtqH&4Gr|>OEM|?;Y6QjxMZO zR=h+NN{k3kfKEZP!R6at-iBp?EnD)%l{Gn*BM{Ves(S)-mgd0vcHcO0F}*EYAK=O6 z%S$DyP{MO}1Sp~wLRUxiDV4s5MzN+ZRhWNh+QFQi>tNy|1tg6><(%Ak9h~!M0H=FM zRTtgY!P$Za;25M{k6P|OfZe@C(Sz=mwu zU_BKjs4H{GQkb>T2Zj~Tzc;EfXHdQjhr^!SeL~%?7-3vDymQ-A!rgrUYGzW^Ct5)MlDjZ z@CF^3zv~)-pstJj-hH+v4IFQ(PrIq$%c3(5d$7D&gH=?a#IbYnaISb3!1MvUji3P? z*s>5{J#JkR2 z?6biD*8aj66;&t^l4u7OS}S4iY$M*r(^mD^x;7neH*@*sT|YbYBiW_l%Wv?8{?h$=b}V zcY8MOj6&EeLy3#&z2LRZGT7pz&WN{ZuFK}0cV@$9Kb7eJqAoi2V~*?0>)-H@l8>>kFyNA24T=F=n=S2vj| z5Y&};d<)cHnWOCY`v7l4c`J+Q-!Q?s?HdABDDf|DE4VpnD=QnSBdO#5O=brle1{{Y zbxKN5mwW4N5Y_shx7O)Xyp773sqAv#MA-a9AE-i!jl34}Hn%gL?0_b3W7x^5?Ed** z$^$8NN=i`IH+dTv`p)+>O1jG1@QfeFG%n?#kF~K>>A4udd>XW~(1A${mqB8m;qdl# zGgx_OF$9&TL#azcK94f{mdXxhFUAipS`t+#an?H@&O5|{Zg5jhct~Se&D>?U>bIFd zP*<1OrO@z9GEB3q&xzYJCrs>RUp z{%9ER;Vr*bqhK_f_;npR40DyJLJ2zS;}x2^3}^QZD==Ymx+TcXMMbfI~c_lu`}5JSEWEum&>#{P+*@04gA&f!40+jSzGgKXc)Flq6#JG ztdIZZ-@=%|mKwBrdQ>2&t8o2Hh+TcXMH@@7Z=D5 z#=OC#qH6*{UAw%d!5+;SaA2IeUf&j5Kjxb76AxEimZ(ArI_u**i`yV8+^1mor#=!0 z>Z0pk{LMK9*+uuptYPwHi7J$!vpyd8(eY;K&9vAJ`Kmxr7mX+LyuQ20zMjx!$LH*l zs6q)k>*Mvpi@aG@69Z<{QzWQMj8osyWy~nqh%NVACQ*eFbk@iBRDbnmhku%~SK%QUn$eX>lvtkAl#|Z0#l%TUdzA7`d4NQmIwrO(cA{!x4*Sz7w$MQ_p((&W(_6itWRB4#gcuT z(1}G|*((s#MYC*p9>9JxW|`Q98ExJ!QH2t8bjB-FBpI_qLC)-G@mYbOt_EWxz#@Dx z{Bu@UhuPV;6-&r-X6?3Km#9JsI?CkH!Q7VYasyjtu;GV5P#4YQ;XOmS9(!M5#U>{= zl&L}qI$GxWK32Lc;W3ZczHcrN)I~FS6pEW&nz4V)%-PQgIxNAyp2Z5k2n)}1ECN=7Cf|f3Gs&JC2LJ7LFoaY+6 ze2fFbG}xwNeD5pCHli*ur^xoq9lVqD7u{QS74k(X@u{#Aj888GpHg*h)VPj!aia7V zJzn?;1a;B;OTOEwFoT6`b;q(04J`Y)7%ZNSg8QXIVL4xmXy`c#6kCRZSKq~u(_=bZ zZ`7NQGA?Y%U>#N=7H$3{D3rMGwhT;rCqc}iFizCEX0n04Jy5<_ED+SSJ!%R3Tayj9 z!#p_=us(wglKP=$>%~A7O8l9;oL5#I%p<~TqL_b=$0rl8wqTi(64X_fumpBQWW$j) zR-AA=F_CRA9E;YE=Xq0w5<7M+hjIEz5cbxR6Jz>LWRaDrc>Q~%iW1aS61NDPbaNqo zduvXN*qY9!&&vBROakYhYG{SN_FGRG|bN z)$%=Yg~Qpl%wp6!o+}X4<)XI$ezu5>+TcN3}frbA1>q>wOxXKiv=r>Kaip0~$4( z3C6zbc^gt`2z%S_8V+f7Q=$qb=%|*zolgX?O}}no+UQpTL0z<_utE{Dsyka@@(kTp z*GW{N1Rd4#`9}v}WADGj`jx*0g1Tr;VP1#+wI|c@{DJl}ze`l11Rd4#^{8?e_M+og ztXZZZQ-Zo^O<{h9^zBY;<=Nk8GDB0Q3MFV38m|_b-+{#~e~+VFTM7hq(JI6|Kk<+? z!)LE>YH}NyDwLqvbiDVeXTd)1x`H3>*a-x6(K@+2SFNKl8#Y+R)MZ^{s!)Pv1@e_q z?Uu~*`dXZ!@(~E?66^1_|I2ge_svExtDZ7dC_%Fu`Pm$W4O#Kso|yPOLLjJ%Rww1P z?tQ+Yb29^sYaT08g%UJNldsV~e}`ZIq~S6E9)M<9UeaFEK`LN^t2K_ z=L~gV5vT3o1+O_k3F_J~ZVcSmvJv+DDduh5+-uLQM)ZN*LqVnrCFp4-3Pq-^+1N?S=$HO7RVYDEE8(N?Wroc9Wn-07+Yo`E zuI9!`;GMS>Y`ZVyZ3G&(VixmuA1V$Gm8n7rdRhtJT@%`jy~tdmdeX12Kv37z%0UpE zR0T0jb9o!HUp8f~Ez?zJGx`Z915tvWR>G^pG^@u#KGmw`21g47bYdVosg}`F>Wd8dO8j&0 z%qYZr&t|F0_CE2{n2-2xM(%%qhhkTRJF`_h*SUc&E&)=(|WLT;Rk8Xl6cwN@|kyZh!cj!rT<6R|8l}ck2C)J z+v~9lj&#Z9#E<#!ly)bZ$@bg(${yFBde{45k6sH#{^vS=rXyy2P5JNd$>k21IXsmU z-;3TU?ZaEhr{09g>d*c^*Z-f^xon5+O9pcyS{?$^dKk*81|k0u|5GT@I{&Hn&>OZm zb-^G`_@BR{oZ8()zOo@mAgD{-_SFft7;scgbRK$Ix$}di{APgPf5fB4)|eVS;J?rQ zKbJJ_srRmjR_M364<`m&hC_F|wz6ShfJ_zoe`$Ms+tA_F;^PVzQC^4cUPIa;*hU=8y{G8>iH6H(c^Dd`N@me?h@0;%_Gsidk{ZzB6pL)McGQsC8ZPu_u@%^l^cU7j*kC_%3}uT1gK5*@GG$qia61%kR<9+xW{ zj<&$z)jqt9%6-tP|M~|z!@%s2?^6aBs1%kSU25Ep{oh@e0V!Vy%p1Lf)RkalC z>nT@N^7A>3oKWLYXO-0*Q`lB*k1r~`R7Uqq!Q9dr4{!13#M{>jcIxL{X=gr@sX~bj zT{R&5Sx2;&ZvbOP_%PL0$6KIOX-AE|}e65+`bQTH+bI_mZ46P^Jnc z=-ZCh7v0$iUxq%CY@8AWg1TbTo_V|7=z>lAtKWmKwfU+}x2Mwgo`YqoP(u9#|KFR_ z_mL({7=J@L(`%SOP?!4euy9wj7%+{uF|X?oRyU=Yq*UFKrf!)AFCDsLlGhcgHF6=R>^yRa7i{UTY;4U;HFdg%XbxBOtI5!){l#cpFz{Mlzop zt)yP7>dBO#uC`et;7AWY%v#if6RtygGwpXBrP^-VGF2#X#4QSHWQIOIR-CAJuP4*c zGnM9^G7t#ra-SXrL1+EYWk`EY6y$eh=Z-i_zouEpRG~yq$3QS1>4Ue8JUMZ*A3u*J z&|F$^#7-cnYi2|stnl&2q}9lYi$9!L>dNk?0iFW`FujZVsl9Tr4x8<_kQUeslBq(8+>9D!*NNS5zzp>>xVP>$ z{`lEgdTKpHAgHU~iW;SLSpYVxoWcp8)PuOaLu+ZgeX>jyN}$tv<^1#A@LBD2PLyxl zj0I)CRAIeR1cJJflGZDu?grp{HiHv(%kyw^hPLE?XPitGN;tk7q&%YSi=P+I;zUF5 zRQ%BQg=(T^xkg+ zR%@Y2gWIY++bn^guCDK2cu#H{h{<(xII-{1JXo5>Ukb64WvWm@-IusT_~N!fYT{OJ zEjYU4l4{?KDFQ)V>c6Mh2jZCgJWkx+HwS!sPgT8sHRZpN4CVx4+?G7mr^-6-VH&;A zB{fe)+veYVttQ@_7o@TtB7Q1L1m28S{`nD%7K!R_{{FB%Udf-U`hI+p@TsVaUPE3r zV)rOqcp+ZpziOgzttjz6bG@?QX)t#DrvA-SeP-jx1uIpr>!%3>b|pG}@?U|OG54lPkR&W#qHK}z)CBbnN) zV66LZHnDO`6Lv=PvT8N2iB10(b*ln3+Q+^8@A z9$k&iSdHZamFv&|fuJthSMvO;(hjV_js2>GWDxp9O8oT*1ix1NH)q{=8x{|p*pUe@ zRH-N21cJI~pU+3H2}+hbLsq$NwHNw!N-WNaf)+JB(R79bZzKCrS9bRIE0x*Yb^<|N z^xehhAA!Nl@S3dpHLSJpj-tf9@)3}+q9+Dg81go>HNsd`lRDM2XSxDGUGyEy&!hK> zVwYkMsFt5?AiQfSF(z{&d=Bf02iN`OV}`F?2C|z04^&H=ewXO~qAofzP$-Jblh`%A zZK`bwKISFk4@ykgQ8#dD(ILVcF)ut19K)>|N`Yrd}r9NMQuXf>P@TI-+VY_>|;wxgd+6-r2c zHOlka9ysDa3McG!Yw(Ev0?Bzoj6hJAUjG`UXLrEbwP~EVKkxwdPFN*f92qZDg%UZn zppLXG~sHHKu{OGkNN4q z10G`A7e{#2mfkW|C_(4DJmTec9bFCfNYyU=1cJKgeau%(YIou4fD=-Zk}uejCx;Sr zzRPEjn>XOlvwNisIZhy`i{8fy#kHQZaBIm)X|8jEOchGd`7W=|urmciPVSXn^cpG< z)J5-OzEgplrGr}lc_=pI^X5hNY-iLX}>+vgUurag1YE^%(HQq%!Nt!j!7*Z zB@1zCN~rJM|C$>Is!pm5%I$z_^bzh(QUxn__2Bb zYm(q6ok;jA(bxiY(Rcu_#X2jLO*kDb9ZJ)ZsX__b9MfnT)-1TOGrv0S_3DyEZT{IrRqvvT(?AN;$lSucHOqG)a_@4Ku{Nr2PhPc;U&)5JzO$v z5F=BC5_Dw1*Kxw{;O(0slH0_1fuJrL58$6F_7J+iO_bi750$Ax2|6<1xq}0?U`pcv zsqlWXKu{Nr2k_@(?_8Xuh?O?g8zWPN5_DvsP(;q1fakBGbn(SFfuJrL58yS)2RY+e z{eIHWgfy8dln}=Z-wd?zNr}5;(l#p3@xX1Rjvr~mfuft{4Z*d|~xuU>E(+UkX`gLT+|e`$U%)JHg!5hfSaA!LWh}{9J_Zs0!96 znhhT8Mn^A!z^*+!&*0VDl#G|uEN9Dgt|ak>6Dz;1DZ>gT@N*GuFdrMkY!J6FF_vA4KdCnuneirOj1~9B(0zVhg(J>#jjU0Mjo0+Fc0)btAy$s;F zg)P}UNWG7G%NzN+AyrxM4`5iqg!sf{Ol%QpvDkn`y=o>9*!8){0-VztlFgp#z4NXn z&&l)+681y{ElVcYO>eYni;ofDjX|JyotXpyYKj#h2}v(pVs{3tyXjNA5>^ z(BoeP(tRRcgP5?j`s`iToeiHQm^^NetN_X!EK(8Tf8BCz@o0%MG{9QY@9qY(dx^J}u{zY0_wB<1<&%rD z74JeLfxxaE6NZ56$BLxoo5Vbxp|9&FXD>UfR5)LqVFeSVAG<-sV*d0$+=5& zm~Me$JjGZbu!X9b zc4U#FjISpU*rl-wfrqDUN&nO3cuQDm9k$ICEvDt0C1p>Ry z55FtDT3d~Hm%LOQDeFukXe&E-~^P8!ld)I|szbO*f zW!GenbRg<8JoEP8F+$cPK;#vBR{oI8u!4#07Y<6^i=M%#4hwmVE&R)lGlr~HmRdNn zE*GNVR!$+bIN4D$crXB(n%{=A5e=mImHI&P+7j4aZ#wT8&K20otM?yJ?(BDASiwZk z%+634{s9(b#qhoQ2950GiDvoA+Ea}L0=ouY=mC#y%9Cu}7Q9pijK6Ow?yj;u(t%+G z6CZYkL9vTIsg!QQYp(yJo;+>D3q|jcoj_n$@%s??VpNTMZmIUW?}t{DJs*~1$Cf%X ztYG4%sSkWKHYAsxjpW4MqGPc7Lp>HZJB)>&EtPg`eE|E;FFv#?} zGl44=9zx4^?+)_5-RJ|D#hbH*;h_vGm}t|nI;^Vo0wyO%@tXHo=tz`Rwb+sN;R1nO zX6GH@L5qhF{=kJF-SojgGUl4HGvOf&E0{PEWCU+bzrluthP)n`D~6D`8gw9PrloCxw$?W^Km|p(RS8cl51wpcH|O) zz%E#31CdtciOu5HoM?V_HSu=i>z2wlV_3n&eIIKGJXMLLZ{5U+QC$v`y66kODU;KF{4Gm{6-aOzaenS=AgI^V_V4`DQB+OgwL7rZF%VP}h)JD#(9D9B@_Xma-m+!OJ&MU(b0Is3 ziG%(jkk!V4WR*AOF&_7^mv4j|SFZoI6A0|W*-xGqy=Ey-Z*@ZnYv>?kIWZy5;Yur* z$XN@XD&wQpPL_|HJ&feRcfTmbQ7*!)4-;a$N+{HqR|e~{)ty`g0=w`Gkgu${ zR8Gz}s>oWsaAsJ+1a8NCpRmDevUXiH)-|WGKwuZ10rKpiRUv8NRf|38>A|pq3ET(k z=+qpwlbGMJV1qop1p>S943Mu?`?{3W=xW2>oN2asTn5@rf#GG~g7*;TW$3(s|v#Sl+RpP(~n2Q8<;Ta%bS#!G{>3`LhWnJ`VSiuAy z+jaPot?!6=2LxEZBTQD6-?kc3eN~TEQiVK8n8l_Ac4Rx zab~&h-E25D*_zcp(1KwF6L=QITl>qt@Y}?ajk+Hy5ZJY3K9%OYzYojIat`U}R9c?| z^B&e_1?FuSRxoiP`>XV1|4pbjw3yG98U@8d1Ak){`=EnBVAq~r_a%qr*Ff3o!^go@ zpHm@Vv;nL9z8k{|CKj+?l3V5_P$cyYW~MqjVfNkkN~@Or1OmHe7L|i7>G_Z~Q~d^L zjds^yPyHuKoYg>v6--z+s|q*b&Vg+p<;0`lcf9wyt^~FkED+c=Y*RJZJ18IWM&9Fu z`GCqKD?Tl6o$=2+?^loY)esYWNvEb*qcy;A6z9$8}~{!Guwuq2zSqE<`-4&s&LY z%_M1Nom%WcwRQr5U2US`rDsQrAnnK+PPCE3q=Mn*EO9+wYk(9?44$tq1+;q%Q+E!` z9a>ewk#u%VFeQnMopF+li$Dv zx7VELR_mv9F1H~&V<8gQg|9Te{;Enz#ZM>Ydv ze;2mCo+J?1h3_nNbbNXSLEJS@wk+RUxaY(~hqlqu;_3Qi+xi_mMu*+;FnOgXd%Z^_ zunXTI^Br!r=JWODP1tQC58>V!6F9@huUhYYFwDq@&6zC{*oE)(c@ALoeQ56G!=A2p z7jgiYz?nk+#J!aTF&pE-X14Sc2<*Zc3;y2Pt}Th(JXhAct(cj>1kQN!jPUb#Qhtj) zt7Ic)Kd=jDUU)XDFqQcAtnBGx=a=b?818w z_|v7zXUSo=@~r-#Achr8;9VCy1Nq?y>B)X7fwe;g0=w|u1Kv|#+DP(y8L%@QTQaO* z0`JY?Ygp>7Bx8NbvvF113IulHy$8G=Ge!{h)Q~+YY0I#J3B0?C@A;|Pl~nqr%f@f* zBoNqz_a5-~h2N?}TnZ|(!2>%ntY8A~cH_^4OTR&>yB=HmrJF!t7v6iIqmxlG5jH-q zz}5}wChYCQgqm;vznywR>Xn1Fd&;p+i+c$KcBy~=vonytlf!zXY#wr4^EP6ia`$B% zjEQVd26Vopxp_SSM)SXet#)hh8bAJSk(V*@uwpxU%wday6-;axJPW2BXi3hVUd4OS zK}93wbylg=XhgO^V3)Xd(5BC5xnc5tYS}qexaY(~c*R+8Yk3eke`5iU@$LHvd79e~ zI=X+RKwuZX|Kx957#ky>eW0i8TDw-k3MMp@6QRojiEL{;g~wnON5~mQHp-#e+XVu< z5;9{UQt=^$#i^XwvvQPtYPzlReS3<66-=-z2{0kun>;$-o)fd>;d16kNh#c!ArRQL z$UGKi+q;n?W7X_n)7K;AE^U03cj>DXtYD&ZqXd|K!tsLzR@^kK41*S1Q{q|E|> zUDX=RfXdq)$e1_XIk9H^NcnypWC~U=F>T3IxU#{Rxb45m=Wwo1`^x#Z z=PF&oMSO1}SB32wDCczQuN<{Jr(gvW@8c#z@~aQvY0{O) zI9b|9?)*GjiHN@^5ZLu@=s2)z`x(X#wdTaT;{)Z|r@WPqovtfb!GvCm>0njy4qVLL zzzNeE{pCJ=TomI^_XPsGaGsGr1!zA|{xaTBx!Lc5f)z|WN}B>Y6RyHB(^MX#nRRb| zebiI7>3k9h?84bdz7jCChkR>$HKjsx9flQ56z!h~{tM2*E& z3j}uIY$U(O32iGsN;Xp#I#*{{!9>v5aj>WDDKKrMzSp3}&|vw&B`+mD*<2v7E4|VP z_~ddHsz%M=gu^m_`9_hWa@yIJVFeTPObkrecLWyCP~Srz8096mYagbxo5@#lpx?r- zs!O6^KtW=wvT} zz^=U$CVc#mRE^>96eKrJ_aO&lD}lhS`%`DYQM*-Ob!#st zrpE@$A7=C=?S9o|Si!_Bqd4ePZ5eDbQi%g@{&G!&Hl*03zCd8t{ne8pr0W`J@1Dg8 z`-4R8J)j5ac#acD!GzRk8mwu*0vw*IXRvWb6WK0<=ZCjB3j}sq%o_*F)KqX-y_pk} zoBGJp*2?5kTNj2EOpLBD5q2c4hWHCAK}NaCzrt$rHxM)t2<&>(ZWLTj-UvxG)E=%w zRTtSezdo54*py)f6V)`M!C}{0n0-nmA~!aWTTgoem0ko01a@tE84Yfm(xFZ23Ql;p zwUzTd%8^=A0vT2?5feNd^3JV?nitjn%DTImJnP(eXB}k zGgGS7ZtM%=mu-i+Z`HS| z=&Y(LpVvgdQ>#u4E0{>T(I2wzZH8L4=W^ntuD*O#Z<$}vp&kN(UG-RZ$eoY{=?7vt z(c-PHeBCWYGVRopVFeQb#XX_N<*i`Rc_t@P7MGG&<15lyNEI zry&vj8CEcH?^I{lxqk;7X*-F>=rO2>gz7J&<<~_B1a^sUBe@xOm&`L6MyGcg%&>xq zi3x3?>%wekZ8?m`NIhOaLXX_1WI&WaU{^z@5cqUH7s6cBSw^Gpr%6KBQUqpU9K2Dl;ZzmAgb+e}rRIp5gEzD`e`0A`&sG6~hW9@LN{-oZ&|S*;!abMs8~( z5ZGl=!5&ULOoy(?raZ>(?*-(_l()p9B#dDN6C}(Ys`N~Q*h}i0hu_enGSUubd`kgZ1QzG>~Bh6ZK>5;r)}1aPxX4PBb5TlANk*DC-ya z3j}sGKWhyuUD9Fy#|oUVnRJPa7+*_%m*B~;f{FMY_V9b|2I#fE949L1ULe7(P37j_ z+ynx<%73zkNvAh~`KVv~o^ws@o8(%A9si1p4a15+oUw;it=7YV{_2;3j!Z2i_X8c| zpB=3PqC9f-t63kO&e#ZMF)uh#r&bYJ+}~54wZWKS1rwh4?4iF)Dnz!p&WT-ZuM_=> zK5~-)k-)A&olRj{k=n&dfX#7?}BW4uROyFCiWHE!#4gcytDNbP7Ll@ND`v` z<*dmffn8^Nn!?of8zI!sT zrr@qAOsv^$5B>I~Ko7GZPLP`S$(u<%)!IH%Uu+#;NQhx!QpS98FiaXh#w%=06&4it}(6^;r`K$ z@afuJp2hiC%6sbiL*xbD?oq5@Lj0mmbP^?V9t@Rtn7tPW>~bu5C#Ahkhr;AS9;1z3 zHfh9jaZ8*xP^@4=q8FtpqcR|8>Q(;Lp7c%Yi0$MUdGC^60)bs!UtW~#c5=e)B9Gxd zZ2=itFh<@ItEXTE6A_U)(lNvBa5blZ6G>GPh|P>qa-Vub1OmG}XXZ#|o3_L2wJ!X8 z_|A_YmM=!gC-y8-u!0GbMGK_y%QK-}8z)YTNbFC-pG3;}j(Y_HyP_B5NGq!BfZ}lV zo2;=9+mhk;2FtBl9#gP_iIK?*q%pc#AXRJ434>$3h>z4?)_rh8Ah4@La*mWcdk0vR zQ@?7J{Iw-HKD>|IHt3mx6-<0wy+GQQm<3U{hjHSZQ&%#hSvNVM&JTgWuDvNaQm2}k zaG=#JPRs}lCcBn*lG|O^XIR0+__YfpN7HPW5}3$|=1ek(zYK zf)*JYIN@Q{l%zy}-1>_h!wM!ArYw+#4$Fbj^VV}>fpHLdxW`8>T*U94(Qjdw>*^e- zYq@NY12Q==vBZtc>FFl_@bO|;!GwmN^TYN#;lR)BoLIERk3^htkgFW^6$tFAzBEVD zJCqFrZtvs7*=PsyD9J{C=MliLf(hG&3#6iwo$$OD zl~Z!SX!>DJtXW*27#h};OJ1~MSi!{JnG2--hj)R&N_G5bx88~D{9q)3oPY>ZGFDGtZrQaf!wM!wk6$3QOW6%+`6oG1vAQjJ8TX6a>e)jeugXIN8YgwU18e5;SG4yTTCpkk6~EB#FB;!q@XEryVs!U+s3mRg z?q^GD5_92A8+CpaK+eOiFK%Qd-#>^IOw2BsFWq)O0L{D}aUz7>g-Ort$cj2s1OmIh z=VeP1$LxbouU>KDdK7~*df(x~+o=pIm>6?$zU1tD5RC2=b7IcEe2_xVfaTO_0)bsO zqO+y5oescz{kNPL{A4R+3@5Pp=5&S?Omv+$UmDmT59p`IoS12v1DOMQNN$y82n2TZ ztC}rMYjy~fMQV(dyO+R=4%O&B_ZbW;m~e*q(kM#`ZN{qgxU_i{JZ&_URy{XeAh7HH zmMkgEMgxZm)fuv3%v5NSb%Peyn9i_*3GXNKq^5NlOx~uR^T=z7@as!Cd`fyEkP&a7$sxYM1~bi49S@*rG7sSlN|~;(Q83#7{7G7(rn`dfxxa5 z_e^R1og?5h=^iJ#d0RopZ)=s@31b*mFo9QZ@i(jXc85sEjmq)7(E@>87Y%nv*RxJQ z#?v!A#`f#xV9@5EvNmP}!wM$w`Z66IP4~7iZowX<$)J$}fnC?97f9BnCt#6Az5h7u z-52)VV#?2wVGJvnD7<-EDmb1Gu7>K}1odA8{gMwTm&`{91a|Fs{!A))c>(h;nuSwoH+Yhfyxc?l&spr1p>QTSJ#En*(c!JCiRQy z3E>6M<@<3Z_-!=93MTLhLH_3YeWmbevqpKNJ4_(3OV+Ip58IxAG`sIS#tjD@GQ#7e z5_~&~VFeR-g&^NccBKySK24QR`=SK`yB`6s1>YQg zs+oxjljDf-Qbl>OP9(7Fg?9j4p3Zj@y-@Q$jen0P4{fh1zqa;cSiwa1uWrz`@g?|? zdV!z8`m5qdmg`Mr?20}Dfn9G00&Gn>3&EW#@)*4hB1ultC*>LK#;}5k=zT75yx=B0 zs;SP~^MfW6xBj1%V&AR;fn8@F`og(>*Wm0*4JTII8%B!e>9b7V4h$=pz&n(9YacV8 zyfrAt25xOH5ZIOL5D4x^ZbCrL4jyA--U4zls3PlX+lpZY6L^Obf78^546;2_pSkm0 zTbRHu8!Ex+te4P#X6r+I?sGqlIL|g_{>K6tRxp8gDDj@bhZ2LWRhUbmED+e0bh;^2 z&;JQeeye-?E+rO_O{T`|e7-Nk3MTLlB|eAKJSJ9cDzNA&O$7qG(kcYO)`8z(_N+BL zhTF|wq~6K$Y~4sth80ZU-ERCnsT~aDb<000XDfRN1a@8D-U=!ge}cezIy^?odt?61 z*C&c)t{cM&Ch)F3{^aLE4SD&B%gTtp-U5MLw_Ejq)Zs<2zoR<$@iVrN_ntbSRJh>D zu!0G^`;fmSZAX3CH+Hqs&xo%XMZbkz_(?qfn)xmlxgaP}$-doKc;b!;yg!oXch7pt z=gtmM)}C+{2<*b^1NeA8OqP3ibXOes(^sru0(TVW?Ty5NnDH;6Uo|S9qD=p5> zf_J{wxxqsdrBl^2VPYH4+y?X4`nBAdFKy{z)IcQqzL=5sk8+ZY)*J}Wge5h+a^2t7 z*Jv(h0nIec6$y0}TZUN<{4U+@p#FXC>{+Q6RA|uIaAV%uquJ1)&-}e2ffY>P*ncLl zE8j_1)88c<2Ktw3#lQ+C{#=j90}W^>|5kKKi?4f)GlDgly>?07PS8Lp^`;d}lA-1~ zPpz6`1rz(L$7%{5u9ZTgBeafgy;XtGy7zMGw=KcBx^5s8%wJ9|Zp>~p_kBl+$J0Dt z)!R<2dB+}I>GOeep!4RUy~Dn>p#7&Tf;?BJ+&{;_3MLZT2hx_hOJLtz7p;0=0=sbi z#8TmU;Ib$D>Ii3REuqyq5iQ^8CKmv%5>P;n=x`n%2V`+t~-5leYUW%$xGEj#fRef{FAk*`V3ys=3_9 zU5g0WoCAYCWch9SveI+W_Z(O_#J$POmj`z4=zCGxZ_>f;c8q}*;d^)s{cc?#)$*w0 zwWC`aty}P3>fcw_v-W+BCaO*q$=K+$)^&~*Of>AZk)C$dg|F3qxQRy>6C*uSs9k~$ zeD_V*dp5E%vok6T%0=FJ91}3npZv8CCJTgtwyP&yN46I<{&n*$x zW83!a@G&e)GiOy#p-y6{aM>}@{AC98X>nDfIXptERG7f7;_M92Uw>Vb6){SSz}Er3 zK5(7HQeg!Xld^N*d2DLl(>g{ue^EqzRaAbb$z^Q zyIRBNS7nOc<2d^JUL*u0*7L%1J23`UFcG|H0u6gM4uZ{&xc`~JuFg#-&`-_BL-}g& zw0a+`R4zY+R=E-nyKU<1#j*b!0~4=*_NKMh%mTlg8?<^K{9D+CXU<{_+%M%dTSUh{ zX#p;eExm9*CK6b|#Ena{>Hap|ASHUQ*PjXO!skgOu!4!JauN+P?gieq>$GBE0=w|p z6l36f4*j975Mhu)53amrheuSAzzQY`ot@$5;uQME>bBN(jtT7Q*v1U(AEeUiy^FMn zwGY=rlZiFybeH*dXWFg-%gT-Dm)6O4f6sR{4UaX|BCvvqG@~_eu8uwZbt(B@2<-av zXn++=40@Oh=iHjnCHqpfVqgNh@JJ*c-M@R$vXOq~o-~;FPzMH&J>|Z2cm_0ScSEY` zab2rtz{;I-Tj71T6H@IkYcKpue~y8PC)2lse}!zRO7;F)?F#=EcKzKS|Bulb_fZ%2 z&xX~8y}_+*n%AHEE39Aw-z|ytzyx;v`K|~nnE3OZ7bdU^-;s%>`n$E4WeP3@c)`x? zE1RTGobc_1$*DW{vplWlm_FC z?e;VT6X~D3SCPO9CiavVLbHh*A!2Svt-B(eUou`e7lw(DPg#=R zjcs7>VWf3*F@asUw12J#CLV3PD7i;uK%H^gqZ@o4F@j2*J@Xoz%HE2 z6l37KA5+KmG(@K=NU1t|@V$>nU6COi_8Xv0>0=u4LkS_F<^a&#Fj?(0Y2-P`1e zX|YsT!Ndg9<#d>PGkST*O05wG6WI0loaldy&bvqTq4gqX(~H0B{xkn9%kTa9UJc*f zVb{p?TGY&HJ$=7gd(MDo6CXosL9OTOX-vQS|8XXRiOgJmD5#f4Dg zHZ{k~M`#gP!Gz`b?^5?k>2%qh;(sBqE8OjYbo;;->QLjU7J=_&tEMi3tP!ngRi~~0 za$k$*C777dVGcZL--kv`*r^o*6WE3GuwuKy_kE|kro-K$pPJjN;{M}3Cnh$Tq(j5; zIy9wQyjH33JtubI*`Qb|tYE_0b^`=7H=#}|=4r*i1a{#$su%;$kbE9zLS5aN(v43E zUVok~VFeR2)@8%uE3VSKjbU2XIVP|R-&2dF!U`rPc;$dn=c`}G1Ld@0U;?{vUQ3LD zbJNw|t$`5}Z6GW<{$KLccz%Tm&6xGzu)HQj7aZ0a&oO~rc#bNT3M-fx>X8O#n(D&o zFlE=D3GBi%a*@C}E6*A`Xxx~1DJ^xzzvQoQW(yN{;-6 z6E}xv(a%<2{jv|~YLyBT*oCu(Vhrg*CLQ$DT{CN9Ij^2?Gik_~hMJt1*Z-92f8=-Z z7-gK;pZb?iqW8}?7RDVXOD+P^i1-Zq*+*PAca zCXn*s>~z{>Rt#MioBbb4g^6mzW9d@sk+f;YEbSP7J)JD82X^6cUaUD*FyX1pqJw(( zqsAs%v|?ZayZ$_r!8zR}9VD9Vl1wA6Ui+8)E}kb~0!9&fia%FvXqePUtOq8rD@0$W zVf?A=zTdN)MPd)TuKDtK3ymdD?G|<@)uc~Or#J2v+x`9Q<$ufou!0HlONUPBkVXp* zY0ok+fnB(?VyUo#39AFuY1GU0G;hFttx*jV*!Ac6)xM$=elred)4reH*i~I++HAX7 z4*k)l#P07q08LEIp;|Gpf{8EtihYOH&7r4TmHZ2VT^mNP&wGA4o2LJIqebNXnj>wm zmPw=Azp^{My`7ZPC5xV2`r7XAdj?IF1yNcARxpvi&`t;D=5EfW4{vMN0~6SVkGdEG&j%%PMtTNYY5d}6c6i1q5?H~+{ZF})?fz{PbYE!I z923}ukD(X?E0{2u*qu;l-`>5acobKV}Uu(IV3Z zHq2QA&srSYE5`V{=4H>%u?y!>L;@?Am<{%D_19{6Gxx1l3`}4b&Kij^@JKe|b{5qy z&dKYnIQ+|~_V>tHHr`?4$D=Ho8JC*3Y-3%myE{x^7ar%uQeg!XwjSB^f{kyJGfty+ z{+YloJR1-Ry&0S7(hYYsH~X~oYGSs9ZiK6vfvehi{XJhPdnzXqSZP>o2lbCj)I=Aw z{%1z^KV|^9=9qZXeg}PgXqsk2bfDI#h6(J#vk$RUcx3tUxD_=Xx`_HVsP2jTW0AlL zCO%AWM?ZX9Kvz8+rF8}|fn9ipBgSa=I#$!CK_)#G@yc$+x22kF_Z>8F!b`iq*HZkC zUKA^s=yEJmQ~CNfy2?hoFTn(M;n7Yk6;?3O-}Jbq3E4_7^4{*x1a{$3TO{zvlDI1` z@63j5+VuLH|2V2)V&O%5&5biz^sWBC_3hY&kBC?*tYBhl&p=J@4q0@;LhUgM6WE2% ztQZ4dML*VUr8UOx(hQ4^{*PA_CZ1H>M!(sF3*s4w6A_$8a6>k>x#lkVB1t0>}Nua z7kBc+zx3xAm?+BKNDq(FrAJ?sYQ@06g-c5Vr1+_Hu5TdpPh3VDnqJ`R!W-IG zk_UF|%6xol09G)u?MwhPl9tn{XVmv!y^^ZRwud?~`M_i0x3FvH*g(j2jBH`$`RQ{Z3$O(g>NKQ=kH=<~D|M@QH5hMNW)_6--#&41k?H#Z-teA=^;69dYdusrj<#7G8#z^+!Z3w`^r z6dIVRF&_Q2WyUMEk%`^iW$Q3k+9tdd;@)in?8=|wLa*&HAf6Fw481~g);BJblo~XV zv4RO4Pe$fwrD9Rxt6frwet? zFeI;6Cv)P!cpFywI*lwf_L8xJiT<~o>HG%O$=N0gIg!@UoaGHjC$-!A%2>g~&j(J_ zZ>I_I7(Aa7v)kLS)?L<-U0b~c0=vTa8H}4%gM8Ipz=;~CYcr|(2C|pGkYrwYC)!*w zAr~{}Lw*-$y2{>+Tz)VMFwNi3(9DKCp1zvgS?D8U1ru_vGj-i$LMmFTrE(u`!>$fp zOO_q=76|MTOZ9Yhb$0O0dJ>i&D3t2#2}kjTGF93P{t*} zMCegR>K$lCrVUNvrCM2H&N}yAK|GH62?TZxZQ)FRh1DaWUlTcTy?YJjsicsl!9g-s zFwrr`kvhAYlk9scvBKPfweGZ>)Yq2;0=x43oT**~bN*^6m8c?Fu-#Eh$dsv)j1^35 z`|3p7Ype-;i{r$;U=#Lx+cHAm2gz8$#Ev9K`s9)|ahnv+iA{Sfm|Qf6%!vnqz^=LZ zPSnY<0g3-TofEe`YO<`6^U2|5&1I}$;?i(O+UABW2@Z_q#QIYf%%CWNRO>iz`G4trfFg;zoK+2$HdaiF=&hbJ>S1{vE}MucPa- zd9p9@?iVT$*mbIsBi)_tMPjxL<3wGRR5%})c>2+S zPW{=8cuGTfJ;t`PVmdc!kps7Qe}#Svy9O{vy6P+;bsr7ng#K|;wmPjMaXl6$V+9jI zZycyko=oBl265tZu_YT2@C~LlZy^xaHT#ew&C8O>grRDT9TzRx^*NuQ_mCDcRxr_* z6Ag1^GHZxRRF%!x74i|>by~_;5r|g~blOvY($r5S&gEFLT9&J;n#EcD3J`B;tJO*+FmpITWku6BMb^Smjnr}2?Iup_$>UT>SE11~J={&y> z653Ra(d?B48@qBPWUdSq2<%E)^N_-Z1Hh19k7xnrN1)L~*7Cn|k1y zG=E8$j1^3XF(Oj=(XC|xIcLHJ0=vq8bD*v4TM@TnHAdC3W~^_6FsN}NT*e9}aGi8? z#;y3S?gW(89f1k;YeQdNk8_8H(&!udFpB?O+jSgOGm~ol)E#IdQBc}~PUVVOjR2}# z??@N(zpw4}pz8A-l~8wdiA2P^Dw;W5IcYGLPD$vfSfh?lJ&_2g zty^{mznG7QJx|`0xxSZ7fj<*i!Gzt|J7u)hIdxuwk1izt?TG719d2wvXt>7n51 z=}Xn~am}_psLu`6dZ>E{MFK0Bz-{c$1a{#zEfQEU;csqMOCtM4{l`*a!rHb@8Qr{4 z9Xau_!u7x|d<;bbE0}oy$*?R&p_4lI!7(s_UAQfX1U?_QgpI0((Bb?j>>nAV6$2}n zK-Y)X8N>v3t^3%K4&^bbo%Pa+k@Y^VEPBz~!;+jel@8;s%Jm*gYCcFkH|kCyu^w2# zgqm|w33cC(NT``@RZ*|C1HWdMwZv3YbB&toSN|V=&vA=LUQ^wn>^iK$r4?gf1rzmlB$U_ zIKMSo1UibE_Y0nMoT^dPIi_waK6-?xw zH>Eu|-Qdk&tr(cVu8y1Q(Qcd=dNe|dP@lx9=T_~JPn_#7sXg`EIkRb>(-x9ir(@se zXc1W1_Taf+Ja^^A&!za6#F}FT6MbiI_nX4$Aus1@#lQr1sZUJ*YP)B(j#ciK5fIIP zt4fQS;M8;?s8`XGcDkUh9QupUZteJ*IJ076*%g&w`bk1(Rub!h6-;C|9b0zQezMks zKNHyXb6GT1OIuL8mKK2(m#$G|uDsIPfMfqT1}35|^(~{@cd*lnfqx6Ta8D%0zzQaM zzw1&~^IlKgv|?ZayZ+q6p{v%f_{(3t4>(#$@u5jnoehLM7^-zX@YOjm=r5P^=cxbK zGhm|5^}lFqgLYc&3Y97kyKrwO9xL1fuswhE26I-Hqv)t>#lQ+C^4dNKb0 zIep+x5EWx!0=w`WRU~lVw~*fhcH+PLF}=rs>~}FS<#=P-mD3;kchM>pt~qw$I*Fw! zG`yyn&3`Mjbu5i}`AIW@|9$YpM2bfVk-!Qjo;N99Hmar69H&((OkfutOT-v>u3lwR z=dyWwqu76&x8oT-CO%wWs9DA9G^Y0~tx{nEyU-k7t0n%g5ujzzJo@L+04x9etr8dR zCFQ9jPQCZqBhEiAz7s-&UAVO3vBC-_Hn%*Nr;dqD`Iz`;0=w|tl1Qk#Yt+$8eK*GN z9U-9h1~x@OH1OdKgmD7*L3xwu9WON9ySLcNj}ffY;) ziHI+oInV8z_b&u?;kmY0Dm+Ww-e+!E&sp)Pt`DBoiUd|LaY^T|`EF!jn%1$x1a{#g zBF4Z9CVCG3YZiV`_m@@-Okfutcf}a^zJK-bE@e4@tpgkX$G#mCkvsd+rMz9;h_lsd zySQ)1E<8SprNRm(o@^RS=kpjT?xtEXFo9io4ll;QeN2S(;o}9?^rN_T{uf6mJ0WSxP&Xi+krZwet*?UQPkRlYzfEiN9Vc#=!Z# zZW({&`j$!^{w3Fk#;80@+*+6fYQAj5JN28Be;C#BunU(~B(Q>sy8PRj>WFGRNIPqQ z3GBj0L5zXNS5y1>pdL4CK7Rapti=i@p1q$}_B~L|&(V2e3`}4bK87NJ6-*pY{A>O& zakO?82NT$Zv$$f6%=xp+a=L-hQ>9-Hf1UFmts*7#OIl+TRxsgoWp3FyPaIfJYdpsU zcHudZSgK7S(>3Zju$Y+y<8Hc@{rxj)4xqW6Rt&6QqUG%4Wtr`_Tjzop11pu+Y%6o! zJ~H<|#=u14lJ$qw(mwK?rxgR23cJv(R;wO3^Z)#oURewGIPz~#0dP-^iMNLzOEYJu@6UFte(wH`cMuXWX81rsk`-;~t8{mmHdQ4JH=WijTkw1g9NbhXD?+>_Z{ z90H5D>ue>9|JWyDB5GhSSjOpVE1b1zj(bt;`t$gKuMgagXWpDuHq(D*pnlyE_i$Lj z1nQOkg}|<>?g^k~wr32~o+0B*+FpmLpk|%#@EjQ$SF~ba1rye7W6Nkd?9smv*o8|d z)*LIChsX~n<6(+E2UDlm4 z;ywTJtyqt$`G#f6onCVxb~Gvb`)I#8fUZrgQeg!XZx?qdqeqv_){21%?82oLONA9o zJn1pNEXH+P?OqfU*oBX}7z5A3A`<_4YW0if=Kee*!wM$G+=wcBLT78OJ?p~+cHtu; zmI^DFaIrgC7UR(&?b$0PunV7AF$V54dS#oH^&ig*q5-#Kk-!Qj?sl~)ql2mq);i~y zz^*kZE@i|AzD7rkft70pu4S%6eDx0gC6T}iCQ2qi+5LykjCNWvFo9ivzH0H6GjP|V zvewu0#f<-W)ncM*C!Ml7mBdccDiv8?<7ju)x;eJCeV57m{OnLqJ9 z5F!xRRg~-k8~EzaCWq8DEJH7v%6t3#fD!I3#wiYoCKK4=Qp^KL2{^!6-SIGI*&@r0xUCEl2<)o5#1-7H_>kL` z)EEoeTgfx>yoil&kc<^f;B&*jm`*Ka|23arIT*>;RvwEU2>3kly%}#T z<#UejAUCRoa0W498|(_}p8Jy(8wRN7W0IMC(DxQZv=z@ecBS(3-+50kF}bR)f%M9; zl%Lk$3+GcqWUOG~aRXNfP7WbQQ_9vrb~2Nzy-0E}VS50=kt;TTPVj&Mm=`2;wfi290`^_PN$gj(Z?}43Ay0ctV32K?j1^4a`te;U6V2p}L+eA} z<8YBcM`7iB7pTD3S?b+WV-&43ljntAko@0-%UHp`D;_IXGefyet2`34Fi4I{Yz!Gk zenIPdsj&Q5V<;N-5$eimka)oj78aMn^0M7d6?_}XZe21+=bNswrh_}2-B=2{4b#B- zmOCtHRSMVn&Zp|t+@arI1Cm{~+o@NuwY;fzCK+k%B@oyp#%LL1D8~=qPpU}G<>lsX z(DH-<`N4N*O>$@q?QR;7s>Z7TmzIB}vVKL`&|)vynAlv#E=+%Z;0pO$tB{|^m-1uv z#>7~zo}NiUJOgB`2*lXNFq-dOdJ>_o)4%_zqWm~Ai)@Yw7KqQt)%K(-w1H}5`7(9) zfL)s!^7O>DWd4Uhd0Qt}kb}%f*HL_~*3A`KJT)aJ_9wyS=Z)bW-^bMB;Ve!}DXlI~ z4@@N`cLHTWL4^KjSFks$Lum0FPK^9!E*pMIA*~CV2?Tb12y}y~#x===L+XrdTk|@y z;k6B9PctH81rxYV{ELNsE6W$EWsvEYdCgI6F>ycH6&@ckA+t2Zp1Oit8YXCeDMT}T4ANCJUfRwo*RQHD9Of2!V1 zJT9pr4?eq+6hsEeSiyvFW_7NfGMC#)$>ghrBoNqTe6ukuYgv!f`=RcrioRwpFOFV8 zA`AUwtYAWD3p%mgt>mp41Bq@ue;Lmc@Vw-_L1XB8(vhr-W z1rw7WyTJ94jmUP58sjQh%DEL{NrTfwAh63Pv@vX7Wk(t|RQF&FcvVw2Hkw7!8U)K& z!31tS{3}XNE#$CT3FL4eA`sa1p=)DU+r0sCVbghxmClxO+>2S{!Df)Lf(hK-bad>) zs>xk<=Mw8&S?EP^uZH^-{uNi=O196-B#zaa2t6DoaQ~>IQ|XnByqsA4$dDpn)`{>dPgO7XIhKkKBET_IjV3`~@a zaD(OztCN>xA&;S7&0MyamrmZr`3eMf;U0s3mEFijeqphWoO$Oh^d*>x4ReFO8%@YC zGqo?d(aT1D_+kyY_evzN3-@C>I_(>cVg2j5)4S_ZN#eAXwBnMyL-rSD!{$q?>4P3K z{Ibb?p2LqUb=4!5fw&TM*@rtEC2D=}W-PZRa#(f0dC!MkLC`d()q^)4I* z`IFkxRVx!{-$Hd3-su6bUn5Leq-_d0Wa>}1CQhZNJvM;XXPH{*jHhqyGN4Vn)^z;I zNV;iC8Yk{gXwA9=E>+yC8pu*H@UOX>(hhrXL;hi)GftS$lQDN8}IaU7#+;|47FwpW)wq%SFv=t(GYs5sy=ky zHJ!q}XnNXE4<=lgMo+vROegiR=0wb}#;jzRFFRSX27D6+)8=|J>EhV05^da{M#U%6 z2G>4GhmHEv9$yk@ykf`+KVr^~S7^yd@A+`@s6Xw{bSW)~tqME%->%+EX~ONQF#KaX z%1Y%Qm2>QTV58#uBD8?V5r z*(2%aiW8`Qmj>`+(G=>rbp+j{rwiA5kD}o^Q)t){eSWNN*9JDH)REaN)(8qF?6bzw z?4RT5u+uu6=o8Y6t*~=tnQ?ms0=phZjiRLqQ)r~^Z(ge2@!i?W_vP6AJ~f1vh+E%? z@FjFcsRzBGr?%aaUH#ampHG!nTdfFg)ws34%1)*WpIcEQE4A(B*YD5DITb5T(M|*_ znAoyvG4=L$qI!{yIWepMK=$e5P38PYH-W&e#EvUy_9AooOwW`PJ#3;_0}HC`9S7w8 z#1xuZq)+Wlt)S+T)zmz*GVMOk0ygYSruARdp%Vu=azfvJIO`d;S=m#!1sOeYExp|E zy{2xG4VcL(^nMjRn$q45oVKo|OOBOje&4X+M4ffR*i)Cy%A?YD1S^<${d*OC*8P)a zRx`p0FN+Z@zwa8w`*25rz^?Pp*3tN++nSdP%hqh4jA3C%rYW*bZ?a+K20FlCt7hOh zXLw|>o>nn9t-0xB53VoQ()kd(8Er z8>qK)nr3uE4qT77#2S~OwsEwoL~hLPPwUc(c1YM2meq`FgBK* z_48JwJ|hL<|8aGmVO8v08yF6cI-Mf?p<}|-tSgqTzCm{>twH{18q6+@m?G} z)_KNS4~wH%!NfhDN6+p3ugVpPR-CYy69+7o{&$Uc?Yv{}pMoz<7UCQTtR`%2i6;}&xF!K454G}yT;9JWP0LFK^^Kdtw5+@RNv-u&j-Phi9&ny+-qBP^UtsD!eAwb)Q5I zy)0xl&5p?CH@wN&9fjs%aYS67n5UWpVdn7D9xEeo2TE1!EXjuR_h z#6jDBYe~hpB!R%Ll&ZDtUF$^oX(vxk^ynK8B}4Ox>y|`{6-=CMRm@)eSSnZE^Wem_ z;qegjF@;zToG%dAwa=)8)iWF~mrZu##8;0v7<{8HJ=iXeUYb$B)Qek?4$p&#;pWwB z)#DFx{mxTJuh`YBbEETeZhx#(7^e z1E%%vN=NRPOFQ1pVxJ#SQo3Xz@g9=HI^A_3wfo}9i|yHLMXdqx@zl&TYqTRyKt>b((a;IxLU4Hk9vj**8>wPCN5|1 z8hDUJ&F1nlejka2+&=o$VS2DYU>CkN{Jmt%3~=pYMBi?jOV9UQ%C4`RPuhM=CP4;E znO@p_;_)t-;2M#nbHy_tGux2nj}+?)6MrFtjoK7Ly6P_AM-^li3!M-5qw(7!gxbX} zTyOk2*g72AwX>pz8`n{32;Zm8Wic6jE|Z+UmdfJ$=99;^>BPSGLiY4v4hiA=6H1cV zwyCg3Zxl^(Iz!(#OlD=7C1l^prKHp)iM4#2L%ff#B-TlZ?6&?^qUX7c6BBMv0=F7Z zddlVz#R?|eFVA2$%S*`0xka2f*wh(6IvYq7g z%_1Uk!*vp@E%TxGV;@tjU?S>v0;}J(oP@8|9MzmplfcN-n@%3}P#~}iAFU*1Zyg3_ zel4OMZnRQOUC84$bxxA-JL^eQ{Q&l**Ev%2b|tCunabLa+)c9Yl=3o?I=MjAzGV8* zwW$g#m>3;CotZp8L6R1%;KcYDZqTY@0^M@5zCd7CO;R*l5>!d{ch2R+w;dkPN{OSr z(tcB{V8VS)H2ZwNlK5WB;e`973Giu3B)xd`t3Y5^@PTM%S5Qf8j%bLuSGKVC_cHqX zmX7M^voY*e#U1kV>T0t6h7T+4d4&|D6%bq_lH^?K2-=oQsrSt`LS13vP4;AFmwujT zjmYO^Om-gz1&QhOOO05&*oEtj=kdBp;dh-J`r~&;;i&MD9B_7Hbw1xC+d|jyGMwwn z@a9A=Jy5r+3M-h{A7Ia#o&nOidKV{l*bad%Kk{j}P+ft*uDbp0SY+ud(m!)8Cnh+V zLE5_2G-15HD)Nje8+rc_8EMUk;Z9SQSjtG_U;N4mWi+lfh2{BcXk4Pc3M-g+8E(ps zo0X7p?u%4!C^CY zuT?Sm@%=P;Gt7*A{ZUT3%{s=33cbPbq+$tOy+u!zbZHP<_8^(KcwHxN8VzFKBJzo9 z@Ogs&Ns{`Fu>hT?%jnl~u?$Sqd1A(b3)YZBQD=D>1KL=?xW>z=YlTQ)7d}Fs1LDFE zc-&40IUE-t9~wE*6?HP8SY=a))I4 z_=uhgE11CNCrJ(StYJxr7j5XNuPPnr#Nuv`BrjdB69X3uCif#mzugnE)WU-8i?k(4 z@sD{KJ)^DR?ExPeGg@DTl|Ef8*u}*|NnYtAg8xa95XCRB(SU7Tyu6caVn|I&=B=+$PjzYk!~*5S0x>>U<>;gkQFx1 zNyyOQ?2W!LX|w(|`FhWS6&Um+?S4GxMAi=((!1GH&n@~YtYBjGR|_^bpewP>dclc; z;S}!Y^`jr}>Z=AN4`#_7>yejNUz3%ggIVUtMkL?mHTf3i%rg6Ekr$KhbK-fF4O9(p zPd_ZwQ{CS%g7rB0NNybZh`4nf!cMHbAp5X){~^+zQFzw58-4IWUxoh*6BkPd^UI`$qwy{lmo9;lkAH_SZK=( zc{8ad<{w5fdZ<`FxAh4xBR0|&UT?ilb}rLbVFeS{_6=cW^Yi5IQZ*-b^t6Kt-D*y3}% zbhd+T^Y)SuZ}H6WIjwTHWS<7ea@S=acp38~2k70nj9l{XrNRm(vK>aTPWg7S>+h$W zkgV;&*LWdWd`M3quq%9#CG*&%BmcRrDdWi^N7$3>E5AJ7Q`O$jiq(W|8)6y!k%Tx| zvF{TztTqIEB+u84W`j?pS^paHj1%X&I70F6v+{n+UMj3$BJrLjn>hQR^&jVtoVZi# z2wf5kiPonc0)bul2>JKNJ$smbZZwg`>#4AUiEqa&nfA!L*1P*@%FtP94|BE#lb^{V zfnDO6r^gP1x>M@0_4c}|KFzGz<%HLj{c=B$12?SLhc`u)zod^Oyonn-{w=I>^FU4Q zUg$9ldhI%-mQU)cu!4!}o2^*W!H$)-eKbeqFy0Avy_VE1y}JtpcHuhYBdLEJp>z0a ztBPSgg}TDTuw*NCcXY{=ZOS%;Va9Z24|eXIpH+>VcAKwd+t!S zYjLD{*s7Pr=e#xhICz#ilD;SJBi-56pF`C0zDN8#%=Qh3_*`H&FLYL61ry76STpOe zsp{#+-g6=`a5(I<+``7J=%T`kR;V>|{%WC~RaE_-GBR2YhbAwxSo3MH%B7t4F_3%02;^7cp-9&MC-%&MvzRVuBKBO*ActaeGWVS!GP@NF>j^J9C zB&}!8aP7THxwuSQweYRXUQc_d-ZK6rd2&!@Ka~sWRcBt2;LKsH@&0}4Y8y>U)Y{|> z;}@7Ip10bmu!0H4r7|<^p{Qr*X?p5Aqld%sL%-PlFP&8QNOts;nWf_@_46J7J*ujH z!{K1J&nzgYv(QQ~ardt^b9Bj6?{(Gmi7qdkc%S%yy|(Hi5ZHxV4F6Uu9RVFb2P>~v zYN>KpJ2A-ktafd2pLB2}?DC}F>hD_5$g3)uJ+*kGE^>Uy%SecI0gInYl?$^PsqhTO z@gl;;HfhO5bba)n*^F%wE^yCiu~Ipwu?o*~U?M(~u(QLPu|97#tzCEiC>ZcQNlDls z64-^0md`Xi8Ug)oCo8$_n+xZGi4`II2uC(x=F>G#wd8Xn;PS({%DCtj0)bt)7WlJv zmJ3|jwN@EoP*=4ia~x~)ya8+f{sMX1hO)FRJ=p0#w~6^z!p0SMVf_wh-b?HaU7&5) zZl&hlKeXD94?I^Hvw=F-N$oJoY`67ecTe9S4+f8C#aG&}mXpqKqJy0athd;q)ZVP6 zSi!_gE6Qk0AGW^yCMUkE9|?6j9aUPFRa3J^`(V0YzHrEt$_suehq z>7R09ORklZF3U%-DC)>s`YYs^fhXG;WzHVhALM2Hb9n?jYWqxi4_7HxFtMzMiY2`r z%}(_@&WSdj&d{^|OJ$<@4S~R}m)a`!@_-BLv)}|LvV82}bzoC?PWIBZhgIz1&k&X$ zwUaC=R56qCsVsf=Ua}y5B~u|55zLou}H9RP1^FL>8OINSz5P zCVP4^pJ|FvZ~VJ<#W3)0{6*RL&n1fM2NRo(Rcxk-JIgwCl$TN5!wF^|sa7n%UlR!I z!u7`Iimp$WZW{9nSVXQz*sz}$)7X-XMZAo%)@IPz-53tH^QBnn zG0leEI?3m2jg}JpPdpY!GKb7whOkO6R44-z!|ZKX|6vQ5{dmpz)&41#5ZO#0N;c0H z2<*aj$mc)uhd^MN9)wgU3$=?0bJ>Q~%THo=8fr$0hP@a9KeYA0p>?W2U>B}w{^Xo9 z5WKsa0vOv+98-W}4gPcH_9l?qW)N&Fu@}w*6E$fz?3BY|{_UQ~kIK-0Ah>@X0Fvx3 z5ZHyUjU??YG=ztpEFo}1KOq7FAK~vJ8`gx+^6Q=o3`(TBX|HZX2>1Bw+)RPr+VT4l0#oi$}_8PFRRo>YPB z--aTAT;frka_$0FzlOuS1{p%MKnRZs=uz(+OV36blL_v?^`b zGd`0nTbb~qYTTq36#lV?-NuIm0=saH@Z6v0bzwr0BeWWJTBs{bTsvgL%9mxaql%`C zyzri|;e$QQD!(rf*oEtjkCFYbhg;*)>8?5Lgc0E`RUT~DtIfo){;vOwy~ge)a72|! zTh8wyjJ;w)993%;ZUwh)XVVkox(ft$;gLfA?JQfs=iYgAM}9A1%n}pgSYP)?X3+9* z0X?fHj&fob9xvt3s1}xBtG$rcPv|9#4&pNKXd8cf?IS~{=8NggdEJF^I85ML;4|+1 zRp9U?nVNs;A`sa1_rZ8}W?TkIHB|E}czd@41m&jCh@0(HSiuAy>*uqU!A`KzEs=J6 z-&!EBD{N^Xt8KcH99g-Imr?wCG(4L&n|`0$NQD(l;IV$5XS?}W7=JmEruVNa5ZHz1 zMfeDdKA#2X7*0PJei!CHFd@zYs5ec3yk2=%PN2;mH4zBx`ZFV# zneU1tF~2nLS8j>U@KI|l-Qm|(g%wOJyWqus8rl=@Hk#2|FdqizD?DkLb9;fnuFqZ* z+4llJQtyT4J<&1C4wygBi}Ajz3M-hv++bOQoYaDhVl=uxl}ibxCVPE|p*A z#M%xn@K0)Ade*Y7Kw#H8t#Ee4os#F-3MXuC42QATjOi}kuCRiM)4o3J^(=jIVAlms zY}@D#4F*`ym%W<`#NEGhm`fi|vZ_9RV?{?RNvDR7gX*k-G~;G{;ixb%VPpcEtwYI) ze`m0|v>pr3mF~31p(X->UAWeH{O-o_U|ramzL-#7s9j8)nmnHkzTA_HHm~64VR+R8 zj3zgr*N!z72<*bGhtJV_dqV1|I#kEGp3q7#p|dB6|rl2qu-nHuxZ%^lF_}9 zKwuYc)BLL_&M)bRj=Zcb$Tm=*$oUHE>Kq>=l_!h{|F$b&3fs<48I=|PdKW?Hp%)spkP zjP{o9U{X>dZx1a^HboW=&{PPQ(+eT@@Y6M|sD5>v%I{TNN!ypY|@TBQD+w~^Sr zT*At-ZPfNj*W>){&;^`3Aagf3S8N~`Fq@WDu@i|>x8dkuGfy;xS z%+^==`gor}U{^p$I$NoAS6%-f&1|?*HXXDk`zkl-E-EPKe=FZ+GCF*hx>>URln)h~1p>PspI*Y|9{#D;ZI#Z6B`(v!?`g8qD`-8%3MTGP&tkuNTvJP%Q#s+h zC=gNx6ex%GuNDaGI@u+IO_|!9C6>?SL{@GPM0{VVl;^FWSi!`Ghs)Wcw2$h&&t`C9 zaO5-~jkhVbdzK0WcKw}{$#(7Oz=B^);e=U6Abd91s?1rrkYWWBMz%Su`ci#%Ovi^4 z+O4O8vzcZ4uG#yZYcfNSPBGoiSeSJ z1_nZ%6Q`8uvcVK9n82~4lC;sy7hMO5q;FF5F}Av8BFKpyi33 zO4OV+LeGGSge__8c0p?v7@}GK;SoF)oXb}!$AdQr1a=8MpY+Eg04#2=Qbu$v7kW5M z1V*N^eYYfLdRx=)F6lfCB6Cv|&jx!10=sYz&f`VD2Y|VhqV&?O6nbh*q?@L&RekTN zv+dXOGMZaY1Fv*1CBEx1fxs^OT;X@r*8m7OGC}b;c1C#OV8Zgt0@hQ#Lwzk?^Bq-9 z#zLxgGng3Mh~l*pctr$m`Fs}Op&QIeX$ifeIy3zwwA&nsWVmE=nF5L2Y z-~M_Gd~|IB*V6h>tYBjOqZIb?pV90WvE=9Rq2C1fK2U;skL?5kyKu|r`^4=Y2Tius zfz*#9dF}rHy@rXTW-08j%8A(*YNBy>!$fGXSTzFNm5EY zPYVQgiFedDGk>^!Bthw%aEW3C6W>?PVS`I=sQWta;bolJI|3a3w1@CBUxd|1c#RQm z`TXs5`fvz4-U%MI{wu6e!i2aIsp&Eo2tVHz%+|N3_`k3Vw|t(T;rs|#zN#I}Xxf8f z1rt;A=Cb&~{;XV!^79DZ?Fz1i&0%XDSs<_rw|qVu-hVV$N-d$~7e|T}OdK#K6K^uqlTZ^Ya+0ctXASM~bcK z3W2~b-12!D>nDKW+DD4E`5KB9O!Vv&$EN+XU=M$3W*U-t&oD&)v{G|$lR#h>Zuye* z^z}s8<9kYx=nje%OnA{5Y)NQuHal`1FC(YW2l~?;%GySi0)bt)&7!)G2N3!Ca+JuP)UUqTBFjgcud3U+f5*9J|wVr@9JJVVJ<<8j^J7nFCZ! zXh^U0&=m;m!qHp&jcoBSFzqH$BmJ&ItQscp_zd5N_v=vb&pbg+4(Kir*o9-Jc-+#V z;h;130O|I&vk*;%2|Uikdj_ZB@bOz9d7Ru;Ah1h}TY5KeBv@yRBugH36ylaJfxp7} zF2~nLz^|D@DSfDvmy0VI5q;W zgT=8FeEz(bE1cV~Oc_xiMp5y?bBr%`@L6>_3v0AL_PQ<1+eJEmh3%fM%7+691BtDyA+>*Clo6< z8bXX`=;=5X+`={}i*LLZ2<*ZU9+FgeWi7gnNB*f{7dc zVN5H9@AdRhlY8f&+el!xt)Sk7i2{LL_$ew$CcmAbeaF^dSbr+T3MM*q3}uaG`ZH_y z1Wg$_uHZbYAsl!(Um&mxKSlZ6MAax5c&8yW*p^1If{BS0!K~VX=kSlu;AIpp9Ru*{ zoAT&+u0UWHev0x~=UMKczvY{9ovx->!Ne!a>1@ngC-%p5H80~L-;w>znuki1_GW>= zF8mbbBSk?Tu*dCzV&8Np#R?|$cLuVaO^2`reKzqj9&MfgSKW^*_neqOU>AOh^3@#4 zHzvfj`e#E1!-+Ekz~AVsKwuZX zyClhUpgH)THieoGcZ3z|n3x>u$LjKL!XQ;2em#E5)-cb-5EgB0Nb!GR7rwjrT|3?q z^4}Q2>R>I36-?x8nZ$N4o6j004dZ2;Oj3bmpdKG_Hxvl$!grS>je1LOR{2D~D zf{8b0ecA1?v)RZg(|8#^^&H?}(=Kq=+g%{A3*TKlT7A16968Yi90&POtY9MJvJV@a zAH{BYYsQvr7dSz{;5MMlnA@I^^@ zzeyml3*TLQU6KE2nD_p((strbiWN-Ym_k18V>1T2cDkdiZw3N^UHIz_Q z6;+Q@!g~oOa1^2>y)qsH9ivVvW@T3e0=w`#3SWzCG72s`-Bg^P+!SItF(Jk$PV7Dc z5_Ik>9SZLY1a{##Qa&?!)DUc|W$^RPAvg~Q&MkrOM@h0<&gOO8tK8uu71S^;jBWwKr41h1r7BI`MRv@qo-;aEC ze-jfJeqk`Q&uc)jf(aa*#Mg6PHV1Wy37jhJArRPw??)a3X*vix9UK5;lp)0mCU7hk ze`cH#Sx zf2--KpyohVm>oW!Vg(aolwLOnM|fq~1{R&n5(w(rdds~CegOwC3m=L2T z6AllDZ&nRp`>0IA;{ z<+B;t!=UfwKT67$qe7%CCdByN*%3qGB>AHZ{d-CvunWia@)-IXv2cEQ7HMymPHm5` zV&UD3#$g)9!O-mYQUv61qzGZDNOy%!k=;os9qjBy&p3eN6;voP?uzK}S0x^pOz zQWpsXcHtZslC-BmJdBTUB2~>&gzOiX5c4xk9vlyO#DKWDCJO|1;Y=8kbhc|8*bkEE z+v?duwgsH40q0TRxmfdJA-w*5GImEQ#R?{hHs-UwJ$zBVMO1L!oxcNn-F* zp;*Dh(}Z-kA?~$2>e>cQ{NeK-OWIvx_fIuf)hwCBeD&hgad)p1{o6k5@Ux$lKb70$ zdqFU}7h$fR-AohNZ?SAFOxn1L&79amg%wQfSrf$S>`th>x<|97LH8biL#|lIZggxc z5ZKkTY6hzae^zPNS2G4s)pr7n-Zz=;nBG{06->BpiDqNNP7N8HtBKf}J;w|BScEgD z_jLsVyOgK|=C9ko@`%}CPOLfO1w($cU?0BLRbd4aCLiapF0az9yZdRPkSw$&fnUS6 z%xifq#RPU$XC$-v5mij>0 z)>B>IuUa6mYemFD=2dgq+O*YfPK#R?{ReoJLbYRAZTDmAeSY0=xR%NoV!@nakDBws7K%#WYxw@=<;q@rYst6ZeKLX088Z%2_U&d9}^8 zLGWrw~d;S)PL@WKtX{&>C)r`{V*hpg}ZN-&3xAo>^j$N zDYM*LA?IBzDt%Je~@p9Ak-_^&^46E*zu7W7UeLfWa_I z?stAev4RO)3w#zJ(hpp(5wfz!SAoDT9LdAKwp;kYl+90Mqha4ERxp9DCZBy(d&BlI z@8lsdbyS$ZE*#0jBm1X%!*zEp*>Z4Q6;?2TTP6QitLq6m6+`62lZ^xdyKw9e&pB{l z0_^hCRX3%LRan6UzPtF`oreb`PCs1vEU|?^V3#;%8Q0DO`agcI9$nEwg%wQTUV>lq zqplF#b-*kr1`l zg=xc9fxs@~7un2u$>l>WS8JYX$^n!28PR-$@ux!?khB7OZPWM zz_|R)HqK-h9CHp$ZC}dEsAw7m`f>e8{~lYZ zYolCtN3T@w;+{=#Ej0eSoSn~#l3TlJqAY3;Mna3+1M>K*+bC8rfop_+dDV@8S!JW; z7?=G5fn7)AmNBDK-Q|&v#k`Exo5NxBLrHzy_#nj!CUA}LwK7{m!JvGR`c<7{0)br~ z5ldOfv?A+Lqm8_b9m7K5uwFNIOY1nr3MRz53TqGy&cTG$9duD3u{&!L%f8m>2@J6SuR9EypQVFyR}R&f=b& ztUR5r86C9Gn+^`4nXG))MS;LB@ul7=Ph;&Y4%L`4_tv+bZV?(ED zuz2z=cI^8-fxxbDRVl32ZdK*Z3!3M7_qhQOxa|k)>Hd&n1rrJTl9)kZqT1DdFDD8w zOoqR?@0r`{7XpD@@w`8Cu`M9?IT_=BQKHX-+(i_JrBJJ(Y%G-ziowAWXKr^Y)W_&0UdA%w0hjeclrN7Y6;?2T=fC)<+MF>kCCpbj+ogd(U{`w! z5B9j=x_Zv`8@!CXd#;cd9HEe@jZ|2{gt!XZV(tjA9pkHPYtdSTSB>K}^&;WzKN2S1 zaZ{e~Ck|FHfoFjvY3JWjFz4A=#pSiQ(i^+*(enI>dqzWjYM}%yZ7G}wCd8-Ox+Csz z=vTz)Dz3!z1E)lN>cH!2;GiGUx zhv&hKl=<5ms<46y{Iw)WDGn3C$EvBa*t(8DU>Cj%BVwexU;=+F@in8T10e1GG$H?r1AZF~J$~=c#!ZQjJ_-l!e^_>ca^cH<9 zr*=9o5ZHyE!91QpHw3yZST0A6I4eABF@e8#c<(bQ44zn?l&_Bgfxs^OF2Psu90-GV zX#*mqZ=_^@}-fQKk zYYPb;%ZlNdbzf}{k}F9v@8P<2iUrSIlS#jp%PCecfycFYgz3i_@Cn+I_6KqV0=qnm zSF`Zv?d5Kr=kPK%mBqrmn!2R9*)ob1Oo$_1UTLwg+15%fxSb^s*mZPQA&Xg4V6C$@ zjF<7=Ee<-&sMz`z%GBbmNjT!*DBl4mzVLTQ#=$b z%1|HSQIlA~1kO*++m#d#Wg~jA-hWdB0=vYVJ7R7^mkOgaSKT#mC3+F@U^B=RK;o^dEWO1ER;SCwL82s+bqgaDuK=-aps!pvD zz9uk%TMwTN=XvPcCf%3cE?p}S*oD6=Bx%Oq7^v%BE6cBhf(hJu`1jzu88Gy+Kg)C$3GAw5h3tl3ab=QgAiw5o@5Vw_?F@Ef$`Xnd zOyJhTBjU4oo>Y^qY^Qa)KwuZn_srYX(m42jc_;grwLr)OjR~AvpRaL05C^Z`oMaI2ioV4Hfxs^D%zu50fybnSa@csGa2}XgCKa;%o&jo~cAE7#{*z|F$h6n&PSXs5 zz%G29c&?XaF;MjW6I--;xo|x&kvnKLvoAMLS5J@RWrRG6fp<-}vK5ti0)bt)z433( z?lF*cZa4G)Qy{cNOxSuAu-eR%l{u1Tg#P@AXgCE6*^~!G0)bt4%z@{0@{fXXL7UhO z+cIIl2~0Sz&t)h4?p1aP$mC@dc}GH|#R^u`r(7Vg3x8SiXpt}Buxr#g7LmGB_~yh! z(_zb5kJWbSqt%)`si*!4gE2YhSxxy~fxs^O{mC;3q({Q*--{LF-{UFH*^aZki}~Aa zu7<-P-5h1zXkUsIOyGR+Jjz=u0*)A@E7#^l3IulT3t!EKwcW3Fv>VOOW83F2$T!JQ zdOVy>v4V-zH7i;D^N-cN&Bt+~);j`JDKU!kjx>S5uIbkb*veLg>NYx4IZ-wt93DH( zREkQLP^@60u*(WoV0}vM*iiGVos$*;?LNCIH=}X{0=pLU%x71cCa5!K%;Lns+;C{T zW~}nZIG7pfb!(aaU~I~D^Gil_2@r60u^_;LPzoLiqqK*UAE&x>Ko zmA#WGRxp9v0-qV39Swsw`76fx;R1nOxL=W^2Vqg*XA-0|?mCNN1rxX}@ULzEXwchf zr+lwY5eV$U{R*Fh42^;oUxq2qA1E|3;5DkehdUMmu>sl2#q@;&fnB&?;nC5%g5locTtz!`Da8sV@LF4*!qg)a26msX z%$l4h5ZHzL6`uWKYzVyDnxq_aSw*pe3A|>Q&&q5KgYoKw8ltr9^i(#R?|ys&D>`iVlVC zhng$IY`;KYm-wvp@(h7%PwI@8E%mzPLtm~|FXO9E|yYN`AB)#_V zg+2pglxxQyQmkMC$HVg3rPJPUuOvhXzy4AnunUj%@-bxdi7@q1x>EV-ImHSl#MoNH z@(ECCm!>ot|6U-l3y<~kS+d(6;9;;r+1j?6Vg(c8dV{B~V`1}#EG6UIH-W$|yq<#R zdf{s``hF=<2HDgKD=jb~W~bDd%2yAJC{y~SNkYy{?85mod7S>HNuZ_cObfR^qdB3; zY*1({scyAa$kv1RY~Zn+*SuiGdv|JL_mN@+=l8*RfB1T}U0#s-#*02WR4owLCFUu5 zuRj(n1N>=Ebv+eUFoE;_@Hc%ES2$oCLiavxED+d*vnuho@Y%y*VUr*_|9KlBdlDva z-XER`;l3jr*%eLK?9dSi?84ch_?MTqEsSp*Otn^Y6|z8KLd*!%!GwZgVk`~$+g%{A zOU!@OyT3IAUWuZHcX|ogtS}+wZ+|e%628|@pv!NInd`9&=fLN=EDVC6zOEC^GX`P* zkLlJatSq^ZSngUP>;=M~Y6a8b!&wK~>D2+@nqva*H^TFzR!@UdIu3Mg!;=DmUATox zQq7QH(5sSZ(7F9W+rWYv@e$UTEg%m4!iY(YO^g-E>AEu^7TQ1z%CqF$72V(M!@Bq!L;0cSt1Uv^S^2wep1>bueMmH=V6ETtv+N(X3eC^D7*Fe;P!m?N}=i z*oCjZB(;i(f*CglP_^H3iWN-s`M!h=S0$0!E-Ac>OKT!vRgwwq5m_h@*oCh@kId{D z4G-$~r~Th$P^@4A?_Cmr{F)m_!;i>5JQqMF#R?|GJ&`)p zM8KWv-6>tNRv@qoUw=tzW)ux;w0h70gXI(}n85o=Nz&z!k?<|HE&U!;ED+d*TMS>7 z;t>t|%5`Y7JJ}Q~m=JfIa=#e~GaJ{Z)=P^80=vYPIAl{a)E&pOQvA#jqCYW#cLw8e zWJyt=j(A2!H7*ti?81?!JUXF642<^vOa>I^3Nfjez&nHS$V|%^NPqEwtT>e?5ZHwy zX!+Xk0kM#p(1_aYT_8ltVnWmjl38q5ZHzHUE^;VeAhScuxrG%XuhyR z9*&O2@xnZg?0qa8p17B6I-4f!6Nd>rH^p=B1jRym`XTaAJ6#~K3&#sflIyw|@XD@; zcrIH`v4ROav%%k9-^YOY^9`hIOP)Yr7mhIIZ{d6-HH!C3FJ=@`tYAW%yNlZu1?TUs zAzu3H1p>RoR$|#W5(c_0AypaMg=>xpJXgpgQs#w&OHocmPx zF#a%U7x_>iunRx!_&lfKWO$o+m{k3GD?HUOfwRl;6+DGgASvq`S=0KdKwuYsYV*}j zZhr8gZ%dfKIS3``fRi6|9BV-@PkA8_ z*d@LvuHNDem!@0M;qa?C&?CUINZ8alT zo^D{nQ?^)t?cJ5!Z?%DSirI5e>q{^Gwv<-U3mRT_fZ-GKt#?QIvd%$^*yX<+2Gu0E zvYOfqmj5);Y)863Yw{_LMPxMO`y&6tBWu!qKPzVj>Cgz1Or|s2n$1;Ok!`P+v)D`{ z_K%`XR`A`fgX4{v{!z`&*1uEv?9v4*y7zc79b1*kTEEF9n>$V{qJ%eZ#Wn>^juBl(LGd+b4Ic)t`Et{mW5<%J6rZa>lN8FZ7pf}+lJ-(y(L56 z6msI)qd1^bYskG$(e(b-LiVQnZh6m*iR4DgYPSFL6WN&h6Mf%87WDP8JfxF5Crkrp zf>+2vqFXSP=DjawC)#b16RT{=;`9>c-nB$_olD77zH@JkUbt*9d>AL@y_*G_@{)<) z!!fk4+j@5HX|!yr>QB68tY_Q0MaT|TMg(6c{x1475mwh^sPFbVCF}pQjah~+vV1%3 zn)Tx5+u4vqMwZ??%dPue+{XMoS5>;4TVu^5AYLZI^d-yGQ{>$;Rxoj{^>+4rppGS7 zlFNxA~`;!k%ldj2mr?#>#rK7FW zRvnbrKi|qKT^y~a{Hfq&Tz-=PGjFY|tg=%RtQ4;(XPJ!}T1Onom+wt3XU@x1l}>e5 zb7Du!M7Uk=Mx|Z59Rw?wxLa1vZd{hE9oFP=;%J*h@NvCY8Je|CAh0WLQ#m_w>#tSs zHX7nkuX#{&YlYl!PJ5c9znN_s`q1itT%UYBxS6r$XRWua`Xx0$usbJ%*L|0hm# zY?uHOLhf3xS@WArzq*ALJkGU_cy(J&|G9-tbIY(Exbd2dYebUjc1wU%-wNwDTfYl+ zg^3*1RyOJKeCw^>&+;;yhbO>qtpMww_$qx=d$a` zE8Uw2y^rF(k?GaxA-m*g^ZR3U)*L8l(TkK#w4_+U{neem8`&t`-g4n09Zu9OoeQfr zoR^)J_7cjNyLS`YUj55DwYDL_b;x^$D|5kj`vIBQcNc0G6Kw-Fv*c@ctA}xDv3NFQJ9ZAH&w=9a`ow9Bl|W#Zcs-i0n+e^DcM?a(DHQjE?NdwHsB_t}>E9v$ z=@Ydt&V(J&TgaV6e~NocOzhlP%055IlAm-R!jGzHvsvJlkV>vBm?99^CHA7F`Ln=r zQzn_-Yl2X_m~iX6o(=CEFBeQR=4Cv6FblpqrIHh?#tH;>;T~L)9#7>fKoeh*lCn^0 z7gfZ1&n}ZoipP_obBdU6@Fm%Qz6<&Cw}@rhoRUX)kKkq0#>GPuzJp(pAKzmHDU188 zW!86&%Qsg#6Z}tnrh0ok^b5U1W_=45%D_bKxnkzns9ZMQs>${8=S4i|ez`=J#ZMOq z?8473zPD3F94MDs(x*MAQy+OXJN$tdw82mDsE#fK!K^ztOeGgdQ;{?FtQLH@jq zG5h1dwRKC{EMhvv3MQ1C)l3@jNA4dpffM6O<6!6EhV-CLgg{^ye(v&&CzsBB+c+p+*MK(R`-WozyTs@Dl5KI&K&uVyu_jPBb9_!s zE*7w7eOi*vn>0~K?UuxW+1b`qr4>xEf(h@0d}f;7f)w%H+IjYi>^S(RLsuGQFj*k5 zOEsc^)k$wdnsu1O35Shw;83SGJ!m$O1|3a7^`VOKIEt0rF)NvawH|rxJB8qX;$>{*XTG*KJs<5Ulz|ED*7>Yo zPFM2dsOFltUl<2Dqr21Qp8f)XUHF_dd28cf)WsgOX?tIa6-+c8m(Lm*bSAC)Ysx5C z83*+$y3^|)CJ6*~iFKvjEFOl|7}4BGF4W~yHajs}MYau%Be|1v*vMVZjI*ZkaMo=AEr}RLv4V-Oo_Xx{XAAOf$}~<4Iv)pHp7*6;X=4QfyYRK) z@4H{)Akex$U9f)?#R?|s2Inz0(SrDo(3Fw(gxA$zBO0acCJ@+#uPlG}sWTJW-W*8x z_cy2AZL(Ms%P=yuJdkvaTFwlUCXs_vgGk?qET%oogN*8`$+Nx8As$Q~^rxj3P82Jc zu%DF8J|sAhs-k#KOg|V8+q#-kyL#3XE0`$Roy{s+xRX7mn$~Wp7Y~zz`qNaM5dwi- z_&V_whY9hJePtl+)Wb%&f|zjao5R-XxR3|kHD%lniihqS2GTRXZ3P0m@YUp*hgZ*n zi1OZa&i+oc?9~#MTbfNQeoi6}dMstFsr$*>0!lO3wX!tQ)n9WDLiJ2=-fcv?=<5pvb{X%@VAl=ONLYr3&@!C~OPmK%(`5sN zD~PX+$-peu@P!Bv&}7Uy;xH51y&OQ> zyABWt?7EY_jE(h+B`v6?jCkHkrq1n8!yL&5z$oDm8u1tuB=Fbi3OD`vi6-=~`&0u??!%2Bq5+}BwnhBHCMl@3C zBM{gn)~?BkS+M=59-Tj;gK*99)f_s7w}pi(NT#VK_B?9zOwe&MpkK3wP^@5LLgRFH z_iPrK)qOT6>RQc)OI>?Vd%2ZBU{}fdbT+%!8uGZ6cFlH?w?V>qhX*CCqeblCV)=LyCm?(%|%;X^(h<&XG zCn8790<)*x=#F=N1p>S95%L+{3$sD{bw_IVsu9HsCR!P!vuQ(%$>`CZyo>?Kv%$E$ zD=llS{5bs7VWOB2GY;O5B0!2Z@@XkUucJp5H z{G#S<>CEK0V7{v^z4iTppkSiE-$ItyxRTf((|m2`Zk`M5LM=J^{06}aCZ;|}V=rzV zCJ(0Ab7F;R4lFp=khbUVKUl%U?pLYo@AXPzR-<_Xi0eKN>I{8DPPv^Vn82=1xoOPz z_Hpv8o((4stVw{;=U0*bw%O#v#}wvq=?SsT*C#Ezr?On-K3P-VkNo4B!h#ELkp+AY zGTt);B*4jqn@P}wRf2+vhpSSV{kdzT$#+vuJk?8pJ2MZEh+m}wfnDui@{t#>i)4+Y zd8alVJ`aX9d`e2j9wGR6@p*h6pT-*ZJWWne!il*J_!YeWg%};EN3nv5nSWE*iHm25 zkAr5s#A@F>@Va}E?3uHhU;?|uqgpX65e!Y7_{O0@i*9$)+VIEGiRW;Xlc8VyOwi3MK+Z zq_Fq1f0N>h#+rE|@V>F{` zXM^~8xc4JjSG)uQyKo&!QZKJW2#ot=ojE0o6i-QE)jhPS&-JJBgZ8OxZ|in+UwQd| z&V2awL})%Ez0xvQTR0C)#LP%xPp>qgYW9eKJ2$$R2ov7qTI<~GCJ@+#Yn?}ngeO9s z4b#;>0#Zq3Nh+&X(1Q*M-zw*{Ph%r&b!lMTco`opk3&AoN27W?QO`L0Sx_)>*dUc{ z>8nHU?%l|bs_b$i{HoZies|}WKwuX>C!PzbEDd8yDS&K030Tm$7P7BIJKCV@o)J6-?}kOk>euy(nwq!-$$yIcK#z7E11Zhkj8f}>`5244&Y@h-^0(mUoRGxC=%F( z>y7WhvnUZ3&xvD1DyvN2xRA}%Hm2*xb&$6^JZLXGgegLVm!mUOdnU#n_@U7zm#j~M=a{(lJn^$9TGhqF3R z_li(gnCS5SfAo&ebNQM7@kxX(x8JKRS|$qwcHt|_*No0g1lqR+n-}6su!4yNWBykQ zD+f;EW%#a3giQ;Evi3)I3w45BxDNR_3w@$7j)k(ewYUtI@tS@{m~z{{4Ns z-d%a>Pacu>%YYv2eu0?IvV;tJxGQnAi~hzgmyFTgiz!A+x|!yEA`x;^QUg zzp!f%?@=|^$@k5!9doM^n)7QXXgzEAPGDy(3l9hx$cc0tt4v@6K zin^qC6$tG5ZZP&=;`#~=k;?NY?$eH^ofFMe>1Pa?VLv^(;BNxS*l)<%7UR%r<5enr!^kIYn9!Gu$ZA@iGLKqo%eydei3GK8&8A@oS{Ac4Rx znEu%u z0)bulXeG(~j3M-@o=f$=nF_Uw%h>$Gkh!UKDXGCH*%02=TS0dZG*)3nwbzIlm$s!% zbe9tRPyDEk^P|$rp`ntAPzEN>j5A{SeLB&rPc-X_x}7xnKd#O*EQ+RC!z&8rgkr#e zs3ZXaMS?rsBVZQH86~I)q97`g5m8A3q5_HmL_h@u%#rPB-`AXT&N(aQjHj0GT<27O z|G22<-tL~6ot^3Gu7__lPov{!S_uSJ;W4RHbu^azvMP;^jkJ|<1QRp+Te0dv?dZTC z+L62MwdBu@QmM~Yk-#ePSQSmR;xDGHp%>~{%lP=<(LVCDW>#D3(YI@|p^f*JwtQBv z9QrlbLdFqHDAW3|kidF0piLSO^A1~qt92f2y2Mf-u&UX7Yo_0!E)A%oUDwyo)t(pc z&!rj1yT~}V**uT3qg5|R#Pk2ob7uCklb~uj)a!;aj$mS;vlkon^Bi&bm;*$U4@3Aw{Y1JpOeC;M@9Gpbx9l@%pRV2A zA7ws~XWX1c_YbY2Q4Qy?+RH166VD{y?uM|J^KKG#n*>s4$6WSi;Q`XFhqhPL-<$u9 z@}(op?o%AWM44SIGf@8v^$%;>F!APZm&3fP`2&H#s-MyGSl7k-iN(8>(8ieIQ@Q%W zSZbVkk^WW|u>P()N#k`(iBViMiyu@$y4WozanqvM$@|-gQJ&Ttuutz`Ug4sqZKo6n z#G{{!SmUpZB-RQgrk@tGz{eG2*q1mU3SLd)ImbuR<;kZh{#@K%@ZUJr_~I6FGE}=S zb%sSCKVRIReooj!aRd`$8$H$r@)A`)TCjbWKwy=*c|1E7Q$#G5YwuUzdd%jhES%|k zn_P<56yUW6n1+f#_h<2<$CO%jETK4piEiuT8MP@S+a0uROqw&3f8Xg!2R_^;5LhMl zYG&kYuH)rI>#}vi3JBc8B_xrZ+nY&Jn`wPzbW7**ooROTz{O;WBbdPRK~Vj>VlMA) zXh%C-6$z}eyO_xSO<6%~qLZPGkY@Awy+KxV(D@LGBbdPRK`=WwZXVB>XiHN^ED;E- zdh3zG9+)K)+i%+Y?$w}h?$g?e8m9NBc!mzo+~FBEsQo!q>N>N9RWCSqi)om%EDq-Zb27*ft4JXSiHS|q^Vy&Aqog^Vw9mW7 z{lodXq7CHk(HMciDzR6#9ua)lzqd86`@-p#@B+5HMc0Fg16_&xyaHx3<&g72Z#Qx$ zsgUs=aq49k)zHSbp%L89ww*?PA3<>h6F)T@*;Mx{>Lo1)1JRF0@ZU>6s;e4C2?SRC z18aX8cl)Ha=%Agm{L&_pe{C_7MgKF6;&oQLii+6EDTgZ0vTj5-u7K6EZe6Jk(asJ= z=ZEqA!y79drp=@|85`NheqNf)miFXb^8z;Lu)QYmjstm~TfkoS?5!CRZwExeoiJ{6 zuD0UxeHO(LOnhixz#I-(X$DSr1Y*eMaBgDof*n=`2n1H)9>Uz~jc^`mca*)_G7Dy& z|G)2;uum^w!!q_%COwv*jnCa8xH>qS?X8|I5LhLS{Mh~Z{Nu8|%GRu*wCK}DR{gb5 zvuBtg8NDK(eKcRG88_92EGREx+uMX_j$hHP7O8$QpTAk=q}c2mPjLhjGhtoUR3V>x(=Z{&kU5T7@tM7j3Yfo7ar z%kFmjt$Ai+Oz=_2X}6wbcGqJLv$SvYachFP{HaK(_soLg2qyAP^V!veN1Bh5wCiN7 zdQ9PGr#x1?o428O#UEY?xPAU=7Q5b%-OsHHZG7J|g%4fyK#?!Er&!g0+e%h3*MbFP z84!_p)Yy;PZ@jAb>2#quf(hyJDwc7^fYrHf2yLXT58#73A5$7vbP@=x!sCOvjF>=v zt?fZ2rB!!f7Tg#g4)?r4Uv{%Wck+8E^f1C2=XHS8^Dty$zU+v&H-qc=?x9ITVr_awE8@4@h5@6Dm*6GU;9DgP7C3k@Kh1` zu{MtNEeT|9dJm-Hf)Licc{F=`^{I5V4|uroNOrTa3ffq5Mdo_7&3S0jZh|8pCPcBH zj=^kH*V@7-!S0$6H~wy27w+iEg$O26o-SZrh6XU@KpkxxbO4{BZ^VOc>=y{E!p9Kq zCA$al8OiOqalu*P=wiZp@M7jZ%!}#yYp?dy`W`&|PAk}HdQ%{<3Lj~e>U7s`{BtVh z7Ml{tuC625*7#I*VrG?O)d${E%o5oqi?7mNjSm~zCxMw}yoPgby33lMa#Ztw_NNmZ z!9-@Z4~zb_gteUc4T#_O?D#b&N510pa)H1qd~V7fGyGbCh3ZGf1Dj#CZKMm;5{W=UHS4IzK@r%+~%7Ar}1vtYV z2v1|Tr@oi)5mBj@j_Jz7YW3ySUKRp@Rk?1y>{M_fYrb$b^lIjXHv9&hlYl8QxptPa zsVHOR`VVDl$4r)L_Ck788`^uE#%fo+10t=U6Cd=kKcBDZM{rMY4@Dy1za95; z7{U)+Y)xQZF zJg#Zeco#J;a)*c+*`O3n~vdW&l>Y%ZS;k4V4})k8SA#uoq2Q_54{>u zcO>sNQJ=qB+EgI03Xci)4{r75OJ09ho}E}CeT-ehTo;+LW?r||1tB?Xo~0%G`n0DV z?k(&F{4t3?>0OJ{g+{_SFcIE1i_Nm@%`W+`?g?uLcTD7=O?3Hzxg7)otMHgqs@IpM z^LON~vSVkObaiMR%i5{WP8VNN_Z*PRymi~KLE);NxVNyTC}z|E8D z`+GLBLm{=z;>Q{-Y_%ZV1=a8K_5gtI#jZLy7@4ICzDyyre+2c)W>3kWR_S{aB7*Wd}_g1A^T^YlhukWlBCiD}= zfr)n`wz8)OV>S7KuFxyT%hCMO5l5x?LSKQvDm*4QRCW3F5GuArw(TlSI74-g5g!p9A+#5bcj zJ77ewf2=R#3@Fas;*2T0e>9)K4cfG))jyziG|IAK0_SmIcmK@seBBOfno=SXSd|?x zjrGmxKzp{<<~c9fOokmi7Ibv-CyFDOu)8;x`K5QH;Tx@h7(8|ykBjX`7muwaV*;z{ z?wiVVDq7M^^RYlUU-abvR=UyT*iRHkFwwB{95(JsW9kL#l3}&slCivF;e2}X$4?<| zfHNC7BLJCEK9b)mT|f^P>Bu;O37q9nsU{p9$J2(+p*MDaqnN;|3hxkhaP?2}A|nub zl{st_Zx|6pPZAv&M=&AgKdh4`@C$pU($IfDQ%qo$IP!acM)RS*fpnmEEg45Jk!&}W z{k+wXX136-j!w8YhBq+sqI>&`1Xkgru2MA~IfxJ3lT7#JG?8)c2Ja=r?LnoGE&X|m zd8xEnQF9qbFd^>| zSH9NfSWF;;<@z<8j+)v;Ah1dt`I$ZadG?D~`gdAO8AmX2P-hftHnIgxoi`iW_>tt! zb&mScuGgCg1Xkg10nB*q8o&#e&!D-c2Ez9P6I*;ou}yp0)3L9;p^YIW9=ywA587-& zQ-Q!L{QZZuYF7sGM;C|EA8lI+cLq%0l@YM2ID0U!{_8|75)1?atMCdB$iyw~#|IvE zqLOucVeJPd#5EJ=+xFr=HN)u%*;-g@fLC?kd_C;$*YC~OTpUF^6`KhwATWX3gKzCd zXa3;D3>q}lR3NYl=e%J~zc1x}M`zM8=Q|16a7^Ii26Ibyow%jXV(LD>t3Y5C&RT=l zFL+u$+_{K8pJ*iH=rMuMKfJ5?IPs54IvsqYvp`@K&K1Mn@DmbWeiP~~ckU?UgfW4y zW2i?q$BDPColP%vF%}4{!Z~kPov=>gJ-TO7Ufy2FhGPPMA7SnJ_1=8U^wo6wi4FpR zRd~lS%qMQ5Jg+p9>a{Qw_99~f?_`EO4LpJ$Th@aOy%I$6EIH0>;Cuqq1<6^AK`ppqQ}Y2?9k}enyn+WGr~EKBl(F_ z>zT@UxIkbP&eo_@%UeY9Udk6X-)OLqmB9qgq`>;b77^TOe=Q~Y$9RFjDx7tKw~2#c zTyJ|9WkSwGA-jYLF)QQWDU4gD87ZWVn2*9LoC{N__6`f-ha6TZ&HFnGc^sUf5pxp^ zJj3SIN>Z*Kb)q?Mf?V1raWqx=~M{jSf1|{DI$P)uZGju%gSrQK6*^3!nQKig}R#fq>XT_jx34gOtp-eM|~9ttis0- z_TwCm;n#zoveT7Mi4Z}boAoms}RX`iZVrpMhWZSN;e27xbmirU zuLMUhvFAb&%e{3}^WcNFqQkUdVZ4#yTqWRi1L11ND*WAqD$U#G@#nhBm4~Ol6CA;pv9?TMFTW8S!NgztTy}6% zBeuQhA82EFN)Xq%v_o0?t$}d&!74FpIX`X&Uwr+95>)3i!4XV&M&+=glbzU%$H$?K zSug$hlM`o^fYtSctR+_A94qXp?mU(6So=hY3VJK#WicV&*6~D7}gzPI; z;aoB7c6vIApIQ1-A<4CbEHWl=&J$M3zVL(!vA>l2%bE!UR^iGtkimj|6KMk*F^AM9 z1lJJ3^Dsh{5|x)#9RCoP&8{}6FH|GJggC>prUdqR=~S|Qzj_M+C*rs6ufmQKEn^@+CbDDbp`av7L&FAsvpYoKQ!R-i+U_zX&^<6WE zHyOS~Y1U+zKwy<_y8_m2=66lyh+t@=(cK{aewap?+_^2m5lo2l)MNE$@y3Bilu)Se zfC;Q>Tb0XHrOlZC=`d)cF4QnRQtzhHd2>sGBbX3p==T)+@way$C{Zu^3ItXSHe16o zbGouWmT}O==k-2(%-_#Se(xp(M=&AgCMtZqxbw2#N{*f+5Li`lB$K^(q6O=2DwQlX8#f&Jl5ZOpqZek|b#CUCwD z-tLyW@rLia@?p0P2qv)VgwsOSGBJpKJ(2-!Z0{)Xzl*H-+ZU%L9Ki(6G(rtJePtl7*A=G?V8%u^SAZOsi-L-~1Q3xU8YoF#|rYOV!0@|XF@3!cI%3%q^;j}PYI z@@@Ip-A;V=kl6%BFo9P_K;B?PPyWiyf$zRFSRk+ppC@qI$X4^%8P?qO#}a}gn8532 zz%jiG<*8S@@e5ac1p=$^)dNrZ=lXGzSY!S)c!h9XVM1K>GTw0@AAh_fzuqTYAg~I5 z3skDJ@-Tj-x+QOMdcE-dzyw|arBYpAJc8FV*XLWtBnSjn;cqkKwjYh-gsZbtLXxPRro#zby9bDbK2&M^4n#baKFL?ehz{s%Pqcq)Qfk@ zkQZ43fmQf^47EizPv>PJHxg)!308}hZ&V}vo?`;PC#Y1?+HgMmpKzt$qCA1XD*U_x zPh?l1QpoHf%7wT4h367X;P)Mvzj_kIe>zFZo?7b!0;}+ImrCUcZ^G;Cn<)n-?-ZV| zFoECn;7as}<+@{3%8u+Tfxs&K{0J+Z`Yhmg_m{ArcE!STA|{0QPnB|Q0l%|8nVG&> zDiByDJ|P=h$MHYgZfoA|Tq`{9VnVEQmmV0$S8ue}H1kOo2&@vS3##_Cp3m#*8q?+V zBj_Wv69rcgzTN+E7sU$%R^eS2uvaD> zeETY4-`-1aVUGzWa0Ln2;RZVtUTe(g{NMnAz$(1!0g*%zyvKyN)BD2px%^>|mUL$8iw)@@Te4Jbt%JYVPA^mli3ItZ+ zBMmE^=FH)xdv$58g!NR2pwAs=7sI|kZAy2()?Qa7H|O(rB?>v3nkW!hg^x7sMLsYW zTwE`aGSym&BbcxsyMWzGH=^OYwAWQbsCnkCpF!63OArXG!bciramLQ$-RqW+`@_}< zJMS@pcgw>&=kj^{x@{(DK13w23fBpMY72K}bKPfK$>43}LInX#i2LXx_Q&wu8*dTc z>mLcOw}S79Vg;JO5~y^$t^u8GIFRB9Ch+|jcK6$das4T+=&M_^1OlrTN{d+Koin6E z7k@aqH(So;51#d+J8$Gs9Ki(M8K_d#&YH>ZhV`MHj&2hOtipRD!4=WmkE<(3(xvlG z!T0$8_f%p++y}X8x-UQZ)RTS>xFHZ&CGNG{{A3DO>HHz8geMf&7Ql5B@LChdzGi`s z$;UTjTBA!sl>$uQvk7zh9sPNuZ*}OB=NAP6tMFPAcrKYVlRs+komA&@iX)i7S0z;6 zYdD?H4(v#;*<6qGJsk%Iw7o+ z!Gv(PQ(09^rJJ43iG=^rJi)*@?zn-!UVn_t5jRJhH$4_7PL=j zjzC}){@%a})1Toy?8RSl@4Tn*{lEnNorgPhbtG@z@*SyO($=S_pFmD?6x+(p^XyqMcG^A z1GT&q2}dx2j~mq3TJcJG<3E+_!%iJcU{(A86P6semKBeC0Bz(OJy15(pU!`8{UPB9 zCd6aa`Ea2!D|{~hWOz<0asI5ibhD5h9dS*%HTARRdSDUrz7ZmwQ(xAwEt^^Th|AE% zuC6&sPrp#^DrE=}Ot{+|(IoXMX3q!C17iI05aq^^2(Hs&ztr>dO3lDMrEK+&bCR7~ ziN+|ogn3IBB#|g9UaY(w5zYs+QG^I4(i$GoIPKiRzV*BWZTQbhS1x^>&u3O076_~o z$B|)nfW^OAz=v0b2;T$z{iq-As>ydRXUmsqXPslrZnH0u3wTxkEyA~GasxBX_NnFU zN82-!NQ9TxQKC=Aa=YCnLIe~3<6Jeh9+t5>P>&mCCT1BckB-Ffm(Gy_fmP$0WNL<3 zZDmJn=W9pqXQM=$$8i3tT*47dsMp47#vO(1=rwIEq^U#uE6ZBLdrpg;0)bWdJgHO< zZ(5PfN*o__E?DxOd_%qAfA1OX8)(#HyegPaE<%kC^|UmWK;MFN3U_Cwg zdDht}L@)VC3)bZ=jpa=J8`@*#d!8$3~x)mj2&8 z(Q{c2eK#nS8|j{ra0C;R_uP~&@7~PzxoPja@7>br=HK&qhdYM_0;@LK!S@jEi7RXF ziK^nObjgwc?i}=07D|&wFRPOIkn_vQ~#;L4`bN(8p8L0gojQsG2KJV|v>$qAd`=~6Ixp2CKX;>jNyqX%Ad+{IJW(W~X+`QpJdIA0XiuNfZY(+KwN8gJd z&r22vtSUL}Ld>Kr7IRvg`SHy9M5A?ldHK@%1os#BL+^I+Lw>C+ONhDOyDuWS_Aio)c2tu-+yDJKw#CVp@zi#VIFHf`98F9vFCL()hiIKvLHyU)BH?Ps z-)&68yidx0YIG7j&`p1;aRd`(dvwXEc7?2A!eeMd_wT=S`tDi$Uf+0uz$&pTgOQ$2M=ktdr#;b7z6GLnt zO1JlKW)}L-p;yuM*3jU=q1@@vGl9S=JSM1=ezTCaO_|F*H8a#Wf{Bh{zoZF~MJ)5q z6KEr5emVVmJA^OV6(|r`g^vQv_3fNU*S7|L4rdQ_W8<~bu%27l?TFVV_$Y|?cFWW` zwAaxH-X-jY8b>gJj|e>bY@SX3-iqKOb|(nG23UoES73d6%wl?S9Aq@=D#9-gCd9jF zo!#B3gJTT;F(+2|b;iHQxVP|r-rbh^SjX_<=ySq2Fi}~ZB9%5RV}T>yz|p zIhyaf=OGYSg^wZ3y-r9ZsdMA_?OSf@z4wo*;|^6Y@2~GnPPyMuFWm&sRJY%mh`;A; z_EeAy&Ej}8aZ}?6CW@A+C1+O7R(^X6y>dT%hrC$0fO`x)ArM%F#{{_|V_h0~IhK!i z7@)=xOq?hkE^QlI&d#jVwh`gdmS%K_14t*Kw;Q8kWWLVS9SdC|1@?!R$-%_~=dz^d1>u|G%RcxlK{HI86Hd=?$wehG63 zkK>n~xCsPSCG4oIJe?0NSJ$;|&~0UGR4b^iI>=3pBbZor!CZ6WbUCZi)e^ImTkK)d z0{+tDgc?UMA-?0RG^(RKz8%ZI_ZuJ(SQX>xs+l~poTV?*p7VI$HcD;NSbiX?zZyp{ zG5qa9jaSz)cGyq*{Ww0%Mri}z!GQR4Y8=4?e)oadsKfn~8`jZ0^u32bVAZOhD>W5% zTbXP4YiMKfK0l?_oJd~Ff3fhEir-8z4V6OHg(&QD1V0mXLyaSt7<;%()9`u;%jx_I z+W2*7g7Qz-D1Nt}hd^MJ*sE{v%akvlLipKDfofW@e}d=$i)B0t^z%GO80e0+zWY8=4?9v{qjZQ7^Ay$a@2{niO{OIU?x zsi3magmUHN$q-%;dsUdf!UUd2QK>d`zox7X3*fsvOC>z_g6Cv#Z{aH0b4>}F7QoYw z*B5$)iP=R4%+P29`?yB?d=+{5v@+{jAh*s~B#a!Z@G(@WUf9;=j+Z^TQ+05_CRTDh#2i2x)|55Izd+}{0C2AbOgm0wA>lysm(uMyP`N+T|o>xuPxPcoq@l@x)SgDbc>oVb`uUV^8^#2QbFkGm{o z>C#gATw^O69kn5ix3s6`&zF#9H*HAf;C8g#?*!89nj6tpq4lb%LOY;ppge1F3jJEu zL|%4yGHG`H63GIu#<)|y=W3Pm;P&)f0X>m&}r-=6&exL#1@pjKySMn?mxBO*%RGG=Zc%UQ3`%8%cYgNQQ!g zY9}RIMX?==FgV9|NT0yNij}e>5=w5N^xSINK z2lB$?xoaCME@NiW^y`IWe3*mA9dg78lM2bb&R&`it?bD}|03cImDpTrDzOcD){lRKowk-gbW-z}x9J2&F!8-$8`vy&gDIr6}|s|k)^;zU6R`4}3@ZnxLg@f!TiUS8YGo}b>3LvREW zX}v;81E|*Y0ID^??#$ZGa?oBI9%Q>&Ah7Dw&3WYM(MZ;@p|+;ey8ubHer3sRE^i|^ zf{DT=3&{SK!K@49@_`7KuJt>&E3wM)aS9ak#bGSfY z)g39GI1dY8^=hg>EnMGU-jZs>XDmBOa0C-OT@r}r`N@o?Xlpw4aULYwhqULk1^2e|p2eo_2qCXFlV>9&mv6GJp zj$pzV*6H{@bZ1HW+NxYCO6aWKD+zTQ?@(%OK~k~Mla?rBZ;Pcm?pX@X`quu#)H?ZF?hZH z(_}fZv{5s^3)=ko6j!e=HTw@?a19@1SPu&TP*deZStEjGZs6ST4X)ol6Z$V}x> z^&mQZe=fNJwGH#2wxK*dpX`Hrh6Yg2u>QR~^04x@=0}nV5c&^8%I{FwFLRI*H)tZo z5lq}VT|ll*OVqsmY70bV(=hq+5m|Y(Xc)y2OneC2Ow6Fxq*7CB(rs3l9Fb(9L~rpF z2&}@t3{YXbDqNn@^(5QWKaiRRZzj`x4^{pP^*%$!7m*Qp6_rhl$bbEQoK=U*e|A4* zniaDt{$;_$l_!P7vcyW`>#wcknSLuw*6CPBNqI9%Ag~Jmc0nDM`QdWv>tfR0BZA^* zgPpze$wF|fOasTtHMaRA!eFDMpRTR<8lN97zwEw@G`ku}ain#J0#bZ!oKze%;=i6U zyl;lf`fo>)Hn*dMHZZa7U;#PjW-eVJ+C98VMua?hIwiZOga`yyZEL=nJO}^kc<`?V zkE+lJdG6S6lEv*%iX)iN9a~8HZTYBv)<#>4_3+II`BGA{6uW!2Kwy>l1aOH&$ZxZB zq|r^HD2`yFQ&b^oc;k-x>11sckE25)YPAJJ<- zr}hn``1tggoJ*3yTQq6z`2RXqqxXf$6I(Q)Cxd2CJX%bcbju~JD^;W^_?p5D{f02P z*4DaoZDp`PV3i&a#xI^oy$iK2l{&k_WTj(MI!|W?#Su(2tCLF>eyT+@o3(BH%?Oi! z88@XPyk`moRuvCkOS0k`6Q4&~r;Xn^VKVF0mTn(2jp7I0wTHswTw4n|_uUww4NQ1h>&w}dbj}{25`gSyn3~w)!Bx|iRX)9H@TwT|O_L=QYaRd|VjaQSOwH=9i zdQDxN>tQn8V@b2rBLxDh;wrO9g9w?l16Ne=$LSd^>x~01$f*M;j$ooiw`?-_=wNcR zwf0Ipw>4aLo7jVnf2pPoVzS6V@cMiPUZ2OEGRdVZZ!!dYM%VXVNiGZ?Ls}YXeMald z2$!=r+0jcBf!l^%bX~*clt615 z-+G8ZVAZj9S>*EjzQme^L$CI>hTp+A*7V})Arwb2A&z6XPJ|o|4y%hzdQm*u?D{K7 z9dKJ!f!nG`SoMgICk(NpZ&K|jj$oqb=L%vBj-K}lv}+(uy~5>H;OOZzslPyA)iawF zq}bDod`#0idag1Hmrbgy=}Pax6h|=Odpm=4m^XtwuJPx5VH6>c`fW?shxDXa6*O`M zDGHlUnoIsfBpebWtPFA;TwG_=xVRSGnJe4=g6~I862yXVOpXLP5-`Yxh4f{8P2Q^`~FWTN+7>xgjj?0mUp z`))L)$#j9hDsfImcV4L6ZlyJq4n$HM!Gw!`8fmj=2}%2-bt{NpFkiMXw4(g#41vHZ zd<@~&;NMVr$OkKWvCn+r=whN?d^$PPJeHiTaa~wHX})X)J`G=n%@PQ#!e>^cnvxPM z#~tlWKkdw?c;;psOCo>HWRcFEDgQN#^Dt(%TsX#w_9$H^oDWPa)q`_$Fq3R=uJz3r za&flYE#8qv-CH9NScT7xO67Nby4>l72c7=mFwHp{Px_tPLQc$GMjF0bM8-uIk>ktK zNtJm#@c<7M9q>>A_w1vA^2on^Y3TW#6h|LjH zy>OBhzn@Havyv1&jU^vmY$Myjg9U#Q_<4CumE*6CrNh@>6xzUqVZAt_Kd^%Q>AoC# z<^O7${1yCI7N?vR2&}^6gL~qlvGSIp`E>N(pY%>hD0vHhH9f(vX4;k+By7QP5>mB_ zguwp?D3xUTDXn*nae05aWlAc&ysEkU`OR4JXw?nUHensX^M0@Wr;||d$7xmLkMp2v zu-v(O5>43LNX8LN;5k6}n;^;M;d@;U9#@5Ou zWg%n9YlrtFvh4~uR)=m_$>YG`=oB~{ZTRL!=78&yKe#>x*RvzR;OEptcQt9=)Q0-mh#tUE9txjHu9#IHsl`o zc1?VgNItpRl9*;KY4|~yOTOtwv|eIo!AlJ00A5ptB6q z{);$SZ7H7!T}9&?cbD;JVd8zTE$M68oW7=7FQE>1Y~o& z(5rRyd8CzabTKjdr7h9auTNe2X#KnjxRrd~NACe+k4mV6p#L)K5|O0Bu}_xx&}rF@}bGF5xpiSzAfj@>!c zhO_~nxH;doK5^}&hudeoh09r6;vA@7`?4HNu_#nz*0W=d?s}Z zw-?&L#A!RoS%Cjw-u)=()sjj}`Ni+Kv>iAW;?Ke=d~Tr5#NvLk2h;>~ftrB7VSl*x z=>9HnCASZbtNHsJcqeWQ8b?aNtFgy1t#{3>k$vT8a9$h&&WkvLiG>UQL;uICvGyJp zxfRvf{^*ns~Kqef^6%LhKPA$Vuj+Wnet37A{+S);*W^Ja25 z(K>7q(^`MX+a*sZj$k5ZSVRrc4BSLvkK&!#^1Y{9i5=`+ zYS?xW(R#~Tg8ONM&+#>XYkfa8>*Gls@EMhAd`8WB&z2*>H8dGqLvaKXh92=XZ5Zs) z`i#0svt%!DCUpR3QcPgg4%g@!!W4W>q3Y0vNVz}kqMHx9=oTd>*7T%aoqf`liU0Y# z2Y94jJCXpa1kGq#jVG(_%t-ldi*_Us99D4z6Rn*7L(i@8WF7u3T)qr0u3_NfiV3VL zbX`)@cH27Iyn%=70(l5{nVlRKvOXM3`C3X!Vz|4|wB@Rsl=sZ`z(adJQV#;pBlFM=bO5PNla zW1L*xjIbl4?+c%WRlh5eN!KhhI>%ZKy>j-Blh3q%tI1fph~Nk&@KJyorp0lx_4l5v zxbmKa39Ra)P9`^kyUPTrC|Sra#< z9%W!#dQfO9uIkzI_Fw?EjS>ALQZ5W$2l zxNHVbG@zRC+BP!a47!fEBvntQMAa^lxV`yFs-qhcxlJNDl=zEmz21Q2%uOI2!2jH` z#{b;-K%CrVQ>s*HWhX>15!N-4nB38$Lyfdm>jF>4$$M?|BtxZ(KwwpWlSI-vye@T| z^$LjEwc_N088PIRZalH9OeDw8JtV)gOi1AFL~?7%BNBDLD>0jrK=Q!(-KfU-{bc(% z`ETbL}nP$5Q1tTygfGgK$iT}-mgx0 zEs%X~m6A41*O5PdN#xea%cOl(57PEqA{i2Qn}pxDBr^;X$-La_WE$%SM4sUS*-3Md zctNHZ6IiwPauTtzI79Zobq1pNQHK;&J?RYtDsU1`n8}N#3 zn6;E794aS+?MIO7Z&S#y=$$08<4|(xN-{|)D<}DR+IgST-D2c`O?tH6m?uI66C*aI zkPch+kc5A<^X=*mk#dl+FzI$N`^XZ zCU1U@fi}XOqvb}wTha;JR04rjE1RT}>wC5k2NNw3;u0x)J+h##cAY4G*B|&Qop^s* zPM#j}A>y0xrgf3By3~}$?=lqLYcZj>Bb{gpRuZFM+UmyCCPGeyJMs$q-U5MD_`Myn z8J{BM22xkb$F~%Y6(;strIUoDRiu3n?ekTi-chn;J7b#V)J!0-3a{{h=l1Gwc}LlH zvfn9K$g$wnB6#K=vKh4^WV36hNmx>VFsF}+mir2bU#n87`5PDLmF8)DM{?@8OkK)~NpV7{`nhQbQn;#^Oxt85bvew^x<78Y3_cncZH<&CDZM= zKpyVDTitByH*)lN8M&}y@xd{w%hI97<)rJ{IJHId(-Qt9sN>Z)R(5)oBBffkr1*1( z@7hW{_5V?~8uj77+KADQmDTTaC5?Goid)A-m+o7M)3#gc24l4=gbuxkk@x*uARmHHHTL8E*gA~e7RFjy8GL!AI_|hczHRwp3qP2@^iO@ z#|IUZN5IqTNO$!d@=6#vCcIjdlkW>-)zN|4J#iZA1@eFi>(pmp4GaD(tis0)?$o{G zG#tr?X_N%7`wWShfDXZc_~X{+Zp()(B6-VHzYmRcHaBNN&uRR(=>1!B`WAgsJK zrLdL{M=;U3=QiTrBC>bO)?eEoX=_MI=ckMt=-a{+fKg>#6$Zyd6rWyd-@_xy12Q5 z+|BH&`TJ;-dORFAxzDyr^^bNYxNW#fR>0dtgBfh5r=!pYCL$}gk(UeeDxbG*ybW^O z7vkhq;NTJs4lek!unHd$sK1*WE7vV(q#QNPlFAyElcZVEnnmD`Qv^NK?Cq|(A65|UGD=63+y9|0~2>y1vz}yRO1n31M5Xc9bO<$+jN|r^cD%M!efF;Y_Fo^ zHztFXeBB%=;CLxHvZGkD3cQ3C|0yGSv5PbdmiIToy@eXTkE7)!qaBo6_xlRtz(gD4 za#HqBtY-45zR)Y5!!h#Lo5srP1N zOG-=0mqF#4lpIeJ+*`Ox3L@k$%jYR7-+sb4F!ADMDcSzGMDzU31n5=3C3uE&^HwS{ z`wIkC;W5F}(u2A3$kdIB)Ooe^XK)dDx#PE{96YL?RBR!-8?I~0{X$G|Z^0iYBvcO8 z$x(E}T!nF9qVMZ1#H;@mjpk4=^s1_AzI^&;y0W!pUxC0XJSJEN5ECTdf3GNA>Ss!W z+T@d1@bfwZeqIGFiil~Lime^L$OQKmo)gE+mPh69QA%?qVH}t^F|LT*z5hpZJ0~7` zHQ#uSTy}G-vMQMh1XkfOsZ`0%{&IT8Z6)GanlydDI?^4y&-B3iZ2cpc507Zc7Feg5 z;NHTnt?@JD^$Ra4?gQRB$Jo*nm&m4)BR9Y`l(~ZEen~FJ_zI-oh@S@F}uf@lJVv%t9CkCQc7q zM>;k%W8Xcpp;yOlOp_M|K2;K0S_uSJ;W0s7oEGEd1a*CWzFxTGcsGMMgQwnW@YHkP zkWKcqQ?tJo8%%I-VI}#&iLzgH9X>j`gD?(EOna0~&f4~7EB59=uM($CmQO8G@mi0K z1Olt@m|(rA%P_fR?^e7^g0FOAXbSNG|G|miKiDKMgOmq*uqKwpCb+k-uZhq24j7Jz$!c@m@g^nCoe4T%p>m&l8l`e zkxk&$m=9i!cN(OS-_5<**{j=4aBra|$C-h0>4}bfaK1_y2PVQtrjTbNyx5HJ?a-?( zwcKT=B11mIxVAuG6&@4Rq4!YB17o{$lcl!Oz&`WID)6;@3BHyu{=}0&KAY{Yd%y(u z7T)N0Q2EZuZv2zmLp6?IB41iW8e7h0mz4d`tG!09a_fhtyhER70)bU{OyHH`YAZJ? za^^`t45XDE{7Bsoi7Yr>Pdf54lnhxM#~vL!WP*DORXiT_l&_dL@FTyu8b>hUJ7hkw z=@7?uXB~oG>83c!?ZbNT^an=-0;}+t;Fr^{s~ju!<$b%YQJZ!hO#<|mv2AD0ncRIa zjZ|AFu}J+BCb+lYe(GZ`54qBZudd8h;|L}`TKEx*MoG;1!*S@tw>8rWXhV zR^c(h3eyJd<-eta`Jc(%gmwCOZT_C;qsT(=oJ|JLS-6Y7Y$bOq8p_-G{FHD66Wc>w zNg24fetxfYah>|gK>igpj4NX+1p=%3B)Jk(E2vE47662IqJg}nau`4HDPO{ofuN$G z>J0nAaogYzS7cS!zQW=QeS+SIl#s)afTXS*BB;xh-TI!356y!Z*sfpZp+T zDgAOmB(SQk=UAfk!Ah&~!P>A;lJCY1r_9HvbE1ok^RhSx zjWfS6L%-5VPG7f%dcH6cGQ60;=Lz0YZJp#UWvi(r_($Q-!YVPBn$usB-K7<@Zc+y! zmx>AT47#*)lEddOr-#!!3j|i-%rDIKVGF;I_)ctVtBFW5?^;@tSm~c;Xu&yYFeJTz%v&tUbp> z(aK_C34TQdHGV~TN`#!h{670<_gI0zDskkC2S&*$i51LpPhVjin0VW?lq9q8%5yco zOJ$Ry!ST@yBGiL-D%Fo9=9wAt5a`OHHLjpJuoAh1fj z5(f{9k=28Iq>W`(!gYlSalT~4fEf9u&M(QRgQY-V6`l!$YHw>}WrN>2mA4Ky6y}z2 z8+cX(>KdGhkv)g&GM7IcD2`wP9|g!qU5}Ax!fvSna}5LntLi-1N{$b^RN1k{=jTmE zwEX#XIa_+joZ<*3@Y#eM{g`OEvhgF6%#f1F8#I8X0Xm0h08b*LI$xW?%l;B0?0)bT)lQ)r{clK#Wjepd&+wBNe`_9eH-`IFxbG}^*}e*8j)lEIV3oMrsdnW! z*}JD6pVjXd!TZwiel@%+4XT*0m>^q!tj*ipdq8jm6N9U=$fdFNY)#{HaI6+Tog{Zn z`Khb}CmKv(72a0{=i`o#oRIfcDVhFC*awG+^KNTN26*sHt?}S#UO81RZ2CaC(ngQs z&%!FaOAH(f<+L*Wc!6~21ljb5HBr%zd< ztTFgOa0C+;Yc~^L@OHXh|=VXH*qdoKdAjM=|{jKV?WC zW8oJ?RrL4IXQ`W_nLL6i$K5{zwNRqQj(phW<*)r%an{!HfSK%#pPlmloT2b#pep(u z<2!O2#ITPODl2!hUIVpIVj9~4V=fwLBPz}eYd0r`HJf)!u3Jq{_`*>Y{T}oEoM&TM zWb-UJF1i$`g%UL4&3E@dj%80T`pDN;eG~|)qT`B2vw3?Qdwzedc7*RaAwo|HF%}+> z7ssZ)>si2TFAD@!(e(t4=Flq}*0-yt?(qJW5}nJ?`KLIKYVFjR{kZC`yBIcJm=#fi z&PDmIEu&^^Vo^8U!-R_hK~=MFjDwQUWVy!dEdDJq?B&R2_)EH+Pa7p_p#+_U^Z3=y zcI=w1v+mxGj{-qeKb}p8C;ZG8^NKTHw8_rw)tS|~x|4?F_7MPh@mx6*k! zRRu~=m8*UtnDDb}zEqrDV_CC1Gu>pTo7MlOL@ksMV=|f-?riU)M!Hce>i{LFYD10r z@PVJf<5h76Pq+KttjR!YUBg=MC2FCB7>%+W(~n7mYwM2fZw8d0s?z0);3Ypx$fV*d zq2fn_Snn`Xomn3}pcYDqak%a^hB2S6M!JVm2Z5lfCJQs+=36IuT*aA4O=|nG>h=CA zm%$jQg%V-}^3AK!%y-OZWydoR2&&S3SPAj`Y^N_3XFD|y4P+mK9xFks&4F4dA;w}oqc8vI_MbbnP3sD%>ZO2eNFp3l%ZUOAiDS0Jb=Xuvl3V7*aW-cZd7 zEBO}9j53BP&M9?)S|}l|v1I+5$tvCJrd+S#Ef7?-d+B!Q%g=C&t2o20_vIKiVXlp` ztcN8~3nj$WrKs7lZ2gbQO46zx0zp;t9d^QSeiq%9inHjvtOdn8}mM0SmC83j(Anww#2c#MY?u|^=MiuP%KM%C&l_Gm(w^7m1p(03_8eJvha8W_oRnMq30 zm~{d{RrI&X*X~lo*|4PLio;i}@EfEA^%=R>cYhjl{k}mt(_x)JP!;{g@Ob;GQ1)Zi zKBedILg8CN3F`auHLv8!eD{M+Szf$aAgGFdD|sC5d@#HJ^P&}MjY=NLE`pxI_^TuOX%A+?*OuIe8x1ADnF2ZZdI{UL}zrQI`tEB=#Rdnp) z*@mlzv+wf^bXV>3gfWT|bWX+3CG!}wHFWFa)(K-R zC1@=ZejiDF*!f^foyX_|fuJht8Spx()jfDDyuPkHBt!5SC_$^ZaBt~L4`y?>iOw$| zR3NB|dN{mZxD{i@v+Z?;9a99~hZ3}YjYczNT^Cm4P;1@kHbVu1s;H;NbJhGhvQ-A1 zbk;VJf)7UtTDgZ;##_{ey?y7RtDE5_5L88dRDMEUxIODKp6QIPjsR+*1g&4Bo_x}j zWodfojs(~X1XYP%_=IVVnSC#JUDF00KrNK`n$A~cqSIu@fHFSTe%#TBy?W`coBFb+ zKu{H}!^C4U`{UWWQ;p@N1`ma-YnrDmW?(x7#j`%?#oCaCi9juspc&tMw^LXwYdO4; zwC7EAqy$ybjDMax_$-F~NbDh9pT|yo|$t0_%Ku{IkxxjZd zPMO6ruAAenVZVT8#M10vF&peURs?HfFfqLRpT*Zk~W}9cRYL5Ewv4sm#3nggp;ZdC2NLF8(10Efc1cIvQju^g* zY!t!btdl`6bg{5kh7#hglxMlqSaIF8pg(4#Ku{Ik*~6=Hor`C2X@#!YA&r3M{L}pn z;(mjCPo8tPb(XZgJVV$$KneN``B=;I6Jzw;;o&h$q<@R5&fb^K1! zwNUF`W2AqJs#06dfv@~zInRod<@9IIWc3c_z=z7+kyr(`R zs-zR~e2lD)>ncteI};Gb4i9_^&ljykYM}&uv%FHswu#I-*%ZOCNFb=na#|z=rZ>O| zIch$2z>D#0$qi$?^87MV3nl2AkDj&+_9Si=TIAQ*qwijt6{=rFM0^`e6-H3nggp;hz5M zVD|52OLXgdOdzOA%mY|DBap$57C0jB3Q`LtXz$@3vi(RlBTB+m+dm5gRne>kURSN= zP!`su6Nau3vlA#m`vTAR(eJ}@k9Eg7kHicJsuJ@u8ekt*rFI9b^Sp+TWkCtL!<9#! z$9uBw9=tltFiU};D!Nmb*QXv6!x|mb$1i_N`Iq#6dz9$zD(Z3Y)6y(vvE6A^@!j1G{nL&BL#x0sK>!)!nxDgx=nUiVi$wdLWzMV=7Qx{87AvZ=Y6+# zmr$13)fGPkY!C>l601hU)|tfKq;$t+@q2_C5R~XWW;WDwJqGoEseAROxQ%6l-w(me zg<_ovs-hJuct+!Te|Gu#XdDrIU#Mk430j4L=Y>BW&fIJ!VR-HL0zp;ZAQG;}9D(g^ z)H)NxY=*OLUngUJ_y?pGN{E#yx_iX3JcGyZyZ=$3d*5m|Oo2*GOCYZokFW~6=;l_A zVQ21sfr*C?R}>7E)*hn?ftC4PF{r`6{Kf~x3~=DQmG0$9H>LlGz67Al2MV%eu~kh6Zm?L`xL z8zt65*@@gKc(DAdKu{IU_u@NQodz;ZlQ8r-swdR_phU=t@$l=83C^#j*1!6@z>|%w zmWV$lnF$0{(flHwv+e87PVY^?0N>h-S}3t5b1<0u*21~rYUQu@B@(-i^Krud1_D7< zV&2la1ZS4nejXmMXev~upoCaK`QOPlY-@`&jGWX;AgGE~-r$i5Uf1B9CJiS>w-st~ zP=Z!$R_~)F%ib4*nZMdIT7iPrmY}(DyiQTIw(P-|I9!(@R&<~QZI9RSa&lo^%fsj>hcaogh4w+LtXX za0F}H)>wN^IJDm92)@VK;Q15N;In-_*z4W~kGrXrTQ0Vnj=ckxNrRWpU_bXQk-~%f zW76$pcs@L>;@>xI=fN)jG^zU?FEo#w$BBpWAxdHJGRgSo47Q_&Fb@{$`S=uL-if`EaaybIG8) z3C^g$owxCI=`Xx}{~+ES?!}_*+d#kDhGsA-S&&WO$ol^LNWR z(YewG%=Oixca{&MmWMU#L;9WHuvyv!^e^!@IHL^PBp2b*Q{F-wlt_UaW;L&lT(ZEx3MRq7D{9sZvzh|mqQ(v z%ZV3pd+<9P!?0B&*g{Pecs{Kf&bYN2Qj4EScMqAO)5{!K+~c{l=Tjy0DBQ}46WIrF zz4ioVcN)&9W%Qw+()Kk5IKR?Xpnr*Hc~>n$Q`-}m$VWG7p~T^cDlqJg9zW}C3vVO( z(q*g}qo8N!K>|Tl^r`bTmK9fV`n{vLM{l6;J}7bVv>6=#tU>Fn&Ag4m@1=P5R1qFo z-d`Z7ioP4}?+)|8u&X6_(Re)Dl$b8<+hT&3hUG!q%yfy(tBPCOeQ#ij!4~ROjUE(+vos|*Ngm6ns@3~_lEob(%=g#^ zB4Hah2OqsHMvd&0=*?(>pep+Q`I#0YvoLD^ zDNKv$(C3x$1^1VD2HoErToiH&y|#`L2&$sJhp)s%l1KdxL-Q*# z+U8DX)Iy0U*J9V0DVF&1n)(}@v1lg5t~!o4s*40wJ#Mzb^>igu?3bjr(K~@xCSP+L zrw*UYsD%>wDc!m}Y-5T+t5qWK*Kz4mCk3NcgfMEMgyz6gm+ApLmhHWf6Ze$WUHWb~ zj-8fG76__J-v89)CvPL7qK%L{Gi7IfADR31IO_uKih&{2_;NwrnppTYl^WIS9QBd z#{!ApM^}Cyl%Oi{KGMIgm3Qnsj=KsbF?#Lvo?iYi(B{oCK}$FF>8?C{K~B0XW6NQa z8MRR2xNAFY9`7+`yvJxXhnK&T8wMZ89z_!cf~qo#>u788F)F5Fj9T5=RQce08V4Q? zX1fox)8_M0&G1V;G~Uxr>&-{CUVKzbN%z#w-)f8p&ZxaTD!qyFW+gwJ`(F^F7E1ga znXEm)zhig#cZ}~03v*U>@!v=JyYT`+Ra2)VYn9}xxQ>7AcrVGCrZjI_jPP?T+hV#; z`;&jkqWG6=PV#o`z)~X&^V$ZK=APx}5z3#(CD`TbI7Tg$*qNK6ofTdc``M{&JPP$t zeE4^FbJg(zK~>^ac^uDD4BwyNXQukITRHc&_xVWX$w#u)>(Z?Zkl)C)8n=){WKu{IECw^jK)IlZx*HL`7 zaX8x-Qb~Tz$J&K_tbG#wS-XIboZdD5pelM#d_GwBud;_nK0Y4xVyTr{%2OBA!nHTjz^qeC*$k^= zY35?c)7Ft!aNnnEh3`{)z;8uw@B#FS@?z9NiKjDL$}P>RV)oBWepQjRe<>Hg9m33R zB0*K|SuN$qHw@9qD4P@2Cj3w?JyLL#qbJ+gzLmUgQaSfhazWqNM&A4J7u5W-5k%t7 z;xc7tToHCU>dmNy62D`u<+7WTeY^q zo&0Pb`j<4CNpAYO8vQq*_j9ogO7uSFAb09k7h`!nFTO_qO;6W$Yc9H85(%oJSIDbo zdm8C7Z0BM0qCRY^i-UZoNlQFkH417Bbdax2YmPxTX2I4MR&u6gQ+)d|iMMeu&`|fv zISto&ae`PVkr3n{I}|j<$A0mgIQyouu3p(fJYy>oRCPJTLGE+Q7JGJ^&55fuO?20i zcZVN1V2KGOTIDpDv#jRk}D0EV8WR-F#M5R52^M+|gLqfX}0j@_7`s zP~u8+2U(q8eN7DKZESv8O=nSTkEIv-u^wOTjUv%tmn)0f7;95 zExfVqQ$N`8$zC45r8hd>@Q2&ZR&r}}N2}Iqb^H)-bDi6t<*?*!e?~2o*k5KZ7rOSs z-p->rv7@cIZgX-DjC&{&RMnFcrory0w?-wdl-AT4^cgHI+|r*F8ac@7ob!vLA4LDQ zm)i~YLG4mMsCD1E;{TcJ1WtIdYP#UytJ12VL5x}`@vE(sY*))0x5P~1#Myi!-JSNy zQfRed0zp-cY^^HV=y5}h4(>dvuZxRGmfTE7GHRj3r>|8ih#M`{cRq3Z4<**~ll0Wj zpHT}X?%Ny4Cp6x;{f1igv}yS}$H9s}@De^EQTomE)pg;MsL zi2^}YcGK@ww9)Xq`m5c$EJ=y%rVj@Ed;l69pizTXv3s;0Pra~7U$y#oZ|g-$`KTq* zqN5RvsQOz*fv8qarJPzxnKkJ?i~AAYN@8yuUkUHNw8pOo}^ zsz6W`y(d08f83|+NnR)=uAjoFg%U?|&s4P0?1WnBcGHR?C4R_4X?ODwfuJh!S*;&B zK=DjnCe;a>DMVQ4bBnm$wxW$c6V!U);|5B~2%}067C(#E)cc=>5?wpB)mmQl!s-Po z;oI0mNjJ=td^6Q5eE%b;$}{Ceq54bvuyp|^rZ#;jpKVzgA_v4VYN1584S9tpFL+^_ zI;ouaw0WDHaXC}6GLIJssxn!XSJB4ZqiP#n>qg5%?`KN;XT>vWp+wS>bp`5GJ#kUn z7@A-zA1kN~(FfxhwNPU8p{Fhb&wJtgbd`t-)@ZlZT`v9pBob5=nDo>|ZR2lSmDv0= zOe$@(Tsr$Mo>2=W!f#D*RSDZhDzUYZJwzO-40fC18MRQNjms%l^;xy9cvf$(Er87H znNl}Dk)SF^yHgcyJSkA0)sFRpvFkqrh;^LFXoQYN?hegHNqy&L74JNCNOyGqk|9NQ zoyDl?!{Wh`dhKClDIgNlPqo11?=mFqbY3}&{4Gk%4#Nui*l4w1?f7hncX=-f&50EV zs-pMA>oa7(2mObc(%#N-j9MsRcDhPM8}~-4cW(Ze&*-mZNepwW?^2XI=tH}<5sX?W@p8jqN&Q|ms`y@w^IwNK&6h|+ zAzUD+syiptCk+N_8`URo!ygTnNR}g~F>0a2njQBlh);#;ch}M65UyDAPs;if%BY1B zPmey4)GxJJ#h2RY)N!omzEEnCFj*j|YV4jT6>W@ot$wLH2VOwqRtu$x(nLlrlrS5p z0rfu0W=C^En{o%k6MjgyMh7u!p@ddz2r@w(8IdjRVy zJOJ6b607f*EFEY$LLjJW6a)fm5!wtFX4?znYp~YY?oc%+s%W0QWgH;|_3~@*M zv%$0Z2}1=8i@uJ9wfx_M_VvVC*G2>VOMJ!M+MG?_yA___7Tci2%>+j{737Wu*{TnB zhnch7dn@7hE0LfodWC$%`EJUNSa-qhi~F%bn;fCeh4y$bE)*VQI>LJHQ#%z*go5{V zp%eG1Lo0mhQQNDrBK_9rEB9kmbzq?*JT7*|xL?8lA-39?v0MCXr82ww6cs1V< z^#66iLnBq6`q*_do`-CShBf;O1XT^-&u!gghU*)SuA{fdfQRz=FR$^YRym0tBx7V7Q@5L z*6{3TElk#?fp2L&aOd;gReZk7_b5KounnnO@j$#cqZUe34r>i9>RO@vR2^{=R_U=i z{+lpyuSf{0p{>FFg*Bc$q|R&mzcJStO|J((>iaS}AE5Ic>XGwPN$gB@_sT|t{>ed% zS|~y1KD^>$fkx+R83>-2M+yX0QU97(B=sm)J_av_JHPxHwNS#jje#6&?T*71%;5K7 zf1*@z=sy{}dW;tcs-iwB&naqgS!uH(1Ma^K7JN}k)XKf5ZS=DzuCi6V*R{Eam6yZ9 zpr%)-Ku{I+wfTzTihQMsc{a?NCi>Kr@K4yIo%FCLS~{pPfEi9pm33XB!2Hg1!3(D< z>dEqR0bb8lEUv7CkCBnWY=RQLQj*s1Tu$F%4 z=P$)FYM}&d%q#Re&=co;Rz1rGb%x6IZ}Pl7J6`{sc-vG(y-c37ovhKNd2Yjo{@#qn zkZ5dCj1>LQ`>J&4v=b-4>mx*?C?Uq--djFa4)xoKiHQRRf~vC3D#`I<>)^(VYHn2J z#@7|=5eIPI=)sIyC?Uq-tZN-r>i^!0zZQ)U2&x)tbYI)F*a~}|Rb!UMP4_Ea&yQfq z{gI4XC?Upo&C=E>tF9l!Dw6{Qf~t-z+pEoUx55E0SMxS*?_8>ctd?x^gALJ1nV=Q$G>IxAf} zXfbZ{1c9I`y0XFRGq^NRveqBN#nUG+YM}&Or{Kg*Jszz+j(3A53ItV&D<*dBHHr(* z19-yo0H}o$bR~t)?gA?7@((S+%bGrn#`I{!lSU2s4!5^|lxO-Y@m)$kA)ZJHvA3`G zc%?M6TZx~;2MYvM?bRB{4-;)sw@>{I&e?WXNvWNS6UPo^)Itf`r}++rEyarLwiY*= z`3VG7-AOFfI#;$uzZ~@(tn0=F%F)JK@JoO{qZUfgKCRJ!*Cyr9rX2h+VVpovRbZ>V z+V5+cpy$2}wO{G7lp*2Uu+%<~Q41w#pXR<#uSBI}98ByJ5OQM zLJ7LM$g}huP#%@E73WNwCJ1=zxl^=*?9jc&)=GeD-RhKu}d(-y_ohejhcS%*GZYx8ud$ z!HilcG3m$=X$v0>JSs+m31us=zOn(Qw;wMMRJC;LQ_1E3e&-g6x%e(M4{Pv~@~DLp zW{%IKCVW(Lt{ByP=W4O#%5~TVMhgU0E$(XskN)p_wRHYToK$HuF0>iNsD%;{IYtn} zN9T-+(Ya{Yee^%E3KLC-2?SM%vk7?h9G&GH?7nx9Fq@zR_2>ETT>6dMZPsFLuYLkS zRdgn!(M6TM2n~5 zMl))m1kFz3IYmtm;^OH2I52aRKu{I!F}zCJa2=+sK8!C;4rkOt37W&k<0YOqaiq;| zG<-i;AgD^{F`5w$4>9umK5X=GfH3EzgqYn{*0LNg8SF;WvwZ}Ds_1-|=fhq9jp<$X zV?nx?FcYQ(&2Hp-k^OIKJDyq#Rhz~$>fP7p(d?MLJ+U-64Mb1>@tB*E`TrxRg%XWj zPr0hIiG+&T#3<{bFz&|xKbxQgRneF%-(6GtCPXw}3+MQZg<2@la1Ki9tY}EZtZ2$C zL;N=_7WVL25hbXK#+G>uxuq+Pytx{h^O+a5P{MRfnxxL|pkj9S_0u5y^Li!}@Yx+D zsES5z`P%mDxtMrqC6w_QB(+eY?v}%nI!molF-u+Rv=p;DM?rNyOQi%=(KswWV|`^l zHmRNsQG6y$EtI%W@CMzs`9+07MHPPc?R6(GkR*F zgyk_qP@@LDE20K{Pn4pY*JS9$qXv|qDjFl@KAcB6wi&+|uJOnOwNOHg4z?)Juw~T) z!JS7xC_z;;`pGjn>YK6-8-n5W(Lq9#lM-UgGV-oD^XbmFrt+jZ?~)eM)}0g$X)VtB%>BeOqyvRm)>lRh5W2)el|yy8%jccH{2CGRv@Tq z>bZN`3r)J9L6l0^elAur{6}Kzrh$xFC^4>1sdjmEYy6{CqiT(B?on(kd!h5Ki2^}Y z=hp4f_AYZl%Xl@yaxpJgX;3yApOsHy)Iy18xA$lpv}%okC2Fj%_VP64T&^ctJe?{K zRF%;`Nn5Ab1%0=uGq1{3VwIqjaTq#o8lx6UWX(#_?kaOcQ+_TMKcQl*kMg9y4_d@V z2n1E7__o#d+vbAiZ`G@kZ?sd!IRxRnzz9Yyl&CSktv2|CBTjHpV;OayXcXh7eev%4 z83I97E=pdZW`zr;doJR{nXRfHvh(5AMlYaQi zccws4Rp!B`E>6o_@Sjd?W8dO4+9O*g;5>(DMlF;u*Y zAv|C7v?2SE?TM$i4G;*bqH9R}OMTUtVOxKUKhjrNU7`ftH^aZ8Cu`_JbP8mY^k+0b ziDqxnXgxpwJj__PvC>!2Z^TD6k~KvMI!f@JVdZ}n&&?0P%6X(fP!)~V^C)M|M@5=% ziZP%37`0G>jw>2Xm595_x8X0~S#+R4P!)~VYcy}JomaMwtbu{6f*7?>f{rUZrzrcN zvh?#?m@*(lB*?f#qxF3Lad@k;J-HS>xgW}?h5lVSuJ9F;#KlU3=#Ox|AY34*ibm_X zPo0sd%&%gJCOf7xYM}%jS9sRsfB{PH=U-s)>KOt-RWw@9b2()vrRqZ~jQBQ#Q41yL zxT4X_Dy*c`fN!wp^DKd&DmnwuXo_E7k@uKeqccA*j#?-|#})O=mw|HsdEX)8Sgb%$ z6`dz=54p`1t>Ff199t=tQ41yLxWeOCb8bp~i@(D)gE)bpDmqWlXa?OG2$oB%(c@?g zqZUfgafR>5O}-AJe}98d2SkFZ=sbacOKMiaOZV&G$8R$kwNQeND?FodqYGYb_7xuA zj}{23qVoiv0b%Tm$qTHo>W(NzEtH_+3g1V6VGb^I`wTzgA_Rh}=sbZ(ATt)>mxUJi zvNViQ3nl2d!uQHJZbQqiW$-U^ia<~mohN8C8-osD%&VGcv1l@*7D~`@h39NXU&KQ# zU&D?L!2&^5be_O{>S}i|W_5LZeq|h^7D~`@g^y}MpYfUAQ}`F`FA!8k=Ls6kg0X+l za-#{}-!nqUfS`mp;*<_CX8XN=!Q(oE1cIt)W`ssl)2lkW&A+?rJBc|Hlo0a(9%NS4 zJ<^|wA4m6PG<%q4N>i_&SCzLm&~@`oz!CPoLLM?D#PyH4gFh<6J>oHH$xx9Xxz*I` z=hglj8Y zl%T5|{42UIUorWVgvWLV2?SM9uV15Cn!iSQdwMZ8NDpSzLJ7Lcq0wBMKTjDVrC@CD z5P_g7>h<$_G9ls0VZ&v3KQ)9=3nl0(2j6LNrl-=bd_Jy8nkEobMZJFhO?>X46l~4F zCN``uS@3 zV0YM5e>p}>na-$1AcXY~^EbtCB{UT`SBnq`x)wscetu%eyK>k)BNH3F3S-nl3A)O` zv!h=*;*{tGXr3(+R7JghjpowP?%1PS22Q9ml~D^N=qd-FJNJ*mh2K+f%GpqXpepM1 z^S)a>84IT`#hu?KF>0X%UFG1F3jeOdg6GLNG?$-yM`k8eMZJEF=JNSGtYx|w7bT5n z)Itfm%E4F3vX0}b?sKtg^RWU!Rn+U}S(8QQuzQtsEZ}>|sD%=Am4j!!bb5|{)e`Wm z-w1)AD(dy~2>r$PXgzj5-aR#hQ41x+^^g5q^x20Gb5O5}uRu_hn6Xvwjv?zdQ2{9`yqIC%CIIc|l#j1!ufrU^%byE`oJ(L#e*I znmN#C{1g_jC?CGK?8eQ`i=l^4o@D308jN_|)YB6#OMj|n@)HIY!_S)Zfqn~{x zh*|xqrFeHfhZdg6pxM}7yS!{C*yhcHdKoF&naj7p<7cVhyV6a2byE%}rt}M7wb~oO z;TfN>f15-YwcSJ-Tt^G%%adU1=K)fxc0a6|Jr{!3ua}DL4sxRTBnP(85p}T>7DF!! zU-&jMO+FT1Ce;`h0N3Uv$+NC}l>({-K=Svwa;8#+6CZo`U?1N!)~!DG5FDGv!Vmor zIX2P&+7-s}e8P#czhNb~d?6On-;bB`{2Fm0Kf{OB^03gkcl!mIcjm%@(2=tCg%J$= zmIVFGhsmiIsz78`5*++FNX{N=!-FxRdlA$jq%lj1<=^VOYSt+6uugy!G)Uc za`>}qV0}Inj=1%ZpLVaqiP>AnvFjVJDFw6JqF0*?SaP|UJi4bP82c=T-}7u_6C-PA zwL24jzO#})jdS3{!wwUf#`v&uWu%0C?X%%C2SP5d(03&}wiV`APdZz6soUy9PF`ysHgKvxB17t6_)zd99tZ zGbdJV4r3qpOj8bfj=;*XYr)^~sy1v#GkCgjJ=nNz)s7Es1unhU!_IcOTG!_7Iq~OV z1nZPvSE)K{3i=P&00V|j(OxTS5B8B8;Lp#|T8HNy;BQC{q&DlW#r9n}k#7Fw8E5W<|?jTtXPs4K9SqHfqFcrQc9CAaE-Fy;hFYLW!*rVX*sd zA@sVU#^J_$IWvb3*=RMk5&Ig}AJ$&H3l?Km!?Tv%z&ZB?3`}1K3FErM_Yxg+d%uSh z;TN2lWRr+>PBmp;pLc|228r-ga~{jYq2@X#7&`x_w08U}C* z`x}V#c7{d!jz~?GyoGg}y+-IcUR{0tpx1j?bxScXJ}!ZE|qqE54QR) zFly6OsrbQr`1;-(_8eI+eanBuiTpXflZl2>D8;c!ISAr<(uDL^7^~B`|7d98J@aHAH&gq;a9ALBsn?1VdfOVZ>|^e_JxNCdf~w35+#q)TV)@0; zHk@eEz8P~o$#m89jF7&AT>d^vTo%f4HvfGe-H$b87}!CD?$lF^K9ZtkZ0Qu~cSP!+vGepX|f#>~&9r|weg^FS?>_;SPz%;qkZ2WZv%sC2mz zuf@?*_kB!>ND!5H=LaXWU|k(R_tM5f=!vxVwa9jZJ9eq^m}ctkfk6u$*{O|Ax~D-+ zky@CnX3tJbXrf~w-O_RrCt^+(33@1G;wB?K$a;)Iy07{64x?PnGxI zQ}5$&n^tVyFlSxu*wz9;RpOn$V91UvtfQ-YdKJ>|ho7k%7{7{^qpWlP^DTKY3|Q9o zy1K;USxCP!l<>25gP#*)*~(M#0v+&H)cTUqR= zn;$<~AgGG=X+EAe@6L8undq9E?8n}@3{LJCFaJBc9}G$u%w!?5zRNBc66FoOmJO9{ z!_?9F(b?{7>ULAziI&@uS|~yL0?(&Tb7MbsHFX`PY!==*B~IRA+{c^| z59V)EMfa`I5#c^4(PAxw+~a}rql5$esp3D;so?jx;j4ei5T?4|TkSyJ~3QVS(4 zB?fZnK)HF!QBE8j+lyUzU#<*_xgZc!b=!|Yqxr*Sx7ji$s@(Nr%GS%u@sCf?dOt#y zmLSKQT!8NP5#mPnkPl5h15R^?!pd9+nQx}%L~^_r>uq#X32XZhsf7}K%MeU@_LBdV zmvCaVhZnPddRwW|=Dt8sRpB3mV+9^^%_GH}_}bEk?VPk%S$F3<`t(N7Y<7@ik6(xV z0SMjywU(0_UxUR?LqKz-rrgf|G$+Pc_^@iV4k$mJzah0y!af*bK;5=7J9L#3%Vzqp z;@#_%rOou&)p7ujRW@?|zB^E_Hp2RX#`1dO+rSnMhOnoVW$E2{PFxQ4VNQoPC_Q`Y zF>0YiPa6aa8(X=0w(409Oz~m6Kdw-Qo;DELpmf0*0PFr1a(azYPONCskD0AcR|1o7c&4BZZML6Ja`C{=Jyfe!$vKir)+v!g;5J7EY<ea-PC~o&bOM|Iu#z@EAf@ z^#;p@pR{AEsb2WBC0=aE>2XSKpBe%|RXMLDIOly|`^Wt`C#H<`WX^Bx6gx*N7T#Ba zi0OIS)%#w<@l**`S}0oEy04(e!d@`y&_S(!*T*r`Z)432y72U$sBH{S{Jpt=(g|(9IR(@VeR{^D@{n)fZa+an_DMsJ_7|rXK9{nx*oLY#6PpxIc z==DvPs8qLVXy;yyd8uD z5gQ9;5B~r;xqac-v1Hd4E>CzH-){6|riO=HA4fD{)Iy0lbGkrs{=ou|p&vLA*{L_1 zwqs#oaY{phpepgsbF}Vk>>#FXK7^l{LV5`$Ht;rreGe6Ms%Rsq)SW$jG(&sSUL>fB zK6Q&*W;@{xQsQ~MGyL1NS<(f*<5y+i)0Iu`dKU_piv(5C zs0gpcYURfETyB7!W;bOt_CjMa^lEus&Y_IWpJa)~ckP7xphQ@i6F6JklXlclzYN!Q zG1lmZ8CK&_9QwDYibi*MG%69<*EmvG+48=Q`0$!YP!)|*@jAk0z+O%rh_79nvI*^a1H0u7HTquzr~aLx zv^l`Js*nB?@hS?GSmr4o96Q%exDQIK-QO839UNfCef8_}{h-9ERqBmbvqgfcXtYhE zk#2Tj3qvEZ%XwQyBXl%!N3T|+@z!)<`xk`cjmmbyeNe(;KqoMPP0hNKnk0zp;usq=ny#EA{C zPQflbl1eRJJ(7L%D%R12> z>fJ5?D@g`@lMdiEVIQpCPz3b;c$Cwl6U(v8!0;#Hol`=4yaQO8uZQK|)!9UF&CaYz zl_gkzzerFOeQvxb_HEBv++Tyiyk2;|;T+YMgZ+JotO87hA({7=;Rw|58T zaAyscoo&i!JetO->0jb&6EoVgYFpP~x9(yal(_S`E3CZm0={IgA>fFj{a9=6I@+iILrUv9h4~IN94=AgIb< z-azoOJO#?_jhuM8qbFM%be*R&7bw>gc}LJ7;rc(CPlKa+>6SJg3NEQ_}qfN_48 z1%j&R)oL`KyG>#9!3i(|^Y>f+AEfol=YW^z~Ubjeq`&MeEtQ0w&jr`gIQ}bhRO@l@7 z`{W?7DCgg%lj-2IE*wf4CPHF-I>fJ^43>H7RaqUG&MF7C#J6uEkyb_&0VCT(ygV zKW0lHNge`v#W6symiwZq5ll*Ifxj{*3HL#XQ)!DJHf0?2s5_gt5!xVv?Rn7xFZB%* z2&$s@#Pj;@PG`ga+2Xtt(E{=J_F}kk2jP9%JfK(0tJb}m&PtN%W8-?U!hKMpWam;C z{;fHzAFlQ*yXz6mDY`M*AD$!-RCNHCLB_5g@HIb*6MmKvY~=3R*l}MxQVS)@c&!Uh zG>52Od?i~`?MDRrCfCE8T|xwcs^+%Igoh_Pz!lqYPCPJ*WE1<;!tyoKa9Z|qcvDa= zUBkKX*fR?b-)IC?%tJvW9>+$q&Gz@9VY^t|`*IB|$~-C+z2FhJ+%=$YS0WuP83olN zR>6pWXQg!|A-s*&!I7-ply`8T>MW!dN_gb0f*~)Dk_9~a0xiws1cIs} zd#r%;cIDEBnh~5RcHyVKIrB=n(Gf^3l;C^d!MLLlENLIaiHV&fnOCtXc1R5q2&%G} zx&mAlRf8qZgE=vxT@;JTUj|=p#^b4u>!IO~`BLcgL7=I%9`YR0rLT_$!GyQ#poM^dMB-OfQXeb^&B5?yIS{#ch*TcjAIxj6gNucBl4-zL81X3w z#;$ED`TXCZ-<+eiKu zRjvA!13UXPk+$7b+jzB;U)9x`Qj<{$NG+6TVVVokYXV*OU2^9{lz$Z4_4I}|$z~3k zHp+#=c~-6oi9MmdybfBTUYGB!{9s%2Tv)p0bC+!Wo}75}mp@(BLVogbE>a66@($;~ z=KR5hr}=6!-}{;!#f}?$$bLiO1%j#^XXe7z7>~l3Y{rS$2~n(8`eJ$dqZp(XO5_d6 zg`U#6!g`G*P85%fWNXJ%QD(0VLzb^%Hx~FK z&8(<>cs<sYlYo5ErPWHF0#3|Iaow5f!LSrlErOPZh0@Ol@F3K!eygpRUH!|Rac_gsO4IFgCw_Ozos_K?9 z1?Cz@$t?yq*|k@2LmDH)A@~u)idI=x~xhtIEsy$v{0G zfPuF@qZUdO?@fT(en#+5cYqVad0n5^e}2Hju~h_us*-z!fudg-jE^1X#O*CZ*`E5Q z`0|VaqZUd;^HbkWU1$Q;I`8L1Dz7%QGN%p>N~0Yikyjklvp|?rrmjKG{pHJwySK#`jg19@s_Ik^g&Vx6W9TwvTx7|6Wy{4~84|X+J+$3u}VXq0`p|TDwqn=GCesfL&?qbEI4Uk4UrsXjWiW z`W(23Z@Xw)9^u4+-lN(1ZDrbTW4yX^d#(ano;LTouw3nd!ZM}g^=(b|m;$2g%sWi#aag zRf~fOkgy?Md#tw@lo^q)kyt>hq5sH6H*H$?j?r8g_kAThey3ar*^9cOn3ZL0Dv zd=m;5LPVFOLdo%8+L#(@MY%8cg87KEM0vVol|WFH3m=^iF8H7gdpeyH`kjMVi%sj4 zpEa|PS|~BfCLJmVnaZ|1VmPt+LlAqjZlhBFO`1SZmF%_*u3fGq2V0HegwAk0^JukC znX`5tQVS)P`7eY%2kOW_o~bjIhehMrr)q~3lU6eYf~u_NXMp#>>hjFiJvcFJ`8Za0 z=t<=c3q@+7gnsHGxb~rmoL$3{6OBd(vc2z$l^1h|3ItV&*|?p4jbWZe*Og1Vy^vZc zA$l@h^vAMXpF4_lrL#a#70m?Zv!e9TY}LuN#n6@;R?vYGkepe5j8! zTbbr0iD-tWkaH zYv#k)_s2h#Ep_`MwNT=5)dleILnk@qVP8&oW)5Z7w|-L^Ee#Y1s&Z;L2l7{-+{k?z zCw{FN!6bO4$YJ3~EtKf?Ck4{~wv?mSPvpc3=Mn7H%%@6ftt5e;RkyAY74c<Q>5UHFQ1Zy9fkTHEB5u7Mvd@Z|F6Gw{iJ=e`a4=Ri_u-8>xj7 zv`=d^6XNNHG; zaUsp*eN%IJ8-q5DWMkLplzMG;A+=C~_Gyjgen);r%2OZZ?MV|xb9~Ns8U!m>Uej*a zc^$r89{`O@R%jnBzsuX`$?FFPzHhE{u`*@ULW#6gfB66Sdh58VnzsFWD=3PJg-Y5A z2Hmh{4TuU#8Q5ZCp(3c*s3-~+ih!bsVqG@a0ejZi-F=DO-JS33=e?inK4w3^i~sn1 zj^oR$S$oyYoaZ^&jmPMA+_)@=vZ7kH`|X!(ZBAv0K-Yn5QKa0{A4Ps#ALF&YS4Z0A z+y<6fY(`N*!eiNBVx&$kvfFt<5TkZ?pm%OJVgW`~B?4U&a|e=Lsr~%EU)Qh1HE0+~ zE36CFr3F-`s31{1D2|Ni{o1el+|z=1>fM3<`K>|mwBBQE9TiV3O zPU$Kl&yYY@&t6fa`}jtr+V(S|jg%Robk=NFrMO3RiV6}qdKFL6Bf+$NCRJ?WYDomT z8lUMw5}E~)UDfof$RC@AQ1_5voO$nm!x<)GF`qz>Obj|M3os3`7 zhxB-)pP6WF(UuM<=&rQtSe>GRggmaj;M$tT?v7C|nADO8bS=Hrg`{_$M~a*2L>s}g zdeA4=cWQm-8&MoPRgN1^rgin!mTP*1;CM%T`+Vz0cT`O;YNM2;s34(k7)f4?J>tDO zQ-7}BEbC5>ymnxd4jD@Xx^TQBs`b?9M*HP2V&{65rKlh=W=RbBHqt|PTEyIn5zDM@ zbV$>;tYfB;M4$`DJK~!`JlnhUwoyq9V~PqA89sfMjWyr9Qnw?4s?(TX z3KHm&$5H+2bfwcx`>Cs{epgUIV&vU^O-QHsT2y&mOWPLB|nA)Sv3kCC)Fv3{Q zT?&kdp!@O;syEL)R8TdyYdAep zeE96Qpy_@ip@+KW=;G7`J32a@dF4OvgiouUon zj-6=Gvt6qH-`6DqUGh==5jBcSHO*IRf4``pf<$Ri-+ix5b++wpzGx%dzB|2SxmDIhh_dalqAa0E7N4aaf z+Q;auM4(HaVTmQ3=#EB1)yj88^*Xq!F(z5Q5+^l{q$vS2)XOV>DX1WUvDISDt6e0m zv2KC7`_yNNKo>@s>#KOQqrdyEQ0pD}A;q2}A;*PBcMPLr*KbzUem^AwT^RQ+YGyv^ zL+jk_t~M#WA$I2e@2nHfgy2~hyVup|MbnactKI*8D4ks-@NU*uTNrR@`mKo{NxVzuvDCwk3pk@|P_ z*V5IFg#3GyZWT#S4F5~rbmgf;pbMWdVh-SW1pW1PtGa&UTj^PXgq%IF>{uwhE0ToT z&6f#uVb-Rol>WFEt@vyn$q12W2XTfT-(8}XcWMthdCEePGpMxmRzm{6oJ9Q9wr;d) zQ3#oBSym#@g>N{G#>=q_bst}c^zCR$Q9%N~0L7Q(nJzRoHOKG#&hiq0E_}m@neDL7 zwDFIkbn^R+Xb^mQuZ)l4McT0!J1i_G4m4Y7^T_y>C-SBG83T zA~DM;cDb<{IzkN_Am>dWfny)B|Hs&H+I0J5H8i}ulxcx3%<>RxEN4P!%}R-?eM}`O z{{sokx)8I@PHpJoXF2STr7gvnf6P6=90BorOm0gP*X>~TrLCpx0VFWuUu0Cx3Z5DH!(*yT1iIw2yY@~5 zT^xCVJrE-=RFJ^2sF-he52stlPi2RS<+F<}jQAJdqKhJEt!}0)a6t_z7XS$yi;7$_ zE}n^vrxw-OWGNBolH=PS{|=+ouIFpNJ**|gwHx z^$MZAKPHn0*;Z22JrXz;6>aPdqC2N=A%AbGEfMIFBjP*!45sTkULsq&*hmraNZ?ph z-EB?BTo8N0_q3Iw)seuFrHGAM6G)?cZIp6D>q-Q= z zb0lyqDxM6J{b}}uc8YCsU5P-K9J77Rq6MvN+D&Xf#n5Lg?*k57Y_#qJjz%m`f_g&O<`!6#h(Y_42qxpbK+*#UAT+!6H)j zyIL>)sFeGPgq&qsI-wOk-OPwz3^^bX=)z20(ME57>b$2hU#YuJFhT@t%gE6pWgE7j zT^ly!F}>dsRFJ^=Yq49wjsV*CuLeAEZbbzNbor&ml6@=U*|zg7#E7Lzsn&Gu99!OV zn6-im5;%V?=69Eho-eiG#{*p?0$rW@4kxRUV_4DcKBA37C)&{ZKWp&B{r(CnNZ|an z$l%%1hDJ0p=k7ndNCdiaEW~cw-bwOUYaQp z=$ha&guI#*%o@7oh&F1kj-(-bUaLp%=P0Nkf%Dg5jec$qQ%BkzMGtzpkiL8gErlK?3KmMYV-fF4Ux&7q9bWCBceG7+ED(Pl`S2LFo%u zzG!IyK?MnnvJ$o1KDvoGOLxBfTPe&E7!A^2z1Rq*^9V$n!twlA1KdIQzu@UU&&mmpn?S6HyTZckZ@|g=7;JaVkVG47aQ1}q#O%oe_hhoXE-8O$>Msw zP(5?EDySfV_l-sqHn%>_v~I-*tWT0E0%4^wtg0jG6xFe#Jt_ro)3XbuszXTNeIr)G zD>b2W-ir!m4%;OHU0BOT{2o@0wBHLKzT8Q!a)Sik1!6{clmq>G)`wel{~%SlK^In| z5i`OWuJp2}J70LXoPr7xc;AS~nz63b(c6t12iKMebYTq`QL|>A7rj!}ft%;ZwO)|G z`$j}y-|?cKDmUXay|q*w23>MBl2WI&^lZz9Ji4HZR9gfIyl=$0iYByLKs`RR=17S^ zmt0lll5q=~{?L-IIFuySNRbG*Z#0@oyIasz2Ws&6rVAtj?=HC-N#&=l>9t3dc)^)$ zskR6bco&Ejlf)ouwYVG)ixB&5K`kwG$zMxG4MV7RR}CMNvsL=`K?3g^G2_)gj20)o zQY}00mk4y>x1ETf8_=G{jK8CPzs;p@I3(nIFsNK4wR&_`eR1fhM4$_2pvBDgyUujq zrITu4kgA}9g!~@t;oXfsDkxMBb~`K)=)xIjjV8yWCp}rbOKmE4MnnY(c}=+E&nP;< z;V(5b?tny~3umCk_tm;SG;Cd-8n=9($nX2_oHr73%*45fe)R0PbhTG`RU*)ZbJiNo zH8p{rYJ8SFzBfb4&9FSYlz3R=X?Hc6V31=HQItSGZ^fFMv!>;Y#I4HFiyMj z)Clq14X87QdUgGaRL+^1C{^YRLEGg3h3CxHP`L$ce&|_~C$jrzY z5`iu$FGSO@%vkz8DVVIPoGj&kAb~j>V)xU~vGnh~)5&dDIb#G}Qnrew@3R4PqDgC3 z?!q1A=Zj>L8nLuUIlGf2K2IgzI-d4?S|*<;BT`6>N9X-+SJ^JkRm+ZpsEg4&-PiiX z3MxokzCN2=sOO>G_Hd&h$e)4qNUIrI-&r>$0$r)CXAzt4Y1$s)`smM*LkH8Nc21;h z@)ZRYBqr6KOZIQwsU3T6tsstj52g#YE+A)PFG~cv7EPW_x{Z9Q^}76*Aoh)qqsD_q z5NG2pN@bHw^0W3Tt!2lBQngU_JDu3gjMsi`uaEa>(|-ibs2ESqKijULg7rnQ?x?7$ z5*SPCZ8ajdQVS&lU2+Z6SzTgj!jv+8p~Zy?Dp>Ut+ZK@nV@A*uW~y(f$u6l4Bxat@ zAd5a$*IJlniGFOF7)P%M|Is$SAa;?29-<4+h**`$ilN&B$FLEbPb!*0v&o#dM~nK; zSx>Mo>(AJ^WLl@?emx!5>3@%hLup|4U7h8iqY5fWVE;s}<$6048WY3-L5`nIe+%(dHSduF(_1Ut2EgDGk z51e5mqpnN$AXcQsvo5|%rVOU#tUs`Olg>!L2NH7K+MZKlXxZw=SX%325`ixKZN%!* z{-HE})k$V&dO)hbi^O=5bu&NoW>MpH`VnNy`ormf0n^y}`l>{r3$IEMJ4j=xYu0pD ze&}8W6(lY_Tu46OIA3@;M}O_c4j)0MfBdR@HgBgypbM{Kjb=mp1nPFypET;eK*2YF zOKd)gyr(xVlU`_CUIV3KG+{<&t(uOZ?X54HrkX>w(B*eWGf= ze3>T^=)$MAsNA9%LtEvaD!RX6o`MPzn2Dy*T*@9pYxg-)Xq`AqBG85TaUu-fdMwSV zpQc+fX@-Id5|}F|#yCY|>8wW;biIC0l?Zgnd3PI5jiwGXPB$ShOTqK=;6x7T{lm9# z$F;Ep`y_Jp)zLI_Bw@)xnF=aM3}Lxs{rJ41Q|$+dvzr~0Knw3SW8qc{Bm!O7CvmRC zFIehHHXHGKu7U~@a)w)m)fn1yUK-O3N|gw7Vb-457a(a29pbu&jp;H?K?MoSs1xIl zmSgGuOY2$JUK1q(U2-1s#9H+>12yK=C0voc+r-C7q%Q`^lhq|fgRi9i?rvZC&X-)Nfj&0pKS!xHH? zN22?MB_yiJ6u;4~`Zo488%^Ck7U|;V$ppIa_ZQWsqeju5zj`pEvC9-xka*gC2}xOd zw8*bil4#@VmQi$nOcq-jlPwYG!rx!i@uH*Xw!)+A(%QueDoA*_=aA$*b~>w}aiWb8 zE~Dw8PZ!z3s09*%F8uvPWaidUwB`HK>ejhw3MxoAX>!TK=xE)bn)-Z$^4mvKOXG6t zG4GiYfiBGR6ssAvM$>J->#3yQbSa+`2|07pvs3~d{Hvil`1}}&Ko{1=7WoE$ji#F{ zywz(LVx_9tNMNR>*pcn{P`aXDzPe*hI6N|&x@Q2pC8e;94NXuVoJ zv894_!I8kK;3BJW#xNRja;+Ls&`u)IHSte2@#*zhXYZ$ov)iJHsOS)wtu{E(LqP=z zxx)D5)5GcaAq&+}@8cu_UA2}iCjHOf)!p;xEZUgqJc9ZyN><0H6BJaC2#L)heinOl zwF32#{hdfG?Yc8bt*lLv2z0sHEF#AK$8^>v`Ztb4+z8rypn^p0`q|`> z`D9&g!gxXa%#EcR3;k67c7;TstN*iwJ_-MngZ^!=DHf;RiRt{P~)NhE}_MW)`&cuHNTsxcFKDX1WUIm#N1^U!$e zS7oGneA@_#Ko_2Ak()7gB%N*EMXlIloPr7xc&}(Q)?%mh2QeK~lM^!}0$q5fHJYHv zk#y@AFSUj;OF;z*yyr!7P4{@Z(a}X6@hn{;(1mAOJWH%b(#NZ7s+;>{DySfV&n{6N z#y+0bajvYMY`#n)&?WzZmrjbayZ<>e%ga?zK?0w_Vm@&}JRN(Avk@7qBm!MdiHpg- z=S7A0&ZUa0qWy^Zp!(Kv%}>#U!K73hn62DWZ+kPNV7B zf)vvJXQqM*68LTxH3wox)8}jUlD{?S5`iwP?jfF67UFG?d6zgHN|owL~i)j z1Uhnl8Kvp5$r6DstQsO#e&`t5tW{N|R>%ki6(r;e8v~~fq>%$psm5zP6x?G1cap$7 zHj#y$KA5&G;OeIqij=R01in{9-H(L9qJV9Yno%J_BG85Tcp_InE{4uG&sQCcdq{bA zNZ@-#MDL^wp|>AxQj>${hS8L#q3VIBYo)wYB=Ef=R$oIB zXrtTZ71LHp3Rbhhx;XOvair{M8YfozPIg=%UF}Fj&Cep97fxv(gy`RDW`B>O+F?7$ zx1cPEKo{Q4VqLBJC~Dz6k=#nomF`+3CcVred3><8!6=CB%%d*9h9>@Hcip zbd&TpKw^FCbYi-ug|6$H4AI8xDY5j`otkQHwT%*iF8M0atQ|&wRc@@_KP>i`g)bH) zm(CrrEl>7C|QB;tS zD}@yQ3ZfbQ)0Jbpt4ajA_PyvtlAdfJla2MYETX>!(n?)sE2fibP*jk>ig_B1YC`CX zZt03+wv9xf3o96k+@)n&`qC{^`4wv;)iy*zuD*BfwI5wQEK4c=C==+y-F(D%yZIpM zAC<#KJ&=$naY>RykxGRf`mLt|9u4-TTQi)@w0n@&mu zx?F$GAcGpUAfLnaIVLT;#Lz+g8Y}i0Vq+{&kiZ&*A{W4B5dE{Fxx%wgN(8!$*CmtD z_j-_xq5_!66E=#WZBMxm_5h;g)V$PYBXIuV`zm>0m{de-BNW*Byj&Qjpp{^ zA+*lvmdg59dnE#0SW8pn33nYr7kp``hU`Be)vUqy2hP@u6|4zE>9BH^s^^}43Mxq8 z8%|{8dJUsCYkx79hlLV>E}X3wSE6k!-K~4TRypoaP(cFU)MBk@XDoeja~rcrmkD&? z{Juuh-&5=y*(!+*u8^;wf&_kXh|2W?5xo zAc0>_qVD;yc)Id*DKaK`gG8W9URU#OHpY zJ4-Z=8TQ`ekz! zMI+ik0$uog6!W`PN74=xZ4}R%844;$$Q4OLZj7J@O4n9aXXHr)y72iZ=C6LlQ}Ws=Y!Y(1p)O5g}A%ByC!=xnjO0O+f_-xfbh7>yb3J zw1aZON+!@H*OXnC)RiV2GU5ZBswlW?Bv#_XdMP6E%&i9Hf4ZzLQ^#h_RZu|!s~m}Wxcq+fue3dC*xU7(mOE&rsvG zY*J7`0_#+X%G~Fosbl*&YGLYbi9nYeh4jdEApH~cEZAqgrO=0N)w8yDI z>bS5Y5`iwvJ{8X^i-Gi3gAlb$o#RqoDiTmoV2q&m{s~STRr3<*Xk~FMM!h7OkF0mGO|k=p=Dn?dwmYL$4JX-+Lwz z=)yXFVvfvt09_lJuT8l2K&tSE1V$%mG+T4~(^RUEFxzJmfiA3OC%&)R4WMhF z^ktl;xMJsw08<~K^2D{OM)j7)cF7j?3 zNZ=kCV%?yo8GqBF16S{sRT?ve?b$Y;b#QG>d{-#!@Xs{H!`l(#?UbEdmBwm#w-aOM zF5jB*$K#hO-<%!jvmiJ2>Dy*fd;B4?WWO6Lu98Q-i9M6ukGQa%L-NSMi~61ZEGqc$ zl}V|@$K07N?cl@SIcv4H^WTuzR3Fx9eNFA}>u<>W9$u`oT`ld;KW_yQIf?Qq3#zLw zVrQU&`da4GYN_sF!3)x=xt8sjk*k|L<^|!md>B2qTsL*IewVR5H?_RtfpXlh(Ru5(W|r>-gp7mpfzO=JYGK0AeMI_S?FJr=U$ zVl#47{N2HOA$v2`j6|6DvzC(tmXR!1QF9dNbry8F;qdi|+l}ZG<#J#&gJ z?5r%>_#IG#Z*3F754xpF1iJ8d67h*N0Zpn?$n<;ozBaybrpLKOjW1r&mSNr!CwRu=vYyP=w8HqqwkszA* zrm+{+dZO9nrhM9LPhKawk5X@-Kf88x25Z=SF1b9ypZz#Hlg$yk5yw@g?AYiO_HvJY z6}jq%Cj4DTFWz`tPX!euTEzLYeK%&Z9%BDuQ3;`HBi^jH!YBQ5S3b=2XUAI3Vq>mP zA@8#M*?Y|#=5aNS;29BXEMFUNn_ZOu@^h5V6%thz`Lh|ub6ER5aiWct?Hcff6aD$8 z=%x~ZEG*RPVIcxe5ZQFaphyKFWI3iM|VLDN`Zmqo;Plfp(dp2o8C z^?TQlhYoz-L}z~J=2Qh0B=8)H_^StQ{QJ*_d{g97#r+Fqbu?qx+eYh1p`|}tKVuR* z?wUs)k5m}{k;s}&((hS3@|-JAu5ZVGS6rl^g2W#yf98B>67zVc&%v7S-;4);a^z3e zWJv_N@My()t*Hy2UZxq(%$qCq1BofV{w#lZ5^Fp{-}5i`#U9nQ9QYAWvA+|X6LjG@ z6st?+oOt5)hTOdKR^{AB!h*iVvNM|t$o3CnGq|n^Y{8jz#MDz^A0CfkYwXsGHr(<& zc#pKY{9@V~1r;R1K2i2(bpo?V)vwCjn&ZJM?XS!GHI@l<;aL}TYg_y9x_LEuyWG7> zYA$6?n+LGj6Lygm`zgEqV<^jx-%9Xk#V;7=%~Nh!@E8$WiwY74j#0L_?QmA0Ef7al zD#VLB9Jl5*910`?UDzj)A2r99KYdV@-y3yM>0LnBRNH|p+GG#uv52x|eWO{+X}bv? ztyuH2bmtR)RO5DWR~39u;QIsrlYTtt#}|5;alhlor8bZ#KaaB6JNvN(*Y}8iG`s4{ zcWJ8fnLiFm1iJ7DMZJs!!oA|l^2HX{q_-L#;RZ*_#yNFh3y$gQYt`x5s@I`Sv zs%0nZw`SS&6#4mD5xWuwu?8QG6QspFTs_L0B!5?pjz3mVLE^DFWsmoUG5cxy8g!|D zDg0TpKWYQ|KqAm3AJv}${yca86V+(@C#Ca7g*6}V$G#VyCDkq}Vhy(i`@ZlL!K2k^ zicI`@tG+MQ3o-AdejpKhTVW@Mv}F56=_|?^U81~)(Hr&hgtrobF6@)2z`rwqySzW7 z9^GL=ANwjy8D-DbY`#jq2PrIIOH+2^_!Z(|u4N09=8PV?D%!Bm4&VjW$5gLfWhp91 zyzZm07cU)|OHF-^#?yVgxoNXv^}>M)5`nJsBebmldLOpcTVKy|MnnKtYhG5B8l@>J zNGzGHFwZictf#-8u&W-xM=ZXsUQE|W1iI=iQdmcgH+$CUydbJw58zj}ado_Ld8y~v zr{~oaHgjV=cKo-#F6Z+#-n@A45!J`NIzGh^l^Q)(BQWL+`iv-b#g={ zi9nafC&D`C*|4U2^}7k~cpShZ&Mi@w4>G4?(+E4+rUJ8neuo@hPFQ4lGZtcdhy3p0 z$M$us%o2U?3gW$Jqx_;=RVS)CqJqSU{bCR9Bh}f_c>Qk8=X1Szo6`mA!E#m-fi65k zkqua(1;4m>qxx-bWr_+C+J}U-;FhezPJPcG{SM&G^72)6pqWIVOYZp}(eoDHv(&i0 zHKd+npB4=jXCbr<^B8hZwBgplo6q`ti8`!7U5W}4OMd#Y;l>))qW(icJk1Z_=4z^1 z>x_j&pv$5aVds1Q(tWA?KoHfZ1@KYRrl>bQSW#4vc=A%q?t9+REpPQ$5b=dx+_!C# zy1IU2iV707m-(_WA$N5~)1L^Uw^aZS4(hLVX*9Mn7lci+Kfhxd zpoVO#ClTmsHCM}A>#4fY4W9`jwYeuBb=X1mNp+++`oU2V(xQTLWq)3Ik%PKsNdt-s z5<{kH+3l)@y1dEyHo`mk^VDfRYL3{m7zuRAM|C9Loxgr~fT>^HXsIba>~oumx<8X& zlR@=-*tH4Xx-PfgkjlfvUHi#XH-7nR(Z*3fg&$pUnCWIUp{S%6_%XlX19U?Uy(0LZ zG@4(t75>@k2BXL9r8ba=I_<~adX3k`DX&Bu(d|6={h+d{Tc(RdpbO8T*nP-`@_FTq z)rppN(%D7g#veb{DlAR6tDSz#*{cubZk}dpBU(gumIC$dXnyqxKd2 z*!js%i<)M>5jVCU8#dia_oMzB>AZ=x?XiSkpEsNR4sJ&Aj3QB~r60Q=W33CX`$im9 zo27*F{u%6qu}q)~&$`HPTcza-tJPx*jy9K$YV=`m7Cq;AQP}ynWbYMU_U760qMw?# zqK$43T=_^}V;29`lcIve#KGR|*VLe*fZp!}v8s}mXOGCy8Lx7X2y|WE;LA+CS``J@ z>)SB-?!xO>hVT1b+MAxKH{*Kh@)A{yTs1`H&AY z553{Hz3E$nxs0CNhyU5po|tcOqBzTe#FSzm)_uZ0zu*6JRMqc0^Xhl%kq#%kB?4V| zM#K{?%a^C-?a;P&c9PB&5<`Q1*_ZC~eE*8p_q=^YKYlpRS$p=NqeP$!&zqP}-000e zm@XrwedJjj?9<_LKCEzeoOaMf{e8Y|uoM4~vWIl7;6qVC;?WjQc6{DE?V=9)Yq$AB zFFt(kIWpJHSt8K2@T@l*W;Rc|f#}<)Z{^6l*p*eBH+WMsBTwdh;jGqf&r6cm(VOM* zecEBOUlOFnzLo)AJkICY9Vrii!Bs=UWai8wRrdt}3#}}UxkM15US!Y6m!u8MHZw);7m-&uL zoirzk3KC~md9m!p-?g8I>WT3;oAcq%nksRk<_i+&!ZRY)Yu|YAy{#;j2H%{dbA?2E zTW@w`@fmFt)9<%EH^Gx1YG$T9GIEv(bm4i^XewvA^J_zVl-_Z2&+!OzK6$c9(Y7RD z!6VVelai-PfxZxE`TJBy-S=e+}R0>ATl*w|JAo| zyen5D2Ph}II8s!QunY5K+NOjws-gc{TGX#8zn3sjacJf#5$M7r6cLTojc@DTNwK-$ zNKru|>3}Cov9}|O{Pq1%T<{jydyl&n7GV{&tWEbk&~Z!7ff2 zK#Jz++h{Z1nNPWuq`ckjKv6;BPX!P5t!N@?ouVHV1?uehnqRY&tsC7bDoA{K>dMAO zP9wGMUlGLHWGCJ;ELFKW(m^87WqaS9IhUD6BFpNDdl}97IJa!2iG>5j+3ZsH+*r(# zWu!3vq`}N~`HRhYO6A2$4J!wVbKXciGjV61#hefI(pUNK+pQ7LTDVv#*T`KW(1k}R z_M;!?$UhI7rzn#gC@M%KopWdNZ%rp*J@n(jZEj9{XVNUCeyU8MOYZrQq$Ygg$kodI z1rD^yc4yZ77bCY%>qxV$u58LGM#}vxB5@~NS?J9|66(i98}BTv_^ptw%AI&`iFkR- zk-0tlNN!rMCUq`4v0lSJlHK1|38JB>GUe1~jk0x@1I7P~?LCflWd~0mCJBf33Zl)3 z27Jz}4a(y?E)*3c+;9ej_1&OiF4(!LlPo#0@)uN4Z4Vv=vi&iSt`iWd@ zxEgR3NIq8yr|R=>TURT$FStoZg#_L=qSj=3H6HSCi_);X+z)i&?DmU@N+#vK2?#zb0nMv%f zT_$*^i5bXhW;{1OPdVPIm2?jxkyyi-RgTXg**W_A{Bq+OyfIy=3^_|B0$q57Vl*+W zBL8E$QF+j(rSxP#qD)z5cDPbXBf1qplxiD=#EfMIlO%;2k z_8dZbE!4k1CbzH3uV+kGuK5Jhs&1~V_(&_VX6ik1uc<5ZnGi%?dfhX4JAV)>aaV(9 zDC)H!>0OJ2<7XFkdt?W(Tjm|n#?4BWyvmmu%4<>mRC<$v3y)CDq;9CfLx#>%`j!cz zsNny7mF2=FP8vumR=O$LaI~qyPoyqTM%`>J5$KY8KI>vtetgyx<;r-u=XiuG^ITbm zr4y-pMgIk`$;XQKofxOw4GyHJAc5Z!VqI-&HJ+plSBm?#kqC5sI_SzO|FI*UclF;_ zD;=uyn|(u-dG$l+hOTbxs&9Fsz59$P;cjeFuL`8Y(q{%=uOF*e^YL!&l~T7_O5dVL zV0#+PxFyy2bxj|od5gBvw+|8xueh=UehtaC;rcn5s-3FwoZCZ`+xy!{1iIvY9Ib55 z*AzEYx)+7gH9y^0Mz6ElN%619r0;I5Rp2@8ph2&Q{Du7YgX(rCW{^ zl+w=>t!z@Aw{ZIy6|@rS-(xqdGK^=#mzQM>N)ndTW@!kIc}}CBGr$)_Mf%k zvyDxay3s)t6(n%9Bxby3n)AjMzsV6%u@DJ#ea&`f(Z%z$_e}I-&V{4~PxeS9H$x++ zW0(i)@!3TC{nb0t!PkQ&4zH!1b?}|R*m=2q4IVajHL<7^A&rEQD0{`7-A;_ry8f+i zqtbd?e*N2iQjrEr1iJ7DMYWz2=DfepeNuBkxHKL_;>8xx4^dm{NjrTTt~zsGbHQt3 z;w2O4l6(I5>l(bEZhviqaS^n^Z4b6co$X6Hy%(!w9?ZT}Bfpfs?}QyfvDQSvC08d#%XRzVg{c zVpU%cHa6B01HX?@B;FHEBlDB~}fiC=I#nm2BlkYoJ$M3g~+;i-$RV`1}qsQaI z6ryi~Z>qyhyFD-Ru?VK9Ac32o4F{n+^SXX@;m27J9 zpY@VhN2751c%3KP)u58DZvS^Af0id}`r}1W%cbuK&Si;}xVE+UJKJb>$vB*%g2dVc zPZr$vOwmPEKjU?}M_t~bZBv%tGDsrOg-0mfgLiB4jPE8)w>n&!zd~Y#mnS=u(zEEd zlfEBD@ilp5mqWS?(+G(`m)!HynQr`w+gKKR(nFf-!?{K5pP2oyuE#sS%wyMIwUYXQ z#N2D1EY-=Mi*GZ_W(Nm_Nd&s^tc$nv9t+;?YX$Y;=(cp8zZYA+c9O2B z%^Pyq&xibeukibX0|MHyd|M!?GVgB)I-1 zR!nlOd2Gius?94OiV70<3cOjB4L@~sy8f$g$YBvx^E^x4P{utgQ_K!vTi9px4hCXbGM-{f{ zyMA`CPp~a-T6jaXzR-m3E%0HHz75&59XE*A93R%)tPXpVc$45duGl&2gAHH*=c?K} zyqUCKi^T0DA7)=<%fdeBM-yv)HsTK-9#uQ!+DQbu@CZdF>mM7QRrQ1#81E#lJ0p=A z=);27o3pO#^rNEGLK}X_|A1`dmD3IoU7kW*wCH& zRecwwF@L}5mU^&4U5W}4xWX@Xg^&o-z$20$tqyy`J89(v=Adi=7H)DI-& zIGNe*jd@dVV}A3snM9xq&$`(CbdW9Y^PmDhv#_f4dm!;B*O$GuZpp5VJtKO4^q>v5 zeN~Ge*;9sAxAJ4BiaRi)&PRyxZ(kO=HG(w^K4uV8Wb)C5PYJKd>$EeW7*mAAk(a(~ z$g(gN8hu=};hf!wk5$chp;H-&Ko=gNh%aex%dc&$!dJbhNKru|aIY_`+9rs_9?{Rq zyt23D3*J@Y##bv#1iIv&*SlcDUu?4CwZ@i~dX9bajr3y=hj(M+!VZWwZnB0vq=yCH z5dT?01qqDz5??YMZ1|!hb$EQ{H;F*kfL>x1Iiou(wPe3&qaei8&+Q{}Jlw*`*8GvVJOCtB1c5;9Qf0pUH-XGv@tEW z0gpDS$D>!>mk4y>5sE19nl}7IP6NKH{97qX4~ftTek^ci6e~*6M|q!iu;I^s)#cVF zK1&3;B^UPwdT!l9hM>*F;-FT`Khk;`R4=nJnjBjsUJwVSZUdji^EyDn%l)u z_4BvpiRsOFe3fE}Ko_2MQ9~%gk_Qxc^0k(Q%Bz`L=3aUn>pE~f`8rn1M9pVb`qBo2 z=uh`3OKu(H$vaIilA=G6NJ!AKtz*Y9zbYHWQB8VSmopK=`|zqvpbPsX)`b16_<+f- zJoNriDKZm@NLMYZXcNb-eJ&7fWX4fTm)GQdKl}5<+gVb?FB0nn z-EYG*cHoviMmRmume+pm%hx$(O9Z;GPh$OicP(CYnec!LE2YR~B+RdB*{5HV+0dJL zqK(^SEcgyrE&nojokXAu&w|*Yn>6MFr+V|IN#msWc8pxdh-UG2F1F%M?E`qdUP)3v zkg!@n*xKzg*{-tl#8ExBtI3tGE%t3iB* z`6!7%7apO=5-PIit1J5OJJTW+jNr$ZeLM@I=GlUJ{Bu2j-fVlY)CLlAWdG*DwfMCy zK|DRGy+oi3&xrUgiK@!o%7$^T-7TbZg~U-ug=M^&!+MKKmT&u!I)DP#E4|zxgy5yc8 zy<*GXU2V;W-!W1!&jT}UFq1^gQ)gN5PZ1%!?xgq9IYC0s#~HP~3P1C^9q*DW6X?R+ zEb%4Nt0M2?6UjS?5f3Uzct2H`{q6;9*BUR;^P@Y;^U77b@PqF2$&2=sz1+BvwN5i5 zXIqH;s1XajE-ZMwf3Q2kYeY3Vc)3&V1CSXo3n7n9U{T8Typt zw}ZR#Rhl+}K&Sp}fTB=Vu z=ZZ?=vdttiW2~?2CJZ7P*7Fa=B68WoBbrVOGSK2i)BtmDTvmxJHSnc5IguO^-kF?IrhgTq%;@cF?Z+uW>_*N4w($LPgZms6Bq|?Jn4eb$n`5WX8O8e? z33SOBph)~ov}A9t{Ul3$*OJnvHf;O5AEer^HRS0B8+NbtPhwtUtwBFfK|+rGz&7v~ z#NQ@1B%Mw9=*q4eS2t(_6(mMDrLme~yf#U#QUZals{`h;7?W14l!KW8fv!gv=duw^ z{Mm*{mC3&os34KrdoCNiJAgH;R@tBpB+xZgWSjn})0$nrSIK}t1&Li1XR*eO!&r)@ zVhIGg@=wlWpRROfs|J-fAW%W#touxMd3h%mP*f6uu7d9~*aq`%Eb~k`gEmk>!lCVS z78=oul^tYK0)eiEFQ>B1N`qLTSs4QY6(nXon#>x64`%8<;}QsTb=o#r1hB=h=>Vp+$AB@yVd-!huz{~E)F9oHDNfeI2={NvbB zKA!zusU!kjkA}ptkI56+;0AvTo+YRt5m-2k^*Nfz_I>zO0)Z}{dS^q6PeRjJ{u6IAko~v7wc#@ldWx15`nJ7!Y=I8 z>sf55#e0J`P(flx!wzgy(j0bt=-Uzqbm3bENxGvmJu+du`0OB37Z*4^36QrDG4pv!M*qOQx4O-yt3j6pw8 zLBeT9qHgo+P3-)Jk_dFUeO#yu-nEe}{&v=&4OEZ_O2f3Y5>B@yV_;PX*;@$c2_Nc*b>ZJ>h0m@8j&Pw%c~ zIUywx=yFc}sT^>x)ojd8!#0pWSM=JdEZKPlTN+Vp&;}|< zboZ#n&Q4gt(n^;^psT!THTKDx9~rcP3KHY`db25evRK6Uk_dFIE2FS+V=~yG2ZnPQs37t0vmZ#H3&%V1TMZQ? zaJJ>&33UDYI0{EXYh0VN6+=IfgUV|1@1r7AkVrk!oDHxSbaQu^$+aGfHmf@Ha z33QRh6`21=jZ!O1U(p)R6)H$%_*7(#tCvz!f8`k zX8WR)vd+3B0$mTrf6&d&HBv^EUT@F_Do7Mg_@p~tXr$CPFNr|cW$Qb-P4A4AIr|I= zRFHVM^}epcdt>EoVMzqK%stNQlAo7RrqB%r{Xhi?rPoE>7)@EFIHV*3UH&b1=xR+d zQ7&2N*C6pXM+J#a*LLf|CYvY|OC-=WedcCe%0#)+u_OXr z|32e|3KBnbvvrN8l~-OiH=H9w0$n)UCZ8*1!b;Yrce<|IWG6E8RUV7_oT|IL+?hnC z=dt(p3w2%k>u1mL>_+CUVmo;kT|%-ud0llCYjen57jx5-WY1s8-nZ(d%P@C0An^ZU zd;dU!BtPWm+# z`~^`#V&u4G>|*2hI*XM0B@pQHe3QfK*uT_Wk8EH-pn^oR^~+fLp*Ole*A3f10$o{} zTo(HKrjGS&WY7jGNSu9|%ci9i>t3XlM4+pF&E+gxb3)hA)ZU;CRFHUJyMk3LdtCQ- zvyupO-D|soZ8@}E_szJOK^v$bk+(RH^((tx*FT|o2?V-IxNG5lM&ePkmF&-$9Gy!; zM}s!-f1wNSNBO!c?a+e7t$IQn(pC`5Hvz2O#V6#?(iNoYa)ljv`;?4(vcjMZRFL@h zuMAX>kh3%KYDWTHb)+m)B=D#<)d*m3DnB9X2d*I4zklyJ66G>N*~WIa$x*XhgP!C6 zLf785?OCb!#bnE{Wd;N)NGLr!vR+x&$+#IgB@pO3_@E=Zw)1cD__YPm{_a zh6E}|w0YE@*=C&}=cnj*w#GJ)Kv%qRH2c`#6#4MnkU#~Aj28n~nf1p==Kt)Kf^8sy zu87zn%<16~k~B@fy9yHS^ThjZ{;r~w2U?QZZ8fXza=K_*JuN9ClB>%()GG3e^EV(+ zL1Ouc)y(0@w!)Z+0VNRVS~qqTTTs1W;mqI`1_UZdgpOLpocitenc6$hfWYqrd?UZJ zS;ai}HP;0X)W;fN&rw05xWj7J{?*T-MN@oBAkc;9P;LViBu+-IW}RQWF530Quni>8 zg=boB1Aklm%{xpS$==^ABE2r@cL2klqk_bQ3h~TnK@suhB@yU~**lW8SW-m%4;T`t zAYr_1Bzrk^AF*~Vi9nZ=^=Q_-N+B`rYDl1h#P^A#Si|XiNt4$L4SJ3Qx)Ng(StX}@ zlF?*=0f7nv%HdYe1laMAKzS zOmSLGwt5=2fdsmS_$9No({qW>wmAlEpn}96+hkVx;ZhR#Yjz0)x=vr3!NxYpCU*l2 z2~?1Xd^v+veU?eq_nT$V1`_BBY@EXG@5>-Vs~QsMN+vVe+1(jrPL)~Y-w9NZaJev( z9h{X;oF=9k92FAiIv<+K3L@r{-uF`s2vm^pZ!(+ZG)pCJUuPH)c)jj!zLFU=>!MxT zuRZzqYZnzHPFBfdkG{>-78Q3gXafm!)g7{&Z46zhotxR!fItO_Gv`;Z!BaD}r*3sF zfk0PSm*q^%sA}6@Gi(DDBnltrGXDw(v>sP_8nl4~x^8aDWzXtt*Y3E|-GD#^i7UxD zY|s09T1Ta?0WsKaE^9b*D(Un>)Y;iNht;c=NbLGgCx7@n7QTKIv8_AJfItO_S_$*m zj*+os^YEk+2z2$HHlOJpMU&T!rWz2aAko7tjkOv*gbX=Y5`nJVC-YhN%)X@U;3)=e zpn}A`sQGNwj9%o=qRAx?=vvf0oxLd2iKJGTWI&*TM3WHk_!G_l^DoFI4oXuQkS0c+F4mM~5ulCdR z=d#O-r;_S#f-))i&+CTzbYlCL9N8^*pitmO5DoFhMQxpkw zy$YMf?%Jgi=P!oOT~v_3r?%X4yfVVxEo4U~P_m`<81nB|2`WgWep|=}xKa}2Hpbvw zA%U*zZdojDh#NU)I?8}R1&L8>vRE*)Ba@zuD1kuN$*{%j)Q-BOl1Z!qfeI3X4=iGt zA8g6-Hp5FG(6w&h5_Z(YjNC0V#DG8riGRO#kwDkE(Mv?l*-FIX|6J{;Ac6PF|NQ25 zB4%3^G23+J&WAqVohm8`B2F7)wm$_g@JlLHQAwNrpQz&hCxNa_sV#i(ivKi7{3p4M z8Rwiy+QW||Q>^M`9&#dghJ7LybTv6~&yl=*^pSl0-_^c<+CT+~W~Cg-ndndCyY@fp zgZ~iNIv&;i#!LK8h}iRX{~LS$4}l62U3>2HJ1*kF&-`zc_y3bX*N1h-{AP=|@CN^f zKn012brrNe(<&%kso}Xo0$t^HR@3$r#L)jk;Mv9Vrt9EBPOtn(wwE(JSEwK%W+Tae zE6Ry4{eOCn1iI?pa3S+TKay)Aeqa90agW1ivuBffJ|WB_xgx3eayIFEFO;QJt7t%= zg2db3DWr5>C$_Dyya9m<5|QFr*sf|fHs@@)5(so{512uEoQq=0tp7xR{?l_*kjT1` zOm@ZgWV$CM5$L+9O(H%KgIT%%jsE~Jbt6cpsgv0I6(teq z`sx@>O#dXaS_A$Q{rOKDs31`#x-Yq$GJ{RL_@7wLe+Ut=LH<9!&N{A&=llOlcPJu? zAO<1^-Q0V25DN@I46wVqunPkWR7?yM!~nYyxU(b1+wK-y>@IBm&HX-*_nG^9fBcWf zHa0h*o#lZ7#p(-+LGD)R@33y#?*n4>p*~4NvG2*n){&Z^~JeWpQ8&CRF-!)FXHWPm4blJpV~xmB-2j>XoC-WIs3E zR$&V!-i2&Y2RNF_rh_)?^c5zss{ZReYWtfe@|H+l0$VVVcx}JhWRi(|#^G-SR(TG{ zSNGugCAO7y32ebc?9J0^kJiSr=hz&bI52@#_M5J$hdeftpMWlbEtqJv>w!A;qoLeP zlda85%Y%CIVnbaYn82!YC#>P{ z2T88HyfiDU%turESoqv&9z8VWje4fi76$WdejA?6|G%F&*n){k!9Ael`%J3ePWKsw z39Q0TJMmtE^YkBYEDj0aIs3bK&i;!p#i2hpZl_b(NuB#HwqU}b?ZeP{Jj;Jq!QTk1 z8hbHPHFC*z+U=4qfi0M**EUi$Y}I!9;MCs;tV$ZcP_=u^cIxw9m%tWGIGJlyZM*PR zS(WDLmyIAMuDGi32ebc=O))xoddViz~H|TSoJgdi7LfqJI@8sC9nk( zL5jcnLceWvW`)vPfU-C+fmMrcN2)J<+)A%4)FrS56Y(2j)JGp~<#qIbBd}`x-UaF> zwYJdTQ%h?B%36irCX(yShX%O~XlGj+!0#pEwTms7xRB1jH|!QhH4|)f?r@mED*T0Z z(Fe9*qR@IF)bmo&-sel}2g~BX1XkIPONB{Kedx{>b~>%X7EIjPwHT`Ky3_{+rFE%g zJ}`k*qwl1`i%4(!Pl2uvJbT6S($%ZN;o+!7^xEgr3eYki*n$a7n{ap=xR~DhQ#1OX z1XjItZw03Lyhhcjw63U(z!ppl`X?67UYJLd_5Vg-6~4QQBZw`SC`oAzQ^(Dt9^G|) zU;?Y~Jy`UCuW&onOm*e+TjWJKI+REvI&eK3b7EEONoKjO>E3@cN ztxTB@OkkDKnq%sMJ)3BvZ)vSe8G$XB=)CWS`qJKwG`C@C<;#B(Sk<}hL$%4~4Rmw& z%Q|sj3nm_R{jQF^nMF6pmR6;d`M?BLy)FE#_PLZrqdMpk*n)|iX?n24KZ`~ime$IY z`M?BL$>zqe`&T9%7IR%E4s5~1|9&gN1Xi{0VF#V7ucd?jzxOC?!32H_6Mr9ghSZ8x z0FQv*;BsdJ{O{QkwqWAsX9tL{`V0Ck-k@_A#ROK}EAI>`H-ErJwJw1zn8=K*0u!$O zfCZ|*5m=Qn$ptR_{to8)x&*dhqQuo5((iqS7Eg57`Y?f2cvV&GU2MSwukwI@zoCFv z2Qh(F|9iC-KUwe-r@7Y>NWI`jyEU$;GalH2iRqb3AmpSwt*w-volthQV*;zpTP}ki zNlw(lq_U0=Y{A6Alr%W+P?2sqSbBCsnGZ~0RW#2UI55$U4j5TQ#|O4x;!|cCOwF~Y z<8SKvzywyUAH5RB-Zr8a|72j7wF+A>@ym8KRDG#Oo4QxiX%!~0$|z?QSWWq<(buo8 zLtqOgZu9TU)c5|Ox##&e0;^{CT@AsV-fKQgsiEToTQJe*KssFKS>9{@WOxo92ex3s?9LjvUr?m^n)EjUtBfYCfvz5xG$XdT>G;4FOvK$=3)%W7 zG`0R@d6&h339Kq!p8-y)Y)zjb^>ut;3nnC|Ot7!MTl37Z-d_l;s&F6!iZmNFt21?d z2p05z?c>)$o2rX6XL@<*_`n2K%^sc!@200}CXUl3umux0PpyM1y=G}%m3Zs;zywxx zZM_a!#}Cz9e&ee{U<)Q@cFKY~HM(ftRV=L-DH{(=U{#%jb@20BH%;BgemXv|1rsUP zvLHSoP}711{)ND*CVa1}w}*}9N4F3i0$VU~xi|~z<AmW4rRK0Ie;u4{=&rsDQLyTJCTx$Yq27G0G#{?ahsXFV$etKk zFfollP8_Gzrwgj^9O3`%16wfhPxCC;bN5X_@|)7U*D@cNz$zS{_*BC?Rd@$$qkA}v zEqMx|PfKe7%6wo8CT@Oc04vWvfsbi_Bd{ucQzID7bM`g8bqQ?2#G`uQ5S;Y{+NAuA zz^b4wG4QGS9cZUln%Q3#2ex3MWJD`ibFK*Ndz5DO|0jV}A78eE2g|NQkUyFI|4ks({KK8W_S{8S@+Y&ujKCKBe_QBvfuyhJ;pq6%%>Mr*uxiT5 z?(p;LS=jroG*7>bz!pqQNbLb8JhOj#v%e8oJ}`k*pCJLROw5C=Ub+OfU}9t4QE>WW z9$bk28-Z2FjK{!|X$PSF%hJ5?vhlzcOss!23En;30XzR>d6yB`f(gG%lig=j{&}ZBv*gjmBc+hM)9JpEyOv?=c z`(Y~}WPuf=KJEwE%~ryaDOS+!K|dWI*n$bSS}Vca-vm;9`~HQ%D&xB8Q2lAKIy9>^ z!?Y}NY{5h%e-n;-`bM4P)KkX?Ca~%vq{AVunu<9De$v(miqG9TE2iQP}rVZqWu^}#2lx##~$U{#HuYvE$nMs;TM_ByS? z7EDNX8IV&qMO|{gG*7?G2PUv;g?9#wwa-+SPbtlzFCzpC`oI79XMoGs+3F#qbbVj~ zs~nuyLH5-+b@t%WTA4B**n)|XZkdpdk=zwUWW(Pv-J}5?Ixs{5+_XI0NSWEX}7bBd`S%wZG4W=kC+s zj>F#wtity$v3Icr6Z`z`rr3Ne2070B@Kd?y1>Ky!GQ0TVymzP z6AgzfhYlBOgYny;IwOb)teWAq6z(1MgNrps>JZq1iO)xuK#UWCB#(r@5LmTOUJOfi zG=h>Xr4FumuzUR9OO--ZTOas_O$2SY^;A6@K?@3zuq@ z)@GEo3R^I-I&=}7Z`KwnxcrU4s-M=WFq6iC-Z5PQTQKq1D;2Ukc7gZvN~==JT7?O$ z!q0i}D!~>^bT3)}&LjK7!#~wEWj-*0Rd_bQPxqF?wzzduxXBJL6h3{4-2U(FS6=cZBuTC?}Z@{Hb0FkSl=obFHsu79` zs7+OR@u>DYybYI!kviMLl(CuBiP-^OsUCVpGyByOI6PMkEA16cO~+?&uVE;(%VU~R z@y|K2DpZY<5O0|)27%LiaI`BYZr89Tw?bptry_o4Q@RXmUe2dWB4c0}l_58G0p0J{1Rm@qa5!^5 zy%ZF~33kVdY+e`3hE>v&u>})tPRQVExR4I+8_o&4{kCL}c`G(_(i`D_VHIv6zuG-5 z$-7By*puPc0b4MU_DhELE~)hBNNwaB*IE#7@3!py#zO*uRbu1?Y1SlUVk@>Vq?`~r zj;UmX42Q0#&_O@6Gt26C?Z^?YmaOT3sxr1<;v*mPr73f%&x>K4c$sKRHWf!P>$mj; z0;?W3mSOM0d9>Q<0i4LXY)9TCMX*V$2FkH}0j?V)(~a|!Ay5IxZkJ5oL?%HOI|5Bc zCef5!?K{quc6P+zVI=cd-dV;LOw8oJ|FAl9Y2D#tIkCK%18M6O!3I8RCJTgejL#+V(de5NcotNlD{-{ROw^SZ=#~w6H`I`2G=hL~1l6K0zbtSaUw zsI0snMQ6}sI)wbliJVGzVC|k65jDj47nOhkG4L_TjlW7m3$jgk=gG0CSwAt zHVg##)T$G;bulp(x zSXI8W3OqV>puzMY_i>@W8%cLCWFOC36FiSHnGp(xN5bea{x!+or`0g4Y7@Ev|##6%MonBMEBL9Q1O04`f(e_2ufl-0A)qwypbCV&sNvYebTl&6Wb_>ZB45}uw{Et zC|KwP(eE=a>C6*7NANNKN1tUJsVqc}i7#zJ;V28G^G|7Kmgjk^yjL2rTc!>IfmOH{ zB+0LjGdZ^Qrt*o_A$ZPNZf*!9o48Q@akpU0ju5C7>Po%%yi}6TX1I}Rmu@J_N~#G2 zR^cAu-*=wtOund}D!xXwgucSW@ADzB|C2i{vA@B6JnrsHKA(N1FwdF-fmOJt`4?}W zIuU=TLM2M^A%}aYU}lUBJrZ;eid{pXMqU1O*thp!V#5%avAzP`mUWl==+wiF)blD- zHau__2&}?AB1tAHXX3E)oYJeghY&d?>L-N26&ok&Jn=U7vBJ!mG=FnNS-+s3KwuT_ zY5x7%@=j#tv`vchm0&W=Km{xHBs##Q7{0P#7=K)%Bc2pPi)+C!w6`I>Z&=KI)XuL( z5@%;CHNSfa1Xkf5;j@epP9$&YKIKsT03mWrv@;2T%~vg`ukQoyV}2heqKVchUB~(f z1XkgmmLyH{Dx|uSqQo4NiC$JHtZs5oQ(@{8Fzpl!E@}5Qb6Y%xD}#c0M%WWggz|*@ z=wH4TX_&h}Ir%$4Ag~Je2%qnsszNHRUabrpsuCi{MC!I+$iMYn6S-3R#xg=vg^V^_ zub4jy5eTfpJuOL{hdUC}IsKL8Sq%w(!;1eJ1oX^7%?8&Ou+|_LCdo%Mi;J{xUg<4d z$*jjilzRp$fxs%GxfvSA zp0Bu%M&oLdJj*a;RyiUNScQ8;lI$HENwVBpF`L|2h#V77i-Mruhy9wDpI&euktU9$ zU9Fx98QMr7unPAyAHnuDNZYOzl;?xP34VW_s|teSnG-c18ovP?pCpZaT8WfDRYM7p zBZW9H(Qt4O^dGZOqd!FZCY3)1s)AdDp5 zn%fuN!iIZ+V3ri3(QJJSLGB^&DPRap0T-F*iO()2Fl`*n$a*AAzu|QIv+Y zf6IwG8P$o?#Jlv^yhZ|nRk%ka=}A^4^5nLjGV@I{p|3FUC@=`#tH)_-cF?ve_E;s- z=$(a<)L$g93ilhIEuD8DCH$)mU%rcxAfsCvqtM9KB*#!xLiq7WED+z zR1Ab6{U7I_Yx*8)4-JOJ{L4E@l}z20-;%MuqdICOIU)cO$wTQJe9 zLNHu4nHQQnU+Y7)rXq2xldie=E=urW?Gp&S4I>J|gG7IlVqOpaC^VYAO&|g?mAg2KhOVt6P0&@1{`%TQD(hR3O}Hd#1pv zP#cH3odYqo?L`~@Xekg_CHC%O|BA%V|E{{9S2PJ9696OZkE^ECe-GdC1K{@=f0c36 zdl38TQe;K)DtWMaZa_4_7J;}O0CzXc3AO2}jr@MailpOBOZDfjBGC(}@Hp``fEM;7 zL6ZheDnygP1_4l^SGf8uA7`)N0H{3BK|QYE9dzyy1g+d0)T*D_>*~p5d(zKuI_$0+ zO|S(MC%Xo~@|f4E5&GIzg&eCuVv}D(kXIC`x7;6wK1fmTs_+(!xB5fPA9gUQK$(92$elvmFI$0tcMUf2=y@1C+rv=})io_zO%Cymajs}IyhUZqL}vhu2{ z+;@*iU={8+NoqRHj?C`RS{^pC8HxSw3z}=r(5UGXFlp__a|VD2-(t>xd&OtT|f z_BWS*-EAhsfr%$Q{NT2pDV+HDjJL|EyB+zqtEqgZX>)K2=;}nVNGG1`+cyi>JNh*n(|%cd)!CLgK}g*RH8iFD1u-MCj5K& z!pw;>v`W{`;hF|G5<~aVa>F;_0)bWH`tI|ic+IAOJwozjG`O+L^!p$|+qyahpp zKCt6kH#n$w8}w%S!PD}6Aby~BEqqS9a-`jud2;aXCInkBf%{OBwmh*V^OvT|o(`f9 zO#Almfr6o<;Y*D6{bP7gB{FkVs=PHNj9?2U#Fgz8F1Dn9voyJCpT+`#RU@nVz-|3R zh~IIQ`*^j@io9&RS?)HmAsJ!f4NEY`^N z?=~XXf{EpoePH06M9?3vjib|k8}h?(rMxe`u|Qyz7niPx$_uFA+c0w(4$03(`-uU)I|w5?Cd+>e?80;Wr4sd+#`~dY;8ft49S-- zZfzj+6(+=5nUWg@LvR}bOZ)g1PNisdq3*_Y#> zZ{Y`F{rAA?b=sApDS0(WV%&P!RpTcRSS9w=l5cg$juz|Wh^`(&|z4=ciFfqLjAon5l#vpva^ zdh=!fh91H%3KN%K`@y4>RnYzUN#3eMQ)`i*50}e(-uMXwR^i`@Bo*DOPwEU=F0Ux5 zFZ2~A_7wZUko48iWwh2u^8WhdWtBAf@HdgbDm*s)8D-&3#+REVUuiGy590fZed_?Q zfFbbESbN{~cXB767ADKbm-!QH!34esOOoL^Z=xAKRqmSQArM&AW@-RM+8=hty;U*kCbl|BOgESN$`&A8a|t>Shp^0yYo5BB)g$+^!99+U!1W)ydSl1S0y#%k%>U0;_OLl4LN^mu#BSM?RzW6y^+=s8}r! z9?oe3GyZQ?ZAqjrd6?5*{$5`sunPAAUp3fYo*bUqSGL>8=L~3WfM;iT_QBuPysHrN ziE(o6xJE)8m=Nc1+b+~2yGAvW2R#-e$11$%ElE|={7JdoP}#Aam#`a-iR4y6Q1_Ds zq@B{PU#)izBqusmkiD$D3D^fiIp?$L2U}mjh&MqHY=29=&Gv=Pe7DB+0J7#_75VXN zFJaz}iSlcMAb$2Y^_o7~nWc@D2l;xmu6(jENFcBZw@{L7>jsct|9HtmM|lZzQA{`u z2!f!NCUCE%c5P|?Yk%@P(qCTIPb9EPjNIf-5UHJd4(^6{lbZS=(0Ri!^|8CJ;r+2- za5qm;-wu4O^H$WMbr3OlcprR+c?<6!n0P!T7=G{AsAj#jGyTZco`fyem#eG}76_~o z-zFL!3?#!VnaJ~PyoJ8PL_&*TSg zkXNdb-L>n%u?Z1^4@}_I1WB4|>O;1!sRQ%Vg9QSsaF6ic`TS5afBRYWQg5-ZF!4Mv z6oM8!37s%pyJ|4^JirC7;FxZR@;+b<;zkUu0C8y%l`aGuEOg8_L`{rV@6{aX%%9Gve{c(%m4w2M`lkv8oz`Ag9fSSIh>f=N;Nn1nEttUT zT9PE+P!s>f9`wNE`T~JfGb~h~nfA0`PMX$-aSb51E4QSfmh}m?VB%~z&%YY!sOeiy zOXU3aBks3m(WI~df-RW9>z8~tV=s`&zZX&WXLSVvtLh9=!Dpi&O`EOSRp&du{E17| zYxJwBpRihsGqy0zuM!`b1YX}oZ$GIctO#Rb_7D|(%n8=a+Nkw0<~k6FT}?l)tt${% zCAMnnZ<$P8_LiS4}76 zR+x>l*~U#Eu&Q-^H6)Es*Szho-8WdXJCKA-3Q$mHA8!r(4|7{A}`= z`>4>g0U5rbzjCyjGr<;2*i`}e(dvz6Po{Pi=O6uGvc2OBB_^mA!4^#D?8L2aK#G1R zDhnJP1p=#DHwO5%_ort4TkUF8fMqxtn~<)AhuM*Xg#hQz+tEc6ZiD?=o_}L#O|MnD z3*xS2_U{ISR8CV)=Cg0qIzntOV|?BoJ67MqY9IKYmB32o!X7;)a1N{_nf7Zyo>o7r?2j=N z2&}5pPlncx-jw8C;&FH{Z$N%5KA{{qX+*GPZ+96Q{`RCZt6v7ORkL?CAW2{UQI4-M z7JOi$WrPgU#=3OUVQpT)gl9Zw<)tmiv^TSWAJxDx3+-XMNjhku`TLS+=c-kRgQga&V>!p8+HVlIG70 zSf9}!WNg6%&SI9NoneGj>QbWII`>>4u&UrE&$G;rq~-ID@i?ru6H-3=opLwwwTvy% zZ)C7&+?4+QbX+GFr{)Vn9v8h<%-X&cd|;yC9iE@qsS(W`q+Mq?ogPGdeLpG>E%k+5 z9IV3E7=N#w6-E-5K2SQ_eUq^T6P5SMU|J986btRT=)2;`0EMOP*5*U44u+s}{mUv1CE4!Iy?o?!y# zO!3U+M>WY27Z*0v>4`vK70#36Gs_lE#I>jz^SDwXWYA$k%%;-Us7NhyD<*w9CF7Qy zO&}mCU8q4`K44msCeBflQU2ykwe!4?v4x2nT?ka0-GPQp)vl54b_pQI?5$YUDGvk! ztMFARN#nNxNsKmRj}{im*n)|QY65gf8(KTLko!0iB$L?BdMvEbU4g(VoWIZCShfU^ zmrJU#E{)d9g(U>0-5Sl$R^9}v4+NI^ji!-DHtFO*9`pAi15#XBJKvo`Mk6M0h9G}_ zKy?yY7Ug+xpPor}lCmgZhV(yfNijY)GL%U={wQNs^gf0Kax? zumdAAg%QNLu3ap{!2H=bI;L_K_pw^V-_bnlvNM+JWNg6%&bgJOOC9}4M^`si@5*w4 zz^X2l!{FP1iL|;$2KRCAwlfLUgs@cuRttH^IQJOSl5{pqbO?N%J%~$Nz56 z|1P%B&5j=a#*3I)d9Xbm$wIC(ChDug;M~}0blXU6cC@>fH>s0epS7tnTOhCsw@{KM z&-Em6BfXgQ$3&r3xUX`%gh6AynRHz0eC}gVo*SusCx~r3H(tgTOyJylNlM~xTqjBb z*!8151Olt<`BxopoSQ{wr)YD}qb*!X+(yE-)b*4nFAoE2ySda%83rBs-wkZ$(!IBa z0nV+Lq^CP;kGWROIPwhYlI+GoEH|^0Kwy;^`JmoaNuRb&*u!Q zRw0MhHD&#mR1^rT5_`9qK@FmqhO-yXs|$UF3HP)xxLIp1?cp|z`*`xLCea)q?D=gE zfxs#}vXZoJw-dQw8No6ue*ql1P%)Al1{Z2Bq5v{ZywDm%u9mBhr^(t?jrhOvNeq3 ze~+rYh(_PA7HXRK8rgb#^1dXBd1THLESUIxFbwRkrBZpS1NTvJogG>39>X?PSSJuz zg-N;GAerI8U_3|`TweQAq-p_*t!SVgnQ)?T` zy~c%UlA?#J2lX`K#I3Fel#Jo0<+In~h*bTdCZXI9@OIk)uE&jO#>Jm-Lz)dB_)9%=^&ais>|rSfui6Tu1HbHEY54`FxE652S$_mI zZF*KNINzV_m^ZUvq^YIcBxx%&>6}-vfq$>Yhkvi8VWs>6tH3W%HCr3`!6xtN4&$@( zmtOtINfT2|+qo8UNTaRLs3=%7gnyx62>(LC^tmA#=iOgmrhgtMW;~gu%$jjp&Y#(x z#1(DVSidrnue9C_ZLjUuw47`rPpGsRKF8;3{*A*g%8WhBie?Kw4v~lM0$TlU63w}g z3>zp=|CY(LYSSdJ>sg0Jbe&IqgJ*Le33sn3`f>f(mu{Y5wyYK%`*0hkcu zYyNlD@J%%4wLT}J7q(Z-r1324xh3owpQE{0kVEZ^&Z}D_Ez>0K+e{O_o>jM;yG)bQ zU^AU^$AA;9^Boi~(@Cu8pb2=*oTSLZoKX-K{iv(`ogAX_1=R{kGD* za|}7L{n}<)_v>Ufd9ooqX;EAAk>`%y{&`A$q2xrtQJ?L!CY(~&_;#Y;_?~UF|9dU5 zx@d`J?WHLUEDd0Xb7p~C|Lyd+-YNCm?{@y~{5*Jx%TS%=mnZYI_z^8xXbG`3Qja0k;8^@ZKa@Td^ z*~tkOfKMLACj^(wS*HHCuYL|slArBMU`49(fY12Fr}u8pJf?Oj8;>TLn`C+SaAs1u z3gFXp@u|0iPkdJYJLZWMj>+va2C|Ax+yI|j+a8@&Yt`Eh{=KehPp}~0hDI>sJu75f z)rM>0{;{e92eu^BjuxwU@19w2M(%5F(04BF2+mfi_^-pM1Hj4kbJ+9NMIH25&kyO;J3W`+zxr*;pQa4wJLnNumY@(UlcOWa7G%R z!|nVaM-AOCFTdJSAg~Jeh$OwA@I$`wdcSOF(_Dxg6F8HLuR5RlCcitJFQ@Didl#$l zI7w1wx$koSZ)@Z=V`2!t8t_%}X;)P^KPDNLoY&@;_*mO(cr0 z>XF!inev==EeW<@0%yAMx73MW#}J&q>2|{f8VqR$Y~W+SS(=h$9W9aF zi>JxcueK)Gf{8ODs=>DfZjgRTyDPJ)lM#73cC@@aua!Vx70&SBbu8ly$)!z6^7>|C zt8f-8_Q!oRG9(Aa&yi<;iYC~C2{HRK#qgIreR!(;#w=DKunJ#2Jfm@f0U2|1k^I## zTDYz-fwN5|sYjRr(Hp*0KC>rEAg~H&xAGdr6k`(6oydd6v>`Ybc!q6tsN6&!?)H2O zIE$J820QALt{r{l8b{&?wqPQ5cXf!UQ=q_Q@_Rn!xK%iF8T;ecRirVQnh+yD&uC4s1rs<^n%74S)g#+Zca~jFwG{}g!dHwW z)zuggcB{ACet9gx7EIvWA4ys|-H6QpXQ&)tE)rNJUWpfYU2T=Ik6}-PID(%`IHz5F zMy;A*LWb9S2@UJV5p2N(&W`76$TkM#$^$+5{N(lmfmL{H`0w1+goGTkmwoHEBiMoo zoU<=U<9->F`4?)+=hn6r2&@vvJdqlZHCZ#k>vjiXtzQ!+?OvfOCw&2&qk-d-q}&@O zWK-i+(9bDehyxS2hC-5Pp$V_l+X>H~iG77tVim-tNrq(Qm#LcL`W?ya9W`P5nAC!c z*FOWU=II(=6ZCiKhn#Zx!msuUNv5RQWz&M6De(kbFd zb!?I}FvN^x_Tb+I?;;Xdg?pW6<1RBNvxoR8U#7rXiLaT5EAoj=aKB4AheWfbOg^#TXwqOF+67n@memcRD<95m`lQ@CEDm+e-)b_C% zsdrvdRE^pSBZvuH;mF^e515fw>c`aNu1H`Nev{#+k=(W*&UBXIF~2#%HMO`Rcg=uW zP`tQE)3${+L#X2>3o`W16lLzI76e-`Ay%?Z0TZ%tQG+&E>cZHz!*l{n^GoGpo7oB2vq#b!d}I3}^O*r~*X{M1{n zWW+Zo*n)}chiXCmxL+FMciMTP%?L{pdtjwTW~oCz!JE_!8QJ-yxQly*E8+Yn{HBLiNmi2oN> z;WK&oEuPk+EBk`ZyM`*g!>pW(1uL7;mStzFe2E334E#! zueCg6PReJvGKb0L0)bVyg_4w?VnagvRb~6HS`uu*1U?;zpHeW_hWvWy#P%m!3j|h) zk(;)(A$x4y*^Oa(LgY9mF^46!hdG%hd9s9SKZP6?ObqpPhi~@7sAjUZiq6s4hPa&Y zVDCSE5D2WoCqnV+<(t-IabItiTkulG7EIvto%r6}1vBzS9mrb0d@N%NCUy^X2XcKJ zeU_-rXZSwMn#frJ>}>Db0)bWdL@1uQ+{cPEiImyzph6j+tA$VKT9xe%8(U7JZRM@p z$2VRxYS~ZCHe?@@u>})ie#wCH{Di3synlwS(FH%qudsU_#7D zxffzh+AR%Yg(I&C1XhWWmpfoVI`nJGOslVv@k%p3=S*C6-e_$}(!Mrk_l?%e*n$c1 zbg>hwO-P+9P1wir+XVuva3Au>d0pzbeqpThf;^$GFo91q<8@x`t%y~I%!tuJfxs#} zvb^dy-i&OT8qM;@50lIFtOI}cgz(vR_{=-Lw_U@CydNIJ4p*2V5LktKM3UxanvOjBj zMbt(b!mnMs9wy|3Ya4dxfJ(*|OyE-sC8@EQ0XcG`EsJl|QXsGj_aWbDIATg7e#fxf zx!r`m!UR5jk?)K)H6wI8ACL4Q0)bU{Z1^cqTMWsB?05!Ee*ix95}&g9yS4GoEHKznxC@`VsNjtQUY$xpND{!{)`+=(@9 zcM-4!6Wz+!h4dH8X{Sdud0#y!Z$MJFbYM1`Jb}O}@w8Btj~;2bpc5l2x(g@7;xk@- z1M7lm^a@(tYG2{k*C-ADnD!1m9_s63D|-O+#`JVb?0k2-LnVtofRSwSk)=GE=ZXx=;NmM zxsOE!kK}#Rda(oi3u4%U3GqvqyFFRx>^oDK%Rzm>ySn(>+u{yy!DT&l@~tT>@E?7^ z7EIvpa7&VB<3(!w%Tw6E`yzo=_^aA{wf1?gvSIfSHnC+5VaFZsvUdn5PtT5DOXuqs z@yJ!5C00_{iJhMp1Bqh^-PB+)T^#p+XBE@bxr=G-Gf&h3fpw`#*_HS!?3eQ4R%d4Z zz7b#xAI&miZ1-R~C3h)}9`}g*XyE)&S()37-5$r!#YF!LtM>TUrKW3EQ2XZE@o1K+ z&q!cLc75MQ=uy5d{qtKZUz5;kS5j%Gsny|ZIHAQu7tx^$?D=o-jMXZr#)_3y-T;|2=^R^dLBBxTc2 zwmI1Ws7SS{1;FXq!pOD}2m8Q;8mqtQpx*Hf7g}Td{JwqcL0kt_^!x z>?06Zg~vvc77w&w=QAVNm&a-H30I)UHYZZm%`}+g1=PLrbUNnnayV{PhyI&0QT3D& zo7XdnWqnDJu>}*jNBEe7IlJ(&1#9wdh7dU>92WxJuzMEWXPm<0IIzHs?fnqNMp-5Z z1XkhfB>p@PGGW=PBbfQXO>*Pg?(}`YOd3YBpu$x({q%D(9e684CytnN7Oa|4Q&xCz ztq=z$Ht`JbJ=>lB`&Klzw-x&sFSB7k4$9bqiC44K)L(xrjqj7qTeZs9 zlzklAkcD+A5D2WoJt9dir!3j@I^k@x#U7!rF!A%8nsy&GnZ6yC$$gw0Ysm(lXviAh z-6{}Rh5L=4jPP}*|Gv?u->_!O`+GB++?N7@RTuMA)GN3b9ez%m zrS~(IuU&n2WAD%Elh8IQT0FQt9m`J`?%hR2A1v-b^;R5&8*gjVe^*%kX>P-MR&!@} zI_nW^!99rY4|7(?S0;Awl?hB>6>gy<4Kuc3pYuJ~B&UxuwqRma zu8J1^?ny8I(8h7J*qXJQ?#0xN-v|U&iIK+)uwgZBy0R;Lr3gokTWIH~qNj>tsX;sK z=}B7(&DnguQq+&H6k!V{thUsq|E_o)o@>MW*H>jVms$!0RvG>Zr7dW!QjO zHq6zhJS&=3nVg&+N;@A8qn-K5%#YGT>Dwxe=(RCtAf$V3`tJ(lxP>-sbEOK*Z=D0d z7ECle5K7DOv$2Qpv$6U7>ajVq<|}v8_{tq7unM=3Ux|xt*i*i8*NU&)VGAaXz6_=P zSGS}sdL8FJF3sU_RC8u6n_3G5R*8{spJu~MCfcxzd?gh}j$8P=O(+d745d9zU*JCc zE}OIdd?mFqUrEIlOla(C(|=cl%B7&=tSx(1ClegXv*6`n+s~zTY=%wx|6Ur7*lc!4^!6 zeH%jiHu0d%dtc)|$ZT^K_*Rc4@Re;$U=?m5f8qq&u=X(qY#(3Q#uiMNJBHFt{M77v zHMG^4Yg^c`?G25YE4T^-R*8{s*w-KR^6EvLfs3TY0D2qQK4%XQ`EB5>N5v6%GAlQP5udaMF1NiCI z-?TZ9M+Ta)jy7kNa#utGt8fc>WwD7hyS4Cw@_29v!4^y;Hw>W>*%fH~Chf^aPh@L0 zvFi;bQVJ3XtP&$1)|5Zb`A*zzz7vNd$1&Yx!F22~iKac))}K$wHD&&MCvFzsiNh9w zI8=+qmF+0zy|!dS+vX@ELmLUiO{BWNBbeIe{Lql;kGK!hM;2^be3H^_XmjFk5={H5 zk7&N$dJf^Of@x;@ZO!Gpr;stA7X5dJ_j(OW7W{U;QtNXh!4^!6>>Ny|rQg@wjDE^} zEdOM}!t|FbFZs?WCa?;(kiU5iw`7Fxj2fplCD?+A=Yxak9>XV^od>o1oIX1(*}n4Y zl*_MpU!iERN{l=<+kyq(nxa_qooXC8Zej4xAlmHwK~15XcE5HTn6Pntr#gb~RAUP! zPL-=g|IIb#&WjQVtm^+Xh%VlqrtjK0b7ua%ma?EtYmyQcMAvMX zs40ki17{`&QL=K0X0rEdIC;R8-Y?CD;HQzSHD@c@2PlVn#u9A7MC&y{bn}+A8Z|#N zmETJi7_;k*8!JXUX95#ggp!9;jw5S902XrA`c`f#se!MYa5 zD@h-t1p=$Y$ZfOD*qYoM^tE$4GVfX-P4@EEY&-Q9e2N3<{RttODOqpfc~@6DxGbN# z+etGv(d{*5JKGX$!NiivLG&E!raAvro1M`2x)GClTPrtO#0dme;U1Bs*RJL)>{A5= zBE`PK#1T~xtsgv2)48kG$5NF!OS7+{sCe!N{$E&yN0z^<%{61K4;`bG62!=HOpiAO z(tS0pG}U@)&nmWSX2iY>E1)M^wkOzvi6JJg^xwRt;lzxE`Yocdt>Xj&tG3S$q;thi!WlegW(yWY)Cyow*v}4D|`AP5|w)+Iqi%la7#`wO6IXi07ZKWA$l4Nnx zl)X6iR?{;)o?r_m)&>RAGfABaetBtgaUP#HWCtgNQT5CY0)bVyg_5Li#oz7@#!+@A zj$jKWHjECW5zWpNTvW7iT&ZiuuE$KLXJ&~6R*8`h+hWQ}%6HO)4ih8CG1a^iK$j_V zLZPiTj=RGR*?4zDjX}AN1Y0oCJ-#M&E6dWWJ=m0aFZNYGS`jZ0Sheg(W?R+1Jm(HuFk!1-lTI$pbd)3` zPg54P$OT5sjTZ>4TGu^*j_LebHS+&Xf-b+*gjKP)3EhUokr&(iX|KjJ)lXvhNzhmP z>77Xf)V?>~LSTFiTEDEOp~?XhHmgwqn4OLz*n)}J&;UAVu!DN`A?*nE-fzHG8!mu@ zCpriOR^b-%yQrlptF^a3xOR>w*n$bqmI1V5iHZ8#E3FUn@}{i#T|00cED~5HM(*;% zm`&kX#fNxS@x*U_v~k08>b`wn!TKM5ba9un>WRZ&LF?VsX=GU*vZI{|d(gm1ZvUz+ z!4^!k@9IyNjNPENB-(q)Mk52Jf5BKbZrffUunPAfKXZAC30r1b0+S8I-o?b1G(Jv6 zDeC(s+S9CRrkJn`36CL@hy+&Qk(H$2aAP*-d5oO0rZthH{OH6k77)Ag8RW$K(W{|m zpuYDEX4zJ!fAY5_>1u>Av)>ji-`m!jU<)P&ck!cOY6?5_w5JXouCLFQsfawsD^4J= z3ilz;raEEF@_PixmG86>`U(@LZ~D=#y>6+4FKJI`a^)*t-zT}t?t{efz$!el{2WLd zV>WSU2f1P`F>)M}>lI&GsB(o}gSDp)-B#(b^r?MhgSfT?TQG5ML^b-ota_mKP$TyB z?QnU-n^ppWRi6&|Qk&nkA@H7d4wn*Y$PP`KBaiwXO*~6{=$#Rc8^ijk+Vg#GmX}!gj~Q~#$kqaZ zRk(%xX<%u@8m*lyJIbvHwqPPN!;=`XXy>~h+8VJ}6GqFKR3xxUjNJ6T0b8(U zzPxgp7&(sV)lwfiVPYS!w9>wRgw6P=)UsG2chR&W*n)}VhA#BqimGZ=3|Q;w%jE4V zq67k~oRfWMPN)9RWs&w|ZsRJym8sWv$h*!oC*L1=(W1-@XxI597#VxhBh}L(?cOOE z<64#esW;+zeZ77w=YDOMr$6FVTgZZmN%r2)v$Gn^{o%+GP-l7TJ32$CPz)Uua3N1rvMpeW>m1 zM3|bOJp)@=^-Y;sm?58O7$Xo^h5L=~pU>83PK#H`%Z;K4wqU|F%7?!1GaAZu(AF*m zJ<(^~+os9&dy52CiR1Az@SAeHus|-(Zbt5d7wz_YH%uFR2;3_=(?3;ht#5nM(*X)t zx7428lD7D(l59uigY%jZY{A6wtDcm6QJ~gGZ7xpV)g{X4h(q$ZkY>ck(TV=4ue)~I zgBH)Y2hJU~fkPWlnq2EFY%$o+2?L+c%8}$kxo>DQZKWRle&`dpwaWrbJpJHA?>G4Y z73?=~!g>BHWt;gC`2hb`3btSZ`{wTkM#YM=`%(GPt0;lMs{IjFXwj`7&Y$iu}Z-Gl==V&@i{R;Z0wIdjFzKQa9`WbnVYj1)rnE0-lqp6i>Ccmt| zg%jOjHGJrBR?Z#UpG0r6P=_R1$nj(=#COV59lvQIpW$`erycTD|JH4f4j2QeP0q@_ zPW30)f{9NN3suwfEamyrwYgD?I(f^zTJcKnDt(Abe~x+tZ~On_>aF9dc;5H_V^3Y{AQt?gi0JT2Z+9R8kcsfBr1&Q-jhDxr- z&B&Ll`u`(cG9&k^W|OlSz5*e*^1Dk9`OWhE{AM}N;f+lplZ(>H-FBmua|g=G1z$@L zp9Xv7h8bn$|J~K!U!j~_KDh*mDZQ5yc}FjkbK~{%T_Y7#kZ@#G~AdRlLolfRyqlD)p#-_a1v~mgZcJChHS>b0t60gv& zw&}#F>qrHk2_(d4aID8A>NziyOq(MT=n^|26x_W@>)ps8EiH#Ds33vQJn#P9BaeQV zluml}cN7S8;ro%#+pB$`@iQ-wzh?$3s30M}69?t~pssF|SkE3P5a<%$yEbu4soT^n zl1w}l>`Z{qw%Da$D~qM`e_tU3dbum8Ac5}{et$53J?&HFIyr7|69{xgjD4m$&&rbn z)-wJ#KWlr4K3sT}be`y<2nxJ?@VCy_!qd*sZSAg*Yq3rOfvziK%W2ifSvkO7?+^Di z{3>nYmrin%MkuHtfxmU0is*NrhR&hnPj7x35PlZAaQ4BgiO?@}s`*)RW{ZO`%RmCZ zQTYk%oFY1@bRwC*K%B{-3+F`qWX-En>SdE;GMG$Kun!0J=O{>ZO&sqzOMd_AEB~J_ zF|*Nfe3D3d!6XG0B-C^*>C5|Ba~5Q+-giDm4p*5f5a_ZP?3Wn7#8G~}@fRoR zhRT}no&)6Cv#AOyNIdeQNt@~qmp@qOgwG|W+PH2b^}Egx2z0f`2})eswY6+N(7^kb z{Ak!)tG!|a=~HQ@f(jD5O0uLmw_D3UO6x?s@D%k`?h>*fWR^gntKq?jL=Vrh@{IhF zoUp#sU$f4SAVVC36;zNYvzH|$n48Gi>vZBn%}jM#p$AFcKU*Ns)ox03;>1SD(usGa zIni?PAg$BDA>_rRISMLBm<~%$8nxoQGJy0_Qwzse zsCK5NvTtSyeT)N{T20xL_|6PbP(cF!n*5w)jUQT>TM^{`;UIxPSLeAzH9Of>ZV~X8 zKOciSr)qX|30XBFNI?Y&{8aMiW7Zd~Mvo0-=91|Gfi5*)R_8n#A$OXh-+djiIa&Kv zejEAMXu5(568LoSQ>>ZqwB%|B$lzI11Oi>p6J$YP zB=9Z4*LNLXYK!-tBevTD1p-~C5+v2zf2DkTp1%6wNKb1)vl!_zEKorO34Gh}y}Lgr zw6V4M47r}aK%nbVB{j)v_Az;_ycK|<_>^u_e3n%NNiipZco?+%8+s)sbpw9Rk@%)=a=V}r9Uc$ zYh~@i6jYE1=+#^8;9Nzusj3sb=j3WPwp`G*P7n#f)$n4{#<79wVxkiRI+#%M>w#u( zGgmQyf<)@J-s(~lFLlj&z0*{eC3)JqGL@;z6aEYWfv%hLFD4DRzeP0((}|266B_=& znl28Tqo9Js*T22h##`2_i|^_0#P@UVY7V0Y(30`91p-}8k1i&8wz;UTo}&{xyvotd z*`w+5AHfPLNL+L8qb|9<`Y>OCZqY&@&~e!S7e9V`rU+cvOz= zFB?V6uAHf$f<%4RM?DeuRNcB=|NgKtxu^L~-AuQRoh}gQ^8GI*sc}UU?fhQ-?ek@* zDcyNuCrzn0RY3)bnEHLytD{P5-RkJXuD$m(>x*aTy{3}{0$oE5sYxMSYidJw|Kp#; zCx=aG|F-98#Wns4DoET4@2g57)wIo9^!L@SX7{y5yKd8SDZDCzpM|cdaj8jD@>^== ze!n@f;HN2lSN9()>2ro|QTH`=xq#lX9w!j!iqcY(8a=nw z{MUWsM8%F~)OA1+jn5dPpn}ACxu1H++D5y)PwzU^>cV}kgs&-U&~3CppzB=Cv?Lqb z!P>44`WtS?U^BWUvI1+tZ(*Z?gu|wO>eOI+&2hNChCKZIeeFky8f;>n!2*G7pGE(BFye`S0qYMN_sizo$T;tIDOc zq#u+0HLDBydZJR*jAmSD!Gc011r;R54C=4GIq0i(|E=Eu^(=Q^bL-QIg(h?s2y~UL zo1S#4Nr-kkRqrrf_LM30-q4jr)Zq6yK|x~g*8b}7@j;rEnNDPNzQ@-J6*eKenLwZ` zGaxZe8eSIO754j#ySLTU*F zx;~vuPny#|T3b3Nn-h)syTl}KFuRvnRY3)bzTF3?on9^0?&MtIMB1)At>wEB%)L|v zfk4;5-|0y$H?7bL`lNB<$7B;arrc<@V@Np#6(oLy4N&h%%e8>rshs%z{tnNwAIna- z{v$}B>!@u;67yfHRj2yOUH9Q-spD5SR=@E#f(jC+=>XNwVvT0sTqoB2xuvCz@Miby zo(lxJ>IP>d(WG_S&jS61TYjZ7wBarv_ICC?f(jDzehpCFJ>s;LzB=JK{f6dr%b)#u zoFWkDig=ijRO)-Yb|Ga4CyqXi)ap8iv)oOkWb6rto!`X%aD6s3*9NW+XRp`PlTkqe z?+Ea&T$g1nZdf>5dB9g7&=q(uGwEpfLG7SPYyPjgM3{QgDV&Ypzf?vA2}|$aiEBO{ z)bcv%gh$0*+JFu7*u|ktAkek-cxDn^x?ihOG@KKy?p;vdOrFO^y}u`;f<&qR3KBQ} z-mg9EID!*iKl^Ggn}xAV6H9^wx>ko~CLP?iSBp3~n-gm+(^cOCb6I`Xkf4IZw|nms z=UXLc)e3dukB_}}IeHFr9y3@V&~?5`W|IAaom%$aRh)=DdRgrmJ)2E(@Fu7r@w(>A z#G=BT+J;7}IT2QOh_pmy$swMi3Vr;7TPDG-|l&guWlA^Wv18vYc%3`vYD0-Nn}#+TB;TB=uxvU7HKv zQAo5on334XYPPnu^aDOdRIHm;dtrAL|62SWL>GPs8w{;~-d7Lo?98nCb`id7k=QdZ zHSx1+fVRB!b3R6VM|Z8^kyfm?w=59o!np+R-Wu>gHJj3mMMd=z<_t(Qczr%`#__S* z?S=ZhBzK{^R_A_Q*0_SbK%fifLXDmHa$?UB%85{y!Q?&NK|T?lo)nh(iS||=ZUjJ+_jDK4Q%nx zu>yfEoTKuz0;dP+^QqtIt&$$XToj4rDW?qTMW^3a z7uqDzS*<1uwE+_IN*qgU^ut8+xvf_dd+NDq9ZmPrHXEl21iG;H;rpCf_tcGP@$~Gp z844;${MdFV@kquS)oHw5N4*IgtFabKY14YM1Oi=H!}0o~;yraimk2s`t61G3F^%j` zoKTpeemtbtgEzO0(V}*ZrDe9v7OFdRVJ*scusY_e)4d1L(b-~^ip1M{dlFA<-Ky?8 zuGh7fj=O5EHqB^ohq*$PD!8CR<~@G9+*QNQR-*^%@%kJTBz!`5CXT)~MRlB|*XPlD zT(q?ZUTO1xiG<)1Rt_?; z2?V-^dfTg{!vSsGf>!*gU00uK^&IB04D)3&DoEh`k>5VE{G+?iX`I5HQ zC4|Klc@b2Q!1*ITy<=*iJ$z=eGNYFY1iIFF+o=cRw`d*%^jY7B%h}q{sx#P2lMMtF zByj%7d$&21q@^xQW<&2D6bN+rb+A*9b>FDDP1bjKKhG~k&#M8f%6yfef&|t(e8=Qw zKU&%(l*J~S$=F*PJ7|l2w(Uo?qccm*WtYqw$*3TKpJ`s#mY3+hZlUb^FMokR*QOck z)W2o+X+0BK^8d%L_$IVW*}2U3> z)^xhnZ1!(OLxKtt_?hONRa*?87B7QXsl|f?0$pRi#Hq`^Y}2gouH<9%e$6ufqxKZ-tC>dIoB3j_jPy-UWa5kHn_ z^|q$)G0vsh(ki1}SheILf(jD2+F~#~@8m=+;)b&ueM}T2(6!`BtlECZLT!ku?;E&x zlj*+S!`QHD_*KDoi^y_a-01(x1@mkptLs z|C$OaNZ{(1!SE@?g}%!ntcz+b5a^oX602tBOx0TD=qCX$k5=e{aT43Ht*L?v61a-T zE66xk>TcDE)!W!sAkek2R;;?by0`Y?=o3DM!#{eHUtI(1S|K>}AJ`TwKp7~0pi zDSMyOLm<$Vn;WCL2aMDXRCvwDh;Zvk2UcvvK1@&)RFJ?`RlefYe+*5UT!Ve=(O)3Y zbvrgjt@5z1Hjrmz^RsI6deUEItFj{AhaMFqaCMkJQSummDBg@!S~yG~(DiFbjB2~I zv$m%}0Usl8a!-0Ws4NTO-KJ4N0#~{DUCTeNbl8kf&{MC^V10{TDG=z|!`7-_Us-AApZ(!u1YcI@q4L-1 zn$tcCDoEh21MgZ_)|Dotoukjq`~(7BC4<+h1LFUwBRlJ74GuXfbfZrq{q)seK?Moi zJ>k7xyj|#}jq$YPwXZSAyjz}+m~H|mKKtxaK?MoiUF7#5%}3LLEv{(wOhf`*tt{54i{_P5cNFSl)HrEN zvrC-NBKFQvP(cEBNqN7F-y`W2yK!2BQX+w_Bk8ME`)H@6ymop8+5Bt|>RG9sHZmks zK?Moi?d91u0VC*=%)>pNh0YNObk&kqt98CzvRzk3AH(TEcUrso4XMP*Pz4nv#L8>y z`eC%zpKY?^t=R&BuD2&wsq1UcmloC4e^)MTy3!X1v*b$ga}-pN5Now71087SfhuHi zxe$Rs7eCvgw!WSvja#jMcE?+FqHmWrCmkX~^fN3*1qnP8!aLoru%}P@4g9HLy z6_2k}Cp(vy&1UM)dBVDOH1C5aalR6y2nw7+!80LzCvI*(nv)$tD(;^y5a=4yWu+Q@ zt%LmftiDpT`Ee_Ha`_VS=-PAz6(sOX2=9O?^`hN&ttT1BrU(SO>ZvQ#&6h^Y(^P$* z^N3k_&J#h zN3@r7b4h%`1c5-8y=hX?%zHQGNeeFXF&=ug)!vTICm$;MDySeKo)+nzbWp9<;2ue} z5(#vPIap^7ETBzng4uH$D;e{gFttg{cG}uz8Z8$a!oIpSlTkqeD@*=2KRurw92v|` zwU{gr=-NL&T|M=0w>ElK3;sVhT@gULM20XYd4-G$5?ERCn)6yD9p^ZU#Vv)ZHbx(=y znpde=e2o9*&7|(VgV@Az4GAhpU}ecy4Vpz$_eIm#KsHby&^796ntI{R7Hwp{-mRzK z?b)<<<}_yN=1EXN0xL`YUE5+Abw3=)%u}NU0$ou-Y3dPWy>?>ce|!wLz;G%{f$XHq zI)VxkSXuJD?d2<|Pu2uBaKe6pK-aroX{!J27_Gxt{q}&(ln7e2iZ5F;@;E^S39Kyn z%H6+}G{1%yEBhu{AkYZiwMwhnO>!jNSKW(cOvxmuAc2)7|8^d`ns(vc z#d@+_fk2mMR;pTk*D`JL&2xN=s(%*HJ(b3?)j5v|Do9{u$=}qQ*HFvNqu88tp9KP4 zotLJnG1-f??6w#A7#1}bQOBnv*=4)m1QjH(PUP9k$Jf$9>mAr2Rz^VrU6uQ!sxN~g zv~%6`w@+Ei#dO=;!L0j!-s=SvB(SpNvy6=~^v{UCtWriLfk0Q|?bfvn23KCdZ@?A^&Sn74bh9zg#7YKB1-ow}Pr}}Fp>g#XnhEt+ww`<+l zyQ_^ARFJ^R(qPC;j-@?{+OQ9kS_=fao;aqcyN`|4N<7p1WyIWwqAAB(vBM)eD5xNT zl_h`s7~*J1b8EJDQg?wsSJ=;s>g7M1sokFl#vG<6NPWH&0?DX1WUl_fvP@hX~;_c z!PWDk`lUfz?e}ke?{4XfDB9>RztefuQ89pm1Xh;(sofn*{~mZp&BI3v1iEYEc`aKpbq8m$hphZn)D5xNTl_fvler64I`esV&{hBTi z=rY-mtoC`(UETdxA7kyeg>8qCJV)wb?TT0$n}3C#$7C z+)1kMqgTSG-4{~toOrEKUn>%ud!z=|AB(SpN z|Ekl==)2q+q`$)qfk0R8X-)Opd0X;O_23K$nxZ zs&;SIRnGse=PtEsJ(Hg8xrE#*n5>|J1Xh*?LsF-Ol%%gCQC!Vg(7TEcp&rPy{WvG=Us@=_e5A8eyHJKB^loS0473k1?uX zBAqe*FljPpqJjz%SXuJf>(Vf~uSZd&pZA7i1Cr_E2toWl_fv%`}v^O z)i<9c44fbk=n`|0BWJhKoSg5H`-6QIRFDvB&MOsbXe{;yx%|#gAkc-G%=}yJNrbx6 zFPqGg{e`qJ(2V~*mO5^r=I3XyRpzT?RFJ@Wm#_8B+f8Sg zOk*p4UJwX$efRvXcCY-OcJQAAALG*7P4xcw>8!WILm3q$uzKaIwXq3wZ`moVu!bc; z0$pa+zN?C5yte=93_eEJf_VD0?o<|Cw;@3V39NVd47uDvdNd<|l{#%N5a`-}`kPwe z!3M2v+;Tof#=z~gePAGKT*iZ-f&|vP21C%1BQ)~l1lDj_lt7?M>-$YjBr&`@#a2GX z-3z;Dcm-3KCfF@-q`L$Em!>gI$`FAQ0$!Uh&Y(52KYR87xEY9Y?&`4}f%5744dLzqS3cY+EMSiSOYB)iYh)(r+Q$BU&D zBm@^LP?uhsqc!fI$;SwscaX-IB(UB!7&a!Hr7y3`tlDBrfk4-J_X72U z*%ZzC#x*|1Q=db$<^_orZLg}Jf&|vPyt}dYIhtzIiM8)lS0K>EetcEu_3_dYKkGd+ zJxvbN)yW;$IIo5ZDo9|x%ijz)&(TFQnz7UIEd&Bx3s!tpAI%%7osQGbq*nGjOrLCT z!V-40RZu|!>s@{~qv#y{xU&{JGqQ_7pzBE8uWHiee%hWy{kwKh7k&4 z1lGI!l-|R0wBy_IET&sefk0Q`zAtJQsjKGDTfh0T#rrUgi!@_CxqTH>kidG^Uf(jB?@A8{SHO|q)tsc>z zk;4T7T{X{rRzu$No|*sYx3J&rIYf_Nyi2F97_A5j)X`Y)>faw{smHYov`vnSK%i@( z@>y-~RZ8m?sLvCR)H_6%Pta&Yl$(MI5?Jr@dv|$fXp?ul>D9aAL;~vNDk-1TN*AA~ znLG8``R|g0^iTAEG`6p|f(rgztatg1+*W7kpL0uSiL*Wefv)j(pVU+3sCsFjKBxA0 zbAb9!Sx7A&_$sI%f%UGzFd^hLJzU+5)?MT$5a@cA^-=Yr8&qds{cP>_0S73_9Zo+6 z1SqH=f%Pu$pqzG!+S;_B-N%Xqy1qDmRBu+DpjMr)*B_0x@27r4>eD?IlND5uz*_g4AkcO9&Ii?}el6A7La)ykeceYZUB9PQemO-!1qrNo4F+lSNor~q zqg63CHNDYgDfMYO+9}t98|Pe5ZQ7GD!RS^`Zqp{xQ{bYiV&@0{R5!QW@K%nbu=eKH`9#18bsh@zD_-O|nxw##= za%8fC3KCfF^3>4J2dUHAk)&mr0D(Z)8rL`Kgs0Wy%M-VD9YR)NJxnnc^ofy14o<6%3O)^p^DySfV^)7!?TkoaM zw#5;%`V#~KT`f+(Qdd;=klmZ;y;yI@Zla&6Z6T#(Uj-E;u-@e>kR^7}i3|6Tv8mny zfiCM0FV%U5NV$8Y-si6K^7VAS<3Vyg*GEAG39NVdd4}iz(SI=~NYM^Yfk4-rmM_&l zDKYXE*N1$J#+zeluR~`^sgqs`Do9}UYA_6Kx0YVtbCGoY=OGa2I_-H@m9C$VcP-XW zg$1R|q^rU&6Z0!x3Mxooy~}6efv&Vl@J&*El1QLyQu}4<{0X<^{gLT>jOcA`=;WEX zWYY_81r;Q)-sQ8`&eiFZP3Cu|`G( z39NVdZupRNx@D0+D@;xi2y|6yR9TA{xmla64&r0nvC-&;u7Pav;zu$nNMQBK^NOBd zqQm?6v48a~2@>d9|Fx3Vx&H?3cf)CXjG0%Gso&v=%qzp1pn?R}yZpT9<7_&V`7pmJ zb^?Je^Rtz--KMeH<8sUR82e79Q0KGbS^RK!f(jB?@A6)(7B^^l-*N1o$zp*(SIg;@ zv^JhAwT5-$`4}tI49XJ6v4K(yK?Mn{cX?WY(`{O!i3=N1caK1z>$rU-E$GuyZRIDu zE7zMYmuVTEiB!MLVS)-0Snu-vLHk@fQ69-=uTByObRDW&N&8(sN;8c;%*VJ^;R>x) zV-zc@lR{8I0_$BqZ?ATjx_S&@9S7tH1iDInu+o|zjnvxwImO4YWZCrEt08RP)O>;p z5?Jr@6DddXX>i~GwzlRQfk4-`b5>f=-cZe=F5_eDx4lMptQ)|rvcD2kkihDd?~Iz< zrw<1yY{Tdh3KHmAuz>$RUQN~FUh8))PXu45UR4$5>sD4l1qrNodGBb;2lQV-7q&aK zf(qTdly*s=MtNy8yA}CNtW4+7wCXye}yDqI*y*9N30$n@I zth7sx&f4t3`ptXme>pT`NK2OGQC~p?39NVdea(x#- z=+R16Y~s4E3Mxooy~|fWPCTHGTbE&pO(lUq*CS%7b&^_Z)$8bc!fy9+sCDO3Z2r@p z3Mxoo^=dFIZt#F+R{21et?DNb=-U3RqPFEtZEe#FeZ4(ocn)23<2Aiqa-f0=5?Jr@ zmF=Ghu1>Gg{a0)eh_hbn5(1!mg9>U#H!_ZzQMNz0;Vc*kB;kPzx!L-?$F)MnHP zIy-5kK%i@}S4GX?^%wQ%5q+K*apfBQcl`*piE~y^K?3VtzLv2(pEfI6Py0`D6$o^N zSFfm@HoL0+J+ALNcldRc`bWml4*%Q~RFJ@Wm+$udcb5jd4xypn-30<&BeE>CJ>mP+ z?@fO4F`6~HN-Y{qrM>OF6jYGFdY8|4&*jl3mVIf^Op!oWp9l->>eNN*+=}{X!}Y_n zsTyxf>#P{Bpn?R}yPSBEOPya>(ZeN00$tHvEwuDa})hx!=ze_p01Zrf;9i~JQ-kidGE_v8q@O`V$#;PA1@H-s(i{^o4@Rf)TElee)S?Ym4+_s zOd4JHRZu|!>s|i#DRq^m&Tt}e_q+uHUG+PdYn5x%lc#U_!pC_2?gCw0cLI67ZM=dC z5?Jr@HRQHg^!w@vvSYWWK%i^)5i>1sPH(yUV7=z7`Dm>^#rpnrc9-csq2ahu4)s-6leNMOCoZ+c%(rQQDQBvU52 z2?V;Toi^2?e=d}V9njB4bymZ!4F_$A}toie7X)MgFvMQ&2$y>s>yRiB6ac64s@|-uz@o@G4c-i{=`!t(1o3q`53ls==%A0NaZFzLeFI+u-@erH~ZYF zn~bTmrt6w$Ax}4Hb{`)8{}OLc6h5Lac8zCcm-iNOUy;Ci*I-zA^gy2LEglPjOl?glSbbDXu1Oo{~7yZj_z^e0+4V=Qxe z)?XmdCFYE_eEWi4U~W7ucC3&ZiUiiX{47qbLfYc`X!gQJOeRGaCVld5y6$gj&sj*eMX`67xBC@!4_d`;IKU$pIm46A7$$`67`MX z#8z6J5eRf)jwZhWTImxVvTiUN5hLb|B7yZT-z(brhpzPL$Ie-13pu0c!cdJ{JgdVHPF7D>LaUwfRKYuKOQ^%t<7$dgb3A z|NWzvx^!jxe*O^%bYYsL!Eo@ffiBE& zH@2EUpbJwNdGDQ4->BzSYxdw)Z6R|K z39NSw2K$``wqjW|wnS+t5a`0}L;loO|3)KMR%Oh;nUHaa1lGI!2G2YL+mUC=BKx%w z2y|h3A>aSFP)I$(%dtPBI|^BiNMOCo>+>cC7PRdLtsK%#Akc-Gf&ANtG>M4+*SydAj_UKeWQFopffw5P?7!rseVdk1}7V zXOsWvnwP_cY(ONi-sSt8Cw|lTdePLJC$izsLKkM#@t))_K2bVnA&vRwBxKPcf%Pum zyPN-uPB`dF$A&ly1iCQWjo(VS`jH-AKY|v$;#pge&xZuoyZp?y_fKlJtQkGGRV2`b zd2W1XH2VV$yxf4cyz4Hc*CB!RF8_b{{Gih|f6(6Ny9orkFhz~u;CcFs`JR7yg|lS;cA-M~@Q-bYTt}-$i3Y>1Oi=Rp4Y*?Z|MBEmGayVUPAU65?JpV3~z(J z(xn^U$_f3(2?V;t6|*P$&!_B0)Z|}xZ@u%$4G&6Mj6U?&f~v_60W~aS92n zclo{4{C70cjo)Nl?jjKA!el7^zH0NBYU`rN_M>Bj94sWT-sO7}g|DgigtcVNHYb5V z7bYL^3bNV*`n2B$(nNI;GLewLdY7lyrM;lhZ~r4Bo{ka-bYX%MPv^?GOLtA(L%#lS z5|WybzEu!h4cs{u-@gXQNcIqL@9~% z?mtQ((1pnr{C4JXm6p~nlC|%gg-i=1u-@fwxMzo{zm`Q(`EM707P^GY4ufl}4Rpop z>tuTJSRtDO39NSw2Im9IY5c1j#J!EXK%fh=NBAu|zsdB(`J1G44NoCs1PQSc4%-?? zng2E7V&f$c=yJ+GtXjM`A-6{8U2aUzInzUNS4izTJ_;&GhIb4l=w4&<#$nJRFLS{wWVBc=tj-D zev!ma&^^c_zSh3%OHrsmpexp{vRu4hJ8buJ^2^MJ#rBJnQ9;6^QcF4h?RstO^G5uC ze!kUxLYIwa<3iH}0$rw!D$9|^{n|PGUz3t`y_oNdCo(EX{CL_zo|qD+wXbT=$1pd0 zOsduJW(@-^2@>d9`L&WibRl-}z?z*YZT@p6TT9A5Zr9;$q=ng~a01-y{p;3GCdO*GR|i-mGjHcY#0`{?_@s zUAjo_D!weZtG)2sMdDf2?^5wea)W6W2_E3f>b(;Gg6P7}g2C`8kdc1}{n=7i@l%4t zb}koa z0)Z}KR#ra#ce^%qST27vY^i^YT=_GF$>r(3+{Cfg{u4+9pY>Ru6Zy#BP%wFon#(a53P(h*;9Ux6K_9S0bbX#tyxwFRWz6k`n zPXA1|E$*$pc12lIV%ius`0HPS3K9dt21xgfz12_V({-)R#XN(lQF(t3d-=gEXO;Aul zLJsdM$;OP4rmyeGqyD=bfq`AXuH{%B@}+l zgdE*&Nn17xRZu}f+SXfIVayV$dOKHkv`EoDd4vfBy0XS!uzkPjzoYiJd=G{80)%`2?V+>9nG{Y&Vq0+_#_WJHJ3FTbzepWiGSVfrNPFo zz>gy?$_M++WrwR;5+u-dX?CVIb?1QjHHzqgW$Pfdi}4v9F{o%vs~5D0W_cQ24W8t?X zEBUhV)Z~^fH;CuZhV1F|W&(jOpA}!F$Hu#Tr|LW;YkX_7P4!wTs375xX(`Vzo|=^U z-ymNWR%MGncN7S8t*-l3QjK@}PW*a6ZrNL~lKs0Vs31WWS<1zyCKF5DAfs-Zu*fa4 zK%nc+zAsW&1csKm!I-kD!$t{z0EyRZTEgUjJMTA1&MI4 zit-TSsmYFguaQN^w$QaMV+8_TKQDfgsu=I~o$Z-V`Yc*W?W>PfP(fmL^@{Qt-n^!!BZg6HPG&pbjEnMZ{~=*Wa5?y)S<73f(jB2Sr+nMLh(Fu8@%JHR(m-D-h_)b^IvZ zG2ZR7+?Y#dIF+EK6UQs4AQ92kLe4avnsoo0MSiutp@r0#C=lp6f9HebYrNa%nQ@04 z%-+p&Kz$WdkQn%`f;`B0YI04NEK(RZO;h^$3k13n-9JcmjCcFy|G7>2gxA&jTl*=f zAaQ(01=-qoYBD_FGMT$$wd(W4Um(zR_r-h3;`#sX_W8EIO*+-t*&~VH&O`-?8!i>( zIOC~FQ};{c5iKMCS0X?l(ADVoJ88f1ZePLeo5Uu5wp?YXpMnY!A(zU_zQ$9N%jac~ z_bsyJA&vb70$tUrzLQ*ycl$QH$suDC{>qNkd=*rXSU}3l3yh~GtB*<})_oe0k2C!Q z0$ukzzm-}U@Aj=Za*agw?M9YL;}ukpusCHd7oVE^n{$!GbZ{cAM^6w4bcMOTk;WVE z_L)`7CPh)cM-UTpAAvyEt3|J+;=6qw?Jtvy0nwz| zJr4yHB(@(hlZ#JHZhxEQKqMU34P(%g;c*;AbF_K-bDs z&!yrskadr%#Dwn^t>=41s337^Y&p3&W8LxDVG_XiiZ1cJA|%i?YwRUHR+=<+O5nu8 z5h_`~ID;I0<)om3#JK}y<$|vzh))B(Q%L2{uSuyPDP-+z2jyGi=5qX_@ABZ6JLT>6 zwdK&;f8d5;_@s6c86FK29D3?r~nn9NIcT`Y80{>6^EKZL+@^Ml+>HGg9 z(ABJ3T{)?SD!)k7drdwJze-yArIUL}BNSASz`qUe8|8POgwLVG(1-UmfS-k~S&i$- zh1WOA6*BZbkSYB3X8_-|9Kd%iQ9%MfV+MokxF_WG^P?p2#R!2wSK+aG^0nY-Irf@< zMtIQbTrxfVFiCtoT0sQ~d{+1^q5aQEyU5+dZRjY0Kvz_s`tqGeljLL{{jBqWr}?Bq zza8X3sI!6!68OyXlN`@qk-j(96SJQ@TNZv6x|-(ImwQbfD6;_lo^WYCZ~x;OLv}j4 zDySfV?=IeJ^3hxJ?{pM#%XJnAbX}R=K>oF=sT_Y{T_YF;Wwm&e}8#SJ8uOQByf(xbHle467$PDrJk!i1Oi>-oEym{kCn8!Twfo< z`M_J!!emvC6TBw}DoEg5i{Bm?_l-=8S*dn&_YeqlEjiLiJ{-IzDJNIIo6&E^J7RIW zwl*x^OF;z*oHH5>OWJ%VX=4Mm-Y3Qh1iAuE8q2+gR#q=H)W=xc|2-*PW|vm#ou`5d z5;*te>Dd-Ph?JVGZJpsR5a@a}uCY8h!cFZ}sCP;y%|DPAWen8Bh0jYsK?3LS2E$a7 zpTz1wHTo-btU#bE<4j}u$&wiL>Hz(-+oJAAvbnH5U2SkzP(cD~5re_E?l1EDu^nxh z;35#{%Cu@CAHRQEtyM|C$8x6SC-VK253Q`ZDySfVH5EUtKIAub{ST`aMiR1qrNi`B~0uMP&ZcQ*?gPK!HG4$y!b2%B?Lmm*4tbnbj-5 zk{dr#>A7A56;zPGTAklsF8zw=~eZIGcK%lGa#isIGtM+^rruTHRA6G~g@A^w;TiYn8Ac1Qq z{OsTagK~0o88+Y+PbP(*g|2gzo5?e-5pB}ETt0@+$3o)psyqw3)>c6U30wo>r`zHU zO675t*l@F^0)eh>p3P*dU4yl(4*Hy7Rh@6->5iIg$-zbnDoEg37XOs+F{}gXv7&Xg z1Oi>=2b#$v=DKM2eJ=Ac(w`TSB9A8Q@ssKbDoEg(9KYl4Yf#Drv|yumS_lNX?tE${ zw{{q>4R5U9`B^=nkWBm2j$JxuuAqVht}XIA)!+URkB*&K_R5k1fvzbXo6EndPSw(aNS>!f|X_G{q}O7Y*WZCVJKUOR;K z9^YIR6d(?7PnYWV-m4A!P?8gN4gE>k^bq!?&Ln|ASHBtSq<_Y2z(sNdsZ=?b_2JnC zs2~wIKV3R)%z}9MVG@~qJ(zho^86?GS?G!!zD_DKW&<{xwSWxH4PtKBAIPX6VKpLM zT58OK$eKT$^x?VTHM?38B+zxO**d8>8}O^uVshui40d#8LxKttAvMyay~Zqv^#_B= z-X=3xx->{2&{h6RoV47S4cPo!H0jr3D!bC!lc0h`ovUfmMPnAktS({Xr2AxMD)Upp z@UzfWa3oGD&ITM(w2YW9@n>n4>j)}H3=K+?jvBKdYCoS(BBTA-@e&6F0$q=m#7P5x z{x2JF+t(H3`^fR^LC!IP3KA!KrAftE5T)cuawFfHZA&;W5a{aZ5hoRA1CIAxMM8&p zu)&uz2r5X7Gfk6 zN|kCDvmmw|Tu53@bYjaceh~(ovI-LD>U||vD$WLs`nHzT*fEg3scWVP3jEwhy;G%E#w>^us~3|>E&4N; z8I=VBU7urPrCr8s!1viPq{I83Y<}zN3Mxo^`IaKN8?zvG^@t+1Hrle(=mr9Tu2wFw z(j{Xy;QPt3q~(V$>~qb=3MxoU+>;`GGG;+oACDq0ZnR^4d$kb=boHtgE3GhQ10K8+ zODbizU{2BP6;zNo=9nVwHD*DK{~kr0iyE@9Q8ogBu64OF(l}!_V0M`}e%HAUYwsW_ zs376+^P)7zm<3VMG@6|6RF#FU?<)}Kii?ersv5HaN0p2t?YCO6z&ZmIRFJq7e^I(& z%!1hTEsBs^Wm$)_Lj(d{Nkd{J$(RjTJujBjYiM9I&ks{jK_W-FD19|%K^(jgMOHWe zM1LkY2?V;LOkyNkV>V#Vz=ml(2oyxDc#w>`haSKUbCsq5{ zc$Pq*tDwRfX^Al#u;TO8B(rv`_V3nA1r;P}c2Abfjad*eg$qd6+P$H=ctVvx261q%eaUP`N_D#mQUlD}3G z-}BYwzuSWpRFKH8$E3!_EC{=q5v1w)eR5dpEP+5*(#ciQI%76qM)MUUJpZ2Tw0Ne1 z3KC!asI=0U1+k}gIC=E2I{9M=5(sozbX+C1G-d-%v{**^PijL(Mo(8zLE_YDO`2fL zf+&|UhvXJIl7{O=0$op!t&}DivjKw+MU!5?yvY#LsR}AcG&R?xzQ!zwu_m*~_`eZE z&6^?+=<3*Ir4(h%26V2ym^>Y`gwz@_NkIjP?%t}@&6ovI)pQ!E*nd5#R8Az&^(|?I zw8@wa*lXefGN^kzVVnFFRFHVZk|bwi7R0XC0pymvkCb%~33PStzd|}|%m&OlIG-GR zdx+$g@l#MiqPumH^w5|Ek^XD~nO6S{nQ+-xAkg*k#&W4R8?Z&CxunaTdg%=AL92Pj)!QlO2#iSHEA&q~c_UfhjYI-T~9%ikE^465Bn`O2s`h&jz}Z z%6t!`<|L6o*U0wEq;O*g%$qMJlT_X*-?W`$t=Ay-WtEjH%}nY_3iL^Tl4iBY#aR6i9x1i$cgAP(&dX`3Mxnxw(2DXL>{nBB03R0;)d+~ zJyzcJRV2`r@F&@}o3o!ZznM<-s#uCVaLAB5B+OM%LE>FVPif)MX;Pqf8BT;|T$MkK zwjxg}i3GYz4^6fmx#GMuc%PohIyKcmR{1m|CgF1wRFGJ4Ns*#5Ql(7~^_-u))XQ?0 zheODwz}W(Ut_pjYZGyRpoV`v@?a2-JBR@LmN&21$R!~7AzkwpznVQPJnR?IV4}R(L zv3C(9f9x!QK-bw4%y!Q0*7A?idI#m9U%$yImzR(M@iP@vkjM%plG(|&a*Ke!{Bzah z(FNIb$_BE$^$dYPS4l5wyQ%(g`GbYt&FaXY&+@NtTgju4X$mSxxaP~!oJS+%PE+(f zmT3cc7ig~oWU<9mfk4;WG|l$Q`&n|ZyWX|Va@Sk={jsCuT+n0%6(p7@vb1Jxh&(u1 z&)^BYaaL|wDv6A1Gf5!O71my}ox6L5Jf-G4PE_mtLM~{-$eE-71r;Pb5+upXf2DkT zp59OY$L|yJnA(>}Zasg2Kv(@rs;$-RWAa-2dz>h$_fWRud8u1@UMea`tcbRiiW64< zls_Ur|G&IcB+zxHT$1e!V_xbsB~LEP({9{(+6^j591H6q%`)cWbo+cz?#$C}_VKhE zB+!*r{hV!uu0P~@3Hn)suL-&GVBQtDHSY?H3KBz?*+|8Ggy%I+lOw9|w42wy0)eif zd(9=ANOR(>=&PL8WeVi*vf1R6o1cOT5{CTl(nH=oY5)K0o-}=TeUf%|E?c>voV@nF zy>z4Cpmt|A=jV`HbR$>yg|b&S8p)_2A*=x!UMy)$GL*S2 z)5c#Q(1oYU`QG*giF7f9vO`YGWmJ&B6+M1t!nPSn^bcj@2P6vwy6{vv&x0)Alhk=P zo4x&fUq%H9T+!n>ar0Ud-#fF}OWr*R33TD9a^C&>V;{1rFqj#(HYBJZfop)g<9nyJ zG#GqY>!R^X&y!0%%RMDJme!L8u^sJwPFbFX}}DJ55q~zQ;8J zT{!2*yS!f+Nt->#tDM7U2o)r-2gtu`BYV?FtD{x=`f`mx7tZM`aP zp@IbV0EPJ6&6~RX7^ZSut26>#IOius#KTeaqE?97+WZBff`r!56A|ASbmdNq~M9~ zs-W)OGy+{X=f_h*RwzZ??y9bx@RFz?fjvMWE=wO;wdze3o8+w#=)yTa{)=MAFv{5L zt_GeUi3$?f1LWk{93P55`npPeI8Y!zqvu02j4d2mBT`Undi5gLImob%)F;5%XD*Q$={=?IjlAb~wVA-snB(5078?XPBsY6QA)&X4aE-3%p{ z@IUO#@na+^NMH|8h?pu#X@6a_TSiA~1iEm}Pl(^AhEls3=k3_i7>NoJ*aPIv+@DAa z>0sHv)|spk=)yTaAr4oJrd>Dp*}I-imZ%_sJwX1sdQNol$`-pgak@sJ3+Mc}^70x@ z7apY9@h_%JRFJ?PAiw)W5Uq$@Y`d4t& zy*EWHnPRo-pR5t+!fKM=uX2Lu_y;`Y-ZM#}f&}&e`L|k0Zz`VMqo8h4vPPf_t4Y2M zm^YGs`Q~?H%#irnysECQ9%NGfV?AqS{G{kWFhrDGgBkbh1H}GK{380wl1U7nS4bF>Q^MN z2grNXzU@RlFV@qQqK`BJU06->^@!F!ROy>Rsk^63RFJ?PAm{qdzCqJgWRvgNSdBmz zR+GE|v&5T9*X|{kt5YQ^NMH|;pYfUpMcq0~4_tHtU06->=iS_1w6w^g`+k!pDo9{Q zPl%+7HZ;>dMXz_Bq!H-CYElTdwqCS^ueiGM6<1V{z#brP?ES@!9DK#K9ba)p0$o^5 za@Sx>7mDR;H=Fp{4Jt@rM~}Bzz1xz~_}YyNU%Np9U0O9MZh3d1wY(MBmA3+;f&}&e zc`NX+Zgk%L0w-C=YXrKyYc4ltEPa*y-`T}=?cfc;>%?mWx-dDyL|P^-y&JDCUs-9Qf&^}H;cEN(SMSf6od1#P|KNs+3KF=DhO?YS=~P)KUQHV8LP($slOsY@FWpJr?$g!5ULJ%B61Y`| zljJYA(5n@(szs=uMxYCmBmCLNWjB?EOi}xaBMB8Ga61tH{)o?{$K{jM-8YtM1iCOe z!u3btKB}BIPPuMeOQ;~BXQQ_E-%dNOMXT-oc4`E=Fge1X$eKIo!W)q)`NUpA1qsYz z@s|JJv*^BSgbGMh8i6iMj_{`R(|OeB)lgL;zavzTzzJ~v?VPZa&IO04jn!oufi5jM zBBqBQppn0FzNEU6P(cDGzuQ3zH*!Gwinl>et^>t@);lLl6rq;mz_lc}e! zf74&0f&@;0b3NE+4>h?h)PvzeH3D6j9N{}A@db4Ei$`|LYJZ6e5;y_Qufek2v~AIC zJF_ZKBhZD(5xy&P_b?53zs!EvZj?j?37i1uJ3k|K)5e-7?c=w8i6iMj&N`3+e6fBK)Su_>nMo|5;y_QHI660 z&X=vQM`*1E|O6(n#1oV(6fvuRIhH+zI%tVW;u8Ct3M5<0L9b-~>3oGgv!lfP8V!TG63zH-KI)9W)enGyb|MEDA3KBR0&Knnh-bUv;6`1Xs#%lz+ zFge1Xma6yBefqcX~X3 znnVQ&oB$VMg>$#JXtCmvz{D~43Bya+pKVM~SqH5nSX&|RXkU$qEM|ihk=k0Xl`%SdP zcf3Re37h~IB6!;d8ZIu1KH@lOsH1lD&zX*KS;R zIujKnaGslY#JBi@oY!ui@U2yDoEfwH}?Q`eNO4T6*!u= z0waMgOpfr+Rrz}A&;P1?5iU_d0w=)vU35YkwW)cY+Rcs72y~6ScFyR+sgkaV&e`z) zoy(xJf1IJudWB0=kQlN5XJhq0waM>@b2hx*4?i2jic?fnlUiotg(2QE*Y2^#UOZ!b znzYJ0cg`NG`@=Iv<7PGT3Ox2$ue;V^;?lkL=797R^~>V6CMrnao-&^12svWh{5VC` z{$!#?pvxuZnPc^X9P4V2&istG&zj~9j}+xqwA@4m3EWf0_nrGHQQDS+;eES2y=qeAs=}4NAVeR{KD?cN#^>8z= z=`3|>*akuc3EVoy)5|MLjdF@pZU^%<0$u0Rt~zdXTW|I6kk8Kuy*kqTrF^RTETEWB zK?1kBa&6dK#e zT3s zJ*%oGkw90UxDv<8!ll;cT<7)En-!x?<7JQ0m0z{_*No}40#wP278-#r z$7|;t?zb0NZC91?Gu$VJnIocys`n~eNmP))t*%1&w5l*3E%8;~-}Tf8balx&of1Gf_mLG0$tnviXDH4PPIO-eTSb> zFD=|G4SQF;)$u)v3KF>0mH#&Jl%G-cw)*m8QzOvT{`aGfnYm-EvL()`-xu#hn2$TY zsrpRlD^WoLx4QBi{iN&0c8|8I(rbuDpzEtoZHIbunB_munWpks9AOS}dtIqKe~Ahb zxYdSx#fs=R}}JpsQ)eLdX0c3~TWn=LUfl8zaoIbL*>|%3z5K61dfs|F70x zHx3;aYC^|wjX>AuCk{Hgo_yOnUg*5&nVS${_PhPqE-Z_bs33t`U4>W|c->g&bIZQN z{aqx`RVOCT(b~P0_1%k?{EX!tBFw|PezdDUohVU30=K#fk@~38$mvwf^9Iv20$mGg z?00xRt!s@db0z@;a>LECyaM~xr?CjVMu~TpevrT9TTcf9C@(YnX?=> zb&Q#1rP_nX&5@`efm>aN6H@rGmBhYoPV!ISnx_%y8kd~u2ri8~G9tm5Nln=wYWm%CwS#WVlc*qp zTU~|d5qixy`N~=Atu5V$Ljg z=6AmsI@E0PpD1cRWv)a83C#5hai#fbC zGzTb1V6In)k54LNp4vsnTE=Sxy8bB+b&QWnFz^57%`&EiQHc=zc z_0gLx9WS#lnWJi-<7eEA?rPo*E~h^mPn4)2fhk?yWl@-8v}j*J#Z7bqU9)>W&E44W zshQHDke~7K+%9Ht$Th0;pD0m50&~4WxGpWGSSC6k4zAInTN5QWVLOEfgUsMA34gl(O$j2zQq3R8r4* zPWF)Hw(t9GUqbfnJ6Esw@AW!!fByR2e_gk89?vs#=FH4FXURHo@$Azv5<-JcTCmi5LBywUjRGkUakiNytv+xfCS?W$ zO|~Srm-J%}Nq;G?TUg?K;S*^Rr}&(5#&IKt()nj%q_;WEaKN%rRKsN>^z=&|vU_U~ zo8vS_KtQfNdm7@2zsJ&3yoCq_+RiIzobXpZLVC6?pp~MZTrAbR-a=XO`*YE{`(=_l z|D8IzwPg0SNO9r65n5L6?_D~iua^M`5u@ssV8UANBMt807hH84!J~ zzp>WtRGBiiQpPdY$V1asJkS60Cs}9}cYB*81Dp#{65mhVEC+mHA7C?}~_T!zX*48|+%y zkDNZsq{bZ=NyqrN+z%8=JKl6u&hy^}B>zGs8ll%|Wu7CL>7Y#JRhAS?nmDz2;M zDDAoQne9(13pU;^Ud4YyjUZGucC>doX~I@v^e{hB$jvL8^R zA&(a-(xzq7VJ<_|ZoR>64sBlNTseY}0uj(cd8?w{9optIzrfHBs8KjJ=3d28m0)Md ztI|roy)h}AJ1PDD=?9btHG^h=JedIX#At4w+Qax}5< zZdeR^3tJeR@L1{CF$tT*)Zk<8^!k}v-7}2rekKWH0J*HPOzD~WQ}FyD2E>;tPvyLV zFm`+F70vlQ52Z`1l4#K?Q)$`;Q@o^=i4h&}tX;wM47a7)N4nyO-rcDE)Ed%_ zMeT6L;z88D(sm~-b0X`~IYwws>Gjfe5GtglZJlA#MDE*fJ#+ zLkdJdZvdg?YZ{TeJ^fhglJ**ifLu@u2(8*aPJV^sS*us7HY|Lols+w;W?8P0!n%Y= zzRS|-6a6IV)4Ce-48vjD*F6YRT z>|)rdZ3Xn+$sB3^^%T1A-DwHRySMMI)VZ3TUJ5YS?gifzIXQJ2Q`WA>kOC26t5&-l zkhPyCv4e-^OK^TbF4#hZeuVzQQ>rJiA^kUKe2Po7?TRw!(ZMyO-_%{o95;^!@!u$; zMB8>>2A#`Wi_mS4M)EMzM0W1Aqd8t)y? z7LMqnKrZ;*>a8a!c@NX*prK>9jO9kN)xVcdXMZkDkRSqbMPABQtb9`G;vxPVf$q*y zHQCeIiln8*U0kD;b05-ZDc_O*kWETMT`JAyzabi->{`ic8XF6MkjT$^17$&#&!L z(EDUI>ipPZNU8oOx!CeW26gK;MuK1BW4;a3zWK@QcLr8qtB{+`;hwECY2a2n38E3g zp#jQ}@?>`5_7af-5TcAhVV{+|*OJ-k(Q70qL+C9)BedQ;nay6YlOEl>Sz5TJOu5** zx>g@G#2tF9%SN75e&#$b);FAY5TWDFN$mTM3OZwEZZV`l1oV9oY8ep5lIJ{AH-8+U zKo1h4Ma1=`p=`|RPpZ?~wGu>JUc6Q*Gn=QBXjUGCXg<$JHDcGo{n%xrB?{z%Xz0oE z=+4`kt@#zens{}QAOdm?O>36-V+Aiu*ECJ!l@sK7K5%^icnQ5mt^-UeTM= z=M;3;DNjWBd|su-Po2uz2bd`^+JanA9zqU&lj()=$t+>BF@@iSXc*}sbUINlhvZIY zecPH)7!}o9Wg|7NRidB~8xM$x9a&A~?*|eX9^4W`3PeEJ+-IN`WOs`o*5;Fw1i7F* zF^(F$)RO#}-;ceHjSvu!EB(nbDS!S#MK5jP+MT5fB3>&j*k@uQ!PsEaoFd5vw^j5t z|IQN;nP~y!#2sr^WiJ-u49ErLAyhPYDskJoT8-ZDsu+G3$`j)cTbo$Y`{pv$v%%;h zh=5$aRnAC`W|_tMW%;}xE*F!@jQLj7dURI_#x*64%A}`De6&9;Qu9Q_pt;H9Rl|7t zbxCkBL_jVm520oi(}~I8B)Qv_5Cwi0qG3da(1|ls$f)pjvPBHS5COT`#~hFv#s)}e zb7=>J+=7Bgyp;v98rY7)s1b5OG(v6SI+KaR9m%?HrzFS)(Y8uJXsz7eJJy~qi~ zwqp$nDG&iO2ndb6(@k#hWd=!(bHES*xkltQEecFJFNLnS!TZranc+7qiO4IfP)LCY zm;*wnyiS}sa4A6`k4~y@|*YE>(?MwW4kHY z(eioo^ z*m?67#Sj6x9(p;^FL(E>K)INn44*R#2Jj@%X$~d0ng%)eOh7VPaPfN!uc?22RB}D1DEFFL4 z5#-l(OB5bK;+vHbt_>2B!nnaAgR?|8bmlRJZ%D_u`)cAqAD;eYFVM7GDb!ka) zs~s6QrBb_^oi=Ji`$Upc;V4ibf=6Krk09}XBFJ@N@92D=Bx0A^TQND|uDl;V4--DN z@Vh)tRCol5{}VyFv+C--yhMT)RK|n(d43w7Vr{l%5e5J*CqouVS(s5g_AW2#sFWK!% z!!IvY<1=d8!I^S?qd2l2x)O*EY?XRew~PUNpDCa%%a z*$-*Bn2+t6PMf5;aw=ZJe~XCH_erv*d^$0&R;3tHAOgxpDB_c`Tw_fl31jUj)Rmwg zza84Jk_^1P)DS_2J*zF7Oim=bx@0Q|P#{7-c$W6%n+#mh%b;DSA%)WWx5>n{MQriK z;w?oMc9}SCLwBk6>HS4dy)&@|x3PIKGqqViGVr)c+s*E~Tl!O;Ozyh%EryiBs(P)> ziws=ab&LeR#J%uZZSj0HnY7G~7g~kPPaLjr&cyadoF#}xsOPBx(ztiYL|?i>qyU5{ zBO~OMwD5W|dA%k_f;~s2do|a1pKe50N>Cm`6YASzud~VI!7nRG-~xIRb(PV4V=ESKmn3$OG)1(`<@aKX_ z_zd4``Tl{2ZJmT`^1YAmEB{3!baHVuay2Z3{NIlAUkXIq^9on1?bc4JWf)_X<5vANovUtrD@-0KOx)z9E(S=rQs(co}0ep34(v zjV8yk^c3m}ay{tzUD|p#4(ltu44nT>u0MVR>D1w{1S!#Ho=G)3B;uhrE4_^WYMMve z_TS|h0V9b2nr#9CYFChriXRrqe|kibO_y^N_+2Q^Dr&E^%`OFBuACnOiWT|p`-#N; z+c*XG_V?tyQab0lHvHc`H<~lG^7P6@-_#S$Z6|fF-d3_lQ)SfuLh%j$+u~9e8D*Pj zgZS^RR{S?QoIS7d^s4tqw*pjdt!>FErDU3nbjih?_;2rTu_78ZQ?!*QuSW5>K;UZY zqWE*fgHKcbg=p~3%gb;I_q$VX51}Ph4k%iV&<`0WM?XKQG~~ad@o3(vpJZVrVnM({ zPlyn?`Y4k*LYLm1Bf6Z~;chrn^Gto8C-nS7iZt9H!_`;T|J*JOe<3<59V$;OYYmuP09z%RA!I7>}ASF~?88G$|_RB)qTWj{hD?-I2O zzY8>t(7Y924*%k<@>!XDIC9}xWeoprUf>`ZJxA4wO;SGNm{F_v}l(c&kRY zK3&=Kg<%cyMauuiKpdN9%7se1YW!imhhTBAAJ9V48;{MEr@JekWO%^wfTLD8`lK|H zx60~IFmKiO!*P|?-qNkK07@77B=o~$yh)+K65Dlpmk(vY@0vX1bq!pGd-`xL!#Bjf zvL9bx@5zVb0b2zv2BCxdw-&yqYb)h+_hBx2>q%^ z_8wEV(c7TmDu2(FsxC{TXoFk;^JTo}nD?Bb>V}>NRlQ$0?VDQJbEp%jg(;)E(?$Ke zVq~`01EDi@oeCrOey_AfNP!3#M zuGNKhuh)~Jvpe!(9@e&sG4*;HOHt8V-g@V2Ej|C~ky$ANY7}Z(%vnyKeaicg?WIZt z)H_6*%<6SkMEs6U zc%Y{*M*fqywVz5~n_s2iY~`8-xnLGgMA#-=IrRBd&r0n=3Pe<`VvPNt#$ps+oy#b| zb3M<0ajx8Tpx&WIp-m$c8R%B9a`5WPRzU>hf^(kx4E3&i6h029>^Zb0XeH2k5NclA z!n4=3h)Nld3+9tWyE1O#>vJQPRgQ;iq3@QJT{0{64%b1rKJv)Rwd7FA{W+Dh7LGGK zX%J^r6=h4|oMk&IS2(CqnDG>~dpcxiVY-!4DFad<0^JLfZ0Dw9^m7%TQ3r3W_jc*; zR;er4k~Jty**Y(sqLR%XVyhx=*7ka1IGjE@sK?LN2TIbrGG1BXAk4FDbKj4Z3`^0w~)55}oIX5c%0Vxpi zDRPWqWcj*l_|NKX$HVJF8&+Bgq(B5*?Rb>x*v2b#Rc_^O0Cfe=4WQom`rg{u>t5fj ze5U9bq(DTGl!;e7-CT@NMtg*oRm?PzKR)mN2`^88R0lBJ9RHoH6 z(&+d1;GWF>zKzL-X_uAT8+#EXP{4NuZ)uvYJu$z*&wbZ=iwM9~@+C(xZ)2o+FuFIF zk(wJwzKyn{Ob;Q`2!zJ8n}A|RI#6)h~?LKps14|^LW6Ty3h zh<2B>L+cr7%r6*Z^f#KN{<-Kx<5PI6;I|+b^nFpYHmB9ue!HZC!FLLv>4lOZbXZ=?xYpe%~2*@SG2D=X1vV}_)NZ!xsTc9=Hs#W@4j5d@6ZUAInt6IHM=H6 zSda^PDKvuJ|$@JNn;6o{yBlajby>2C6T z0IEH7g_=IQndES5s)&GGg>$v%xwTuA^PB@3{%4lDd0>W8ymY#VfLubf-PCk~vS{gJ z>C^pWCgd_8!gfXRQQoSp7Cgs+f}A_xkY73_lKu+;xnL#)OBi3rFAqkHr$xgA-Z zvrTfrT81D6A|9<%4s-1yzlmH%#brP8;nG6o*d<#L0l9>%!5G_t#5HHN^s3N|AxHrT zy;ZT&om(OzW4R355fey2%bm*ox~El$fLt(c=jVfSrjzeqo$xY~St_JJgri!f)a5b~ zP8#C#frFCCCS6y$&TlY<2*@Sm1CV!45_wbXjt^H=F{D6*xZ_NUjV7DJi)w&o>&eWp!cDx_t z{dsv#KsXCpf#oc}Cb;~{0BOb3y0ZT0PYLy?F4g|G2HqReM{=jH!EgqH5Ez*0u$NFmxF$z3fjOIV&{`Qi!X1MWQduD6fgP`XpJkax5 z3ZjoN(yhruvMWVW0Y+^g7=Vw@F_*J1gyY2tLvhL7 zrgDNj8gIzb;>Lg1$di zD%JTAB8Lpf#JTH@G);dE<%r8YlgZ6do_M($D;pv)9oIf zN1X*kx$#_Fa`=Z-{wP?G$7=^qB#^DM-r<^&w`j?wSs1ml<)he3h6vbNZtXW_lG7y) za-Foz0s>u2;9Bj3k+H9UMo42hlVlCHlN&yI&+X=aTu`3ALnPL19**@kZoD5!ACk#5 zi>->YW|^kd`%xJE?ToWk6B$~JXe9}$Nu+(r0($TJHVhFD^kaE0$qA!f|?rPUP7+n~f5(DaOsWCg8RAH%ZgyY{bZ7B1T~~FsglpTgg8wXOJdM#?YHX zd}VvjH2yE?MaZ*{hyY*Wxurcbh=2KTy0uPE0a1RNqZ77k(TRVd(aFyt zKn#5nOI~dpqc-m0BnuRP5c-Gy=@Lt(EQwKnFK`qQKnr54!m?vX_~C`B#{v&opa6uR z5me>e2=a+ORFm8Tg`PwGKrQgA(OPQXm5D9)opbs#A1N;yqt{JA|Z# zepPKHNkBj@_hI9(E3%<|+8cEBvT!7s^J|~Fd)QwxTx$i(0HcXe@1tJiid8lCwb>gv z;!Zb=R_{?z<~Cds*AAn`PZiW47wcy6*=t^*pr}<`MyX>@a{IP9>ua}C4jsiavb?$& z)#UbN(w(mm9Vsg8j6-(~!uqw2RKKGYN4y>GO?=n2W*eqUPq5=Jcf8ejMe*eKS21iYKQWo_PO|<&Y_l;UkOC2~ zPrM&4y-Cu53N>MFp&+AYq7I`nPf4$S6y))^_Kh8Bl3brTFEJwUyAZMYYirzzON}g$}{ov=QC zv-BXahK$DXf5)kkeTA99XBga*L>4q<&6 znS@LFZIvv1>vF{K3th?0a5FaU*&Z3%E1X@6zxTxGPnM*wTa_bv%?l@IM?F%PwmqWQ zx8*B?f06W{yM=swY%q?V^HmBvY9mA0JmaPKl8H^5uwg^GVJIDUmG#5A*t1ggUd{j2D!1>WNz?fI zs%0-D0RdYg%IK_dBQ<(hGw1tvWauHoxeay5Yl@colPwc!vCg+At2P7NvCX1IQi7$8 z{QOZD9C&4?wESITS-;Q=>))kI+4+sRc1P!SB@Y^yu&yzR3MmkQG`?7;T_(9Tbl`}l z?}w4L*N&*mKIEvdw~$LfqmL0G(^VK6Iu;{+59xu6yNq1> zVl-%nw&bLXEPM$$U+G649gA1@+8PN6$R)H8%~&#oJj_p4WxJ;;q(Fq&s<73BG#_Ze zD$XBJAw_TEjvow+mO?u={nvQB2%A7|+6`2f+vKV!Bplo3zK|klTN%m|w2pqX9z#6J zcB|v&E)Woq3tA|z?04u-Iv`V~*yvPfeGnmz;2YO5fP_5FJixpZlZI_!^y zEKtCAg+8IH3ld4!=~dKi%SY0SZeiGdgeyi3?PSOWb;w^3=sJ_=L6= zKOjPkyh0)ph)cC7Y~9ITh2Mf)_B*3-$pSB&J-Z{n<&%~huqdjTPEO%BJ;EiAFy3`6XEasPDk)YF;P zl9E*fC=d~FZZa+{t&q@2PmXwgdkVSUdL!++Wu*!!5TOrF!st%9RC1kgL~zz*vSCbf z?YW38YC_gryysd~P5<0pvSc?K2R1d;*r2Ymh*|kP_dQ!FSbVxuzE^&ps6&FIfH#(+{Z%`mZ3Piw2hI;^K zdz0DY|5leZyel9CE|6{GFVMILkPR1~s?+mIgghKXh|%4vgF(bm{zt8_+an+#mk_Zc z+tL6sr_N{9*f>|nOhAMXC!zrddJ|<{71nT3wtx`0gh=?_hwh}!tlF%i_evQ?zYrlr zmdO56FtPby#J0&@MFfaU#n`#;dtb8iKtr}}rHKqF@VjD^`nzH#*CZ7the2o+N z5ReP5+B}om-B&g$pILnCAl;U*p-~S-h&by@FQ1;1SEwq_*uy;gNM!HhnvcrEbfV(f<1qdcItX{HqDsY?$Rn z=Y5c;<~w-<3+t3PQhqt!fHkIwm^Ql2A6;T?12qOU_)of{{` zegK4+p}*hKlB}87mtE4Gzz^Cu@;qFmWU;!oT$1j9OD0B2x)zp#77%J-`A*&x63jw| ztr94(?eI$oSw3?jyIctC@Yh2OzYDowY>3dBdM(I955hXN?jpnQLhV8{f0<%xRdRc* zCv*GwS# zzs7;X?HfeMl%r+z0n=*dR3I&0P!kj zh;}})-`o7oL^i57l~KoYTK&sZt^T8#eDNx;Q5`f$8~B!6M!`2NvTCjkEi>U(vN|eU z`(wp0cBca(BIQ+kG%G>Vu^qRPYb_-7V8`L?D+WtER^yDce`Y`SbD1R(DF6Xmh)#FQ zkh%r+W@guH2!a%-1wlrSV=M7br4!5Q=15Rpl!VHU6eEucjH+f!NFQ3HZ~ljSF+hi? zdsBWkbF~k1tItn89^Iz@%G>#_UlP)Ui$&Q>#$uy-p*S6#(($xmA$e2mW^VT zeosW5K*W&Q61o_!eQ?i|>*~dx&)8yY82ftno{Ruj=zCStSLA6Us&HRjK%5(-;5FZ8 zvKoE)iA%?&5=z~zwJG3dMX`G%-Qn}v4#E7)>sEl2t=q1RxKo?Uu(|O~a_bSx`kqr+D&=YV*vB5 zVa^~$Kmd*K6W$ABCFg4XEOiw>cNV_&KfOVX@K+<2Yw(yDQ&#WwpnoAOIwJ4Kn!u&? z<>MPNx5cigtNla_t@4VJ@PZ9~>`H+sL*xqGhc?vJmR2GhI=zz8d;hI=Ng2n`;#CJx z`bN!<^M-HzPlnjqt;f7^hINn{D9vDK-;RSwW2{O0SzqqTTcUltK(pWuM;H9oq9&%A z4}%-^WHKzssPjv;WY`1dA`UDx;sOoa$%&F|%jx<%EK*a0< z9;fZo>ed^yzJ3jnJ@aR<9^=+yVQzytk3K(?9^Ct(ZM(%_?PYHhmIU7j?+f_5R|!PSl*>aEdw*%(&1pUOcg z*fO5A-Y`L2`yiLF!nt+rQfzZ{CR>{2BkY3+BEVY7s}22}8yEQ^YKrW#lKhk>2eVboYtzyGO1mqIx0HU_Gl3P8W z!6I%xqJmw4aTY8Tb#@?lYpNsbQn$0HD+JakVU?(IJVkCkvN`KES;G))iT6nf&F!Qu z$>RGXtTjQ+_vg!doFCIKITJ+$L=F3J$Ko& zla2mWEdnbw=(Lt;)fn3nTL34i9lU+Y_U^{ws6n!6n5aJTl#L-xe zEbGn&-ftox1TN^|pb75>%Td2&Rxg!%mVhE4gxJ8QSzr0UU;UYVma%{kA_$;29;?}} zmy7#Gv%Pceg&LpG^IxTsgSDi^#&txkqjOU?$$jji+4Z^g1PVmxZ(Nl^v)^g$ch})_ zu+Nr8WQwOBTf8Avf;B}jPJm|?{B6VSgUHfqRawnZ4l0ZqV9r|1Q>P_r$mnM-Y~Y-H z3K5V?l(B7ed(x|gJKOQaUVSjAB`(PwD-E(}AXGhxh@7$Q$*bos%-wCefPh@^B!w3h z-)cmhH98hrXAVEju)*7>dr7)+HZqh4PXzca>?-DD(Boic**=6?bgPR)$9PK>QC32$ zAevVvtjdzZgQlSmeXP{mj(nbA;&Tml*$wLC2k{@jyg`F|1-?hhqYZ<|(c%2x(qS37he zMy`J}j&gyz5L?_RYEl5n?hpQ(=^WM(En$Dm{j$%wPPpBHDW(t zr5o%MiY=7os%QJLH(oUej9B0*0dpJ(t(Y=e4v!6IYiAx8VjRc?TgYF6Ub9#BD;vx5 zjksR|M+*2Qf-NA|>QzbZ{l2VVXqpPG0b0I@_`Up^oG>_ob!%`^g0>4SAAX5PPJ7#G=%=FJtD{OYVy2cmJGpt30R`OOLdHT9o1&vH=K+%czi%^dGV#{ z-lngB5V+ueh2pLy$S!R>*}2iJ#9a;gB~UgxG*XWrg~T%FjD@0y4E;HXMj?k>Z`VdDdEZDDZP%ig z5m|V$JxlPY!UPIHpou)!ce9pMa-u1>t4EI2NdLv{*v{=nA_8!U<1wW!mAAWeVxG6n z1cbl^wSek(X+l;$@@3=nwJ?tN5^1KhQy}BnEv#D07nq`5d%cy}wB(B4ACbP=~x|NF5UGn5X6&a|EP7 z1gvOAVF|6tw3$cMMME8!P%QvkD74CXep9ldS9R90sGf)bT>4mdjJkJ|P$I9IMw&7^ zGHr_;oARYx6(|4!ErwSiy=XzKr&}}ErGG>Ouo6+b1!Ek^%ZRqj66dJ`1t8#xiqNN} zjrdE`IyO5rMHoTIC0hGXe^>H?9i~A|eE50=YJs74LHz{xGKO^^VR=>6#5{Kq0l9wn z#o6zxYV5DKyH*&As}?qV+E3hF?f zx<;z+bbJ+s`hj)@`-I|coQb}zqSjdJ#9$SQFjrtb3t}_6k;W@Nsl~R}1S=87U#NO% z(OM$2)}2yIjcYT(5+Ro$<4&-S{2eh=4bQg|tX-&K5&DtrQIGspJ40u$H&Wc057%=RUsaCL@jlxVy6tr6+>ry3i%*o_J6 zAe@76#Xxw#5_!+$0OqaX^*(U5ggXxOa8Td5nR5U05v=dSY|;0D2$-uuft$Nw>(kM! zag$wQt{CovLiXcPIDa*4*aY@)AwS0f-XuH`5Oe)8tFK6#)5Dn0z^B6bfN*YrKz<*+ ze0C5!Zc1dX#=J@#-YeK;CF#zj(UQl0y#Bm}XVjs2^g$-Co<$$rPD?Ygl9~3WuRwvf z6@)LLA(xM99h!!-%Ojrfdj%@LO_4}TW~A|N(L8-jEJZ{dpY+np&zRru9CVs&ZVh_dlQ2; zNNq3Aq53pWE`t?~mOuU-$5yP*5)c9x)B;laV42RF$I}FjVOx2m7g6R^vrln}WE-ds(KrCqX z1Gl)`i6wP$;5R`3_bmYdTZjgIZ7q-5Gk`5tjRl0DAE*WN)3u}AX?_cKyOaJ8Pm z947x#N3np2OM;aMTtYwk_Ug%?+2$jRIXvMPMicFh7=)b$wPijRCDGd9 zc)&Yf{P5FV>#?al8#BmTL_jXVc6Ceg`w#c-WWLI;EbtV0T`fuSRA5=pi z)Jnc8zh2s#t;Dy4Q+-$yAXGyjsl_(As)LSISl1&$l?BX&!V`YX`L4nc1{uEypw_p-oIND(80* z(PoVL-ImaNTZ*g>U}42TVdd{+Dbka5+)+(LfOSP2j}CR-$zP^>u~i$4i9i7eII{fi zt3|F{joPq}-{0z4IWp@D~a0z}%EqX&PePqW{jam_SH}tq!4J@-H<-i_329Y)x+22vn zcEb%&&lGDC_O&5fGruMg?%e<`VVqE_ayydrvN229_C& zF|q&IjEy|^L538F5XK4Jv2!3>cC}>(ql!fYn0F-^c38isJ4NawE+bCcjMxwD%q|$W zlJy^3VqNoKiY{q{o2Br^Dfa*h5m~r=2y5Hxws0?1xQhyAFu!TxQ8M843pv9 zh6pH|-(6}`liXVvz;4RJ1q9@R>k5A_BgckxIIm+CJr>H40uf@*Kaa5@wKrqd{rqkL z0l7r&{;2v|ZuP*Ptr}}j;Jkz5AzI1eD>vk^u8o+^&NTl3f6xF-V;0++B}jW@1N`d4epj%IL=3{W5f&H}z#TkXMBbW!YD z#{$s{2Y$3LyHG1>muxw00J|gI5qt)?`v@KfY8G=)Uf8}Li`dWO58$ytgt+?5Iki`w zysQ^%oKl5Agun&XE`&zS*dYHr*_IX0Xe0UzkPEJ;$Uh=YZl!O=OckCzhrSx*g1#Mk z8XPMZta4z@B#wX-hydfnt-WWQY!T$lrtIgt0YpG9xHF&@9u4J)Ro<-B?O*kYkPGft zDB$x3x#L+s_T?A%UI9he`-HQ*tpQ);GQU1-VaQ&gN)IC7F3RiM+iFSR#&*p0idKQA zWN>$e_ofi?_VXu;KiV*FmrcTrDp;il?@jT1djuvsN48|S9dyEtDggoSm7&{(6G*Qy z+msWNPN}d$9p+(Reg>h2UqgxihCQ_R*m3~@xy1T*K-DHa4V(x z`bp&FPD!1;Y>j{rxIo1}_W;ICA-(!Is+q>Tz64Uhcg6cS3D=`Z`HOX`|6CgZ0l8pR zIsaQieWwtAv&E|QAXDLn0z`;+$&TkvA^nP%tJ9mErtn*k3*L6)Z&|b&M!vXwSI@Nm zjv)eaiS_MGTLklaEI-xuv-LuKJ4C?Bb*?KPLcYZ{WwVCH$&dmOVl8L9T_^I~xfZK8 zs6aqKuAboLEJ8Jhwjo~*IWlT~NVstb5n}b{iga5Ndc8UORQIzC@7h5waoyF_u0zUF zTChLirUW7&7rd#9(5{^N#H7T6J^oNnxWfw((EH$To~7H7mn+QJ&Lj)LlYt0fze45% z+mek1)-342Gk$8(>A!cU;di0Gg3yMc-lTmSE0*)u-2WQk~Q)qcVs(uS-(xV zg$)t#Mm9fDoY#@`2yf0v@>UsAAOh~~{2jK$25xslF0qE*s8t)X{<067AJI~V6o?T0E29p+Y->v+)~?5XHFRVfYCkew>RFvv z8~yO1`ue;|eU_bEaOFw`jNg;;||vHYlj-t zyQPz~X$`+2d&i2JU3Zb}M;hvuroW3+cb1K0eVi|;$g4ytAAdxf-KM@=ax_cPnH|tZ z=kZ$3z!eIbJXfo4WT^4F)5k{X^1Btw>!D+V*Jf^evCT_sQo?KbV8xDib}_PfsCjCYbX6%BuxAZ1b-Meq0vxJ!9m9&*XDW$hLYRih_&Wk_mIk#3qc zyC-jN_lCSBRWsMweuj;2zhC&YTTMqgxK%K9>o~th5?9 z_-8+EyGjqNuW6`Ozsg_CzV35CQ{VD!5u`u_nixiP<%4jj&ajqv^iF15uB=kxgO^fh zeUPi?{xJIBS65sT&+BrK`Km4=&DW{b2TZXY;nk>C*qAXHcvuj_$7pNC0e$-bu0F+Sx5Q7@_`gxcBZIJbG+$#KUyQe zlU6vHV*4U3b#v`O(E-D2BtcfZS~Az3d7oV{4F;L8 zW?T7-K!743gr3XSd|A_$#_W{ePFXjzBh_zrq9|)N)<5n@(J~8)%9mmNCY~#qdQL$t zHt?Pw$PDIx8Th{X)`h?P1@r^u>8uCyn%GnYF@Ac2hK$7w-)zYCUS2Dsd@ri&q@n0_ zFoyE@-;Dy}apy`8_G}np+iNkQACOCwVf1)7i?4E1z4}+O&?^1vM5=4PkLRrTdMu1! z(5f-4Tldpya|bMF7b3chnMG&yI4`je~R5 z2{W^VR`Iu2=;Z%*Nzu_aSis)wg7lOY8n9vtH9daKR~O6kH|wV`cf& z+Nh7CfPh@Eh1_R|k7Oy6x2rJ^d&-ak5#m1hcU%lJPhYPtc>V`N1muFdC_-Z%M=}>H zy}IPi68XuQNp#++jarL@9T>`heM0C#S1ZT zwl`zl70ul;LA6%_SgiS7?o^P&k;Zf z@=!&;u57qTb+)u;p$vNnXB5;Szbo@4h+UZaT%DP;T|huCQO4NRV1|QEss)Wt%Lw!k za+M70Veo?_{j$fr=XnDqc4ORc_0*PEGNeER>=Qz<88g|OT2_w%(6 z;@Qt%HtMhZW-_D*2w{FK)J|o7#ckE(+(ZEZEm8kx9QO?PJu`NS_oI1v3>)%K4|TS7 zt_&#<0d1PUe|2d*TWT~{wcWKwuy(=5fDRFQxU>hmbE-n^>~KNQ71WPD(3_$@btHZH zN8YNh&*NBb8x!@ROLrN1GSCl#twm_S#U^Y{MjKXo@G?JL`ro(8AGM%p^*t@x`;)&u z?=4TCbHM1tRpjIAX(GNgr>BCJyX#VCJnFvanSZa^ZwF z-0M52K?h!70Rd$5ij+lNSyX?13u$|roPDbsMR=Q3;=)%{&=OHbM6GV@$drc6^kS%h zfLsnud}*lX3CVr|kA2XllwNG*aBFs>fh0o;MCdZPM!GGNN*0-O#GmUy%;Mc6_0Z&f zvVBeY}^q zs{@%bq?DW;K#|vT3B9Q%e2L!%TpP)ZdhJvbCQAYZB6RD9P!xQPpOk;$RxP!`zX zggX4=HUS}U36|Ju;6(O#c9c3Gc%?AUp)HBlKCMq2FQ__0Q}RX&^8;EUoSXc$Q15Qc z<%1Q=OH36;5NZLAKYwRJ8OK%}zo?oewO8&X^r2L~u8|Oba{nr3Jd5=_slIP?o5IKxBA{&kS4pIi?AwFqszv)+ zDnvl8ebG9)_|0Ca`YywLHGhw2mNRXix}f}t0^1H{z&M)kYJn;M!!&= zD5G^)f3|mo84IjlM}>%zzA|+S+9bstvHe%iXGevw8XmXRMN?O+kPBv2#Q1!RCWOT_ z%u!G5Qy1mh^JFf8}KMx(s1cCT~z9Ze3R4cOgQQp;`%VNP0KJYoVXbI8?XpJoY`j>7Jxo6|o@N_WNQ=+9$}lU!^H-xLF#iTQN^{fG zs{Twj-hI@YmX?l^yOumnRZY>KrSec z`=YaBSkS2!YS{7R!u)_-51xe4?DG~l^sSS@cFp-4-VLUzZ*GY*3UWa^=KFcaY0R0X zsjc5Hz;KN!8a<5a7uClP{?w7f{ux10OnqG9W{9?r|A}EDn!>6*>b^EDxf`-Wu0lCC}ShY-IH7sY)-9Ij4 zNP!6G8Ssqo)S2wkCP%fk2NNMZq1q z`@&fYDNws&E@SLJ3G7{?Kh*6wrEu+oToBFI#FTJ$_sB!FO^voxSZl%B4p&$H7gl3q zS(@JxRZ-hXkOIF8N0$F(2k&VtBRfqUHE#ii2*?F3lzTEqC$Q%SOVnYtE(i$71$Q{Z z+ammpiO6^AjWe>alR++VS92TRmR%}vWuIou7d#n=fL;`TlcS}Mz57;^S%0H~PX!Us zN8!1-tPad(Nh8*Q92F3d3;K`zG+f_=l|8m)fuU6h^!fxY5WVmhlx?T-*BnMF18ml+ zaE;2&m`Zic8eqNbCBv17zmbwZotX~VPRk}vRUri;;7Wv$dU7%woHRkjCq}4{0uj*O zc$Hpg3{$6S71y|26|S}WYNk=QR@F4sgZ=)s?)vYIWYJwTG%f##&<}`!@_7EL{!He{ zUjjX8-%W*FF#84bWxOV}B97J3w8t~1ju#M+OO(;CPCV;fjbKg1SQSzrLgzYzA|pp! zV#(`{Q1FZy?B4L7S|uzr%)DKi_pI~%R7imcID`4DB{NyyYUgmRnNBL? zf~^uWkg*5&NyF^4yLC|rf7=7hg`m8+uj#@K!wAz)T z`UU*Al8I8uTUY)UzRnW!z#Yn@?LeSeUPU^tr-B{i3 z{AMwvbmHejC5q33IPTrwKEnTE(=;EH^M@m>N2zp(E`Yg>G*tZh<{^uB#d=d7#Z7I_ z-|@E4=o=Zy2%^#aka}uoV|VtF@KYHmqw^;&!$N~v{lKa+Ub&F#t2}Ui#${X{-a&Pl z?agK%Z$ktMKnUkMs3g2Z4X56WUgNETCqEDYPl1qG!%3?BC4Z)!#%pU~45?w17Dd^Y`1>MU3n-)JJ@xoZKW6NIQ-%o06>8OlqUCKR)XCs8 zta?|W)_v8B$#ag#kV|J{M)j?&rNIA>t2cq_`T73G$C4}|`>te(BqB;ZXXX{5tXU$J zL{X9op=fy_O4;{a_Pp&REzjq3^0x2Uce3wfU$XpeegEhGzVmsV(>acNAJ04MojZ5# z+_A67WW?e<5A^jne1tY|fkeTGl>v1%Ln2p5M)7_y?(E zFWinEdD2m|x(7Ge(B2Z4L_Wc?cXk)s<1Iw1?N%zb=rI?z=LtzWwp;HHk!Kc%jziws z_bPGz$0fkWgyDL~r5dwks(5~<0W*46)bU)yX9)6)dh0$(^vmd{UwqhC)}rXNPqzBn z%<3<)=fm4FojoXCo$*SB>j!VL-Wwp2CYg(rvw;*-FaozBA*bQii+0UH^v`a|FamSo zc7rI3uNK0)F%>RDrptYf`Ud+02w_L6i8EI^ieVqGNC?b@M<~2H-Qu@?-rhkt&o3>F zcDyD^qle`F+^#Hs*G0^{+nf`WwaRo+>h?9$EpylT{E@W;DVU$6R)5-8{K}}!B`%yp z3hNazVQhl7&@fzdocWze8V4gz)l$jjb}j*}if5FM*LkHSWV2dZoXrYTFhaWd(j+cP zb(lFqT(tejBn09*x-@nB$mb3&E7ugu;Kw_wuKGC9;2dPRiEW}9->15G+E$X#GUC<1 zO}Q;wgo(}nz-UJZ%q8E=`Fx_iUh$p3_}lZfeCqA~P$e%ex)@_B{EyzvnbuIRQKOIe z*BW#p)^M&!x1*T`Z>97}(uM~Gh=Ywj%Q7$mw;@@&#u2XvAOtt3C11@LB7sml~s2Z!zDV!$meRt5M>`6Fx*Ze!VWcGZQ zJjkg5ar!=0wV<`8qSi-mxPOi#Hc%cGoDqt=`%puh@cV>5e*akU3}Qd-?7ZQ;Yy-r2 z;LJACm*zZGw1yYDi2l3a4ll~~Bt?#pI&jK3+Qo8VaYm>$2VJ$)lf8v!3%H#rQBcM# z^d<1`eo9wE-;ESsa^C1TKN!wUMx>e_|NB$*9uOkt#a`EC3YLLOHKltEYS)E}>8~If z7h5t&cS$;i?EA1>JA2Jv+_wKA&o!*0(8z}y3N7L_hX&!|s!z704RHU<^W);{O8SV4 zvEs$!4OF6_5hIV1ayA#0x1Zxh&tCiCtRF?t;1Mph)%VO6`mh@IVryf#kt;<4q4r^^ zpjRASEG>%T0D?On);g!fi1^d}^!(e2>cXOZE^oF%f$J* z`SqxNU_cX5P|a0FU@ocVn|F-RtGDnMPUcT^;&4GFE#Tc~0{Kf&WR={8@jf=X=>f=K zmL06)m@BE>aB1P)3{$;#^O0gdOyAB7o(bLOEOeNqoD^`D`Kz3eP}W57F@d`l(mM!Mv6Yrv#dz_Ll%Oi#VVj(_!8 zpGONR`YU4-#2Hj^wls$b5!}+`(aR6o`MmbJ${`0Gju*pRxHm~?MosP5yOa9kxUn(< zb79>@YVTO3+s=5c?|$b6eGWZX@Y^|W4b%hINvcP;`$_udc0uBC3ss)yc&(LI&IQ6t zw+V?5;c<)Qbr8j>5sW5pj>6+cpGS$xo5H1tHf-<8i1dZKbiakZV*8a73{xb8RH}#W zT(3N8npk@Op^9||9*GW1&#K3#Ja?J#4DwDA$CO(7s6o@j)sa6aMqn;UE0K*>OY~ay zlf>Z^GX+yHg8cJMWzQ-r2Obu$YL}11=}p&76zS&9a$Fzg!tF+)zKqfr4;}!o_Q0J{ zv`dk!8mZ>D&*kdnYV;6ivP#Pc#3k=0)@4-^??!ltvB#H47Bb#D$yRu?r&rb^ywXfW#5(Tx@+QzlDH-T=- z?J31Qm@k+}v1%wPv`&%EKXA0EbY?;76Fm(V^ci z=GBVVbI%?t^^2)KV(o+5xb^5DD`krwy)&ZSQj{cmdFL*Xdoawz=#jT4=g-c6F z<(4@RliE@!jatd;ApS01cS)`J^oN9 zxYtnJyfk{q#(D+%m~X?yw2(paxIzedl+-qZL$Y;cMDU?*@+iTz#ifNamU3cKewJRg zIw15W5N(v{LaIU3HEwAMQFm{BQIt_h@QpPE+0k4h!?6iPa5T&)m0`k_@ z(b7mwg$!*7Ej_C@M2eU=3H!rGAa51lQ?WEm(%T-GJNBWy+c zfmOvQ$8S0=mBfYR5zWsYE!By<_*7F&OLP+Fp62Ni1?gQ$ACv6+ zl|@$vOYv(48n{2smdi*Bm2oKM}ueRYdsM0=-2l>_0FC_Zn(9 zxWV(oUfkUmWc6d+MZT}trH9z{5f0CO$zvCDN!sV=QK46ivlYS|>~>ss zJo51jCJ)C|6~Pl0YZF}u$}s?Z?-Ma zC6i{6G!ieHeA2U?dWfyHPRU~zbKyFX8JUmt2}(nV+JZF-_c`XmEkdRrYbpGXmC>EH zQz1n?;Id1%AZCYxzN$7_RPH`WT0d|-aQ)!ixwO5w9cm&P)F46{?PyL&bA{Z!W-H#* z%+!}fH5U>Emr9D{$REkXk-1iSDGsw1Q&8FE)p_$#KT*v(L%Y-CuZ}7BtWa9#Nw4z$ zqUZcITJrrO9aAs@M|i;b;E_Plq`!@RHS3mykhoBk4IyvbgT&o_miorgfIt+Cz$c~< z-MTbXR1a&XXI9Ua5SR-`s=zzERfdR7J>NrqxOq|x3ywmYFdTJDYnaco_>v>(J?9E>KURM9DQZg#XVt2LgHmX~u+Et#q1 zt(y$zj{n{H0moeiG0fCRl~_2t``#!~o4Gq!SogW{KZyUh418uT88JyS*e?J?SnC7Y zl>9g`^vww>-PA!c46kdbo_~@wauRY&k-_(a^rR!vA|!q-#T0!1NBR=!nlo2FG-tdx zmOvTi!f0aSsTwCh9;UBjLB_2kj=J@kDDn7c7{e3^fm?($eqpP(u^%b!Z+*aU4fA|M zRB}8VGB3=7m#9%260=?YddBxaF>lQ|sjV==pv{LjZ6|8R$B9s?c;|4Pmme+KC+ZSH z;*#ny?7>>SZMRXv-FmBB5A zbT95fkA^$+70btpQP&1btt+*gB!l)ktPk}ZBicOgCn2Pgw7;qb#7xtS&I-u*d~~vE zN<2l&cC|R17XBwapwb~SYM7R1kw$T=!)t<;@!IhG-lFWkb-6@A2$E12UIq?;+h=P* z#(^{&ebcBxB4ku~8G*QP-@yE6o}-FIJxdGGZ$pp&i39lW?0>rd81=@=O!af@HK<4aiFo~&yNfs+XT_x&{+p}Ij{99&++CD(jvZX(M1;m;URByC?`S;gWPzs-N@o)PSnK zT6~{{Aj9E8hJN}>AJIGRGs6hXCCwF*nRs2l;o47_#$INaf)QlrJ9tORS2Ip8o`bWm z-PG&l^cR0V9hVT8OB%&Y4>QP6jdzlm007_E`Dz93_qXG7uK(oLAX z?9K2UMbfOUHfSM4gQ^4m=Vn;>sb}?1?L)=Eor|TLlUUmkX+~|jwOdc>9U%&?jtb&4R4i|MeQaC5Gz+uXJ5`p%pne zh}+XZm!LTz%`QAQ$?=Wv^zjBCk=J&DR1ZAHq!L1`+Bp3~M>|pFyFHiY8jhKfZb-*B zc&dLI-%h+Mfb(-S@5t8s;7Nzu76H3y{<3l!IRkfqeivsEe6#8?DWOp6SDAFlL7#hPa+)x@~$^L&CaNlAsTt7H*|7Fx%2Rew@KMrzq8;a7BqQ!_| zgh5N|Z!J7VxJn4jCCvho`pZ*qYGEM;t#g&uD2Yp&AFaJ3^nX39gm;c2A#h7eGnjC% z1$w!&O~tLwj`GThzl&xUtOgC%>R+$hiSKXVq#Ccam& zM;cdGe^(RF;$4Mz#uf=7^#Rsnq|!?p(Pf^UC|hlnq~S0^9*IXUScxam?S*~h4hbP~ z;Tw*`dxpK}aKEFtvh}NU{}`_TvKDn!ZN=2EYNDRugLFqxnjg|U@BF%n=#>PgKab5I z59EKhF!8L#ch?|lGNG<8yH`a-KLTqB#R6jlo-2^c&rnZ9+-xk0_LPzkm`jSRBKf;a z#JTrP#M+4JQXDcyV9f`kWJn`@(AMU{*A6T)q|fo##Umdwyn486Vo(>+txXFq#cZM( zCB2S8jyG|m!yT-}rO7a(a8!`=t|5vFC1uuB7h|vV=P}_4s_jBMO{M)lHk*uN(aySwT6oZ-CacjuU-SV#!ouO~tO(-T0ZO zJ}O51*wj|*{(cDkR(M*$Xt)dTxuMwb)q_9U(MrSR#U+^-*j-yN$c>VUdpp7jR55EW6>!$32>>?z(TP4e1d@^C5pl z?K>5<=aJ)S#^=)tt{=Q4@UWW59yWmQyJ3@yDHwrU0rpV=5ABo|M8H28U(9<`L;63KnQ85B@dBr|fJ9LPr<;EBHdCybZbc?U!dHSLw>gTun z)$dM;B|Z4)=vMXGjYRtB-DxFj-#xXviIFDuI}HfUR?~YHjN|prl~ynUb76V#01X|v&!vBcnwmhDTxjeM3s{NfrS~{?T(*DwHwak(vc>7>rCS+)ua!DV(dJvMeSjXu7X^Ar2+W1YG4%P<=lXTKAkIszSFjAs zRdcPWcBb}3I@h@rU#gB*+{Xpqlt>SdTCpgc6SoBaxh9tU7D?wUIHGk^$bSI z@o#zTVRo44VePA71m=R4rl1owQodLxUbyj;&C3iD+U2=YNif&s^`>-L(}`N(l;R%j z#GkRiwLv2A={yBfFyePrGYVQ;`wm(g-mi77$=k!(;P4))3Z`I0Tu6I5eV3PZrbM^T z-B_I)^ZN^*%ONU8V6K}B>}U$?aV=q$0DnnX8@{l&BG%;maH(>{jfV8;rddW+P;kC2 zImgzSzAgBrbzMZ8VQMZ$V6KL1+tQa0hG@|ri+iy5`)a&i`vD@#;e(1P7$Nt0rOzhZ zzpRf4sQ**J6pX;*4I;TBZFulsChFN+E9GW)r$&1>=-c#;xP-VBz}Hu{5pVk3Lrl73 zt6>D@!YvI^-mXoV)1g=qyo0L)jyou$Lgr{~VT|S+bWqlIouhsExl#!l<)|kADt?yS?Depfw}NZ18bno9Ok=XvM@xiQ!xc2@C=4mdp6gl*_RSTyMgO+ zE1ul%yvZe1dkX7o+PjU;Z5yX*bw9f)opbYC>~d1He}@*2MBAUHboI>yVR@~oiYXXD z+SSc=w@KAJw^;zfwGUw5nt)m#_?kCU=OLSFoLAyx!CSY z(Po1tg6Qbw4)lgd5G|TT>g|!4BIlXJs2bUAXxcV6`xUF#e zd~Uos++ zRZEQ)Kc=}+jKExSJ)XBKr|&x%C))h9Q1AZguU^}otmW_UP~3;@$X$?^qP;ubOObMV z5r-Se+QYB}F{=F%7fiv3@_!R@tG!Io+I1TZJ@_C!l4|o4MBT<~opH@^Z{iUOHzxt% zIWIw^ueswQQP9Yc`~1PX95v}}f_U}%x-{A`mwnW<+}PhK+60&d@WRpkIoj8t1Tn!n zNWm10!1W^}!8%uqc^fZUpK{N|6kJ>UB{(rTK3%^xVT!2uw*l?iHc~zRF-bcG(lPok z->B9z%+k_IN_Dys)631BCL#)EOENIJyiJ6f@i0mA_A74P8SVphJ#MP7jn|zq<=5sw z)vsN$mTnv<$%9y&j(&R2(o@CnvVKwzVgw!wgqT#z)vtJji-PZs6`UWg{ORZF$F_0W zx!Yj3hwoL_S|n;}Nj)M17VBF)CyADiO6AmdUa2PEou!=$Yo>%z+35ylob)%?yz4KmaK!vDIee|$Vnv~9jyjrM!4 zYAxfmMuRIT^-Go29G}5ECOPjiWEs!R_vkGle}dbH=^CbB#3~Y`Zkq!c=JGbdZo)ll zpZs5$-luaQW5t~Q)2%qisB*eJ9TH3=&p&BV# zsdRFytodz=(8~W>2{n&6wnz6|8Yv2YEmiU8!=n<*BV^3q&w9PQ0Fh8@mVyzO3zrs7 zmrTCseU3qVBDIwem`g5Ilb6-RG4BC_oU59Pxo~YCI$CR^*ZOO=&?4|I*_+zJRqHF} z97$Ku{<&FM zE6R+}^rQ%7y;e)>I5SjRwL3yNmR(EhdNovA=TnTRx8tL}Yv>4Jo_0vZ2+W0N8svL@ zTSJ)mc#4?)F&dUWqjFcRdkuGuoZWEJgF4g&sBlS7kVubUs4w4qdqeRxbf9kH$+4qTJ@`%`6Ou-0Q!)@-lS}!^< zK}@}$uVDn{dgA_5-Ec2ji)=9mTK7awuAbC7TpX`zBgw#ASldB1lJ-0G7oe}!(F}?y z7$NJ#4K-42e}<>#VhTp&=Wfn1w@9VY>$^jL-2Ylr^S_e7yY4ubD^bjjXMb*$N-dAH zQt+3+1L-_le|&y2|D9o{;Wk;lCr}-|G?^}hdf+xBBxv+|t%nlNUACG@t&0)3euO-E zUa0--6wfz3Ckm!u1a3FbyFKdaH=D-sMW0(JVO@Px_a({n`~TUyD%iWU*xvo9IjAXP z=FtDMcOR{d)E^v;<|CDC6(cYg_MJei!6z&2*x3XgHfXSm)F!B{+Gcqa+q-aDQv5Tv z`mK%M6vvw^3(_zGb76UKJ0|nKcE~fHySmrVFa;y9?}U&6BO>)WsnI+n){SBW=923% zJJW=1JQv56(xz%&s;9E_5cJw~4~6vF;S!XWLeo$6QubMyD+Y@c>e{mS^fh_IZ2EkB z0&jlS+eM-vL{@2|OWl_#^psn%MOG=L8x7u)z&|(HFMVsy_-QU{i&E&A{~7skyWcNM z@q3@ZU;kX{jQbWN@HmG1wT4Wp6~*&vtvcl5QsI(dG$Bjpah4Y|jicZPbDrY|? z(Of7AM*ll|p<=yjHeFPbN7%jI494e8;aM|Rsu+Q}R=I9eX0usz5qt@3(P8bFnQbf& zUN%=M6-GbvicnG>B+;Aef&tNS*+AAcdMdBo|BlqUm}_B1pt8DsGPQLa2#D3016b|E zsr*^#t1g&=dlT0QJll_R*nJw#+x&A~sTsak*=~_YuRwWmJtEIMS1PrSqkgxF>+!Jm zdbYpLMBeVIzlJFo5i;wlQm^@Rx~|0c+Opab=GbWxPZ$`V?NqQrv3W9!es*iBOu3z= zI5^Fs${s-T#V%PtWQW3j372QmBP+O$TM7Q?{*xvhn2C7 z`5~1Jc{Prg>AgqA6pTprd#;F< zakS>(;!yp&&5&vep7UVIe5^zBE+_Et%cd?81tE+>r@Op* zn?gVLG=X}|bT~@i=36TCnqvfR1w!oR++bI%gL#?4 zecJ4QO{wRcC^`gm#>A{zR6i0*gJ30-M@gLpCOl!J4FWtoP9XzGa|wu_gTfQ}C$7Ujn~RDm%IvGD@!mU6c8Gdc*anu>_GwmKH(|cF? zsZC-3DepPm22bOb-Mi>{U9DA2!H5YPX3<-P@M1y9@1I4{eE7R4J#}27Bjz%O&7w1{ z(^S2KDU}f$Gb4EGjDz~K(Ci#c!3f8tu{77?jXDvs|AU3RWgOo+MAuJFsi0y6=K5G; z5tzxe{=8|PxJ=BYb zmu?^y^WG8yb2$tfL)((NTHliF_6;Uu3&Q&cV+FgwhN1q?iUk#bAVhTod z8<(tY96Jt1VjC#cHUEk5uG4xwt>w)e%!Tt_%ZSO}rilS39CWo&69seOOvf_fsc(X4 zzjLm3wo;0UDHvg0?9U$v_v_crcOc|_UV?a#)=v96v5bl-7$Lu*Ff}ScH2RxJGm4J6 zsDt4Z46CxrJFto{T1MD~$BIjSHf&Yj=v>T&(I;*vX;yDzl>V@%f>VHL(?n)x&U!Cs zC6x+u!A#R&p2O;2{0p&y(~@IzS^l`5&X|G`+sh?t#}W@H)UH^@AG>j)Xnh{5cD;;R z{#=Z9JLkJ%3-ftKizuzt2;j*3(_ThA?l4a5nw`hKR5DR91tYL*Lf(EECjQp>%Vx}6 z;8ObB7%ik@UAh-?!D9rL4RL+l`iYiKwYld#2NiQ+v>ctVcW-a;WOqG&>hf|4fw^#O z1Nf=!YtHM0lP)joOed7=4eVC*;5M$7+}<)-#R$w*$upD&FRKkL zTm175@6C_atk1t&-_6Bb6?%lwuV?Dhy3hwQqW_)%zSsW?>-g?g?yr=o^j`EAKyS=tq0Afq}2+g9Q65w zr^&Q7@llB7?)F$7cp!g-^ZBa|vlh{PoiPG);nKpJtfAAm&v64==2lw4-^J)(%Tnm| zUO!w0m5la|(-QcJEeUjm+Ec~8SG>aEFF~%bRSA4}vM)XLk5NKkE?LI+ogMh=N}YIX z8yn5stq;xG!l@zKmg2ryv!yldy~&@3l$6T3pgk{m-idb@TSLQ?!iu&u>tp~WDV-_) z61>L}(wh%~7hLy0PgF4l_W_m%o^5E|G0?hRCv0=2_Cfu>u~~HvE_H>m^?j=k zzuC})&&=>p@pqr?8b)7qw1b_OFO6E|6F5C(Yy}HnzfqiK8TYaHar$4siEp46n z+efJyreFkaY4Ev|Fm5;K1mvKvrQq`7ddO{+vNVc&jb6_7eEzB6*2P>qy3M3Jjk}a9 z#^F$^IGbrad5M9USMN+Q0&~gZYW|36yt<_e>&JRfOu-1!Hi?p{T@_NcxaLn!$Mer_ z{V0F9LqcG#!aIP7O?M&3ixGdccpmq~hyLF655*KbSFmh&6>)X~Pca2~d9m*uXVILsrZlUHKOiz1$MOE&gXouCRhiYcSi1VbMrF#(4N?hlo#5>nHJ%3@ zpRW}BJV~*1!e0>1m+v2Pja6E- zh8gog9|i27Mvq7)aUnFkhqlRwf7*VRO>MPILgdYWcZwIQ)HrOCj3z!ieR=ogh0Lt_ zAZ9+c1vMN!Ne$=6FpMxJcBIBFIwdoLpj02u`|vhrKCx_lAj1?1fl3P*1e}NR-RDer zMo~Jw^{W}ppMQZGSNTb3^Jf%xEGo^<8U!+i{~gGexSH`kmp)P~1EXT>@*Z#BbJN18V!my!$i%)C-lYFKs(#%x=bKDZerKhIP0heJI~Hud5S8r0^` z?l#ohPj5#d2L|omx`~9qUxK}JoPl@W--P#@<|-jP?V3^J*Gy_$T|+`c3ab%?l6csb$ubc~NVwylCnT-w4j2j~%JpEfxQZ5dnW0y;4$iwop4bMB%kxvg%^!fWJwfo198vdC< zF#^jbq{}yZzS_J4e{rytgdkomX+hXnkP#}O!ERsLlB+R{@9Xv)-jw){3(J#NwdH>t z`LP>zoCTWbn1T^_eFRJ2p&Oqu#*!yJ`Jfr2J!#$-i1V77Nb$NWBO2d`P#XLq8ya*L7b)BMt2oETiteK)Ui_KYDDYnIsQRWxy8o zHFuzIKe%XV7e~>Bv3@k~USo#QX<@;%a8Cj?R)egJB)3cguRd=bZEtC-Nn8kx<$=%A zDVBE*sK$DhKc*SmhfxFAoW{EC7?vl?*t{!-SBUG*%GbW787@Up;u%a0PkJzN9d1L9 z13g^UgW)fM1yD7XSM6Gj&2Df>LSQagMnu3=?sT&^JM=X|vy6zR0oS_Gya@v(8Io+W zEq)rWJg5`fVil}mI{}wU`VuKM)rWU@P?~qBm9JsD4UgTl_wdGIe^~JzK^AKA)Y+d0 zTKr(!rk>U?1tS8o22-*K{>VZ2>+ob4zq9HSJ5i^ejuDval-`%-%}b-k49J8+{=6N* z+kSk?#vQJrV+uwX_jje_@5D9^~j5{MKdDM#<%0>d>`r$5o=E|nLlk!T^ ziC7O}jY>%SUS0U?JWC!ms-2FtDCUw^gUyF~aPRH4d9wFV9ghaQF3GFft|WIps$m_z zXi*Odfw}M+4Dq5b`tyH#ROV5;8b}DtC9lqRt9kKkr)jc+L~D>V`XSeZC$))1r}%DHtJ-l1jgO@lf09{CMA<5(0DK5d$8` z{qFoyR4snLrMHB@TzI?@vPT`tYmX?+nO8YUUtuoX|Aa*L^5^S9zO&UAE=&3fbK#yP zB&n`H9}w|}wO*d4VvU2jbgKe;C&m`T@b@!JBs(JxQ4ln-p(Wn{;o83k4_%V!xHDS%+Wh# z1m>zelD0fLfEw=?@70Fn1aPx1foxRYTZ~`|MywqIdpLy}8o-{KRFC)OH7vr})lXj- z!4!me+{TR#JmW>JZq5Y6tgM0D_lzCOZd8F|gv9lt8zn7ZKavD@)JgYho_zGcxvcuy zGH`$Jznw7NN8?>M+?%N5&0n;h!A>0bAnj`uE@_zm;nWvxcC?=Jy?C>SA?kT^Pd z@zdE>>{X^IC#nx6cRwk{q8V~4NcFh?&Ykay&ZCZJ8p;UF^{5Znb=wtkvbg3(voIc( z9m~wOu4H)ilKLO_6M5DukVm-mW5JEDva$b!z^j){Y1#U*a&O{(A`y3o^L(pX%<|P6 z8G*TQ{YZ{o3?Jql%tD&P2YbTNh@XK2btQTnndA@&kOY>61W)+ReZ}o;j>sc->O=Mj`(dkw(eGMSc0} zy3Og+JGHq)!3gXLBS{NA`J&3x>DEPXPZ)m-b4h*vbEzL^5gGLA)4z~g8;y31D1`m3 zCVpVJr>)OCOknJ42x!7ne@suKg*i{^wdQ-m&0u zjM1=iDpPsPT`$%@<*R}z7=gzdtj_&oxPa{Yw;k3}jKExYyg_VK$BF#i5;JxrWdX}8 z3*P>}Woh2O;~+ae8cW)AYI%9FLatAQdhBl!#veQXqMOI(GJ+`>@g{~6|5=K0EWGnZ zPL&_a{o+T`{vS@s9@7&usF^$XLYu;P#a|*OuP5;V<=p6y=5u8VLSWA=ybdg;aFaVT zsZD=af6%uum)sv?dQam|TO`u?*Blw9V1(S~FUm~go0>OZQ}6wiS{Jt{{u0EukB{Nc zW?8b(X3ZrT7$LPfxl?%(KX9iEyR;F!%V_*aT&RAKUF=%~ANcNx(&_|wQZWVff$XRD z3>e9sd-bR9x4dQ8vn_EUH05lq1d zJYtAVSR~)oFPydV1A72baLsYM5t3dI&5te*U_U0OQ>-~L7asW#-Ih3wzwv9!-UThE z*oTBqOk^+4#165%#q0*mOW#Z}m#1YUHQcCA4Ov-KMl1@3$hPN|*`6kU6->bh$%91Z z{F=l+2G3)2=BF!I20klFcM7A#r6o;kzYqKj!|p}#W8IgrNNyz|Fc+2w-l*Uy{FwDj zR;&9~6;m)mF4f#QlX#_C^O@bcks4kt@tT-&A%ONfvXI_n9bulYu0NS~wM$|(Yo%$J z64nxYOz|_oQ&fxPUG%2J6{0Eo7Qgj-Gi(yyd~_}=3SFjQ3P#AKatoWrgYpdQNvYPk zxa=4$BQ8Y5^B*<^wD!Ir$q$FQusnz)A2F3r3+%zl{#+q>)i9Urzk17}`7Nsm)^z=1 z4O1`zw+P&{;L+T&UIYt_l@SsbvRA-DZaRg3i!ie1(_{qh57|ey>6bhIxx}B{jh0WB z@QIRaiVRgYvk0}^Iu$4(ZKT-HcZo+z{Lgp4k!3g7D8?f}7(Ew~!LbL0`a3GLDdUSz}H!l!Z) z;>R*SzUp2pHgP`eKd@bbbeCiY6GKoqw_EDU_NQ!+tYXY1TN$Tf$Meq1=CCAV56KG0 zx(j=$;B?7nB44<68FL&1@6IFt6-Hny6CxVVh4Vn3#ZvmEDVTz1F!tyXvc!HozwEFU7?;u7TU%>tF3;sFAFF_ky$L$75Lw{hV68S{diq6aLIt zGgs{n|0cZHXL;expAv+RF*OS#B(8Z0ntM(7Qq|(!b`_Vo&X@ish|fREyBIp;D1G2t z3orF&1$Sd;O-nebzDJp20jEukO`Yo!H$Zs&KGgXyATBjMm4y+QYgg1cr7C=>d`o!E ziJZATEGHijjSf}I#T1N)T|1lZxnA0N&_6u^Q9ds!`!^sy_57NRWe_+eF6dj<+2GVk zDj~cDv7|+(;SdhG3rqGmLws^K zfsAsdr#eg7*zrp%nKg2|Kt0yi?Fyy(PK++Y0nxQX>0DxLsLpLs#@Vt=H%4%7b)46o z#PAi_-vCi5acYi)z+94y!+VHhaqHSCRh&raaq46!uW>(|nBZ*FSRQ%UdY)5p&9gRm zI7$f2g-c7UW;AdtM(p)D;YiSEkVeUnNR3%RyLlL)=5L>AB{DicF=mmd#Yz&iZooe1 zDbycQKM~$xeaT2%doaLp?|@*c+HZHcIFZqYK!m(%7wbuuF-IyRn;`Bnm$+|#bdYD_qUy;w))ebrhO>wYgXKvw*4z;#2$QM_S;X$LiyyR=*+rNKgLW$9 zBD8Klc&`Y5iKIW+T+-)Vtrp2LFapaXr#fCLK^UIHXpeg7;u%@SIi=#6!p;~TuSeVSwy z%W!|uS<<4Lo26>UW6C(!eG(w)V7QMncWFsmSzO6>B@C9jukeMaw=V z2$esP$1aZX!Q+_pocOu~QT@eCM=25r%fmJb3HF#>GOj*{Ps_$*7mrstZs}yOeM!yd zzrK@2uwKGCao>)E#JQ|<(l2-ij|?{JUQ((JMb~5m=E9?g>`Kjbeh2+=J#kaEG_Eir z^N$N@Wa|8JXz@EH_j6w#F7A)?*;TS}K6Tui(Z7zXonDl7HfDJN;_Bz562wi9CQhXO zvfO_`Uu`p=3~xc?t4^sfyYlBV5)i6xfd41w#{;5vHOrE5W!dj&7XB{5V+reHa_L_4 zoS(&WkUZ-w>0OM#TAO^1%065?YyU>1I!e-abl(NfK4H~mu5=icc@vLp&d zV0mQ8H7GyGaBlsx6V{?Qx=oq|q~VSGCH2^*EO3%2Sl3EpchT!=C7Rmodey9e;FHQ4 zuviurjbzxvLXbxX{GxVCN=o(1Hl-6rNL)zg!>sMNsl;ZmYUJr8)dPK3@@tS^6G!C~ zujhw`os!2c9jj?$dKb0vSO`qmSyB_FVyNco>HOLR$o`=L$* zQ!rwmo_lI-8Rw9ypuvetm`6zu-b=J}#M%dI9I2m3?%}2-h$DT+OMQ+JQvZ{&7J*sC zYwd=CO>=OY;I_hVuM<-6bV+vcdhR%OYiEqWTv*2ta%}mml2H;7TFyzbAn|&ITLB(& zA6(LdT^n?hwGT!}Z8fBAthil&7Im%GlwrF)?L(qw@Xc0?1H)L0tYj^1(i+8RI}%#A zNbew&U-tZ5NF$w?bkz!G!kNw7K@i2-Ml+s*o26xz(UwK6HS>s()bP#&{672pIf-TO zTJcw-`{@Nenrp-}1w1KP5`rv)ToBzM$2LSmfz@}$MvMz@&ucH6tp~U2sD-RsMEx&6 zpcpM9#;<9H1cW-HCh#)*A9puAP(Pu%BIyh$S?&XJ_~1ULbZ+b z+LB@!ws}K^#gPn_Jo}`Cz+A&T6>Z9-#q?n7;vGx3@Bza6={jcD0+$xf4IX(2rw1YI8Hc>iFS=^P*pCvo zM3$BTGQ2~np+}M=5As0n>nFV9qu7b{@VY!gU>Ufya6{o!ThZ&=Dth%3yok^aUMKL* zRE#7UUJA9;ZH_mmbSusi5_2!9U2pPgc(^9mRy&5SeKKTBR_F17%6N6*hv4K@X zHT2&G0Y8k2STI&=41 z+nDKoTOddKXm}?q0lbZN3?uND;1s|lR-A2EkC|qv8s@@iGA>9n6nfJDL-FgtFODRL z?opbun$*!G3X<2{f20=RFp_@%7v4oDfA7VMq@UT;{?Bps*MJ~+&!7i2Rx)K6EhAdN zd*1Hu{pmuV(i9^kE~gNUgg}(>vDcv6`>#q6m#bOQfJ)8iK8S-PHz0EH#Vg2R@E@0i zCeNee#jMPS%E?wYDT$w`k*Z}WF$0acD@r2`FDk_0u>2)5Zf88)qO+wog_=ac2rLgy z6wTs9^^5zIBMJ4G#D(M)tV`C&;%sGg&k~R6MXa z&*po*R88W1wOVyH&~(SXti$v^+8ftBv~R3Cyo>Is6;4X0B+eOn@NA7Bv3<;ac4xDx zZrI#UGn|45%s^{q?&YSDq|KDjIuIk^3)x5^Cbs1#kkKc6teCLpC_7-8tzn9U7zO?G zvn@4FhOd#rhhD;GhzajIw1aL$6ba$cUn9?gC<%i|X;OG;q?m2@lKGe(&@jS?xNwWW z+vK|ki&Mr5e5!knguq;KTjl==78lZ^S#bOPj3jw#WK%q>6A=4RF+j6y3-`O8L!_j2 z1XvmE;2s6+$ViR2F!AK5Evxl+FC(wUL7SLTG6fKrYuQwd%)O0BQO^(EwOAgNVNM}s8qD7$|bK8-fbDe zH4-&RAtgSt7;{hYBuk+q_tfMBQ!pZ`54@ppT`?{yj;!H-y@Yrp1ISVkA|Wsrw$5NR2L)zcn{(F$O9_Fwu%!m^?N)n1T_q4fi2-kT|!q3cs^`kBTW6aW%G!rksQb)Z4}W zME@&+;+;(a>w2^_!wAeJTYdR)!-UDXA~tUDDao?Lh_s^aTKb*cG|z7o$aquNPdp1R zWCIuVk?cgwg{?Ctwbip3>A6$66W3H zk&HmvK(@#NEBc9p^GC7Y)~_YYQu?kmYiouN7BgziU>+;J$@3Y>kmf(>QZ-ogzju;G z@4qhVM63s~jv?m1eT8R!Bld0A4|x9^=?|<|uzn;j!vjQ}7WZl5=l3!Kb4fC4*crsk z%rA=BCx{Benha|=$y2m65cY$cUMYb~t!3*Kqb0<=zpX{~*VW4Lxs*#jD`f8y36XQ8 zjqr3npt!$w;SvQSu;onl_Hh;uy)$U61)K>ZieyLQ5|Vii-Gxi7$}GvMu~c&jA@%vn zWnG2UipFe_x20_9BU>Hs6JV`fI#C39t!A5_#?r{hshVND7Y)euVV;+ww1DfwX~Drj zR<`B@Eud>Oy*b_!X4KX4(IPf2hGkA`OECo_%(sSW=0(ZW{Z+AFbV_Wr==^;=yWihY z!w78S$~JYWInknO=p>fC{*VhsU@lx*$mMN}7L9I2u;j_U6kGIv-WfGxax-eM8_h5p zZsgj>3X=(TtoPJI3Z`I$EaO^r$ZWhZinh$2La|>2?^v+64YGLH#)*!thtctFm8HE5 z=8|?uJDCra{-WFD4v+n#WAuty%Eu7b$nj*S3Z_A>VDhyLFqTo8%S1E9_^)Q@S zkat_7M4jVN%)+vrH2N@_z_=nmCQ{?|;`qdX6hIuC$mZSeAjy!vDEvu>GU;LcJ2zWTG6)<7v2HDt8afJgxB;vtX`vq zRH7inLfT*R-?M`T92^WX+^zpF&86!)NH zEt9iF;bPv`1m?SBrqos#Em`D5sXS3!UUY?yzr2DGw8~%^*qZ<~&l)4vu+22`F<9XU zA#q9Thh5YdaWrxYZE*1-!xplHKy>>jAte8WbS7-$Hc)gJx{`YI z2fH1wgSaG;ZvWJ@pQy655*t1cyf_$vxg_15@nwoQRWpIMo<3Rfs^EIyb|d7Y@NK@LRN+}^2xF4 zA!0K`^)D#3ib)iNkSr&%J}pFie1Di-&loBrkVQt&$cG5*EkPpn)fpCabtsc42qD>w zBCZBJ;M8gz}kbMBHnv4{t+uyVC^)IWKf)Uv22VY;9pBSe6WzQR4&@cjX zVQ&J&!)Bg*G!n1T^_zXNym$M}jZH3(mGyGTM{F1)9LH!b$`6G}>D{x!FY zjwyJrhIe{!C+?b?_;aZtueRPrmni6T0ecW2{>nH|*xFa&%f=s(d@^{?DeYK^FZkiQ zL|HH!?`_mD+NhDN(+csNO(nk%@*2TS*2~kx&FW5U$@WJs*nfq+UwOU3pV_q|HS{|P z{*r<4T1ZWg@~ndAA<5%~xv*?l2O}nn%-eHV^piJ=@$6)+;Bq;*t2>|KtWz>#dZS6= z%AzIg^R7NBMqn;153&^Wj~2cUqS>Oew{o$k2y@{&K}J&3$>R8nxvZx}zKZR^3u1&; zyZkbGxoTI2EkHtk4T=)qgO{;^gN>3W6(b5J_-X;$V4ZAj535?8)ssYPJ%ue!Pm>T5 zm%qPe91r&d)Ea=uhnKUBkH)Z~9`PDM6pX<2gIxE`qJ%PZ6+1WMv5IX`Tqn66KbFM_ zv;D8=!E>u5|E|P^WJ3o2ty9H?V_n$64ND{hE}`rf^_>r1PN(a%VDkb+qM+}}{oxTi zSqv!$`FMLJYZ3(^%p@Tde!KO{oTdwP&%bm=JBi4qsKILZ2RQQ|=9d8~8e zGm!li{(?Zq&$sp4ODck4bWiy)SP zzXU$ZHnC!(tquEl)=^qzaHc|>84>p9&)vkGDNXqlmwXl17MBE<5LO)bej?quHn%CC z>Vmm&i^`=s-+G)lxi*g#RT!k;vg7Q8SWCc7)(Vrw(u}#Rqst2guQHem*9mm{uc@Nq zMpw41aD=qhVlHXjC5KHD#Knh+G`Y<tnT=QWrMqv4Fj zqO;4C12(y{AesZewus+t#G{fBD|_NxhL_DLjt0aOjKD1ouX#Kube>>ET#f?*XIaE~ z_2kTWuRfh|u0HckNlZ0H;0($b4W(K)(k1HPR2Qqi37p`l5ELyk_i6GWw_ah&8I$73 znzSPocxqf%?z}rw$}WZTI2p@A9O)U*98V(wG2~BWu~8qy4<^`X=}j7FS?|KAv9t@t ztsu`q|0q?D`x(ZS)d!?E6!6=ShGSP$Qe_4;&a(u~F#X^SR?RDz*L}H8!%@IMq`Rw0j#A@W%=K8L%GN7EmCIgQ(o1nu|B+C+S;1RZKZXEyj05v@v)_vO1TX& z0%s#4Baj`tgi>8R;LA9u2OQZifJ{r|eU@_-z(?|+d{jEvo6 zge=(x5$U=2yhF(H4OxfmQj$WXg?h7OiNx3?8Dty#m_hGz-^P+=>=|UwHWa)qk?l^J3;oG!7 z-Y!of)Gx~1hC^pov~NGOTP8gkz~4dGtdcIws}<}++n4%8u8Qk>0UL4!~&$`Rh3#y!xFHrvtWr$9dv4g!% zX7?}Y*ES1twp)ICtWrYTaRxzghfro_DZ6VSuIO)hg7C&?1@4lTp|hEXiNB*#&$9Nw zz&h}67M{UNT~mZjT~1i*XEI zYx+Iw_EAPg3uiO?)+Id0Z!G@ucK0gT&t2#XslR$Ke;VyOa>lBoj`oS$2SLtK7sjBd z=(5hH-Q->MD)oD_9F`hgRbc&scVj+*7-V_W7p)%c@6s@W0tLw{hR6oA^F4w zgEA9t1q6DB0Cs)w?^`Cw!@CUP2l4 z-B?L=K=VMY;V}GTqDiwpn#s^736Tcn?7v12feL0CV^CD6^IO~Sutb^iJODG9n7oI& z)X@>J>r`J&Ba|Wh@7gSQOOUk(o<=R!9WU0`cMXLB=h|u-p$z^z`s^rY?{U2kc-vyN zW$HgR>yDLp0_Gk`QT$)`&KoEDgNW|%GChMaD2o0y@tg_&J9=={@v!}8Z4=A zhN$gvIl5c>P$*ma5o1sk{TD$G{e^$DelZYkS6j?}IsF~<_u+cb)yaOSoF90kWw39T zqWJI7v-_Kep58G2O63_c%Zfv4+r;+yMy^gpWw`U7=4PcfDRNX(WRM7BB(={H&#Fnk zRway0!>XIrZ>&-crcZ;okxsVIZgKKP(PDMFzjs!*SN&v#9Vsg2Oh+H9j+5(};=VFb zQ&uF`nQfGuK$8*F)a>yt7FsXusx8af*jf*KAT#{DlxWr_YhRfs(h_V@zm09<6BBq} z*0|Xk8LxjDVV)|EhAXMTjKNURjy6lx8`65TJ~9gGH#7ULj)tWC$y$&IV{B>VV|BYJ z#fuU~{BSq3o<}5z>*!`^?hX>Ke)VF(eTB%grhHJF52o z(frQ6yE^|(EUr08gfQrrk88DI1?KTLv(@AT~s zZhq(%p$vk`>NVPySMH2_P*`&M_sLSv%`(sxjzqcvix9?dk?pfmW6sJjw*+Lw7d|jw z?Zs2fYE)tjh8jBBW-WUePb(>LO|H22$#kvW4}S4=0YM^+K~+MO^?z=rXO4wOarYEu zFfE}PBg+2y+4O%k4Ia)y^~xV<%l_hlwA956lA@TFoS*&795MsX#;H-0GYHDMa0HIp zN75281b@f%qEb43Pb`GJs;^jtFhuWmS(DE{!4t1bGRwI1=cctrJansBO)>^SSrb~@ z!e2j@3vBu|!Q~jPB~(ACVu;(?TW|WDq8f~y0%Ni^ z+Tc~RlqIV;GUnNM6j5p3df%5D)$&{6jKNT3Gz)R8Wk;P7k~1iZjvJ8~&{sFvf#)=y&Q;C!&$F%i>!!5+9>%{)`i+Ua zZoazsUIf&LSjia_MZZw-ctuY==V2`TReF_Cy3;z_jcE_%@nL<~H%9-mxO<>fxW0BU z8e(0+WDN2xSs$m{ihLg6-mI?pmF#%$rz=LrK;-ZOlSb%s`QQ9RUO(-3cPg|R8KpaQ zSZfRPz9kp9eWNJKI%A#9a`LjYrsAG)vC|8YeQ_}DRxDNmB)9S-z~M}c{ucm*`NiDkeQmzsN&@AFZ71?6XA6olQYP?%V*A? zDqb~xo=yUzEzY&%9Ta6%&NeY`ixfRePBvOUwVgTr`Xp%bF-y}3WrzW7eZ;)2c)oWD z!{xX3W`;u~{292BF&HZKaF!Ue8vXn8k#Q|L_sF(tQ83+oi54{S@vx620#OU+OXDvm z+wowsab?DMkRauw5XLTuYXg*7`(r^d8qa*n6<1bV^CCa ztxj3_F^grpUd@mJ4$JhtvDNx9`p3R%s4f%d<3uvVKC(rW$GpBj&pue zxd+CBC^%yi1-Od)b)jM?rf~b5t-4fmbYNE<&KNYS5!-*aiRT-nb@Y7vzsgITt#>TF zrMito2940?QhgLz53PDYdq;@>wl8N;6jfJY_|4a=A2kP$PHn*2_MmM-nqAJVk2?k^ zimB-Doo4G#4!#g?)Z`3`O31N^`;_&ED`fwmi@XWw7i+jPgv>gQLbl_XNA542pW@ zo?~k}^Q!c(fM>(*JtA|wxD^NJWfXtln-Dj2d`ZD0(B8kA$R#^Fqq z8HDf1^+?jOeI~*6@wkd35yoIMPVb`cb)%xmkWkB$F=*yw>3PzYI<-Jr+m@V2+9`2? zj&+&__d}~F79r1N8IH(wUalwXm^lh<7Q54fIky9m8 zkIP@Bde^dim4Pca&-u)fG|v;s>37wlUQ6 zYt0!H<^J3zI@zS9UCEBz4b`{mdb$ye%WaJ(D3b_bFdY*MMsL=0?-)?d57mb-7>cTr z*wXBP9+n#c_5}^)h%5QFR~dI?d}1FqR`}N*pMOAqPKto`J^W3|ps4K4&uqWP-;{34 zy5R5F;doSE2?z(blhsTbp$s}!@cfdd2lSTS;ZVEV1IC~zI@0hi?16jqe{N2I!slbP zi2B=>Q9lp&40UY%Q}Up*TKeNXSxV%kodc(?)gjN-0!GUoX> z-*juVZs8gN%WEEH42oi7Uc5RUs&k_8_Uz(SjKNSuF|a56XG?vpULl!K!5x^1Fl?jVhoC+8iOY~+`FZJ zO<8TM*nxQo?Vr(nj&#g0dmVIHXI^<=oL?WpJ8^`;ayxOZ+&S$ZoGkYqn!p$gMU)6D z+lQ{`Q+E!_c9vkqpnAo0Or$X&}$iByQbD2l0Q!l#ouDBd5=6+BRkK~bdB zh*i$scXXnq3zV5##Cni4XJnb0*t+VZc4;~kY|nmT42oizniz3BPp6k30T;VsEtI^S zqG)#!>(pznYRDf31yfck8leoDsR>c*hfBKUwIDbh_!VPN6zxaityT}O>94QhcN@|K z9r2`}Nism1cL`BD`44?LEd=KN+fh;mMe!cw(;7E)_@nXgZDE+C5z3%*7j}N;U(+Ab zf??w4VjE>p6rH<-2%UXTf65+;b%ta%f6$qMb{cV&dgQ!*K43Vgv#VJjhccMXi}6D) z>wg1>z{+vE7=xk6EFr|wtV|tSDF~{@q_OT2ol9soh`Ul+Ezl{oBEjoV4^4YsRJFP8 zx-MF!|FdWs6pwafJuiwXD%@{-*Kw}=3;mEd8&plw|IUko24W8LMo|XM2Jv<-_qY1U z?&s36{Rm)A2cqXxAMrNY_iway!QWE1;|zu(T8Ur#r5F0%lldy_=wR-EASkAf!Xfg7 zKJA*QuHG5K7z{ze!pL*Zp?56&R#HtqwMG}p-*3lEX#-c!QdB1~=b2@5iw^xWUH*)ofy`v!a~ z1n{jfoht*$^mwN_XV78&J`r_y+)&olr}{xv0#E*`Z)$U37<8X?&7{wwD5^0y&PQKY zPom1mQR6XNDmZOep6)f=e!^N9J;{-Jv4nTU^QyDwc^Q8Ib2!SNsO)!!$mt}rtCdu| zisT8E=A5XG#*Br18%`THYt4{{nqp0#qKLl??}JP`uKFaUs;|0@<_wC;e`AQh7E0^o zlD=BOh~HJ8i4{QSDZKyVv>{gS#amqGDpBjLA^g*%2uxBJS~Ngh5F|nw)Qg8s*^oT7<5nB+ty7aR z7%KR0Lo7TlMR-a5>Iavrs(IHQu)gwRC3>7Pgv6>-7*?GKiaTXL);p&v&l>`-zCFko z6t(^RNy9q-niOkG_P#z!y{Wdle+Le@?~X<&gE|lKj;gok6`somaUVk&gQBu~JU84t zu^T>p1iqt2^i37_W)xKaH9)_af85CKa#e~s9%@_hQ)A8d`SSgJFGW3`LUhkMug+(T zgo0fQ8H1s&-88IqPT>8*mGK>ok33O7dk%q?1D9$+B9y`XqKSErR5QFSHfST(WC(+y z3SSxGE_z!6@Cy=qO5IU|J%+*SuoR8QAsL4g7fF#2E(JjiiGOXxUSA*^NObLq{nOs7 z&gp^h_evL>58oKM+vZ5itYArc$uhMN|T7OY5GgOZn&2_S!vx>IY@;Tc@3hUaFJB|4|M8gX%+`MN#}l z=)I{=R2j$8u%t4c0YMlPMRf&lk4Ss3M#WWukbNFNBa}hCyx8+Hid6MqYQg7DjTnQX zm=cM+hegVzgBOh7QwEsg5Qi~$73PFPJV4w4hX%t0KUBNR_?< zcDDt5l^O^W>f$X%BtjX~%Z=wV9R8q=+#dn?U&h)fgQ6^#pBfI0@EtX~;XC$s74Tuw za2WC6fsIBegZskUPkg3|myd!9!H$|TD2gg7dev?Sh#&GDR9WJ#X@oMkzr9@UCv`mM zJLqchWDJU;iYmm>wx!|2>)vpxC0104gP%J4sXn6nGv~8v>(?JnW-ib)LK$2|hpwy$ z@%cSq?qQ6!D;5?y5113w~UuluudQfcO%&BM=B_4;ys|KqZ!}Hx8 zID?|91>uv9$!t712pvLrbKP0l7@m6IIgm6$86=Am;?2`&)ziBRY>TSR85EVV$`B#A z&%SjGz9S%dj#_?j6wIu9UI`kZnN##g!{T;ZTE~|3)t1FAQ?I`t1O0!sDM2HIL31L^ zG8!#Ze?*1B`Y!l4APk1uw9Y8FdskX6jK+7^Rwb(y8z;l&K>>PP|3D+YM}f@w^o^SB zv)0H9x+~Z1_Et0}!dk|kvlX791558uVhoDPJ{)LdKf{v@8`sBo6fIh*LL5Wk&Eut- zMi}GZexsx_YE3K2mI8`qsk;*lI8^}|z4k6qO{WEcZ^(X4 zBa|Wbq!}W5Bf1Ss+zGBLXR2itCW2pHx-KdgWK8e9QU)AdC@D($Z!`{jESG{$FHjgEx8clvolFOQxlN3ewe_{7E_KuvlEmal1j|Aq9{i&iMrh;_& z0!Jzxn__t1J2LFI40Utz6waWi$xepwT_P>Xxb_k5Eg#A=4qw8pKG;8}?$}gBxm2+p$s}U#lFME z((nlZqy9PWy3KPmLaYGd3 zPM)TzpO!M{xWT*PTRoLOoSOpE;?W^Qp2bkaHH)_{{9RgYemNPunxGq(L@0xf8zBaq zeI*Y*34=fj_KFCDp_t!i!rGg%Vb~=2XT&d>dVDBju8Ws3`-d$u^Cg~FExs#0CkNZ6 zK*(tPzar0KDB|S7zFJIOwcINbE;=V`K_YYnQzsAJk8|vuT!Ulq{+0yXMfYDP5M{8j zDQ5N(%04a*Vh*@421RY{=xn6VOP1bVB@UrR!@N}WdM}O3r_m!!c9ybPRN#2r_lGfR zZiyp)r@fn6T+>Acq0?K?2%UG?T>CM`N3A|sURejDKanyhijH~Fy_!Xhsp71noRC2y zltE@{?A^tKiuq(!d%r}dH)T*1RSEIuW1P!v@nk#yEiosS$1qkq4t1dUJzQ6lu#ehyGqJ5Pn{ z@8T8HC5mG6d8r~_HKFKg8LgxdAhclaebwH~0R){2IQH_9s(Aq;Ez zb;g1#=(F@1jEsXPx~lg0-F8@v=gpC4QB=V*2c!GFC$d&oe`L6)4ORYM#=@gZ6AT)m zj0$dR4foy;rCaMB$aq`VOKlz#2bXKkF)4$hs0ItM@An|}-TWEgyyTrpBa}h28a%Pr zxtE&QX9l!g>Y*uvqNoPr{4q0FZL1OjWf%XfsYX$Sqxpjn_3UBlQpNbsA#ll4uk|(Rz@0Q7v5= z_I$O{8LLr*!Ky}7yF|15J5`5X57gZaxa*fj=yOS}Mu^`|Z&&9RI>7rnSSg|milXZs zQD@3FRlLs^Jg!${6=7O!VJjK&sr-KRYGn_2k%9h1s%oSn%qqp=VDv9)$LSDgIv#f) z5XGS@7Frd-GqxgktAU&Ge!$J88H1vzu3$}O#bI?})g*ZN39I8o$tZ(XMex3f&AV01 zxydkNS|5WkNVSFPiV$=DJfcFa;gEbU#6~0ZxwI;RJ3z1QRJoB6aKq=NNf{JHl?eBk zr2nkSB!$7TpDSq^p$u9_5hA;IpQ`tEB4j$XV+@L-t1uz9*$=B1N5?{=P+Y5#)fPjM zYP1k5qYtP#u_K}7PkR`H)~u;^;e8WHrgCpN9NOmY(JVrrOKR3acx?YwRmHXQrgi8- zqN_N9qH2du@}B7`(lZpk`TRd?HNs#uauHZyS4)PBhk{GvSoNG%bZF%T*R?6R>XI3Z zPV%OVK~Yrg@Y}t;L$&N50jGwR(lkODv__8S$sF0Ewse~eIZ^#g%AhE|9xQIOKsG&9 zRd(@B0JbBO=A|@$6n%g1ZtU?)lO2u!VNev=yM{`AW1&p^;G`Bh&q6m9-RVhkT$(?M zOKZH0_;!A(hBIc!ltEB*w;P_4_M$qjqUWeC?PdUr5C&WCigBrR7IO9WnGn;Wo}xS1D1&CT zLPW*Zm1R;A;P1*EBxO((+leOjR%tGMmL|Z7HBBXrPzKFvvCrw@Dtq@&fWnJ2P0C;> zw!>{{L<_mcCjpA@&Nb<-Hp-w`EuK%^-Bs@EHWT)*@X(Y&QMAT^cd~AJoE2>khYsdp z&Gz|_dH`LwqxT#h{ak#03aqHMo$ufwt9!a`7vihS4duWtaj+m8G<9~(U;M+ liLBf@0c2saNf{Kyec^>yd}Xu3c*qamXwnE}&>U5W{{t;_7-0Ya literal 523584 zcmb@Pb$AuW`}ViEOYz_i!5xwnf@^@_K?1=E#2`QkAqnvl2n3e^ff6jZle4oM+@)A? zrxa;%DJ}5M%$}3pn*-lp|9Ep+Jdso-;U~SMjo0Uhg0Lj5pkC!_ zPfnl(iJaq$k%+HjrBqIA++9>ZJEXeh^AdJmnp$bbNiSlg%B@;{rO({n4g{)l zj4vk9d=Mk&UuylRL_2$M0xd|;GL&c;5>|$S&_1AmQg%--2Le^J+$37kHX`VG>JA^z z^lgF=rY}EQleFzs{FGzwqND@AnF&;3-3WqHJ3qzmdXzNi&mA&akigUmLe{!|%DdB1 z(ptZrCIVIFeC%i%y(7HlLRMA^rXBP2Vs%9_wWrah1px`PAc4I=5Pm-3ucvQ`CY94S z%2=XUH%E6>C0_3K{t>#?Ur$^aO;-0$H4&)7ej^Cy{QdQ~@MtnKW|NE-Brvst(58>S zzAZ4Cye+-iM4-x?51R9aw5;m0vclF!35k{uZ++&Lhy+@YprtO+7GrC>G*t>smBdno zD)fhah38zMIhR<@kw6tK1!;)8z1PyxRcPr-taQbt;n zG0(4+)r~C^tev)<;Kyf9cM&%Y+^(|U?P~VlFdZ#O)OhQ^`poImoc=z6DoVTB{h0|& z75bycDoxe5ePmdWpl1?k{=S`$3<6cQRDFXuc|S>AuqJ|ASlO`Du=1gKU}fj(SXOwh z$u~VJ(emNMf6E6F^h~U7zL6?C7piP!_zeQ{foW%XV>ZWpuo7ft#4NU)^W*RPpyv|l zxwwk8FQ#O)t#0`5<~m0U60E*i9vxGK1ge-{dp((b*y@9OXZc}%AXVS@!7bk)IBoV} zOBE+Dg|-s;h7YtL@%?;Y>$BAjKQGp%IaO%+24Qt9T_kMBT*cZjJGUc&ErYcqmM^CI zek(x>60G)E?j3y~fht;V8NJz@b6e^1bJo4rQm_Ku>(1HZJ5_J20XeGx~A%Q9zZEK0Y zudAZZ$lgX_-VQf&A)Q9MOK~G&#PUh?NREwtr5dkJi1iZdk{&bqN&U((6OHsJ^JYe%iT%1A(fuq&C@nufNTQXZdn^?Oq)@ffgiimMI9G z-dEA*9BR#p5sX>f1prvbUea%oLTp41-vSP~7duTDW!yE!`qJ>*~!axN-t5 zNPLQGLslMZW6Q^b1zGhciw1Dw?D_m8Pengo?rU%6C!ZSm@e-wTBDgCe-r4lEWefr> zNZk0T5P6X@-c}!fRLrk8T+o~QKmt|f`dBo*u)b%t2Pe>iL|{;P^7hs+n~!rvopfja zE)E2$uq_Ber6<|-XLUUtQib!~W6g zs)IR!?G*_rISWaQ4Uz^lSV4Q#d#BG@^;ky&RTu8%CH_PGZ7nf={u^y#?V;QUT9Cl} z2|}^AAGDgEyc`HrJ+$T~ua*YzQArRM<$tElA3ux}XhFhURyPj5)N1`{qzVaCyI)3ouR*xh}ZP=N-1G!2NI}im7GPI9UDX@@>cT6 z>9b5*3HN~(Bxrk+=!k0bv2oZxavjx?KoxD35^cwXT}5gCcwa@K*C_6TUY8_#UE*be zbwjTu61{fuk`{!yaW#}<+gox1El8MauzR6uO2Va94g{*`)lQ<g$Q?qn*R83@9YbyXBPXW%~2LT3OHoip&<;+goIL7{U7PM`$|I>tzJ&R{Dm zI%iPmoWX%W6}=irbk1PQ2c0u0bk4vDv>-vpD|nW1wy2X*%fE{Qfhv0Sk?1wb=40{n z!V0~raRMz!&?}roubei5UO5$d<>UlfkiaJvf}nY4Q|Q&%fj||uF+rd+0ENx~IDr-< z=+#c5GXq=cHe30FLdRVP0#)X=ORu#Gz1DI9&x=n&kmlD~gd=F3l|rgsswT3$)OZ+8Hwa$qCHjYdev=SqBx*wG(#2Cpi$PGN-Cd@mcb=;s${hB-Y(qELPeTMP|9qpgwADijwn| zpUizAfhsH!L6~)JsXQi|kq>*$*>$3Gw+-Shn)VSll0dl7YS6E%j#b7aq>tfqa~sRi8;Rx5G(XB zTBsoSHy9+JeCtS{3fr_G6iwMKUnyzy4||Vdt<-{g|oD_3^S>b2;^wU{0XrTZG}G-m2E}(+-Y=on|T=i3GvBtd}DBj zGnQl@%IZ9%<8W9s+i1&QqUz0`9}V~OiA=40DAU+vCI zV{AtPRf7l4RLjkdCMVDRNQv@ahG^lM;R7v5+z%eEiX~%7-Sl3RD6=h8EBnwGOX5;T zt2h3RAs_VqVo1M5YSHsi-qVw7LYP-)-q?ulx62E*Nt>y1%_&@?xSq~0ZhZc_| zFN*Z0#O`^)+R*AoKG1@Mlr&fERVAAA2`){EyZuLMUHlCnNTAA`k3WSe+T$UH540c= zRdu!+=@m_!Hy5WqMpT=qy<6@`pbE=S5I(dE*J5@VWrgK~rSKtei5jsXid669Onua; zJYJiU$H)g-kf`%`wA%7h45?AolM+8qoT2?S)9`@=s*2`YrZ$-wMOMtLO9`o}pGKY; z`9KR2`@Z_9j~~X6TO+(E(K}nD_NlMo0|`{U{X0p$J1UA;uQs7XjeC*WXcvP(3li6_ zELX4ejUvMex1hwR`vIEw0V7ptL4q_Gr&=DwkV21Gsyq^-wA4z54wx-0!4HLAbDMqT$f<$B!U-hTUG2}qD5tO)o zFlhuCJqDVmZE|gfbr7LWOxMY=M9PkX(MJE zsX_}9^}T&nY^7Sg|M) zDUYPYoyC*1u9FQP2i^VEtw-so|MG-rSFvOJ?@u01riAAoFkTCn$J4GXJA2<@I@~?Ky+IR#lUFw@&&$I3$f4nycv><_b5`_5k{WZCY zF$2JP$->A0wTBu*wzkb-nxhE9!@NDUAHod+=ORd4_&Q7tDIH5jY-eS4wRvaF|93|M zRZsHvQ`?P+CAtqAOFqYT(t5r!2(%#aB~L$f_vly>JdOF7e5$Q>s*W)uLjqL?5_+lK zLSsqQFRWcfu5F{$5)A?^NObJcOFbS&XZkM~@g}*s_U?>9V4W|#*jjykKbHLX%3S|+ zCgUe+=aUTr>lul)mE6^JYhy{eg|$TK=T@5B+mS#OrjS1C`?aMu!p9)cg2aX%?&|!M zSQ0|}3SE6uTWLS^awJe?&bd#-Uh7|9jQ-(ycbiLvT=9G)vmdkZs_&v;Ytt(hK8^`O z{!L%ho_7rbE%swJ64_~Ey!v(RSGAapKnoIn^+K%EE?da(-0c0tYr|CQvu~sdRSipS zbE!{L`*_GeN>r&=glxWSq^g)_q_yOE3;C#ci|q@?Si{a(NYcx}Vvf{7F5U9QlcWL7 zC=oV1JCSY~ME6QFtW7UiNVd1b#hlS8E}!XnH&o~*)(Q@@>K84fP5fv|v`D&WU2RJh zT97cO>PyxvB zO}%6DffgicY*^*eA$L3}(UJAR4HN&ccCeK$5~#wGrY$kcDz)z$BUQ04W?55?T1W@) z{^I9<>NUMtAfB9ET3M{KIJJdFkJbJ)sgG9^tCATf9SKxLwzpV2pR|z4eObHO{UKKU z^}Ru$1qtU8f=f~A<4$+>Y$@y4vZTd1M*>yYDh1(8)-kHrUj~5|Br5s1xfIABPagU= zqCWO^?xH^a3yNPRFS16f z^g8dv?xSkmb0QUgF$lCEF`?qtw8c5&NzU8sUadj)UZm=JM*>xQoEKXECKl2oh54xF znVVF(VGw9RVq3Ux+WWk;bPuq593giHa%Q_DfvR^86Rp7qE##R~UrPMq^isY0z#!0q zM3<-K(z?>p-IwA-i5>Su(lO1EKozz(L1_2mdG+Q~gFp)sMdO3^zoxAu%UE{LIdS1$ z)$+oTKoz!QnsYswTxentI3vTkRu^%zHP_D;a`+Ux)~0SyYZvq4DME`u4tuIDr;B%?SGT z4u5~tc;6@b?`issgJm>EBY~;~15c=aITLI?`g9G}o3(4r3A7+FD)E@Q`iFfsqGz5d zdicN)PM`$|`mPaw`^-pH`%)A2Bb}Ez5UASrFkO{av_Aqx5Fh8=Sy*?jm>W zRS%bH!c|DqtD4JreddI8PM`$|Pw#YfVD5Z2ALDg@y?pU44g{*qse16Kjh=5tWqu!J zIg+Hli;LjrD)nK7nyq3uKc?@kWxT5@2&;E>*2m;4%?Y$1v8K%?HEqTqTdL}=?5U3_ zP{@Hm6_$t~EL%N5&mEbS6KFxgyV!QM+O#eq zj(G|Qo2`~AH`nIl&XmUbvN=sSffgjp@5Aj{R#V@Qt~d~=YBxDTt-CeJ<|9X+O1kgs zwwyo<67>_Nsj{@nMiiJ+T+f%c8z<0$1irB+2$%Zj(;t=W<3OM)SINF=qfT3FKH3bv zrfoVtiWB(0;O)uv)ISUC=PIP>Z0X$_t>%x$+X-kv;&@^gb!fHiHXnOxWYNn980)o2 zpvs)87u8y6Ee9BP6TjzAu;v5gK ziwh3eQq{P|9BuC!W331YRAGtG`EKAQ?M|Kmhq6NA$;Z6vlCJ4CA18BZ+NM3@9SBrm zxe3CdYh|_6m&P*y%sHlT^&rtYC*YLLM~Rt7$mp}i{W)5Yz<0z2A>mXN^3paJMFLf0 zPZZw&`P6Bfk4dw1Y0q852R$!)AD_P$x-fTL*QINWlprk#ZVd`c=dT!79JCx z+*q|l3li5m?{s~1*=S>Qa338kS9Lbp6%wez5)lNktDCHjFxoC!kZ74V!PVQ#Xw!mF z@PU*3DZjDig#@aw+~_++ak?Bi#%NcVb4=ltj}66h&Gy-9(Dll7xu(C-&(VSe?VBPS zla1?Ov!U%HMxfawsb#3hhr4+l3l)2|>6oDN31o#vu!K1Io~VwwYis&`$FiLIkl z+w8T)*HER`ww3(+< zD#BO2rG z_8SwGeWMmQ5U8qq_kfuDYgUn^To7W8jZ&%&yT%DypWx?em~X#0C!!u#Ax)#OcaK+Q z=GQoZ79{4iP8Z+5%xm+JqgH@2L`!ubP-RZlprvhm~<@3<|AZAWhMHP5i5fhBpy}_7l*xP z@13*1Jf})1302&=540d*yHeXywfJTM#mTpq1A(dzH3o^hhiBm+h2|NdJ6Zy1QXIC(wcf#`6lo(jvX2QtLw<2vkKymvRZwPTPER9ih}s{vm=2jbE=m0 z+^BW)3E=r?@Hnsfv5CIbd!656OI7lS0{T;8j8|wuf{u0&Wm=;^NxjgUuG|L_ zsEXJXthSoF%I0IaXJb8eOA}7e@jN5mHKN&UHF3mTu0op5WP)qzr*A5pKnoK2gCf+C zo9tuz%$k+-yT#i%5U4Vz>ROip`jsEEapGvn?P{Cp#`SK~*i_Z2@(`XXdVS=P*hbs^ z{Yg)Kc(QS=MGF!~x2{l=r-a*belwT5p8T=|_kjeeutWsm_{}zY=e3nNffgi6ok&uh zW*Kt{L8!Yz)}P)puC+*@3d@atnS#dR?0NNpU(ZcBhun@?w?|dlv3IZ7-^jBg^=Tou zIDr<-6P-n6MC#HvQWD4M6*nJpAW+r)oUX1pUubp&i;ChIolivRGCxNjIQp+l&{Zu`*VC& zB0IL9R$qJcbYaK#-;GwXc3!An-_M87!qI}n;u9y;3w1}>X2=B>P1mobTyY>!g(V^g z@0QSYgRa#a$_j~*z9-a0`Rw!d=%-WlMFl%M5U9d(6NF}UZ))-7jOQgSM?Y4Bf1k$R zRvxQ7R1YmOqQNSh6v!`LlgJ%Wq$RYh#SJZ`pFyAni9XdHswF}~NX5pZDe++0Z(8m- zMl2Z;sQP79HnM)=M6$L{XG;9z^H3XK#)wx#3li@ZeNvZno??q>m_6v7)^3~e6bA`Z zl{%cCv~1_cBO>T}RMCstc-JvHtJ`|jAF7RMdbcDdiNCo#REy3H;jtO^5;5M{uD9%( z=AC9PD`v?#?k}~_qA4WH=Y1lciN4)txu@;BVB`ZWNR){a$o%k0WY%IfzW34YXjNK| zbVwDd8qIs7=FL5oY|1yA5^0lOYQ9;#Ie``=Jlp0cwG#b!TnK#+dE%eiaEl{>Dl9h| zmGbA`TBBQoxev4;G0R$z)GXj@^N}q5qrE=rNTAAGA3649)z?H0;6BiTM2uRH94hE* ztHDh>3+PMYdU3*Xs2KUue=Kji_G9)Y`NN)7$<;Mp{CB!;P^75-$HnfPKnoHhrRro) zv%xl^{**j=a*w_yAM71^JHhII*WnW6b%8Ow#n70B+Bx)@**!Ud>BW55Y2%IfJ=t>U zmGAa5`CyiB5yqSSU)&4oUn-b$&ItQ?naZ4xnokSrSN0lDAkl(^IUhIM6w`ZrGFD}f zK-CCZR(ok#8U5pY)ETY)l(9S?*xHXbx~$gm2_x?|Z7}sNLHO9{xK?3>4=1qSAu;0l z1vP9_81deeN?ZHva)-1DTgEvMs9G3%Sj|&nhAmZVpY71<-Sp!GT9BweajSalU4)IO zpl;Cytn%lC-NNEOK0Vo^_UIWwI>!|k$K1c5MsE(YwG!PUO&b+x#Cf3wi9XFPtIC)# zQtwwb1Bq#PT=TW%90^q6h$;x~w@zriTN`DC79=kAxvCB*6GmS6c~BqPlS<>&_%V%2Q)#@KWW=leHFb+tYqLKm(1Jw8 zk9*a2O(Uf8_INdo#;b9H#(bzWUQJ@{mBxIiG+s?&?U+UnsWe_qGUC-{dHHKJUX2rI zLE`PeIF-h$NjdHDY8s7K;{=V`Qfa)J#A?u zUQIIM)rw!UXf$5Ufk2fxRWx2rqw#8-KnoHy5>2J?YLXGJ=DaCNqw#7E1gfw^c)XfM z8o{N~cs0ouua;4pw3Vz{snK{fPS|ssnV^wqDvei@jCi$5W!GqBrUyC@ zs4~|%jaSoXyqZI*o;;0HX}p@0Y{aW&q>#s}X*6Dq6PR`+Xk3{}`#YG+vGS zpwVDf8n4Ft2aVcNX}lUgw*PL7?KJvKqw#7cf?1HT9~)OSB*xjtyTnnvT*IDwXL5rz*Mucpy>H3z~@GZl_Rf{=5Ahuk=N zDkp@-p5od8vC?Qa2GYGUGab&-j zc&S;ev}`Mj|G26RkqaL*S|SptO6eOey2&w;=PA~%j%xknQjH8BXhCAKlYs|j-DMY zrJVdxM4G-~dfHbm@yZz6(Sn3(jTH-?jFt}dXLph1!^X;^8yY^4K$SUFrJm1_8;2NU z$mth@&?|Ne??ai>tr*h<`qek+u(GaYdIZ`^q){Hd2KaBoeQU z7MFjDkpc^_7_4Po!{zlm4IgMh;#u!SV(ar!(y!~PP-5>{A33$0kq;zLRdM5J@zLKg z(pS=-60K50W#5N}540dL@5Fp@@#iRM-){B}r1RU+^74*`4A%_g zqS@ktF@?;iwcc{lm`LMs?0|``NTcBTo`aD^#Fx2pY79>Vj znl0}0ik1p*VDF^PsW?$~Tj5Bc3R?{AQE^f7vC2kST`s#)3{|2eDWawL`qFaoQ{O0Q zYt9y#>O9+>NO`-9L13LD5%eKRY&<$jDtMGdxE=fb0a!eKa zb4gk$mS`F!jUCpS`q=m}Q1;zs&p!vXhFiGiLV%ZIYz3)BixoWjFF!`F|M^ppepoSviMKAC@D`k z8%u=3L2}G&!v|WBcsamV^tluxjodnd5=AG*$Zzf%K9E4wm%6LOLnWf5VhJo>ZN=Uo zS&1@ypo+}*6KTAfw28*6nTaD6C&^o<8w6UAc)Zt7ymm51^2tA*`WSgOMz&lsQiTMn zXv~*LD$#`r15If%U&#AZQR&Na=obrffhV3=1CC3H~uV*sB5en^y;$Jbwsj7>NC8H z*yX|=*P{z9(#&U_#EYG_x@KExk%S}`S5!T0tyHMGL7)YRzH$3p{pMSwjcF`GVMoi2 zQjM|(ftGst4!Jr-Tcm=sJ7)6Xvt)}js<5LEBy#RN>Y5s6k%(VM>Z8%ijgm)cM*>we z=F64Ft4SI0YBG&ijNgRWvHimBy>_-+8>6MB~*sffgFaltGw% zcumoycMlv1RQ0TS&9&(Wixkb{)fOMyD=qzC5NJUH^F(8Q()-ILt2)jy4vr5HU#T%t z)z&#goUaJNiN8GLx8aU686=!v4HNH_j+Jh0V|8AkPG>pi6GsA74|DeuJ;uaJJ$byE zTSO;$`747!3ljh2>L(r=9V-pt@oGI!wUy7*F=k{)pvrS@FR^)Otkmf%YgbWA+Q?@` zgFp)sovQW{FVou0`x_%#CpVWrpD_rm^M1dy7Qfz)l|H`Y@oE{hDF{P`i*mnJ27&dA z1igzF{ny1x4`NwM%(}Rhe4@7_fhtTP{c`=8mhw#>gD_kEJ@1x2?qX0%tn`w{tJUAu zN?zW}kwBF>=QLi;mBy>_wo7Bl(rCOIAIa>;wsF?C0fUl#OPDZ_^OhpDtS@>7_p{tG`#Pu1~*_DpVbLy)~^7O>Nrf zfs{BkF}u{5zFotfW%$*b;p%+BA|1XvTue|>(z4`^mp=dHE`FXA=6dj=MM_F!zV zyX3mc<^wHAn0@@1JB#$;w&4Q_RMnX`-Szq^QcF$lCEfq4>yzbfUG z>Rva9?L8x1%bmAKb2@s9$*Hr`rss*5MqAxP%%33qFesaN)3(Bk79^AztI|5tQfShF zwe|_Ff4a7{UG8CbS*PDtxLXm>E5_zBBqu; znFy>cdi~>=4Crl}IfmlSCf9j`$=7pgE%G>(30RcY)=gJ@JG!PW1m zMLI6`7rQLoxL+?2FLmxwQ*77L;_7kIA_Wg(tz^@)Sn=9>gFp)sksF1y!j!%{qz)yD zWh*B&J?BWE3QL4OHE23U9Qc<(paqF%Zf^T$gb<5~3CrPwaw!%vO`s<7PXdl?Dm z#e+``qSVgvE*j{g2bN6iFi#aX1@h6TN)U)LHw(1Jv^#*17ps`SZAQ|2RVS{bSO zc}D_O?bkkZ8J#s=`mGAP6K>SbTYA3CAkczD#ZJkt>vveBtbS}3-lA}0X-&E#fvU#W zO1Q51%OZ_jpO+FoH6}`v;|&5WNQ_;w%C-1*i*zp^^U-)xd#U9PM*>yrU)FV9{f3T- z5$wrC%d+9p>JWoK3li@(r@CfOu}E`Eb)`h77T(fFTh5U{)u`V+UH`dnk#6uOEP*SN zrHV}rA2@r(d1`UbTY<~K$SV?bd^k@t7Lo>rK>#> zT_xks_w2{)`4wFYljtfL|DCUrDRh;L6KFw#t_VqVmCQ!aRWgOHl9_z4CwF#&J@=#Q zMiN~m<7)_fl}w?lWSpR@WD;G~<4^wSnwLaZ5&830J8e9NqpM^JT_rR5V3uzY#`8qF zN~X|NG6%wbUZyhVgRYV(bd`(~XhFi954uXG&{Z-A0#$UCOron~ww$}vy(wF4-`}O{ z%OYKI=cPzjXhgc=&X22~6r|H$lcZ04#eG4G8}izI#=C=PL85uJhoVzRh%}b3xW8ET zo1A0LaGok8Q1xt8HfhPkiBi70ooTzuKJKCHQ)UDw(1HYA`4#DkyKPlw#h`bx+cx9< zL?lo}*KsAf;?8SU5cU+kD35a;!+mtC{!naA(|gufaTn=|J1-x5i5O3vYc9Jc(-n74 zpyiRzUt+06Q>4mt#U0N?-_o$$lhZC3`9KR2#p48Narh)@314wPq1};lwI1n^DpakW z|3=)MYpN8Om#w&0p8Qhw$l}cjv>-uO#wEJqZd*5K8}z5#-r`803d@bJxXX0Ko%=uw z64>$ufv&jAbj96)K$W>Z=!&~SSKK*)79_B53c}Ng8x@xCZs;mxoh5%lK;vFD~RDQ9XbE#2DX56K=|#&I7=po*^Jigbn7 z)}z`#-ys*i>BkAQAVJr0MY_UkBi^f9<$*}wf`4p|%Isx6*6*INFNJAoe; z2yHFDFMQpV{Vw+p;%^fDOROnhTVxiefVT3l3%l^+gVF8&2hs7!1{X%$7ANs@vE$Wk zC&{ad=Tq77#pP`>`?z$9TV~hwl&6h4!H>tg_LCRwPU6QQVwX$=ru|h)U!IS#o&Q%p zFo#GK9aSogrK(xc)|q@DfvSsZhVEuWqf(g(%sJ-v*qm@)y4BxgE?rj6_VU><-kIm4 za;5)OR(M_{3eZ?mcBUFvGy6aSRp}$QbE3+|%miAFEYHE~VCA)m|Dy)c2NGXD<>hpl zJrgsPE)uBPTDBo4e%?PJ6H&3;c5azIag1E7^*(;Q%rhota{o*OT6RW7a8Emz$LBpW5v?mEa@C_{ zo#apPMm~xc=_q4gG1oa-kYHbSVEL$erb8wlI3m~oT8Oud61D&9)c}b$WsP<TWhT0{st_{OyJe>@bKOuOM8I}|Le+$K9Jb5Cz#VWf6AP5Bv6H8jJb5NpJU&i zy=?{eQ6wbuSTfl61h=fAS7aon1svtSukYI@Q+=QXiERVZIT7$Ib1T6XmsB!Y<$dty zasRQkBjMY7GpCoikIj@SZ0)GR>x#Los<3xkF0kSqAoVRN?I0Tvm7uU$<@#Pu0#6Jxo2= zOkht%V%#~M(=~Ty?zKpu>ihj1M;W9Ges?B=79{HbV9ZN4&dfY7K>}4cUoqz#uTfb4 z-*1U%L878yTob2?nP-+rpbEzrbEK5>$_46hRX|6{vCV*mEjoIY@MK&Dh-J)nnM9h)moSyzu=2;|1TacHJgA%Uv1`XQc=uMLN1BJeJy$iM|$m8ZV%f2=_yPNqk4 zda`roR)RH%Ds#IkH)On?cruc>T~M{V?hn*U9j5cAPPil6^Zt+3GF?KXpf%;_bDyY% z<8|RlB=OU%8d{LRJ<8}F3NgOA<`+fw+~1?&E^Ir}^AHkl?BRwxrwKw{FJHY*|0uF< z_g)PxNQ_vMg_QpsB&lUsEPZ4pU%f}OC{pp|J`;f|bE-xZ@YM^|jv`h1?bpzPMCm2} zsD;W*k%IUxW6MvE*IVbLdq{6gGZCo55)p*b!&|H;KHb)`yGTqsmIB@RC}T&)?-QsR zwV*i3+kLFOQ?+Anl!N~R6*kghAq z)JLUj0ZQr4F;ar>8VxN-n0*A)2vnv_j*+YjSDOe_HFI+zK7Y7NEBKCVFTDem28&~) zhfP;$Xh8z=WFHgRf5Q~qBlXAe4av4U-`X$rUnWeU`_E4n!h^C}(sE6&z_V)-> zVa@)lXQ@I95?GspFv&eYkNF%;)-PEn)1Boq_Ngtov@SXJgR!6Nf{6OW>fhJ4^J2Y$ z0ea)?F~qr(nLrip=t|!Mm>i%d7mXo*ZCER#1qmz#y1QdkfbLZ$hP3T(CQyZ?E(mL8 zw`edSsarjkbGnCH#?Gy{|Kwj!@{%u??YmSWfjP%LQn3`wKG1>$?zZ}U0#)`A!`OKd zQ-u~JzMl`YAc4Eanp1@Ys;~^{7ke$fN>D(QwEDsx8TZJ{yCNsa(qRH`uUQV~CPKkL zTPyKe;HxA~j*@yUF%zhw`%l7-p2Jdom3t9UlBMb%87)X)Y6W519$%$|B}&TsY`2L( z71lr9&r3~R->XVGyW%LAcFYs*2l{;iRp)7RcFF)_eb`K(1qqxDe4juS&OUhmP-y>< zSpT4XLZTxMVXI`gD<5*tg9Ko#vb5*=4;yF1d>zMb~kt+rm9u{$X48cJ(ZqP_MT1fCanto*(Yv>-wI z3hYvesX_u(v~Nmumhp{Lp#_QW=L0QB;C`39*JhLz5~#x6D|!FWY5yRse;|RSi+jM* zZ!V|$>a-7%INAr1Ko#we67A==WJ(Y`6s zafP>O-al&4UR%x9YcniJ;NH34Cs0NErbv73H+-N43ECfFA6`0^WTXlSRMB25(t8G* z4|+GD(7Oq#rExcrVL^hcN1tqg3kISdN)CgyNQTOzDoCIQBoCpH-QAI z%&DSx6AHbXkgC$V3A7+lZpl9)y_+D@`Q5~d)8mykIisWj^lkzPRGG`F%<6VE=8J<_ zD`9sN8M(!MSaBa!`ex>L2vpg7v+>po5~#wxQ@>B31qs|o)to9MP(^3X61|(?wP_~M zf&}iP`h5abxVJF9n}`k2#d0y^vN3PZ@Qx}vJD2FZofz}>^49|NQk`SS3S-`$VL<|S zKc@EvxhLq$-^Gx1#vMz>9@})rD$zR@-ivToWjf!z7^vUB5<|S{9Sd5Jp!0T#-mwtl zj%7k};Sdc)KIaRN{1NFv>W5^|XZ-5pgTDZALWBza_v-#bGZ;e2G^5htD zir#-9fhu!Z{X28#cM};qTjP})_pJU`&&EWwAVFvS61|(SjXwV}W&&08o*|>u|J5@e zXh8x?n!ee8xVqxG%T>yf#ZAXOSzld95k21+yXr-P&GR53AaY+zT-isKVW-1tHL{ zik|dWGcx;jYXvPxVEqe%TE41&RclVVb~F>H!uBQzP5al>FHVujx#dbmOJw&Sc7h#` z&-SahXG$1Z?aAKkubWy!FSkb|=bN=O5vanQg6ZzSFRJT{9=ehqH(TmxK|;#CPaHBX zg5>32TbMqex;|5OB_{{DnFv(jPQmm`Ds8IkGpe|fY=Le%T99}hw_EJEA%f^#*n54K zb63~vJ#Zo0)|d%Y(Jwl{?%COYuBKP>cOl82-E_1dQTS$(I6fhY3=R#UK4!I`#HSWy za=%t40#&##wjhN5UR4iT*@9$W(Mm@P64*ECD0-->9yzH6@g!yfRoFM_?x)RfY=6+^ z9luwzj{vNm?IQy_wvRFF*i4`W32ZUnCs1W?iH46qia9GEJIhkSJ6XZ=VhZQpO%hMc zi6RZcOVLyvxL8y9^9NblRbNrif&}i1PNVy$)>O_em!yC&Gl8n+K5=5b$I)cnO7~LtW&&0728D}{CdQCCHQ0OM?SHAEXm>@a zLGhLfT97dB*4$xs4dwAdQ5x0VOrYwAUH!!#^Nqdf1!1wDymM!v-rLy>fPROA@0iWr z>_2#cKY?NRfSiH^B3LD}_cY z`4+(}NZ5}JV*l5KhQ~jztj}_8_kjdE{yM9ixa+F1hd7PF0s<{~Ui!V1j2+0oPoQes zg>=`ebk8s&RWu(8&AC)-|G5Te`4(Z^v3!eQ79{M)2C?~v0Xv@L4BEzK8Fn8?uw#4v z90|1GdF`d}zX?Y zzk1f%kw8^?fnMsxy~ZA}biAT1aRhCNL#h?F;!e6tTdYz^S7S%u2K82{G46B^>B(%Z zs5~Y5Q$pTU&lL$&;XcE3-rg%z*>*WWdh~v|X*Xjes+Xt!xO!uko!lKW9|8ttMWcn=0)jhwA z1gdbSX!^D3_rc2cH#4OUH>$~KLE=~EWVMoa6uEl61NHGM{o+uGQZuC?<2#rLRN?;B zbVr?ECo9uv6rS&IlVr3YaXjBjbvk`k7cjjg^|4`2kTTjUPWmxnrinlm?!!&LfN7ba z1WK{e#X?JEv>@?3WrbQhG>V*@CQ%>v=ld&r7eq^M)Kn9JD%>5M?uw}SDCu`2B&R!v zWwanM?NyT6XJr)Gb)J3erSdPMl-ModlE3A>wQ~B)$x}} z>Tr7A_%lsJGf`6;t|UGWm5Q!^Afp9|&ZCmlXu4PYId2vxTwu`dV>Fn+|CIVHs zTRV;CY}j8}^uq*c!P*=OT97zG_oH{Y8%07II#VA_4tXdkXMLnivkRFBRN=1kf>8C8 zyK-aDDCvi$#TB$5ajfzZ_2r`|`c2uI)JM&6os>sEc}pHe%a{mMh4fpb7Cj$DZf{{< zPs&=!O{re2pL8Ikx`GxYDqotfE@>1^M$Tv7LOPhExpMbmSLyEb1||Yk&S&SV?LJ45 zW;!FzFKDQYJ=G{ISif7JdlF$4$3R;lpGIF+BWNtJ`+t2QC-ba*FB7b(4a`orZ8mp;@IHy@r_xRK*;K zRkxp@sq$jP1Ld}SWc^36>hzHcT9DXvFjk!?#E>7$FrwC?3$oYpXJT%bF(v|4e|Sf! z0h9=+!Md|sf?I4E=umxet|f+%w!XRD%^pb z*2f>c<>LM67TO+D6|^9+n(kA6<_&#C)<>nLrip^-Z4|oXl%oF|y45>vR_)v><_V6n<~OXUKo;ZPXCw zA~@r)|IWUb@@>NQ6)2T{D~hnMpV(=G`2E<(9W|W7`3xD)g{o`xS`tXFC5{AIkf2|n zQt20{{tp6GN_~H|#b-NVpYQ(OI9~&_e2Xx?X7w$CS&*Wkg6Gl~Qq}^py^xIaP-Phm+=uL#-i8 zLUpttF)^FFy8mV@IThED`e@Vq63OHLhjq&G=_UeIxSKs)wY*tc8#%PDx={$x(SpR! zb==isH)6?>nas!D3T3rs*V;U zhBWG>KHn2dhW*LPDmFA+dvJe_YFRzmM4+l;k6!BWF#2Ts1tY56U#h7cH>*WnPtehV zgt;wD43v&WR=SMlwPP z{6WuosStU;X`qQf)$prcYJq04r27H(O^&tJeERW;WyzWqy>(O-oZ_YC^NS@7=X4j% z#1rR|`hCTj3|-V!M+*`Q_IRn|$H$V?Bh1IkGbQzo@12RYteHSn_WNGyxu&ti^%x_% z_N}bfPH#$PooJ(@1&Q5*hO3L+V~I~X`$o##33c?Z1zVBP4_!?Js_q95SH+UCq%J2W zt!t*Yn%b4Tz1KiT3ldom4p)a3k0mdP^rk*)_GqqGZ0=568Z^++g2XRB4_CD=vE(=> z%AIo42VCe!vhS~EB2X2VI$FK)cMSQUvoCpO`>msX{=rZZf3S>>79_Gy9Id`-7)zp) z7%@!r(9bpVA-=r|n+R0Zc|2Ne`6-6fsLJkA)e|22o6A0=Y;++VEl7+!I$Blh$C4G* z7!fnUQ@=HOBAK^1n~6ZxzOO#&fxl(wd*DVRiwc<)$$;Q6neynUHwPtdws%5=-I0pT96o1aGYAsDVC)C z#)wYa#_5emN0KRS=_UeIkxhKnpDxq+75|>)^WFY>qxI2ba+XvLEl6z1?W^|77fZHW z8_x1^W1@cjuUOJLAkjpis=l|cs$7a8&rXh@#OXdkdTu3-e65(Ep#=%S%~!pYCzd3f zV#KT1Df+%#@nndfkBLClmic}v{kA2Er{A^|g!nyE^^}$~$=|11X(kJt_qRYl)jvxt z$&sBA|Ioe3pG3_fuP^2`5vYo@`l;zBW5^P>@swyaK16SSWEN>T{~v-DBu>xsQ)7RK zC7U_%Zq;=CV?Y8)te<2eP}Q%ize>MONtX6zU#I-7L8w0cU;?QOtTD}KiHpAvDwGJdiKl`ElAL>JzD8^Ao+ad`vj`? zx4CJ3Ki^LDr_ZmZ(&twr{;A+Xzn^ENU)duphh7zftuOM#^W#_5gRRf$akf6Jtekp= zDuwCutI&6AR3uR4S1-gm?Xrao&mBOCoi#(1$0R|TH?cZF3la^+PP6u>KK{(bh*93t zm9g##(!oBvOa!W4&75w%b;&{=)nx6ePFRR?^V}?H_n{92El4b_HQhQZcRcBrn-OOd zgB5q{Ole@X`Wh0bsudh&)h}8|n|SuUzR1+6%1r4Wi?usXtpZv>;LaL%8)pj(Aex1|xn+ z3{aX@j*)&Xyw*gZs+eb_wd8pV`KWkPBFfiK$@?lwiYmH8LkkjTibq;+XNxEGWkx*h zI97=)6d|okJ7pqJ)xL0yHSCOqB)uF=iN`^sl{9ffqXAn|43EbHOFEp(ld z5l0d_DJzn_rMizxn+R0BdzfeqK4>A&oY)uTl*D$*-kO7@#h)tZXhCAnmPD)c!9q@z zVMOi`k}~Kj^S|$Qjdz=?q|E6m!JyO_Ars~4xO1CI?DeIH^I$DsJ{9=Li_-hLp z$%*nk8!Bfb+Do-tHZu{Z`Z9TuHCnZh1y0PzA7AS$opZI5rp7hb(Sk&p>mqBPR~AA_ zF{0a|YD)fLE|N88D-(gLtZkF6n|D}<=FjGEZdzI8%C!2@KOP-*v>;Jr+)8Wn-z{YB zdPdaj|D#ftRF+zt>R}>KRqOUD>)~y*K0bD%ghUD{;>(KCswW;gT9C-GVU>0EBMWK# znGqLcP)DJqqF=4m2ORbfM_HE)WA=uT`-U2fPr`H!}_rL&PkbhIEbC4Hkc{knw| zY0HQX&u_|SYJU)&&W|(^sOlnaw&wcTLJpr|caVu&ugS}2y%85I7^R~HiGn#cTW|ep zA$QI*qTrhI@(151V)Di@CIVGb@2%GU$+XVB8PRKiD%U3$MDljLjus?b&+M_DS!f}7 zp0j(L!q+y*RfZi9%RKVe(SpS9ZTDE6PFu)9eqTGb?>u?lwKd`|WrIuvsusW8XT3j< z`q;{RcyCLPv!<*R7o82#(SpR;J^QRDj$267c1Cz~_K_o!BSfw2PbLCYPfH!L=8U$G zYW$w_@X*$B?ni6!(Y6-QF zLZjK8aO&@0r069D#5-R@bhIE*$K{xH(k|*_93$T6SSp40+Tt*YvU0X zGM&#d-aacL9SW`Ln&)z;jus@$bB2-D*4E{pJ@@aXPd|`A70x*ReHvA(&>!1zW`XmE z!L}KP`S}$i(1L{h*dVI*oxNkRS2BNo^(}&_-i;gi^TO8gwx>}@pasuMzZUF5zexOl z5UARHa=S~2XeaDXqpmq;ZGe_<5yto1zeO+$682+*I6g#h{c&}{7I*3MM7`%$>)$JA z-7d=};>swlvC@^eeWTTC^=G6FpkIka0#&cOF18NaN5`w0>`7{~rN`7-9(U3LpNE>( zYoCQAS!X@7klXXKiDu&T$Esw<_7>KsCqfmpAh99OV(Xa~v=5%iMtw}LHIMkNUt`sJ zn+a6Sa++k_bk#yaZ?jbO?fZ&^X343RZ!%p$3ld)SJgt{X#*;QL>DR`Et4C^UtGl|X z=ekWZ5vZ!Wx2JU%9osJ^v%OMAS8to~gW zGwtl6tR%s8n2A8ugo<0!7Uzs7Id3y!%JBEvqszI;TWN@b79@TdyE$z=^>KbPBi@zI zq7PeGm^5lP&_tkWTexr9`@Hew&H=U_)#FA!y~*OTBsH$Lf)*rh$2g@mYZXtn20Bq< zq*Ow$*0d&R)ZX1hpsLH$a%o-j$CG_2jA-(@v|eFqUGivuCj~7?rr}UF0%*U6vvi>%uH~HmLO%s8tI*U_VXf#!7|C*Gz z8Q5O0RLzSFyjNa93lh~YWOG?aOSf6WI+TcM)lDDwU=(qmQ_Mu5%DIH#Qk43*)148~ ztv&QpiVw-(sjz|;Bwl>X?lPbHc+-IqwT}1E?{)PjRYUTa2vk+_adRm^TggLzw&I>N ze~@0~$z<}{@VHc{3lhCfjB=SveI(pxgp=o3eQv1;a?tOTi9prqz&MvD^p5_6%D%0> zWTc;-^gN1mQ+CK`LE`$(M3-}NJo!TRyr8SEF%$G6Vk{Y1VX28gRj$LcU8YeVZt0BZ zdugJc|9vcRS(zxK1&JjQ^IUdPAGtkRQQ}o-?NDcid)?HCaoU2vp^aPI386XBitR zFrs%+MRYnUEH>+%PDNcRFhp~H{$1SGohngjjsx=NuNT8}=$!#w6sgK7) z*u8U(VxfB99SI~4jY2^S688CuG0SlG3e_LpNFZAAG*={0WuBM(`#dU4$DP=5Pj}n8 zA>XC=Up;%`g%%|2(Wj_p$7UZ$;|}deh3RNP!uGW78>vD9Rk)|S*#})OmFT%?nbT*> zSK}l~@#C^?$Hh5oQ*FC7|I38wXsLVmfSCJhR!-oV{?)UbqXmh1t<%N#FWG#-{AVUm z#Ug%L+@D#`e6Tn1SdN*6&7uEVUaB%Xw(myGj`1%{zutML>!ZuZIMFdUr}(Mu0e;L% zgRLT?njP~x&#)kI;!9p}SnqUBBV{H~WshA%wc!KXQsuI>)k0VIi_G%2XACUE-u1gid9K9CrdcuZaW!@h6$z;mGr%g~&v zc9SF2x?7D>te-GVm8Dg@d~EgfjUH8Kf0EcPG=i(zluQ;EO$g=3?0X!H!t=A^FdgeQ zqSn0RV==pMWAAeOsV2!f~9NgY2PR-9N}rlSQ3c2!{Q7u80p zkU-VK+;v@-t~vD$A2<$P`PfiA*K8kG(cZ*k!ySE~1&KUiUBo9PwtvG15~yM&%SzbM z2U?J5u<-v8b{=3=D_a}Jf>=D2fUex^z(Ny;tmt z1r?GVd-qte_uhN2|C-rs&&u!ip7T8So*cgK&B{z>CzDBLjXx=RccYOQn7}U9LfF~; zGY0(icdN#&on=m9XYo&>(`i*+o57x4VKunkd*#q#?8z5eyZ-9Kx7mLi{(-iO6inp* znvD>+^+5(yxuRWv?)rO6#0n-3+hoa}(QMpR`%kQj3GBj0iy3V>FflYUTb5e88;ODU zgHQxBcIDTIk#mj}Osw+UDCbP- zVVqOf`1SF@arhw5+vLT(fMO zx02rqCbDj9A}_-H_z_}COJG<2FU?2{tYD(($YmsIezcJon82*Jc!Nib|WAa?{3{Gq73KQ6s-@h_a4y<5e-m&BIIj6x!VqgNh z@RNo1sIY>GZCNMfx4vCGu$yhis+hno+<(MWtcve4IR|6O{pL$$=J@*^2P>FxNR21H z2aWZ2F@atA?M=Z)#I|EqtY8ANrW2Mq{eKhKg?odTidFI5vTe6bO!VaLs$L!kv3`F&so6Q$o< z=5F|Pg45cPV* zOv7%r{ku=i6-u(1PW-TLuM+>W&bRxt4x z)TH1MdsF{yzGFf9D^3j*ym#axN<={sn7G zjulK48GMXPDsF6a5EIzN+B2(pynnXMM<9PIn3zCLkeqs6{0K3nC9sP^f5^Ap;yu`{ zkAW3TNJmbRM@0P(0=x8ks`6JtuV7+h=1Ed?hUd<|9hIKIu3=D)MxV**KMAa0V#kFO zWS^g{k*5hvU|0V6Fmi>%3MLZZdN{DGv8N(TU>AN{!_Na>7m#fk&PTzzX4J6F{yrQ^ z-VRF6{?7h8_BVkQO#J`z@xKUtP2(DYFR&ZANnNkDr-}U=sj#A>0xLx-EOSHUR1;-Z zT(~j?R;HXtN-EZtqxj$97#q4ubhj7X9N1XJ3MR(HnkXN?g)2Szx|YlDHj)mvXh&;h zyQ)~hgwX7Z+`)Q+G6u4l!E)OR8c8N^+tO=4Tve=K!ff~#*>di9r68=l32RR7aFOo4 zZbO&fcGD2pwE_Bx(a=w{y2I{lrq(V}Mzc2b*2E?%Rxkl8eaf&ZYJT3q7vr3zjEvSa zseDrnfnD=@Jd$Vji^?Zzwb_}q;p}mqVFOlolwsXRuJj$WMegRL&kqOdM9Q#&q!9uu znD~1POkfwRUMa)6rbc351rxYTCMHw&)mK{twou+I6r@Ho-^nG4O;k3TL!Ps_Uu9T_ zRY^LULS83*l{+2MZ^JyVvUSwi=0qv1G?VbL<65w|c22(kFg8E)*A{aJ)zywF>+eVs zRxmO6`8hduW2_ReaRZ#ezE+NExVNa(fm}$Kz^+ktdGegqvC6xR>wu_R$5HLyUsRet z5GCw7+9*%19~`TE0GF01zr#^|`dw5~14Ridm}p>sUv3-~rEH$gMvDU5)m6W*l$5!* zsfNI=6z@l}4T)0T?VS(A39owUrvuHD!XJr*6-?k-hp!XP)l+NsZmtxcpe3+t*tBwTFhluJhe5%l?&P zl~*HuftWSTNxjpdr84rWhl&+UEO5CjoAiv$&yrTOSOax+UQ4C)P%VL7-D}^Mt)Z1v z=j$RDN@$?cexAyn_wFiIF!7@GBl*5tlv3I{1dhsneM7bT+E$9m^`;sEyYTN3vYw7~ zR<|XzRxGMERk4Bz?KwBS`#7sXn}Y01SqWBgm0=ZVo{7nDHDKr5aFx(!X!;w0U9je? z4C~kC=XAmZRxp8E3|y(vQDFkRa0@jt$;@gbeJ|0Do_Xjh;r-%rq`KN-RVFeTa%q^_=y&0=?<~h%-ez{4v6>s`$ zs*8reF6~iu+36oIMTdhevOB$?4uE09(yyPQu$}5eo>$hRGW(8JK=YQ7{SiuCYg})Qng=?LENzSvR z9jJf8*>F^>jT&OGZNuO7x!VliQ)7ZDm@sVXiIh*-E+clHY{-5e1_kezZ5u|Z*fz{2 zM+8<3N5WjNvb_Rp-sk^5{zhQe?nd^C8c zn((}DkPZ8-3;Sg`$o@`X1rs>7iOHtQleazHzleWzk6kz(tWB@HEj2X1U-CBsy9{-h zpH~gVzzQY|HT}N{>@u8LZ6-EF7GGe zUO4Vw!&>NyL#dGbUN|POf(b*6{7h^p1}3n}P!2ue_O7;i^O%Ry9`Xo7?qC_R4O5nF z*z;?uEZj(pXH&Pg*?Jo!31OrmP4duTHreCk%h(8 zR_A+pDEWDWe=C@P>~b>X5zb%1ewkETeQV;OG}Gr1{!L&PWV4g2bv6)?L0JtdE+{O6 zGA;)`!o;VGWXRG?^;w#m4Yya@cNP>^$kL1zOhEojd7+X(^=I(tL3_2w4nZ-6Owbwv zxgcMs3|XP`3CM2j4B3qvurUD0@hLa`9?ccV{V79sW4;YpL}kcsY=poHCjK4+6WFCK zN5RT=QeKoBWf^;`f8Hgxc8jOBkT1Bf*=~7Xa6Ih-+mKmThK#*bpRxB*mYtMZs|mdV z8GA8-U67YoHf4B~(_0(tV{Y_vO zu0xnHQrJ#P9Oy<9AXhOyD#%+bA087=|1r(flnJsMAFCn7Rd=J4ARjU=EhZqdvb-Z8 zfeyaLdiq0$*O2<|aivor=Q1X+3-T|^kk^_1&g(2KtK>>|Kwf98U;?tx%JCjals!|y zY6YvSOC7H^ri&nVG$ybM@<_{&d784!)9}r9Y<218*2eS=VG_g$eOyZ#ywshRhWxvjz%IzeD?^T7s?YJ8=w4f@ z^3|P2LyljpU;?rQ%Uhv#UoQxR7-lPLOAezv=u*fdj0x<5oWe5XDyI5e#W#xCOHJ;1 z(Djh37%P~#{RL*mxW?1&JcF{kr@a(cQ=q1h4;d5K)u`BRdBE^^T7?s_{`S%oQJ}{l z=Q36>0oj}7)1M~MLNnSzIc~qQmon}P)DQAHV*s zzsJA?cHtw0XSMQ<>eu$7GFhM9m|rbfbbN%6!&rvw##Eo(c<*@!^>qPJ$5Tfqcm zA(s8!lIXLy_2GO#c4HN?8!P$Qjeir^TBsr*MdsAf@WH-hNCf@f> zmG5LFQM2W&PwiaRL5*^x$|J~bj0x<59L6$aH>UdR#;woRQI*?7X{66?{9C~UWCfPz z_DiAqzG$1Nb<~G*h!UjFZv30TF32e?Lw4hQ0&*2Mg6zi5?3_c+Re6b9Dpw%iuMF9Z z`8H&Am8(rPMqmXKe~*C)?7~O*?+nl?klomDRP3A^Vz6z)-+%YpdG8eyOu>X(WH)9{EG)Y*kB;}twhiTD+t6=E1Xc`3!d!-0 z_}>I}LB3z!#`J{Y`GaLQHn>=y)8Jy;hQI%vUq};LlL=Aym&$`AD|FC5GE1X?R z*40VW1$=|-thFF#CQ>l5xzBCu=6$T)IlOfsdD zcnrJcx+(2;$Stm9T;dIX8t^98aPLdNRVJ=1txC)X(yzgdrLNyNaDjA}{%!U`rn_n1tArY6zV$Jrd-ghB<>T7H&F`Io&l1a^(HpGxfKBvGHy zY@FK6*<9UnrLyAiwVQ+$Oa#@KN_O{4qNUd{qQ}M3s^Vy;Y_099A+T%F(5d9=^d#C( z$A}jbZPcOj9hJlWJ`z?iaeV#^5?wQiisM-R-NkF{)WgRNTj=WGGgcy7q#%AHcBP4CK>{}HlCS9t~N@d zYf=~yconkNZTC@%Z*rEff{AC{=8~3Y66vMPnn0{B-CVs=&`-&pX0IWzYroTcV*enK zZtCg)M7JSc>VPo;%F{}fC9Gg#_}KX*Xk8+`-`)|3iI+O4Yk~unH#My^1a|ESn@>z{ zC(_D1cXaJNzUq(z!Aj5)O9?BOI9zlg88bPNy2Uy{j1}%Z)eXhQDEAf=(Gb{GHFyyb z;i&vauo<~C7x!0(cZg6j7rzs+f{CzCi%8?3L~3!^6^KEn2B`~w#3-r5?r8|@8vSe$ zIRalL9o8}8g7pwJb62dgq3TT$E0{O}v*-eV7=DQn=C=dYo7r*7?6iv_Rxt7Q!ea8Z zMV=JYc1 zy=o#Y9>?bJCfi4=5%n_^r^-huCa~*^<8pGjLn1xbt~U_3O2w!TH)kjXL%k_hF!9rA zIXPgRNXuso0OEmPjN0LHhSF%}ID!f6+U~NPw1gODlNn(TdG7i`o;%s6rhpYpK)zoB zIfbcyo^S&o1_3cE&ng!a*ai8839P4(PZ;{UzaYD@!Nsz*7+h@I@OOO-V+2z$Vc6Ca zklok?vK#XrvO&T7W!r}D_Y5w!ZTP!BhB1OEm@sVX2|suXFaa|Bjh*V@VNmdX*>(?~Q3SFf($`(XpyZ33 zVx-KykgspQt%3>cYCmHnnOPu(29_KF#I)JbQnBC+8rWdDf)z|W+BK3~Ii5^|Ik6%j zO6smop`FBE8Unipg^whD1yiW4T`|l{kg!&Xv$%1ry4wkp!|+(v3VjrFqUo zX;F*Gv}b$^4S`)-gb?zjcnUqXWiZ4z96Daw|1FKWe;TgC3MO9rhmhb4$#e)O?zRe( zX1J!(T5~fr1a_^q3?cUBDfH9pK@g+Fm9f&+&na|x%yb=AFyZSOLL%~@hs?8uR^Ks7 za>-1h^UXJC2<+-&GMpq;OrZx)^@AA0lZH!2IwjB=miu&A!9;2M;pD=-WIFCRBN~4k zB9&?!N863Nsv)qe&Dvn{ta1vS`?fC-zB7hMPTync;VRd4Si!`KpTXqi{bZUokj3cW z-d_@LPNWwtK4=K+dc7lvG;&U%u4Q@wVd2_K`ch*oJ^ZV%iWN*uzY;_ie@&*NOEIE^ zi?2lM1=H|>r8NY0ee@0@KN`VP(U6`%WbN%N4c|13E;K8nVg(b`*9VaY-=L?jFyfG3 zJLy=f0d&jwDjEX2+$IkqeSA`=^n>NOvmV@Ba_#R&A2qO7v4V*jn+B1WRw=a7H%6S1 zn@ILEeCUZ2&Kd%{uC*RSoI9pac>^Q-J)1}YC4A`Qwk|4mIY$g4&23U>q}r8eiI?5# zOP5|Yr+0q|DpoMD{b@fk$1Q~_r`SCzub`c@VSpRGZ_!FaV3*naexyN23f+^%2xYX5 zBu#Uq_XhZ=Si!`hJ^jdqCMk5`7DluSv6e0mcc8WHI%o*&8rr2F`93m*W`r}s%*I^W zrBtSiig#DBf{B|Qdy$X5Qm9!kA0VDtn@E#8SEmmAGdn$=KHcrI~CN_8PK*Cn1(APZsUbPJ! z#ZbQ>G9q)LhQO{)HXTUY>nU^;&s^W|cxCZWa04>pQ>2O&Ou#jYjLJ-*_fp!yQAGq+ z6r=XmBZVxYGz4~;-t{3#H&W=OL`Gcye1={;^+ag7HX8DUW98rd`kie_e%(!>pI@{0 z2B~>{sdJ|Z!uTaI8UnjgcC;i86;f%%D~#CWw?}y2_q6*v$nuXBO#IWVB{^Lwm4@&P ze_3|xJl+ze>Dym1DpoK7IfaSms}!owJbWahU9Q`t0eiCkAAw!4QUZaM67q?E$D??5 zej6Qv=r%WV5$VMA;hRYo%6rhQ>u+3RIxawST|3MMkg9Tw*7 zOrx7eGve8}mCE}2*|~S>$7l%b>Qd{9;5ImoCh@jg@@5rf=(2{nrBBDGSiyw$oR7?I zBy=y`&V3)WT})sXZZR;EsmeKBcKK&=T(_Z`R^s(&qY$<-jkdb3Z86YKoP9-iaMU|_ z)51U%w+u{t*t9_~g|*9ORAATkioI^?DjxnUA0IbFLtvK@uwH0%EsZAhX2hKhA9WXh z6jMAL`>R;N#IX6x1*@zyddHmI2SX%`hMn5gcxOjrv!tP71~M8%?I)x6l6ibJQ)8Unk9{aPaIc$`MhoMy!BQB~C~ zp3chULv2;8V4`s2xx#rF-k7+tp3JMdb=1A~M9Il)rXjG)?b{q-(VH}y(S#9|jybCX zp0rkUhnuKa!NjlZ*@Ef2G}>k#BTk-kQCF8~t9;+@reXyXvz_J$pWr=CAi4E7L3yJ&FXi61ET)E#` zZJyj$**l|}hQO{^+bKf9?`c$bl=VedE%j1kw+ARS&sI{gf{8{oGlY?c)96u=5#h40 zTIoozk}=;>LtvLxku;&)uQXb&4;yC)YTaGkCXZC6w=SV#1rx2Cr3t>r(`W=IK9jy` z-0Ja4OONk5Okmfuo=L*)g6T9Pm^~XzX*fW=^)^DeGU1I5E10O+C|T%tDvdrr&7MCV zBnGOZ65^B$%gY)9yS|o85FQmyr)Ao(Eas)iFm->?cxBVq6FRJ5BCAV+Q1wh2oz{*K z$@5356^kV)!F97V1a>XH9VdJ#l1|gUv!}ant3uTm^^=u(%UA2Lf{Bq0CJBz`(&)k4 zjOcMKOl^>wstk`x(-0b$5GzC%O{W3VgMfH?ZJhc%GfgS7EL>-T6ioaGj}`Wxhs^Vw zxW8zk+TLZd^5B}MhQO{}LbQ-nES--1F$`ju#6+mawoX>8FF5P4f{FSwqlK#%(x{^i zdp;M&MyXE6rYN7zd{r=kUD=V5Lg(V?wD9XuK%D6vt$MZ3P+~h~D_Frqh+C8}Auo+m zPW*C=QCH|Pl+$6gGz4~itQ{f1Y6a9Pl8t5D>=L8K49aXiC9GgVs#-WFzC}7c-MKyx*ZX#qsul{O z=Yq;>2<%E&Z<13QV%+Y}h)O4k$95>_y=-=%C$Ux;xuiM?r9u%?H!w{<8j zQ>~bWz^-S_o99@Rg!z5^O+&CxU+KxN@$|>9Zz5JO5xHtW&iZEQG=5+ci1B{qKq+r) zG;LDqv4+4dp>p3GZ}W6|XE-C~TpS|xtr17Veq0r?f{8l;qjLNp#`BWyK(xCvOmZF^ zPrbh!)ezXVVn}MvQ}}&U%VF;g@@|ZjIyXq7{j;}-Si!`&;?r|3is^J#4$I`ZAa0B_ zwP^}%*LH!1z^-K*rshOLjG$ably?l1Olzmoi`}P+Si!{6o3nG$Ax48??7hLG8RMjK zF=^DVVT6XjE@{&8oc3@{bZyIe;m6`9O3i9crWLQX7O{ef<_VcOZD=}O@wo#KSI0+6 z8Dt7Q`LlwCz^)8wbxuKu@#704w$dnR!}=+7RjtAzRxsgmYh6xdh!Gvn`d1s9L`w;7 z88rLeeu@d~I`no+P9yl8=LE6)`JnPKQu?+Gs;l5hv4RQ1Z%{va-nAdB;Bqa4ZZErA zzyx*~e&>3^+q@iox3ZS-`9h2&e_Je6h92ZRGgIQTZLu)*NgDmKyfC?bYL0LT`f$(q zmjj;XCev~mi-qcgv;=kq-wYED!*koXJM69gny2rm@0g-QtQ#$11rx(aFTvX;ozl|m zt$u}ub;Q7Wgv^hN)DYMe__&ww{cak)#=isjY%7Uo7rT+o6C)(7U}DnnE<$Lfbo!PP zZ-@04kCl%g4|EeW1a_@`?If&#zNlk-F*vH6SE=IBE(^%H$Z!cOm~eBj78W_B(>ZA+ zfOzs`nfRvY4wCk9w1&X0##gL`RbSHRkhP2$*W4@41 z!`_z$qK5lpG5c`=>Q``(hQO}bemNeypnp}{ihT$0%HqA~lv0!~y3=363MPDf)_atN z-$!x&6=p(djCi_2`iW=|EQM7 zp62PaTg8e%v@x@i>R+>`?HoI52<$p?w2ns&xVDEmGQweDMXB@Gden1YdkHI;XxhE9 z$5)7PC6*E8?J7wDGwM^no>~ICDr~p)Xa_NVEo21!R$0ni(SW{w)=t6-CRz_NWjV0v zzHs(+Lf`u}q}h@ib#Z8=A+XDP#CZ4Da39R>XA4BZ+d!6gfM`HnrTD{M^klEb8UnlUeIEL|-Q1*(QWgcGz50x-T-`4G`j;f?sBsa&|YR?V${tE94yYTm3d`_G*%+zDOJ~mU2z)U^< zRUyn*BQRr`Z^O(t0&|h`zcz$fbVdp6g4uNhX6hLsu!0GggGXQ{^M4T71vB*s%!AG+ z=Im>#KHb?t3D(b|qcDq(e}@Y5yeQ0~K?V+y5nKo5N-SbhJ!Yn$h zU;<{lQJ6(X^|R_VpFjA!7IE#u zoHzpW2dRGk;M#?a)sv;Ylpgx|gTEC_Xk$brxT@`~+ACXN-W}c-c1_=BLbqQHr!VSp)gaAZ^L{%3N!WiwwAyO zCU8yvoxm=bsrUQL{`KP%hf(e*iM`5O3K4EwsJO?xNFo9h# zyN<%Fz5H21n7|4qU=ALIIe+;C%)4`enR@&Q5);@3GwLYJ)cX$ty9{-x{~8y^zzQY| zHT}N{>@u8LJz;o)91Jt{uwsnRe~oL5UB)JOc;*#&ls4%F6~i;FKDC|ecM(!2l+CrQcdW*xNtfj za&J5c{z59u9Z&5bM+W54Adq2$>N9L?+~K0We%(fytZV2dk?zbXDDUdnr308wpl0fomGx>Nj#zJ6>(Cq(H_KOkfv2v#>&5o1M;( z#e<)7!`+J=ui>u7wjuKdfh->RzYk1c1ryqm|Bb*d$kjn0i-(aISiuCYX?TmgzrJ)O zumv3pSv*$EdPjB^ok&NQ;8{EfWbxp$!CobOC7loHw_yyxtFF{xwM3I{Q7PRnkIY;h zORqzYjE?sANzJ)E{k~YdeWUk&FJX&JTt{_1rs%U_x7tq_TCSP;)}7>9djW9t%5b z_-sN35dzsr@@F+hnmb6}Yru>ueKwNc3MRr{o+Dj0#!|Bl8=zm}VC5)zc#E{BJ{!qz z0=sY>!nfyj9HmzMMcM(fkzfTA6&mLe=ipdcY12B0v1o^*l<-5OmXM7E6WE1o8fH#L z)Rp|MOZ4tGp2g#L&&$vf*?n-=^K4SKOFShR>>20y`nu9<%VyLLvUp$x6Oe6#Ko*bu z`D&B5)su=hZBErWL_=U#ktTVh>Cjj@n&;%mPOUE;s?&mAKP{+O!NkGZdF1TMSn9}$ zSL2R^9TDD zZ6H0q(2{0B77t8dSJT?}NkwS+!*~{tqmvp)H~M(e`ybp@tY8ANZ4k)fLG@WY%-2D- zh|E^h@{kyZmbS)XUl-NOkfvoZ`z}3vL}T;J?|s4_A}l)g^Gvz@oi{16zYy|YYD7i zVvc1JwcIf4KM3qHWaay_?LMtjnASTvmbaxZ5vH_#n10*iU}^f?bcB(Xh!sra_iF!x zz%GwV6=`0*KqExPl#9d~vJ0`}{b$2|qKlZsx9e@WO}?**HbP(p6ZyGj|AWA;PY2$R z*sT+d5Lm$kt_AHG!~}ND@+v_0jtn;v11p%o=SdsGkbRHU)xklj)ccz&;oDzRX@Q&N zNeTG7mKfhSp1!=do3|gRSysb*`{d39+V$QVBkc++nD~3U!UT4`h)bkr9TpjhffY>P zcC0N2v{edq#B1@86ha+lS@3N`Htj!KJ615!r^!&-Y@xN0^AU2W2{paii7STuM4(mg_XBLr43QSx3I-Ee(n?w`L8 zOkh{->1p)xvi(K~d@ZqfA4{KHJKC1T9$WdVeyYN*>TXL*mB6fT@U3kUB$nOIa*oCiM+8FqH z6?oE__I%Tg?-yT*v;>B*EHm&xhuMq+(n0P(AI&Bye@E-(r z;r@fR99Y4`%tMuELh=wJF))E$fA5#z-d*z<*MxoP`o1B4vd|tCRxmOC)LOw6R%`yV z?P3DEHh)+msE>^iSi!`YiitwxiouMre96sP_WTZ2Z~n&!fWkZJRkkv~rpaKX!bd*PaioVB*}Pf%MLJTO%dM1a?77 zr_ipA5Lm&)k1#(Pu-WN92<-a%GbdIsQK+vkz4+DDNDNG1*WddL2hlm$+!}H-R4G6# zpk@61d|(9=(-YI^-OIOxGJmuyOkfwZbjsTGpXVGam>Bmcjdt2S(?|?VU>CGP%39-} zF>rfzx>;3d7OOX z1a=uRn*T{)1ruZ7tD54?OB?BtVFJ5we@ySH~1A#23e5u8Y?rPC1D1#7YJ zJuP|K1&C5Lb@2bNGIZ7mX}Og--`DxYo?^0>e*5$iPZ3s_Og!3105iJi?_rx@{Rdv#7c3U93;unShM<1xCIZwJJ*I6F>w zee;yCf{Cx`@jQlASw?Iu;mCS-VOA5);@3tK;z)De&3@z8!?4VZz~?#@L#MigPhPslOJh!;=;n7}Sr z9goL2naqeFs8vSH+)-V^3MMi_mhl*U_cP+LgAXTaRjHsMunSg&;xQ7gbO53UvmpV#fv-v?Ci6?`uO+*7j?nzhVV!Wk z-#IHiMSP8cZwGZ7Ad-nmp}L`(s}Ck%jdD&G9OVh#Lai5YqCv&68UnjUB_GITzo-+Z zTY~p|W;`c+291-jf(ckHJ(pcwAFO1=^=@4`F=OOJ4S`*sie>N^rD7Oy+(zWY`NXUs=y;5T6->ZdEUv7s%33qxWbQA%YD$5hS^~Sy zuNttE#b{K45pKRq`I*0O63;7I0=pXivJ_Yh>w1iE zIJ|%pvpr)ZtY8Ax#t~SI37(8_%_^j0F^=4d(h%6?StWzVm>R{1D!Z$3V*mL_2`iX@ zHGX)EAb!qYe)8Z%*KH9R0=u@uK-_A_F~uxL&c z{W4BNV3*%)6T<3hV;}a5vZ^wN6Ytfr5>_w)tD6y4SH&kYqD{$loLIUlR6}4_(?=zE zjJB&8VV1Xv6Aey`lCXjaSSgLiuvx~4staUJtoSuTLtxh`+j=}k#ZcDE*mvwCCjyrb zldysbSSgLi*s_ulK{<~&k=|yIhQO{%bG&(s{Yk9P;NIy2C!TEYFJT1}utFt|;mP|Y zvriRJS-Z+x(_2Ge*TF&Ec#Kl#Sd2w;3v*(__g)fKFac|5@)-RJuztzmb&Ob$RE-m#hPBZU*i|Mhp2vu=V!e!n z7d1F>HmsF|6->bT@jS-Ea*UWB;lPP9HzW;#U1gh2>7Sr#9lWF8D{=fFaawG@)*@O_6EZ3yPnulw;{mnP zz{-w1M$F=VK=@hc>#Eq=ZyEx-CM4+3xlfe=KumqDKZ6<9tLU(T30R?$#~4?c5q&S| zTZ#SoCK>{}7Mtp0l$g$l29|nac=fhAtY8Ax(Bv_;b`Jm|^XPb9yIY2ZY6$H5M?JvL z`7f72K&;IQls=ruYhj{d z0=pU((8pLmnGx;0dUGOZSV0vln1Gd`d5qL5!+^keViq}=U&%r>P z4DZB=3vTj>T5h5ZLu#g}%@5tilK&0^jQI=cT&WP_cpu zr!D$E!<&kXxK^w=kFl<19Swn9WqZ%&T9RE$&Qz@r+2#LLFafJ`^Kw`% zVnq3sE}XdEw~2ljT|^Ztn1EHrd5k@tjQClo7AH)1x6}~W z)nLB9pBUGg5j`i_abopXPZcYefUzw7`AB2Lce9!Zaf-@;F(1^F(AoLLts~KoHviL|1=}k#24a3-U@#eE10Mq zsed-u@ed7j>AgVjP=0r~U02M2kI9S1zm!szjMhrT2 zg%fi&2WklHNrD6pWbh-YSbIDOgylcLk6U#o2))3hBvGi5`>@4;S1L9e$DV(@& z5w2nd6DtZp_9W<+xGrJDnvVgT_`H0AhQO}*w)!!E&Nmpbtz}D2g!@FOSi!_dGyNFA z!b^;Jom7t#)p|r~2<$pCEsmGN{v9Jmg;{f=Zi6TlE10-t(}b5}dF5~*>R!6WM?bnI zMr#P{YIkUz2m5{8B#fv$r5`7JAy*hyFu__XtE&~Q7|}Cfip>7f^rM#0x**3i#LyGT zwhiH{YIuK;-)s6;`FFo>eY@na7-9<+BhlT1GJ?qZ9*u#(u5}|EbJ^eRYB1vM4w(~; zpG2!z!NfVI!MQAkV9JOab4tPgLq?srC=G#KrC_~n7NgE(c0O8mtj&qL(2KqV#J=jjhv|RWt4`%u3ukE z@EDb|8SxOFhFCeO!qX8}FtIkng2#Bfnh}%d?d8N=mk}BQyS7wu;W1Y3VOO|S6V7vD zYR#c4Rxly8cIPoZ#4_U3_2-;u`5{0_0?ZPU>7;vi6IYRKjNsWc}J zb@0^?*tI4wmdD6k%+>fbJv z=RJUvFzUg|;R2%|SiwZaDf%~9bz89*yJ2L75dw^~U;?{fw1tB+fVB`xE*tN)J881iUm8@quKDZ4hz9d#tv4V*fGnVsmbP8ldnMoZuvAeys zhQO|nZu+-N3p=nL@>UoXWJh&2sg#NpOmsc7na5~SkP)9?I!s_!`IftRjLnzX6U$2&rDaF; zVD}>(Rxn|Cc@Hng)e($PU?i9kE=Nyl2<#fwZ!eEAVK{s8x&oukj3_!^)?oz`pI!Cu z&m)F0qBV?YGa}`}CJljI)lK&C7!wI2Zo;TJBkq-0r^5;+oX70vZ3e{(<%0}y&2vxFrvO^2MvK;g$Ezw zF?#bS`XG3V!HBjWJ#<*X#HBIEc#L!0V|k@(&=MND#ONoZowNkMohY2 zlVSq9R$b87)l{cmK(vCle2nNDx{+c96Q>L7>#CIx>t8H{H;If`6j@Bf1a?IR>d*NI zK5}OXZz~y5Cc#d`3MMWA!TJolIdKf$h%#bL1yMs_*QaJj`T01|fsH^0!&_HI?Dy*` zVg(a(?i}VZ)=cdVL`itF%ZRP(;xz`d?H?n*}0PFrocU=Cz~# zS9=xSSYraa7Pr)2OFr`v;W_XYoE?==N+)6k6ZpFv$k;2q6U*0KqdOPSS#^!Iq~%W+ z5oVsRCJJ$dDe*2SBwO2xW6}y!o3)Z4Z>kFA@a)}8x?Q`vx-!X2S9(Ds>h*mJiGFD< z?kn7st`C__vKm(q9S*wFT_0wWfz2ubvFu$TX%O*O@2&n!PG7gCF^}7laZ}5P4JVhO z7DolrW=LuAfJvsqatm`Gnr;!_U{~+Hfnn{IDl^yxvmdI(^-OE_m-m z#w{ob#Lq4f;*FrLYW?mes>6*fq|oqHLdZ)iamHJjbb7x=Ad9TU$+ilSt>y`mpA8T# z-iC_9)GF$`Zq3x|fhpu?xz@tR+ty+^%ax?&#J0k$n>M0**_9;NzJU;5zXA~DUQ6Pe zuO-#x=^a(8ktyWO;L<{Htc`f>T`yAK#!~2)Z7p7V){9KqQCEl`VhzOX9TmmFex1}K zD=pMSwHMjYZKP17os~FtT`v-_I#!r`tGu|%JB7qOiWBS)SpiY8@KeF}WR&{wjH&L@ z;9kPFt#bv>Vr9f5%hEGz+@B{Xi%N^G%hNO4u2?AekGBM(Q}1-aE-6y|QKgPZSEOfF zyE#{wmt9g!gYA#*Glb(W&BZqL{Dclq<_e!@vAViisI~Abq_>(=x1dyNO?sxhGQq>V zMPbnzw!_*)czms2Se)YCS#Z?-<5At+6o_8On~B|rbW?5L6qe34T~A&<9lvLHaT9Uq z!+j(w^rXkMe+r1BgAb9^yQ2l)!HgL2vx2nopqE-=*9Gd^%${C{{Dphkmllstu0bc7 z4<=UCEyeEDs?%~4{fT1Ao`<479TAJY^H(#QtrLGeDMXhHHzjrAi-|Q37o<@gUJ4O2 z&BPO3OVZTm)}&x&F(3j{W{4l#wp9Cul#}MS{z>jss3Uw&_(g3CJRuhGo87yA{ziMf zc}S8S8s_#H`yQUsDn2xkIy=`>_na***-WfKeSeM?{HDF9rLR|@FWZgt*f{(Ry;-Ot z?fkx4u8-LhAP(D_izNen)vT!{rBXdNk$}cUg`BB{#O1eVk>XkKcHv9`v9kRP(kiY% z?uVVXevTx*w}X=V zS7<9$?|fI+ywe?BbiHdm`!fJ@s4vREaNg_?pRs&+x9Y3kc zg@WoOxtthT-G@#Zex3wYwh-qnZbNTxlgXW5=Hdv~*7V$(^#UZ;}(8%FC$gWh@+QqF^q+jK0s_!D7inO{5 z-BhR|saEnEy*9&H|4(X~uHI`u;v67sq*#GtinNaa>mQ0rIuD&l=@_pD1TGF$IC zdj0|3CA-rRTlWc@-JU^=rL>N8`D8J*ou!%dvpJ#55ADoZTlzBXu)99JH}`w4aP~YE z#yHc?A#rkeyL~`7KO7|0wOXRM+_UbZYL3Ps`}}m_fAC zzCMCw&)q<@dK4}FT2ff4&^L>|fegmhty+4l@To{=jZdTJd{RAT6t|`8KBv-2-&f_P znpFj&dL(4V`)RE#C|O)oGg7HvYmv}jW!zpl^*##m?n0pO6!mhKzth)Bem@K zMII3vL`!uYOi%fV^xK94;=#Lv==bmzw3u~a(IRCK9lzF*#x^PdwL3H~MjG35i<~s` z1t}6Rh}v#zORt+36+4s}M19)&P~S2o#MrF^Y3)m{)Z+nbC53OrNE=2KC3_Bim227# zq8Co}q-E{Oi`y0qq81PP&{t#N%2{#{4O!cUURzooh)4F3(kKgeA`We+yQ!v9cHj1# z;wvtMtp03!=C+RF#+(#dG_I0Rel2^$TP!|Ay6jq4X!CuKF6PW6?pkryQ+!=GPEX8j zA=;LWqr?3R2y3Uc0OCtnxOl9^c(vZ?niS7>#&ewWUL=v)?n%lkxi-|*JXsZ6mKmY0 z{3ud9a}LkJ^XYz(3@#O`tTHPH1U=nITI=kpmY=pjGqVuS^Q&*!nwCG)LNT9P0*ISi z`$i0A#ag!}DMmwJ7mf|zMvaM*u5KuzOMKy@IVw!xd2H~O ztbMffWBWy=@yeDO0=saT;QNxn2Pl=rYQ7E&;woymG^{5a`#tq9$kZ?iQ7cHugN6{k8)ki7cz*I8E{tEnqY;CbRE zCfmQ1{1(-7E&&kc<4I**ZBRa&I;PfpX69G3~t`GXZ)u8)#F4O^=lTXzk` z3MSH@#nQsH{*mjSV=eJlwGio9+ugd4^Ji)Z?9$8(H0c{0AZ?uXOt(FDDa9=u&!W?| z_LRbdq)UAt=vtE{6f2m(^Zejf>mDeTvb&_KbAOwLz%G1*CMKQDhDiaCF?-tSc@!&{ zz%vm|OrF0FmVW%&uiKI_M?+wjw&V#yN6Fz%IdxvK)fCV3!SjmTCI!(N7pxV>73NU8 z(0!Gj7Ad73U%QH81rvDY6O5P4?IsmkTtYqFSxaCSo@r%bl40LmN;+0sy>NXw#q)>o zyrTGCe$>262jdepsFPIYpb4}k)}~FfoBH7v)V~h$uzpB8aQn_#WU=2j)R}` zD^XLY!HRd|@=%UibIqmc6}qVnQsz>uU_v{8@b*FrDcHP=YHzbZOQ7rrc=jRWhbw+p zbZR$$jSR)9LQ%{Yn`OyJA{Ft*ftr?|d4 zyze^bs<}tu`x2g!4d=srsu+_HrdIAKQhe{jv!a*wUQSLlPEfj)vWKIpSY@6#j7tXTO z5ZHxheM4SOv!bH9EJ|&>`4PeMIdK+`!YMV#_qwUdW|7^`yX9S`O(sUGkM5lz8OJXR zQ8sBxLYdkW&*#K@g1+cFOL172D79LTX9VvT=N8e%cr(;WbgUAko;P_(u!0Gk{RH~d zS1O8mZz9$EcCR%AcHwL*@a(*8A6;-LT3uZ96v4-i%Y^5T!fI(Dljzu?G3tAG+TEGy zC#+wSri^`8i{creTH?ycXyM_j81>5GZKVFe^h~R*X^QEsS`^Ri!gIb%Og=X*L02A& zQQeR4B6!9bp5caL!+2<5bs7op)EoxvCfJ4N-D!!U)0)sBn_^VSZjYuMn80)X;2ZiJ zKk6_uMt#02M?+v2t_8?Q`g}U=7zv+i^^Z_LoxCReYTm$OZYOK8dej{LZZpflTJ(JG zFN_~k-^0a%J>#rdJAf|VT~oKURiug)OgP^3=k$`QjBvhhO3N>+rJEb2C9vzk!t_km z_nl|Lh^&L{#L(Aeb^GafwMjsK!jy!OHe%{){TH|k`rC*eUwV--y_$H;?8e42dc-sl zk5sbO9VjqC#R?`~q}SwontOu9m^rPsSoD;mF7^F*4S`)B7u6&;X1aI`RTy#qQfcvS zNM+s1UK3TUVB%auD;~ph6(bS~77(4cJL#P2YYFVawGOKfx!j>A-r4FL+G)=RCU$SS z#%s4#0E_V>c{{8gRzsJ!UrS&YJ~!~h(z}=FIo49QDQcXic5%H;^-JO9=>)LrYPC9uo+#R?vyeFaABd%95c3jM0c z=R#GiV8UUi{wr4bJtJ&3trV+&E2Xn}Hd4h3CWbas$htc|9!ILOvA)S~Hi*7Go+~#x zX$kC_TVLTvwY?rACK5#qzJ5(v+-A6HR_GF$`k{wM>Hd|)pl27k>vKqDQAjj*KG+D3UyC|h0Zxy^z<3708U zUBop4D?7M+6<3~JpmdJ!tEnqYsND;5`oIWVII3QsUx_cB)+n^W01bg%xZa?b5o;+8 zb{?V>z2K|Tx0U$5wwTz7|CFpuoqi;G9DQ9wOqpiO|K4OS8^6lFUsfuxWvP;7(n-Y% zCYpKK(?YkVcnEK60< zSX#-2o@+J7qpy`c5IMTm((PH3<(}Tv)t#ID=u(~R(e++Kao==5zTfPp4aLoGy7O&u zU_&5A`8Ai!pH@}gN84)%?CKcMniiU|)?@45x-|M>#5ik8|uaPJLYmd zQA@aGHIdFtIxm-M;G$v$6UW_Kb9&$@7USN~Mp9^8d*y~BWDP~pvCB1r(1iL+J+}Be z08w&sL&@y@S9xC(cNHs`82y9r7&8(W@yg3lYOp<6nK4t;5ZI-y-3GPnCA(~E<#3<QHq>?Q7&<#yowb}xLypRX3NfbB#m+dqH&Y1(x#m1@_;%P8UnjYZw%rw zN>5`nw;({ExbBXzFp|MhQKa-gzzSAr@wS>nYlc(Um+DMn7ICA zI6uOMrJF*GYe7AvI$dn!;~k1?2<+09eC>!(iPrTOtUcFjM(*%v-LM&nJVuEU?I6ai zf#akv_rD6>OX76{OX^1iN8a`kcglKKUi)_9rSwGl$fJ}%Oc~KKJW9G{(SoexHMJ*iH9f)rqVGbk&S0QM6Z?S@VI<*DY&Q-ld(Jh@5 z2XyQ^{Y~(`cJlTZa;fPT87uAo(eGDk-9yBCGBMdQHAd?6eg--1Fi61)CXUWaqs>b? z2;oE7Q58NHBVC-glMLzdNyY?rnN?4x>ld^U%%}DSVtQDNq&7H5mO=hMtYD&C-!$s< z`LOWOiNz>>AVxY~<1^_M{7uFLcAbFL*iK$rF0>lPVpJ1jq?Hb^I!o=cO53DV`utrN zQk8TQ2b6$yr4RNa_xt;cC!3_v*+;y|(pjvo>iEP+0skb>AL*6~RvLCmqjr5n(r~-K zi1!3xlYfp!OQT}9)61cbni!bqz9W@hKN?GlePQqD&#sG>lIks{Z4Reu z2<+0Hk41JdQiHLx>E|^zn%c!gmm+D@_r(BGz@MFSyT&onf;v-ar>f;O1a{#T1M@$o zMoG0z;a#0Ws8SYI1E13UF`53LyXbTq@?@IcB_?h?#L7dG=&0U#M6AJPR6XAdUk->L z=q#_n3RX0Pl1%%~JVu;GuvtR4&qYZN+w$lq=cO8=GID8aH>FmzRJ+bCI-p=jOn9i^zM_&^g$8UN;*7^kfwaG6a#l$*AUnx|CmJUo+?GV zJ!}uewo33m>U1SBdeH_2E0}0MI-Vxpu%;1rS&XJ`ky6ehbMbKNvl;@s@Ogso$ht&I z1=`t&4ntRJ&Icw;cgEAQzU67%&b|=i#pp?_BP1cYmUzPJ zqLNiQmi8IlnD+Unz4)|mEIq!-jy~$zMm+E!nwGlMl zafzk>BsZdgmfo5pgm0s|M@XhyYl>D5rxko8n3#7qmJVI#MAx~q-$!p)&1%*7^5UZt zuQUX9;noAS8z1q1T)lZ*PS5|xeN{@bgeZiPy+VclC4m7 z5g}xk?7FTwS+i4QCp*cO?CU+}bKj5q_nz;6J$k*K*PLZ$&aCet`t}{AboE&-mtdmW zYc_O0VF^#Wk6>x!uSq7urdvolx~Dh-yKtUnbE&VBh}&BWsaM@6&DSQ$a4UW={9NoJ zO>|6#-xh2Hx7JAt4@rboqlQA@PUY!V8YYwH`Awy9fd&*Sn7B4K0rmxp@ZhJ!h%X8gQ%T=!3@KJHand;kr2Ve2Gf!zD z@9<704F@!p9@f+02<+OgiGgk*W5HwvFyef(Wa4wEmGrl}7I#%WZR23VRd28==dVzu z+Q@QAwNq;;^Q?;EE5Ss}p*ToP^a8_ZCzeKsp2(?pIq7f-1y5JfVo;08%mq)?Q zq7m@>hOP7^bQ-J}5(J@o{iV;9(_!8bcbGD;FH0llOER(S^9vep*QQv(M8%Y8FcyNq zxmkZkR8}UFzQeVob8MUpD^F9R!TG*FT=sGJpEM>NOeW2S=}OT*`7|(Lx;q;B%<_kk z>l|1b%`1{gbJsVp!l?;&RoI2!KYN3b$)uO2k<`0Lhhha2>$k?hz`U_g6RqTuWL76S z7Z^%6dh-N!@%ielK`I$*at6NVebkJcJO$2_hr)>BUee1GQ=t8lP{$27z~&h3Qik4N?Q%X!E)t92tU$QN?bMx47+-P za9kPj%8E`SFOSB7?J2beE0{|s& zysihY_el$$2-~&|2a~OBSsF!K(n;pL9isJGHw{)WF}FAr+7t!A^C8Np^NLmJ#H`*4 z@#4SH9D!XO|AfNj8-cLto-&5qCn24zmY#?MT%t5sdC8t;o?S4s?O-P1v{{`vCY|*D zsS95n=W=OaBCdWI*t5Kw{oe|@YfkB;bn6DABEG`b~rP@Sx(R^_|&m!Re-^wh!V(Y`~ z5U5#4!26K0&NAv#I_Y~pQLR(yFJc7~rG}yKaq4hrXVs7q`QOq>#M*J{^6F+Bfn5$i zL*VFhFNn@m(zwq~5o|=;t9!dr_F>%4|l6^-o?Zb(@>yA z<6ufXWvyDXnsjo1)(WBI@FkAGF1+fE<;211B(}^;qkbO@cx@eCbBEs(OXEN~vAl9q zZIH%R;h{H(3CG=`usqorLR^%!wP#D&iMPIG>e+Hjj=(OwdQYX2ccl@R!l{}qxx2YF zf_Uv9zFM{`h2{2v?HXvRbry5?feGhp6Jf+7dx&oNm(956`=yh8hV?Y78_nhj?82)M zRjQ_jX~ef)7fsE!chGl71ejeih5qU)SYi+XZm-+J_f=2faNQ(0^{*+^IlpFUbZ|~1 zqw96lEY7at6inQ6U?*SC>kbb8-ZJ9nk5nS7QZ?BJc>=rmRg?3J)5r$WR&(Mf<(?HL zcI8ZhK2v(Yl=6=(jn0*6WX|7K8r{_yg8!#1q88v}_J#H|fIwzH+?(C+~pRC6b*!A*T1auwH21dF+ zV#LvD$)upEt;TPZAXVxmz~^$- zmPWzBB(mhUqh?OFn}iiiM0%&g>0?X9xLIo$;ai(XRvRqV9Bb~)5!i*FAtO2_lOy(a znk?3e#|kD~&nLpyEr-RVONA_r=RT~r{mxe7;S3ysUHILw7($ha#MW|!CbrI7`jVCb zQ7Z-r)APs><35KUy9XG=q8)?#?k`@j3&{vyH@^rP1s@ zv{;{WeVC)h_VhrGz%Kk0SY$j_&Tp4?)HK**Ayr>r2j}9U5JH==R?R#efh`f0>JAK@w#Wc(vj^upXf&>Kh%=t;N#pHNKD{Wp)BvZj3efyI&y@? z501bt|9au@sj#Ky+`?AuS!EvgAxEw~pqCqLlge@fV0O_^QZ` zStVfw6DBoNLAP(2dULBFmd4q|fuwK43v|9_1xH{Pz9+Vy({vnZo?AuVY|fRif(dK8 z3DC0gm%8eYKTBi!tkERK@&g?bxSAud3qJ)GpFw*(DQ^Cqy3TDX;j)Iy;D|G^u*>(C zIz6*BOJlFaM6yBkfTnqU2CQHLugqp~GAzPLE8EKy8a0wIfn5PhXF+oF3+mD9+ORab zypJMZGWO9Y2Co1sn80h@*&7@XO`0ceq&`=*B}`yf`(GJg@^z)U(GgRY#=E6)B#@@j zQmqQW3MTly0M{)Oh{@OhT9N*SBd{ymd?EBOAZqD;Tb717o6Wd=t{t5|^ax-D6S&r9 zd$8`LkgC|9n)in1IRd-*ok*h&rjax66E*jq6mWZ#FoC}-Y|Y*8G;+F~jwWdDPL9AX zybFqbokNp|+_pX4{G*A4Q^z$CzCV?!^l>cNGT)yT7uiWz!33^jRI1?zXOh9gQ|OlJ zjvRqq_&u>%vf?OGmc5=vO&B6!1rxYdVlhSPBFXTRyJ^7MJ{*BvIQOuzjN*x;HJ4>XH zh*97(Jz5>Swh-`l3Dc~P^VN?u>2{J{t}f#C-C+WM;aDt-#}i2XuzmE13%^qjyZEch z*GwSC2NlzGPqs){!36&9vKf#)Q4IF`8xYkyw*31hcFH1}4*Vh{*tY8AS zA6PugbAhDB^-k7x48aR!U`sCz3&g38oX3*__Bo&2iG}~kClJup4Im_0=x9`-QZEqHTAPb z>lpFbKq3#{)RXU&-;uC_i4U*rVbUON&AY!!&nxY=GijBtCBx$~j=-*sW$qApvPPY_ zcPS%gw{Rk!BlP7`%^3+Rm>7RZfWS9~8tY4o8Id~5g&do%E4z`S9D!YhkA_1{u(qb9 z$6Q9NwHQdAZ)_wx96Bgr1rv6Y0PdbK)tIcF&4^LjE~G(Y19{ZKT^xa3yMB3qX;5R0 zUa#ql(DipBY1z%>0r$5{SiyvII|7#PI%`(9n#u?o=1fAY4CMvaHgN=YO|bHYv<4=c zO|5+y(PbJT^?)ct3QE$= zG{<{6Ga}a=NT-Eu zE}91BJsI)imO!M57INEei4s;Y(K5{$UIvL8*Jaj>NZa5@4w#$Ea?D7Mz^*mlePFnQ zwPwf~6GnVoA&`3my2+(BeI=}5;?UW_P~O!^Q+m{x5v_kYk|XOo$#F>r9D!Z@uC3?$ z1@dy6m7IC%HDCo3cn237NlgXvb-$&&w_`C!U>Dvo#=e7h`xBGqw(`G`dE8zyOyGU6 zY^BpbXHxL~4ZRcbO!~TT2>kZiAuNe|0AgQ9@TzL1o|AJ1w(cGVDg*11CZEgLo!{*{ zkOawZ>9l`uB&=Wp*Gg<&Ee1$))1TDmz*{a2yz3j&Z0CKXEfELk$Qw^<5v*W>-y44L zOkXmgt0(J4aqwLNdM%j@-OKthu zvOiqCi(R-zRjDF+dyin@io6MjjoiuX)g-jN6}&M^$he zmF>Y=m`Z}0&(R3lzq$4#l(`F2#C$M7LB4xSQ^5l2vVN5fIj-L zjw7&(j~bCbZYsHHoJ7~dp2`iY8 zU(SI>85t!F=0vdjaIB6dQ+!6##@%Lf1a{#Z!$xtIM3cQgJ?Mhkc@kDI;kG^%D%RKt zi=QrGX_T#*Mrun!=-GQ&9D!Xp$FTT5!VEHbg(Ho>G+)9BCT7xD*w1#-#gE<2()fOG zI{E#{o36T=$r0Fva}1l|jg28mC4FhyhS?HUFwr8rnaB~?#plHC zY*r?tR}W2$p0$KWv+-y>e*Y}?=g}lmdND`y`h}B(6-@9W^y)3~T>ijvqS!Nz`2G@T-y@zJk%e4*P8>PZhV&6lz2+N7V{mG(}UF93$u^fS2Q{C)AZL(Ul zEN;ZE$|*!5s>Yq|iJzQrm*w@Y&+wYy;_c;{lMgJXdrHP@<$| z8rhM_k9x^F4mofNCVW@+h1#82Vnn{O>cy#vOsHmX4EJ+B!f zjt?A0-cL4`_tZ9!jxTnCtzEW@^sRxEvt|%jpExYO_+=>Bx;uhVhuvbzV`ZI;p^X>0 z9@I#7*Y3wf-@;M3@Gr4e#sP0Om)cm~RHe(Mfr%rfF5nbcDmHART-B!>Pm(;LnLOF( zBjDe{E_{Wo&CtY`ydAER1)H|??in{|lzmQo*QAYPx6>Vt>z0YfX0??(=Q)GNg~Os< zwX%D8sKrQ9^UYAMmk^_I`|ApUNoT}O%S^cVV14wRpl;Ry@uZouvL?cQ7>Rh^T80)* z8m!=mVmQ(m8)sPMLXKy3kT<{hU4jYhxX#_Fr1pz93BTV|ZhzvT8WU!J z213Z+BjS+`n{r z&arFr8aIHO7sWY_#*CPo9Zb4?zDF<56=?&>8|sa}BYJi=VGen-5&Nm)S` z7a2%??s-c;6|+6)NWt#|zbAI*ttXHV;v4FkU7sVcD>7^ZY*>9;ylJScxf^CMhIlo9 zNG%8Mm2e-hvA!4dI+7%wJXr&{-^QX8d>TWBOn5?DyxPK|BK}`b5fj5zp3tfPTCv-b zudIf9(P=a(4R}kVi}E-EyE0A>g$b@}#NwXHnxgFAex%0oG2K39frJ%IgfH-bE-#D3 zO^20w_x9QG#CG&kYS1T&Bd}}fUJuY|Q6>iU(qn|aTPS&7R6)IOIZ9Z;M9Pl`q|W>ToxQ3NM_^a4hoe9z>XUf(pi;xN?H5JHM;)eJcd%{MNWnyl17qRB z5M8)ZqC~*dc@a%sMsBBe@7i+&cID6X1&J9crFNwDulrlJPdl30F>kBnbIClaon0V099jsPd z7nj^su4=?le-d#(OMbZKtOF*ni!V{L&Uli$myP6ZyE+3dskpAi<&nit%=IMG0*qwq zeOZ7NOz?H$m2G3lnwW<2J?B&r6WGOH)wFqI$XVxxa=V&dfE7&OI+(3h>+DNdbR)UU z<+g|k?7~lk?J{*AOFReFm&@+&0<2&He;HW$*f5^_4E{?!s}nf_yYQQ3y`qtU-|;nt+Z%)t=3H(5;j_Y?S*<=GrBa%7B_T)_IySiwZ-!=Ydy>=Wxk z>#;Nr+4vA+$3OIan_!N>uDZ?cusQ0K*i_ws5v`vDkR?uUY5I_y=XRasc2i_BJ z9#mRne+Gq;(+3{Y`wO1|Ca^28jW={3`bKO!P-**==S7gnSr_T;^aQ{PCN^b`ff1Wk zaAUd=BlUkuYvNMOi3Ykr@f(e|b+4|k+D6(WpCXKdD@mys3#K$Kvv7#$|ts6-?kf%_18mMUe-Mb7}R5ksN_tzjOTH`;tH6 z>sLw{+_gB8Ol-Z6mT2{%SiuC&)9icRF^UXyDx|juSaAe)_01Xww_5%cb9yReFrjn` zDSJ~wzl7>htYCuA?Lz2OQnKd|9kk@11{2ujy4MH#ef%wkPf^NXz?&{)d}TY?@$(Zd zZY_>4i~DV?zN)h%Tk=d~v&S#FJ|`yd2sFEopZ$q%L{s@l*XtaCUASzjR1NnNVqn=o zu79bFE47%w?JicA$gU*eNj;hDDCP+4!X=o^ZTIvb+lT+AJ@*wzSiuBtcd;_qdlVTT z{DUsOvzQ~W3zuM4J_`NFKld8?up&aj3MO#7OQqU=x0dR~IKuZCTg3}kOu0Dg zY);s3D7p3ZBGoneKymbE92L57(@=P6k}jH-DsgcNCVLR4`B}c*3mqt-yDHmJ7$c6Mb-&o*T0sGXt~~nyc}X8drl9gI4(TC4?afx z3mtc|e@|oiN5CA46-?Z69|-irX0g*tB|=j-n<3;uXcIY9JBK5%YkQgi2ETGdv%U(E z-*6b2lvhtaRJ)O41rt-uoZtaIBlPF?M;w7&OBZ;7X~A;Qx{neby3Jv{#b#R?{V9SnflD+k0~y{#FMZW};0OUX39)kBWJt~rZ?z)^3zIOBB> zM%df=l8NOSntoeNY4Z`Vtj|_4WJM>bm)$UMdb&%z$o51zoEQm?e~*f<<2y5=d!{cr zI^+V~`f?w|3MPtOheDHvMPgW<68HSG)_9V3;S{wf+sP5w)%&m)tYG5c=poQ!{XwxRu010j=#D2Lmu}Dn?^bXGcE#-SfX7v*#2Y=8cV4CP zC0}*k(wW=RDONDyGRXxZ=N}d?+AH6vk~n|Tv&#!=a4e1^unWhIXZ@($2}D?Njv9Dp za#7`RBzc@R8|zbtkYStm)2EZyacN+poW;TlW#`MT@2lji!7PnqUk}r^S@|4+UHBQY zvDc9y#N~B94ZgmIdsdjZz0VhhTb~uve3YEH!g>PHXlxv&R|AHUf1zg_H9l1YQeU#SbtZDB5VF&hhs`nux&{=KAxLu0}FS-Rjf$41JGcL7aiq|n{N zils5ad?eX_rcx8)-b6Mn3x{8+nL__|{Wzli-$~GWbTe_t7bWu7NGA_s)6#&ZI5wBD zg44ihvoB7YF(fLiAzksQK1X2J$q`}T^>K{&!9m&YJa>^diF4{rk8L-Qv4RPld)W7* z%{a1uSTDLONW~G@)&61#JgUqTJsvAD=tfzOCJtev=)I{rTu#J!j3=6SjUno(q10*L zKZ+Gh;M~J%hM#_TQw@xl@d=fz*a+>+CJw9?80AE7C|7{o%GhZ zPtAQFa9>VL@F#6_zBhzC^Q@!pFE4QfcHx!*TbI#0f*donr)^&zqe-nMgX7ejV!jvK zpO5OOX%EA|ach+r2+IC**EN%fkx>|R3p-A+f(cyPv7T_tDddr{CpD?t%MsZ1VmaGW zJ)l~=uC3HpPE*6lxX!a^lg@i6Rxp8UZI!Cx!4&dw^JJRaeKSX37w#dmmSwZa#LI6f z?RO)O>pNote|^}_V(lrUdi)alwqzMcU>EL3vk3f$CJ_hy9rW|mOm1um6ZoVR7F*;1 ziz@%Mn5MN&;0Wx(<4mkyJ2iy7R9~dGo=)Y)^fB>2UuQXpnC3m8aTTLE0=w||KHGWE z;`QmfeWcq@j-pt>1a1wm6Dq96k`y;BdGn`!9D!Z@JWl&DL8S8Wbj{?epQ%$;9Jroc zB}{52O1MVdyeJk<4rnhP)fQMTX~)`EfgYPRhsA#sE11BwD~sb55lpVB)@Z)f)NllL z4b6>#gDoS)n6dUO4U36^#L@JsM!okl#R?{H?aEH>O$#Lv4@x!T&OhM@?D}zOI`~!Q ziZxnFq>ztiCy)*|wCInSuPIhAf$K_khQiV?Qd#v$V`XxSBd}|@G?lH6J}%b&RlWvR z#-U{4M{|0t-93sGOyIhbjijy!Cx2pF(Kc_(I0CzHjltT9_a>75eFzQfc$uq9Fo9d- zY+Q6x7_mtkL5nV*;Rx))^$Lq@f{0WCgvg(I+w zZ(oJ76C`tu&(Vj!E^~bYOyK?wTO+JLnrLsmPK&ckIRd+IKY_((nCwlSe0oZ6bv;V4 zf(hJjWAn8`N0XzEp3sPsyEp>7a6f@XJQ?9l%t}AgCLQxBRxpA4pKOlh^C;qSw2u0< zSxE>bIG7s!36F{vv>Y(B$3Z)%L7JF0hdn#GG$%ITX519%u=ez^;w`kjiaaDKLxB{BIxjV@HEqc;xSr`DBG4u zstgFd+WIp`V3*%qHX8lR5Ze1G=aQKl#FNW^{OO5Rtt6~qV$7}ps5n|J_FSvX*Us}u zASBU=-hA4YBd`mv%VDPj=f{#U+x)5BZ+i(VnCR3q2(*o^iA7uAurwyEo=L|2_Mttp zM{)#q@#}rUrbUtBz`3-hZ-#^wOdP%(0HS|?v99wqmPV@u5#&$fEPD3mYL37zy#A8K z_$#sJu#4aA)ZC4oIoXR) z^Wd|Z)T|JAGPeuF%rlqHHW?2#=bFOe^`?@!K`J@cH22m_j=-+kd*k8keiJBpt;{a zTlm^9pYno(AA6|}?ki?@-XV7!F`hgBaS!U`sE9%HLE0a3>Y#?C;6S(eTBappk zkYzu^fS2mrN!?$3YGd{6ran z3}aCvmdAG0OpH)TI6@1Ks)N^DvNMaF7_nluCQ9aGyxiT^r&6a^BjR)_#4b>ADuMv+331v_15Lww-ysPauYkwYhEgOUiL?` zy)2z0unV^(Si9tO8d>agM;Qt9t^Vi%D~sy;7;K z_8&?h<6$h#4}GA)3MO!yh?S2^38Y77H#(@FF2w|PiD^L~Z)*-07b$ZrKEsko^-@!M zYiJ9K6-<1wodor+cY%Uy%6PjuyDGhoR!zywmh#fbKt=*kh;Rex6~Oz+bS?0l8gBB9}lq}AfaV(&i7_SkF9a!REuqz7Ugp|0=t%$Pk~*v_2JEI<*H_^izmTt z`f6&L&7xSr#KMj-;7?4zWL{rJO!*f})_$I)X{eRS5!iK!#ls4!)rRQbwv6y-5KsOM z|Deu~n@6#NiP3DAP`B>Q;Df0W75G3%ELrY3NOQG3nV+ zl%osOg++@fRxqJGG6CjvH2_$sM4`>9oJkfWHqmTMU&#^J)wDwle9L<)CjECR$x%6$ zv=4eC91qE+_;d|?9tVHYhDF~P^5~P7;9j0jv4RPFvIpx&dBu>6)po+#E3zMWzP69%biU~*xWn7W@ZqK@^1&pe9|AN^R(5!iL} z`fQl|>!?_Ka}XnT?4LnO2V6R_`|B2p6-<;)Nrt8GcZlXbzz84hSkke?TQqQ9$r0EU zw>TXfk3JTiS!`@pmjuL+okhCpiVGVlRxnYzG9KOuSHup3m7F*xI+hI4d=z>nEaM5} zDjt{$_kHTbBR7>e+q+F?lCY{x>W!~+DOT|B@_F}UZ7gZ^MW^In%cUHFT}y8#LBC$+0^({8hpkK8@cmIB(+1@ ziPcvoQLJDBmmAjSe3VFDyN8O`yaG4^yDH`_1jmpQ!m+6y>^_$KizoHZiQ+AqO0j|o zTyEIP%$h_pEb6qVlj6@2*j2w|0mLnH5g#UxU}^N}oIvdLO2o|kB#ISG;Bv#p;T|TE z7v^2S>XR==VAsYO^P$3ZwK(d|FqXzwJC;WKrf|k0fno&{xZJS!u|JVmpBW3&r~7dP zcJ(@v0Ts8-iC3o&WoeAENgyA8+d%79@f0hVz~zR0&*KuwZH6%tgsI~wRxp9f4Lb##<&xQ~9N#Mm;0Ww$A2J(k#@B-sufgm-;vj)^ zPqv5Ik7FrTFoDYrn;G>;BrRX2gXOY7j=-+r9cF=P>n2duTd7Ohj!qzR_gjPTZ6?JE zCUCi7XF-fjB=640fbG>lj=-*Q+fw11p$Tk!tkfmV(-TNkD-+POjiFe<1YZV^viGqp zDFC93133b_UVTe~307wCjUC#=dMt7R>DS_;*wJb_#R?|ySCqYvy@{lNHIiL)$8!XB zMX)$-Cw#iFEq%(I*9GH5k~wXo_$h4)#R?{HYk+;7|0R;m^Npcb?{OS~UDc~%L6~O^ z{jV!+hSd3qWbTP)!kLm#iWN-YRt-A`Yf2JXGo?&?(Q70}V3)(U84$A57JSQbUJ_}SbY49# z)q`RM6S$ShR;#BZlghfsC3js3M_`vl^C(zzbpUMquhkdWJDEJ%-AhxO>`1YK3EWy{ zGjYvQNC;e3xB6kj5!l7|)rOQN6Q}R#n#PemDONCnTm5Y9$N3a;HgUKnH>Nd5U>EKu zvTrSmTWfLlv_@|X--E;i?!B-R5$2|n82v+<=^Gw!y;SVNJ!H0Ll%|k!e{Fj2(J8Jc zj0rrp%p$RAQdmr=BMR8<&`661evl};ZhY8%LW+zVViy=C9b7}g|IKaP!U3i?4jh=f? zBkp$l=-AS0+;}1;@D46kGh|LBu676L)4IkI{w?gnqo3@3xP+4<&Znq)qCGc~iV3_E zjqUEQ3@7V)oS>(MjNl0D!sEVdtj{Ba^xl7-j!cf@#&uXQ<1`rQA3*Ch*Qc7W>n5A}RGcNKG=9a0GVYad@_?v0)Ig*h*=) zt{b`Wc1+;Ci|ne729gm!kJ7CCLXN;LJfFbgKzixb*H!V8F%^P3>MEF7hxYaD+Ct@{G;6C+_-5&%12l2<+nH^-bI9PS*XYC->i)FJT1}I6@oyI>(M6 zOMSKF%!j!gfn9vO*Wxa0-K%6ETbr$tu!0F3p^dGfzcrl9SXy6Bo|efG*oEUxvM98> zSot_$C^vaMn_boa#o5IKj?l(t$+nFkt8X@v-?j7O2<+nHSr)7uO0>*c%3j?hE^aL* zaD+DY{rKoXQfr#ZW7#f#{9D+?N3;%!awk81Tgk@u2BpkI-(EPG%K_iK#aG zH25@9d`2ohL6n`&)gp}rT%RExob+9T6-?m%u1YnoVH&ySeOPRj!xPwr&(vi5)!6An zHzbYt<8E7u6-?m%F5AuVJe3^FHiIeWe{d&yVi$j|Wfp76yveYJrbg{3RxpA4yDSo0 zaw>UUG#hdk|KrZJ#4i2>Nisf#j9xPfD$~p;RxpA4yUJPEDWqTfJ+M~R82AjkWYQvXd}JM?yi{KHM2@n85vAHirB&nPg8}4LzoJ;t1@*r`oYONET!3 zajFe`E4AWImcs<@@3Oo*D}{8lh=x1M+i?VT;ZxMu`rU&mB+TN0_+wcI?zA*a;QlV# z$6}O9^3V4I{|`nSfnE4)H#YAanM#5a>w%|HWA4;9OyF5k_ReRdlDpGZK$H64xs&Cv z3!iGoVtJ2CB__)cLuR{I+x*rqf zcoZnuyxjKY2Kay3Ld*H3wQ|k)YIG+%n z#OiA-rk&;94U5Z}nF*EW&E)$7T?u|`nD}MrAWk+us#f>D#nSNJnhPGoI?56KojC%# z{JIL_r7v;nbrnw;vF_`2NWa)kZhk-_Si!`u6N|;tLj%+WLzOeC7VDmd?Hzl_wZ9!W z0=vFF7R3s8NxhX+Gh(g7V>mJ2R(?FZAHfPHF8o;{{&=aSo~ENjNh>WdlP(##%9S;y zWORA9*m22*65ktNAodXzr&nd1a1H+r6$5sO@82XGKW3oB#o1MQ5}qZw%02ShlUM5p zimf;9DOok;E41ypTpT=GtK`e!-_T7;5cjQ~cj9_ig($siDb4*mKyGo|ikwbSi`@-p zm-J=lZ{sT&d-H_Y|8aFm_ipdmRW%)GA{pq|$rl>+CRo7)z9*IH+cO)<=8COsaET|d zYwyeB;@XSW>K&b5u{3fn_m^zSd&nxOAHfPHdhI?gN+FZfw{0FX;^4uzQoZYT@)W57 zY4)HsymyOt*b`X`-hJA@ha2;S@OwX?l|eJ`wmai+YqqlPb^pYd(x}lTfUszoL~hLd>Wp|%cSEaedPgW#vFlN z?vv}o`NGT-e~3~(944yR39EhNTQ{``zIL3(xL-|O4ReUh{Y zRxr^j$pXCp&Jf1td}c&+jv=}Gq?f!ihsAG4zlB{Zbgdw}##A&6Q*wzk&0adaX}G+9 za5I8)9L|Z8U!D|Gqc1z;Tvb*spMT;bncnb}=f7w`u!4zLqq|~wVW4n#yAC6k-VTti z_ZTY&t@$Z&1ai%oa#mdQbcWzPQI`>0mu;7XUw(3Ovx`zi;RkWRpnby76}pneIc-QC z@m@$?QC}J^*NPeRieML~tl8GqJ0$fi882%d9p)5F{HxZ1jgh)yx4Fvt#JYz2q|vK` z_p943!S)+JdVYeemRF2bF2T9TPowP-kZpZ%Ec zzkpH|_(kpze(qB4JWFSzbS`YDY&xMn!3rjFUH*zsT6YtEXZ&MtP<`{D^kUBl`S68L z5+<-KwL?RA-v5KJe3SC5Vq*sp(~OR?euLAXLQ(c`Y&#s4kIkz+7D(rW?y~sAl#B3( z2^=Ml?fMO}BZjqB@|DC0j=(NHQsK=HJz13IUUKb|G%oHSCUERN_WfAdmE?Y~mGAdn z%MsYsx4AWBe{mI~J}RqNjmlaI-!IcYAWPKMotmR(`E138+p#hxhkS|26RqlLTI`LmpY38`lz2)?B+zTc|U3?AFB zNT=S7m7kU$;0WxxG^#NydTSzT7b@kvwBA!GfA|=A)5L8ORxnZ7-xxF}ti*FA3UO~_ zt#rHL7`gYJY>vRLVX-Dq8Eh{GTv2wVbotSYtl2R_-dSfVjWO>4Et331jcya^;$jO( zYBW(a?$A_vGp;T8`wbQSUNvGwv&&7%L48lT>nTG{!33OW2a7bL#5X^c=#)15^huR! zq+HL^i6gL!zp7I?t;my|L*$CQ-qMpxW-xM?hgklsp>*L{H|UTQBRaNiB9)YNhR^Cq zaZ)!W&YjsSEwVLsq0*Mvk03Ks;u7a3|LyP|@NZ$4w_{g$kP<5%cURV) zcVB5mT3-hFd`JWMbHfV!_2!C)lbTB|9+vQ-Lz*agG?l)(*g%uUtp}RxlC&t2gLx%Mt(XP$K-Tt>-|7v&gDdk)KO2fnA&0_lG4Jxnj|MOzg#gd0kDDz{1n(Zqjr|$+z^nL*x%&{?7}&p z_0{aVkZac+<+k^416DAB-zLkugU!j67tV5@1RbsvVHeJ0Y+Xi!PNX1uki6p3Hoyud zaDHR8&nF9Vf48$-GdGJPu#3;T#?e*M`g9Lj?@yV8TNBzwEnrZ215t0eu2kN#C74|? z6`@e6MPHw*lg?%ilQ$ZwIRz8l)7nA)w_f6|H3~7@M2mPj50g6^?c@mTN?O?-#vF4L zhp|1>>`aUJhQznZRW{v|Ct(E>b&*|QPsJF~YL7xhzG_ZF1s8dJ#zKz3uIklYp~^i> z{PSF?cjsHSBZ*#)a*xgl5>_zr@J>(o>X9biy{ZuEtWKoN7UUy~MsNgnEi<+OEn&Wx z(?+Rx8)lr7+Gm5TmDz~k?;!3E;4i95MgClqK0kAi+ZHwAzO|UZJqs51!O7(Q=JIS`zUcUKQi(my4xL?AaZiW`gd*C3q^RD4q8Q6u}L~Iq3wI0cI z?=LSieap3dFoF9eDpkkz%}B2u{p6o1w|DiHvx+LXHXJ7SKF*L) z=EQMXPx(viNshp-rUkvh&d*I$+bWT{_r1y%KX)7?`xkU3T_;=+E{$(rvasJ@*t#>T zaEImEl6C`r03Hcp^B-qSL?hxTo9cHbSi!`}?5x6LjBd+l_T}7WB7Rs6@_M zDdttV5LDh=C=b$;%1&Mp{P&d)c(+q|=bvnsi7xBM%b!}R2v#t$#NJD=q*om}*ek8@ z&_rwT+(utnu+k-1G1;C~80(ts@Uus~|4Czs>btOez&LqbOnoj5On9uwD*Ws6|I%zF zdEqzVdEO{_>53*Cfn7K+u+j5Nv&93&Bjl04jJaHba|XUYw*UO}dvSZtNZIw1A(sXw zI&0d9oxUw{_)t&jd41~A5DvEukX!!x!`&fv;it|@)QR;lYlf@*Vz?PMeuc-ZwgkI~ zZ^|r6W_4FaKPDd84bOLb$_eV`1S^<04yoeq+yaN()k=?LdR`Oy(7<((gX*;pF*W1M`Mjj(KfyizncpyRObx|Y;r++H!*PG2~Yts_0XwnlV0 z(M`x0th{rrwXeW4ZG`MOuLZ$lZprYvBF#F)}IACs@G*pT@=cm5>=TRxUEs z;|T1+_r%UbN~wf1u0e9AdbJW(FyU@KTlCCw7tRk0Nr%F|t7wHlh12FU;B|KJGh;;*Xp&iByWC{&J+A9HVN?a*9t&fN*Z#=m;p zFR9q_=vt7p!{xflYn*}!Bf3ruJhVtSe?+N$s^mK`t!ISXCa;VmunRvCwm$K|XLx*m zs{AkWAor{=v8iL8_ zE3ICcEPsvF;}lFJ#Lp8qH!l*pHc{G%oAy`3`l>{^=Q7|3?CLf*Lkw`;DrmbYS7rS5 zkho@HlDuq?mt>uON0_u_gHRXLMB061j9`$wP!Pi!N@eD^g_d8I3F}8FME;y4F~Krc z?qa!uQ!s(Q+H5t|l*vN(NAdDQ?OD=;)meof?UxG|-Zzq*3$hB|&&Uw2={4liV<&(~ zlZ8brjduPkI0X|^8Ew}mT{yK_d4qez2SQ}G79Ac~8klIcC9AOJ(pq6oYbBR#2{00=X`1}8;u}X`m#g(yVMO&B z;rmJ@C+4=v5?qg^%3X))OIX3gaCU{&|9={hu319K^i+9!P*aY;E?`$>{%DP`_K1>3 zt9C^~z@v2ej<1%cFT3+0Th3GBj8oy9PH`C2@{YKFHzj!28I-Vln$4;Nk!*Ozv* zF%v(pjS*l@18M%!N?}iEnsCEa$%*GZo5GeIGvsULTQ~(1T7KqYK!>Hm+i;~nIPF|3 zNNf==|68BI5!iJ*p@TT+D$6}%m1p(j(|B;HN|GxDX9+8qIMm-q%=o@TxI0gI=SjwI zgqqkSd81||E!&h;Xz_flpvh|{-Ja+x{3==_I5%i6waCpX%vNU$G1rt)oVNwmV0nMM zd~3;Hy42>ruqI%ZaBg`E$<*_{5EV5|SZUBwD$LI+G|8MP=*?6{if-;U6UpCTx#`}w zl(OII#}r+rlrq=EF{wh1Lkr2n!cTB#-;Ycyg;-x;CWhLD$yeT1QLJF%F{6*kbA*|1 zm64*5HM!!=m6PQJk8+N{F2^6f!srtVg|I?}7#d|H9-0*)xAne4v4V;D>}t=jG-Ccs zL$C2tardw&dDg=d9D!ZEFZ&83Z!Q(6nUaQWw!TI8kUf#pnjaz!pjV3!vo7P9v-^S}2o?VSsxt{)`d*xN}q%eXI;w;n7Udfig$%bw2+ za1(k?Z7IE(a$l%e>nG@>D(8R1zn8_%ZwJd>P8Kp&Fk!Qf&8suI2cuQ0-rr;~`>&g9 z)vcY3l^~Wz>Ty58#Q1;H82?fhyLa`FONSbBX<#CX(I_U@BDkHJ+!p+maC35 z;|T1+c}%5RUQ#T2%^xK%%VUu|QSQUUH}(b}vox;#m&Ujo#iHTGvGP0veU88`KJU(m z*e(WH1<6kve4|*w`52c1map8tiqB^T%OhP`tVvWpFoE+liweAF2*kGxlN&d$;t1?& z-}t_8`sMGu*{3`GmKa`6PC${JY)k2yQ@lc;%lv!AYG>`#|A^I{hqCf(ZW!g>^dOfdvVZNe zBG&hUyBIB9x3}cR&RgLw)|_jj=~<6r(>I&fs5o#aYgQu5D4M^wLZGXOr2YQ?|0GA8 zy<^$DGc$~Pn+DSkc@5W<;jw4Gxr^%3rM;ULJME6UczL&tcJadU*x={pHCE7A7S=w+ zSllE_l=`6!dWc)_rGTS>W!d3&SA=Pg~ZnMTUyxZ1=^z7<~aB{ zIGA4?HIyc?u?m4MY&UXuO^Ffwedhr*XxA#GeIT*UEr`7vFkRbI$!zC=-^TMMPkU2B zG${nSu>D&sC+aQd_saC5|E6D5+Bp)v$_6p*{3PvehIx%IFQ)Ooce~NhY4;QYUD%Jw z*z1&yoTYRkpR;NYheU;%L2QTL7|k`v`~|!3S-_jwx1(2M|0+Eky08bAJv9;@t%F$IjJ{ghT=N<;Yp&)83pb(Aw~h*dE*$OTOlCXr{~YSmjlG`Ah=W9U zQV{EXqO}%cG26$pv~8TmR;PQb)sYij>eD_W`6XYlQKQnE!<1(ii8&8iGvA%nwQEJp zx@rr1`-)#Byr_2FI&}MWYc_6AnD$S14{`f*YZl?@sCC%qAzDueV&mh(v~kDHPj%pn zlX$eqg?zp?AXJdpH$8~CO?J@cdzjZqnE06cbn&IpUbPegU9T42))wZ5X&365*SOyD z3||-TNzcmHCsdF~-7IH=M;x@6wI&gNXgWWV=}k7F^%MeK*t^Pn)G&WBamEM=uyEx~ zIDf5`?BbpiT5ccptyr#H-d8|m6d6f2FQ;*Q`$fX$`2;rN-`(25kLG;$%B4?y>Y@>} zHSw`RpbOuMWjn89<>faFr^KcK0u?0ApKrz-l9y{YHk)t4wSMpCMV6&f+^vQRfiCrJ zdq?@@-0j^E+9OXnMg@sI(FtrvtLfT-9P@30W*y=e9*v?F_gAvS=1k^& z|DW8aSPHRytrY@Y`En+)QinHax2u_bV(UV_;zjELwD{Oe0~I6&4_VDddvDXu4L5tA zuznRp*}I99Z~Z=nK-bT$tJyQJ)ms0$X8U*>lV3C+Fp^fSX==saphVaz*6Px6ZEJwD z!22fi&RHJf!298})!qgw zNYtsYnk~rMs|9Q_e-F(sO#D}505vQ$Lm|+GcUtbj$`dCZKOROS>Q3S%)@)%Pmt<=b zb`}+$V-B!2mTTJ8>GHkbdXV`S%GDApna^%kujV4B@i59*dQC$GiI3B>Sm-|wwOJnK z-EGCY3y-5Iv?p<{6$x}5*qP0CyWiCk_nP=3KH6YYbZ z^PA5PO%rG0`cuCtofHCHk^OU6=Y*Tu=K%A$YVR>moW9wM&W@R7pn^ncuSYDc&;#v_ zjX4?&Z?izyQdjzsZ<|7(>%grXR`l8>t>;to8i#rg5{|dp&;_p-#_Ug-tkIYC8e8fi zLhoj%Po_*_^yZO=+ueMue)xbg2b$~8LU9?4y|5ElQ>>G zNhB5RMwg46PzZE6^v`5*hpn26t4R!S>L4n&>qQ5~?=nz9qIZW3c4O5+?PV*o)oyIs zMVt)jP0P2fQV4YY@y=ww+_JO^bxopm%@$(B_I@<5_)G&8BnlVJVBT&=wHoRF`vqBB zVV#*wPj8M<2z13BJj{GnpVKCeG>JnU8;Kw72honl?G03rxU^$C8@oA6D|^6vu52IG z6}?ssrBB5I6arlvQk5uIi*B+wOqJAf5VU#D%4 zH^(S@_r=`4+-O=EbSV=RBye1jy-%O1d~aSE<=orBiUhh=Yk@4)ZLM~szS+*l>|Mt< zJse4k0?%1dK?27Wi^Xn!25)FLg5De}W*~vCs4K15pB8JhqUFusqr;b{{IWv|P3zjp zKm`dLS7dJcaDLG>Z~*mryFek(bvAz*TT*6$=2IuxL__0!nc=VP@}C*8%MO|4ny zbz`)t_ua$;k;ax*NY`RIm~HU)5Erp?Lo1rFGLOuY{hxwF`i$1>(&992(*W~(Jg!q* zl<3-)Ha7duKmuKx%cQZ%t7mD)znR3KYlX#$uAL|-;e~+;65Eqovu?{~XpVVJVqz6L z;dr$NJ?eHrA<*?9v^A?(aEW%mxY-6*uD-&3|LI2)-fuNfLBj54ARGB=p;olI`J1=; zyN$P7tHnP zXtH^hsv&`{5U-nBV2zbp^FC(JP@>*eR(Z#0+IuvHqk@E*o9MjxGTZJsnwn&;Q3!Nl z)=AENe3!5z;iE{i{m4;40y7X6OW_T(*wNF&X`_23C4+@7%uUH0i;abyA2p0F7Hz8J zijYW`xruKwPjyD-sbriwq?fkodMcf-)j=W9g_$k68h3nv*cw@bn6EG0yey*>W!q?_ zw!4c7)S7K+)=$e{$6e%YnZ~l4Bx{xsvklsA=_#H(3#U1Y%Tud@YnYhXLHl>Ir*L&# zBiC-$*5=;x6b_xzSh4eMwYL-h_jdQRjaca%M#Wmh5GqLA>5<0%xYpFZJur!p{;{G} zYBX7fmQe_F;it7&(%mZv_cnr#1P3eM13x=nTfU|K+fa<%$*8DJuyPF~-sM@tycZ7A zzQ|hs7R&R+oyC8{qG@9PFoi%D-Vs?h$|%Z%j*g&>vwf8uB#v89R7#~_{H1*jsTOrVetw2WA=2qdWW$w{zhj3)lB;ZQn0bBIEq3wu|Y#~Jn?@3}acnx!mLdQl{Bw39W@ z`a6lX6?)OjI#~*VE*vG~EF-bJ@c+<(3O0PMj0Q-k<6zM?l|`7`J@D@HAB8{{j$N|) zUP?WY-My)-eqpDKgGlUrv6`KoHB~D#*ldF>tHp_i!HsF!yg~|rE*yj9`+4Lfk+b=b z(RN{13Ugk=CNy~!%XWK-Vnx?5n>`z2bDwyLjDBgXS+8fY8;+VSs?@kKqFbIVMwR(J z2^Az-^-W{^0@`)U%M_4dN!!EwX)MK^^&*Pj1cv!)v!$6o$nevj|#8;Op&yNtd8 ziG&IgBY(7Jhn}yBefPh1zP4l;A-PoBVi1?5qVQ(Qo4~elF{ZQLR)Dg+SNm1GhDg(+^`q- zUrr)akm!Hnw)QD^dF=8~^BM!Qm+>0aZx}1f_fQCQVYFV3A2DNi{Nm%rsRF$T6(lhB zE@S%re>2-YCyiH5DuFIF3$QG8EK8}j$rw62nNUFjGXiq;&W9mvT=DnDxMrOR^AVUm z!A~pOdC3o~{2d$m{j`npJ&;gieXbsZ_=?0l^sH4|g+LeHb-62^=JC=u3s8;c&6T^0 z1jZI+#OqrQpS<>$;Z>xaLZAzu9+_9$@PTiul%ITFv{0WCh-_lSQ^t^|dWl;PzZmDo zw^ImoVJnbxxTPh)qB~^4ci3wVgts3tO{Xx3s01sGaY- zaUr^u(rS@#mp#MBZcbX#7_*%>N=Xsz-#jpQpLPm?F6?9EsqEt>uwTcbjbYD*(^HvU z>gSv{cA>>XV1B6jn>Jd?z=+r=2eW+~JD*opM;>ZC6)A)Y68KcgO6jsn=b7n449lyb z3W2VF&)wGkRw*01ppkivOI~aFzXRqNgX;|p+D-muHfEhnvJ>pLv?+(fdYr6CXBD zG^XhN2^A!;*Ot-2tbfGjGp&t1amfmSu0wWfm`~9fu{ZL2%WHgko-SJLA7iw+(T7k$ z0!JT7{8%DpCpI!(M)g$)boGj}vP};g#Af^Y$ZPaEI#cAdEJ59TD$~+tRyH%Io>o|1 zy`i>)y=>D-3-Iw0F^#P(s&^M{%|7#+|K64+q5{g&%;OP+3KGpicCZ%S6SUMM^Y=L8 zGEDd^tWKBac~IuJ)$Hfpf3#lLJj7H#E6a3WsOc>|g-TRiGC|aT5JywSdJ`&0e3NyI zPL7$V9Vl#mD%K`l1dOUcA8(XW2z246mHP*Wv}KcDCQ^ZpXO-3JxFShi-S*sP9$S^w zmt49XP}Zs;p{`rnI&=k_er6!qzg(ga=u%e#_W3Ul-xHidcV?$5vv4GEb&{MdxdihG z*5Nd&OSD3u3uol=UM=g+uNNFi-rkM^6(rP^PK)NH@fPl*C{LBkO2i9Y7|W7x6P8_k zARk39=dI+ZAaOf>BAd}|pLQz8d=suV{yevxJc{)1ZVG`ejP=X>N2NSs+^3P$XzgPS z6(n9+SF-B)PinJjn=ycfEuBTN$dME}%Uj7CpbIksGFMbOREUBjD8{j$6%{1Z=-`8# zaFOjkoL(QwRtR)qMnIlx`J$qjIX{)oG|O+Gf&@k*<*wf?6-4c8Ln*#ij6$FbGXgRT z@K_fm#t){CqvZK#kb^)1W2ACt*lta9KRb}-8mS6_F3cfVEN!A|iDTCO^z-s`0~I7N z)+!zqu6-%$@JfY1mztZfo7hlPiAtm?H+C7QAb~M!d9Qxd7nkaGCvhZ8A<%_U zJXx!_L@QCfZzme|^M-*65*T~8SZW?=A@a$Xet_3|g+Ld+y~uN46Z?oxmINBJ&W2Dy z0((1o7TwlF(fvt0xjrta5a`199gF2))qcXGT^%aY)R|C00{debd!5!q?DMKT%u%qHRjR+Map1Q1I7ZY8y zsKMq~8@G0x7;694_#59!A<(7Hcc)aEE57``X3WiKtGsO^Q9;f!B3itUeRIK_`*aIg zAlmuwHXbeNq7dl9S&iH$ylSKPo4Uk!a=$B~f<&leF7yAoD>h%1V)7b61-6Ll1N$1i zF7;9fbg8qYW3dB7r}#FMbKsT0>M7|zZm|-kcc{ZHKn0vAO?al1FdxWK<_wyX&e#po`bdX8#_WujLCji3gR(iplM}Qu8+?P(fmU z(fh1x$1|F*zquoK>Ec1cEvGwqrX5fSbVWy=X77JwXrAxP9V4|}CW<38Oc98EpR-R^`t)QcV1lD(w z`wd3k;G;Y%Q`r+`6armXvr6t0PI3{OZfjKSTc}da3JI)0CF9iR~0u?0G%0_-Z z(?xbv2Wq(BfdYrtLY+jb|2bz zew;w1hW?oO6#J-E-B?(t?fiSSG%@FUKbrQto1!4`JNza)xa_5t*v{OWQG415Q95rj z_3xOZ5a_!2<{W#Sm7|U7WM-FIw3sL+lo?2=6d_PSBCx=1*80t7t#lFd{bTHnv0`zB zLDaBJkV2sA;m!+eR^>-pn6tSau7+K@xEnv1N~IjacZ< zh~CnlJQ{woo?>rUzv_9|8Ci7%UAER&Y<Tx#cehffIbvdmfs~l>hNFT6{{C{cNYRC&PKyC_M%Lm(0$q=5 zKV^fD|JDNJ4nDbt<<4BO?QVbi`n{Y$1qpnPWktCy7X4II8%nADgL}O(#pdRtR*BTocHryz0#AUNo}+e`f~jgL}nM>$9Z{RFK%PF@%3=-j5wA zY|dUcJBR2_sg=mKZdZjs*RJ5wJmg&>J9*Qbi!M7DtUrBIm4a^piw=RHx%cD=J7_DpHoOoi~x~-)er3 zTZN+Z1MwB8`Ftk>33MIW9m#(NPGl{%n&0DATyNd+%n_r_f_2t!znbyk{0BR*+Dp{h z)`G`;_{DlA6%&)LH{uCxp0a0^%(!SkTB2Sq^_0=*S%wuABwh?^!h2tR!7^T(-~4gj zZhFao9vjgeswxD!?gZB3VRJ6AX*bPZaM0t<`qxdbjei$3v7&;+%8dHldhQy_9`e74 za6)^1V71@IbWdA_K-a1TbvVCvhK-9e?^WeD9rU5bS0nK8WGgC2^zI(dm(9;**Bs25 zewi8V^kuof4Zp}a3W2UVe`@g#!%nc3v&>J`bWA(ltIkg&eb;3xDoETsQHK|vk;UE? zHLp?PPz&8_w;k2uM->8H-49gdBYN*)`zM>%nDJjT{a$bZ%3A-`iV6~qCRFDQPw!~h7WHyj|IA!-(#|Sb-m?gKZ;)AXP|<_(R`Ko=DzdT z&I;x=5?gV7wrePbw9Kav=(_T%953B>8vB)Fwy0PBOrNnMlwQ1YHc&yrX>oa8_t!Kw z>Ye$i9{!5fmsO0S4M)ydkw90YqzFD~$^_=Q#C&%9zAUESs!^9Br+aJ9}!lk#P<%;U*=S!nk%YVQ9%M*v;0(!rS-__oEj8=s1WG-`#p^B zTsTVRh0X8LeO{#g&z}m^;Dn!n3KDA1aPn6LeZuB&`kdQJA<*UCEQ-q*C<|I(KD%L= zF8ZxYjVS2fAilVaH~$#afE~W$An-2uZuI9@J9T1J^O}8o&@3OlV%>V=z9uFU6(sPE zSS)L1m(U&8)}SV7i>yeXtBZdrzS<_4l?(e{pEx5#mjfa-j`(dw1qr+(@=5F)q1(2L zp~9Oq0||7UpB}-t-5Ji38k$dH)t2S;n79b~xVMLa3KHtQn(;nHuTdq4O6{Jm5a>#N zRi0mcGlmtAeXv|vv&B|#>(H9+pN!zgqnvo1Eir7;Lt@v(=8=?xd$xZ%n+`J}W9n;2n`GWk0&>ee%|$Jvqe;B+!-jsUOeVC4mLB zH(TwN!^QRD_o|Y$Y(oPTB=C;NRWJ8T=#!4c(#hcy6arnggG%xdyIQe9@n)<2cU399 zh+dAOOD{1{K|;M(fh$Yvp0**h%66|ppeyJ}IDb*EHLFpsxV%P`ti%=^mq68aSd8RH zF5J0+UBzp$zXDoEHr^x=<| z)nG+$oA+wa+akKqE&FJmU&m7j+(EshVboY1GCk57`p0g$zs2~yPTAbGy zsj~^g%ywRXs)OGDTP?b~W~xGWnKKDor^Qmh-yX}g(=y$s7G^gig0~I7bhx_v6 z4>9aee)CDJ-pNt-_Kc&Xi8~YmT{YHv@)vE&vS+#Gr>frBMSr(8hU~|jGf+Vytdt-3 z{}aZXN1J^~^b>FW?wJx4{{CO1_=sR$-#&;Hck&bH>b5k9_Z=U_PVO{+!SI8gx>JR4 zviEynpn?QmPexc$eDuS|!iaKiDg?Tc7X|WR%LR*I=BJ9gEX&FKJqFo(=u7(5p!lPM3{;T7=UA?LeYQcoz1E8|-VG5LzouoAJ5Z$)wI#pe>e>0VTGML{BOvG;7*<-Ba?4l^>b*KVn(Gq(?|s^3N- z(51c)W^G?5O569N&R2>FRFF8!KeBz^1=zG+W(;6JuTJz07aNia#|+ zXTRi~qT{|K3L05aA<%`97a7_9c~A^X?MB00#u=y}apBf?me9+>F7+_`-Groz;&`V7 zirjy~s4zb-Z#Va=*7LfTKv(5FdHIV7TlS)-*(cr@lP&%|+m0?iU16Yt1YS>O!)5L3 zPoLXSnY;@X0$pJZZ1{i|g;|+5=B#ha$`fL4m2MPKzPo`65_sP%mUCWbM9mjnN$b>7 zA<*@BL>|7_&zXJbWZvDINk>Iy!$i6k?qHyT1pfZ=jU_irTwBqLM!m982y~^*vGAz3 zt}N)RIYWN6#VQUa^r4YelB}p8fzPoVac&YFB{(8ja3UVpZ29O z2Swe5ed%c8K86Ys*dAqMqJ$yRr}m-pZ}M>@(Dm2;Hyf1V!e*qJks{%>M|^6~m&ol5 zM+FJ&S7hCf6$eCCNFQ?edsiXQ6>;$g`>Q#yWHKXOX?&0Pw`_0PKB9y`1qtjQW%hOL zdNHg}n#IjaJgfMarKB6$%CctPp3-!s@M_+G z{L9!7Do7-Zzs}k(KcxA0FrW76-PVY}N{z{~^{asdx{f}7#76Z#t2G*C5#ac(yy9jtzWc zAb~F5W$###zt6OJugylBpdf*}4`ozs#CkEhNf+8TcD+KNE6(vD zn=|;G_W6HRZuT}_B(5G$q&n9o8mJ(Fdm?4!;mI?_*wV@La7JZ?Kv!~=t87%2H`R?(t_@fmSByex1Jk5Od5Ye+*3Wd${QwVhBsdAES+wnmAJJ4(&4x`$O zCRb9a!^>R^6(n$vs?09!Y$(#lr_z^8M>rDb+T*vMeJXKId-Bkn0c6b6MEQ(VdQs~a zM+FJoMJspF`G<(d$tmQ1w}LTa{SZl1klLB(Pqmto)S~z^|Q?yKABX6armXYt*bwmB2mT*Qbyho=O#3 zB-A>PUt2};NuEvVO%F$fKo?dgmGj-)EXSYznO6t z#ylQin?#?+WeZf0P^(kUh~CP_9qUWASMF8_bZs2`4{Nk_j&^^dnLp2tyu%Ou=toJj zHVIUaz`BZZ{nhR7{9XBhR5o~yLZC~15{t`KqffsMq;p*-3RI9#Ycx*%FG8%TJ%l{A zwN?mpVJom$>U^vtA_@+r8@A8=iO4;AiA(M z%Xs^gej;&B3i(#5tF&_@G9O)LFE_o_@^vz2$h(q8i+njlX~D)5nfSlZh5eY!BBxCi zy~_=z4n7%5e}%-{%lDZ}^?$YI@6370G`D$TY~5t4c%YPl{|jB%AItWUxLP#IN}@Nj zdMN!a5>+R^Wwj^#tDWj=&fz>=wun1byVA^FOBDiLIIhTjMYRrybvN2j?_GzK@dJrX z-+wSI;+=N(jycx;9(_bS+|!6kk9(*P=)%!Xu3`CcPW*SX2F-H&rHq3}EGUqVA91~{ z*+rRe^y|y*69t4$yU0NqopHv2?A30INPpOzN~hme2z24ND=S*xS|RqFZ$sO{ zFBzyHq0VH|8!i%$Ms=i>sYet7U22tr-HsXTX`u?V;(4@kdL6Ef!I4O=lUZ4r4_sZI zD&&t*#wa9kZHqiJ%q5XG{aK05wT)B=bm4d>ZgvY->Qf`3u6k)XK8M$g zsVZaPK?;E`tPm}8^oQ)loEEj{%!gu1?Pw(M3@-WXdU}X_9U9TXTnB|f7uKql#f?ix zi*{>UP)=hT9TgbYV?lS##iiT@k&hBR!pXU!Z~nt`?JP z4R&$y>~m-O;CNFZ(1kUHoi5xwDNsQISBuG77PqR3hvR$Fm*a*)pbKjX zTP#niwh-e+CDG*3n*=IIsOwAi7OgF=?CwKL*RE0sbYV?lS*4(RJFz9QKP{@8E>J-N zSCPmy^wk=OIt>Ppb@W(;Ko^cz7R%jkUBo-zL3ARjkw66rTty$vO3of#TYuA=D!34MznDTty=HW{gY``ECrQ(XJyE0$n&>$rTWf)5NcBL#XQd zsv0Ut;K~uXAE(MJ;eBxs-LE^#iUhiFypmO*HY^wM`IBk(7CQqKBruL5f5EyNM6LHp zRCiEwg+LdMSMqJ*${rCC-;K)GNjFeI0%Iq###W?NBxkiH900J_0~I7Nx+60UxtGO3szo=Rd{hW@spH^`Dw$&9(M~k0!~%h*;{7gW%TKg(k|#?P z61d*WVzCy<6w4cSrQvc9EGkH3Wm))@m?A81toi;?bn`B8>3uh9^CV3n(1j6JdA`9D ztH@o^gSNG3uEbuEaQ%^ocaCvm`wE+LxJ6|T$z60kY4hUx3V|*)&M>IMNpW;WFWOnI zh(HAiOITih;;c7IykAYL847RTi!LxmwgfD zJn?*i^CJJqM9TB)oI;=rBS^9hUcD~n2K1oUx5G3uBowdVb=* zm^Qc>#cbZH#4M4x_s5?1b12B(C7V&4XOXu=*JjPAR+T*pfi8^6%BN)FLvgiSJ!+AC zU5ULSF=9~xZjJh_)xBZHmSX(wh^+Q?sc^!5g+Lef67ocZe2>Me@`Bp8wh$^v_&62h zv-UpFx`dgzqTi42isk(o4f3&72z05v&yFK!#K~b@shnRsf&Is@R{8nKhu-XOgCYXk zyzEOZUJ}))8;uMMR}>^hFS6q)Z%eR?L1wGn7<677E!cy!gC!IKT}qp`G=FkKR9M@c z25mmVQ9?>4|UtSu*K5R83Ua?bdi~ZGl(2Kvh8WQNjHgB;scY7v|g?6P5NvT#;kQfkEh#!v+ zVfEUYtv223p{N+ujRsrhCdMZC=h3kADy@*$H&^)dB+*B=Q9oCyq^~3{}py%#yGRpwp#N>^e9-L_7uog2y|ham+Rr`eHJy^RH2cc z&ka>OV5ygj*hdD~c?OqoB&~6#`w@=H>5k=duJw4EyB!H@0|Ef#4U=VCd~^e1iG-7kol-P`$Wb35p=d-F!^nK%>14%*WOL`7SAew zVAK9tr7dacBl4em%u?4+(XNG?-$VPJDeg=Sri4eO2^Ay)T7O_Qw@lN1eKiUCkHp)9 z-ZcGld4)jNwO$`sj@DOem~QrP%g-DarIP*_hkMr|RE|p5s>E2Wqf>E_8I;TJJ&o4V zmzvioHe#cgH>3hpyy;I1KVD}i1}xQ{p70X*ooYJevYhP6+VDQ+Z@%E{b}|2DIF(H( zMW`Tw-%r-qy0lGfni5FcGb0rOU9JJStYSh>EupaasUj{N5bjx?GVF{1nEC~EvJOsO=51n!WR-=p#vasE#! zGEWZ0|Aj8BIwdO`{hTaj2KbX#e~nN<0{8ICJwHFwM760NG<`)?g+NzjxwkK=R9Wqx z2y-UWE@QTs;^jbXqiPWJ(|+*rJTc^MUV0NN&wj=K1+KBOvOrxw zcg=CGNnF~qK|D(QU{rh3m=pzwq9t1(W;tJ%(16ge)|b}DW=F06qrSFs*%&)sZ>Q4P;#1}aEkl{{IyZRs@LG;|Opot&o-=)xN4a(!a) zqdfI~AIkfEpMeSzSnbbZd6#~MXFTsgp|`In1iG*Wx*RzVKIfKsGHY4(v4IK_ShY~b zmIANy-J?5FXz33MfiA3pE_3vqzVNGQZD^o}oFPNibtJI*qO6B};Ss;xwFRwDv{MLl zVGVSPrHNA>!K{sGcsU0`1qtjcX5{7kmj7 zB-9#o{p^d1I_DTItPrXY=)zsba+TiS2r=KKJl)(`j!;1YYu;Hb6@sdXfd_)=`WvPY z=)zsbGIiImo49q#n+9*MMyMd6^f8t#3x^ASp%87eZJ-e7!d=F)W=;1QqIQ&per#?` zs34*AN|xJO7mIdu-&pvlr9z+!cNxn*vFTRP;di#Nt7RKP1qtkx%ajMn?6H z3V|-%mn?I4C9{RNzSPLmyFHE@=h}97E}pzZA;C^U3wmg-KzV^9`2(5 zU9pnCFy_pvMFZ3GanFsqmbuMW;B0B+lze=t$6#%6Szk%Gp1LBYHT-LwtXYjvK?3Iw z^0c(=SH*v=3X${eScO1W?~}h+Le32B>?yNv?;mkmG(F@-tu{szDoEfAQ0@|nJ}aib zDNen9M<@ik_OAWKzSUo=orpBAaku$NvAudQ?Z^%xRFJ@VsoeGZ=ZmP;%85!33!~f3 z9r@sj$Fyx7eMPmU3D?}mCRlZd|p3&ft);7ib9((6M61nznG;(PfLIsIC z|K#JDfwQ$@>&#E}bdg2x(CfA_rAi!aN_XS~=hx7Z`}>Q?sgAtKoe|ocAAX`oCwFf1 zV39U2*s=e{jz7H*kurjk^)^7RMfcx|9^5(J`Ut7dF zbu_>EfXjzP<>I<=qG2yW1qp07GBPpqtf+OQlCimAcZERLb^d|<54r(zp@H}9@fH;bP2*TYy4sS@Z4m-C9-wMWLLx|EPafq&}orNsu)kHqE5 zDQtLd0-l2=-@I)5^NmSESS&&ek&{MV)>6iXBeKg|Zd*r(Yp zG$UT0LdS{Up>1eH`)3M)E<7(lMp#CtiSQN8sOh_J%1Hu9EPN%ev2&Als;RjyBly!q zQK(oW>hduk;r~JxRtJ*5Ih!rU52{6*ZWSd|kie*je0Q!rOE}!ssjwycJs(b>1L0>~*0DOLV1{9ugQwk>^w&TqVZ5DMD|H*H8$> z1#iW2SIU?zqT?J}>T6=mHc)UWO3*U<6@A2Fa+ml`zUmwR4 zDoEgbPM$@Vd`iSkyJ5sfH&zIA;d``vH&~i0K6bxu)c>~up@Ia?IAv6=`YloJH5su- znK+*H~88PCw)>3_UPGA<(7H0M5v>?&JF@AWO$$& zswf1yFk>c1&WI=C--q(-Op!;Rf`rAt2#-2lhV86s=Dd7nKM(;SU1?*3HyjCcVa80Z z7TNJetNYF?2e=YBthKo@4r4-#*mNrtq|zKjG3(aQOrgU zeHluHM;0bUf&aVcrW>y{<&BnD(R`yHX8aMULqjNbo1;RY3v+Dp?3x9Cg#YZ~Y3$0?94qu-tp=>B zBm1is&iadYjj5Ha$%hIOScO5JdB4I_|Jw{&52<6If&|uWkZ}ePp<8a2qv!Kd z6#`vYO~7K=cOXh%+%ANsKb&cxf`nSpA=0g!{@Sl3yq0$sSLUe1Gq4 zVWK^o*vO3gWDbbbo0TX;vl@L>2z1phTb9?&)tP6QIeYbWuAoOc=OMpp7D5GyU9~Fn zbz>T^16Fe`S|FsX{&Hg;8l8||A<&iM8_7f6%CcYM%uiKgW|SV1^4=)@qadMz#OYeG zyx`DSR?{I!5@n`G=-)=aH#UYjDFnJQo=yZg%#Jh zPuXDhuv)NCiBk*9>hmgJH2PiiCRC8PdP3v%_7-7ZTa}d8I9Do6U+8(wSmx!c5a@b1 zrW|jyEI&K=Fi;YoXGZAdk`Eb=h6EBSNCYy*PY1owx;82$iAO=9dfhyRQMf=Ug+SN+ zx8-=oxw~4;r{=vnF~vu(8+^hjT`Y>i!=m`hnwzwUv$DoML~iqhmg0HyT+^m5H1E~F zJ6&|&gO81m9m^6bNMICK?z@}es*ic`%_x{BL?O`Sak3=uxZ$ssGSU3aKlgRiuVmz> zdrtxg6(p)G^x>tfpR}`e%=U5Nshd7Iy#TfE?xPUsijOYI_XoSM9WBjgx9NB%ec4S{ zvgCCmRFJsg?85`r7Gx!gnl0+LhlhTpg*(kYT|^(BS{ap}P(fm7 zcW++5r5B4nY|b)VCc5cA<_A-Z(@&*p1iG*ugnX~<>ZmWR9!Xlqmj)_GJf7#px6KS@ z)tZ{4+V)wF`Wm;2WPkUHLZGXLQvD+6l&>DrY^`C9t*AUDy(&lXhn3oB;j>FBPmHWc zDyv^yAH3XXbyicd07z`?Rf@0a-c)nwYCef}o-TR^Ps6Yrj8zD9VMah^W$HQT)0gcv z><;LJ3KH%S#rU&``dWjQ=Cj*B*Iuu5{;F|zGgAn3shNh*>UR3X>nDtYr>hVuNci=1 z=M&G@*3Ne@pWWk?^6DK|o;6xutf~;`!c2-hXEeK%USP*Iqw~>l!j_8dQEjy^J^b}Q zk;jcj4ayKINMPHvSmxF#q5p}$Y6SNPQ3!NlA0ziWA1kgu*!JA$nm1VKOOU{}DQm=g z2kMuezBZPW@l^?e4i?#GZI+QMMk#0LiAt9{Aly_8w!Cg zoPEf%&*}&2W1UJ<@X%~!mVpFTbg@`Q91YgzwhO1bC-x}>y0GGr+|Sw6Umsp3hQj`= zRw^4IffZfkE{NrRy8SebwjZ6M5a`0nO|lA9TQ7al?CR90b5Es06B255m}WVydeHlN z)L~SpLZA!lNy&2o))dhf$I0Cs$6hG4sgS@rO!C<+Zm+K#+LFF@tgaB~!n#dfFws$Wj3QcD`tzvO)XIQ9+9?tmqh!wFJZ9--5vp6PF_u1iO z1bD^}DoCUct;wzFy|vJWVUlQ@US99}?1A-ytZ9h^x*B$_$@9+M7`x+$NlZ>>dc`s} z#$C74@}2Pi6eLpiwB$`5kJhS;i$?nO2j!f4o7LSp{sMC%0%B;0@kgKyopey=%Pj0vJO6&w0#x(vz18{ z9r#ArzI|rQ8n3Q^!2CHzpyeriCBKP1%P$*;$JA6-SsVygsI2(|exMUxF z$-ljgZu6@u1iG%5jpD!lxNGT;%z1nAPG9}|<6(x)bwQ{gfwLN!sXi2}2j1>vgr101 z2y`u*$9V42E}HYh5P6L}w}W;6#c9Uj4KaiY5;(TYy-TqXx>!8k2uqGs2z1%Dt;ruP z+OK_CU0Plvs8JccgzG%R)jph1K>}wVa^>0mX#MQ#$%cD!NrgaH{vtJbxxb&}t`xKP z8TYBY{<*{o<9T)7Q>x(r-v3jqpg+vu}x7SfL;lWEQDo9{;QdvJS ze?@(uYZ)q&R?>Q*J=)&5TGAolEr@y!HqS`m68mJ(#ew4-w{+!ADqRlld5BqaH=c5d zjF%j)qC43-(%Zh94OEaw4Cg#|>QuJO(R^1c;Usk1UygLE+p4k7FQR?d*0~I7X z)`;Uv#AtSYu=zI8F`Dad`~NZeUw)ww=)y>dtO3zJPQOv>wec|VlYt5n6V_JYlhXRK z4ZqD8K=Z$vp62w{=;QN8A<%`95SjD(BJ{>dw~U|TTBFHsa3ND+IbQDk4X<>Rg{X?X=-`tB?{eL89b`YTUDAP1b*p*^8#FtE6AOciL!u z+DReMrMB9coi%-K!U4n2&6Q9=;`6oY{L;oUto=hX`fy}-+s#-2uH6arm163J^EFRRZiSJfzzQC=Bwkic1{JQpA?RPX=3su6Ok zvO=H>M^w4~s((q{|B0Ki=dL=|B7yT@i)GtBKRw}dNh5P}HD#V$p8^db-J zjGxnMDKh{h;_AwX*Zpa++9z|CvAwaI-XV?|XQtFu2z22LN9G3`JL?%<{fE9n}YPHMZe}r@1|HU%C#pwfLL#R@R3x{q`sLZ`~FK70L zokbHrjps>T&5Ap_iIu(;`Lywi*pAy~_O;RJYI@CavgYy@ZbbzNtZpu|ul?fmkd`47 zUcZ4tpsVM?3Via>IgH7ZE9B|GJLB}Dg-cProLyE_kihEZ@_lefW&K)CS!(jAk3yj9 zTg^ybwA~c;dYkz@Vp>+xhi{Ffj@{;1Q9%N0mCJn8x^nvM3YBQWk(-%FpzHV5Fy1!* zKWy(XGaDW-Hd22PP??6;3AUnw1kO0*`jR%G`nPX7J@52bLjqk*;!5#5BL=gB_00X} zb0S0Z`M=|+WWyVWQ9%OdL~>v1CVxF7Uo9F$;T#EcotYZIhZXL|+)J1%2l@^2(`yIT zrY&vXGE|VjI_q-eT;ZW-*J?n2;#YAb(1q(xWX-bZ4A0_b&A|8 zGa;`YGP@;JDD5mzK?3uJa{u{}Z{oz&)?^8;p%Cc8)hTkX{+rL@UTj+$@w~D?1qnQR zM81D~d?wmeXixWdCnyBEaCM4YYhd$EO#ITG!YT#|RFJ?5>hk^L=_`?1yCY>89twdj zWp#>WXZF9s_|=~3G}_8hK|+m}B#AE~rgBFraCNRiC@xr?BA?x=7X9dyc9b1;OT(2e zNML+M#&>7_68*Nfrw7f}9Yz9OxH?77ufFBgt1oIzsadnFs33v$x8=J*W*)uM#x~S; z=4ORJ7p_i`*T~JUTUc{?wAa%>1qrObEzbt*nosW%(}Jv1f)oN>xH?5vxp`)<{~X_l zPS@;ipn?R}-KWtekk`?L1}aFXxrs?V?R5K! zbt%uiJ+&P`(8nP z?YxR~sK5gQ6(lf2Bcq(Z?esZ|E7HjK&lCb(%IXwL*35!>w@%@7__c*lK>{;PaxLe6 zJH5}W2M_k6xIibul`cqN#>`?#t!SrTmKlI#xyk|wbm8h0 zi)Ci@0($5HN7^^kpHM*pGk>z$TiJa2&Mi(f@p_;_pbJ;0$Q{!8^63pn*^;m?qwL2) z0`oiaT}`gV={7PSy^W4i2z24z969%C{8zO8^TF_F7E7ogfl)k}6Yly=%vy547Bt%Jg5TzOhl zwYXAu5DDDrFJm&Lc8j5nVk!KOyF#D~YYfKpo|2rj+dje=UVZ| zy(;bQ;G_`f!fMJEOa6$(;&ezYniW=rP(cD$`O8^Gn+3w_NIZG0v{4DzV}R9^Etadl zXNoR!6DT3$tAPssU)-%A^R@Hmh|AMklJmi*3V|-HS}3!Ye3}SZ-;UlM&M{Cy0(V`= zo}tQ2v21!rYUz@#5a?2?A)b6NS^WOpmHyec&p-tU+&v=eI!8|vn;m=5U~Q8^pewR} z4(pt7Q~MlX?lDQZI#JBKmq_8;7aFJ_fxBSjdeJ81MfdLg=$3PeLZIuw&TO{Z{jQd{ z*L=qb-_TDSJUocnM@1W`Ac4DiGEubKQyOLy9W=$p0Gj%w*_{Vc3(1o>;Wo<*BAaSttaO$w@E=L6kwrx4f z9Di8zx?@&p?seHiTz5((V{)`W0$o_oRz6q5ETZtIq2%P=R;gQyM94qmS^HXRHJdu- zy6{$qAM!jc22+=ZYHeI}VO?HX|7zV1K4j`3a=AWJslST^?x>UJl3iHHpT;E9fbb0p zfiA2sY_Zss>CQ)1=})!$Y**?CBeBujk9}D|<#5C33_?FflS2WK>-hZ?OYZuXlF28xL5a^m#xv^H-xDZ>S zvaKYX!jEe)7i4YR6;A~!NUT{qWkcuZ6|{v*%xlE-sIGaqb)v;DKPv>fimsosA#=_6 z*uquwN#eJwFXsWHDEP)pzIQ`QZS(qc>!8oUyjSZ4&FOZUb?=vY{N05q8@BwLW*uVG zlV{|f%nW13o6%%fXg9m}wSH_XF~w>VX2);U+a9~3^8fog;>45i6i{KF|Nh)|AjKB zvkx+(sDjq>Xq(rA`)Qj`wqXmj==4olx?Tav)wE!3>=>+%FSbjg4d3e}3MAH68gqTD z7m&+EzKkfn-wEH}kxD0Je3cN;)qLQpEXFmDY;hF{t6S^Qg5Mcbr*n6de6CvNa`Vqo z!6Sj^#3C~r4kP1d>9pwBcF7%tgtU#F+UrqWQabIW^;$we7rg&0nK=HaXjOu={vn)w!aX zWc-lD=<12Ws)t=u$-w4(G;G6g+0kw(r2W$Z*2a-bHQam6$`v{qQST^aSC=!iY_Go#2G99*Z2DUs`Sk>Qg0eK%i z0hI+_ku^`7Pgahah>o8rtV$@GM4q7p37R}dRfT02jiLdhotzy@za(6aq8rdzHi{19CO%j|R?QZFQN5L?Vh4FLeKKqcf(j(Ay_(NixXmYT0Su|U6x5>xGBmDh<>dbBUJY+#48rhqz=&wP-lxg?&;I{tw&WpzJfdB zoJ&TlSt3ZYKErvIVPio89XsxZM3E56>$v9bIb?IPJ8Q%7N+Fj0l|&PNK9UgEfJ=H* zseSD6W`{JI5dWRii8A9}Y|n2!DtO)C{|c)>Y&Za~`H@1qn)@NBKmuMv)(ba5ctA)B zt$TJ{LO>V%Ct?{-x{t&YPAAie2c9FSKtg&R=>vi>@tRHb6tpoUpv$Cw6sNFr9_ju? z{D%`<7vPdnNi=$@8iooa;B{l`AG22D1fO{79B(NhpljWQwcO$b*`!X9_1YAE*=)r( z-bT_Rj`?^+Qx5lLPd4$_pM>hK{>6P-oIy@porIQm`impM$>i~enT+TePjSHSP?}#| zhM@w9;@G`hbZ`RE{5gvelXjiJ8=S|{i{o}l2#{|R@QGWCr`wOFjoQr^ zDv;>zwVJ!Pa5CAUwwMtIdsbjYS6}M3U5SSTbVWZ{$tArDBvUF@Fv2@T5tViCPd#p1 z@>vaqRm&!hBMNpEs2l5xgdLnr_HS9m3cQ_^Dfx{gis2g=G5TE|@^KnKJ5VzoDv%f$ zcSg2S2qh{z*Dzw|wHhv?GMJu?RN~<~3ch_hvv-$4*$lFvM=>MTPclcExj{5zMSC79 zkXXCgPnP#+I(avtgb{{K%Nej*NkTxEzR?KocS1Zdh$&)i_^J-Wg-=3gz}n{+Dv*HJ zjjcO-E26@58SUM@m*h!=&sg~3!m3B}0?3A%jjWAH^OF(X)|c+6apIu@iC15a%4|D( zkv?m-Fydy~OYWS&k%0wT`uspVq*w*l$6-?O5C>I78@ySA_lhC~4!OJr0y4xbWtC zyts@iH!}0$HU#g-j}t?Zj__h{N9v4ezwF8GhZDhWJr!9SOp)3px}-+Rje z4u?m{Z#djXvmY07FFKdW^)(vN5uGB=BH)_*-Q#nt4Z9$1?0(IZ>R$BZp#ll}n=($_ z@ss??x>Jm3v%?B&2bjyCHwgh<(jGv+ z{%JU%ZXoT_SC@whB;Z?uJ-e?L;t2sh^j>X82?1TO_rc~xAE)Df9Rg^}eQCc067Vg- zvayHf;OQOR(9f3Jd%&+lKBO=PvmT)*M{O9oo}RUOBW$@_S^F z9O}Q(*!7n5>ov^7-yI}=sJnA9I{V~ur|aw~*&g``dE4}$3wI5W5YPpGT`W(k$9~lF zhB56}If#b}B;b36#rt%>h8jAU(1P|-0=nR@i_P5G?nCqTo6?uYUOZGF0pAiVUq-Y7 z));F+SH9vU1a!e)7ux}UR{|$ zN*;8R7$7;i7U&8McJ*laIA`c1ZD*17mvwY`GWR@e zkS|v(SsSx5cjGCSVyS`I2MGaPaCFaRycQkDEhaJaTT>Sd6-e|AxxyWokxEw1ld(1e zOX_h_+7y~vZYd$4OFC8RRm~oN2H!XoE=Y%t&lk0tKvUD6Z zw_741pew=u0#}qjl{9N5GvY+`TfDDvBrWan7lsNXR;_);^?DUfp2+4f;^^Zqc-Kc? z>L}kMA)u?#=P5UD**LPL#{x#oKcmR^KH^2yyBx+)fyAoazqlv2{K=L(BB40EE#DH3 z=?0x!QUbV|@BQG`H+c~*RvbGQO+Sr?o}WVBmkvRTimr3IL0PR&xZU>q+|NxJt)JmD z#%7A{+{RN6N7D6kiV##F@uX8*6n8g~lopFm`;=jgxZAhM^vA0c5(2v5Gsd!oHoU|a z8bWDw(JurQNW>3OLUYE?AWx53u{H|7JjAv^Vf4~l9SjNRg3lO>#@+f6*W`_--JbWx zP=UniL5fK0Vl2_W$gwui@MavOJb{{C9v~s03qE5ko7J(O_{8C{G-+-yh6*GK2Dd>^ zY-5P^ml3Ruo8|BE@}5DoBp^XTKo@+**vxiq8$K^Rfcihk#ZZC7=tu>0z$Kj6rcP#U zG(K*@r%e56lJ0T|0bTGJWAP=L%6yXIP`a)|1%?VF?(o04>czoiSW*gWheD;1X z>aws-LO_@F+1*yzi;vjiLX9RkQK+f9cKDl!=5xu`(Zlz386WItc+?(S_a6j3Gwc zsu|)sr$NGZTx#M?{oWqNP=SP^R#!COQU|Vmu}Bl<0|I(Ap0*L|oeeJUZK>;0q-=(uUQ zY|4r@jJVNo5Kp?~Lr>X%!BBz3%0VsM1AQym&)nbaN!(sihc{Px(Npb}c}PIlBr_G% z_ij7cwBA1$kr`Wwe{Jhe@9S&wP=Um_cTc$m)(-U{Ngo-prkPdrOya0YypDu`E}s}> zbh4`8;4l6IBi<;l!5w$?qfYk5JX9c&(eQ+O>UyMJSLqca8s~4r73ZAk=NsK61a!@@ zR!01j#r0@HGb1Wp*5SnEj`UYo3mz(v=o0gUTQt)^KCS!-BLdo0;SSyH=;&@X5(2th z*qQ696vz|qiKB^-S&Q+((U!FOYabpekm%C2p8GX-r@Xh%Wkxg~TZMl+^`I3a`br7l z(th)Tvwd+|o_F&EBObO}hNA=%8uGIr4;A>mcNPnrUgmpwiPlj@Xw2M>HRZt4B%R~y9{`pdm;W2IqzXhVr64;4sA`_wB&zQ;uoF4XsDI|%_@(tgP` z&nA4_nxj5SZFs0a0`}oqRV&Re_;gnfI%VuL3<>Chy(re-?bD2ZS`Vf{iH(xp5+vX% z5E~oVzQMv_U+VGwkc5CP*c)UKTdDW)%1a~ZxZ2&4ULPdj+LVIAhWeZM^R97paKb7H z0bQ_H%i?!KPT-m9ljzDV3njf*NWe8V1%=4ra{Re2lFryaMM6Lq?47gfD(h>oQSua8 zVLVyV3x@<8O)4m4A1K9{lc&@4E8Y?Uy5QO*8%?nBY@pT*s&_w7vIYqWINnuIs6t`5 z+=8v@yCVq!U2w%zLE-B*4%0rf==3eaC2OgWfKdc&u8-~FC<>fI!wj4y1a!d|4HoOX zZZjI=oI*2024ko|0>(M8I#{L_$naDuH41Q+5YPpqI#^EfX&>-$VoaYmbmzORH9&mq z@p`k$`{>C#WpptI%QtOmM1wweL#lC;7cZ$cRt%o%pGzx>C!z1`-0gP;?J8K;^pp_C@i3x2%IQzrS9W`dl>Rp#q6#dg^F) zp(2UZ-NgvS4VwIoB5k_eQA9cYQ>eG2OsqLU)}WR-}NdI0=kY5ut3kdsgh-<)-hs(k`Di1rV;J0s?0+L649xe zsH00yvVO-}My$AC!rM7^qy62!U`RmM-M5zLhl(MYr7Eu7xgGAtPny?*D)oPdp#q8D z53~@eb0pzT%NTL4y9GbY%arz>eOp36*R*JBwAJ2v&WNEg)_hco9o;vfT0$fP*Ij)(q_vSF7K5iS;%8(}epX8#`YCxGh6*Is z80(_Gz5U5Kc@!f!xg~FC??iEUsf2*8D+TuGMD#$yw;Rof(GI5k#d+ghSihvgh!5C4n3nf{j35DBea}0h%gaWS9c&!JW^0e?@cRWnT5YurK?M>e z#|%;Kg2>jH5SFRXNRL0`=0|gn&yx_)^>(=_a>xw(hfwMH0Xxb=>8v&BXxY#<=+N|8 zt;!3lw#e>mQtM|pufcNZ^-|}o)Dv*Fr z44d)l+=*{HcR0OZ8!9273(jk>=+Aqa{I`@L)OGVr3>8SgC!g()Dpup$>I|hT`sGRp z=z{YaY*mK+Q}?;+N#i^gVW>a?{({-O&m9fE&!~aa=l3cJ0bOt=gykdKq07hp;^?%F z8!=QM0sn~<6g)J#@WE=B4*0cKLO_>vh9zH9mp7{GOWQad#!!I-{6}SLkW19~7+Y8B z{`rQ4fG*hAR#2$lt;I)maG>rr4TB^|3gatv~V9r`_q0FNTuQ9VB3ngT?i&evGdSHKzU6m`Moe zf}>X!C$r`i9_-VNe)Tbvj8Y*1drs^Q9=MF%HyY8eEz)rL>piFcNFqrFsY zC8KRfz#br5|L~S$LrW9-xQBy;fG#+jz@qey9>u>{wUGQac9K~GNWh*fd!N&Txc-I} zZSt^^5YPo@MOcrl=WTqzz>4-AVJw;bfCTJovyoTl=lH;AYg$mMCn2Egu95-r|7cS0 zr~I6~arRA9N3?hd-G7Dk+dUc0}(T;u0uOMj-@p%Z0{(DBY^~rreixm%g&-Bp274-Wg7_rUDEiH_vdSn z`txuq$ev)RKmx`+vrHlVZy@=ZNc#NAbqN7oFtU#2rW(Ej;h(W|W5Pa31RW$`{5Gp^ z@TC!H=*QDH&#NT_bV=9fQ(PO-$rDL*b$+2F5)cw_q{mi~E%k7%St8x8P$VIsOBy-g z*24q4wo9a(MYbez01|M-%4W9ZF*v*+j*iS+A|ap)Mw_yIEQNXa_?D^kTbE)C6-dCf zV)kF6Sd24elj&UL?GggIV6-XQm2#5JXe&*mmh}RL3MAlKG24-wwHd4Z97A*c???#f zg7K+r$D#RtT;6U39enu(h6*I$$}fv({J0Y@Wz}@1CMfZcfG!x@!lFNq5p2=flg^Cj zAc-868Tu;z@ZNjku#NA)pJ!=&*Ox$9?z;t37bo-#`+J0|_|8#%8?!F2^Oe zov6WCGYJ7*FxE&xp?cnRJ#rVN@(`T4Yb1OP!Www4J=#{26=W zDD2C|>r5SKhNe9a75KeyMS$J&hA@1mt`F51A|;?J@ajR%_5SmEYpd6+jpy4^u(o19 zdV84#4;4tjl?^uLj31Bpbd%9JXUru8bR9{PbJptF^)C1mYva?(*;v8WgL+08@lb(; zahvCydd@btF<-@XoP-xs@To8_I#g3nLO|Ef-PgDcfm!Zvn#8rD?7(?Aqj@N`>)x4% z3M2~OHgk&G2FY$77uTcq9xK3Yv;yeCa|#jyx-M6};rb2OCL3BJu6ex;U4zqVN79*R z-(jdgf@R1?!PBZ`-)qEmwf*O-aK)3+^x=sI5(2uy_O?OqCZ3aZYF$^$9=#vW8#t2A zJAM~K1rl(@OsqhB3^$z}MK69mDg=Do(wRSB z--l+JA4QOWuC+^C5T3Z4yImyi^j;FukH7r5H?>wfhM)q8pPl=ml;V}#pb6qp(F0-u4;9XFf8e78zGK zNI+K~mHy~M)=uuQu~^&b`gCu8@)aZc>gYobDv(e}<&j^{t=z=zVjeH^!+!iLUp=~a zke-BqF5_RGD7w{5dqv(uH7d1CXjjMmRO zNgmi(D;rGH+;>id%wHQA1{O0;&H?9a!frK3tS5 zDX)<287{WrZW+ZtJbF%^xVce)3M61wXa$9t)>C=erbF^i-%d#g=z29e3pM4~a-017 zvo;p{NAojobs;l-uM1FtL`D8gbhux4Zl9uz5wk<5@e?jxmK$3fl@QR?F+Bt6p336V zxATnndNzh%bg2&^qb~?hfyB_2iDG%hjFjS-nkV);Wl9Z8qpL_$El{9xH3ZLXdLfo!I63P`y>Q(9a=UUy^@{d zOugJ0vFXS({_lY+$>SzLfC?o1a4a(a>j3wzr4J*HE64L=ZF7jvr)?4fx-?7^(U&zZ zxs*9#zVOiDas0DOXUL@Yy9KB~B1JC-dBk4j%KgPG=HU)A_#LOVkzrpqN(ktBNaB%( z&Udcs2xmrcVbl3bF<*#hX^j9CNKF4b5_xR6$4x}N7?JyY27hYR1@hIiTtYzCnW1qg z^qnG_@zaqJ&b{J!&Rkva&|5D+1rkq+BhcA?&$)|=c8vJ2F@Zmo{)v2WDU%S;wdm4R zRKr#nUu26pOz*yn=RksOdjfLO|Dp z&yi@CwmNdM6|-jB+b8gW561{$3h4q=ATf1c2-?a0U_p~&w$SzkNxYVWhtRXn6bS)c z$~6%vzE2nAJWf2SPB{s@=b;%whpiz3R3PzlNih0a^owhHCg$b*a5sq;UIYo}oP8w( zbopn7A z0=l@2P((LsqSN`}QPuh-@Zs4d!tcjj1*kw`@Yb=Y@7teT^we&Qm@ZG^18n9CFEx}U z1azIRoq#NKHBt65u?COY&KbPt;d0?n{Vf6&NPPY|8l|G|-2V0YjJSU+f$wdxMkwjE zTS7pWTE`%Cuc;k6McxC5bf=Xm}3>8R7-?i7yjN(VxE76eS<0S-i$>w^Y zA4SW#R~3q^jgD>n`1>n6(E%IMF;pM{-|g(5;lg0PZ>buM9ko+NdMQ0nKudxwaETb7sCr$C*Uz`4ot}P^5YV-x)&|vC zkCi2y7Dx2lk&e8>VM|)GtvwGFNJwY4vpQ(-+27d?9%mH^0bRQX+9LI;K?hD=5u*)< zmnrjM20f@YvM_$#V z^`<&JR3HJPVb~hW13g}IxCWh|r70nxOP1(}{Nu9av%JOKvg;zd^1ON%YV%B+hYBQM zGz>ecWD|aDKqq>fs7VOu+Pbn2x|m!k-?d7NPh3@E$p4I2qvO=O@KAvSjD}$qB;73d z&&3^Sc7uw9fUaL>UC>znV{+}Bt*nj2Z>GFuy&9dctOE}fNWf?qHv17`$CqYxqI$P~ zV@N>P_1CUwU5BUgzdo&JZOqTN;(hjNP`#8E3>8Sg*cKM$&2~&$wsfZVYo1F8=z8QL32^%4TQoTCuBb<~jPmWtV7_P2ND zUCNB8Q}?|XDv*HDFl_fgLq9$$%8=?0sgV%SHPDDhHm}S{sa`B=qhd}U-tKb`+K|5i zLj@8r8iwtV)_3IB#R&_%AnAVB()#AM;tR54IjzpU<** zylu_m!Ri}OQ&!(#7prf;>KG8!zrtl*Sgjpat$=*|r}h=Ap+LT~`Zyn2>*Kfu>rkCg zHF|o!j#xpGO#i1ErJsuh5&o$fc~jGnSh0GLCav`#hxXE>@fVC}`RR@nDv+2JX+Zp0 zbw}sc>W(^PErJEB)~v^>HM2~&WE89X9K$Lgv*txs`(UXeXkBayhdy104UN54rj>i&J4e?-)BoZv9)2W%c*|^f0RwYjL(-fC?m7 z6%;a;RabFst**jqxX}z&!_Ao0aBG`nK{9s*af!nWFsrXdJXR0qj(5?=tezX;M-Acp zb{epwVzqv$BCGX#k=6QT)q2VHJE`2%;re(}wH5g=W;#bz_3%z}8)EZ%3U~CD*b7&E z@I@#-6if}*+KaiPNdT+9Zo{gtv+C*O$S^C;XM9(zKS-4*uQum8{1RvGvM+8G_7(P| z>*Wr#{mDo2{7r?jt9FKXP?sC>$0zb-sj&vQYmXc9;8D@CQL5s#vYEb4c$8>Eea6~T zs6gT~Ci1IU^JV*0#iNoP8Y^_Z9ZcKkzY(ne-Y)MvZG$ZCwGRGKyI%fAf4yw_P#sKe zte5|tyi69TCDw888b3l9<{D1>uDl{Z7o=y-S}&h(uvK<8RXh(y*(vn2s=9Fa zX@%T#v|N^ZMGLzxs*n%+d`NcXhbF$?Zh_ov;$E4@T5&W{>3NUf$LTbBXFl;7wLl(R zzFT%8Tk6^!8z?{jqE==%S)6;-Rl6hK7~PwevRuVMs|u^0SGmgCAJWD#?DORry=CL? zXyX?v8tWTw*viiPh#5%>>*mSFKAR?}wVOjtR~J^vUKhC+-O<52*ypb6?A*_M*1-c` z2G>U<*}FTbi)Y?`abdl^Qwps<8i-9x3#(oyjXXXVe1Uz4RzQpNXoo|i9jdnmKf z6lXbu-NS^9FB7O$Ris3Lgj=UQ@?{#^Wn(hLIm^X;n#owJadi83MSed@muIc4bYEGj zgdbigllM7jCCl+@hb!(clW*UlJa)xTY+Eb=3oDv{K*iR@a$5( z56eh-k!7Sjarj)l)0Rv9UTqe~2G!mw^7GF9>8&@GyzipIs?r57>er0*yWG(y3%zH%Z<+QE z1@ti>kFLy@Mcw|!{;8MTtP>9Qv!k1=EO@qFCtt>P>P%%jby(aA@n!pbIJVD+MW>MK zEaH13i}+^0kA^hr{w@%W)z%k2T#G03_xhkIo-TM~aU7}HF%12<;)pNZnMyu4x+4yW zGc4b7lj*Itk;0KTwPewzU^3&F8roQ)hmWd-5QpO$sBpC*PAd#24{|I}!aT9=()bm# zsDA%EA@`FOd3QU69Nn&q4mRoHwMpa1a0^uwTCI)YH?ce{d!nd^O11DRwm{ICI*wSc zdCILDXNJ!WA4NLZU+4H0rno6?45@az%;kO*>zFM58BAZ<+!t!bEWo)(hLQ<`%eWoA zT2Sx0`^lFK}=m&aF#`%*_p2o4x;LRx2G4P*bF@h``_GsDo=d>nfZ58=}+GO zyKb=G)0e)E(V++5br5IINf$N~pUP(9my``4HV5mtCqLB18E>-w-`VrCNsjbNqboII z*@sN__9E$57H~aNy5QMAoQU$qCETxSP5dF*ku3gq9Y^PBU)uJ%6I~flwqo+=nv4u#D)%xRu}i$3QK zA@BXGWeaEBVRtZcT`G-hRK^Y!ib6S`NP15XLZMGMY_)v`(U?3QDXnnF@R?>uwK0vV z{kVl*1$-r=L*t0*nMp`_j0;xrk0nJv!cgg?K3Fkp8rfMr0`X(TnN*9DsnofjgRuWW z7&=;?PgE_s%f-y9SF7{Le7Rri=MJTLM7ZfKcQaCFNA;#Ag3dVeP-tHD7g8_b&1V-RYr^naitH79qA&AHRxvMP;zQ7Zgp+>;YF1D3~2q#dTQjqK3tz2 zqi7Fz6M1Tq8Xessf`}D>ns+*5<1NvxpAFe;HmhDqR{mQFb5m?6&3QYm-f8$};l=p4 zR@dI@ez;=etk%!Q6FAIPHpsH}|Ep{Hed9Fhk*6lRJ?MxqZ)IkyYngI?Y|}ow^|Oqv z(6F@^LjGNq`FnU0Ee^ROqfb`|qdjt3UBlwM@SD7Ot)J(qdgB{~^9UzXlX305+5On{ zJd;)q@a5JYte0PYTF~mMc|I1Kuq?N8*f}L_7?0Pw7LuKfz1`C*$1@^zZ6-~rpTV6} z8A~7mT_;x*kiR-x%Vx!lVZ@Oo=~T-wi0dFz6`bqyTHDaxH5@N`o8S7`-gP9F5*8&H z)bZXV?#BCT1S*iwTK(r}&(9XysOy$VFNH^Ob?>Vr1a!fpWn-M}%{ebtNVCn4EZ<3$j z7;*Q(aBAGcK|Uo^Tk@2^C!^Dvz*eI3GjTPeH{XxW8h%;6YK@~<#g*j!QxSHh%b-@* zu=BR~XJ6me&u{(h8S(wBCS7=>f^)s_)oC`niaZ<1^yg(}LrckIr zB2MK&EB*eXNZceBgq4|Ji2f^<2OE4BbX`Yppp>Y$=XG=#qs#*}Ozr!I#|2PK-U%5KX-P8wK$qEKH61y{n1dkHz0*Z9x-nHuB!)iv0aH->*qr!b@Asl zX7XdpoZMrG*vq*2-a@FktS1<6nM0uhiTn4*wbD-~>oH<1=PCp|uoQ&AWC;OX?%&4A zgM(e&i${wD|I$~;vDOmK8YWYyK;r%CDXncxD-ntG_8~&T*B-*O@>voBy5Lo35nIn< zg@Dw~!kFY)lKTM(>yde_ZS1uZ$5H0)bA|JZDYOoOM5v=a+igT*$$M?mcZs>+Ix~&J z?}BYei9Q=Q%FiEk5xPE1rBHzc9Oiz{GGHFHBm@7-q;89}5mX?-va#3yFKa&g zzskxZ72`AMqej9(0=kr(YwBlS|6dyi23L}(mJGVQYj*?{NU&V)_5bCe-@SW3S$98! znk+cOK?1stwI%iE$p6}~{b(c{y_`mGZF|Sfjh38VZZvq|v|dTMjCam~CJpUwP^e&3=RTbcBO?>GWj3*Bn$_kLk#bKK}o;5t^zZ zkTvP_nL(4J4M-eZ@v#06%x8IgLZ#( zfrAPp&XzUS$1nb08{=P|AiZ{FP}#e45(2uUS68+7JfYLaS+s3?J9KW~a(Rm3pA6%M zR(bM(razxqhH?3SS8vL+C0gkFIGJkB zj*$@1#j}#J= zVNXdCUF+Cc%r5q?0*Qs=*UH}{{Gr*XXv1w`o^BNVvV1JsR{2UkWm{_N_paxrUJ zCCgeiZf1)-D0lWh=dtSLBVo_n2)c30Qi%cyws(>Imj&wJqj$nmtx0rLQksN-t`M`f zr0U3@J&|l5WWS4o;k+0c{>o2sRNnLN$g7rQ{(p{;&9_^f5|(IBrNvVQiE_e-DOi|`Gp>}3GRW|M+xw?=j4nH7okN@O~ zVy;G2Au2UyoL*o8vc2?1TwJ9yx$4n3pmN6WWglpGaXX(0dG=?l+^Rh$}YMCX?dq4P@)BB(%u zts#*A_VDJ;)uoYJ{pgON^CSdxxfL6e@h`*wIS&h&5zQIuO%K)OBd9>)v(Squ&JO&C zSTfRzhPCsc1;IFXGpXBqW8_{Yo!77sBE#gPx#;Cg+#lP zj->O;|E+&4tLZ^y4+c`#BSjJdx}-<7;j}j`aPCGo^{zzTv%`o z**{JW`>bl!i=^p_^9*YJ2GP2GCe-KGdWiywq|akWW4=Qx&E8S9?o?5$7hOL3FUiaV zoQ)9Js!zZ{*MEq?>w;+Nz;>)6!g|T<2b}S+zc7Pz%j)nCp?o=>CcfV+Oc=8mxn#{F zKP}d@&ahNmm`mckN$cmr<}A|I{Jh-$vN*${@H&>>@i`!9J}p5|fy77SY_j*w`Bs{Z zAWu)DSziP}FMYX$fUbnL*<``T3;z(kHqWLVEmDOWv$N2hj(NnQYfP(h_49o4R&hb= z=NpsfkyrdGx#CPUc2vjAX3<9tdBUi{xdJ@=AjxbL zoPnA-rhvpLysQ87{z%Hmq|3(skoT_&MZc2@$gvuuA_+$ZDXRz^~HqLlwQp>I3#B;C@ zf(j(0Z9LkYNjoWhkPF#{5(2vJ+82`L?VJz(Igi)ZGHFamaeY%+7X%eZ#5fcZwV>1e z{t(|LW>ON=BEQi+OLDgGsQl^*i0dotzBWaloq6@{3_5Q293sC_iJ$_B&0q7$+@Blj z^Od_ZLiyoJ(pY1au|+RY3ABC%WH`>&A!2BF*i^9_KNGGL%_4fPR7;*byI-R53h1`$(DN!IX=uKl~mxuq55YPpWkR4T326b&zAr)cA5mX>?ETe$PcjvlSYa6pRPTtL+&id`h zIlny;0=lGUK2<-B>YcGCFLv5tt+M$f;Lyqgy~0PKh|UX0^94aRnFR*l%3DBgT&R*& zJQH&p9_*V&w@tPsOD$|LR7$olAhvtg$qa4{L-3neB>93gI>W-8jJw@K(gq~#Zs(C< z+eXVK3W&9l$ZAJTV*OvbNvEHY^^b(CgI$ zNyZT`ylZGS*{KrGo%~RQ43%@qNq1{5XiOS{w1UFlJ5uNq+y3PB5pP`kJ(DD96mW#q zl~_GHi#(cH=QvPdJyM7%Gr}ZL=Qo_Y^vm_9xpO z4Z!e77V77cwTYJ8)8y3ub5!waskBoQPYS1dVtBleSk#nDo~LVZO$}l-sH>i-w6ULz zL?>bi0bSB-l^T;umpMC<4>x4^YVTyy5ZS;57;Htcvy#cCp@%px_gZwVeKJ|Mav}FS zU^8o@yLT#mxYvoq%)l5bkhl|iT}U(Ad* zASjJ4J8w-2+F42n=(>8Et-Z8+%*|G$wR9)_|fJmq}K^UbVq&C`zUNEA|iwydGrdHC%iLaAM?y&C2g8PK3awEx#OlS1B>sLmk z|IDDh?6rtO;UM-j&BPJWMchtGgq|1&~2r7{1k~Enp_C)CB2Qm6{ z#qkU}CM$-tOI(kj0txlJ2r|3c24(gUSE_ZVX3~611)>p|Bq5;dS@+50^)()Gv&EHa z{TrEdt#hsX;PNKU$2fun*!ZE-T|42IgCoe$G;idZs)Dn2gcI`{F39bPG9&CyXHw3Q z$h(HBAgDmXCO(4P-#Qq58YdC~fthr$yDzc1=`SIm3mzeh94O7Chn=3te{Ua(paO|2 zk0Z#~8J=jUt{CxqBrTIJDE%ZSW)Ttsx};}b`jpjB)Gv|y1a6a@IXtHWAHvDvZvJS| zT`@YL>!D0)Q*BJveB8`I1rl$v!^w+PJo4WoMkhpk&!k&pJml_I*Ou4ei=_)&PxK0igNC<5sNQzw`y0%u_ zuh!6%NvktY$qyh)2?1U3oLDU9uT1*&@Y?$0xi9OX0*P-e;iNcW465lPt~=*4!r`Qv zTnMf3H zr8B}NlZ_kwknRR?jpblA>%C@O<<{Pfln~H$FKRN$shosmN;&t0$vX9#%MQYa}TgAAx3t^~7_QMiF&Of8>5ZT)}#OD}!=L1JRhyRRk)KPz#PE zI2zXHIr@rjO9<%trZa`~T{9WU8^suwp;yyryR#S2 zVuMcvuKjN^n?`o|MxZQL$Nv)tFt;U*zTa{j%|HB(zz6|IThLROJ&SUTN#eII&0t%*Pd5_Yju$=SmZsLL*~jdlr)NZx@yj(;p6 zpi6q@-}a``l#6Zgh>l7EjFUKkXOLTNA*kTJ+y9A~FgcP+h0#iQgr<@tLI@H?hvSLd zVgefJ?#7O)3ztSeZn%mJzIT)m&;{d*Se0YFG#VQ88J*p$AV38YhS98t;~I)4w{vA} zv^b_wm40uLLxz-quAMg1$;9QM=<_;pr=FizDm}bJ6FVv?3RkYqB*V6jM1jE`n3^P! zkU3*fdo7F)4NN5b_Q9xnO+Q8$vh|y9x76_m6D0vEkeHdANHX6Bq6LoPuEs^3Qfckq z2DtB*77|i7i>Sr>qg&JaW78WmiB}1GFWr%`N(0Gc@FrqI2GJ@H=mw*(T)=dry*DlJ`Zjz6w`NT33Vpx|^e z#}cE6He!6q7o$`f^SCR1q2E@31a!e8Wc$^Ar%>~OX1K`VIe`i!M)pV}%e6ewmpy}7 z8@caOX!_fpczoe22?1TwGe2#eO3OHNTvvKqa^~;|wVr2^4#)-VDe+-#+#kqdqfB-1 z?K?jRR3Pz!&1#?9+7mq;B_37NfK=+x+Z?Ypx*{Q<>)n7X@ThLY7HqdMdqmq9-06d73~45}Ph%5zpFQ zXuP}F#__SK)OVv9estr!gn%yTng70#N+(Adc1#3OKL!bf)`LDU8*Euyb>Zy1KXBni?aSseJe_@M+fUZ3WIi%&jE;{qbpAkp; zq|vYd1FULPO`rma;&nM>lDQ6YbqHX@YW7c!XR6}nqKgD7koemrmqZR%LKb(#Yqd2d zjTSfQ;98w^5(2t%Epo|g?Jg)neIz5+1gF#8R&8;Ub|$%%HlK{DddUr`9)m|+m`8}w zFD`k*XlxicpUfG5jYB=e^Ki0Hr+=HM;Lh@S1S*i&JZ>J@rrQ>s{4|OY!H-!T>~jiO zzW<8I(b9PrQMqRtzRkxw~TlaX)aHn-m=Qf7&=@kU=ly zK0rF}{3UHb!YY3OS-9;2N6Z6R8>3F8)8d^skcZzo2?1U3J}D?z?@One=nD$Tj*{FD zNaWp{PvU<+;Fdd&Wo-oIrPDLk3i!^K1PK9M@abW(Y6CK9(z-nKd%Gst?pHuO|KhpO z+FV1PpobRivjRyu0^{W*eoQtw~&Y%kxzm@FXj9*#<4bZ>sSxj z>LAh?+Dk$}7kqlyZjSIwT7F?B(!ZxFIdgbUaq9|5guNcOuj6>uMkl9C8n?TI6q)M8S5^%vjclF8ygmtT`>@ z-be`OD*HN?__^DWA!WL3Zpl4cMmN8-p{kK87%GrpJI2U=d&%T0J?JCT9(2woHwgh< zedEWFRog8{2a{f`4ckx|HJM{Uy9JHFP=N&7`9}WR6X%fbLAynDqgmV1B?NTsm^6yi zXBw0Jy$7;3GFOkLX478^-#V?rcFvQC&b1%%d%wmb-R4-*&gF!>LN64ZITub&2Pl)t z^9L~^|6w4_`|(g%_-HwX3M6Jck0-S!8s)w!-i#QXKAMjB_(`~`Q79px%g#BH^o~>~ zKQ8oUgjZe=jeXfH+_%bMNA;fqiHVyNN&1pk@?U>BG9saQ3=N6-E%349B?NShZyQbC zS80>ud3uaMb;0!5;*Y|RkscT-kQjD!CaD?sL!Mb6u3*vgfwZKb64kz=At9g(uB);Y ztf&y06#q?l-|Z`c3M8b_>Vwk8Q|q=06yM!1A)rgTUOTWhlo}Yl7hY{%hoAxp7#+`Y z6)zo06ROpy{{9UtSH*u(@Nm@{9xaQ;-7$=!0ot_M?11E`AR+w?{%{;YE%tPwx7$h2 z9J=6DXCp{$AG&3?F7?+_mt0*)z+W006}2Bu3-+tgb3LVZ5W3*g!&du#c+&@qwCIlu zL6WBg67ZL%ps@R>A2rYIK;2%t`jRKkhwda%HtO#GU9bRf7)T; zN8zi+CJYrw6snIW%_bM*<~Cwo%YM#*w8inZP}@dIK-aY9D54NpCf{$dfD!E##?z3n zQ^GHwDhw4!toj{6e6*A0dDp}$d>sJg2*%`h()_dEZ4eb|m{BJR~*&h~1GTJSEy@a0`n5eOjBM&YwlWhZ)mC@Kx zUpVsiG;Qym%MsXxpA0Mx{d|AW+9*@;%W?@Tn5f*ENS=S&E}ttJ!OCdba56-1t)x%Z zvsk9+>4jbR$-r`R+?@ig;!aSPXDJd^Fp+jNg=qIHm3`;+V`W5J`@`HH*J$4N2^@i4 z_{qQ`%H>UktLMw<(M~oJRxmMX=^T>StXy_m+m@BFYJC8Vx4%sT*XnZwcHt)jd#_y= z1Q|mvP@jyqYOG)a@9JUmKBhr%(yEFc`?{YaunV8fVo@XZhC54V7g#4eZOuQM_?Deo2-_oLg7#Am2~stg%VaUG2&Y)DbMzk%@aqnGI}}$ z!+q`T)VF0CM_?Den{0OQL>Oq#UqjOu&5*Ey36Gs~iK|V9JUYXQmGS*XDBQnQNG;}$ z|Cl2PF-C>EpSl zIRd+~IxZkR^=xJ7wz6-jPx~0SzBz?{xbR+$6-?mk#`ZJZiUIFllW6MRb`mDAtJ|S@ z#BrRFd}oz4D)M8hZ9NLaxHzW?kFwv7V!Ti$eUiU&tvSHGv}s%15#V|tmfHRbm#~5fT#wm^Y)~W^wf3OL`X_P(cEPhWVvwG$sh_4~26Edp1M)XU z(E9r`B&=Wpw?{TxJD=6|chl&n%tai5U4c8}NO9OQ&4si~R)&WV3LDcGQqA`j5>_yQ z`xW*ySQHFr0+-Sc@7HhycFnmJLIy=-X|{Y-GEP0C4iNFFE@T%Ulkiv#kKuGTIg$Iz zF3OJ@t!2cqSUU(DP!B8&&q-Lp1dFgkl-N73{>9!&HXI7YhyT(WzprovcCB@DB<356 zWXnPMtc(HoM5r974NaHaldysb7Ac72{TD-MiMB2DY5$9cgg)g6?8<*} ztc?761EG3(T{wC5y@VA^u=qv9lf^=6@h=vV;MyN1cdH8*m;dGn>|$}4$Q2f$Y5%_n zP3f&gc)X$`j2o1$#CrMf9T|^(@%WlWn%XxQ>g5?i%SPD}Rxp9b!7S58hBN%yS|6@_ zTg?&Jg~vo}e~GsXgggA9*NZlBqa{q>aWIQ0cg`I~wtP&hz4AB$yYTaotu#FGg8J^4 zX@K)q?#YP>JPu~L=uG`UcW?>y+p(D=unX5?7Cnjh!O@`y=-P){B&=Wpj~`hM>52e2 zFlj5T4awsO?Bd&p%SeCd-C`GQ6kZ@<1rz*Ow0)Ex3~jxWK7Fuy3KR0CSs!E_*hc% z&QdPktK_>|QQ`>i4%N^XW_LLPyKqZm5v>=Gg7Im0>8-byxfX?qDIu=JYi5M(zq){x zF}cGC$QNp9-hoPvz%JZlu-$D#$AD?xeQLh^B-b-w;;$3g{@#M8U|td_26j6ehDj>;LC7K z7!CPxpJlmB& zIXwYx94)5@c4{Q7U;O7QsA$U3}fW=IaKINoT3wsxuN+FoA0fi&?`m zj5S|`~Co=bZyVFeSo=BrfqdrGkL!6(|j z@-0VT*Pp>6sW^40w4mt?Rz~mnDG<>16!CDj<95X3o%VQ-IEzy>H5nR}X;JZ8EVt_( z6L_S?_IUMAhJvggMC`kRBd`na%x3EbD-vN~A0yiH<0WnfHYV`6i^XESl?ZyLev`nB z+7kXQ?7};m*=ojyc*wCgrYpO3;&v`$0*};KG~Mm-@V8+dI%9+lM_?D;ldMviddEUK z7*o}svD^-9OyH3ktGj<t*}f??=P2HAXZ?XF9ik7ZZ4-#`g8i zj)t)|ZRqrz7>>X$r*+BXTyAe6^U)GkOZJcmc%|z^jcn#iSiuAysj+#VK{H`l=Lu{S zzL+DhtBGF(>D<;v7_)pUD`W4-Ft}DeoBEwwDPaW@_({a}+*yV|*C+Go*qU`5fn8Oz z14zTNi9!?4BdiS9t^u&(zy|6TStwxz6Sy_2R1uea!ODCWoigwsM_^ZewL3Xfvq<<7 zcb=7TXq`JGoj5_K{yZ&V1rxY6vooWe$H3&g>-72cN{+xTK03_jc|!pG-e7t%R9)ywM#tz$c!x6Hjg5CSvza@Ao!`w*B~F>0 zxV_Gpz&o>9#wnWw*nIKH?XyRZ2`*Qo!QV8ngJc zELtqt$l}NvusE_fiVutT`osuaW4giWFI8N8A55_LvSiVJack$^HG_k%yTeMYBOHNU zI64s92XMv&nn}IEUOX&e1rt`ydXPn*9mVi>%8uW)#ht-=c0cIty@4aJYs>MTBv3nC zG@h%(L+;^k0kU~NXm@3ygq32s578c#Djv+zg-bvpE90_*h7~!v{gJLsw9>oWMm%!bF(UAX3_Dm1uFG5i7%P ziUcbC&QSPm2uENS%kn^avFs5K{$-CSxz`g$bTNgZ;8O0MkH!&J z3~dK;S$mGaE*yJ{wU3saVESug81uVU!fgWAUA}$9-|qsw>vja~hqooHU;?)rw!huE zH}ng7i}6?B*b6&Mv(fZREZt^pMnW|)!9AQ7omY(TWGj+ zGe=<8Gr^9W{V&tTA+w?IcUEgKIiD(F1rz-JI6Pt$)LqjAN+d^)z^>IB9Lc={viRVy zQWN*&j)B!pngCs4AYla)IQ|)XOI)-?SAS z&Jox(dFv=rd*PHg=8>{zJCekMvOBZ07~`>>_0%WUM8c0pHZ-c!JP9k9z#{|p=H(Ot zFl!_&?y-;~uxrV(5E8MehuAD!Il)uN&c41^k&vV`gYw~ zj=-)%6_bdykG1&0Ovx^Pj?JDsC2gT@I|?PNU;>W}*gngyzA*dnLAtcTUXH-7%S*?R z5w?TH(7F#<8K2$U;I;cD`XCb|tY89<4A@z+Qa3PfQcd3)ALa<`(yu?3bUU0N9xHpv z%2+XM449pIPA9K9Dq#f^ID#FU%lP09!~Gu8mNi>A0=xJ~h1U*@h2Z%g=>W5BTns}@ zbc%8y)Al5a@qd+bMI$!3!CkGlwA<^I9D!XpN+R2nY8?QZbjsunX5|mTCNF2n<@jj24llT;0XQ zlC1%x!Q~wBM_nZjeWNkc!F~U1nm#;>Bd`m%O_l1X5D7OPkD?P#q;hQ#6Z%=<#Jgab z=y#N|GCpr+QB|Mzr!^bra0GVYK89rmx*G!-OY6}b2;uq?OyIMNY=q2C#qVueL!z~U zI0C!)UNlZG0c!FxNzKqPT%U*u{v70g-@TdJrfJZK$9F5_Gj1@0?f&_TIL z9D!Z9rLnjlD<{FDb&siQjt|!cF|l-y3#rrMjOc5r%gS&)8VDt?&e6!yVH|;7xIHR6 z;)7vx$#L3aqPc_>OeB3CPxk6R5c}6rGJusYnhwMJ@2Af{>T?8keJq(k26p%^M%+@y z)Xjqeq2sH2w6b@RdQ#hQ#GGX~X~#00?4CP@==$CguNF6ySiTW5=f6BAOYQvN-H8{} z!{e_SE0|!}O2{Ub$E5MUJSG{|KJX^}7Y$mc&3zYk;n9cEmrQ`^@mi4Ar586Y!34`t zLN2l_W10W5jD5K00#iFRf^+^Z9D!YU6s4RVaDo!2#_&NkpBpV6<@vR1oN4f{zm(8?<2Mtzt#waS(puyYcV?|x@YSFNv~Bk< zE6IN&OYFjG>*WoJEkLu#fnSf z;+qN)b;TEAgTB#^b*G6~!9>DoC(^d@dGWf9a(>YMwikSf*M^c0E!CL7uEWQM5j)>w zqF!4iYW9}S!C)9&McvNq5b$ru^%$4O-h`z6tZTGbb3LF~Zw zwExdlGLGN9d67FAm8Vi)nc4jRiRInyQ6yAd-%MQ|H00uiV?tlgliXvuw$A>`wN>&t z3Zjaa(U&_Gas+naXyfdS{&pP99Vk%S7(@EG&orWasf&8c#V!)d21d+Sp0GJAPnei8 znNXIOto&bIvQt~5pw8e$^i|LI1S^=pJs*31u=Vq$@3vF7+sRx^a$Lu7d~%krD0>>z zzAT}ynuk)XU;@`SwoA`u3Ve*aM0dvca0GVs-#LOD)j1;`nWMBQ?@zw4cvB6XJgX1I z3MO!UV-X#EJz>e4x^UaF9!FqT;E^FDDeRzFvQX*U=XG<1o!9ii=;>yH6-?mT!&WVu zj(`cr+QEVY6*4BU3&#;>?}L%UVRJ8I*nTZT$;tX(>~T!6+^PS?S!XLhr|seHI8zu9 zujXQsV;7EY&ejbUI>YmlCNR9o40?UU5CU)WMAK&-B<)#tz9YP}<;PtDH@T~9}!Lt#V*t@Efg!5=+%ED8TzPDEZ?r2agSQ& z1#@yLsYB8Zj=-+IhsKi4c2xZAr<|j&z3Bt1ugY|w#eRwvObjX=Plo&{5o==281cx( z4|J*usol%n9D!YzmV1z?3oFF6R!Ssj{gO%G5R*oIO>fZD#gmD>?shTqc~9v_@g(x; z!hW%^Zx1Q)whLKixLzDKSs_~ad&33QW|~=bnPLSKq}gb)qTe=g%8Jg6cy`$rdXC7V zuN$4GSiwYH;zM=~lEpz2lvDAQ6DGs^qFhR%k8=ceUEk|P#`HKPCQndK-ir>7;1|;Z z9(RnPxE)xW97K+MULpFkcnSF4uw7x-N5F$K^`QK34%ebE5o&BtzTev*hCfxFwR5A! zL65d?X~6OA9D!Z<-mrex#trrrUT1R|M<`Y>fv*VL7vA3sLM{^;S1oe{cHz6pGW}&w zf?f3rXtVF^AP}kznBcEfcGD?P5xSP1YFNw>*u~e9@?#?*QoV*Q>8k@fB3(&#k2tZ* zpKj8Hdqc>JSZ~oZ$V>{@;YR#MOcHg5Dp3lauNwwQOLo%9$qfK2m@s=clyvMeOq_90 zsaNa1Im3qXO!_3gAxB_W*j{(i-hYVLFrX(ROg;^TBT-hg%_Jk}V(dZY)z=aCT3bpu z4^rGg53=O(Y+-Pk67ikh7GbrK4b6_|0$9NW&Zxv{yUh@oz4R+dyl=`8*mY>H2k8c~ zjq78jj8ViMg4eF4p4%fikR%6crM zFXq*9y$>cnHW^PW-p?1utx|qf=^`H}c`}K*J$%6t*wx|O6!Q4mBGKi6azBcDg~5T| zQFM>}I?A&3l8gV71=wMTKN-)m^_sG5y?j2F;Mg#zU7tojduCItVB+{^U-FdY;XU{- z5AU$%q0sW=a%%c~F-Kq*&IQ9VdX5c;+hG}W+|M*_M23lwl8NL1%flP?FAuMMZ5R~T zuB6i+#&QI9;n5kJhf4^Dku@vmF%y68Z2}W4UoM+9`YqP{%fmbNav1#Ryp6hLjNu6E z!fzIAwB!&Dzb9^?zF{`pdlV-6XL=GP4{z4LJiOmr!eDUT0otmNfAhjF{7%L8o_Co7 zFP4wg>}mgs;tU=*{{x@Rqs51*07WI5vd4EQRxp7xNwAUS&#Ca%Z=W2T#1q(Mml;Ds zPOTKCH5FOC(#sEl-B!EhwKFRyRxrUbsS}6)a;yivodzS$8CX=m`%Q*tOzMY>*{8;|;7yt5~AMF?pH(Q#Lhu2Ff zRxkmfi6n>RSU3KcW4%vg7>u!BPKMk&#u3;xQkqV>vHa)n{^dXK>OBL>o_LdHX~h&P zm|&UI$w!uBz2m+;X(Aa9~%U)Eucz%G`joY=Gc=Ntd!KfknVCJfxZnsj$6q*%d3 zW0P6rC(E%O|1ZaSqV){0OnpP%kKWA@*v0aclcE3RKi@Y$0#4PJiKD?*iWN*eBr{11 zmSes7zZ~mLwb`$_*??O2-^LNxg?m1>3NVDN#O=CAoUZbHA|}o`hZFz*a;!f)Hxs(N zGosGx*K)lmcH#b!#bW&v3E%2zQNd~j#R?`^CUvrlIp? z!u=!5N>Vfn{2I2QzuzvPSiuC#q)z^@9P6$ACT`296#u3Inlut3D0G; z*zZBghwG>-G>usg=e9EvX1v-$vpOb=iV>?@Erqu5NXGh{fcl z>W}A@Im`F0W1-IB3>w*Mh>R6X;Jj;W?DIPkE>F*;n(24cc<%n)k%?sDu9oWBt^8a+ zTdAH94R@L^pmmC`sqwl2CR}_ck`E@0)W2sb5&j0;oC*CJuchZ%a{ytp zV0hUg>S5JJ!U`rPADT#9jO(cPyDPB`&p!?a`NkS*S=X5(unVu_vHiRG5iquL5nb@s zPQnT%+zTg>izT&U&(%tvxK9J8!}0aGbidhjj=(Owj;B&-+RcRKKNnE%dj1ktFk#kf zGEp_ZDDK;)#F{*LFC2`P%%c_46FCCA@H!sreNNAU1KI9$weJ)OE12MSg-v=81qSy9 z(%w-a9D!YU9gpoK?;QtpMm_31cD#fYOyFH;>?~O&%O_)hj|_O>#u3-KlR|siU4hIc#O7KI5(As7hOx42Rp4kYbU&`gw=!SP&<8(*~MG5+<+<_o(dYY!eSj zqiyNIy}A-sFyTGdpNx6Tvafh6J5rL3VxU~@LtRTOIRd+IkIGg|Ud6()g?4mfgt>$j zOl1C@LUNjFsq0p}Wo5XYiUHf*w)E?c!5o2IxJOl~=2#}c&Kr7k-l;AURxrUwHx6NO z?)ENtNOXRfaRhep`;c$VN`|J9bBM=Z6}PJx6MQ`68{d+lB&{>Kd-5X}zZtu5yk{0? zqC*N)4oe^-h3i}dWn2c1TdY!fStY@>^he}w4_yf>n7~&-r7F0V1TU-al69@0t1*FH zI9f2vczZn&x{qi;qYixHq5@+A-%YkFOp^?Y4_A>6IfWd7T{zw^n}K}5qJ?(Urg8ZP zxah{1z_pS^Z(W!ILW!GMo-)O|`#DONDS=a3E=p9B-m)g^bS1xH{P zUdLs%#5D;{6&8~8?)(ZbCitw=E&LO}Ho}x87r8;@1HD6T1gmqJ~>XqHZ&G7fn9h%i%NCoY8cpDKSqB$ z+H-rnFoEBY*;6ed7>*QOppDIUa|Cwb{a!2!xP21r?)OTq?x>qdaaZWTq&EC+Otj+@?*wJz-IIP0dgL*^ zuHBI%unX^?WU)o^Cc@Kmujs93LnW+W0`F*L5#RfHz%&+fK-G2>M_?D;LCLcAB#wvW z-|E7(mk|>7QfCwY_mOJj3c*%9xgYYD~Ib->7@t}RwDfzNQW_4BtD zu&_ft*tNYLM_`vQs}C6;o+?K>m9a9+4SIp+Yc1%uM8_5@n7~mO*n4feC`i7)S>Et` z4aF-M`-dcxhZ8=Ehp$Q!UUgu#{e3jRXD!X2mP;vCFtM~cfead1SH1qUvPw3oED9pp zX_Ix`R&oS(;Z+Crbast_Wr3D*{;*7n6-?9_A4k&7_0-}58&<|I=V(YMwj$bP%QynN z@TvogJbW$&)=oSiU)nmKVg(bf?CerEi>B%~?UZ=>*B(W~hqe*qo_!`qU>9C>P^mhP zjfHU?nvkb#g%>NBm~T3ZOtNjIHq5YMWjsrdfnN33k%uYi9D!YU)q%x_dln1T6=R5> zX#&LxCX$xSB*T5$t0T|$Wo6`A#Dd$qGV(Stjw7%OuR5qy)8@uOpP!4#)wEEG6-+$W z4JT7#JE}upDw!P)pNfT3vtE&3X973^yYPG&`yURK$juZP;C-Y~*#UaZzx|{cM1a{%ITec4%Y8JE{ z8&_&JY9qx8Ci+g!Al)DB5uThK&dTub9RU|d+|`WB-Ng~uh1YJ`o{0~$;K=qhf{D#K ziWN*0?Mx@HbO(vGRZ2Yl`mZCPvQ-mJlduAgz%IOY%d)tJN5PPeJ;j$TR#U8C;&jYh z0@<0ON55gLjQ49JVNaI<8ko72Bd`mv-LjbdccWnSu3_SP^-78rOjKP;B@sVM!~<8A z>=CBUvtV1FpBin)O&oz;xaU);E{=(YUnR}N?<2FhJ`oeqi)RzZk_Y0@{dTMj_lRg{ zPTmPUG#t{HuK#jhrOY_VfOICZC-oeE(TS&z^B0 z9yJs%)?+z3QH{gI?$QNha%wxFu{azF+n5d_j zPZlj7Cf-dP&C0NGj)R`-KZp^_V>tr5@cn0Vug~MbCat$Rb%!U#3MMv0&Lg)SSBb7S zMzS&vxWvJ@g~sZhccVE1yYT&Ief!aP7<6```ojz_iWN*)9!@8>ub&nxXF9Vo_Ku2! z=D+)?GuuUT1a{#X!)oHZczBu_tM(h=L$QL1mN{u;=hKg(m!P!TMI++C1gzEDn?`d4 zcJVc_|I~PR+hn%dsPQC<6-*dSNhSRzYO52+IdZ{y(c~PujB7{Y6l_zvjOS=SC zMi%?$D{glc^Ns~_1a{#kwMtcGod5-Xb=js#95!i*F)a~qkq32~~?9+8l0=TW-EVnTq#}U|t zpY1H`LZ3vqc+Ov_m*_yTf{E*qGfA^DD|LfI%GhUi3pRW1--gsQx914#;>Qfxc8RcL zXg_hmkD;{nga!Y4=ftI>rT&`#`?=)-7YX-|td_iCS&rufiwlD~P^@4A=L=vvOy4EJ z=c}tk_cQG|0=sbk$WB`5rNGWp6=K=iuLLWY!1)5$901F`yl$zkdR6206cgBm`$rZF zsfx|-mI-Q?PTvVuFo82Lu=~MgQtPMtsy#<`pqRie+&`*Rag&n4$#98!-&hsJ3MOzK z3YDs{aT1(4l%rld#DpWT3-^yKd-m}pSatoNy6CGe#R?|){2z65S%%dMMd~znbB@3+ z+&{9jGKNX;=kXPFN_At36-?kfE$pO)aU$$YFH?^x@5vF^h5JVq{d;pF9BlnaU2w&a zVg(a8^9?&aP@4e3Yfh=hMfc$d?85ycTLth+gpWlv>cAWAC{{3mbN;AQ)h80*&#F`E z`se#|1a{&6k-c+vNrczBwd(8z9Vu2YfioYmceUaK$j~WMhelX)1a{&6k-gEg6~#rG zr|MseJ5#J+0_T!qEADav=R6F5g1o2~82GO}G=sh*x_%@Npz`$x9l z$3GD!-Xd!4U0o?wFoE;Av4|&`?4MgFs`q5{;|T1+Jt})TZ<;GVF=FSVW)HW$I^u{X zV^fu!weYff{M^if4f|ioW9nQ`r_9SNaPTjY52q?oprXsHh|`7vP}QiPt=TD}shOgd z3kSYX4>T^*_`a#{;?Yw*7Y*VfWiZZvC<|B%B(`5!m&RU8@EL z`{fbWln8&>>pkS@pG@F|%`jW6V1mE8H5Z#xlTi-P>7kLW+vO~|&yo!q&#KSr_U760 zq|`c^PltY~qwi69%l-7yVL{4X1FIv(^ooNs1VSrYtYG5uz(RS(tGJ^jdMfs;t&}~8 z-6kgp?$*Ipr`ajZf|OkvQ?IY;r3ucmPQ{aw(W<&qp8qge`)nu8Y>VHljD(ogmb`f9bQjuynC}_TWHyi?fn@xo%|-diB@<81k#9Emkn$akW%- zcu=e9+Vu@1zCP|vEid$eM(6u-1a|Ftc2wSUu7|wCtcDR5x7X3~IRXeZ?QA{YKa=w; zdTV^5KB@gW*C$5zbc9gLpX!w3Pvwu+Cp3myuNl#z#U3hX+rY;TZEUfEi4no|$d7_W zrN3-HGQz5QE$x2S4z!b6a%C9Tsg;MP?H%Oy?I%|r+wT*%l|D?d2YI-GE&g6itQq!4 zE^pIS_?iBfm9cllA-ZF$1Dw~b#}U}|!LI=+HQ6MDtXB3w`V=Np<2zR1l;4&6ANcy< zE5b5V?4C?#ju-&DG~KxWfeC!2S!|JCaWr(b8mhfJas+na|HPiPFMQ~neiAJ2*U1(u zn85d+&3**?P>UZ!q0+h?M_?CjH!78|xf^w9XbXRTbmm$VCU6a9=UAqrg*0Ejm?xp;4&oH6-bRDUv_?jH$F~{c3^S|oo<~QZ>1-`whMRR5Q9OSm&79%}e{5e! zSi!{Qg155e(7l553WabB+f6+>ctZW@mpKBvI-RadqDH?F5>_a?ac6zrPgQm-cg6!M zVFeR^YqiMQFdfnSUu3))KNiy^bKPL@nNQqr$Nv`7Y-dezHnqO!1-cvVN?5_fNO&(N z(hEZW80A-uU%!(cUO5r0M;zk_?Bajb!Qxj`>r#IRl^WPKz0-y)c8ayx74}};TCXWF z>3`DZTIv_|xPEQPy4&l-{KVl9QwnEed}J+ zE%QZi)cz%50=t&AY)9PcJrkODSK8oit7mjh@DK#7zUP!dpH8SK8AH61y|g~?zB4kZd*qQABvo|l7u!4!&Rp#XOh^gYQC(2Gh zo2N!lKgF{`bT&Ak5~bLdnmg2%DW5>_zrF|H5EYO`1z63~PZ z!mmCs|hd84E3=4@=1=4aqI*x59GPI-EJq+v-W@UG+)E zt5#y&f(Fuv=vL&4{~&SF1%+ty49md@!-+dLc$6r#L^CgWd{{s{7`Di)5Uk_>(}EU z<68-LKk#+KSDN*3nQ!R&R&EfRzlOVOnBcFjj;R(rd@>d~JWJyU?BefW;M00=-gPWE z{hlIW1rzxHvGHze14ukQ8b+m$;0Ww;?`T4rCU}cPNBQRmP8vX07F8~6epd-AnBcFK z(dp)37daYY{Ioa%yUs1{MB*9+iY-l)7PZ2mBUC)Khv9KrQu*Vqq(j0i(YC#Tq&Z_o z-pgU)w62XM2bXT-wMmMoc2S7%x+XAly#o|%BxAN~u^w*m8TzUHP-y6;ZHpC5 z@MF=jAyqWzi38Z=e33ALUHEy$dWN~xbh?2v^m+0`!U`tpHg7?s%MC=GY~?vPJn=2{ zGI55-{^vOYyYTahjWX{2rP%{VfW!3t5>_ygkYhx~9kCNfuy{Ufmb0rqY=|EY-K7;A zfnE4{#pW#i4Z-H-Fu0u=Bw+;;xTUc*;aXED740BD*Nh{u3qP;e{woJ__!4Ogt~1}M zv4RQQHW^Xf9cE>T@cz|Kj=(P5(%48}wt%}$*a*2gOpO&x@U1pzbT4QUB*3|#LtLxH zF5Dj36Q_p`l*aUhwX1(gtrI#Cn?I4lgk_(&aogH^ok+8!dqTx<<-PX%P8FDj3Y#*gfym6Gktx2Ad8&IRd*9 zP5YC-_p-zTHp;2SZ7ur2vswM2Yrs1-RxrW$aASWCf**H#!O{6^I0CzH+#eR}CDRtJ zmRW#l@op|65GHVs%HD)OIKqzu#?V>+g^a%oyKpojC9}h5*t?`9_#S5aCQ!^HOyKy! z?0vA(9eV821*p-dn7}R^hl%ap8R`uU^}f*b=XPAYB~0K5J1pi|Q$MKVS50$!1abs+ z;doLi)l!yM#_z#-S~zJg7dHwMe6*e!$EHAa=TiD6dI?8h7mnM&;(oL$r7PnngLa2J z3BRBHYOh1eCN>q%gf*1-ceM%PW!h#^kW(;$$Ea+sZ}WLNv*Sc)Fl{48U>AOS zWznX6uF`2v-r!=ffqSpT1RgE3x73Q`)Z5k*zV(zj0=w{AI6FV+ah}SnCP4Y|QtoXV z6L^%#a-|q)Xl0cvEcU+65!i+22G|aW`6uWE*YRxc>s4;n02BDVgq^i)nh1d}T1)qS zsp!N*F~nfzSoO^rgQcpg(PZ?V@oEomI|fvY#jhxK-j)bD z71Kxyt$q|MnBY$j6hDp!yMe!mWNFP2*oDt7vbZ?xEI=dE?(~Ui5AKX2CUD$1m8#v> zC|I>BiJth=o+GdepTT5NxxPk#v1&a{OnXPLf(icgz`%kq`0`Muk6)eQ2<*aVNm+Cl z-4M9%SV7yZ&*sjIVgkqOWd9>C5b8d;PgiHBa|CwbGqLOxwwXU%vwKUYWi;i^zG4DL z-()9?T_-{G(BE`?YaNcjuFbhlM7(-VOtmv)Pn_}fyUu z?(VM-Q85n%Okfv|bI8WjOI;z@&;VT8xTvv$2|fbm;-lkWb?2rqf0c?Ou#1nMXgX^& z+XHC`2Q$~Jv4ROcTfw%(k>E3?4V+blaRle$BI6COb_B~a9UwRTsv1Yb!vxNb!1A#i zbpQhs6VQFRmm{!?kENFdb}+8K8N69sPr?c&aPA3~X(L{On6$2Napwy)Ca~+5{y-9! zy+(AHq`Y&E>puvbD!Rk(*Jct{Fo82-uwAUj2S8UpOISOl1xH{P9x271M%}*f z)yzS{3MO!75B3IW)Dw1HvI4dDaE`z(JnmxSk|E~cyv!Qf?TX{ZSD3)LM_2^qH%4&2 zsR;GjF6IdA!sAEw987NqJ%`&sX3MSII1v*#3yMm$UAqOGzGnkXHk5J%cHwa_i<4Sv z2u2V4!@NIdx$!P0aBdcs!)_k^3?{JQ~m;kOL7f_1$)v|4Bmjh=ny-ajyb^MbJXU28qaY}^eNx@z0v z@4_xT8_oLmN%iHm6+=Pqd1u?QtjvNV-BxSb5B#p)wllL}2m9QCeKz+i*VIfj(##*A z%sM}`t1owD+2!QbCbn3?M7`yi1?y5fYBqQ&MDXcUdEvrQ@N{Wwj=-)nWfwGkcU>O% zdS_kMqF!kY)3lx81B<)YwQaRMvmn|r(dI`_ZOLOrW`Vpl-KNnHZE5kKv6>&G(#B+v z^0xi=)fdgqjci5Hq?IlH-UaNJbl-ljbb_Nw;>*ab|5f9E(ghALZfT1ZOx!KVEO?)P zuhfIlD%FC39`fv#?hxS7h$FCz|5Z7I95jC)Pk`Uq4Q#Q32^aRC{tWxS|BtQee|6A2 zaP@Y6pVcHt|+veBM-A{+GyfqdsmX-8XQ`N`^8f|%AoimbV;8F9IpaA~rxw79ZL zvti;W;rS>fQu@K*Ecw&H0LZ@clv6l@ySj0UJ!Nt#5YqA=as>WQB?HE5t{Zg|9$721 z&Uq#$H62+@WcdAA!U`tv-DFR-1NNFWMN^=w-V2Vvt`j+#1^zYth1KhnGKQ*0vzTeo z;J$I0bm4-VtQWCSxKY@My9z4rjKUejy{ND-sss;qyXa%9gVnfn6I} z3>PK`E4AdggB`u|Dgf5%UXt7o7ReVvQUwS7dXiP|a=GTmKB4uS`cgNoee$z$PQo=8 zr4430aA8p?0>HIhC8uCQbUq`$J-$lN>Y?1hCB_1+wDN`3xz9NQyYxNx$fNt$7mj8r zvmZ`{PV{;8BnbcXOu`B#B0^8eF^?jJv4P63YF|5q<}~z#HB*0c1a<{IE0bL!Dr}Zj zDyw9<#{TqnM=!Yl^MiyHOf39yOKxqJE!0g>%1AG2PGe37g5B6_l6$}b`I+5XVeXmw z(xZ#Ha=+59!dwR(Dc5<89C6c6*ziY}5hdww$V{`zaJk_-PQkRM6MEC1C{<<8sExp4;q%`)cJ^ zeLKC2G`kQ67KCsFcI}9sD?9IAA>5m%w5aVpbBRyS>CowuEMWx`tE0!s-CsotS9O*4 z;a#wgtSF5Huifi80=v4-O_x0#w+VHfl$9Ty1|8_G4wBueTXy+M9zw@(;s)<`;N zTq3_UsSqANWYM!s*UL3aHVW!+5`x!ITF zLRofWspHmN@|$&Mg!KK&s?4fSX7uUBL^#_dPmL8!Y_Hrchu*Fb;{24+t8b7oUDcJn zMJ^b^{c~I%{!c8Hg|7t-PmPCHQ`>Ua2NSq#HtJg`(7yZP!DRR^HU2K_YBlGGoTs`f zTv@8j+{JeuKnt5C!tR=FYOG*_{~x*`qv#bDUw!hcZyce2;e?#h;I@!)-hlhHZ2dfx z?I73{gv|4L63xP&6KO#bmuray+sUUz7#kDyYSs)Gc3nl=#M?K;F=gJ zVFeR|8XlB$n(PzYQ_ag zevP=E2-9qoG0TirnT0}wqempH;J%CRukr&8>8;36@S9r75!l85sy}^M#QM5H@blV5 z2`iYuy%IZ>;`xchehr1kFJ+FvF1`)MX51qE284m>Zo;)FOyFKgrCN6J8}VSV2V)v+ z8>+x^Lv#2PSZ@#MYz6{w1eUVxVQ;XpX=x+*a7W@JCO`zF#pg zykeGw6-@B`m3LchTCpGjqHdUS1a{#z&(;kZ1#4dKkAiK{tE9ri?wY!Z3j|?mL+KlP z>UZonTPVxZlcsOYEa=ZZA7`IgpEy2Pb9g``SkrvYh3PTdG7C)Dn8EMgn888H)NHR# zgkxYW-C31c@NQ7HQ2wTov}j9a!58-V9Q*9p!$ad-n=5?HQP$|)eKIwE^OC@@byrTo zMAuyQ3-9F$s}Czg=eXu_{HNTBmWdP61Ez_iC(Q zViYT*_WWugt&Kv!b2C}TeKuTrznmkm%O}WF6ZLw7aHUe|uZ%526In2ygB;minyDEO6ekPVkOvBK3Uhsj*(NUikY; z>8a~BE7I&<$ztPJ2C4CP0i!SEuM;{tHI{JM?D=tPpXSWN*>JS_lZX{eY|qOqxX5S| zMza-n{UXh(ud`vWYb-}#7yh+u%pe78zIKa-A)YI^`eVZG|C`8k;i7IsuD-FDHKr!vsesGY?rnBZ&4iw^VTpQqxX@P;o(VAtu6)tbhimkaAgE6>{OHflNQ@oaENzbE70 zi?1lYB5YUjOuB6i`cz)s%N3-Y52@L{r2+ogz7`A%RGoXxS|S`>EiSGN&0Af{zWP?c>YVFeSx z-%aF%U3o%NSEY;v&CN(UNrZwaRvdv{)o~`WZ6#~99!fiZayFD~-kA(KMc>s}!9@Da z336`rF2N*PxmM+s^T_k8WSFr1D@R~gvGoKw?b{CFW`^>sdTYPXq*NrsuJbz7inW8` z|I_X^vNqW1$!dYDZz@#>dTHwH&lQF?PRHhiH;ib;Ui2gXyZV4}sE%z`XAOPF<0 zAsXf+%QJ_^!WAK%Be1J)g_p+X>QaFiD|@^;&95)Jm`6i?zzT{LOpM)}S+IbW5%sSO zn~lb@>%(a<^4SgQ(#c!n!QRytc5flgW547iqzSWLHJ2W2VzWE!a}@imQW^F-CZD|M z3Q64zpnxf@7DWlVQ7xpejCfEuS-AMQh4doyw&vq%Z$T@$B_meYACn83dcyJ*^*92% zD5D3kZ_;7k#Co5ESUE99ABMQP!IrhGkJ{2qIAd!lo!ppNu!(&>%RXR-*NiwS{OWI-*tOewav;+hEnr&tY%EvWMfomDAnHe z*4SR$Xk%8Rl+h(7RUY86kJ=^81gv0U94o{4e`q#mS#d$mbrRvh_?}?J?qH8*^Ke89qZ;p{M+hyDJ8f zb@ScfN&kj`6-?l(&U%J>+sT)&qaZ%lkR!0GM`&kx$w@E4T&2{jD+~6J>#6oowxttb z1rzwHvy*xewWMf=00xEKIRd*@Jn)k3_uC6s^_3{JIdS!6!6FJ$tJhH6FIlmx>)L;b z;MBRfg!?h}cK2n8ygxYtp6uJn^>CQ5`|hRjEnOf47AXDI(p4=;!S-;7n{b39u**pQ zwx;sxeBrX8()(;Hbs+BNgP`8>DvA|MEa`n)vvtxO;dHh_Jiou3d>SwXBJ^rG0=xPR z>nzL0bA;xdl{+{}E+UzM-f*)~UBC(^T6uMrgZ70B^K%qp!|NK7XW$CGqZ)Apc4dH< zT<$hQ&~Z}k;7=D_`evXr*n6}AtYG5iWiNTZrMJ*!uR`>gZAP8?upabWCyv0b#(oQA z>4J~&dY*CzZ{)O+jeKq3b&{oR$ga$SCG14iJ9eUK|II^QFcjgBZcy&OfYH-(>6km3N3qAQ$LfD1R|FB3QJ6aRVL1SUDRdZXcU;@wF zv*-Eu9^}Mlcet}wk0Y?ljI@=%d|7DoMq7#A8eQ~M-Y@z<`RKZ~SiuCI7iV$k4>cfF z3;m(A`n7}!>{=~%kTZM-3r+Kt8L!hOdSsJNFc?={mau{eJOj;EGcp{=uJUkr_53hL zVAnw_SGmx0sZerFc~_h2GMxm+v&iz_b0n-_0?(1Nvl;XA$fjK^)ChFE?$O&JIg(L43B75Fv68R?y=4u^RV*6A z2Tuyurz>OX`9>}p&pBc6>E{Uv&qw3;Og!Vw_5t|a(WK9t2|AAZxS4HC;5Sw_raloS zpD2t3r`jzXfn9j!o}Kz#xD`m@x-rR}_CioF@ zVdPGdIEuX+jBLdb*oE&V+oiX!0qyBM8X^}px5eiK@#(z02RZV-A}yP}mz4Q-t<^Qe zC1o^>&uC$b6-?lBe(bDF|0+^6%oW5fjW`0k@GLj$;Tjf_n6Yf9(@cGqoAiI@)iHtl z7?o<_!Ik7(m>0->wK)R2@GLjWiBvs>1Q&Zj(MWAutY8B77;G&y){g|#@q;tVKS-Fs zE_yQ`xtg&B*~9xvj}_zdKWnYyYRfYO4YqzAi2~v9KNqQ zDq#f^xQ}6RIbW_Ny=`W}pm%FI0=w|c6x#vuO$1PTA8=3nIax$y|yROoaLF zlkepn6`p%4BN?}Ap7iR4>2SOII*!1u#xrHvQA31gEtGLdlXXEfWzRG)>~Vx*1rzm; zu+zCA#lnXuKR+yJuU1Af;SJ~0v7J4^z57dw6-=yt zQ7)(K-zl6Kuf)2)KOviTW220WRw}>*cC9;pT{hmbTTr!BG9t{nFo$-Y919UJiO7#G z%e6aS3tE0nrT0ru%iZQa6qdDWCPfUcl4lQoB|Q0~+;fXliPV+EK;qFW1S^;**?&ep zYkIxnVXUxMJos7(|rm^gCl zn%wg0C1KiAh1luPf@p6_1pDU$X{hln&BQ|+gq!pES(ROjZfW|Iv-#a@X4<+rqz1ggvkzS@}_5JbWcbVAp}Cw=~dWsjxj)xw;WX1If)LGa$Z2F~tfd z@H+#GTbsRr96J{Rle?F51a<{mc9w@-m@nMfr`(Trm-5M^Q2}82>@md(Ch$80Th)JX zi>x{^5$50h&JoxZwbP5;^EpE1edP{z>-dMnv)PrtEdMfAFp|L;@5Gs`Ne^d*};M%u**|#t2}v` zukdA|(gq*&4JP*@li}A>ExJW8l@nWT6JTUh3D=mh%S`1PzcvY{oRnG;-ollP+Qafe zX!=pCU;@`3m8#j}RPy6T95{Cj_qO}O7ebh zAk;Cs!x7lED9cN}vvz^7BT}g)X?xz0#YvMOLhB2~3MO#vQK>f9H>3u4-62_57chZc z+eR*sm)4{T=BJc)uD95N9;+M$6Kt9RRxp8U58D^M%9*A{+e4*sdyc@aH+8nkgH}fg zpZ;Yf34iHJ6Hg3+cUtCv6-@B;YQy#fs(-RK7~A#Y2<#dy6v>Tz{De;Jl)nA{aP`(< zSuO7y?<-<~2#6pJVxS@*n6MTviV7kYh>{A50U`!ADz+eq-7N<8wu?3M*xlXT-P`ue z+UGjwd(ZE`eeL`HxL($po@bu<{ceah#^D{GAtEhsO%GS`aMe(pitqMY8~*VcFZZ*T zv^t0cuIPzOgFx`ncy-@u(9I0&Bk0-)?x&GFIZu0UqPhhfqPH|KVH3 zU9T?*O@Ixn7n%CuV7k2ToX6b|q5~F^^ zYo5+NH|wm zsrB2jHt_0Wo#;|?9{m#f7!AI^}J^!RFJs!Dqh>L!%G?8Q~%~Ei|cXMC!SR6UqvF&b*opdR?Rk4 z`FdX`zQ1U}Jqz6E)~}|73KC=bsLA4&weW`5MP_|Iz;b+P`J zADfxR6U<}j(86yV6(rcTLha75*-EU9PCOYjgg1Q=NkcxH5)$Z|;>NTScJr0sSp6@* zXNu98=BH1FafO{uRO1x=k4{8^5O(M{>-X~X^T{uHI^i?Np+dJ_Q z@4C>Wp6@s+NZdE(YHRD~DGihKl2~nZSJE!)#PD;y`IfgWXmyv$5`nIcHMeLz949Kn(*LW2`-bv} z#bGo=#JQt_Qm+Le?Dbm1EjyD~1# z_=Fpx%b7P_Q&Y@80*Ghl8(>#57(*r3~bnv=FpbN`_h=*I;h`&49i;69e zNZ%X@Y*!415dUht?%)gxJH1gN(1m4MWcU;L2AkgLM=O#SOJx@cZ282>-4jRd+gjWd z^J~0BpbP7!h==>fmai@xN^jkxr8o$yMgH5a~cRFJ@ZLxUmg&m!hh97lTtN)Zz1!hIvLUpro7?Yg(8o#!eNDoEhI zp_n^={=(7&T2h@HXNf=;?lg%JK-mhs>uHrn*RMsWAc12EvGa4IHs{wH(ZEl2Bm!MH zn-nKsPN;l)ySj98Y&}8+2^>op3~zVFa>pWHYT)fJ5$M8sg2AwLd^)dk-;;`L8xtx> z$fJy10b}?>kw<7sqlOZJE_wbj`{!i7#>1V;_E!iMBo=pM+U_e6O8L_II59=sgzzG^ z3Uzb}kO*`&6eG)yeNvQ_yY#W>>IX~ttPPcEL!^;VLBh5AH7(t_y}~;=31VD@^}PNh zUpjZOI+Z^DNSnMSU%6bz$vFSRRqaCNV&%zU2V|)TMqh3N|30uU?{Yp(BG8rAM2z$wwh27ys=wVYHmmugfC~Khj(&8h5!3orEEzbz zmXi@(`^v1;N?NuEy#C)efBRz*k4y7RFJ^uiL+#<^SS5Ijyy@6enA3V_UXA= zYHm>AQ+xgG9@;;SJA505GqLEyiJVZ#y8*}KJ?-ndADG7UamkI@Rk`z? zDLiRUCZU1^&OgPwDsRePKJLp8YeOUgUH_iGRs15vH*j8i{TZX)K4$GsPUm^|2NEhs z;5=Ha+}W>Y)0+wTltk53SlYt=!WFO5S30xQR}9mBR`FM2+Uu>)fVwld*WpU^EUXzBKtTdqR1uRpFOQGSs7UDnp%Q_v0GpNC z98X_mytiIIJl_rCPNyr=kt@v!6(n%}DaIw@9+vG>Q|VmzX6Y2w%$g6h8sF|IrJkD^ z@f?#Vi6tg-(*wO|s@+COL1K4>ds<@hNyWuoKl$?DcR${@TM9jFcTytIh3A+IhCc3N z_<_yc=+4mNMpTfn_;p*W)MJaXE>e$Y2zWk>A1{$arbBN^1iIw&QK{lij!y&o(e%hV z#)mDRXqkt8D^*17X-VgI+M)|3)h$~rjLm}|X?D&Zl#sQ0{O-ROig<%c8Pp*$SW=J( zoAgcVzq+hC>W5CGRO-an-%g`1>$XYf)yylM(gIA5C~Uo%^wvdY)$}nUrZ0o4EuJPR zNXWk`;^btWXY4~`oeLxaUHEOp4ANyekMG!rtZsHUqJo6{cho(yn0tOtqqYgT5`ixK zHsZe2wrhBJQ7ZkdILU|#5}pBHHIuZz${H{I9Av2-bNPT1J*bCatwf*;zos~UK6M$N zU)Y`89oHC9L88v5PulNW&z0zCy(D@so6bvpNv8Y14@(5PcNqfiC=o;-p^i zR(|nYSNgW2(1;2Wm}f>r@4TDOn|w^7IqeQf1iIwE{KJzxUUF9g&9=U0L#iEc>UFTjpksW8D7$C3JrAmL?uYhUu~hq0 z1>@h^CE3AKj%wOvOJk)UC0KGpTXko7JwnLKcPA^#%ckw)1_oiAHtuI*tci$LuYZbN z>y%Az7pDZFf&}i2i*>j`N5maIqv*ykO(M`G$FOX5{>{pr8bywN{z0f9f&2Ah|Gc0) zAJ}^o&0cFI5$M7w0&zOisRp;7BJP7|xm`mA35+NZW9pW5_@=m#v~taZeMq27j!wv( z5X7eyjG&IalQmS3FtELvyZJSxcVm66Z*YkazEa$_v2Tw}5EAIZ^LPfsh{GNDw(u;9 zv92tgyF?CH(qdkJ zQfgV~&v+4=!_S)!qNn+`MkLVntIiE==aLsnT4()C!-g|6csBA05mXB%L2b0{cV} z-PSmf@6r0wg@Lmr0$q5PP()^Cw&1@Ldy~!i9n!f(iGWk)A{w`x2QMz@K@HYjk_bGD zj;E!?`42BQetT|LvY7o?I(dzRd}94)D@#7GWFpNu{8J*(g%N3D{xQ;ti{qJ;tQn-p zGbHd_y0~@WRAqkWO9vV-&`cuGg>iD?1kdKWyheTp`mL6eBIuC77F@K6{Q~&G z-HyzEA2XtYgq+uT`QxvASv>kapADitf0P&y5hdRyHv2Q6fGLnflhvn<mM2n|s%0etU0-Z$*@z!OYNfsU7_NGA z6FONTf%K-W_*H)flesJ1Mn6T9PV zsmh~vWOpS^MFk0$weIX<*REON#)Y`8B6=d&`2y|U|>BnmIEl_`5(SOzD zfJWrti6c1@3Nma)hH(*tXbZQy{SA}b=@M4;=FRR>ng3j-tgFsaxk3UFs+=$M0E5lJi0_(h3jSBLjaCe1lQp_X*T`BIKtk7hDTGvZ&8Jq(>>48@h z`aAa|Lj?(JyF}KAn;!J+vdCH&epVvTb->eu4arGStv~AR)%U5c)UH!Ynr1PUp@Iaq z!D6KU!-351M3C=*aT0;9k5(@1R?SYTGuPW)he5V9nA(x+j8hsaNMK(gR@JszQLudn z>e%48M4;>J?aD0sc}sQZG`;_5_1BzyB05p#lc6dqNMN5R;uCGl(Ei?Wv~ymLM4+qg zl#0yaxT1#j)ce7#2oq}kD1p{j>=lFx646Wl=mu~LK!#DNd&q^FDS!?ys4s|t)`C|N~PT4 z`%84E@4qdLs33vsTH;o#uuFWFu_tBivXKaM$?I1qch;nDPa07D$s_sJ>a|(zx4qTF zHyn&>*4AX7I`vbjyuC5KQgwE2QIcAFfxhSUv3+&2+^bN=-8ha45~EgDW%)0=sjbfG z^`p%schN@$)1-k35`iw0CvMC%C0h09qSspcOU@ML-h$fAYRFMRqV^b9X1<`4>NijC zYXeSHCbv@Ibnd83peuU5BMWH}u3oLF|EdP(ZK%)VHWd8BlB0q|ZmDsb+v*-pew-FmX&O7RQrF|iQWljwDNXG8u9OGh6)k`9@?;qZH(%kMtU85 z_|lZ-$H!4!|Kk#Yu0`uD8B4CGI-J*u&od14{$V0z=J#f(AaN$Gg4jU!SJznSb?{4> zue^$FGQD4$C=uw|Wp2hUEUu}(->4II_1R`$ieRokSOxJ5|3GW+xsyJQab*EGiDoEfutl0Vad4}Ki>P?UT zI!FY%{*?W#4IE~pP8+WOs`fEQ_>|7+v~KnCAXJdRbzd<~4By9#M`qB7c^f1GU8jOR zXgeIssZ-MQT6?Iw6)kUGmwb|6@F6`NS!Aq(TEE!YSliQ$Rr}+mT90-%KAhvgwob3E zHtV2|$RgU=kZ+HAl<@Q#M+J$GbzIq?_YKv(rFG(St`&8w9!Ot49g_%jwOD1(UM2Xd zPp>%$;&o#i%ABUs%dlM>6(s6ba$#Ykg4KyxI?=b96&0Kgp$8RLO9Z;A&#BDj?r*3% zw$fXMp(88OfOXC3*q@mk6(q_&aAJ>_v`{T>>Giy$nI)}@ZAD!R#z+LZaAqmq)#U25 zu$C`9TD_5*4ywUMZ;Mk0wskbVAL7A+qg$$NwmKRwPWNIV4^z}v)Ae^X^q;08Qltdk znR{8>3e|)yH;z`%4E8X(A2qUZY?9jOg1hl>p9bvO#9`{B8m@wPQPW5jYF3~*BZ;Ge zME{rd*yYz_)UxS%l*Ku%0qyc~qjAaWBm!O7x{CPrQVl5Nc{Mr`F-K~5k+ALP&+LLG zsMY4_d&0h+{?yvTi&jNVk_dF2nd;5{xjjNnZ>N93Hx?Ip_K9BP+V5Tvw)$Awv0pJ5 znpeBU&u{5TMK4L~+7(yksR*(pE z;W$|Al10=YyQCnBzEF>&f&`8q#5$Z-o8l)0P+Fp&M4$`D^I~q$%7^kV)uZ?!(bBjb z3Aui(9_3Gy-}zGff%X!CE}WN$vt+v(P|>qml)PksH2**X>!Zj{Iaj6iFWqR+@(B`w zE}RvM)8w<7QoM%^-LAi!qk=?Qogj8&$`o~pl|I{UTOph*vrOpX-R%;AE}RvM-HdlF z>FR-ReCMOX92F$6wG*S)j}bKCxd{)W@gJ`8$}it?RFIgkswtbA+gC06t*-&pyc$l6xnJMnKpeE+WxJ#meP(k9%-4OP2Xo6ZbRbK-*F)e}un{VM^bN_NA&?V2$ zowPReJz)hO8CZf)L1JxYG@Dsxm|EjcZSjmp17m2^-9dcY`+qqS=yExk!X918Q`_CI zD+sH|PGX0wJ2!6r%TYn1``V7IYeW~dRI@sQh}|AXgCZL7y^+5q0$uyt_GF#kcT(R5 z))T~tHqlgnemMVozZ9W@M4!!_m~*!f)x5j6AWC+Oq0T2AdDvT1i9na@pI)pRJy)u&eO|8k4}+ zr2hIdLN2tXkDUwH75sJh#Z!6E~9weH=)RapxogU9&IT(`=jnt8{v+&sdgKn8ue}$)rt5_8b)?@C3Ms zdySgQr;O}JBO}8l0$ssY543rM-zp#f%l7tez$~t85?RdGjpnEzfhWMl3AaNF`4rZR zzCW2S5$LMr@KBp-eqVWQqK{s)66W!8)SaG~ZsMpQA)hAi^k^whSGrJ2m!lGat^>~= zYB_yQDebfLF?G49CA{jCfy9RHQC}&~G>0!HY7_B1#d7mlfLyI%8)=;DfUt;YGkU$M(JO$Rr@9Us9z?9w7SSp zK?1+5$QrS46%Xstk6u2k%#lFXarLz}pm_=P#1nn)+{Et(Bn~DD_$NK7P03*#-bKmTqG-B->jtUa^Wd#wvkvF=ROh0#R zk_dFUE_tg}`ukLw^GYuzqX(_y&S?p>w8lw}3KH@+pR;lc*Bqkh@Wlrbfvyz;-)X$> zc_lVZAL-ZHvyC5W)tdY#{^Y12G3Dqxt=EQwO1Exc3ISA*kSjKR# zP~2udZ!O=nc>t|{K2=2p2`oJ#A3*OdJXFL_b-8j*Ljqm$9^~J78~Npd{b|;@@eCCt zu=I$#If8fa4u-yDefy3?peyP9S8bA$xtiWdFIRECTlnYD47yq9z)?X0%bUosv1K=} zwl$4jOb(L>bWI-fO?y?kjOzSEUya(hY&)-B+>53!9n4Wd0?V5?3-Ea#-~F%~U3fG@ zBG7gA=69`Ann69+OD|W|ZFY0#c1hIY(0Yyv5?J2EEtL&9KV317#?L<>5$Ia?{f8Ff z{Z=`7TW@{5ckSaPdUl`^;kP*|NMLyrr_WX#;E&fuP)htqi9lC_>p!)QMOT#8P4$vk zc_-u3azn}SmI=j1^iKmSoY2)&^vfNj1uLikn=G!Z@rtevQB?4XeHN^@`@J{~qeh7`VGbdD# z*jDzvw#0tBQgMe~t}++y=Sz+RP}31M5`iwcloWJ5#%GN3rBx$b2o)rDuKJ~wYO_i? zR99d3IkfaIk82!54%<3$jCybgEzim~^83+k<{f)I{jdMz?;h*&{xG}CAE$`5lu33$dVp#Co;990w z_pvNPmG`x#Tf5~|P9*THi!4w*%_#nUD7l2KmR32@g=?}RcJNpk@?X}RMi%du)?Sgo zw=V8cyktfOS0lOAJs}b3!nI}bJ${#=wPh75vHF&@hKvNhLvbqQh#8f7RgV(yypjlX z;flA2#kp99ew_BD^67u1wQwZl@6oxd8SQtdNpDw`Cj7V1b-kh!tGUWdb+4eW*47(Q zfs?ptV{eo4{C=q%tyNBa9M4-zf{=L>|LxJ-1i{ARY zFT0yp*e_0h9`Pqskf`KwO-qPQRiex5L`ql2Q(D?lL0n^rK-Xn)D($DzS81E4w^x0< zPw?b@w$yfQ1Cb!+e@dStzqB4#rYR?nI~(!YV%53VQNC1jr^~16NY6mxX~27J(fAe0 z!dU%RIV~^dQ+L#+Z!R??0$unHMGlCN9pVgcLn=SONqSdE*bIB5y*&Jna_*kqZ6mXW?W644W`YN<>2DQ-!6Klt2yF0T<6MW4cd zaQwH>g&Fh2+#q8rU+_AfX1u#6W#2<$Xvzt#iS+Fz2DzKNt7> z*!|9=v2O=Txebvxzh$#FVf|6XcaJ`!e{(d5t4D`WY-TfwKo@3W6lK@$Fjus6+FNrj z!w6HHx8=?9i&s_`B>Hh5}3>74BMkeB~t{mgl+NRRRST~LYx*m-z z!4|nyRNr;g-_`!nhxpgJz35#?I7bBuoRNtvX`fGWo15L}@7ci;fiAB$CT!62@~Zc1 z{hO~Jdz81!OQ!PG#3@ZskiZ$4!Ej;Y8NRPf0$rJVEx~kW~P1dLR_EoKDv*#O* z3KBRY)AP_@gvP7V(UYsdoZT2aN!}K=MV#WpDXhtncD|9DRkdVjio<7&P(^^-`imxRR z=(;`Ll%1_QQ*m0Y$3PbUPSvz8uC%PMCE*PYcrOIr_+T(JYW!X^FDy?7j&+pofvsXG3Do9|yHL>F5F_`BLeb49T#YqIZo`^HmzkAy#{)6=zwasY) zKNxkJPan{kP(cFot%>;dnKQXd&LjS%ZJb1)YplqZG2G2gv6`)qWTJc)^Nyd+@wej> z2^AzTyMq`ZA6?I@W?bQQhsH_-x++w;rrC~kP`cgLYwex*9XxN&LB8i>ytuFWe+m+q ze?pvT$UMxKxbEW*BI6_iUH8Oj>GOnNfj`FTHL605V|>EZ#r#Wp7eWOI%vd4XcGv6t zP{|zL)J!JOwQ0C18=tyAa6_=ZGn)E)I@_I_O|RdtWSH#>b97>cF7b?i<}=q1Bgx9y zjH7}C=IazW0XJ@Ee*3a$P2)g`Ko@4{5+lpuMJ!_RFj5Bf;HV&h`8vf3x2(ggm*rqu zvn5|5(1jVg42Htkz09S?0LmM=nxldQ=IazE)>mC;jvv!0(48a#U6`Ru^f>X4S)JcK zsQc&};zZK_a)Kd&**6V_KyORFqhb<`IQm{9(1jVg#LUapgKw`ALpeK52^AzTU#FOJ zUJBvqF>T3vgr!8F3v+sjb-1H3eERO@q-=2{RFJ@YonkfWSU)~{STMyK+#~{Ba^{wO zyGC*A@eQf_J5MQB7!sH-M`XXSp2WjyH>C9EH6#LEm^DV^3VS+*-!JV=pG*5n`DBp5 zd^sXI;oSnheu*b-%kh&4bm3e?zeF$^mAW^2|H7)CFOrUkL zKKAK*p_spQ3Fcb6G>JeLwvXZz#Pn1A)BeW1uw73nzYh{ugWhYejVXbDPUwHRG2kYz zD)Q;gD(Wf`=#txA&zP6Ia6olF=3)||f<&GErtHSHet}~W^mny2@jG`J;mWI*Pm~CB z)yc48XTnDX4!6-yjFj#0gXexb!=7L2OsF8yF46SA-Ehxz{TZg&CFpU`OqOqxC=uwY z^+%jn6Z_{=6ZL1D8~d1>sbwhnWn&tZZ^{l;9;^)Vbv5>$X2#aenXMelb2ZB2#L@kq z@nu)7sr7DOLIsKJ6f?G=4p;0_^|!ld#RGnNhBF;)P*Wn%g`--r)>q;Q*VcPd%{NZc z=oJYkYcsZF=Y1u`OD`oZb?))+20v<;Z6gur!qK^itQr1@zcvI=%9JwFC>)8A3(B!$ z{=b#*>-xB)P6x5B8`6|4#{c5@Z=nn43*n zm{|JKdW}S&3uk@eT?O6cZ9l|Qt&h{C*&Pzm>1Ei-5C`?}Abs3E_1~+!!*{WA=QmU$ z(1o*C(Hl&=#g`7~O5UMurCBNx^6AW4&o1$$gL+WsKOPc+E}T<~`MKG3o>8_ZW#0cP z&Cij*)1YEi?dv(-&nAt!K3XOb=)$!DaTXx*FVFb%o?DAKVXv-s%=Z2QWzGP1W5fh2 zW>I^dQZ(GnSa*sQ8*zK2GV6z4Yu^-^&~fwYeAC5Xi9nZIsvX;TrloQwNw2l-d(>o~ z4^^W{tD6ztyod8M%qeUzG}$+mJ=GlPNzDjC1qqyA84OC&5oWQ=jnw>5i9i?T6c#P@ zr>CrNu^pNJYE7shf%7YI@6wkF+?P9&%kh>HfiBD`EV6hUa_4c=tSMkmTS7%5q?y;? zLY0p>SBWk>X(bUj3zM@zg*0r(Yc4bw`Ci)-DoEh`O2nS$rSs9BEW~XSttA3on1M>% zwz)W)-#TSV*1aO7+*C;5{7TH#sDN(@DowvV+De4vf=pUsg}(PZ9yj<0?`aVwWz0eX z=T~Bu>a&I~oc@z1J#Q-!=)#O(;xE7R4_|5el5Z*#C1w6X0_Rs^RZZQ`9b4by@rjWV zfi4_zh*K%fr?^MugSb&mzaZgX2Ube8OmUpYrpAGWdX(1qt_#Quki6V1&Cq@)ik zIVwn04XDDJENZ77{cl&l(dWvvc3cz6IyzG#(1j;$#2Uc#2J|rAf^vG?=g+P*WCND; zQD+}_Ggfb6%s`rPI#|KwSQkU-aous~)#G*E3}sh=i4y3>b#r2pnWHI%ME_L-F4mztBewDI%o>CW5*H6EEPAJf`Z-QN z8{YavEh;_xFz-C1nna-M!5BXlyQH+b_krGCW#0Fp?K6(?JC3e|3KH_)ag=+}q$xM~ z8P!Q5(Dl!gy3DSGvpQtI{smpjc#~(;3*M<^B|-%Wd~f1T)}?+FHOi4}>z$BFBA)HS zGG;JLYFLvJ57wl~{>2;>B(ScCea_Z3$?k&(%^81IBG83pOzaP~uS!1}dD586=Q%18 zA+;sn4|tOGZU=H)^HL(PWxz5fqF9f5(8n__^y=&zjtUakc8Q#s`)W{~&z3Z-zX>6M zF8S>?JX(cvHrvp*Y*Ru732cK!PL8<8{T*01QVGHjAwYn#5W zLQ$)4^JTo6M4$_6npk^HGNn1k?8x+wD=oNT%cApND`|~fjo7z0o$tgNu#d{AaDB$o za%E{+7Epl}->F8ZAc6h7Sko_OMQ$Q?Y4znA5+S*2c{1A)mz62=^%`}gnnXRc{$icv{la^@q7;qY^4e$RmKB zkv3Ff)CL}82$l$RtxfY}mwR?lDs+=#w3)_bZ%pbO(6#d_k~Y`*+kDplUHj-!GE?$?WziSK!Q z-jQzf>Yx1*fi8@P6su8#XY!=s33RN=EshEj7EB-;`vms-z_-LjB zwqC}+^=&T^=xQ*=inTgdTA6i8f5x7Pzs0`YSU&A!G@*h7&d5ZJaGTN;JGMVB91$rI z=yLFIW_^yDD_?i$EnL|PX0$0MkkgMyLInw&!-+b0#+u$;4Cad;ww4HVed^-Lg1xPk z%zb+6^ZJG@{Zr18j~djPP(h+eD^E7&UO}MpQ74{sa;EX4Yx5A_P>Dd-RbPMB;IEyM z_fQ{^y>xUZlO}(deZv-n3KGkl{8?n^+`!Iuo`P`srv@3Tyk{%_4VDOWH5j3?(mu-q z|4GpE`>cCYgPz6?WWm`@2^A!qOZopdOa0efe@6Jb+H_}eSysQRQ6kV~{?7OxvE`fo z4C~7x;2(5`iup4T!zeGPaa_ z)j+RCR3%i9z&=>)DAseK)1U6~r#>|$0$uVbBgx*GZl#{)+gkcc<8~yl4;ClZC%BQ< z^*!7}jFj=;LKn_5MBJ-|6J1@up1=IJu{8fcLhhY6Z*rwkCUbb7>46e~uCxGuRw*Ds zsWVeA?WsRs@ub>Gl&jX}m_-oRkTKR>WUbrsjPGvPg~m3Ew^02gd$*1m$q1%x&I4VfsYQ4yR)#3wptQ18{a#l+Ox-iyV+)L*Eng=#% zN0uM=a#WDOT?dhwV&zA^b$d&y8*xS=(1o$?A`@H68@^HOimvVWkfVYG?w*K#FzXW^ z<`hJ4XMUClbYX24`9&k%@`qg;(bY<&qQW|X7jbNnO%UAQJEvJS0$!yj9kkV*lB3KH@NVAPe5{NC0tJmZrp5$M954TE9G z;m^Eo?fd-f>kvW(3GC;^+@N*|8X0zsPifUcBG84acp{#9x(P*nUdtQCM-VDVU_US7 z0LGOj_i}}Nwr?wmKo^es#oe;@pYeEGH?B~T;w2~E-={$>HN(_|1?qG^>yVyUk;?$E`b_$dTbYWgBakuQeXZ(EQ z6q?>|8$$&N>>tJcp!$g?StQf!d;25;U6|iX#HvmH$^CmI(#eQ292F$+RGRqa<4cm; z<5+4o(o7=Ig?Y-vs#`dNFqlm!Y2T=5j~S3UjcW^`5B`gDUtpbN8HiLBUJ6TLmyM;u5L^>@1Ec>C#(q-Byc5NobBtT z(8B0F+{Lz%M4;=_<>u_hS|7E`1ARW&a!W(<8L^x1sq9FoAb~pq;u%Q+|lR@~KeIy;J#k zEtP8Hl~2L%y`jFNB-@Q%@q$l{Yk$ea`En)M}^q&JWwvqie0j>B+|R2o)r7WFR7I z2C4LU@EKMj-b*6Th1qDtjUnQc-t77wY?$grs37sHVe9|K4DTcLj6in_n$f1PS=xl^ z)g=O5a+aGYaiX!QU1hELymI8WA@#q1%V~H+FIfT%K8IQy%A@8nK;YJQy?JKh6LzW~YmQNnc z&Np^dcbh2U8Lf|Yp-S$DS$O|{B?4WTxk=;}iAbUJuIt$>F;7PYiB<~+vIDk#)Pb=9 z;u#fvx>6U9f0^yPR}z6P%s?f|ZnqwECi^OT_3XBkX$pyNr~0$5R~D!*OEePC7?7Jn z=A|8Y*Nb-~0$pRLB(vtF*QlA#^>X#He=iESSc?CSInPl+qO~!D)n2k!egCJPAnru< zpwNl+`L?Grfvz9hyRgq^wyNv>^^92#e^Y7bHaFgM!eNp9^nVHxS@vnHdB$aRX{4T^ zDPeg}YMkAcZ#pd#=rUo6Y(s#i2E^#C&uahP#4Q7O<)?c%DoFIZ(~~t@bx%zS@)1PX zyk6vF)04O8xmP04b#-$*YhUMxIx0qQeJw7Rf?-m7*0H9idzjMpHT!}yzW@#7m!3FK9Tv|CATr*k9-;TuQB}SIeWwp9{nI0)?5ZU)! znmN$XBR&#=F3jaFB00V`rLf)AXz0~@3>74L&9BdL56n{4|1va%oDHOBhrH?ixwR63 zF1+_ZwQ()|WVd=0J3EIQ|_FE{CDM(?}Uqn3Rd(x;nI5`iwfzrkQQ zaLM|sR zCOXemQ9(k!kL5@Q4{Gte1*JWmED`9!`!vKl^*k3!YaUK5Uvv&a1qrtfYFp=Osl}`4Quz zq z6sI}V%e-)GHyZsrP9o5S+26$(ll>?8p{(xI!mYD(DXft$fP63<_TMTe{s5U6>0^WaaWI;vKj4qh%vaji?}jH`$3>b?dC+ zlR^fN>CA)DiWj;tW17KGCU5~aKFcJn{@EZ@kifh4#A?)~Iow|vMCscnNCdht+n?BD zsgTdx7Z0YOc~gT>K?3gy6t#AG4sR~*k51_JM@0f%m=jXu3QNus0iVO@R{Qcns30NV zqnPq^AWvU5jDD9buOWdh%+@8Iu{fC*9vDu6CT5zXz&(o6y^RL<5edBIlHoMKzmJsp z3tbp@Vle!0ZpGIO&LY3eY$hpi&!lw!q#^fjC?63poL)qKl?ZfUbc$I0_}hSwiOixM zevcR`NL2A!p(UI@q-^xi`=~~9>+%#noEG#m7a6+$m$?C5a()J5bvy1nbR>DLUcyj8 z0`D9ZxeeQw zV@A`>%}El0E~U{ywsramJ=gHS=Dro)Y5j~2_7jv4x|N-S*4Yzs$|Mchmc z33TDPWHGyY>CeK~jV5EvT@4i^DzCaxd^L5say(0ayV|uN=6^Mt&Lym8NT4g-?PhW3 zolBG(IeLE4sjE%cfj`;Q*Kr*~1qttWam9@a7At>W>(8(md0UHHHi~{{l@)h8{qNsG z*R>w;#U-}RQ<|0gue4jmYqN%D)6e`n3>75&=I0l+DqN%_4AY-c(e-6T37QvssrXf& zNo+xMQjoYM#>Sh?nLLczEEr%!1&L)D`9+!YCbAwE`v{_D_;@zI>k!Iy$dL$i)p#9Q z9Jpoz3t2Hh5Ebt<;WtVTAis*!jIHA?7LU6*o^9)%8FcW0iy79_dQi^`#Wg#RVT~7!6GX4sx7eOm8C1({j}a9l%zv~m zW^Ko^dL}xNAF`P(o860=Ub`X@=xV#FUGZV(ELQqyo**_@&DOe48cok@_YJx_EWgNZ zOCBqAuX<30)cm4JL-JTF8~>o4MX|-}*W|H5pQ;Pucm-FMbs(E6=kJviB+}xei!0vB zWjj7c2;$Y2`K)bHHmyCjQ6kVa_2l*9QTBOkLd6<_xVH8vi!L#WyvuwDLIsIedoLHK zHOgfh8nqTgeWetybz&qH4&5yg=rYaq(0+MMW}A)rGn}8f@PVJQ=zF!_L8u_HbfueC zuT~DbP@q49B{b#dj}521yhjp&F3&-owBBWMn8U^ZLHK3O=F_$fqPrtQf~F)c)!t=J zWF}r^g3dIbqh&cw`tQG&C9cp;)t|sRR`3)=%;xF5# z^uJ?D#mRhL&%yNZz)^`nm;9?%@94*OUL8uCXY2|>1qqkbSS{&64qG@>f5ytOt$Fp& z!)g4PwGx3Ye1`_Z^wj};N&gX4J*JiPu8`PKUe$^NC;#^r42Bs&)p=;nNa~jVMa6#$ zT|+Z!X*rAkKjOMi0WbXCpQ^@(8JC}1s!huo%XXTy4RSAz)(l%GGS`1w|DQTIq;`A0 z#%eG>{0H%%hY z711k73wt((Wm*jqM41`6{K~2}iP8h{*{?LiU3Nv|Ii{5k~be2S* zYyR``+PfWNS)@Z(K`gLb#TV{MrL11LMpTd}zPv>HGA)}OyQ~v?uWr+#Z3ffTDYJ~& zXPEZQFG_nbfwjKUKM2337`^`5roE_^NwtozHll*WsebuItG172CA*Ck&!`*j&ze^5 zM}1c8ln8Xmr6j-CR;}&#bZXJys1X$;?E2>y4e=h!vTp1BNA1QwtXkbvnw)!8BG4uG zABQfi*FIM4K~OI*`f|6tYOZsiKLm82u1}7EYsqQd)^gxu$qViDECzQ zRp`P#Sj->`Z27$(-6^>Hb*ZmK0&9U-Ra;z#n~m;GCf)Z*1iEl!AV%RxI>qK~ zl*SB5U@Z`(T}$IBd3`Br^mK_p7q)z22kTJ|ANfxP?KGb#wQxvaEf6iW%Y6P#%+FKH zB})Xluss%QmWAuN>#*Lm+^vVyQX?VPs8;h2@->m-hNEW*5`nG*$1Z3;=MQCjV%v#Q zvbT>VJ0NaA-F?Y5xOv}G#S3{dE4y`ZklWz=q9esU*|?7jg2KgrciY#4?b)zU5FJ0{ zvey31s4P{J2z2dlb-dWLO$SyYWtAYDo-flz8lq@YRK?)ff%!#_^9Ha<9y6t9U>Osm zzL81nK~ih7&2^AkYW!9BYYhg+TZ|R#Zc9NPwi1CZY_$!B2~no}7qzC2R(8RtAaP}n zqh{YWjTPk2(cjfC7fz1R#7>oy2y|hqEuxBBh4EfrJCbSNlEJ7T;o#C<` z*RC6_v*8kfE^M{MTHnf5yx*a&6fB;hobwX-PM#{3TN&&?T4lnlE+xBnh4u4B=H)mywFsHFJ+k0wU3RqI!aXLOx3jM3(X z^v`<#U{sKhOM9Pi6P7Smk4y#ZN9Jg;o!2&qu&uhm<(F3b-7iA zri6wDqk_cI(fLJH?JKd@RSpOuuwc2?^_wfbp5Ia;&~;}_e$g}=b2jDbVL|M$ey`az zt3v6ULxZy?SnEiOVi&(+>d4w{(*&`3a9!R> z{N?-aGz~@ti7)S_X)hj|u~EtU1<~lMH-A^ZI+?69N(8#9?`WZoE(&0S&uP^$W*Ov%%{XEuEtAD#CdlyzDh@Gqt zk2vZ>wwZpxs30No=W6$o6}I1ey&!xBb>SNaH6$02M;Qrp{oNj+#l*$1o&n1Qk;2FF z#YK(ivU`nSRFHUTKVRFhqZMniO0VZJa|ZGV>!uXD)mb9YwZ1`H?d$gL%xT_SLC}~2 zzC1xhM&GatMg@t~2Me^pA7WYBiur;V|8@%R5*0yrH=0QVx^`U{`~NWZ7SL5I-~0E$ z-CCqAMT?apr9h!QnFJ{AdU1EBKxwg3D0SQmg^OO?z0D-JyK8ZZ`^DwIlbpl%38(k{ zy{yGrS>4a)?3u~TWMpR|Umh}$U$#yoV&t{7$|~nFYSpHqsdTZIz`9_uT%LD`53E;G z^>}BlB}icVr!V9!y3Ge(D5g#vRNGWbP=$4xqL7BK=C13Ds)H-nHPu}tu>I4z=+60k z)5pT!-1{GGHW@um{P}M3tZuR1= zFXZNFv^MD5Zne^^Z!0x_i{~Pid*M2ZW<$jJ16$%v-fGl<6}pZ<2~D|DPj9e1gd5Y-X-_zIGj6uA4SB4p4XI` zPui#(c5D~Xg2eC^^j({nf&7_si00$;U1eC`c52AwMJ57OX9Lg4cLojTnZkP#(Ovqa zoSWQAT|Hrrh!!N;^r4-Ksy(^a*xp1WdMs1YR%@(Q-<(duvckHHr9k^?AGRv9uGd%l z4^Jnd1&Iw!cF33g)=`#@tRADL5xj4%%D#eF2QQex~648Rh zbe}VFrKvsmp&^mv!*Apr<)%vu^@q=X6M-r$1v({7e4~7;&`ga_*&(6@iG@p2!UN`I-=a(@Gf4 z?jm<7e)1r7*zn9EuBsv7+xeorH*hSEkFZjz+|nIVK2;u|_8FGWM4)O(#>;Xs7Ro29J$ae83(Oa!W2Cwudr z)td9ErM!q>GvbxvheoKI=L|Bfi{ibB4qh(*q_vZ!bDW7#<2NZ+qlT*2Z|-GiK>|yi zzTDeDRx-E@R^5Wvn+Q}j`Rj_@J7*YQktr|vNIra9*?F>;x+ddmh885S)ae|Sq0f}L z&$_FJD%~;>sCtwwJs*-hg3p_!`Dkz?y(*k&tKOXCB%%cgEOnYkZO^K@#kE#X=FMm# zQ1vsuAkR>tH*Z`eANe?T$wjS4eaXp*ULsnMFyD`$5rx&2wd<(;))zDps46?R5?@ob zHQ(`E^HKW2YB@PesG1P<#k5xtOgl8|KSlFVN+X7=^|Z%wY_;6z`#5!V9Xd@D_6Lx_ z{T+Iqe;LgehKy5dhSF&^K%fd&>nWya$y)v?%~&;bg0F}cByb&;-X$yRq)cr$TJ7Oh z#YCVA*Y|18xy4VZ8WgNvsplu61qobFrZ3S1bX0hqU^TxbpNT*fuEW!c*XbDAcOId3 z5sHXtLBhPk;xZ>*ac>={?pmAAM4$?LJNhcg07Y3^slU48y|0KCB+PTp8cj|q4QKaJ z`=s?Y5vao6j-JjXUMWuF>CE%7Ekv{+5nC?}f8^Dlm-*D3>eZ;aUzJsT+SA^4V-tZY z?CmU;9-XtR1&%jSZ+i_A(Sk&yS}xo(Lpz@BR!j2HVr?GPqkTj5SKEFj0#(@CQEY9A zB5L>LO#Rk*l86>0F2nT}H1gdal zidLN;j#vD$v{ZlGO(&rR2^&5`O(uwv><_FZHn;`xh5ZV}2p{;MR2$w_ zy}u_+L<!~a7PV@Z)@t_>AtnM<*sst%PspX_Yf)d#)IL^33la%M3h-(bTkunI zU+Nj|7R#qrzgAm4a3|74pbGmHi)CQh;_8n#)zrT;&<+;#WJn~tmg9L>3A|*z0pz3q z!&0hTu?oGpHN!-p3VR|tJGxn8C3DkKYS3w`6#OtwewAas?2`K?tGIrzT)Ssq`HJ^l zmM3qLYzf~gS7>yBd;~6>q;&gGQa!zaLx^|R^w#Sz#p9>dL z$EaokRX#xnlwUnc zsMC*>Hxa1nUi66ECA}A~$Ttwt=Hf9W$8!&LLLN^EEl6D2_g;SVwE$Q8Z6+eS(_!V+ zGEcSc=n^IZRrz-ulN@V`Nm(}=-RS87Y zob^D-ImS=*xRudFpsK;SQ}Ts|ZTY}GGl&ote^k7tR#)#9`6Z$Si5GXi$;+SA;nu;k zi1^FtlX4<&4Ygm}6cd4}n~fgJk#jom^~IxzNY^aA`m?8~F3*2mL<5<;Rkx&H@|x)#dDD?&h^QKKO^Nj_t8PgsB#rjW#2Y`Fo+Qv? zE;*eW@Bg7_QsYcd*`v3a_?2)`UiHsSB03j)sWkH|sWzBUP(lk5?n~Twqrpd#JXYK# z;^vPBN^~`POYd!Q6M?Fg9$9(&@qf$8u9HOEclx4KdFZZY?O#Mf3leodx^t%?-Q`K! z&l0hv!be5P@20MyPklZ)zj|wVE(tA29PL?x zzrFBD=DF5uJ{CBuA?@7N)$g;K2vqeO>%_BG_2A34EFt3NNO$$oDp&QMOL_?{NE`_$ z#hd7vEWT{)uT{hRgHQfq6LZM zH>LUa%msN+c5SuxL#v`{@QhMwulqMm1gduD$j80vi@aYiZC5`kqO=;*!9%T=bXG(Q z5`+4A@=fK-@Rgahh?KiSJ=8q?%Bc%ZC?*0`A^G$3<$LP$umar$m2vp&-L_1;pgfhKIQMFUHauQmQz_v-}S*|*v zgmo{h7U$(n1gh{^LZ^5fx~r7?$6ehssEmXbB(QDLdyp&dD6#Za#5EU6nFv(jvxJ_U zz27OhY86rkEh;9V1qp1M^cLNvSIU>n#npey7d8>7!e<^kjo!S^pGiG@wY>U$d0G>J zDtwj@ku|qEikvrO$4g&=|d|lRr0Az=J}|+<7E*o zNMPHfr`nR-s&95dojZJ=i9nV4sn%#s0rj4fpPHCymxvZ5ux(P*i|Y`6D8W~)aneUh zSyW3dy<|huoPi%%@1BxeHzc#X=jdxz@-RB;1E)t^zTb4J*@$m%?WGPp!Au0Ia0io4*mxDe^N;XUYj{c$T9D{i+A3f8ca*&F z!hQ0Q`TT7DJ_n6=&(<;#sKOmgdOs?2GG85CQti>Wri2zGaI8%`qi1p|-FFvP^Y*A^ zB2a}pnDn)q+mbTP)kCe`N0QKj1dh(BZ_m?8*%Dk#%@tuLP=z~~bn5BaAmu~DV(NJ( zCZPoh9Gz3&o-0^MDC40XZErOZsKOmg8Z$JRt~gsusOhfyN@zg>N9Ri=Q>r$ouXag(Dk6a@+y$Z) z`pVCh@1FJ4b|Y?zXh8x;=X5^Y@sCP#TDjXFx8Fpd3iplZOpaFR)B`!|tNhAN5iLky zKSu9VJ7rQwrfsM$$+FBupbBUAw4T@`kD4a9mfC#AauF>^nES*Rg9@lZaY;?Nv&clC z3TO9p#@2lg^=36%xoi24h!!M5Ok8<0^HTk~X`H5Inq^$a4x1c_3|CONy3G?2> zrvct-t?pISVPbg^2~_0^t<4{I6L`Iu<;X`}I(zPNv+C;g_!=TwkifkV8pFj@QaxfT zs9pnxmd_O&Oa!W4r}*){0crV*pYzGb%z>5E^;HU}YZEStXh8yJ zNE8Y9xw2ZZOD=Ws;JYRQRaahBXZQ3L z_V*=9gIrbArdvHs1gb(0Jd)p6JD8L|-AnQ@W_P$Usa-{N^TY}gT9Cl?2l_VPmi|f} zUQykrc$)}RZG5~}{`*8Zc}>X_@-e@ysCdmTtA4&+T|x^IIO?Y;@8!jnmyOD)!(W&Q zRIN*#A|KmPU0&Ys3Hj)D@B@G7R#u&KU69a%1kPTx^ZFie%i4+cDdrdx8H&pr9(28octJNj6Ac3futAOa!XhoS#l{ON*1*U;LMR zY*2Ued)s`~<`ANs5zMew7CVO6u}6rA-8?+)K}ryG%@z^kL_B&BylbyyIX= z%{{J+gcc-lzDp-lyxGjt&a9(OYFf-hplVrf{e^S@indGP2-Vo9BpRznDc=!HW&QJ4?e*L{A zv>@?qDn$ZT_?h&&>^mYxZY&`0z2T=8%3>x^HDG<*>ZwG$(Fr=|#`Z5vTAHg!QgXRC zeKeVCMcnEqHRAY>vYD9DWq#6>7qPat0quG^lTFIjd;sq|H@|Kv`lSo+{j8LJ-5|IJ zFB)Df6{11pEqV2f3A*K6zZ7{@$MO30ne_)`W$dI>i0rdNxo@Ytvi5eSrq(F!dS91O z+@)-qR0y;n(I{vn|1vg1D#VU!G5pum!us!C&Ku2}Ul^ocUs@B*BjqOg_5bp%<$PX1 z9RIS|)k8~(`XrWb`gci^cAZ>4j?c|dB~iOJ6KFwV*0ET=)NPecn+d!hcn>sR+Alcz zKnoJ-s;o;2y7GS!s5-XrNYa*_sS&6;oSrA0=7#FO3A7+_YW~fnVbfFdfds0yRD6}x zJUBH%yJOm&)5>JfxjJ&u9LBq-qe^y{_q8+rZZ2K4An|l#2f1WeY6QL~eEm&=Jp6CR zcZSVA@ZDe}Ftz_ppsHY*Xu0JR7? zSg+86#L&G3_#oCl72?CY+Fbju{no19zP#;(mijf$Kh3E^3leH(U!JCuL7NHfH#Mc^ zW8}xb_{|t^{Th2BGl3Q)gbwYv``!vV{oe$t{y%y+==+`r_v0l-x#+)(eWlq4T9BCX zc@QtRAx|o)LIPF)-NT^;iSlOyxqDcaRD2+TD(qd&`KTHe!M~SE(0fa*ZD=)KyEn_u zPU1rv@KkzHv>>593A87IV@*T?RUe8>h9w;xEw z2NJ0I@8>x_$r2abPdY!@c#{41Qw=RhR6CqsF7&~E+QR>G5+)&mDs6P5m5O7FLJJbX zZbjwz~yAkiV{r`&#Wa4M-n0#*3zGW$Ra5}iw= z=c^AIPrLsnP=!x8Gl9=2T!+P{otZ!j64xd)Rk>;o-GC^wq(mWkC; z@qq-Y@R?}#ai~`eZ~U#Qpw%B+>(Z|?Jd5FP&bsQ?W&$lpXyZ4krB=t9h&ArV;1cqd z9Y*cL8fx}|79`B4k^GMdlaN3ajsX9s*Xk}>kigSV{+mG6|G$yt>?6zNmj#WHC5{=* zKG1?h#E{i;seO}Ex#virD&zCbaw(702(%zEtLI)hqZpow4h6)XVz|@@EtK=)a4jS~GzbB>ZL-;hkReOeIxFph}w&Yokub+Kv_^ zJ}NX04Q}^;5U9e@vN<1UK_bJkN<7DlHmUeP0#*M#3debEfA2V+v;B$cT5fTMY)%zg zkO=pR<8S7y@^>sNBv7TTR?sXtmA(X39o%WIUdB-UH-Q!;YTk+E(&7ahs;~#AH{2R0i{S}6VM}8Gr91dZT$D)OobyI|gzT;V*0z(9fTMCI&*0mU=6HfOQ$lISq=tOd_ znezFekvfs*R)RcuS_JDdVLTD!Lm?lk&4)}rxaQ+cc zI9YvmKFXI zy^FlCoO&x4bMS#gwVM8X;LE0LN$)7i#|}DedeTRK2Le@?KRR>yr@PvzYD1mCGQkqH z^<%cOimX{!ZQ<8IC(x1_VcZX%x18E7#>fW}_G?XroatrHVx<>!|g4bbnDJs(;_Y{yi(Fd_RtBmAkm@YQ#twRIGc|VdtWF~KOG5F^-{suyAuLGJT2w%{IZ9%>Ae~s8Lht?0 zi_m}T?S)lxhxe29+}4d)CYP&k{GIyUd25vVdjoX>El8-I$#Ug^6KrJ_-)fsO?(CfV}wE8(b8LK&zNXh8z=MDGG5pI1gt?5`7OLE=UG6xqG;cowv>Fy%Z` zz)hw9Uws`2RGG`F{omV__(UTgm9y-TyAKLyg)TJ_2B*I&?+OWH%RA&3{C_3NS1W|G zMjO|Y52xm;k~V0t?gK4IUebLQC3Kx$~M!t`FPn>QC6-o2(+X|7(Mmd9QTwKZ;keWg#B7mWm}Sor>#H2 z=Htrdk4k*2ZhAh@f`q+~F?@`Cn?~I=)96c(Kvmj9S-2(FaN7uAVMIoC&YAYQ540d* zzt+YQ6!jvdQ}3PZ_@9KP`tmdz|4Ann8pMFWhoW=A-l~?y!tvh)>H&Bt^#IgMFzRu* z*5go~1Z_pq7|ARu@j|RyvZqd<1qtf;81;!STbs$iMca}~z`g^-b{gqCzEPI4*gTi?>qrVcUzv8z3 zN}&FV|L(6u>aTQy`m5g->KT3$m_oh35~;t^3A@GCU+MS5)?exO$!H%`cO|O3I$^)J zw))DbzH;rFS^=Z>!Hp3z^;aVGa3&wN9`1LluoUzj?l*y!)bjDWhZCuX(|sU;d7@rP zpdOAJ1odzt^>8|Y79{L7)W|vYa3b|^4g{*~b;0mKJ)B5AoKB!6HNx;gJ)B5AoC9H} zH5K(rjCwd*KB$KisfW`Ev>;)>PlgZb;Uwze90*jI?;!PX67_I8ffgj}*G7Luvm%LR zMLK~N`?Z!5nk_M!N7-r#&AcRB{jmx z$8wfIIy=9E17W8%753oz97m!#j!sZ{=sUaGU8DI9qdBKu`|Nqr{!S-z=Pf7EJW40f zk{V&O51OklnR- z-Lsom?dWKoIC!{Mg8s%SM@(ALI{I~Z2M zN3^;)5_W(8eqA8s{aXsPoxMzG$FvS90rKJTWtMosFG%-+1gh}aPLXFj%dtI&C+Nh^6I=bq3$%9l=D1+Lo-Fnewp`d} zy++X~M!l*VSQS{cd`_+gz+RByXxnK}zk!tnu-%P414XXW-s&QBHu;Eu6eIW7ra|Zu8wc_~u z`sK;Tj!jwF;2Vwvs!Cr-?>~=-YCanA(<$1I`fL3TPU(}e`W%X=dK&K`)N8l7+BCYB zhk6MA4(hW)Tl+QId4)5c;@Xi$`$(-7X>HKlqC&Q16YDP;ulqoY{aPdDUdt-1EN_n~ z>fiM(ld6R}5U8@(9-~G1mA=lVO*06zmx zR&BM|ApBa-V7WRQ1X`*`4Y7{RZA9#$Z;K@*-7wZ`x}y&yw3Tyh4cqXsVqznfd$S{f zszQrj`JeH%6MkhXv-TjY z%MK1Oo1Xu;o| zbvHpcJ|luxn&?VIx;$xE&>bV^*mAI~*h|+)RiEQ8g`N-1Wu;k=Ft@0q6B1ar8jb|2 z>}|#H5u+Yp8Lyh#hh|BQFj{S^I2TbVVQzyOVgFrCg{44i$dUEMGTDs#ffgj}PYGMk zP%K1z(8YL0A%QA$>Gq~4&N15)2Q5h0pEyR&hcsC$_Kr7ZML6@qIn}$EokD}P;aqLp zlI~!3B7$uMT9EjbagT6dAkEb(tR><{v87`5G9&bwhy<$4yBR+gED&dOHs;P~L1I=) zf>3Nh1P|yji+oJ7Oc$S?HJ-IdpbB?V=!?)V(kdR0f8Rkpj%4Hc`oiAYw~{{2iRIcg z-5ZE6St;M+n}+?aCBH35l=nZHG-^jIKR>7erE1yd>-=DxBY~=P4-O=KOeA88MwE%Z z%+D?~2(+BpwI}H~#neV@ZTLs3dTuz+m#=p8fy9$KyOP{a#qtB68j=rJ*E77?c1HqL zxiW4{x_vd4-#OQqh!?X?@Fj{tpe1DAx}<$KV!3mjCV!-gxgMqSBOHAok#X&^r0I`h zd6gg9C?o&!gS`1AM*>yOgZ@scPS1~7YqXKfp1^%PW3oY@CDA%R>94o3oV&LEBUQ=t z$GwjoeIOD1dT!FOcd@+Bs@CMA_O&FgK6fNgwQJMNB=#wmpLB0aL|(tWe9(J?K+Dfg zQ9I*Kh)Dle5D~GL!&%-CgTQBz{aPE< z*vHq}=$zh59hZmwV;fnb1qt)>ywSt!)~P=YA4s6e{`4_?%=}PG?)1$d(1HZU*3&nt z`hSy)-*Y5T)uq_jq}P;l!^c&Zu6*|rgFp)s7>!S}iA;0&oYsy6sxa=|V!6mR@g7bF zf#u%SmXfCrga5ea7lci`myN)hhy6~4!Ko+E)OdQ$5V_{RMRx#6p9x^Ijb z@OP2M5}|qRodD%=9fLp%683AYq-jL9IY5!>|2LtjPR$-FN2iJA8*2_GV&ljFC0`?h zK+EIdL*-#TD2b>7Q$mT-Ys|uX^0|k9w7n)l??;arA*i=|cnMvhLBmNm;EI zE$ClEc|P2cKvkb3{bboYnlCBUfryV)B&E{?gFs7$k^SWNKJ*?=!kkP+l)~Bv7@pb1!*8(`Y_$pY~L9_OvS5wipCj=I-h$4<1b4 zxI5hZkFsjD+E01B-_ZvWxk9?i*@s4RpBdWIx#Xv6O5$Zl0#!x*I>?`AMDy8wnhMN=wn|xA8wqx!hSjusIuo=8!b~=rQ4`Heq-!l*?Tf=#=D?x ziafjPczs2%ORvpxn+nGM7tN8L&s8SV*Xy(y&oS!zdeJUf-07;qxVH)NUv$0WTvfqN z7&8{%tBaMK(Z*~7ElB*M?vf`=3)lCJ=qqEp7brK|89q?;V$~A4+=K{zVjL69#Db3T zimPN0XhGsw_P^!O;0PWVT7z;PP;s5IJJ6U%A%Uv9r7p{7R)q0RSG6(q!6qvd*JZ z`dpJO?Za%dyY{bFD#JS%KG1?h=_1Qy-YkOq7SwvUptFfenhwV95)!DQ2s(&vi~YV< z`Dct#R%k(@QpII*RMQCFGq^kXh)KUr5l1@`s9NYpscI6zwKY(Z-Yjv{1U9n zmUTv-hy<$kM9U*BQQXNr z7ZI+{!j;h-4FWAkPDRU?e?{^m9=S{nlkr;v0j3f!^7ic z|GN=X<4d z?yTRLSf1#->72;NzD6_TEB`tYsLHoIchXFXMc5&QJC%nbZp7 zjR*)N?AO{J?HC~kFOYkfZNGMOxs6K9Q^!#szBglk1{*%o#qUvsW5$>PElA)SF?1Gd z)Ny5f8zXKB2~@48XL~3`h2_7et;yt`dR&QWZ4hWd0?Uog*z&%iG?;J1Eg^v_YmF~* z(*mRU2z?j1&!E?ea|0ue3@u35%gxAn4v$aD{mRB2L;_VK!Yusbw^6+Pf~}N~F< za)_#3l}mH416^!!02A93Ru_625fErWf?^wfzf(_jcVJ=F-^GzY)gJOumV6j8bKf%E3Dv9;)w>*~?1XB|9@eJ#Y7RByXYbk_`(?uO4#ls1s;G!hUV|_~r6l zX@0)Te-fH1cE5%1x-p7h5VT#gji25s%NBLl3AEtvMpNDGNOiZ*IDPCB=BoC;V?+pH z4(&PDdJlW48>!kdF0VQ;#(Y0COKOBh6JH{$Iv}d8o+|t;`?aRQ6w)rh=wC|c4WlNa z1qpl2*J%2>W432Xxh+OyCK9MJ=iEYP#9vSDr>6=nNZ8xIk@K+0la;G=jWJwmD`{HY zwU1YfRW%&9qs4x$5%%%C(P}sQ&sV>`Zk@At)%kLp9NDW@&Q9Yg|E z^rqGCx1eaeSHVZ22q8(UF%;J$Qxp=@%H4i#ix842LWmg=LJ8xVDHI{36BHrz+fw^$ zj7$+iET<76^!t}AmQ%(1C=?;&-~$PYth#3(=%H=?%^nnlu0#*1P0-c)eF;zLA zca%<`1qq7%ktsrm84*JLzRXgN`UN=wu_fQ&XRF3ly zwg-&Z(vPk`*YXf5?rEUKmrzWG_U}w$Zti?_f==u|u_5t=5XZC{{&d6V9rt{UYucws zqL?DR)Gd~$p?UbqD+YlUBxuhfk)o5BQQK+9gwu|R?gI%_+5c{|+MGMfaf);@5t;=F z`?XQq7lwNAm?H*(7N0w76Wv)H3k`3s#rx>_FnnBo?#bsJb@YKm&B?11>k+;Db5p9j zr*4+w3y(Vzs5+KBH!)6(V-*Jk5Fron;1^FC1X_Z#&P=>QsyT@@|43DjJB9h?Gmbux zxYuJ?V!Ik~>_rYg@=^DVE8l+JkwDeBmE9B95fR=~i;eo{v=e`H*&xtzz{feUORYF| zEV9BMsq$T!ji+39^nrv_IDKL`(Pvv|kxun1r{(vP9SKwoucz*rN;UE5ni52us?|%$ zGTmr{*giUq7%gv1jM8hRz0Di_?y^ zL6vRXZmaEkQ}QVv*?8RtT9BwZsj$4{l-)1w})Ds0VqgpfiJLVBtwLP(|vA!dsZ()&SMgpf=TLhN^h zkU|kcIzjP1zbzDN@|&<<8!d_=gcOPp`cFbr`45bdDME;?)FXtNyADz)LP#gjg1<|V zDl$a~F(X3g$>TTjng>SCvHoChXD>q|Rdv`)IsBoytTYP}=01@kgg8YA>8ZlsLY2KP z7(OUMh*N}+PM{?yZ_a3lTN{VG|rfEcA$IGnuB7;CnK=VD;md9h+KBb|6 zzO}E*pJz4JIQl?hcb;9=E~jEyPm2~i*!A^kc4fOGfvU;dH&_F%#j@iMwVj4>oldYu zszIQI_gH7Gd^46!?$qRuRP}grgq1tt=mUwZ{gzp;Jt7}@wH?K^gATF}mmCRH4fwUh zy5mVKJ9kzi{DpmNO|n6t#rNAhYr@-DHmzFgKT_4cH)my19DN}1Yu8+BhWD|o-hOQ_ z_4J`6_T{-FfvW0jXIcY3#WK059wAg>FI)TGAkY$4WU4jo_gJPJYyU^8@|@Yl`hIov zfkgg{vDUo5Vp-nKT7=M*q#dle#pvO%HlXTx`$+4av~g_OKy7b(@RMyUD1$+uieku{E`e>04HG#tK( zUCiT1pz33(u~v!@V)@7E5kmgC*bCd3+ETNfHPO`=M^m(jm7;0%Q8A8|=}VZ;;)S6f z3?FDg!u~8V#?&1?T~DG2A-%ss0#){Lut9jTO^o7XbOO^$aWZ0J}&tu87(y2Y~(1HY(A$_%{ZAbB8PGgio zu_^*Z*61br>TG>s`?qL)g!Hvlj4=6Aq;0g+^w)Ut`LAHz2NI~FC!F?fpKZo6;&3(b z=T+lbi@%FBmI!@KFgZYcTE`&Jf`t9rh^%S2DL|}W|Gx=M)o2#QZKsK5eRF7$HJO6~ z#5|1*0xi8p4Hep@jb=qW2L5pe!?Oj5-pw6-AhFpxMEH_5njPP)Mb@-fTuY2<<4B-t zRqi1|>Fm+$(;KbTc6nJ-%+$po(9+5>NQiWcW`|C9{UcRz6>ExR`#SnSqTZT;!gKd% zHve50^6|i{hPYsaBY~)hwhUUbP# zChnT<=mQDgDZPZwO`@6fL+jgPmI&gKC5{BDZr1H3RB9H@jACQ(m+1L%se-tlIr=~% z!~G^gpVQ$y87#5*h8S!hlL7?SKjR4_n!5B7# zB3;a>`kq)?yb8B%sDjN0w9&u6({q)mf_E7`$9**`V z1ls3d+CB%Zg$fi|qt9g@WIOebj7QJ|O`T_xO15H3zJ&d5NT zzV%ycgE+w180n)0iDAz+2s3(2w)u!TnIw)XW1O9U1ggxb3OTw!Z2FfmZa+#rau4c} z2VJcy+C^a^M72hptu{Z)n@93vgXx}S}7mEr8ffgi=K9H+(NEUUCm zY#eCh0|`_eDs@>nzaos4)njoEcUU1lSu$KND^%TVvQ(JZHG(av*-$VO-S@8$7f&?^ zv>@T#cd4+Ta|8=)sg00pJl!Eq88=k-fdr~3eny~J9NRo<@W+)RYj5~K3ld+-E)%Xb zjbIlVXrsQ*7ZSzh?T!0^1gdCF7EZG&mu8)Kd9+bhXhCAT&oUu^d}NxU#o{c;uujaG z3V|wGjTR^thZ!q(6j>uuWR0G4`%_pO4cKd?HqWH>eeFaC+q`zf!Gj`2@8|?tkg(S` zW0qR$RH%65oiPG<-g=_YF(``t8kI%ZF?6DEZbTGglk|ubeFUKS)}vlTih9v~*xQ=6 zlS>gW0>#EK?b`l#gYcVc71OOZ`b4xKv87|6aP>nJE1s-H?=;NSQM~G8jAW2N6_yCa zz=&khuNypLijcQqdmB1enk>N^ss!V;m#%(WB6t*ec)!t$9cM+=uM zQ7p(skCTD2s`4~kT+q=VFjYuoITtM~{T0c2m)2r&LhnR~t}c!Qs)9>T7fR2IWKD)^ zaWa7qqQrmB8>{DNN$5XaxG^)5byf0f5h;+Wqwz6f${d403ldHC%@NX6jbtx+YH>2L zHE89wy(59D4d>yh0>2A*v8hLf23-2rfK4*_r^K{ zrV5F@LGeO{yAjNtqHJj2Im2|Zl5J%I2~-sxm>`I2BUs15T4aso>SD1#w6R`-Jsh?V z>|OO(HIZV~^xBRVB+xg#h0SJ&vzHn9Kmt|6pC<@MsRuuzRHan?lXr$VceO#F1qpLL zW`uZHPyI6H2DpP!w^s)3om#ekRKY)XGu)%MTC>^+`%Fk{ok&#w%iaHL%{X>FOpD&} z8+q7z&Nh!i0#*4^O8W05qK%tIw5eE7$o<1e6oUy{?)>XWplZw7oYv-*;+RWGE#Buzt{sBc8-qZLuV(>k zLWMXsFE-mBsoGX8S$IHEDO&kps*sp8sFgLaU>ti_ON;k8x;`ECT#f{)1_&Ljja}jx z%cBurS{Gq`Y`Ym~xpjJ;^(w8fJl~T3k5t7KXUrwh(FYPuwk@_!e;UiaEYsqBYVDrM zp0sx)P=&oKowpHxobB9i%u>;U1V!>#Dc(o#=V{+@*jGmJKBlLER&J=W|B?~!6A_tF zN@qI@X+%_h*1_-h32)jdK>AoK?XfKEUphTW+i#;Ny;>Qi=bzf^KF~t@=f4TsC1(`X zqto84OJ-%f7r?=wLMMmkO1%H=fDFliyVMct(#sS%+7d!saePG=^f7g{& zDBDl3OIR!E%hvvRq_O8)>I7Pls8rjNmGbFqtBLzt&=<4bHgh0QMR7okB7|(UJyW(K zQsss9bpkC&-0SGehK;bFVY*>pVX1^m0|x?C6hFf#LWmiqn?J9I^tnwPoj?l`6f>ip zi(?y$9u9MrC>FajQ?#p37$ zT9CkzvmT2hQY?-Gfhuz?q3O0ru{b(`79`B0aBHntvE6uMw1jJKID@p028=b!#n0!8 zF}86DT9B}hQH-uIHUh=su-~ybBE{n9`9K0ycyA#K#eS_3bmpKQ!)v5!*5+2IQA88G%rW0sE0#CN0cV#^Nr2I#{9SBs}Ptr2-@uUTl z_O&Rd6KF||&{A%(JnLIW>iDy`17W8%4V^5e$E6xR>bz+z1q^W23A7+#E-Q+8m9*H` zKYt5V_G`lj#nnn$e62>H#eS{*9q$dT+&O!w+5f7e6RE{=YQKw7nifmV%H`D6wzJ#N zV!zf1?bJ8zzmcl<>8q;m=)dOOuF|eiMWvvBS4#UkeHD>@U-P3~r>4?=*G$m;P~m?3 z{w=#oBeav=w0K@4Rdhd8`~9%1G=Hd~a?`)Hr~RE)AnBwxxF5fN%dXOX*M4mfTAVZ7 zkKey#S80THil-I_ZKR4?lxlBLc9r&9sG|0$f057dL9JG`x7yTH+V7ePE$-ajGoZzO ztr65?z}KLt_fhS=k6opCM-}y5`q!t7R8bG7+IzUvRGJSnp+(8sdr`F5uQh^t*Wcd> zv{tze{T_{$0E$EOGMej6>R5t=_bk(5qapc5Bp_Gz&oVZYW?_@xAk zrS;kI>X|heM2)beUH>Y9{aX7wev^ROp!)>%{;+lA&1^x!?oZQLENQ1qP^-)z;Xt6u zmM7a+7eqRhqNtCPPM`$|b3QzajaNHAb8*N=YTwE+Qq^(9IJM$SPZOb8khs5|-l6~A z#`c|t0+D0XD(hQ15U8@%H~kLK`R#8*)Q880=mc7jn7lcPm-;xy=A%_qusZhdNjia+ zfVfD$;_P%?g}-F6JgPcMy=a}{-~$QYgb4aJd4kQy^`SxP+G#T#2vp^!w^)z(F0&DJ zod>8LnxEB);A-Rfje04%#n$Ha+;&|U#!nx-Y$N9IA*$QCJvxCFB+U7^yf08)HE@js zfvP4i!uhk1Z8jf0hKy7TlwY6|XhFi9k3}8YtLtiHlC=9g!+QWvn3!Lm_t|<>y}lJ& zKaAh5oL&FB#j+)~t6C}Ii|zw0NMN4m?1V2p)soMjI1s4H6EvFlIR43&k44-1s&(b- zI)N4>u+-_?DE627tXOu3e5eV1xT}x5L!M|a^==Dw)?6o@z_cS#FQFsP*uu+}^Y+gg zsr;~;1A!{r^HDE1I+wF$ZMApf5;}nvB%b$c$x~YT+I+ars-Yg(SjK@smHDd+AKl7G zO`K}#1kQf6W(&SoHXdHpc808V(^+eY$vO2OVwAJ8BE84%bo?HASi)G2*t)wG4a_au#1TyOrIVWVCuf#= z9i&tHGwAt13liph?5H0kt(-ec_t9fk1Y3OH=wGS#(dK}9K9*&VU=60NwB;irB2e0; ztkns$Ac1+Jw*j*cm8MnS?LeUF{mqFiSUhg?F)U?(v>@uFPM`$|EOpv_y*o;JIwHy; zA3@PkEV@9L{=1k$i>1!M(bDHFeRKjXNYGQ1*}qX|u?)*NR+|5?z5{_O8b9bKhH5Rs zVxi}`1kdx|medI24$??Qf|1N`!v4FOibgW*f8V>K(UN2zEe)c0{|29hRhnu5U00@S zEgdw<3VMnvURrKHC- zYDxb*+bX+G_h<4nqpy9Gp&Z-l-i4*1avSl?in0!gyZB2MOZQJ+(&*+)a(PjS zqXmhNx4hV^b6wf>)1@g@zAMW~xmO6%^)$6i1gZkAc(K-Q-Pq~pWr>JfQ&T$Bx3m;h zpo)y8==r8Kb4jYI=L3Dy8&$6b$up^(RLJjb5?YY(@vG0;JK3K&oBC9fiqH3vEWPrZ z$_iCjZWhbqEUlzsk8?`{KHaij+uff{d+Wl&f4Z;@VFOsn7e?>guufa%yT^yEd+0*> z$miW$O7of4crztg(Sk(XW!>2KC8cbA;;V5DC7)&P(ttHj6DS?lzb zu1>ruP92m<$lYr^>#*yo-hWhlKAN4sW{h__TSqhJMPG$k1zagr)}&ri-^Y){F@-Y; zXhCAhvytqcTSl9Ym+rKOGw_qRepo&efhsH!IxFlzN9l2+bW-0tA5CS2#LdP7S!vn+ zjPiCHXSVG`lO1Z zTZjT$kT`j067#IQPjIiKl~vXU!=$&?jbdDLPZNQv?uEkH!+WyL$Kiv+rE`6ji~CMj z63~K#Yg_sfT(#vk;_^J&39m6j>~L?IfEFZvRE=WadxQ%?jkHvisum(OaULV?`##Y` zpsGZC6bsHb!RDiRkx3>4SbeVlaQMj7#9#`k6do=ccQiqezENQu0OxaQSt z0WJ8uVLXbR-eaGujhi}Jswfp*sO4U>v**(w$~s9Kxm4P!&w zT@&(A&fnz=V-@Qf*Aq%iWMOe<1ghGU^F2cXrKzRYiCG3$6VQT0z4VjVp0fw^U!t=n zH;t71e$5p}lsaP~P=zHz^T95`(vPS~;_?2@rm{j}XYa}E=i;UMeWG(%l0&37K?B93 zSN%)`s_@RzTPY{oNi8mBl6rm3$8)vq$7VcrV?K?&SYGGe>}LOB%$Z7IV8CEDyH8%0 zm#!&QdAdkmOMi+-2lbVaKvm$$U^Z>hFQIlnZCtYJQ%}iv-V<@`<8!iC;gM|m+)Vm! z)h#iSm54R2S7jN+LYt*yJw|DzTX=mhY5(m^ zq)yYis7niJ-gIZFe7V!6kqoNvKGB=^(QPE}Q`x0o)5@9dITFLO_GYt!jr&jQCH4N2 z&TPykE!vt`uCFxDGnk_V3G+DddH)L1 zl{WrTt6xh@1gZ*d^I|>z>CPH+E7jeZQ57Vo{eDtFag}EX@nS#yda-QOa=NefWBV8V z#q!X#naFk4M@p8fN_o=k{~?|{&1IxKo#bXV$#}$N^ktX z3O8QgG0g#Te~4y(W2ZTEkg?u=Dxj!^H}MxqBX@MC7YTERGIHbj(Ovx8G~KK zw^t)g_X7!hKGK=X{-M(LgHze*o(D_>s?77jxAZ2t@{vaP#c!Hw2@>WpL!F1?B{d=~ zyPN%|i9i+3MQO)`-fsJmAv>Gwx|CUIJm{6>gMaoDUTjWCEW6Mo#(!4UB7ck%Lnlp; zF3jq{-j=p79OKN4h-LS$-O%Rh8kiapj#nLZsf)v>;AIn;` zrfEcms+POyjmE5ke~t0l=rvc?3DTzB^O(;fe})z$a8yfgXSSFiB`wU&(#B3Q5vY2* zHI@~q6X3tRi5vMSRBM7XYkY22K4UCH3ldmv7EAwkb*0m8#Uyphd@Ii4aF&YmM2ls_ z>$=j+BE_V|9aru}3li7|(}^FWn@HZp9{_#fwRpz-`#`!I!u<3cElz=OH(Sn5e z8C7RpC+W_iG}8J4H%zlTRNdW(U~@Fv{dui$aC3XH zGtKB8#vT_U2DcMiex&&Mo>znhtGf}=K6H$9yH73gNz+w4u*+CBY({N%?{Qu6W6rVc zN^l+abxK_^Ic^O5Ye8$)t!^_Sats(Fb!t^ZtbA`LUwkQqHTuwq-Of~7>@p>UJ>T4z z-QFA^#*_+S_n&rRm-;m(LL4zhnw47+7yUTMD^wcAx}Ryuyw2AU@41X(yE3$58Mf9C zd!7zrfz5icq#g~3csXx^RBg&ZVWwY8wxdBG_HDE;s~qx`Jv-co<;_x=O+EdQZClri z)sJh&rgpaw@qW=bY0|(rp^HyRF?*Vc?8Ek8;bHuAHa#hvl{@Gyl-xgoy?!@|NiSy# zYiCTPzT`#y@ltc=%dBtwS<@U4XGO``=slV4BZNW?`V+CX*f2>9+A1!VeEo4=gJay? zN5-*zv!4q!69*CTW+{Kz)hIiRh=Tz&q)vN_NZG1& zR{nkD!M@(z&9;=xCwgD?V7Z#^Wy5_6h>gB@vm6;Wv*e4;l=Bb!1EiR4g`}|ib(HY6 z9_(a6h56JhEH+x^!8Z3-+1FM@#mG6{EHKwjHg&T*5q&GvlMXl+l)iN=tGG|~V1=_D zVn6bh5pz%RV6AT+V$uvx@%CVE)@5)a%eT5D5qG;bl-@mXk-FW?s*IiI!4Bs=&f+rr zh(QZH7z;hl<~{KdcSm`%VqX+CEU5w!HNu-o!O!zb4?e{3pKmE2?a#0-m1~NB6)nNs zTb^ZyU)2$pO{&D!-#x@C(BJ8F%8iYrYv(43mltQ3I*cyMHoT&bp$ieBb$40Ts@Wvg zIcKDpCcDU99vQ>B}q^wxN`d}Lx83aQ?|@ zvn3s(Iq`yL4m9bVA#MJ+OX@Uq7If#m+Oyu3ZPJ_t*F%iV0v5Qkv3&MJ?(LaqPfqko zNkdj~O!{yy6sSUpdOi4vqx}xEchNqaDCfCR1>d(x)BifNS^2qjpVeY+2upFAUiY`& z=O8vVE*BiTRhf-<3*p3{#Yvc$zg;^0+e}a>5%hjW9bIlJudKk$WUSZsqhz9|ArRCh z_R3Nx6-~!(lNuYn2dYrwrNw_ozI}sy9G#D*VvgrF>HW3C0zqB$jPUx@SE4ca>T9X! z#v64Pb})zQ0LW#ZaM7ffytDrN6&C=k?T;}%*+*sVngdYWiHq1de0dnE2})(`rWnM!85GgCeCL}-J4?y6VDbwpqzndta_0M6gc_h5ZC z6sbZ9@q6xRu8S2*ETm9v6bR}Pd&O+}qUrJVlF!9qNEJ%Z=L%o>anQmiNnX-+^AQ3; zUG$9b=We<_t_U0pv+kQBeUi~99Bq$RLSVX>H>x*`f5wn1l&Jlo2L;ZXCHKZN`MDZ@ zr7zBXUJs7)Umi+O7kyUpk$y&h%()Q<`<95$UE0Iz_w^v^>I>=cart`O88--5l`e)0 z6~;&vN~q`J`_iFFbp=dVt3k0te3F@Lf?sh`rLCt2wjDj7SDxI)wg#5yx6PHsjOu{1 zzv@Dx_YpAdSq?L8z|ZL1sr^jH7wK3$mC zDTC*L{W}8K8#5M7!V;OqDmA2I14{Hbq6-h>(xJ1dd>ozsSfQ_eH0w0Dxj;~t*sBto z(U>&PpLNJ;i&UXR)@NPFogN9R?#pfLu(iZyW8K-ewe1Chy672EDBd2l!jC^@vw@8p z<9IiKt4Fe-Y1<5THdGgEdd&ipj@fKPv@W!s$Mf!Vvw0g&k4?ZGu#g2cX@Jy4>8_f( zu%}}lENv@~OWrTFL#yda*xMeT8C57@y-5O-+BvZ7qx@`l&9+9v*UOpPnO_1yUD-YP zjp3|eqIM$>Me(bk1`mg`Rri04elAS zmL=GI5fn=N?5YdPOY>m zft!z)!}LlyDzWO>B)kx|k&Qj@fKi1Kt)H1e;fj1X?wZDl-&^f))!7oZzs)0ope|*a z4%BYy#>;m}brWZ_9)5^@D6bL->Y_d5D<*R%;nI0k zEXUyjqY5P^cQ298@dr!h2y(-wcR#ydry2K;j^}_)Ro}FQZw=0Arr$@Wx zU|)F8-=oUrr0_Nzo4R20&~t2r=T=4)N;J(K3PV~KLHFM=oN!y>h~xdQvYC1%0zqAS z7xabd9i?!;m3#%~uXMp#3vRMho2ATPuL%@ZmH@MkWcr?cVNt|xFvv}0l$I+~IO3}T zH`#;fn*@atHXVLWV0xW(+s;?xNPnqI?3K|i7i@aq8LRo8#*Xp` z!)*t4!$ZGNc3`_Um<&?#_rPeOw>;7*!wEg&pR;NA=LiZV3hMO*?{WLV!zGUQs#l;B z1`d6~7H`dCRQc4jFP!+e58AAV6Fy0yP<40WD;bYjkMT~px6>ci zX6$(3$m!8OdfNxyY&im>Mor~y7@N4@!<|3b87E^#6-xY?U<}3Om9Sbxe!J^c&k2Vn zsNj}6Lj;1lMx5>g)z^>0kCVZiNFC^iF;g3%xlR-IcTgX2wmSuv?R;69dmrfE?j)F6 z__M9EjbQkm1Mq5zCnrh+9r3(*L)_)oR!}IByQB}y%Q_Cq9f6!!zrYzYs#GxjhPpsd z7ww@!k$A!p|BR@QSs(f^s!-zC(mpUM@i=T!%599e>xg!H?={sKW=;*r0t?||0F zn&FGd+o5|^Z`k+j3}oDNXFo0(!jtCJP~LV5Ghfmhq8Fb9>*rH=8yWeI`0;8J^q8>_ zs6vU|nuc)b_+f}jbK*pMw@ElNz6EZM$QB6d8tva39*3NRHJOt+alO9-9v;>VgR(1x zUfn+18{F2Nfto@Op@%#k&dC8ib~MEgp(la%gc6&+^#-fWr(wZrFW$!ag-+P-Nkh!; zaz!AhOT6aQuN?3}QDZFr`U$8)iFJMZ!1H;hp!T{v2awas5tlS+jK1?#glkS+^nOz) zZkO9(*UM_y&~~8|wO7_!2R412c^g-<9WZ!o zbM$(mD-y&-uO@#hQkjIBE-ld(oq;O!b6dLfhQ0acVAm-Z-bNptNoe`21)k_1DiG8q z-X+$fZ186vb&TKAR+-pG3w}qQhtcy!vCdvvp!|3qeuj=?-@FFF)e}b{dB#}YhLMde z2Kco`yGi4ebQX}#4vIwn8Ee$ttd4!InJTG5iH2HQP~&?Z+D{zC+fd%H#zo82ao{Cm zfuJthTfQ$*g$>?W+Xe?*xK&B}{yRhqhVkov*>?Ot$KkDJi?vc4%zw0|lJ<%cNh`Eq zBBwoP%d_X+yX^5sv?`iAUustrDeO5^oN;Em634eZ_0aFi&6FH|R;^Bk*dgPV~1a;AS zfk)%coq)+z?a+{I5$+O7tb3*jwc7mNWy5$IjT93xc1k;J>9|}VsEf`<^I9(*t+4EF zI~>&akCM({)0u60e0=AVh;eAH*%8y*{T7ac5*rIN;j{82ybT-7d$nA9JT6_`0lO`J zDG<~}&$>b}WYAbV_N@aJ-_WR{Gx2nWp7xf%b8Z`rOVm4Kk|y6Bn(&+U6M93Q%M#m&8}tLVxIT`{4( z;W0C>#eRu9s-S(#}elv{_y;xiD%tw%?_}sWAdUU3Be*k21cQ;e;W* za9MalRdwcIm~OZXw#@zr^}cDrL5oe`(n!IM6d1thsLi0$x;bxSSL#sI$<)HOKT@lx zLW#BywZJ=IGYk$_;Y8#cQ!m8fAaM6cwp$$ry4b*~-%XfmQo+@vn)5c+_QPd6FfAtm! z>Y~?)$3}f(xMxidysq>St{^2GUulA3Y8hzFZp+(v_Y|?~*Y4QE&s`v>i>{vWQTQeU z+#9WjFYR)xrtj(lhU)o{G3Y8hoYx25jav-gwXVY&6Jtnno(1|NF7lPQZhs7LKpQy*0OJPQ(>LBm$!BAn@7D)mSe8Ig7rkTnj8}sJ7&&Jkszydv^;y>!#&ybuiP6O% zh4zJ;n{%LPN-0E78w#I0CBmWe+j$#Ry#`$7R#t&ACF}E2n4rsIPB;#g3r@L0$B$^T?VG1MqZ_A--f#^`NsZw7nY* z?G$ssP*oQS^I~9$-CW3iAwhDkCp6qNi?>nTdH{ycG{hb}jF&2unDCv?=$wp&R^#S# zLci}|beuR4QPn~qsEeKvzW>L4eca^7b6G-dg>yxT&xtxv(jgV<4_Lw5SaDS!3#$j= z%*B%hg1YE=u}22-m&nDiG8~&moTr^B90r z%8k%#hPH67C^2ECE);AFg|AL>kB>(i!VpYeIuKO??lyA+C zV@Qj^SW;?;5t>hwRH1~}hWlTAOm8q0Q@36a2Sm_ zPWQrgOAiSIbY|aS3dPT)2&{g+ zg;`!aYDQyNXxs{or&lQKv=ec4vJEqE2?m;DKyw<}EY5(kxLrI}Ac!CN%%AaC{Vsrg zPaX+Wp@bN9uXq)Y(^?0y!xh5?g1TtTzCxkhKLw|zMOMJ-4vgmW(b!7Y7P+vy^#L>A zu8zD{c`H&dIr^()-nI#&3MFWiCXbYzkizRNEtU@cY9kQT^`L1E{Lp%9hJ$=~8_kxb zV3dA1WG(syRH1~JY0<|d1+lqO+OV-LqXc!mIFt?QEq%R|tBiEm|5?GP zLJ2W$Ddt-;Mz7u~?OfVLAgHU?vn=Q_PhHw_Q2q{{)k(qlTVXJ;v^k?uQ#6{2(h9|g z>SP@6v_g8X-;+^=5|ZRl|+?WqZ%-(P-2=< z3^YprE4{DT#fkHgDR|Q+LpnHCO(3Z2`0WVzsPaj&KY54~)=!ghX{QXS|3?j>SC%Id z;LEx_QsU`NLJt*+C6&oIw=7;dFZE)yCzJ@WO@qVx=1Q^YOL!alT~n~lEq8cxOI0AK zi(V)G&Y7Q#71`6J>(_beVi)|_3tAP)I}rf`1<*N zJ|J<*kxmS0%;-6x=gR$BI9$~IE$JUR%G)@por>YvlVJU~+dvgce9#YtDG$5A>F;Ma zF|$P~X1&Xjl5~Fv1a)a_4F{LvKhnB@W1QI2g~tw#T_Rncvk`8Z2Ee6k9Wed-3g$Em zf-%p!!MFSeFkn#te7|iBH8Y-Y!ivWs4~PtgZk$T8A|JTR#t4pE3If^Z(J`B z)FsBf?%$Dy5j<(*gcHwPI`H_MvF5QEOf_NoWDDio)4;0-`fcL+9aiVl(Dqbnw z0=EXH3j}pNS?UWb485Rh&+eRvY@UXyQIjL8A!3)VKu{OGvV2x8JPmj54}%ZOe+gHR z5_`M&K-CUs2yP&^5tyFF*Czbn>*L!3L0$BI;}MOUQZQEUI#{jWrd+QU0J@8OAz-gI z+g0TUCec1%zDkol|LqGQzmnm{0A1cj!HX2!Xm$n;^<1Z<3MG8g{J`LwH*DA_UypZu zWN8_v!hY>sDG<~}uMOX|hw)k#cPhYR_97)!C=uJ(4~Dk%hItoz$Y<9-74P=k4a?kS z3j}qE*W4s92`#(!VGoxbQO=nk40o?4^7Snf_N1KuZq4z5)sqIY{HOr%jZT5V{sz2_ z&Lfg>%%x_`ee)$HRVZN>7z{@)`oM&p131y$g%e+!u!}D)2n2Pl<|F(vU0>L7M~?Cy znU{=PhVrr1xzkFjRPG6cs(rq2@SEO0y=wI+8E=060WCHi7TTc1ih}`=Ug!&R(sXzm zMPrlk%yxAatlTRQ)J3l>uShyR1?|^8g#!Ei!WE=M(#Qa~!oO81=6!h^CVnY62p@v3 z+FpU6E_%Q5x}1(lxVL=|W_tU!^0QAE*VN?gAi0?QYBL;E#@?wk~^PdsRslN{C0^FCh^> zx&j;atx_PU>+k3=n7=C;TFybga zr=$ucN|aI1*V_p?yxTofdLzz#kW*|z?Rl{B}9=KRoe$m=J1C-TT; z#!lWkAe>!FMD31+gajK1QRMH$J zn!7}M%h!th6VdauIa5pDAsh!K0=yF--+nB(ZyCXR)gT}dU-Dd~Pl>w)g1TrH6wl@u zk%-U7TC>8}u1b$D$>0$%4l2Leuz&(y`Pm1+Y{Zy;yn5=ObU2qg82np}XQi#v zVM?SSOgT4>9dt{BAwlNwD8Zh$QT;R#6BZ6*fBR)9sX~dvk5fUl#su~(kXQAMrzK)d zy9sRYb|ZnHE_z1zy4tQp%o%6F{tTKgoGVH+tVn^!-z2!}KZdt4ep@2ebG2YSJLCxj zba+uUZZi#Z_}uXWoe6B|#dHYVq7Pe!TJbhs z6(yl)Z9CAjv1L;|=|9seQBtW)sfX?6DS@x2QA zS(H%Ulml}do=FQHJMdna>89YK%^g_dG@5E&lRhrADLdfjV|j_(XYV;coLj1QH2tRPfiE5tc_BW z%W{NJw^^weGPMSBOJ)cJbz4HKj};JEyaL^Dgz44Db}$Hz;n7yX-Ms%4gj zD;MQKs|C*_ntw_O&*n2>=n;46k%t^dwtf(QW656v{Z~E`2$6h{*(_RJQlUoaUUX(b^ckn$^v({{6 zkSlMax+o2!k8}Wocr}5buKD+7!i@fx%vM>+#PVKKaNp09RP(s^~7+ev5c`8D6= zf`RoL;M(=s!VEnn#0=1NGu-iz$yc^vX|6y}*NU}Mp|f`vP^rk_Z}dNQxL~YQ9|Q7s zD5*jT)fMhw=41#p;nO)`x6>ULS$t+=wYLfcb^ZPl2%dAaq4;M$Ck&6eVD-RycymsT zk}8zwo$LyaM-2nbnM*n0@YWsY-TS~cY&#_o)b(|w9|Tkx!Yb7boOt%d1$(|#V9T;^ zN~%yo#m*VFyIH~Q@Xeg)9PEL|&EB%-`Y#27x~|%~!?*j^5d5i{6HC`kM*C*JS)Y|^ zRaBuwxtkr_TN(&fZ;o@~fsH5XML%b`I*kQ_x{PKzL%__b(E8;)PTV@}ih5tau#Agc ztEfVWjA%YPG9nWOggoWM++;7@a`_=s8K^1{)U|5(Bru4}f^_S@oKW?1!}5CX*^><# zRaBwGf=6RvTc-tJzPUcXcYkm3#&vFY*(8q^0zqA#2khYFC0;$!voR-3wz^}Q=4;k` zT*oS^P-11#7`Vpgs4pLsXILCud~l>*E!*MJL?Eckew!_vD4P$ZhH9KRwZa2+*1up0 z-mR;sLJ8fgqhV6eO1SeuofAV;d@tNe3Io`)*g)h2)xWV$J&q_*ASC0=i@L=mQ2-cV9WY+n4q4|a< zY_#(aB~>Wl7(5yb$83TNMRKH5PXj-6xO1H~x^Pb*sLR077RJP{f@AjDoY*+r8+$f+ z%*KV?QBs8xY4=9M@-IcudtiS~IG^>yGmmQ6Ps3vZL0z%K?cnvuwa_O|o&(6}?}M+M zA2N6U3MEx2@#fSRaLp@*CufW}VUX*OWy`KHJJ&*ipe~g%dpPr89UOijztLK7G#Zo~xOlHe;Wy+MdTP?zyG2Y9Q_^H_$+k${8K{BY6k zS~fC5Ur7~8WPKhFMf0^e^TaDYxHMQi8e?J2*qz{I$>`Wi%&Dw)^Ab z%{N%Yf%Ho1YNWzz#C<7-X$j+)Nazg@zI*e4gA3aU`zZm)@uP__-;9Gb}6=zAdu zuYNeqZhZDCrv!BwM!SH%#u~UXU#_;0-!2e8&brLnx1K9eg%XFItYPW9BAD?@9$#&q z9gHWfPB3%J#R5THC!bCR%kHb-a-JMv`toTY+VnWj;8QoC3MEFav4IZ-n_-Nm9DCl( zG6d_Z9$^cLx(ft#?F^d&gBLA_7U}Z)hg)e7o@;T6h2$p#RVeZ7i!B&z+W;{G(v?y1a+zQ@!`7x&VnIF<+13s$`CvmpPS9WzwJCID}K$}sK?`XSG#q? z4j;p-s6q)bQZ~1G6wVvb0Z&DG2n2N*KVq=A<4QQ3ERSBu>)$Hv8kd8CB#_gU$x`$^5xbT zco_wPy6jy6YIC>1qxg=zjmoKGajQ`~v{;K(RH1|z-|k>J5ue{y!&1Zk0zqATYXewu zV>>u>@5$Rx>uiPNb=9$pxo#CzC?Q7nd#tlTm#;0+H@Aa8P*-t(0Lgn7m_Lx$al%R_ zV&efk=O?dq6;&ufGZz$!=TGf0N}~m?c=t<53F?Yj1F-1lUWhs^f{yrGP=KvfVV(5sy zm6V_^A1!mps9z3-Rq`z7oNmtecTHn__NViHs!)Pv5AkRFC|9iXsE1BFG9*e+*SGo> z(4pCWs5X&z5NcB3f;T=jz;_l+fhv@sS!sNJ*J}!X?4rOpV_kuuuI-;J;M0sUSh`uB zhr6(QGB%2-hsS;=0#ztMGZFbbb-Wwu*8E^EXU!1^>Wcd`94^Q20naA#7|!{yD=t#} zWv9c-fhv@snTR|GE7cwKW`AN&c@_{Qs7pg-B)mJj6MSvtF`QIB1rN6W#+(g)0#ztM zvrl=g;y@2PYx$bBE^fdmL0wKAN5RQyCD1Qf9$7x0?S`u~-m!yQyECd#g68uo6j{2S zc(LVUcJ+R5fuODrLo7jS!B)sgmq(TXy6$M->nR)4WH_S=CB%GZ?cJWZ_4zHU^k(l1F`~3f!=CSUC%6 zw3ShX60{0~LQ#9e1HZp5VP$$n0zqBfRjk1849`>;AJ5xZHggI}ImN8s_ew?;O3=C% zd^YO1JDQ#!1cJJpdQN~-b8^A%ZX$03ySn0_*=yLjN#__(a|y=y*{wV zlBO*&8s;l$9Y7i#PiJm<^k-9RJeZ)4->vx?B&ili2|5nuSrEIevB8tpn3;V^AgGJZ z-17OWx#RGcYDe5Q@`sWtl%OMLem!_~n9N75@cYDiRg|DEI&;h4ysXFJs^{%7wSI>x zs!)QCocZ@W)f)ZRt6`6Dk)SR*bIYUd$Be`E)7#-5wSHApp#&W{^SU^XtZ`#;OZ5Jr zD-hI0XKodWmG#G?N^KiFRAyd96-v;NGmrhyvBmR2&G7gyGl8HkI&;g{2WzbGnx`6W zW#g-;LJ2x@=4%rU_E=D_F$Sec0zqAL=9cf~vDX@Z9dC}?Lq}Fog%Wh+%%4}K4j9?B z0saUbBoNd^XKwj?dt*ENYuywb?1xrSg%Wh+%;Pc)o$y#fJ>1y8uRu^2ow-#gVz1ld zv#BX%K$B!Fg-2ARpRG|bNIrBKO zL6fnj>0j2RV+(n#O2VYY1poY1ma6;&uf$H9D#Y=bMdcl*T>u64H_K>Y>JlXG*G2f{vVdM0^J~99{ICb@V?W5Y$CyZh1ZATaz)rp9&u6vqwo4 zO3;xrpVMFAj(4)YuueDg1cJKg%q@>+*f0gdqW-Y`cS4m^p#&WV^C#R$PnTg z76|I1v$#CgdA>V35B$z57wi`1cPT-~!F&$js27%Iy=DnJGzEgX=v*(4h=1gPjhB96 z&HWFVQH2t8#I&<#KpO3-mIk1$>6he^Y4vQJ&M2?TY~xnBN`bIk`UHr-*`7w!O6C_zWg ze1{4TfBdrWGJAdap+Hapnlp;_EH%j z5Y$EIdU=(!seb4mzLSl(md&U_2|9A-ar!d?P@~=!_98A*AgGJZ_42XLXJ7o=Y%^=N zGM`a}5_IIu^Sqh|V2=T-S+v(efuJrr*UPhI2m4}#>q>UG?FL2_O3;xrAH7=n}HY69yC0~s6q*Gp1OIdJ4W*TAx(Q+7YOQFKFk)X`%Hw`vD0`P3F}>OOMx%5 znDCBKg%aY-_P*>%*u!Q7dlcLNDM4LRlE*@2>Oh!on#J2_tU3_~w;9Nee^o=OP@=Qb zFmP&W2eqTs?7InXMv!ui$lyIJ3tNIZ;)$EhOe~3*~4eE+aZmSR*0k( zwCTGDpZ$1ejjG$Gv*QEn3$-RGL2GI9@zody46Ds%A6k83^s}f-e8<_g&K|#SN?_}B z6-X6I&{~@Oy_Q!UTKX!GnQ5sA1a;B##_I_8wZZf*j_g-lQ=|$dGDaix|LF*)x60S! zg5Lzx`w8sD88v~RE_$YU721J;7+{&eHs%+x*i(L>H_IJj9!4>>AMS8U%NIr;i(|FR zz2I?+QSfn$eDAgm^To*!%zBQi78FXrF&9|8ZY-Smlgf$86Q1~fzy!9v|4o6QuJ>15 z;eezAiKo*!F|^VZe=m{P)dlYvRVcCPj~&=Q?guMpWpEClz-5)e#8ly60{I z!yINx9}{FExWiN&mmSa6T*+f)4?^JB9cN(A!-T78R2~SmzUFW{A&wJauLH5#HH6*O z+{&mzufKTB@4ffK_USgvKdo9Is7vju54_Ln4f$W?T9YdldZD(bIcr~YgHeSN^g1aN z+vD8u&k;>Fui~vhP}iM&H`x8L5foR*PdN35PWZ8)HM`KXK2n7e^vd#HJ+i|WAD@EH zt`-78U8^@Zz{un?l4*1K8})LW6)wNPYbJi-m2Qbb33_Gu?h&^vabAzPu<3U)jl7XX!TK`9TT#Yscrv z%6+iorFf?6c}O6ri+<;MH4-NeEch6}W_#XXRG|d@?cx!?KPKa|Lu1(9qW1zpUGzK8 z*XYe0FzBQ)dzst-sX__*Ysb%3u{HLZ)}Cz+Qxgd4qThLiB4pPXbXr-D%{A?eRH20U zJNVLLIJO8s0ofUv0zqB$DZ%6V9HVhgx24Rq>FvsflYK#V*aBESeLQQiB?ww7b0FJ& z1j{Vp8CyPiFjFbV``lg{gV)OEvM*l;DXBt<#HRsZ6*nF7_R3L6@@_YNKbEo=hr0;` zb@k}x1@R5@Vf9^k<)_Kjcsy~^k40!r7xGxLriZ}k%q*Dv$?~7QU_5syu$C9uC|{VSAz^^Rdih(#QQ&p+u#29N2F528)-Dyp1bT0>1MOWGkHAD=9%; zV&24`l6ahv7sgRJxfG#cj1g7!SwM+xepSsuI^`=@x^ zTN=VHUwJK2g%USbC&78U32?2IT#BD;aJ{WxN2(6=pDmj zw(mq^1E+lUp^>pERVdN>O8}&~&Vu`AAp~+_7)5 zm|dL7)>ruo1a;9nM&1`77LDU_n2~8IP=ykf4%lNES6+iORE+gK+66Cud=UuhI(|A3ENWAvFRkVA?%WN|=zlT~tTGxRRVZ=3z9&4WohBVPD!&yS z`(=wgqldwZq*ek!UE7P%93mXv2-We+@>x?jkWDjr=rDA>JeSKO{Ss=EU+jnbC>(eyu%g zu&4o0g%Sl9Qefx;3y9&{k@MWXBMEr%t35LhnJW;~wft{7OdX*Ezs%)PM(Fr>bo}7T z{BAt~s!-xkNh(|!pbt4ga->tcTXE>+X2mSbIx$L6SCG~;(CXR-q$K&?o$efqO<#>< zX77eGs!-zf&lDKhzCB3U^4T3aEC&Cq8psy%d!G{2WfYwbXO6#>cAS)>)zj`pBEHpP zoupZeDwJ5iA_-!DewHqmMsuQny$I}ax;Z;>bEQB~SIVUnc}>%rBzmkgyL!n2L0$Cu$fMilC!t!6HH?Wd7M`_~5c6vvsifet?&l7t_Pdoz4j0#u>Ijz<|VqLV7z^^x~6(Y=<4`xU%Bk)_)PPpf_LAb9d zu`fCezAX=y?vIvd&okqvV&CWS;JdR@AgD|HMx8WwLoJMx%0K>QbZ<$zcdGcUjcn+J ze^U=jH@dtNcD$s7*oJnHH?Ln}1QY7L5D4m`&lrAR-3vsmxe?%{a!z=bP=X#4ub>MHohuzegYP>TPFQF+a9Sx3Gw^k)Nm52MR$h$jV%R&y677+f5LT|f(5T9 z!6qk#@Fq+N`YXz32UmIE;m0eXRmcZMKa0BPo4!JEG0qn=ZIyf%zgppqo)Yx8oyV#z z55S()AEE5?8G)cKI%C134HtyqaI2=Qo@tpdGeHSDM&U7D^}^77ohBQmyIvrui_X08 zk<8Z!)T|xICOnuU&ajX%6&-8w%*lmO*zK<+t6CT(5Y$EIgLpjL!Wiu4YQu1or7%-O z2|8xvF%to?SZM0aPOa%K5Y$EA!uY6fO&orn;?GtMc?DFV1ReYGIurbRzPcui4VEaHj19)LVufF-1cJK68ozmMlCW`;p^We9DeP@eiRD@85L10h z+QIh{=Wkx2{5S?QXSLx+1cJI~MPeS=Z=Hk|HwQD#Ba4B$3=bv4iouVhn-}N*Q{8xD zN)l>Z9>|*FLP4QKNn$)$Y5tYQn5^QxI&(f5Z%yR$iLZAH1a;90!F(>`aT30Ver(~8 zNT3QOHU@@6=aMcEc5@$ZV=b@cz380^J7qCfAgGJhv*l}d_Q{B5ec6i-U4^=}l<=Mr z2<2afK-ns}((SdqDcI+jg3U@Z5(w&|)q?pi&YWbN`m7I2|K%xBg%a*YJ`mQ}4nAFd z!`sNZnS%43>a&5V=>kDrVujdcVR5*lW*RHA(EwUQomP3LcZ^(_I~u2S&S#FLWfD~= zLF>gU6#LJ{;+cmz?Dw8#Lj88?qIVCktJW|Ys|%Mg7VIWbg%W-b;^Ej21yujd;z!;| zGY(7hv)JNA3gJ$qE_#pghSBC+mG>f_y&Yd^N)<}j9Sn!d<(1!jS@Yu+=an zUG=7`;kd;EUh6D|ZlC1!bEAM5^jJ2RY1u?5sX~c@zsxg{OP&`v>VC9Oy0)ER&&_9RST6=p~L|bZgo#W>5IWuO(q6yjKR+SGufB@Ym^G2P$GAvCp5S;17g&5InnY;6b_oYn5CL; z5D4mewao=aFI)r~J>~pbhxW0k_B)52w^*;F3MICFa0lC&xxD6bFHSfPipGy6c`WtC z7J;CyN0*(UcE$o|J*p=sdKSiFlku7C$B5NRs!-xGx`PeNf`{$9a6)@yG~T&ApXv13 zBoNefcCIrt$)5vnGdpo&yp+v{N?y#?8I`}HpIWekZ48HZ6%laFw z76|HUbln-2-JA|lwXHdkTNZ~&r3tM4yX9quLa)xWeBoR}3KgEwc+W*0x? z2?TX5+Ux>~q)afdYsLx79`X3uA%^XU^;1%X67fYI5VI&4X1O)wL_t*y-in#UT5rh_ z2kZ8DthlLRr3>T#lbP&}U89?1^g9HyiSCF&3Mf}gwGA%Dj&{;k!17K2Uu%wpC( z!v%u6-X5F+y%R%Wc(<>dFypKGqngiVI$D-W`rW23@q6x;ACK2IM6fpXJ1eO|3ECcC zF^Nq^&&fJWcR}k)N>G>ht7hbpjLI9jY_^85abCx@hHbg<|W5B-}R7m?g9~R8oZ! z^seOjgO8JOm}Munr>~AcP?uPldzE?;Dol}&`T~?xp#=SQ@ini}$#}Aj7F&72S0Jd1 z))D6`SiG_-P8h?6-J2=Y3#SBqO7N&+J_A{5GLVh_K3gEDi&oR-6`FP=pqYj}^V+*y zsG3a)`m|Fh?w?7-!luCPIJn>5FKCc}&NtmylG}Qr5;P^~Q(K|%YLkffPL5&g zii-q-x@i4v{&p81kH2{>n#A&TLPcvz&|e>g!aXJdpYW=h6>ql)1a*nkjRQN!<81W^ z_IOghP}i9f^jDPcR=|(kP0xcR-d`aQ)I}>R^R+uZXW6f39Ge=GA;hXtg2u-2d;=b< z=65cRsa*;d2+CUE$%$*7$ZE~5mo*vkC^nhM@xr|1Y^SXmUmUxg?OilaU0jWZX z{FjE1INlX5FgZ?t*@W?^`o@+G{nAPxsEfv-^LLz;qj10-W2X7MGg5^TM^_j@QT7mU zcavkCKMuCU*9-fy8+u&?g1R~j`34nQ!_c{1Bev*#Z=?z(RCJ7CVb3;@+iN;+@rhSZjGBzPpZ5&PU2<39|8QM(2S1a*l~#q|mdG3?wc z>CYG=qzWZygoi@$RWie6M;b$fyS_kB7maA<`Dz8`7&*Hm92=@F#5z-gMtJaiwH0G< z@X0tBuFwz&>Y|a^{Fyl38V5aC4*4_Gg$Qg)(0C1=4cKoIULSo4PLF9W5Y$B@%y}F@ z*U7kg`e&GRTp>h~Q-Vf#@LKob?))j*f!$Pp!{}#G7mbwX?>Liu_`FYF7Bja-h=`{I zjqu=ETZjBHvC&9o`iRFFzBM)I}rLc~#)zNIc#m ziv<{>P%DfQG+u*OJb4qrGc9JY<99(IsB4o@^Gr223JvDXV7gB`3l+>LLF4cE+g*c5 z?4LKET|d!BAgGI0Xya>MDN)$aZys}Q+fb;)MhO~6$m>Ag64v3MFVfB!9x)iNH6BE7;0&?*)RoXvI8UFI+zgJEj(}+L+xy6-v;! zPKDw~VFYegu4R+H9}x)ZqLu&n+ue&u%s#u4>j)e@ZzEHmR3H%4 zMJpI86a(`k@z3_PtV!u8p;93wXq+v7n|KY|kx`JOKZk=R{t1G9MY zNumlR#NYG%A>o+#Z97w0&{C+;NL{p|Bp-zziNHxiHZ$FiVp0CQ;;dUJag1TtMRi2x1I}EjM>|o0xoP_GFl%R7p3dM2fsd(F7$?AK?2?TY~ zTC+TcB`6F-SC_IzujVVMLJ2xo!&mirb;?S^Dt0tywLnl8t(nXBU4k$)>R-x!s1^ye zaVbIPYWR`!6)Z)sDwe)ypFmI-t^La@U=9z%@ojf7i+THn8o!jFb2Yq5T0{uGEmgA5 zQ6~k0x@Zk!zK^?C81Adx&W@EF5^5Dwg3i?_6wTfExpGyqpPw!Z1a;BM$~>PlD-2J4 zC}xRsj|erFDM9CI_>NN}La<(#l7;@dArRC>YfAI{^QB=JF~68;R3BDSg%WhGhF1~n z5`wduRk8Y8Zwmx<(c0JwMJjJ&!MS2qJ^G-MDwLpeHGDqtZZQ5Bbb#H=y)6*bMQeO3 z6m2rY5I1jU_h*(XsX_@l+rn!Ig$3i#l0$6hqZ)yrE?TRce{1`Pp^ASgd+>9sk}8y- z^Fe$>c0355sUBkm`bPzVx@gUHg~DfND4xjJ!_=?MQ&NQzbOxI5U#lL3YJE?$4!_q6 z1a;Bc@qA9EWhizGC}*qQItVr5DM4q_dA3t{Ao?vh&&HQz3Iui08u&b>Xx3Exaa75S zCTj|{?kPc61Qd!@tpo9s+9ejT%}F4ri`MezN8V>Dx)>g02Hn3@QiT$9WrL4iD*{kq zafLm)*+;1IPhH|}1=Ytxu)wvNtZ1E4^J=;_ zVQ74E4{J0}y@D!~n9w#I!kn&4?QTrqGm!uNmwrJ0|HXZ|%30m(n{F8u!hQ{(u3X3e zZmb>5)^9jb8P=x0ss33{{&x4@fBz9wp+rs8$vWa=*MEtSmdomt{EALY$8LJv-+TLY zV)Hj{t&rPzTsZunHo_XuHItR)H8E_R%D%e4jaJ1li_ck-{O`$w=l?^{CKL3NDuAVNL%9EYzo0hhaqd#dI=ZEa8>u(a@@45Gq zRFM1LK6)7Qo^-J8-@Cq&bFe5u6-vBoFs+WxTVnA)2!|Bs-q$5)TnwXvnOoaaRes!$?mVRl^`&6~@+5B+}xb?vGAkGMMSU!uu_ zZFQ}0_%MOpejZZyxdU69u;(30>;ApTqly2tK^00|w2rN#I}VWk2SHu*%8JK96-opY z{nv)=lz-cx1a;BtFSY?|o7NrSsuR)d?W&@>zr7dE6TT}VLBBNZBT_0euul)wQ;5V-!>>gT}`&#s%ztw z=fA{c)pvEDl~Jp~LYv&L`}@PEu55nhfdBq|=E#4JgDR9z-n&*u^o{KLKM3mj@~(Lu zvAFQxCj(U|vF4Amjwm*eS1sukqy%*}{agS4_n?6Q- z+_3*apld>#F>JVqQN5Fv0g5qDLBiw0W_=9%l3K3Je-Y@qk{Qh=it|x-u9h>3#1p4w zigvw@oaIX0Mh5Gjma7`Kr}zw(2~?1%k{_<8t0dYP#6SXF_@tI&q%KI)m$2E=p7itC z#`^0u=U;P*zciUZ1&M91>+0#elI8|Sg#^0r_bA8sZB$-g!o*XP={1)!`p>pCrqF$v z0s1;z(q79RDE=$Hc0b1N(U&8zw>zCUV~qYt3Xdyv#p-zd=Z1lXZ3gF=EA&Lap~I== zW{GNl>YyNK-a>&)A|^XKKU9Dhc8UmEAPeITE~ub(SL93 zjTW^3k;VG|KX%aGABA;=3KE+?cxY`VVWy7fH`%7F?JGk&(w)0Hfm{SN|N-P6bEV?3*F z*dIg%iBZ25eT-Fa;#8;Z`WQpb+8D$@0$q6ij@xP|i`?c-$pI6k2r_8RCKF0X1 zhW&F?kifAsIR+Bwy0(|-W8Bzi7y}g~{(B6df7#-ZiE@*>(s?bJ{(E<{s7tZd<)cCc ziSSp~^z`>=!(J*9=)!X&$7q~7S6`#stZLD{n{MkrcMGmX_qA}*e@^Ub*rVSyIKNQ4 z;>O?XLp@DGnD+VAw)S+$*QNUZpUF17x1)kY`NckZy25kA`z{jbT6}!5K1R;}d48aR z#J_f~`WWxsTN+%6NT91m#&mrQU5<+Zfo)N2e{QW)+++Fq*zoC$3KA~|M(dAi_qvV- zF_1tP*1CKKQ9+{N#&CU%y8ov)fdsnn+{iI-G<(%QxvWcFBZm(jVf4R8woySMwEskQ zyta`;=YED`$Vi}TF=D*}xic6FFY zOEu0=^uMl&F$PD43KC)Gi=PJDXHNPb1iG+aBG)b|NUWG)raxM?-Y^Cd=)zu~90N;^ zWm@{$P9I}fnOuW%pn}Ag+~T%RL07}NLIPboo>P5{s|~ePdc}Xm*A=#Lt1h3YcP$#@ zMgP0KiwY9G&lS^Zcf(l#B+%u_&gjp1<9x%b1QjHx-6Z`H9xn1XCWvFM4LA&^>pt#hNFW>pbMXm^7%jo z39DVjb4Z1s4PzjIE_{m0F>rL*cILYM+V3u^eJzTk(K3Mw5)H2T>*?7I4acdGKv&tB zT{~#;s?{>AT~v_h*{T0Njks09Fa{Fndam$J8quhlVGLA|c)DoPT8)^mGmL=*y8gS( zfC>`U_x$zO)zSurF_1tPwpZlyfulqCq@J)KooVHmZR}+5`#=SW=wZbpsr0$w93&Fx zvM!UMkKy=#<{&p-+FhtcKhtL#9sc8z{_~sdQ|Y>?mGqxKt~MMmK?Mo5dnY~dWvt;S z4z^wvbm*=>l0N5b=zq6lP(h;nJF2I*emCq7B7rX7lyUl_@~UCj=R^gGdZpXyV|;65 z*snzbT{xC0pL0}@sCTxtK1Q!QmImisBEW?so^lMcDa9qU=@vsP7C5tGViee9c{ZI9 zI#XZrA2YSxlZyX}pC70oF~O!c8zE-gGbU^6^#6-MS6F^=dv}AG_8wj&P(h+fX&?5+ z+{mGdejob(BG857rE&~ZkVyCNVGl%%jZ4NG92FAi!ckQ@#`1&=eJz&AjG@^&dloI) zZ3U%rDb~77pn^mNZ^F*iGIChj*YJ6c1iJ9t7{o9S(jQe|ol(>^*GzvcOXpgwwCa_(1rCT$G}le9NDB~ zg`(ZZUX9lF5GwvFzS>bi0(TAhZvtJdwiJ&Je)vCEJ1R)vz9w=EB+yl-!AyNQYA!bX z)uMs~?w={gKmuLZ%9IIIkiZ>2|C>P9f45$f_ZF`_+3FQcy&7Z@?W~ntF@j#6Q@rY> zy0PK>ASy^K5<59)^m#kOXA~0XTHsc^dS_mwVGLA|z}?K`k|Tkxw-pQYXE1A(;T$9? zNR+B7cGDH*D7VdU4iX7;4Yn*^C)4!*%t4}p1nvkWmjelO;V(@lP(cFstom;PT{ur6 z6FAm$sdY_#jdsoZU*kU5B17WMBnv$~@AUs_!=Wp)T=5#V@c*+S1r;Q6-xrU)E(|hU z^@0Stu$Lj192F$&gM;+t7(c==1`_DP-jW;x`~8>1ID>ZeZTQEV{`VLFDo9jYR7{@} z{ZBat66iW#s(8Glo15XR3@S)WeV?m8!j|@i?Oi0$b$w{@ipIVFXLbo&tTX)|6>24~ z*Ly1c@760SNUVSMRZk}#Fr4Q^0$p9xT=hib^M-S&s31|XOBsF1PggaJfdsnDpk*MR z4^)uY|Hf1wW5?Rb24@fnbYc5Jj)A=i>?in^C|=L7EZuOP6BQ&znwaYAYUv)sdpi>7 zTGnEso?!J1$HGxTB4_F;eNVV;lJ<7s;=kfH0}|*e5t^fqG0DO(1}aF*Gc8`-cJ-!V z3?$GMe5R{D#{K1nF;GFGS=-{C*W68p1S&{eY89$4xnpT<4^u2T66o@{`c6+Y`eGQP zY*_J3?ijIpIMt_k9@yqf1jXmP90L_3Ce6tv+V9bHs$m-r33Op=K#qaqNp(6+A`Qj& z?h<36|2?*Z3KA~Qi^s^$j5ZvtMFL&ZM;6aJr!Ud=-!1+tzOGO~;+1o8jLoYJN1c&C z7uLEQ0~I79J`~TN?{f$`*Za7j~Zg`|G)3Ms31|>yO>U%+Q;Ci zkU-bmhsX54k2TW_pE#%>VO}pwe}wFd;TQlC=vqCpc!Xu?OT#A)DoDJ`nV^p`!PGDY z66nJ58M$^*LBg~1IDL#h(T3|qkwDjfkNe=PWr=+S`cbZ#rDsSpnDSBKOeGTM+$-qm z)Fv|w&L9$oF70=|vYX-EM~nFXDM%c28MRCM|E$J_F_1vl$NmHKBal?TOLK8aihqNs zAaSI+wf+v5)W|Rf66nJFV{rtLSEbL*Kn01s!v*>nT}v6pKmuLzeYdk3&wJM!M|YYX zA?H4iW`Q^S$&-qq)aUIeX7p|-v7Z}E2M$bR$DaBUhjM=6e8g-^=C3Db5Yq%(S}-@8 z*;eI_FKY~^#^18otV~}eV0a{T$;xGYyQBZY3B%% zIaJ%#aqN+H{LsfXs^6CS5`iwc?MR@F3rkI~r?Cr^T^2KGkh_Sm%J6JTe4UF#psV8xE7s%s81k(BOhMSZZ^e`B+NhW2 zM-}00)tk^b@@ie32N)cm~X*=#T zp_Q6-CKo{1C*f(mTEpOJ_R(*6NMJhQGWvrUBI;V2Ts_J`0jO3QKykGs+ zDqB8ABG84uf3au3nLVFB(^B=EnOW5IXglUqa{;lh^nrXgvSiQm7LnUqpAamc*hhGL zTOKgQTK(voEtLa_7Xg;6denUKtNdMYRPMXlaE}-pbwERzKo{1V*q!pX11BNo>eHVI zMOS?+*yCDT$%rrIXyPdgwsO*Xa{pLK`tW!gwm5YyS@zsS+~Lgkb>f5jS*UUDX+@|Y zVf@5`mx$lsvIn2mbqAGj;pWEQvrD)|*aO>y66YKQvTV4jxo=@V+@K7`vBjs#KFkzcpvo zhwLHcr&gzN4cf5rR+~weomE9S%3P=1d3z&O$q6k&1&N6*Em-{A?If^TML`UT=*)Xu zY@qH6mkD%X9g6)+4k-LWgC^>}J26sSA+cJqV9WPxBd`B86)~=PDg6G>ChEBNqa*@d zcxH9F)2^L)?zV>N(`o@y$+1i|E}OH6F$HArKy4iE-Oet&V`@FM#A5d%RFH7n)|##E zvy&WMP*)H)42X4(G;`I6C`=8Mm@Y9Ar}sx=qHyer*#g}!ywx0x-AP+2NmDHjiu1CyIk z{3dY*k9Fe~6*Hx8cJ@~7wW~#|aiz2Ka zEbYLF=4{rEEKms2~v|2!As@wXP zEJ6i|pjWL~Kg&a8*=IXJ#Lei!&Br`ON}^Z+m}~tS3_-( zHiwy(v|!uLog+r&yU;ry%-O%5=g5P0PW0>eHmuv~BjiI5ZTHq!tNQT18)~S>E3IYd z>T%YbHR*PiyedZwh{sla_=t)%)ywO5G5jthqK})iNgvM;R$mb@damfpZ5~upS65{c zfi5hQc*AOAH~#8jO|@yxC58$Te-D|nk2}tgufrTgj4#=)e6MFMHFU@$i9nZJSM6`P zbDPwvYW%t5h2FUqY-;@rWNc<1x^%Dw+xhxDX(!&pYCpIwi`aRT*l*PLox|OE=@Qk{ znZwI5bp3I%U>A;_Cu9EYX+SLc-H*2zT}}0w)Pmu6Az|0lg3b3jPxkihF3RzsQ-3}n zrHWdA$pDE!7uLFHWnApb8?UOaPU@I0)h-f!YFV%wjn0!ZrL_KenXJD2_w(xNl3TeF zfiApybh?vP9(+xON@|5upOt@;+p+kvN6D0m1L#-Frp(s*JV_qtLzN#EY}%ajWbIb% zovgzz58zeTS5jXdTC1Q^@45xs`t&^U+&+NfH;JnxZUFDyt+IM=R4XY45>3}xuqfjT zBzAf~5u?-w4<4CWQGKUo?#J&!7uLE?_o7>WzU*5SHL7WRAu32zo@~Ju*1bSJY}Lkn zE|~S_5v{7KJ0>rX2z24qBi_On=E3RwimGwVS_JC{k8onUrfiMrc`~!MHq-Dt!i!HE zS6)3cwLU>bA{w-3Q$8FfUVFU-vHg<=ACOod}oBaydkHduglNY=3z2Y0t{3 zGdgS}s2~wDqbYOGKTC8!0tE3a&6~$nH&Ii~CQAgm@Ce0w8lpY<6E{=!!M9w33KAzW znzG8z&yt(XwHRMJd2-_`rfMhABS8XPa>;iDcyY%iCh8OC(^AQ?Of}v$WgBjtCZmT1 zix}?7KKwf=qb5~5Lr_7&IlBW(GC4p_JPr~>orhk0#64qmzSnz+K$oMXCHtFwiqyZM z_0Ol?@aBUqmQ;^)v7uF5>{ysNBRzaV>E->FtX1GKvd}V;&R%QDMwuKZ@!ndlrSmCo zK1DTBTUTu+DODF(vYN5SNo3(L>6^qJLaV&_p5CQYx~iU}AhE5lB^#J~lJv;e#$NCH z`*OdRCDl{MjU@tISSGPYV{30-E2@n8$hIs+1qtqE$=v6hB(8I{7;VkGdHwrk)Uut8 zBm!M>T`kx7@D}q*sKeITN%e#EcDz(GR^iKG@^9s65o3(KAHVbL7bQJ9P*jlkR?VKx zonAm5Z5$>Dzdk

      HTjy@UN>xple;FW^C@H!z3h0i}8J$4{tf(Bh6ZnOoNvR#)m9-D3S#}oPn0;vNeU9Hh6}pP0W$RONI}fr z{_LB&7;Sq{A{YCijvUPsa`~CqG6(p9nXvU6@Iz&uojSw-a`}pwY7yhNY z?zl??y5y2aPxj#tUcIBoBQm9uV`=waY{sUn-A|%dX(L4e_xyNf{0sU$Vk|`kiT67@ zvSq$oNy#%>$+wR6;d#4X&>zjGNd&qcmu${P(E_sGbBrKb-tp!yoNvP8; zv)`Y#li*;(@vDDKeR$)@JM_b?Rno{75~tcXXP-{*CK(mA(ZOehe*8p-yL8R|SrUOR zJVKq$ZlDhj$$di2r_H6PAYoCpIeVYBmqgyt%5gHwt1u=u1r^5NeEL0olvgiWR=Pia*|H$A){DM-ZGS+RaK){@4nwQTYyroQ}OlY_L; z$s&nB7apN#`;7JCna7UPf1(akRFEk3p*fpzY$HiB*UEAKq8DFT_cU#tT_h3cl1o0i zgeULtq<}Wvb4@Bameyi|6?@-w1qr&GA!1bB>CHQo-$|oyT%f2Rk^at+UGkhua!s|P zy3GfOU6;4gCozvD0$rWp+Jzw;Xq#)7nh!wkha}jYW(qhb02kLwbgs30-d!kXRqHj^xL-B1VK+KYpU>5?asy zmsD3sWLCFkt&?Vxm-oks7&$ZC`LH)DXxGtSBm!MnZ#vza#Xb1B)WOudd`)$X82`@d z8B4m~%AyV5TeG5%u_XFZ7X5I5vgWrU$cGzRj4$JRa-VX;XhEIoDk@0$AF^h%s>SE_Y|G35;@&!oE^TJRa-s&4_u1Jr+sK9u znG!`xiG9SySojtPZd6p2{_JU^_RX+iYj!%4`pa{u?{FJ-=uS7%I4FnOuIs?wF6u~3 zJT>C%dPja?WF1=ahLws65|e^$nDG)9(#~01Tf5J?Ge29_igrI{E)nR$qZK0)1uEY@ z-;PcmY%Y}piJ7f!7>^7jwyU+HTGGLZKV9xb4_#~|5$M8N5G~8o?RfZ0o#d)2+b zhBer3M&7uJmBhPjSf%j#L#`ozXB~r*T_yh%efrgRjZ{$pbO8Fct$z5t%UM`MgkzF|0%@{(5-^X;#%yMFok; zH*MIoo4=Gs+j0eQ^-5bltKt&UtC5{VpbKk6{00xS;WO`UB~_l;Np*!pdv3$V#MB^; zgR~eG`nTg}R~;eq%XN?lbm4gtyZn!A&X3;vpcE|ctXBNTj#c_FMOphWho1gx!=nAB zD<)MZ((k`**vZE8lnNCmiWp5gwd7kzS&_)`(75?~*m|rgR{Uy{J@jBr1Kj zVe#+xD-qwdawI#p;9*`qB<`gm5$MA6B<5Huwdctz9y{*)+Ci;z+?k0tk12l_WJ}ot zxDH*6s`T*KzP+pM5_&j+&-D4NMO7Wqc;+PF5JaOr<>I^jMtnqRrx;gK1BryoFCTd{wBrq z!CC7Ri`ThgfA#-=S4Z6E(5K@#HlWm5N0Ym;qIMhYjpgpo@{}a6#S|4JaOWm5WAbPu zuQ_I=a(v)gi9i?b!z4zENE)BFFkfkY_Z7ieZ_H%H%vqhT@6L37<8OJ=!o3{9IrGuw zCb8}Qa~+=~8qS|5?@#Bp#y^$C5#^;ANW?ar#9jqW_&t=O>%~k69`_W3Ha@bL?WlET(Ho`J`ZyFD? zI7!-XnWdnD1jg3shO|%Ti%jN|q_x)-Jd)1kCbIMcgOv0^hDY_mIh{AQok6~Jyr$_Pp73#m+g1-b~J6(}T7t^P+qy)`(a+a6FYioL7eS@3!0_=YAH8`TJ0r)83ml z&&_6&H=kEnQy+@oq|^C4OXW7VO46r!fsUvkac^rjb0|2a4EFaCM>V@*8oxUA7m0dx zP$JNUM=1I@UsJd)vmW)$h$&p}H-T-gRf?SW;z2#mPhhP6ZzUnmlYVG3fklieL+EC0 z9By)>RPHjaHvQ*1Ekp&0n<-h$W9@6D=Q=Mz*z`)}c_XXSfToot0$o@mVx*{d3ePjO zp{4J>DV$h;9E&{Pkl2Z9X}sll_O?b95>jaZZIM5o*~XS910QMY;WoJ>^Oy^cwAn|o zC%JtFTQ=E-Sble-?(;I(_j%1p;l@5R^wL=7RnMNRQnjNhJvf=KU*bUTh4f{pAd%KQ zlRa5uPG)Y@b}6tMm&|jQb)+Rtof#_jPcm7RF7-+9*M0^uT-PP@oo;qCU`~4}1`<0* zjbncv)FP)JYwLZMPDth%KM8feKCTdt3SC$u;%y$)Qn+bnTY7(?2}1>mnajtq!A)xt z`_|e%Mg6Q&_|a7@X^FNaB?4Vo(>mSTPRTrJtwKjm3X*CUk8sV!vCKKY6&dK@CSu&a zn#3=M^rGcPS7E3i(Naxkt4}+T`p>j8SW=hFGkwJyp=q*2pzA}IvFx33J2JhEs~{{l zB=L4%oM=q#xeQlO+1*HGpXMs$&jiEOR6n;T@sm#lv3VxLbyi4hf11XOZgeE~#Xd}8 z$M=jRJ}1nL+FtA|5$M7r6uZhlPU3AmI@3~O^(87uRQo5LnUD@-=d9i$#+3I-{LO2X z9y^#J5$KXj{xcy*4KVDqN{01knhBrJ&{S|#^(%B?t@7SIE?$VvMXqL=6cIrmd z4chF|U_l(M5jeYzuk`1+_spbN{S(|x|5#LL!bNk=7JX9aX5yV)s# zO#Il1Hs3OmRSq3UjOIJgw_cduvM-^OSs35USjb*kYd`Zw# zMG%oKlla)=|uGS|UYbrVmVXWJ{#M`bQcb%n(E^hj1~cL>ql)MBXOskUNb zCHiv76^TF>o>}pJgI1~h2Yo|6q!mgf$1>G+3TMXaLdn9;%|(peX`-%fSER>k?qsMS zVe%-Hc^pqBPr6wNV&2wN&XTT@y>s#<0$nMa!q_BnABzt*7eu9kG~WE}N-|(tJgfUW zgw5$Yh{SfTOYaX2W#d*2Ccl&hG|w`GnT972rD797luAqEcjj#-kBoB}DoAuFAI7Xo z3=wZ-Yb1yb;i8>*{u{A*I8P$bg-58ZvPk2f)q^Cj>OzJJ5*7W!Sk3$)ke6qnNZy^d@waGzn{8 z7_~W=jT|0Hj@+q63qB2D)9SgCsrM?-jcsPl?q`=Equt;rPV}?jmOjY80)=cVX_&+ z??M-rNvHc0p3Z;#7)9dlmSLzM5mhII{jTgw(le@y7_EDx^Lde(Wbx`I5`iwcu4c1z z-m$eE*>L;eeykrn!rl$V8MJmIr>d71F`^vOxnG;bB>MBPLR65L^(dIFO$sJcUTf?6 zo}W+Wv8&BU*}}_?NTBO=j}YdP(u>$9mlZ^lL+QMx@gt?o2oq9ebSNunPRNZlQ4o$u{aj{MD@q@aR?bxa6*u&D?6;%6*k91uj}>Z+txcL#|; zmt68ZaqYG>xuWk)O;IY>TOlb(*w}@$ph;Hb$G@*djB?%5dHhvhGCR~?BG83p5_J`y&PV#J zQ+!4z6I776_c@I1Uf+gn>-$B-2%M76eYb5>sCYLx66lia>eH`Oo@^hZY-fK+zWGSD zbk9#EYVQ$p>Q)SE*6g>^_|Q=@^JFwTx2HB~^YoO65nNq7KL(9d7EJvvDM*Z~D%wQt z%8O-U}jjaGH|3<$_dKNSyPJWNUuZBG($;5iy2b zO5>XbXDBsh9h3-k;rSQs-P@^r;h`wyLAVjcl4EJFoDyx((od8zru#*V9e+}Jsg^xS zr|4G%6(qiWjAMZZzAM#tZWBbZODfN<9j;WqSB)Zpt}C_)>`>StrN7xGL42K*!W;DU zR@T&LMi-44%N~y$r|ds8ljQ$QXQL}mRM@0B#IJc8OK>`%%vm~L5QA5x@UR8`%JHif z6cr@yL?<(c8S9m*XSIBTu0E+eqE0X3K+8!4y6^}^&&w#4*YNgJ>U-6ts2~v)pTO3* z98kJBZNk`D?v(+9knF_U2@6G=A`iX=e?B9adOGAOxs;D*tW7U%85@?M2yB& zQhC$X14w$;DijqYI);v8Uri<{t`TX1D8DF$Uy2;7*bi?i5$LLGJf59!uu^=zQUp<` zq;kgwL&@m)a&$z>1h%GpnBo``LZ-eL&;CiRro1>bk{~VSgo{$RMbaeY((}d?6(lCt z8PAr+HdCG@B#Rifn^U+)?JQ-*ICF_WmwZ$m7pC%2His40d=na5Bbzlk=%myW`9rg| zWHX!H%N@DaXL5K)c^V^euxcq|F8Rzf1sg-0v;gLP8*cmFj?RM*75Swja%!%`w)~Vl1P4 z2(NtaIUPBwwnU(-dg5qi{-ezQOZpQ!X}kHH)Ew#PJ&;?4xsIQd4}Bn47rLi6@)3QvIB+ zvKqI$vb0++q?%AL6Akm@bh;j1?fJy=?bLm_-xw-LV4k0N7q(+--qFKeeX#A7M4(H~ zyW8hnqgVrz8hdq0_i6pOcp%=D!F{|q<$!h^sSfv(J?{_Ml0C8Wea zOF`^v7{X`2eMHOpA7`i_vF=Y#b|zv2`C{Kf5c%7}xU1iFy7T)ri9pvF^ZxAU^997c zm6rLkyz>zLapDttq{efG3KA{m^kfs3tRW>fXnp4w4a0bYK{sftS+6AmT{YbMvo%(8 zNJhPyg6JF?%=go0^aIfqp@PKeWj)!cw=2kLdo6?KLQW`Gcif~CY=1K((3SqXKfAMk z8u4hR^#`A24CZy|3z`;Rt_T$*OwD?+3*#4)o{zMQs^q63JbC18y82-$i9pxO#vbe$ z%O$!#T8|}fRuE60|B^14R<#HfB+~!%VsROB$(nWL1mSKM!W%ERORYUkBm!Mwdp%i7 z?{Q>Iz2D+@p0{ie|J&t_c;jvDB2e-v^EjgVe=9CmMyuF9;@vk1xlxyWA0$n$n z`mt)yBS^Ew_e6|Owt;+5osab5{<=k|Ad&O44@)VNNrFtD3L>F=FmF8n8GROIED`9M zP&0^SR}gpatOJ7By3NQX{8Vcu;lcfLXhpR^QjoY-KZxbF3nR-DwDr5~riSse-pMp(%^rzB*RvDBETl{i z(!IPEqsNhOUWY`}t^2l8RFG)-Vi>dP>r7U((_+lM5Y9I>^Pr^{@0AF2O_?*CnN4a! z?w3dsgt)l z@i&bd)6~qv(hdu_^8&^eEz8kiJnV)IEh;!G#X#a)i%@nx(31EcNfk#G9UjI@9_&W@ zmOCL4=)yV_vzCvBa9>Y%Ix69UR98q;d+*0e=JzIv$FSS_;n#Sw{&RJSKv({4FLq=7 zS*70Jae~;sHIUC-w}_O<`9YKGk7Co+L}hn;8XZ(4g7tPwSFB59(9RFS*^v)NlqoZ` z+KoKx$5+O0B5Ud!si+_^O9^7teNHN2{j_py9q7lszuzH?_m`9ibWJ=L$gXZRCL7ml z>yVAMd-17xZ^^FqWmQy=7{6XTYv-3EuEAP4Em1isw=yGn|i`_ryK~BEY zV(e?<&ZC^1DfcR`qJo6QK$R_R>r47B)M9MjN_nqG&DEZ5&PaWOCcOr*wB+Kx2)6pg z*sFsx?>xssEpoZeP(h+plm6`LNtIj;iWEJFAH?xo)bFVsY6b@ zXo0ypxv8nN!v+$U@APHMvwIQCGT9JX}1L=R@`@C zroRT02hZ1u7@ zfgB?C19*9)q3XYSghZfA-q)a0Y*$|KejPPnMToRZ0TP~-o!O=5Q^*MVO2lYY;LQJ> zUsruTewaj{OWr|%_3Fu6-KwE3Kj$m$2Y|#2TUETPaWT2$t+lCV7j);_YSmU}-tm?Q zbYZ5yX!Y6k<`Y|0Q)|`jE$xJW#N!T>?Owf-G`^(u4eTO&@yKsA)QXjQNCdhtTVBjA zEqCMT)>YI)ha9A=cqDpHBdqT3b!1LxEfJ$+Ls#DVQ8jhI+qM#cF3fiq<0Z!Z_~{On z)Fa-_r0jkq4ylBlu-HtVRM%z{2Oj9dt?yM)`%kMY5$M9~bulg)(4QL*sGz<+UbzSr zBzpBGEdK0vV*F5>eLdFIod-Ryq`t`0Nd&qu16=GIwa7!vD3({Z1iz6oy^$!fi?HWe zyGeaRRt(TZuN}{DoFe-?aZFmDInFNwAF2~j{ZD!v5{KPsGF3-i!RKy z6}xz>3*fG${?f~7ou$lTBszU{X0Ds}kgiX){PVc}1Nr{jI<@PYB@%%y%vTjF8d)H3 z5cPxB;|mBXNYwe-g{|DSi!|xuCt_6d4&c#_zi2O)yApve%sAEQTn`N5XPrsEsDIBCi9i=-IEs9OD#6^n`FYCSW2JmfB;uy`Vo&?8B)>*Qix|%`2Jt~dPtys7 z(~BCii0Le`GZJ2WG<}5G%;iTK+Apo_B)Wfx^e2LtdaFC zS1@)kue5eAWj_{6d5}oNz3eTytZ(8^MSEbPY?4sI_1h&=paasoQKSP4)w_}ef zDo9`-SL~kDFOWaFEQM3vMTn;@XEkGoEXda?a8MfA4sp-mymjQNZ^^(>9TA3 z@H5?dQpcr#DSj8aurDfR`+oZIrdt)7c;_2M1qnQ}I-OIdA0ODYF^%i-M7f5#;E| zMiPOp*|BacG$cn!|D?qj`?d!UXXa%8)P^c5NZ=TdPPgaZ&b+t%vREVVN;1f z*B>KiHl*@3<$hBwhqrPKXFgPnkxi{@siJ}e*18zWSV8#C01r}gjEzK~D`2cMo8M-V z@@BLa<7=2B|88SK+O=t=qJo5cKFl)PasP)46|2#95`ixH{W#Yaw&u5c+;Ft*-$_LU z2|1s0qp>+pGkxM{6WC3~H}&i{Zoybls4~!eBE|Rd=yVZ-EVzSzy7JDxtBMK|mQp-UgDJEc&DR8pbKkV zr>niA9gmr4Po8}1Ak{7saz<`yYDZqBLnL{1ueC&=3$GrruR*f-ecV_|CJt&XT_s4! z*~@n`39l#i$r~`*S|ZSezXF}^!vM;c?|e^UCN`I@b|mE7@M*za`1YaYsQZD&5`ixK zZHis%j&$Yrcbm~ly&FisS|sE=`d_+4zP~{TEoGb~a@wQW-Ln~_^G+8jV*s-w#GF?| z68GCk=+%`6q$~(rvyZt4Vg?~X%fAD zH-?~sMCF^&>~Vf7N%*a0XYOb5yx@8^^=W=iK>}T+R*hm8uEmi(-rC5-rcH7DX~0xk zdQo$N3KBk7hBKGh<4F8NZSS@zx$%7Um0UX3rM`j$y2d8Qumege@vGfO5Fw-D__oi} zseQlW3Mxo^xf#Lo&S#SWbG!sG+dG~o_nbtHKCax41iJ8=7AyO$61Y?37#j7qopiP1 z6^`E|eo>zicx>09^!e`yh6)mL&JXF7z_(Z>&=-e{B?4VoBVx_nH$k`!qdgjQWvC#5 zc~hbl?wP<9K8B_=*i?uFy70`3EK}1&Zt`sy9eBSMLj?)U7!#}R(-ZjZw{i4WZ=*sa z(1q8uPPe{oBL7x-7#;rUY#}O0V1ArV_iJYYw^%re-Yz=ghy=Rum!{KsEJ@;Bs=86v zuMG+2bFMJXV9G5kQtoQ7L6&Lk#zfAG{HR0SaDw@jNF-lQW&4_TA#OLdv85e<68Z1< z{?yqrQ9%M-n7gRcHB}OM-%nvQ^kr3o3KH>)liACMeMtMs+HY{`=0q{x9!!UmJO?Du zg*lia!!0?TziJywT9)~uV74{xdyo0tI^D;5>3n+SzQoQco1lV(oJT*#K9!rab0gnp zSCDeq(S`3M5G%<)rtp$xpOsVl&7`*#AR+HLPXpW4MsFSrA2Y~L; z?S2^)6(nx#2xN9;z1$y1dcM-Gl54)h`O`%+ z>4oOwC@M(YR|D9Y#Tg{}!ze*KTp!IRn9QY1TKY-^y7CVWWiFL6$Q4z)myG4Z`HZ%U zXouKHiV6~sj`*{uo;hTgYm6Y4U5w_37B8U};#G-2*VS*K?C8ZT(nah}D{_%P59ePa zSJ9w;{U|C(RO;@><}RN~-h^tu!L#S0dFt6b>dcx-1iD(Z7P+r=CX*yPZ9a;99nRl( z-$>Wg??6#OBI1}2n-D#lIICLio>>{q@66gr%MeqEK-YrkVAlWEbkh5t*7kXGVmM#8 zdpnJ+YerE)qFyg=wrTqU^5wR6-#y$nnwNUJjrzDhBS@g@$nGH4vBDg3+rwWFPlpfZ z^9u^-zK?$hDoC`x=*bobFBNTTouQTd?!w`GPNzdOHm{9DpsT?Pe|ErjDIu5p3L+sh zf}hGiO^00RM^HgxZk{{qb#fi45~-DZ@S{i`y!aTc_GFKO1iChi_G3fLmXj7Iw4SiC za~QuAe}Ojif2E*;#M*)VSfJ@f;^L^4e7|KR{~dISUJrJ1L;_uyhah^}55sx%+$;1* z|B?zSNEkKi%Led#68Bx}58iPO=hm**>8{eJ_9KBV%vKQX#EEG<@zFk#HEb}!U6Qcv zi_a^uPG7WMtrEAAMR_HqotTio_il-MNoF$dWqO7rhBuZ7bm8+#>}UBafu}CIKzdj3 zqNpIzq561cb8VBNI%rRv22~SyOaBsdZEs(RKo>r*#7fzQ@qEgg3bdAYEJX#0CNsve z{`cN11sU2MZjDDAf8NBBu0Itc5$M9_l^7iih~*8HwlrYeIEo4qzO@tC=)Gnn-cGwy zm*u1Q)04euSh;kGKo>r*#B9dp7;bdclNO4n4k}2b^^9Sr*@S%U5-Vc7_K)GYmQi&0 zz)Xoi7e24Vy1tZX?sO}W=6%Vfs36hhZ5S(+6-3%h)nY6>Fr2&OWzqDa$r6Dsd|rtj zhV@=B|u)jw{^J@O(>5H%V(h6)O@4E8@dD~;3^zJ+)u-3)cQ>J@%&JNRx^RWDcq7|MF>86UDs{@KsiJ~}JPVL_%azwzWJ`@2 zRFepF;VijW<-NQY-!#;bj#^eznm?Ba*ezJh@Gf-a&L2Ez-GP-Q0%sR+E?talC-vk- zZ@uWt+cl&;mywWn9=7k;gHLG?NS8jSDG}(x9im0+)mrSawPBOutNKtJL&7~e&Nf`?>;I$_l=cCqmaORmri$_jp3b5`jgBBDH4G$e71{qmfmr^Ys*aHn>|%}izgCz z4;J$VXXAOv9lMELy|EI3E_}9&Hg)o7KJL(Y(st8SiV70=ED^t`Tci1a(Ix1`%~=wG zE_}A@bX69O;u`}iP~X5=6cr@!jw;q!z8uLHeQZjHCC!isbm6mIr(3ae1izBgh9t}>*q-Xy71X9W=tAH@lM-3>Es>DDJn={{*PF#eq%U)6%b8Z zr7n;NbYW{iWCNaw;M*ON>4QVdDJn=@lk%g6_le+O~TPF1eNQN@P@hojr-h zx^AMVAb~5Z#JoY}BZi9Ka?;rz1u zVp?s-9Em^|_KL+C`t>4*ckBwXL1qoc~CUWAYh4b6()=;BsSrUOR>=lcB)!f4P zo*Mad)BdRx6(n%Qo@k5S4d;0$w@@X0ghZeVd&N54w6$S8*k?Cgxha*Rf&{KS6!QlE zg!2bK_R>3KF;yRIFC-5zb@(IZ3bAuOSiW!d|iHL7Ikf+qRczpTGtb6(n#) zt7t8)9m*f1U8FbPzavPX3wy=lc^(|fpEkQiwP(cD$7>m`0|AunkarfxXn;8;;F6>{0@W_47sm0An z1QjH3rL-7BHVNfR?>(mFn>UaMbYVYQtmIe_EZ)`lhT3_zB&Z;PE560MohpU!3vn;# zbe~iO33SQ*^M}(0^NL?TP*>O43Mxq8%5||?z4j3Prr&G2aQVUgNT3UM6A)RZxk3E* zKVRsylu7$hK>}Cci(Tv959T}U-_tQ>KMRpS7w#q?o}AwTxyyr}bis$}3>73WlR#wf zs6qV0<K0K2Mbm49SVr6E&FL$nGr1t;%ouPsR zW~higAg=rK8MA-WeQ{-qkU$siCLmgU@4fk$yi)4YTa}AYK>{;v1Tn~upKYU4Ge^~w z2z23Y0%Gl8GcVr0TN%~CzDW@(NMOd0Xd&P8;VFAcsG--*B?4Wzn}ANY$kT)W`D3gu zz1O-36(lh8N$iW`>&@5t8mV=PT1f=Da5n+*i^}THo1HOHCm&XdP(cDSxWsD1ah^PU zUTO9JA?&=vs@S!^zm?vRUc^QRD<~@LBq}H>MFkW^1-oKHrATjrR6#*(*s)hEh|126 zz4zXGFWCE0-wdAnJ1h6)JlDVW5}$G zeU;Dx3AhuDXCyTUX4{Ok$jRki0s&Ppn*fie_6uNJVhl->yFHcA0tvXIj*m;C`mxb* zx}>y!TY-Qom`#9Z5V-2c^dIvbZYMe_p#>6fXCObJLfMynZ^ZYKm01Y{RKaWlG8v2U zV>`c^lF2D8l+XeRxWkd>XV}%3?G8622TIii0;*s(0iIuUo*x_5#hfH`)KNkUB;Za> zJ|ld)FMBts5sA8Ti$VgbU^W5%RrJV@9r3XskIn81nRFllcbxLEkF!79ps*klrd10B zRKYAhJPujQmu(!}l-%f4E#&us1l&2xSK<`xmt6{Goq~Ch z_&QE>GE?j@#3`M(BWQtynA2%^`y^&k;(?8$%LD?dzBkOEr^g(U&pn*Z_j7(tNM>i^ zwQ=^10|;6m0kd`Sue&gwQ}$LnTzaKkAfW2}o)qd`d0QSawut+9RhrDUc&p)F_l_ZG zfdtG=#%H#FrZ7v{FQi>CLk{!xr7RvnHJyi|q07Dt+3fg!1D4Ew%x!^{ZO(bYoOzIV zynPgv1@%SVRLVQ3`ZR@oT>k|H?{pIW7F59ucKr10jmhkga|_&e^+P$dKw@W`@zmj4 zd$fe-6XVxBKZTuA|B4Du324#%1GMbH9?8y%<8?YA1~ z!hNAYKoz{QGMQQW6t-gOR!ok&dTI1dr^}RA>N0%6Y+s=VQ)pSUC-N+hvE0YrzoOaw z%0)OaX|WtyAOY_Jei~Hs7`F4lLfmb1sz5;1)Q1W5ZHvF;Yr-w9*{gsSNWeQ-CJX8w$87m|T36cjr;vcE2_uHk9jD{b=gSTF zYR16p@$B}rN%-Mv6ACSmfKMVGs}>W(7TC=?MDx!CW-Mz=xM=>Y7-lZaE7-nmJw|psITNXu7p^KKdNdi4*&b zVpyu$0=%g-j6w?}+OHf&+kY%WD{Z=P;>Dg==0BwX>$k`g2&mfCawOe3E+2I~C}lB! z@hh5b4w;YpSY=aafrN=oI9;=U9@=atm1^PhSmvaWhfl0oC=gIJq5E)Z-#!mDcaXAw zuhorV^ADBb<}(*kXo18DyCL+dY#!QYCzZ;&PaNycvT>5rGJ$}q@3LVu>*P$NF~2z{ zGJ<2+et!NZYf(X=1rlHOhtc-$O3}^M(mwh*SK^qBK_*^YR4x!uH6c8LZX7lP1vjzc z#4{Sh#>dUZd%jdqXo1AwFN3J;_-tewAmsx%Hg-B&{WuvDmpK9fRXzhF=wf*)8n{o& zd3MMxmigAq!t)0&rO*P2-UkNJNxKS>VYZZ+`{e8CJQH*rKHV)-AfPJcNd%SmjX`Hq zbvRMFB$gGX7T|r+b1Aey;!xu-YJD#U*<3f|M2o@k{MkMgr%fI%5Kt8$8&1!6j6@ZK zR5`KyT`Zf=&opy=ouMRcizSs$dR$zWUlQ zf!SV)z^%55x$YqWpE3MIofnC0o30m5a9Ap2$A>DI#h&kdEl*%Wiu&WEHj9Ov{g8mq z7@qxtpC#nz)f$Jm777GZ!A$UcKWFbmh7a_{xNotL@f{NI8N*}l!jqZm^XAz7<7k0^ zDwxZi&p>`lWNDqc;2WiJLgso%z-J7PbowiqB_B1zo-!AKfGU_loo6tcpTzujd*G$2 z-6^y{0zPASBu88d8!=iBfBkx10STyrIna3?7E}H;aiKMC-b$ZB3nbt(hL7}*r?9mK z>R9!Yr2-OA1-~-*$Z|?DGr#JDmtNYSfEGx=XAIA0S(eP+c5=WSZv_hkREZ;iOY8ag z>e6J4)_759frR+HDsYZt9pwC!ztU)dfGRlp;LqLkam@YUWxP#!MgjBFsy0cd8hx+T zjmX8EfQNQWWQXn_z$cbQDxd`taCFXN4epF%%bs7voo^ZlIRT*xW-#PycXpGQJbxcv zaj{APEs%g?Z9WQji)1Hmp2v6Gy9l`rp$cYV!917z zu3b2p>GrS2yAO{PGGIaij%~fGU`&l&=-hC^kH83!WUkof_;@I=}#6C*=Oyi0` zKo!im%6IC$iefRFHepY#T@+d%A>JQdA}6vYPZZdH!c~EQDwsKz=gasN#Z2C8#Fe9K zD6~KV-jDqL;Bl6x)fBjw)fIt&Dwxlf?<@Ki#d=)Yh~Ljt3Yl&p0Y^2`3B(iG(_J;V z@yYW70aY-QFaJKj7sccHHsR!(N+Dw}B;e?b&pMx)$k^i={AST{fq*KQkys{MS;PC) zsLi+v)d-n~Apu93{EWi~6WO|f3cOK8ArMdnGb{6`uq9D!?wT!l_x)``24zUV(K3Il z8BJnK*C=qOmumz9s$hm_o=Im}6nnB^E54AoT*w3s2{`KKBjnggY(y6YE^3e~5Ksm4 zR`XT;>rpK0?pA!YHcQB84GH-5!edgKOlD(q_u{ltPl13c7^}*&?}bfaYTLKqY2}_2 zS|9<^>6;f>G1_n{(Mz zcE))@6r$B30l!}O7i7PwOl9d>yx%cf zAfO7y*7G&`E7MriwPk#_Y=0r@9un~TijTrKPh~e$EAT7hN`ZhXxT}DF3EM|A@}?Xs zHk2S}fdt&0%VX}|O=YesOYzcxTLJ-9aCd}E<}@mrjVhgwJsT?!v_JyxGUn?a*3*YZ17oA*p&haxa*sLM>U#%JIS|9=U56fizLy}ldfd@`W%@GKwf_oQv4(wih-GH{jQOAGdx&-j&Rm5RKatG`Pj!Sm7SmY0Xf{hD_47wN8g^cls9zMKwW(E>FFj7>VD_k z$)g9~XvvR_w&ZiK0ZUz(^Lj-3c6X*eH(lx6D-r1GX-9PYtt;L2IvhRDXpCA%b){&L z9~xrl%850*oLRG6LOx!*tAMKWYAvavaX4zg{fR_nSxc6sg@~#mNdYa8u-M+2E*u<$ zq|)+}%v!iJ`7IAp>E1~opz38oHyXLE*WbkNrft~7+Rnt~d>&Pcccn7VQAmfMwDI8p zugC3SsA5k0|03@v))!b^3pq9yBBAt$%>y9oqT z!8YXC_f~dhT?e)y)5p#ca{R)RJ)m#CHj&tgoy%=Y{0El`J|Hn*6``4ieNm&jGe&4Y zdv<N5o-peo5?04?`wkFwiHKJK>Z#bP(xkc7v>D6~LA zT;W}m;LCQOXiDOnL<$5{i7UL#-G;F%jlbY!TWu6SPfVx7mi(6cjB`csTp3teK9})s z2y151fE4b2DbxcJ@Jt&XpV)sO`;f0m+77i8+6t<~4EzB`quA;;&+x0eXB6c!+ zUeE$p7vW#xv1)CnFh}cc`1bcxUeE#wIIqDY0W&5t*}H@IklTS8NI;d?R^8jCvVBe8 z%i{`PqRGE<>8}Mnz1DB=LM?CP(!eeKy&{wdookv)oBOtr>+O``<&cE|CF{KT5? zf&~)ryehsP#ZP40*gOmEGI=ZzP$ixprNU2xntbm(I#RMfuN7D#s&17Q`7&?A0LaJOJnP8 zvgHo9^@Nf@Vuou0eLHux=bv}fsY7Y3WuL`fTfejv2&l@_Dxj-f7j+KMG2s2`%GETs zz;Kn<*r$33S|AbGwt(snI??HmkD%xTR+~8*f2_=vKbn(6*Y-)TdxzUE&Y=UFq}Bbd z?T|x%j+`Nn@sr-?+l&*LU(YaHv1FDUS|G8#IG1i1Ik=AI|eUnR%z$;8N>Ta%h3Xp;39%|3`QT(n2f7g7mu-ZR3{=5W)Oa?MT5r}{ z(~cBa#tY*sNQfhV`MY|sd83*W``2Y&Z5={r;bxDzvj4ghO20mBSNA)}CzMXu8K%x7D%)j7DHP%(fHd(Q0XZ4DeDOiuoDTW5_^f-!Bn9Zz5Ktw)ooiRc zu|lI-W~;d2l^ ziQuz~pWw2i2lJ0?POjGO+XF3-fKMg9cd2av`)F)QUPWuvKmw}7Z=8?wg4nF0Mr29b zLN9261boKGWDUZGFwek-#O+9hKtL7j`FyRY%W$TFKj2;6P2|u53HVf!$=YW}vYcJ# zar0;10s&R9=kplhS(DhDtxBx1AYKkFkbv(*9)YbM!&dZIgj*gtED%ryd%jH8>17-< znKBd48gf?-Eszk$4Ej8?QT#rFqYOJDNI(_r`TTU?JIO56-U2&VbQ7M5kP!QB@VZp? z`a}s@JF!e4pb9>ZdE}XK8Vj1KgBv_K*$BN{P}|GWnwafi-Sm`3E(y&;E0Cnz@W{quX{lzc@|lRv-z z(MvUl7Dz04x>#{&UiRPb+J6|4fGYLA8x+&tXVpVM3nY4EuTZq?S)UKsx)DK{D0{?_ zx@!Qh(?4bU?<)w2;WjhSqx*kGCCoBjmA%isp}2v-+oi{3`?y09X9y6;?DErdU^@8Kw^8<1BLVSwEsasmEVY` ziu=JS^$^ek3Ed6X6lGV^{|5n8D%FP->28_z5YPe%>(14R0ncXq4+5(G{r-R!NSw&n zrEvaMpASet6}&h9xqi|el~H0wFZqqHD{t6ld%Ev&MBQ&VFD??$0tq-TE)sXpff^G< ze%;^gkl94B^i*Em?|J=y)C^Dl^Zz0NEs$vA(o!*K{vZ0^38?Bcx3fZZa(x7}KmtA= zMIVrWsxK$ID;{{%=L1?G0iWQa57@f4*BaBb(s6Zd1+SAxKnohy=7iqJx7T9roAMdVD|vs^Akt^Z_l9I51kBc1(<|#|I>!3O-jv9}$bv z>FI-)>z;jZMhDJVhy?86B)L5;v<;~%$-nn@Xo1ADfgW`5)c>q5{o^H_K?17a9LGO; z>8^zqNPLd(MsJPwt*5OZ0afq|K=c7EkO<1}L-+0PT#pY(Ko$H>5Pd)kBwmgSqECbV z%!>Rw0ab7&L?oaE626NEQ}uqX_04Imc^b(QPi)VQb7W$_C4;1+O@5ZfEGyX z$?t~FZSGZ%4@f}Oq;=g<75X!aC)ONVAmP@zCmLk*zX+&uObtSXqw4Ed&;kkPw;{-) zrb9jTfCN+xUKxavQGGt31rkjkg(BM*f9CzfnnMDrA{K?CW|5BdlnPoP(PPCh^w&~{ z|3N_2wkeTl|C|5J_5D+>bOtSu*pxmV*}wW<1XMNcJ|0~vGOMRl&;p5@{u7X+;(rlP z_3z(N&;p62FJjPrEA@Ix1qrBv-*Er5l=P&A_x9|z-`y5&z(R||+dfQ#M zo>D;qs^A={SSo0NM5EXQI^uYJU#XCQDsk@hA1~>w;V~`r$zWPtdA*kFpsttx{Ep5s zLt&lk8)ZNXBnDJiA=i)fjbtDJRp;+nqSh{dMo#~fNxB};0*R)9*2t~6J|B>PD)>AW zeLxE&@*-SNi=aQ_>whPp3O=<(;*st-`O`KTb*;Nb^|Ji1`=8$*{hrFTyz2WZf)+?z z+VVhd7+v3&7bKu+@xu4=!+ZaH>4~L+7DyQH`YaD@l2lLMg#=W=-Xr>e7D%X!QAgUT z^^FrD0adV%i9TSjhQ0mY$BEDa34T5Sz2W<3o=Nlp38;c&RFQx)UT~HxYika5_*~x? zJsji0zYEtRMIX=tiGWu#=!^L6^~@ST0;=G8r0Ao@YOh!1nLpos-b-cji2i?n19lzg zwb!zso?ZfL3s;f)I}1KxwS@lE7YkNmmM;r%ZX&;kkJIS-I@1_`Koo&4JC zY3bi@27!PUNQm|5Gt-dO9`YkP8zYoU^K5DI`GaU*p(EbJf16tzLVb;$@Yu%2H09I@ z)Z)FA55T;MCW|f8B&H*r$en@C^g;3}6zH6RGlx1;x$P=s>y?2Q5DU5?bPb}(nVgv4 zU6U1U+KW5R^ClS+T(VGA70(@O3$ebpdfo4n zMzipn0qV39)tC2dG>a2T-IL0!inU%Q4JMHFPd+OoB4OVwTr&7U-S5VJMYwy`1BGn2 zq5Ma$B2L^1T&o=Rq}t2r-BdF1+l4yS>+MB&+|GU?NXkClRODZ=+%zZ)&7^H2X9g zuR6G=?zfNX987NPsaa-WD)*Po;e;}!ha#ZgEw5eQ(#RnbmpWBqvpINw?`c&MUD|vO zJ~J?{>YcBtyv9Z%EEc4r%gt|id8VY1GyU|uBvnd_Ik>^zJ$1iJ)aKys$M<-x;XeA- z`BZPNTK)QX(l1oIg`)s_|CBN=>2b4rMh$dY30d1Y7KZ}Yyzc=YRCa@{Z^d2wCqwq4F}*O}|QUX7eY4was*Q(Zb< zgwsYpsQYahP=v3hKakt=E7+*FbOm2det^fw=X+gWIGU72e5g~E-I|53^j1ew3EP;? z!UOxOqfxw<46o}Yy9>2QFwVfU8wL_bS638dF$}dR&B30ku4qotBs9?|2jALmiT3fH z7*p31{lhg0n_@3bRzVt z!&9qr(PgyZVgM(eBpDLJ&wk`lkD*G#LR%Da^AIAlopIw?wy25r zA@tM439DNhBkj{CQ17~@&#f#I5_zi++46D*^}gbYLac_N(=T1n=Uc9*_FM$I&UZwx z8CIyn#R-UoI`P<#8C|r<>!+clTWBK+zcb-?tw>y-dIqQ3j3=h*8Wesz!EZGc_CVgr zFdd~>n{XeN?rZU>V^fKFsVRkTeK=-#-l|%DvO^a7;4cwInVA@ePA6(%%_tnbz|m5p zN%`{p*c`MpS|ZjK%%VAtX~cL_YYN}Ua0HOoZf{N7_65jzxkP-9F;ZT$OCdYbTqqo6 zz!jP)Wt|nCC-YEPu|!0+e5P!qJ&Noq`JjO71908o-eh%JW)X)H?izDqW0e*wSQ1K9 z-x|{P*;cgsg$ZaUZ+E!<0oPk(GMg9rY>!6>8P`UaLJM5efqzLR3#>9`Cr9SeR4HHWo@tEBuMytG@{qI5EO z|4f&{bw{|)+2+6l#eIWxlu*}8B0kMlnhl60P1;&f7;6C69ow|4R%G#B^7c4@Z zAOS~bJpL;21=27}C3iZtqHyd3M>Pj*_j+~Xz1^g)x2uN8@vX=t(x8JAh2J&sJ8EfB zXL&g9?L+E%yO&la9^P>ZiHkE9?pk=KisSYNk8a>X-?7BIv5N3yfKLNBcfup+9+;Dl zp99E>dsh_EFI-Ve6oE=|nj<)81?RGOtlB3%a{PJ-*c|Rgwe^nr$3YL(cuJY5A$lC;xuk)%Yv_Qgo zyDJ*8W;pVvUc6tuS2rcK{(Z=gQS$@>s^D9KXHZsJl6Go6$@~wklvih2A~Z7rRr)5P zTYFtle$qsA`c^!uIO~E^3MQaSYh$>NU2BcWZ0i6rpo6VIKox8ez6WcQ1vz8Wo3t5W zqJ$PmB$>LRF{8$zXPINTk5RA9$@4*er1p%eKtL62X%)tcm3_z;hPFlFF3KFT;A zhYbB@qxSkPsG>9$%?~a@i!NE9Z=EwysQVo5Bek712@CKcTU7@tp#>5TtXz=E-56vl zo5hJ&BTPxLLoX6)6eJK(1>2C1;bN>vz_cEu_X#4j6(j=lUC_c!lhK!f8QjOY-?%$QP`j)IbtY(33@61L1A6Fr4?Tj8*XQ0|M6-YDK8M!;B zBcGvChCi2vW@KS)cVa&#ULc?fwunr&d#W|bo8OIGyFXE=IV3(MI-{-TsYs>GV(vpP z!kTm(;!UCkj1&l{g4c=f4L@Z?#?2r^>urJZZfkSY=}j?8j^2$%I5?qu=X22nqiQ6d z?1XNtn~Ahiws9XR6{aMBc@xV|`2qn|utoSTA%4v>`gb933$lfpL&9OD6Y{gnMtx#7 zb05mV)}+zVE@W1#Oo4zZ*wQ@u^Q1Y+`HsnG_j2XJp$=%|$OS0R@HTo_?10|-%|qYp zuA#trrpSHeGBoMa9qwbOwgnmf6ce>Yi)VuuMixVA_jpbB0azKia# z8QHOvkY*Z-g_^@UE%3HS-)vT)MQguuAHl;7$ys9`a!PBd5?UaU?q`B}F4~F~Z*Is( z$g9_x5SOs7#G$NQAfT$@S39(?+gcQ+F5`svP!n=+V^?y!Nx2eQAYt;*4vieQ4!KW} zGA=qS(DR`al-tc02&i%&V25@!t3-=G zXmcXtLL;(icn@+!Ua0)^*cN@iSB)y|O>yWeTO^xQjqD0daM@I2v@%MGK3SS^;*yyW zaXj9gq$U(8p#>6NZSByS^6kjeRi6`P-Smh}d{5H+QHel66)YjoCqs?MO%ES3Xy{xe zv_RrZPdgNPqY@3hCS~6{ao>n+{@_h)+LZ|eREahJuG)y~aO*`J52h&nR@kDgkqmtg zZiZ*9w?!wdmB_7Y6WpSMF|t%WjIusAbS1Pv;@VbQw7`m@{_7fZ z!d$py|eaRD0`?eeL^^ zX-~Te1XRIRm&x>d7?O@11IY4j{=)Tu#IHPC-eVC3lBvB*%$ukxz5Kslb z+hwxBa}CHt+Kj8--Cv4I0XQ$978#yo4<{AUi*|{HC7p^W4PzA3I|E`^GKx%D+$f~6KLaAU$e!b&Q zr9o#rCZ4g=NvQr?SYCtnP z)HvuYI$YbG6F~{u81!ue<&2vp!>ywA4LWtG8_i|`~MD!jzG?4pvF{2;%G09J##2pDC@%^U@ z1XPKo8oyYNoJt8H!9H_@c{o_YA71t-{rwr#&tVYvvG;=}DSADC)NJ05pal|7Dos#P z_(h~Ta407{dg>9|$H64{JD;Tke+#Pg!tBwmGJZFo2;+o9mM(dJwjZ(S<%DmYwnyPB zPob+7!*EljJ=)Fh)XW-AUXn{n}vG(Zk#4~954C&-v>y~`Z zbyqN{`FK|#ph~QH*Acn|h4v$_E!~Bh!`iO>YL5ceokVk%Nj2ZLSA%TW9z@yU60Ka#YsK$!W3L|TLcYGryHd3KXZwOL1leAy64j>O~$ z1XRHi%4BV+4(VqQNNT!I#?S(Z-);_QQ1A(KF<3fpd({mcGIUoUS@>$CKtPpP^ULn) zq(Ac|BiC;c=DgutxHz+Icu||IUEhOzd9X^T2P7W7aX_`}51}4Cq%*xkUuhGM=f1>g z)KYOl6eAV=k!fn={60cX%Fhb~REg^b4dvS8NI4;mYz_;p3yIBr9g&6gesuij6z*eCur{$B z(UsghP6Yz0;F<-`=x|k&jGk*x2JsOMT=Qr>+zHK{x)Zg_N&K(%kJd6R;&#}H1b5UR zaAgD%t(rNZJ*TVD_^^0hs-RaKcj{YF^(<+vD5px3==E<-{CgP+1XRIQCw|^`V@=Yoc|$UAVk<(^ zoKeGfD-hb0fgQ00dcaq8Z}C;#ti#Ue#^Z97tB_WBpBt#~k>zjP-NKzf3nUsXv_N0) zEkWhKW^lsny9U8}AMlTLA^}zEN1W088|7$*Qu1NLiDkduVK>$G1X>_*^sF-qYgmp- z9!bOxbG}NgR3{eqorQWtj&nwPHddf@{lq%){E60@WU8em*>lW^z_LRkaD+2j+;kQC z&^d$qa0^f&-$&~cuaS-d0aftI^837>CK=k;kZd~NT)5_tu(EeXs_WOGV1H?Sux0=+ zQG^LO`@}{dpbD-u^0^FMO;UdI86NV%gTOX{ZS|wE3o74Mie}ecj}{G8$j-J8@Q)R8 z0xghmdS!uze4dM3Lb7?O+%+}Hitbmidyz;$Rd#b1G{d_T*%@SUVvesSNjtj-M;-Sj zVF@m1Q*9n1@@(uA!Y03Ld4k`A&OJYj}6ffh)dp6r79 zwJ1QHETmH1b5J4Q43FUJJ$(cMs$dDFGw(IY8lTfR_!B130*S`9E~v_)6fH23>hXcs z{P5Dt_=`d=5Ktx7oJDDp^;+BUg@o=x&0(Fqs$EcUpG-7VUy6WOlBz-;L~X>Kym}L8 zfrNR2C9<>1L~k;3II(}DCTVkI1wMYPr$9i}o82y`*fJA2nn*sZ`e>0Lo~59=Q2>GK z*@Zk01kd=0GM>%+ueEJ;zLv`L^6{4={sgXiLn7;w3(CozhL+x!d^A>9CA+tk;7dCK z1p=yI3Hd6(GfgtPYytiq*_%KMB$^#^K@X>=BP&nI$GDxEq^!kq{MxLSKtPpP^WHpl zlKIGAXm(yO`76K*MP)Tbx-0T=_)b?eZ?p|6LV5UZIbY#7ZjIi)lj2K~KB|)`#+Eq7 zetV_Y- z3?k41iG~wh(dcG9(30U&sniqHh+fyLJ5;Y|jTU-~fAXLG~2>#9amnOMryd9}E2_?T{t&r!aSMn710(|Yh zD~i7SLVoaQ9)_*X*Ktj8-lJPV2MS`*Z6wA8x8)$|Cmd4jC?*d6{Y zsDf9MXCrxJK$dCfAj_g)lJUzGy=^gH9$}ErGn%=gg@e|~BQ)~y#sVwUe&|AZ{EPzb zqi>D@nG)L$&8Z9~&;p5GPhHW?@LTeQm!(ogHqs_r+m1jd8;1%6RKXVEXSnUsCxvsf z(dN6sLRejif;q+WS^tj~1X{kOrJ~OE0cp1Vq_`K6QUq_sT9D|zK00xggjbJn_!-d-XR zKV*g^EdH0gQKs0su-#h7TB4>?isc`S@;Ompt3&d1kI4_796+E263{n)*G@Df*Jc#U zwS$8N0;=|Cw?q!ro^mf2$;bT1Iwb0#j=a%`0R&ngA=aa1gGS_CPNmoPFF^tURZTTp z^0*%r&#DfR4<{#Gd?VTn>LKno_&C;wT)72l;bI+oZIufmuYd55ETX^!5WOtRY+H}z)m8p zZ4KFlfctW@X#Q=h(UMZ-X!#J^d~7$%imLM-K7{x1lfPZ*m_g7cmRPG zNIc$cL#29@O_2K4KpPFVUXd&xHFl6dK-Ic3D{8^}?u5F&Yd=JT?Hioqb+zXp0xgj6 z&$FuYQM6X_(J4cpZONF8c036th1Xqa@%10_X4~>`pZl(KmECjsufusbVY(IlI`Wl# z6n~EKZ=9X_Y_!Tubf4d~&;kkVC$99M;JeczM5db z5|7Ezr9Hty%^_j%(Ur!%t&xxCXZ7$nnUeKBgy8Poq!*Es%)mV?}-V8};LIsh7Cx=`o$YkI=T=!2$tQ z{r0%hCflvhYk$dycPkxs>6RNF?-WD^O?0IPZgoe^hvniv8Lo8APA_D$JQu4QTG6Z1 zdZMhlckTET9oA}_Bc3%gh(HS@!sohD>jXE{3zP^RE^DC9*GN; zK>`6)unqa!xm=rh5Pw``+D~XJNED24r5a0mBlm7n>o$6)&3<3;!nZGo1XRH*%g-3; zq{ZA?@-y$t#fV>6r>1XRsPcU@ntVYT^^I+)%Cvn-ajV6F1X>_5E76jw@DcL0x)Jij zhnj4g<3hZyUvGhcs=)_b=-jw;)T^`PS|E{I=|W3>W}=Fp(ie-vHcfWw-Ew^RO;3Sh$cT5S%C*M7vrg62@j5O zp>19ipdT{HM~$5d8+r2xwlMc0&;p5tuPta({&lBa_jRXctI1rSpT?U{Vu66Fd3G-J z+Lscv&{Fy;TBoVW!mnMyjYr7|v_K-$#D%s^oQq!EmF56E8>p~Wh7a-72swckNMtOs zpxgPZ!SuSX)Mi?m?3Md-eEPbFKtNUDMQ3`sWD$DwS(*a~w9;f1x$2};%Z0!Qb-Qe5 z`qq908g}u&qt!hvHJQw^A?Y96ioiH_NOa!oOe421M#=?}k8nd3W@IEI{s-Lz0;*sM z`I$&RG+5@Z4_IS>JAoER^gZNEFJ3Q4UF&8)Y&o$q=^Y-?roBKwm00sfV>Q{~Q|5%s zvLeTBIngC{o6+~oR6O^M6PQ(?Q2G1;YWD-cix+fa(^*JL&(2E=P$3!$wb5$oYh`qBhQ)7V!vd!@3CU2ZuG;-0QaF@nAiHfGRq}iGEDmj@GV|d~EgBVlk83 zl2R^4Z~be0EqSo7+K)d7W=f`aAv- zERZJ)sxF3pbg(uXY}1wK z-d741NK{O8q{iy|(AeKn)P3IqHFhw%3pt*9Mj)UHmXP=MS}mrhDJOpDB8C=7Sm$vc zCza@dnpBUn%UUd!d6I;mR|Nv9#F|ql9d_(fFEU9{f{hkBP_yWxXo4aV&t2<4r)eEU zaiQb!-czRZ5ITu|4v_W&xS8?sRb(%c^{Y&&QoTxsR_o+HB`%Z_=&Hc7cE@cxCzZ z7^cG-U_YW>o-foK)^=MT2RbD0IP%>zhWj{UuEE+|3na%|&&1FIiTH7*^lRlA6j`@+ z_p3^Wy|^1d%1ovT1XQsA2imXfIP#w-`8XJ(%cd^uM`F6Q!cKea>4hh!&~Lten*7L~ zMi`tz=bsJ7e`%T03ci+lHEIMW-23aY6^{MLR@aV#1rnxj?CFLZCs9nKL_{zRmPmuh zUy42g0adVsGFg?1F1s?O4=Ga}h@k}%UJefQcg_i9Q?~|ba9W4$3=bsH10w|js>GU) zUaiXxb_gO(`!*434r@DQjy>(S=`@mklh%Y+g=?~YgZmSc3Ns8XkO*i*x&r_psMiAdj~$Bq<*kkMWih%pB?OJ z8<(>vX~;nAJHmu|^PMlR+etfLw&m)vYZF6A#Dj7KEs)4}x2J1#&!Q3wX^p<^M@_c2 zb^w{zd%r+H6)Yj2Hb|&BtW)EwcC_;GS=4{K6lLL`qQx#$gp!UAIwEL+#B?hYn!@8U zoa*8-oZIU&pVJ}atzxqr5>REo&W=vfIESKVOK};&WAs_enh=uL=$jX`K*F%ljxMr3 zhu&2Na>Der7CXEllvH~z_kMV}dV=R2y_ zXj5o`#M0q*bmyzH$UVxB`!Ly{&-SNk&E&Z$i z8FY_FH0d_9qub7$K`J`lIBmKyEgEqNJ&lp#mS%bzuyYN9N$tu?3N4TbG`FMInw>?b zRJ(IxS(-L0jvqkW)aMHXRKXVEz1`M;?Ud%)C*%ul1qly(JGx-NS+u(@ZfTmP0kb|9 zOd6I=5eTS)?Z!`#OgCWTe1b@Lr)xsZVV!(W+tL=@PotOGh}T2wls5b9-k$_!KBCY9 zi6+6uG?PaNe(=Mb*t*7mU7FU9L?p_TkbtVmM{Q}r`%{S4#j5qzFl0*oKBRl+Hp*&y zW12euEb76d3a8Aqr7i}?(LOCV{E6??@wpZlB8-3zy(jJnAFnI0xA=0;bt{P-dzv_K-^gdJU3upZq# z(vbU@S*Xtrne-qw>qG*oU&;p6CDh~ANs&aI*@)6%R@qCySt8Pn(Pj<0#P+N1FRa=ZE z@x3zY&Q8?wL@uf@sYdaMjx-q;p)t1(aUwL-nho36h1iYHRC;Py&@OzJkSE_Iw7!Wm zja{FCyf0RuvUyIlGA|pAPuRkVeU+yC3~6uj+$UckpbGlt&#RYKtko7mx+dlerGmt` zflgGXPYzNE-NAhvIby~1;s}`=TqqDw1?$A)0Qy+7{M+8-{D&dRDc_xGE#K$$srPKu z>6tV2y*eE|XmCTx+ zDiBZwuZ>Kmw!xCM^5{usWVtF!U%OC$^YLiyLB4NnuM4$~o`_QJ#3SEgOX{1QfM)R> zd^~c%z={nR;Y%ibZ?A+FNZ7}^P=lROD0A!#PV{g#Wxo&hA}vk)1OlpH8_HyhZ&|T? z(w$VC3=rB15*eLc=w|z9)N*4U_u*k@&EAjmAqhI60s&R<%JOr5GR@gv-~Gs->EGx% zTPxbtVJd3E_gWTAb*0(qqtJwTebMMqu5_QlXe4VI!hI}hXv|`~0?CXnrbJf{ zi|&;LtC-h|jL)?eY7U7u?_Frv<49yuGl~01jJ0GzFB%BEZRKXUJ$vSK| zW0B1R$jMqaKZ~y7r?RzAIBBx@p#oYU0r%AN*pKq>$_5X@`MEN^C?ufjU8p);vu!#$ za8t^JFnqZRYi~4|ctuX6&;kkZdTc!WQ#t*_5OT2Qyg)$JXBBliH9rNt$qwQ^j-6Ly zi);px9$(&5Xn_Q5Lw;tMR|97Gbs%Yd%uxvmsItpaqdmQ5Ap43W?!(bhlSNyGkcpGs zmCynSvA3(~s<1X6Ldfrxg9QSrZa-3`li%c`&&DO(M=jH0b}jpo0GE+UXn}K-P;Ef)v`RKc+XKN)DjVdasA6G`L(EebO%z?=+X zwuNtgmz9O7T~nTIJcji0c`Xo7^<4jfBGWhvwGIvDK7J-VQAYk4P68fi zDWL@t@V=4BVtU?E`VJXEemQsw1XMY7zOUGOC>KSXO6EQmPI;l6svl0&Vttj+0ttAh z@wla7ca?o6hm)uIQ33%~Us~T&cy1~}E|;V`s%59w%DtV!$WY68CA2^S-f2AcHLP_hgA|z_)TGv_JyhX*>pU_)BFQs}Q2Hr9vQ}%F((Z zjjmjS)Xv`HJ~qs3z}^oJAX#oJmCynS@gAJ9PmQ%N>`kf_A^}zKD?=u$RBOcUFZCu< zKP(ZxKOiBF!fWT6vioISh|cwLfq*Lb?Za0yPG`|A7B{?>#-tILj|yg;5_3~^F0!GW z#`wrjoJb?k0tqoU)yqbqw8-PFd^pcx0trENaZgRdq!n^{PKu36Bv%w&TDYJF+tP>( zSRmmyEw{>l?F#v|*Aij7C4}DiQiRfYjx9())o#U}nuYDZ%IA%i2=mq#6+ShUXyd0; z0xghul9^Lw6#G?fnJE#^+VrCv=y!BNks=UKHGR&W8VwIeRJKLRF1D!4Sw)145mxx6 z5NLsfP0q|JjbV-`;DkgpYaT$2j0yH>l_U^Q745gDX34dFXjyp?C)(>e~?^hRv`e2PFoRsU7HYpgVKQSVlTocMb0u%dU# z4!nF_6oD2FQM0Tg0zZ}H!HWLK`s$LG-U9(fO1lih1QDGM9hZRpY zox&=m;|a7tBHU?4)fCqf6yqTggKzuLK#M!LS^qHt0aev%yK5qjl_R6)QcRJ{i9?D` zK2LE#-%$iwATc95vugG0a@4k=6o2La#fNS!`G$?#MhFB{{k68bCa&XZ)W2AY-noJf zD>}?+Kzw%&Apfpmh>4{z!LftgAy>&gaq5;BP@y->%g)9eQj*x%yHR zlJ58;ily%iNOpNJffh(~ZIe-zHFXP`~ig6|6iR6W<; zS@WgrHgb7Ag%fQLTvvQgA4jsUT*lA>3Ad5)Rp*}EMwgmNaR6P`hS5gJlSnrYDiBcR zynIK^$@u%|>2+!S{POyniimIgS#@+9h89R%X*j*g;M{%GPET5+-|I7k4!amlGG;Fn z2&ig{cGS#X^a$mxme!qRKW-@&o{lAbM;Bpefy9Q5u~n*HAE6G{BqFZ&Pl9JT}F|N&8Vj+DqkYT92`nFd`Tj| z2DB6isA^iWy=Fx9GZg)OFee7TzOBeLOd%g_EHJb{!ptVRO0U^-L|lhR1ottiX)19Y zcpE_is+|3{*GxS69BrO6fD^rVJ#MHzPK?@`Pp78nsvrck#nN7f;D8|4MoV~6mra7ri2zq{FpVd>P5*@RJ2keUT+*k zzuZY8PET741XOKF*j7_)^$<-x-j)*^?5`{CxFr$SEN>;WK;i)#Ulq9YA=+6h5x*`C zq`9x+iPN2N0s&R3i?-E7ez=W_J3DZq$LebeTSry(ec#{LLM#mIZhhOWc+cL;?m$sQ6vO~Q1q)GZ1p&pt4h&Q*EI<*| zbGL;ZC>9E0BX(lPv(J4#-|?IKKgO8z#S*!|UF)p9C*>L&t`O*od>nWDboyNubg_aY z9{o(yW4ccvdbeDlf`o`0oe=Mt#^z@m#NcIvEoJy*8sBx3LZItqpZMed6}rJ31By%H zrTM-db$Allb=@XVLBiM1E5W?>25YgxAWk$NVxeynC^0rhA<(t=Vf^v)2QRXew)rK| zr(=e0vwi{<8+JgTg2dkeo(VJ9B^K>u5XoIK^wK@Y(`oMng+NzA#K?rz%a5@;1+rx4 zwW)=jI7Bzi>w{(y-nol6>*A>kIn)1=WwD*wP8&6NHlcz9_9gOm%E$S{n(ME$KJl{@ z0$rEdI_O8gMrqFijozUDzuT5c3+k|nBW4pSNMK(gU%T`3it8g5GkHU)LZHi|rh}f( z|C=_im{B9i@unpt;s6^f|5b_t9TIjjCetLp+@e9rZ)|b?nF@iff8X2atCMQ8`$LTW z!)8y4#qU@#{<`c;LInxzWaM_+`+t_$dm1miJWwIfl^)+lA42`uQh8&ue5$|ZvZcP8 zGk=*skWfJaI~jR{ncXi-lgzMsKh(^}OZO&{cefWip|H z1a>m=Up4!i#l3k9pF4THLZE9&p*H%MouTZ(BcnHPPCje7a8&M|Z}uZpkibsHWGZU^ z)xuIw^NIQxg+Q16sn+_BsO4<+4Wl=(Tu!!ZdU%;{Sm;BjAc38Xyos%UjwLSN1HS0t zD1|`R^>M9r`@xZ{(q^M$x#5{?DYGDp_v<*4P(cDa899w|$+7HS^_|y`b5jU(*%WQ9 zTTVo?y`7Byb1L-o{_wt-8~Z` zYix=-YiYZsDBYRXpHM*pI~kM7&-C4LpkXJy3(tqe(CmEmfYXyKSugrvD~=Uma_kANT?uzos7w}J=G+( z2X>?{)vGH6x}sBC=mA@=u-3k_WsT8mQY;(tcB6m0DiJD3U?(G=C|=AhdOhw-D=rjQ z2z0d@+(K`Vl*&qdGWMw#olLdNFFrutxLBA_K>|A&lW9*(Ug7%Im3B@yDFnK*o;25= z6-{G1%tpsjB=NQ-XrDVhe)^T8f&_Ll^6qFC8<9S06fN%aKq1gIdt!6FZFB}p=|4f% zsL(mha(4e{iusqyQ9%Mb89BvC%r6eN97p?y9#sf*9kgk#r%isucC|A)mLk3GTaM%z zPxVS27|06vZ{7ovPRdF>6Rr){`4#>oTGvS z_9Z6MJ)Z(%;NJjx5jnI4k%oE z+ve$HSx{Rc&^7gYQ{8#?3%1>Rh^%q_PlhG#vYf%yDalbm0{asA*WhXaQNHI)YRzsk zB+xY}uBo0hC!3AWWAq=_vNJ3P!)MV@5zA0P0y`Ob`(9K5QD^upnzN;oLZEAwe^b5q z%WRfsy`!v=9F$?1;W3*!h2~|bAc1{}eE!k5fOvCo7M&Ya|2Pupvb1li|2>z@wly^R zk8N+$EfZ(VrunhqIx0wDUm~~kUfPPnp0g-&NmmOJ=yERCRIgrJc96-&Mq_nKx1`z5 zrs4Z$Sx`X&I~jTAXQ-`s;5L&kx!+I-bX|MVL@&DbIh&fx=s$+q-M8$SF_Vf9$R$ug z0y`O#>348`Q9C=396mNy2y_KMY@#oVc+4ueHjy=Qr=(dDt^`t^{G9|UNMI);w_g6) zh^$`$bg-EY!96(q2ek>?FY<`zsk-I8IJ@Ay*o3sjK6PR3-KT;hS{#w%aye)6zFpzEyr;p1g;A7ekCK9?QK+`sOY z4@3OO{y>sI1qrpsd3)orUbdSbIc+!(KT3l+wZ?6nc2y|__yil*!-jO{xXFM_azPPCd+diFxS?CC(Zqqor&)fm)BBu`txQ#>aUDo9|rB+o&P=`0%l*~JT6#wi54 z?)P4(7qSUu%|{qr(Wl@BqT9n*UeS3Rp@IZpH8Ae{7LRn$Xg-Ml~rn?{_aZz za~)uGMK$)<7w0Qn;--$H2^A!;TassG;ya2(`OSY|b&D@yHK zU&LiTZ%avs`w#PZ|R%B_H8y!7LVJ}P~2Hki6#~9OsF7%-ICmHTh>){dRd!B ztu`wJy4J0eHAY(4-z&x$-YOA|MLU}YlxIR4LInxzmQ1EEd3%UE1zS?|HF-`LJ{P(w z^H9CJNM-@IjFYU6Pn(L?e;nvp(|Uvo64))tSK{?vB64^K@(8J{5a{xG5~4TslXp$} z&5|{=z!qY@ZC9!$PyM2T1a?a%)6)}uMZQISXpWtoLZGWlXozm{y1_nvH15)SQMR?H za=$;VI9GsBK?1uald1m7{^DOY&aliUY-cuMza(4X_HUL@$KAc4J){23fK zSo}F3NT2e$S&%^2h|S2w46*uK+h4Qk-h|!wZ{$>Jw zZo6Edf&_L;vh!LvNHn9Ac5VI zJXu_Nuz0s{EX|DBtq|yXmlLcfc00==rWjq3?*lG08b?*u>=URUf!&hHq$jo$yR*ko z1|3oebS0l@uCswjEPImC6`2|o5}v-}C}cyTKm`fxmgIbQ>=R4q({VIm-%*7?*V$G_ zjyso)VW)hIt|(R;Wm(n3!m}8+m zvc|HjFZ3BjCs6lxaRL=2YOEQa@WEy~J5bFa>P#JNdDChlm9^QU5a>#-lyv-+dnCIu zYn3D#w0)sBcAiA`UeN*-B;LOENa&F*iDd@S%GS$r#?GInq_0&7bp8IEbo`&~YUbiT zM-rCoXL^H4Q)tGe2!RR`5j8y$?k-s^pYR&Qsiq?>`J$)NLz<-!=;BdFk2|L=VXyv;#Ms;%cSOeszgqDb3$ta0fn3V|+LndsVY>KCok38O#1 zkv3oEC~jwccLxwENZ@Qh?g+PADqiMfu~BXORRU%UHam~#LFa0+SN2AY%u{p4fLsOm zqft``75uz78<5XG&W4Ms@8#*?hLaQmT^)uU(O+lwVRh|{8Gzrlnc{c5-uz?2BtiuV zoDIl-RgZJgI2(|AudyNGRG)N0$mIGAJ$#Y>}6{r7swiZL#K#l=ZlbY zjb4Nb5;z->sXacSqIu~uw>>mFt^KN?Rh$5)*yGA37~3cuPBDoEgL zz+_spK1>wfUW-=Tmv>;p=R(&@ze9RGlg<`aHf8|pHwKE&59?9kDlG^VB(T#rZc1My zu0}T}eyy%TpsUQ+czt)9Gi**xV+Qa%O8yMSwV~S=dtj^T=aw$Ru37iecSK^K(;^>lIbS=hKA<*?USG?Xh zB8BBzV%&BA?a(~Y;H#rdMaWC2Ac38}ydTbUnW&rYOz+mc<4B;ZQ+S-79(jw^y*)|R znBOl*oP6X;^{!@dRFJ^gfILn9GeRtzGmJbsUsecoEiM&?iyk#c z(k7=f92F#RHXysAo-0KBbT8uNcPj+C{0_wG37#1&^`W<{vHZ~j@$rNY*|dn_s33u} z0r{NMaixgL7)#Y3EKmq^mF^j<+tq)_79JicYYaLTBKltPqp2Nda#WDO*?@drn{Soq zab-N6ZP7y^&^7DBLH$$P$E<+AyR7lDYp7^EZW2}PYUZdQfwKXbWahU@JP({iuL27z z1iHFzIjGNydcw@LjC*lXB0|OdJN}e1nQI}ng4bu1iC&AI;hVW z{gk!5X53k`Zeysp#RI6%n?(#2B(T$$C)^gS689eYlOKPtA%U*_Do9|bFQ3;IUL^`G^QW3oGb~7;D@z>E{pLPlu_rsq8gZXP#Qt^xG_=$z3o1z9 zY(Vyd2Um)0|H)+k`>8^p%d+@@K6u|l_PCmZtg*~LM9kUaPfLr~3RIB5*?^og6j>?a z^U0@ut6L}px^4y?(BmegGkr@VS)={a1!9fuB>MHOi$DbloDIll^zkc%rLiB4%0EUS z&^3Dd0liS^J8T`VDQnn7FA(EujHgN60tG5a;B3HT$~m(_-0ClT=f;Z^0$pui9ndG= zNnvIGl#?}lZY&V2?>MSBB|@Nr1kMKJJ@f-siUs?;sr#}G3W2WE&Ik4AtP8AAT2WbJ z?2Hf*aK?ugY}z7FK>}w3aw6=#N;LBFqQVDvDg?SLSqJqMlTWdtm-5LPHP?rVsnMe; zXm^Z21qqxD$aetW!^HW{UNrSVtU{n`XUPzK;F1L9nrPe_aq5VhIGXNFvz8_ZRFJ^g zfZT6)>MZ)C`B1?8M1??CU}Q_(#cwwgWsMoYDi1qx$$cD+?3O4{K>}w3a+Z-%R8;Ql zOD(&^D+IdyR<_c6+=*ffF6@>y8a~OgT-@hJ+us}%s33u}0l9@#p_r&H_g+^Q*`*NZ zsz1NA9-X|N*>y8IdjF&>%Yg3_=+MV)0u>~1HXvV#{fmkb^(IlSbE_2sU7AZ9edNrQ ztVbcEqfff~%o0@2pO*AkCQv~FX9M#4vA&3CojiqRwF*=Sbh+kr&=(9@%3@v{HzAxk z^w<)dF_rFq@)W2bfwKWQd-Wv~ zlo6;Pft|j5&bgt0sNg!2UTY~9B+xZswS(SPW|O;Gv&m0a&9LlRH;XFf-)}($37iec zpW5^9EDs;fqMj|>6#`vr2L3ueeC8sSyMBK8b>wT5Wchq-HtE$HSx`Y@cCBN_hg|(X zA~5Qt$Q-lVT&RgJtr+sedf$9Sxph14N2>MXxA9AP=in#0DXEzDtGm(H_WE*2EO=W* zbKW(cP(cD`1M++RCs7n@oUD~k^-~CR?G1dQ_ZqQD`&7-SG2nfSsQaxbyIFH0p@Ia? z223VC_K4VZb0YhcN50+o{xXhb|o9VbJvP{MA7OSSm6f~2o)r7HefQ{mtXmt z%lFyYa()Vdu9%unbm3HkwWw;;Xt`{s7;rZ?|8Rdip@Ia?2IOnk6eo7M*XM2B#wi54 zHeP)dWMTaplfrJM|yniYosA6eK)4Eny2y``A@IZIya*9E3`BexNByct$`}0AuB6}gHp)*P-1iCK2&d?WcI?pP1nJ#O@y^j{C-wTpi`LoQseN27g+SLZrwsi|%d2d8vaz|G=h04)IIIs9P5;eNK>|B{Ig??B zg(=2~k~Th42y~qg>G~<#RJOX%L|LO;(r&T#)F7(;^d3hA37iec=bZl%M76_1=)`J^ zLZGX6lXQJwsXOd@P2=Qb71tQid(trKd+`WI1qqxD$gg~6qWD*01YIu_sSxO@5OZH2 zGVC7fUw*W#kruaCY@FpuPn=e9RFJ^gfJ_lYk%B0Icev+U;Jt2 zOHs4ya8!`M*?`;~v_B?xtQbeN&U|D@psS0sJZbkgQ$8OYBx`uw*)ImQ8&Bbz?lDx5 zz}bL&N9KA=L}vQZzg)ozfv%L_X}WpCLss^`{<6lypZmqB;S=cM)xiuEB(T#rnRbml zChSN1QP+u6H6+mW_F$U6XV*ja^j`RsM8!wmG%Z)4 zKm`e$4aj%M^6N-iK8m#V3l#!g!zak^huvjX_jOrW2IRE1 zs)~gJOyAaO(PPmp}yxoDIm|?Jr|RVjd4#x@f;bpsU-c zIDPNFI94$JsqAs0H?0+Yc8;X`v*HCRNZ@Qh?o2o=7SXjmX>-NH3W2Ty0ipVYy*rra z3SHKCaejpODBtV8nRr;Bf&|V6o}$Y>A3FK_fI^__YU40{T&2zI^k8EKke$D~ zsJeYDeX`vzP(cD`1M)QBR8LX-_*m*aX1hY5Yxk2dy>7*|?8Cd2vPQ2j-Nd}_zT|su zi$DbloDIlXU)NE>dzT+Ie6w63(3LxAp?>*Q1Ph-xTh_Qctg9$oOKvCRSu9XN0%rsA zmAGiQaPKjRiXWS(5a`Ovvq&HEES#NRWXu58ZtW!Ayz!^`slx;+NZ@Qho}_gOc?%Ng z8aH8)K5$AX+c>$TtP#DKM1_sh>4Wnw3o1z9Y(VbT?&u)meoUuo1Dq8CUEeNu)}ORm z_`exI?6NxIq|;2=JL5kKDoC_h<)G*F`#)kqz*CX@-&*rt7f-V5Xk*P$yIf)k-;?## zIs*tixrD!Wwz0Ia*lFF08-4B7_IE{KU@`4xM{hy}37iec-weech}9l(TFtv&3W2T~ zjy4v%ut+WFjnUVB^}Q})_vc~afDfU91kMKJ->5<9VsKq|CbGN~0$s(qjpbDMd(CUL zQNw1~H8H&9GG<=yL#QBuvjMq_6PYIJw!gyWFY!_cbak$1V__?*u`WN1=jS&AFN<^Q zzp{x>ya^Q~a5f-+C-%E7e(>tN*?*o2fiCZ?e3sHVJ=oQ}MvY=EE{NZEHJ)+Di%>xV zX9Myc`uwS)^$1^H_Nu(o5Kg{p6 zbWsR&Ep3#~5)5-z zmg*PQu*r*!{@knJX_3(8KEKhmKcRvI&IV*2i?}L=hrj0QVtXhAx=!uNYpHc-3%lRa zct$_6#A#6>`zt@xxCfzv1kMIbroQ&qL@nRE}QV4Wyv&m~|vOJcRw>6&8=UsV5On6k5;+M4` zRFJ^gfb1YET^BEQRU?~1|0x8z)*i@X>1UtBMmIH{(GU5VEK1d^L%nS45GqLEY(VyE z@i#=}K8-1=PkDtv*D9wxmU%A)d**38qhELMocI>jg05thk+(trKLrV#4ahrX=iQV~ zk?)&hXDz>^i#m@y$idxNA<&iMn9Jh$=PuiM%h=OzbNRYxP-7JBTHBMO zf&|V6sc=QZ;d9Z8(#96$s33uzzPwj$ z?*p-MnkNmgJHwDbmt%^_@^aOEcGAb#)4$s~RRno@)9DTe87fHNY(U=jRy9+Ma`&Q_ zWm+o)y2h?ISsMJh&q~!ZPA^9Xr;0C)e8`+#jG=-AcKY%R@1RVPz21v@n(iG#0$nA> znk<*n?z3;%#-4uv^{K+a$%nR%Z=|Dw1a|uJo&Ly7an;d_&fRZrK>}UFJDDu!9PYDe zdpgS+kHS+$(Qn>VuI?ZUDoEgLK;B<6BvW+S?n$<_b}IzBCf71qYSp{P>iV^lHTsTE z6%X2a)1|LT7F3YH*?`IPqkpC-HE0y||78+Lpv(U6Kb=3j&Fl-ck~QYEO%>Z_c~R5l z_5u|oa5f<4qV}0$Xxec4z1^%3=&JnwpWdk74d!{SzO2#d?F}*i(MYPazNbJ137iec z??;(Tv9H81YJFskLZHjv&SYtJ=ra4Tt(vTn{p*HkSYkLG^_V75K>}w3@_E#%OcB*{ zD3$sgsu1Y9(7|Mhp|dP=vysj5dP%CN?&MAlla~lokigl1yisn~LoqgPFx73bMj_BO za;3?#rjB4ojueqK&Yid^%BBpVA$E}h6(n#rU@}!3_E_BW8bm2`q7(vMtNxlS-PRmo z=bz<~HNJ)47Uy>jriN3Z1u973Y(P%7lkbXWja{g#wnrh*wIoE|o_Ay)`#SQ8?4w>S zIw78=4y9&p2Lvie;A}v4kfjsE?rZMkG(k=%;B%oXsqG=XT2IRAe7`a&!5-wj)sJHbg7Byb(en;m$$vv%3SnN64Q~u*?>GJ{Ozx3 z{I@Gh+~KAW=)z=kc^9kuC$T1GKI@+Cq2#zDfwKYmUbN(IaZo0k9$)RI5a_}@arwKw z!+Wu->~l73zK4=Djs(sI;+?7mkB(T$$ zH#Akv5iceU=Yv-aRtR)q_O_hq`)7-QpL4n8qN|cLjs(sIWIs6mlc-;QHE$vF0r7L8 z3sbe_xgvQx{(R3Z{AN36B|RGnoDInRUDuD|ZR-PkU=K%yKo{m>%f2@JxoBViD39yd zk5EAZX9Kdvz7OI^hl^bA(?cQ9g(=rEsmb=aD0=u7A9lJ2p@Ia?2ILvu@gIc!t>=8( zmJSMmF3gse9pukvqV1NCT+HjBWJn`{vjMqfvGapi8z>brX>ES` z;~~${Q&~&QpqhV#;Pc25{7N~jK=)xRkxhc!CL}};JRJ?lwC3PAJ zoDIl5fZm^k&4bFcs905nKo_PT%iAvkUx=!+YSQrGm6eoZByct$cZ8!piw^Q%RODMR zg+LeP7t8E{U)kc+#-?=rxt)^Mj0AT2a^I&`j&K>+hL)}}DFnJOHCX<9#J&>eIHS)S zek7a|Q5a_~$U72G-@5IRleaSB(QOOfV0%rqqB3$jK=n>VA?0Rfa2y|htt$YXY;=S+7F_G6SBUL) zI2(|!k|X~_vm8K!qoxVJMMy3;cZQUrfkiU|CiY`nkHJP4x=ZI?gJ?O>s zFeQ@}37iec+os)2CwBiglp=1QQV4Wmny7p}7?vY;RUbz6(o-y`Ac38}+!hHjorsQi zrSLZel$=p?sfnJI59Nrv$VDRq`N_z}bMz9{85~L~?X*GS!g%Eu?CqOHHErz3-=}KirY>+C?e3 zGDzTTK+Y38{SkX)DtpS~?FxY|%*~PS!nG_hapC~#RAY~lsDlJ{`f{>;B|~g};7oSY zRRUd@|0DlZkI#r(>xNR+&KM=<2ML@F$a#r4E9M5e(aKac83uYVbrC@T7^It<}t}<+tZW8$A2TJQr}fd?h+C>8<5Y>hny9q zV@6QMpJ0VR7v@UI2}|`vv9_-lm1sIw$&W$;X9FfvRQ@xf)L1XNw$DW&(1rO}^0~o= z!=golF(l4)7pNeCvjI78zj{K>;l@y_f@Ku~U6}J_G6l_w6Fpz}QbqUN0u>~%)0aLYW%$Dt%DIb(=u%$Fx-loFG(i zNYtIPgZ?)I7@N3NbT~4Jmft9CK?R9R^N#5M{rEp(-QSD6blfg;d-GVDtk zji=W+KcH*TJAD)aT@>&{^Oa`-Y^obIs_n?&nMZQ5QxCid6(pAQv0<&`=0K!%b6_`5 z;eFjkvlG!i3W2T%E>Esf$%%kT5kV-~aHx4j4zBxYzf?5Erum}%V{__FZ| zHxEu_Pn!5B1iCs^d!jv%X8}4}&jLK#c$Xh2_K9t4C8u|wAQ4;MhK-P$1FqK1fm6O0 zdCTjyxTC!17YTH=z3^CTCC>u5SkD5a(JdZ*&w&r`K8jF5;?}c#tc%HDW37JC02XRJ3$Ui-4PL@#0q>R9gHS<2Uz3kj44=&EST_fbA34K2 zRN2J8RU4)d=qj4?NUJE%0$8kP0lL>r;nO^~^FE$K2o)p(J@c_&a&w@Gb#tKh@zZ>L z*(2O`sjEVutH;_$+Anz)z{h$PfVaEGpBJ|97*A(H1&O~6^09+*bKtpkbKrT6(>&_o zb>3j}0EIwTkA{ylU7iK7S!e7T%s79QKOdLIOML80s36hsZC*A=ZVoK7ZVqhycZ!Q@ zZ~3+gy%hpo!xJBBHbGliko7D;?AfclUE>^n>1tO(1&LNW^RnS`bKr+{bKs)$Y3|)L zA35Ibs1WGt(dwbrRh|WKx1I$!-ToTi*uMa+xyJ|N=|OJQf>}-SvLm~Ze8SuQoGUy zkMA4_bX9iD&>UM`Wy#jF0K5L)<~Oorp78xFjtUaBHsoe}$R#$|x;ZfE#AV*5Nk2Ng z;I=}bYu@p6t#E-P(1xEA26{$IsG`pQ9B$LqG16VAC?IVwn$e4UHEkedUot(ya{il^|fgYI-> zLxe)0>)Fox+H!doV7m1zKv{WHXk{07nptlyM+FJj4Y^pd+#DEa-5jXkbe%6MGLrgd z4O0ko`PRFy9hPSS7F*8(xVOyU33*3Q&;0Ea^hD!-Ybf<)?76QkAl*?a5ez}7*jJk8dJ(w93b z1iH5WNYg^)Spc%01(;MNlV4cmMd$6aG*pmyx7Nf$<>o*~>*j#VoK&7L)Q5&#^fn`b zt~2}6v>);;fbD(bEWp*SnS9JjFFIU#k&X%yYkW+s-o5**#!F*!;L^-gUaOW5O`Klc zf&{vDj7!rF$+G}UtY-m=_0HtYYj{yvuW=Sska*s~#Ok-b&$e4P2lkFi<$91enVhyN z1iAto(zH+VEWiruS%9n#ncQ};C*50f%7O|K-)opygxnnHXWbll)i#xT(P+vw=C4Aa ztI^N9+Dv&C;HdR1K$VJ_Jbm#u{jXX@Fw?=U1}buwF-eQ z$1iEx4S5#eko7FU;bM>YsfRA~qRR$>3KCh%O)Pg^!ERbN2i(uy;vtT%wEyE)g+N#A zu6vqkvCghr&jQr?_L$#GbS6vh?E)1f%KS00vvPCbp>=a09o#k?~0&zQ86>ARfe-|_O^h{^+lrsP%(ADzV z1I?VZkyWy$1N*qW=J_fNAk)F^0u>}OrsZKiZ`ZK?)`adFBOdWKp9j&Ex0@9LUCFs0 zYAO&Z@&_%U}W<4O<3a)m(Gwfc{= z4Kl6S!J5`Qw9GqRIIjymthP{~g2dpbdD$bGm~LCr$ag;c-y=S%nHvR+o2?M&`rGoc zR`P5Z3$&(A7YTX8SNaX1$8CKCDoAXdpN}1q$?qMl$?r!aAMl;Ihf}lCy%hpomO@Xo z44IzIt?AiI`@iJLqlVGyyUhhENKD9W!@7pgVtGQ01p5*1@9|1+M^T;lA_{@7aqFIF z*JKL#I%^7e>!#0n`TFvnu>4Ofs30-M*@jJxpUSSJ*OfKygx%r#`q5Ol;bw(ESDq73 zv^K?Lepdx!4`9#qC)`rZlSbd1WEmEM59&ZS&wmrwXkSoTYYtb93IkckH!-{ z6arn?dCNOY>zZiJoEO^9S#E?15_`kTvledawP`^{jmYkwd98u{+1N}Eg+Lc}-ts1$ zYJYjPI&;|a7&k%%iGNedv$mt&XtSCdHQG%1z(=e+&2GngCD{~ofu zZf=AM62E(wXXAsbu)_iwJ&-3o1T2ZgrN$7F6_KzMsB$;JmteIKJD2cLIsJ8_;T#z`U%W` zn6cR(`YemvcUjAyM5+Y3u=AGN2?am#K)#9Zp6EoVAWE`{%8}6{A+CX=a;|X=5NYP+y0pq0$td7%Z%L1ANaS`HZ*=p zOF{*SI=n1?X8$Qz1eHiTs7iuz9s~HYz(%)>vluif@f@ zphfTUCUo$niox@QNrI}Oi^K6g3ak`(ce9N08_o5TePb&nvu=AFGKfZqF zKZ1Kxkv*{-6(ssxF2x$~%kmw7(b4C$f6u3Fa-zkHqZ9&N*m=wIIN?9JDcFgoJXy+7 zL88d$QmkW~JfSdYw5)OY{0Dyav@8NanTxCul=ln&)lha` zF`E?vUD$ccC)G9n@$=zsG-|9fLj{TAJs}*v^6q5{tImv&JoMv%=fE$r>$q4)5H}gFamIPzZEk=PjSnn@x21(om|=Yn25R zBq{{hv%Dj3v9eP-${P2F=kS_=!^qF|m_ncnJ8${i*~LWc)({%(dC!6h636=4v%j@( zvKqa(tTA<74j)$3ovIhJ6-b~9J8zR|$utx7&m2s7+Ef;(ATh9}J+obx!X_1MA#1E$ zk;CuI96~3Xl0u*hJ8${EB+^7>>kXoknSBK+NZ3@cX9cfbVm&_nCu`KYpTlDgyU@uo zV-*5j*m=umcaKeUcjy3`Hf^dv1&Qh{?O8cFdky|tMb>z?{3~zxaUhMV5vmaA!p_@d z+A=a1osRBD`XX*VjBZHLTv3 zMjTrsP(i{r#h&%xiR`mWVOb;c;t$@tNI%N+W|Kmo3p;Ol`$fMz^zUOYS{}Jspn}BQ zo+Vkg4F}oA{kdfg-r*15c&`tAeY9O6(1o41+ygj~kJ>EhL3Q+P0u?0stSQBsZ`;Cr zb24Qg^)EOVy&Tb-zBE$_bYbUhGL@CL=zc8PgZlK26sREauu&P-=KV4@b8?cbv2t}D z`r+P(vdgVe2y|iREq~6-7Npp*J*m&ur2-Ws&gLu29vlv1y}m@t8U=snA=d?tbo;+B zg+Lc}-tvFfT#%-|?M*@ZW(ib~*l?>X`{6L34Qjqz)^MDahjt%yqWzP{Cc zyA+T&6!fFFy$1+Xkhr^~9AhDYEVk=(S>wvTT$H$a5Y2q#pb+T7&RcGO&dg7_rwycQ zK~)7RNVrum&sx`+$XYD#Cu_uQ{Ksdn7($MFe_4<~7k1wAOm)G0wB2biB|l2Gpn}AS zpz^Hc&9UsnAY%s5IP@1!ca+n?u?rOfUD$b>OdlNcP(J@5bi70x3o1xBZ!gd4fARTW ze{Ls!^R5frX-BVTIuhtoJNgN8=5g0<=girAr_!-{i>y!bTULtT?>EO-KOVVa8UNgT zk#;A_Udvx5LjDYnn6{K(S=>;&^Kc5Gf`sSWBU)kC656s}#-07PiNV~Xe})!ZXR1P= ziyAG`2FRqp0`jF*(>cz6`dRLiZ4+;{apC8fY%Upod|9>t(NDyD`5zJoS4^Rkn zb*!{Viz&}6VvVXEnO#6Qd5+k=A(KgClfbZ5^faZs0^ZUJ8^2~E8 zfvyYZ7iw)~(qFbU>CeG7oa?M7k1aKkP(dPki2Qy$?891Ha{=DjPv>V^&Ev6g;}rs3 z=cg~!TFRuqSZmUs)Alg_%6loF+j<hH5cG}1AiX#>I-*tb5RI%`7RFA zy2+%!9Ba~FE}6wQX7V5Y!)^eff<(R}hqV})3$VkQ3vlb6KOgegmNIAcRS0zTrZCM@ zCjFJLCjI%H58;triqL@-JqQ&f{`5Jl1 z{t~T8f0trI`TnmJsK-DeRFLTK=#Vx}<^qIUa{*p2oW@hi)uy#u+9(9NUaSh$I?JR# z+pET$Vb`xPes@?sdN!;Xp@M|>*h3nZxd3Y_8$^)D4F3JU7W6NsozX6U#vl>AQAZ~Ub`f70hZM?CKKl(XY&&7?P;2vGa!MkQ<))}t4#Vk zU`_hF-fuBqn%;@#-?t}Jkf=K?Ui&F?0kW;R0JHMU<9+-0rXNuS6#`w`fkJKtUq#Z=4n=a{=mEa{>O_JD=CQGKfY@|HP3%*X4R4+AEp# zSJ-SM{gt@2j6eG!vjLNya8!`E85*aR*?5cfwdMlst{=?pw|G#;yeSHSuHCm6XisI* z-x+Jt-#_Q&ykPMW^rzPejtUZ0O2=u>WG=v2Yc9a}aSQmRbEBzI^j?KPSKxvLTDVO5 z^Rp)XrLS1QvuAtL>B%xd5N7xd8SfL-@gdzO<;yLWMwA74rh^mrVNm zU`_g~Gf-Pu~7(g`3?%!?#raVFl*A^ z4Zl^~{M(=YUFxZ!g2aF_2em0O7htY67vN2=Q0|-=K%MMn=t!WeThm~z#;hz>ysxnb zFumm}9{E((m{-7p3KCtP9nkvATz~`CT!7g&p}a$2039<;QV4Wqm5^VDO!})}P5P_< zb|uf_F=Q5 zN}hCR5+(W;6sRCEe&GRakIV)5Wz7ZnoHvAzct44r)oh^<=xX{RNb4+<{yeQoe+@EM z@C)`6s7(8A0u>~}<{r@UOiX9DthoT`+ZS;EQWJ>v9HS8Es`oEQ3zA8HbF4{!J-4pl z9h&=6>Y+e^3KEr~4rl{qEL&A<)$!Bv>mRcZFTHCjAv$wvrD? zA5GI6ZxN^Es$ zC~x>f1qsveIIY#)`j9qX-UrardLKZ6g-c~dwHK8tu}>k;<6GF6GW+yy^FUQ3`>st`Ebs5%Pw=AJ!ZGd{Q>@k;6w* z*T3roDoEU~n4nFN_W`6^?*phHZ*g}RF_yM_E>#G0ZJ)DH%k?^fZLr?(w>L48Cr6JV z|Chl66(qWUO3*qETEcYeeE`#UF6I@AjVIgHV-x~iVWvge3VFld4eJemU$?I3kEZ*P z2kS3TK_Yq65zQ13#%^2h11K?O5zqT!5_RlYTOrW3cHkn-N8a$~WWC|7d?DoDI+n5bQr_W^vi-Ukr&d>QXBbPE0c&`lxGwJmU`_ElT(zZrn}$40(>=46_3 ztBeH|B-T|;)Yhf_-)8@gMf=(6?f1-gOU$8M$7D{Re5$`9-*R5$=ws{0!M`GS=Zi

      Cg}pRi$b+iA_bXA>$&d~|TooWe_LLA#BqLH5NvtfKonZU1zYKv(tC zN6iIhY}HO(H;DYv`MAy9+H8wVML-3KP0bv%^IxO1w}A$+_S`Mza&ZY`|5O59-}W9g zZ*TEk+u&&s)hguW^<(!l^ShaZ3KH!qI%sA6ziA7L8AO>SH&~6Q-`SB9DuJ$BbB~&f zw5r3_9WZ7YzhCF#oeLJ@K5jDz6(rt#XrpaQs?DAZu@alFvP+K{_vF(R0$m^5%I`;7 zKej#6I0Z2z?JrwBeITzmXd0n{#NC)S+BoXR*2w$@IeXoBk(K!()21#@Q3!OMxRqq~ zikiWqDj2sqx|IIOYG$nDTA9g&3KEk#wb8=gOlQ@vEtbT!QRmp+!!f*u{0of)x@=b^ znXBXvW4#+1L}0~l%)V7T&-v?1s35U5PaDmDXDEC2$k?)2(eNzW(DMvGFl4Mkpewd} zlKGhJ3Rb6*K}@}#!@jy-=38HT6DmkFIoevY*}9x1iF^z zB$~Z1M6xn3jTyk_W;v{L!7LsTJ%Ug{;@ha!TCKs6toCMu=ruB#IsN?3=M8dK2z0$# zn`oZbdWTF5F?J?QBXZcye`Y`%{>mzhDN3iV^&?b}SP<1pdz-wUJw9V>Kztl{j>Wi?BlFCj3W2Ty zXO5VkJ~_f{y^MW^ouj|AmW3-*($6l03KCVDwbDj9A7Mo*7(}}31vd3V9Wt#Ug+SMq zK1a;6e+hPWwXx5ztHCceHM{}&&uUAkAQ5S4sr?x)SjQd)QSa*|MvYq0;3CZw0$m;M zB$(OkbL{=*d6M|J;xC)Mx-EseH6T=wsL{ElmVWyzyVBnvGCy8rgO7Kl^FOOA1iENw zf_aDQRd(8DjwB)*=i=v1b)}q?ii8RhHkVsytF~TY-F=Phfp(STP1VgE>11>Xg-~2i z51Z!%-DE+FjU)lBdLI7aq!XR9FH9y-kl5d^h1M@AmDT%XY$xn(a*MSbFoZ$}=28fB zT^@JX-058!^Sop18a(-xm$&KRP6Ny4a8!_ROK+~_E|$iU%m#7k=N*>+@hE!uHB%wb z75eLtIro|etohpslK2v7!|hv-rkAa6a8!`^>(g9wjLu+>`Wr;??)R9}xpDOK-7$qg z*Mo>d<~!3Kv-kJLN@B^Y{QTooKk{+k&rw0b;a@ZD-Q-6sshvTj*rc<&xhK=sv1=6q zUEdoXGH=@OjIG$=C5elfw!EH9QA+Nyh@*mpd1EuJanMuN)XpGUG|pg$Y&PTP5J`L%1$fmWGbl8uI7bDE${(9*lV`tRhrA8q)$0tFP;wUCYnqvm_?V8m^~j(&%dY7%E6qi)pIeos-SxCWEzWI-AaP>ZuUu z8vHNLT!_D7Lu>StM2Uq3c*L?<^seI%4HYC>_%_v=z079z>m4Pr^uG*NFL*Y6jNf$( z33MI15@)_r=M}qtsHY^7nib%ycFdxBIqP&(keJ!FsaExTHj8U$5DSCTS%i5u9dF#x zf&{w!qvOmImcL}3yL6F6$;-C9c9U83dFeb0Do9i+(NybFJDbf*?ktJ13HRBX=CkNc z&Fcz*uKJVX%oh6>tjTndElpM6c^P=pn`;FS`#fP;xVh^Y7n3MrLkLAr_$K^ zJ_>=ZCE;=AnV%o9)ef~K(e9NE_xd@7X08eps35WZdlRkxune~QW-UpqFP+9}-SekZ zw{V3(SKFI$=9}qv*}{tzBoXt)hPROKttQ4S7pNdnwOv!qm+r8y;|!u%Y#Q5CYZ5go zwn-t-71=J{Y%X+z4GbtQi8Uel`IH3{C?#R5Kn02Z`yi-{I8V2#N`h6Dga6FwJ z7^4vA^1Tsn&Nz6H-E5m*64Tb&^7B4^%MQnuYiw-*M!$AyJ@$#5KLSHgRAQ`!vZQb_{vKPCp$- zQ}-QJ2y`8)d&E4UYz#~GF_QkqxY+T+!^Y7zne>MW5}~VFYD;7`;2CQ+;Mu-e%&Dv& z6)t^9A<&gpHPJj~`ZnfNXpgMXHm4|GcE^`GH$Ny)L1NzGR@yX~4Y8QoJCfc zKwCcSQV4XNE1G2f;~vRUX04Jn+;SJ=-D^%DyXxBnDoAvk(OSDKvjIz4vjKO0f6nrM zpG5EXtx*Vc706057ca1yxw{)le-m;QOY;*e>GPKbUEZbW?rc+W}iA6Nq;S0733@KO(*?XDS-+S4aYlZF)|x)t~DEQ=Ftom zS$`H)2)}MY0$rzT95Z)l5zb0RSvUK~72x`XnRM-Hj0F`WHZOJ1++{Z4P-`}z>8CC4 z)_)eQo#v(x=xVakK`T7@|L*LMj;h5gde0=sHUC*qLE>L~(q_8;A8{kmf!~;N!+ie4 z47!uVtk3?__D1}FRh@fW&-eSr-)x2{WSC=N=I~=Vj+s_Wf=-?RS6n`0nw&UjKPKuIst?c+ls4zdqM> zzo^H*7ySL}*={QcCvRy^?ioT!k=@L7b7L75BrqQ!)7?!E`iaWSdu!q}0$n(H%T~wD zK9pR$sXE;?mQg_h^8tqOwwXIAr$jZreVj(13ny>G_|tO;m95;V_Uw#dRFJ@YfV}CC z=|aDUzfgbGh}8&m;p8oEGM5L?sYMP{#IqO`BrqQ!@1j-RXh^&VIaxC`0$n(HOFr>s zU#j1KFin~`ol!vo^8u3U+t!X!>nxyS6QeZ(T{wBmR^UN>$SXCO>I{lvRFJ@YfZS2_ zsx5h6*h%jlpR5t+!pU2<8`t!rL+@r$w|-%a3KEzPkj-EJX+!&F|48X|WREGF4xkGs zZ@EFTRxdi>b%F{!f*BPgFdrZ{xQuHJfGo%f9PWXf7837uBE}XpOv)0y=is~5bB>QnuK?3sua(``c8&Xx@=OB>~;O+j57^QK!p85JZj zA0WGN(_LwxM@yb`#ncFN;p8o+QO@2}C$kMdYTuPnK?3suhEcV+J@pOl%&(ib(+G6o z+SVS(xiK{~0$n(H%Lz;5AnHAI2!A)E3ZsGqe%mkm+vB@Ywda1E+x;~m zfi9f9rD@?dlzvGJ;J6i!2^AzTA7B_wPJ2*Xr|}%UwOAw2g_F13$FgM@{pB3QR>=uM z1qsXt7>0MYNvF?*@&_f^8i6jHybYu7T3>Rn63&UEwi7ByU_L;8Qnw^>J`%rre2CTW-39 z(*bnh=KrlE7<`1r2d2arG)PTq1`L7^YDs2R&A!%rPV1qsXtNdMypqLS8e-0J?Y z0wmCdleb}Xb@!uoD`NOs{*nSzkidL^G!7dQl{Sp!Q%;vP0$n(H%Uj0hBPjFbOdfW) zk_{CkFdrcQR~2OG%g&ixw4j4VpbIB&`AO~JOU-@cz2}qOHdK(ne1P1s-ruBz!_&BP z`Xr4&7f#-C*0*Okoe7@G4w3^v1qsXtNba?xNgFRs;m8k{Xau@&@|K?P)!~%1G?Kkr zB->Cy0`md#E_&RgpjMGwDPV&}pbIB&`Q*IdOEv!r=Z3kPZKxoD`2b0)*CDDPvvZ@K zyEFn_IC&dJqvd|ItTdF{G}&!K1qsXt7>3*4PpRgEP@cozYXrJ*@|LdUoiGa z!50a1;p8pNFpnTArBHT0pKe113Csr=##EQjXi?qCyzfq`MxYBPZ#m`c7etXM;oLub zqYV`#Fdrbz7k6(;c^k>DVXHI(T{wBmroy!GlyX9DGEYpjp@IbF0}LbQi5Ioq9L<}< zr)dPbaPqd_QaOg6u8!sz7XxglAc6S+X**r*L1X96*8i6jHyyfnJ*8w!le)QDI@hzk^Hlb@ zl=Ju8|KXtJbad6(zkhwwQmk?i=*Zj>(J)61c}trtOodR5{R<-kltw z5$M7MzPyEhkVQUYdeU#B!Wb1KaPyy}EdKb89CBmnlg*(Tfi6to%Vr9X3|i4Hk!lk>C&3}fm=kO-VuC#@|@(I!ibYTKt&P(Q`Q}2|WRHwo?MgDhKDKcWdNgs1aAJ5&)VRPbSvf}{d&@0BhZBjeAzELFpUoOzE1VN z9?qyBft&y2XUU+ARQSa+x*s%DCt!0RCh(=VJu;1oPL-3xngNUo{&#WnpUeiC8|fRb z%ADidS0m7c34FsyEKQ^7i>q6ZkT#UEfFTg8TE#<9`q;NZ{r_ z$wpP!NiT2s@XEMfH3D6jz?Xlu1=&=2?QmXxHWGGmiQpbHcDhOzW)E@hRC=ic*{6DmmH z=0Ew<9kiP$FNDt~#%Tn)Fo7>8!gup%oqGtU4h|$#kigA<(xPjcL4OSn=dBYxH3D6j zz?ba#_Wk55`+c8zxezKy;2uAD3s23U)Z7RzPk1ZY^8d92(1i(n*?8idPXn4w<~z?$ zDpZib&41FzDb1h~=O`|Cn4}Tt!UVoy6c5TL&yOQ`kol=X1qs~aCz}xNW>D<|l2h~B zY$Aa!OyJAsNB?|^jE-RM!1#PrkT|041YBmzp!aj5IQ7ougGitY6ZmpQ)-s=Vb&B9E zm%9|8g2Xm$C*TkBGiX+~C>}6yiAJCc6Zmqc_w)U9cgbYF+kJNdDoEhwKbeHvXHfU* zkzBUviAJCc6ZrD`Sh}BPT?^wPkD4}AkigAXJ~}xf&{+o-dS{rvd#zap@2*qrumV;J$~|iR4t3foE^oh{S6ONZ{r_Npd)3(aW)sJn;D* zjX)PB@C~EG`h!&BH<>efEiFI=3EccAd7taKG;&)6=k@HS5$M|f?nSfEZSH@&08R^! z(tDEnetM^B0V+sb$SgH$MkoB2NITlxjPWV)?DQ&uf9yNevUdSiHBF|X!H$1-0p>K5 zUyoR9J?m4)JkZ$Q1^CUSj>?|Y%e;Ixfl)yMI|7C={nTaiMd&m0#A%&CSHG!WS)cFt z&MbbsLY^_9e7Nd!ueItpIe}3@0y_e-)2Z$yvpj0K+UTtl=(;y=kyUH@pJx4e_GffT z@lhQjvsBji@r()**b$J-UDfmE5x-Yz+sio`fv(1jzO*WjX{q|3v?u#FH5jaJK5?Rh z4s#e4B(NhOyW5(aHQ$6Wg-wjp2y`usTWCG0Hbh0|*pvPLs@7j+9Q37E|B7K$kid?B z%xX_hnq@^_(!SCe8iB4$0Sm0PC2?wXXL}bQwBcuJeT~%=|IIW;1qn?2%jrk$pUiVB z(rLBx6pcXF)WZ2zT+6T2uf6SEfbmhiRi)tXsdaQDqk;r>1Y{4({zCJm%TY?65UvsE z8r5pP71d^?n$~5BJj2n)OJ&YIO$|ncGAc-5N5C-n%26{z-JteMf;9qN^B2yuwmn|2 z+E=u<2eusUrCv8Eqh<{!Fe*r3N5C-puRLm=$S$Yj6Gv+Vy574!*Gd|_P5JG#C;NL| z?xo($slX@Z1TZQ{U`IgiiZ=?)cN$e=zn_O|1iHGnn`Kf<@06=PO0XyU!`%9)*744Ke7iTJf&_L1 z4CA}T$4#G}t+?&QPc;Hvua+fP*IW-N$36CB|M1D5slp1MaGaOPs33tI0eeRHq})W% zg^jUp8iB6J#_`t5oMS31&z|ge?C`nT*}#*Ny1OzeNMJ|6F!pacWB&eeFK#@xxkjMt zdD?6%am^X!;$iOsH2!>`>N3`w^G`W5Do9{QK$5ao&Y3|ugLqrL+8Ti_fA=^m@~88v z)erVAK*oY0YVblIp5a`bQ9%Mb0x}6ZTrlhYdnEr+R8b?)HS$!9^>w!^s>S;=(s33tI0Xe@qR$}^G zn#DDrM`#4PE{vLH9hgw2A`|UhfSmS$YRs(|Zn49cP(cDa0+JCy7}S#1pamY9uFkYm9sI@O8fSq+I`EO?EfJ@K)I|< z;F6}X2T?%+6aVrZ{fH9NKQ)1mg?SVpfv%sIMp)ehycjZ`e>l0y_fIcKYzD z*{j8D&ichwBhXcPDAXFT@s7%VVo&xDNcK~UAH=fC>uEy;3G4_M#_@;6=ARv7xa3ZV zMxbj`(@ECW*c&Qyq`eDp?cfOY=fj!2Vp@z16(q1DU>Nz)#pW${xuJX35{*EYZSO>D zUr@1{ci*1uzm_pVO{h4XD?duMp@IZ<1SGk9uGridoY-+{t~54HYD?BOr5a&8y}Ma|$mhO4A5*z4ZyQ;?zl%I@I0;2x&Z0B@Ky^ zTSGH#s33tI0m;KTm6$F1Me@E7OC!)_tr%~uPR>`Cs@{{#cI@p@$|)d%UuWdmP(cDa z0*0|J`L@~0JAwyn$=3*UP3t_)dbB-Fl`gP%0j@Qip!N=yXPn5hp@IZ<1Y{ok>YnL5 zCz2Zv&DIEXee}&(>$mr|s?4VLF2JXaCaSeRMY4azy*5;kz>a{Ng@03K{xW+C*Bi1+ zBhdBu(HN`m{q^efa(frx&B%$$p~h6++9cJ63KGY(_Q3M$Wu{Fwg`8`(MkCO*qWKu> z^0L*cb*#M$u=Qz>>eF^QXT`6up@IZ<1Po(H;a&66{h6G7YK}&rYjc~?)>GdVYO}k& z3-G4icoq9(7Qb}~v7v$lb_C=MAoRBR@tHVoy|{};plj3PK+83EshT;+-UTS!I9iP= zn9UCF)VHC61SbCF-}%Pt=Bq{V-0sEs0wmD2rhTC0Ci}wEx7oV@|)) Is(*<82LyZH(EtDd diff --git a/data/kuka_iiwa/meshes/link_4.stl b/data/kuka_iiwa/meshes/link_4.stl index c0c1213c180f68c9ef3bf01117b8df0275227135..ade9b0cf18ef99554088cb48960c1066269df69c 100644 GIT binary patch literal 77434 zcmb5XXINFc^EMnr5j%ENM8pDC5CIWZvbGiMhz&dTE?AHvW!X_tv3JGZ6}!StvaQ&~ z-VuB6-D7!Xd(Qv-Cg=V1`oU{o%-osGB$*_WNmi5Si13l4`}K9{KQernOT(f4hWG6^ zvX)ovdi7k~M@9B_@vKJvfBh?9M@ZU}C*J<8TJ0sokio6@YGId}YJT=L%?B=>)`+9U zzc&01YrWSDe>YqIPRIa{s^0ybfB0Atn1T^!&z#Zj+qkZ+^9OMw;9=b@S-bZ97lFB2 zjys`|^M^A${veJ#d9tTPt5$zx;9C7ho*8PGZmr?pY9~1V_@f8ZoR!XsZ0e zx87{}5TX5z_;Gx=_rdZ3e-N0<$^o2zxKtUBo22b2@$>T^&8-~3X||SSDt0f!wEmb` zv;Ky^S>^mKV{FZq-pSdMynp{rRN4bu6qiKEoC~k&u6$qNZ#_`kVlGw2i3bn%LOJD1c6@i2Mrb=q)cqwKC6s`YxNZb z=7Rd0T|gex6cFD>I#|bsKIzc%z5l8Ezg7Tw0sqtxH2<=zj-yR}_#Z3&SdXIV#+K5+EHy|^p`^*$_{ zki%*D#ikDN`rHwL6zb`3?YH5@Y}2iE{=bnL_N}D3@-B-u4E|1t^YW=8!)uIwYiL)F zDGCC6KC-`ugB&-5+hFq^kOdA zBPd2-t~Bes;$ZO~`A3ia^AqK!<2~sq_X%c9!3aDP5#oCQ{M4&@JZOC<4I?mD^R$!Z z&8C?d)^;M~{^}@M#4k})s?0d1U<95M31RW0<&z@|Mdqh#85n`N9C8krP0@ADeg4SU z+O&;K{#jDqvnxO`1tXyK%sJ4Cga07*^rx}`wBpkdfgDpX!lcYm8zPHH`wQ)4lwE0x z5ts{F&zuUaIQox_TZ8Y4J5~D2>-kD^Ou+~fniC0$85tw8%0eTM?V$0$5^rT;m+gwSU1Vsjr zV#hV((Re@%%OFpk0g;#xC!1HjNh`i1EUbTD9_HVPk~@hs>}G#%x;~H+*`1Qo5u6Mx zKuJVjKop6Ok$a{rqRmExGQ%r@ljlV=ay3xpLb3_z@xfCbtmh}EU!6i<7q7+VRqxJ; z{|YUlNKKy8s3Ru}E7Ks)Kwjc(V{Yu82`hkBW9rKhbv&ed%}ojgBXX`a;(LbcoYW`^ zwYqw*nsgkm%bBa&24ERA=LGUXwoUog$+^-`*Qm-LuIa-Ye9i^)$K-9Xl6P$*EnMqa+sMWw*36fR3Wp?jL%c8D!^L4O{ojxoMnaf2vO!+5w_!ojAGZXK^k1fQQl^xD6B=l2Sk7<*9E;G~?2B zr44Y~RA|(f=UkgfQ`WWz&2N8Bl>Jsz(L&C2)-VMlk|y@y#`W9>yw~>SKTf1k$DNeok_b7yV65C!%S{}N-N{e%jO0&0+AzzO`tV3^$2jKG@`iY6B))0Qz=HG>w+Hd-RsCwVb5rdvA#OlS)ChW%QNz8D9jAixkENs z{Bsy3xr4Z+VHrm1w*y3v-1X(A{JB}VOSN=NQ4m-*+4Rv{el{5M+FM(Zp`eXwoIK6P z$jNaa!}&!W*=J-6cI>gIZeR+o$(lOzjo8xd;0QrSvP2j z`ze$xuF6fxS83|JC6p+L@4q}{{L~5T!JV4ALO}>cHo10KmrnD;Sjl`YstjCiW>Zd1 z?4@MET&R^Lw!NIIo7lzCb~^bH3LfAEB@W;LFc(IXCwrUA8rwaXXCY`ojKEw<3s#!k zTIO2m$V&DurYmiW5!i0TYjG=i_SrdFAp~ULvM`s@f>RoW$-|GMXu{`@OhF)zs(R6o zr(NZ!SbKK9#7`B0eJ$3HT>I8dn!lB2Wh#AUihVFw;Sf$buBT+kOt9|dX9;psuIc>l z(gekqVE=)=5+NFR>YcF_MY7gZL0~S`Um1~svPP8(^83@ZiWkM6(^%P&8_S{pKD32e zEwbq;pXd1?uEK1PvVIu99#Di6hZGHS85#Y!rN12~WnBP~HhX}q;B-N39`T(j2*hO> zYj9F>znLt6^$F?K*hAKv;V(-LOVqG;#$H>U4V;%Ym22WE%2i^hg1}sz90%|lv;vPd zS$%uWS#9JU?~<}j-X0WFFap;W#^8-Uvat6vvDI;vh7p(x&kTfQmKrMSx*QhWn=hr9 zf)Q$aL?^eA%j%Yt7s7fe?SZX}(S%I8H$)cwbwuQQnWR`3TU3=%XI!*=JS9|A=<|$X z3P#|$ix9o-5c$p6CvJ4C!7!K7&bdZ|XE&%eF0_91IwebRRhCHW`(XI6XCBu=(nnwpWEr#8bgr>Xxy zZWMYz$u@tg&T6mg$IG%y3JQ9!!W3RA>FWv<0s*X^fpJ6J!GwZVXBtVhbB1NUZ#vvXL=g|R#tD3-c!HH;{* zdNd!?w-~$Ky)d-k@4_QxzRLF0>*PA7P;gC7_U5D|SmAXWKpc*WlJhV0FyDVP9%e>F zK?p@BVmrE@JlWTcJ}7>l;We&OL+pb|?d<;Yag{=}(UjW^`*4gSonf^{uTqU4bZt!R3I@l2s0glgSVxguqs0@G>J<|zt7;X*y1 zkgb&xWuV(HbFP+4DIOCTfky!$Pnsu6TicraXs)r!$ieGGyviiRF=>o$*&br9dv+?j zaNwMI_A8AU_lu_E7$WTSQ0%q9$0+?9578R+N>C7(%LGxJBq+%m$swdZ>^Ud>%Flga z--#(0VT~Bf0R-$j0dWrYoX3U-((179#1xDmN(}iJ#NhfCEY07+z7r!bmo@S-7i7S` z6J&ISJ?AypJ^qG$r$RyH8Ys$5$btr;tY1VR@Ay1ML0~ShoxjzFR$D^6z4%4CGFJf_ zY9#2Gq99-|YK^@@)DsYKXQzr|TSCl*p{|fk@I=vJi1pp+ zEU$Qn@+6r@L13<=WtrM6kYV}o6k_4mJo?M4KDPAgsJjePFak%TAqFrjL9Xn0O>66N zktzrjV^^c+Y)7Ij$iAE3`M4+u%yl5^lxA%~GEWPDlepwDGQ=1WaOM0|fhiaPy%L=Q zcsPJ(nCz>a`aVfPU@jO1+H$MrQFS$#4Is*SBzFPs0_}n+7(pN=Gt-KIc7fF^MAZ5X z4y4tfT`)yKpmPe)10rh8ij?LzAYP3TFh2go^sQF5#!;q&j3jGxjr4>l=c7EO=}(As zDinl(evHmoE{%#2p%7h3he#(zU@mKH(b^NOF@8c;6~4&L_ND1;h;(Age-Qtk=@7CB zqBvDR21IgH1UmmR!Kk(NUF*3gAsyCCWiv{(rhVubi76oO-*OFfPC-bmW_MZkyw*HB zSAP|Oxxh{5+cGu`$5nv0r=qB86HqPX|Oq3vJQxDb%<(4My$nUrku`*u3&U zBJ}n%X_|4uOi9YYbkhEeX1HyG-_rxg(ivK6^-Yuv9|ef6n-{WEH7m*$+4ZDRy%g*c z0r7Ee05N52#x2kzY=1^@K|5+}yh=%`y&2lW?kerrwSYNuL4qV~rMGoFe;+uV8&_hr zX7GDrd5HNnyc_VemI z$gjD$PNS9^-w(oE8)C07UKOf0e7!`&7QNWXm6o;bL)Uh(Nms4A;=pi$ zDH!pWaZNiEVbFs0Y+!d+Wo4XRu-;I5;Z0d)DgrT==x~j^tVMI2rckocEr85>pc$to zP~taIBlh`0j|e(eUt#->-e^*e88?Pe;tbK!iGwIctBBKVtbVy!NhZ7grjMTur5lU- zQpkJx;&5qmt-3aT32jBa${8nv137T+lEAmjtt#<5>M=tJ)&}!$Umy z{BUZC|3ra*;cihGj-_{39FXoughYdBFQ03&co5LJsx)QglGXWm)M z;A`xrQ3ppKMlSBkcspt;J^2D=viuFrPr6K}y`Wc;77d}dr_4{(JI6WlXRAE9m^_U} zOz~!2ZptuYd5|+vCPH7{ zhx2mYTZHLhB8@u=h)r1v0+$3UnT&qAdGmUHHh;D-5{J_h-TWA7QkWZ=;WQKKZYfZN z9S~aoJmufn^iY{b&ol z<+(HF`&Y^;2%@#3zpWM>uPJDlIk$T2N0v%{@OWKm6s|{8pTU~?Bt)MO0?UT1ml;L% z?18t<6UT-~QoAH|x#Gi&W`nrph%L3w0H%gxxKa|i;=hNr-f5%NUm7kk7isiFYu}(A zvrLRrJrN1a)mN`jZ<6qQDim9}UrMB@_o^^sVTAcifg#i-xH2Q>FM@}A>)%6v-(j2> zb^4})z+7Q*ed*U;9?bH@0X*Enr7`;J0l9^3wx7Vgp_|iWntMVGM&9N(t8HFjP_!PU z+lzY3TMOL#FannZDG8$@^y|aAi*8X#N>9WHtP>#<`}frg4qhj0m#h*&3wu*yyrSfA zkk;>3XF9E7A?Da*qFF`!xYAn>?zdTVs=H1>QOEA~6Lcvc5H=Sseu>`=`SSVBxBGz12M; zHWmn0#yK9r*kizn$?I7CuMBtb=yr~Rz+BjF5Gi^auG?IiA&Q(171$=2OZ7f;j*rwo zG@T&)f^`Lfxvmipk_b z^=NGPTI#-Ox|ZeXLoL-HV!ks(^Nb0i{EUAQN3t6_^`OA|8Y zc`H4=_9ao|<4pyDxhx?jntBk<4eARR9~Wyi)whPX7v0L1k&5(2t*8O9Aky%vhHFbm zr(T`)lV7Xzc_-}@JqSXWDnLd|1BiZ=ISP6tWcAVA(|U@ndC!WR6`iT6*=9;?eri|` z)mFu$`sy_k=ZYf7cM43w2y7AXyK|cB9roQ6^?uwHcuZg}Rr6hI!SB9*%T2$}D78wN z)|HyREuh4=FjXu<+@lBSeXic5!I`IoqG3u$IPWkhsq|GdL@P>qBvLZt9BAG$b%bt& z^ky|ij1~5$`qDJd=G4;22G(x>Ls+Kupd=xh8n24MD&wGOq`r1m`HcLN)(Kn_BcL-i z8bj27e%}AoDr-k~y+-z3mO3X|gx%^+v(7fAeb$U?g4c$)Bp4q&N^jPA zV>GoabD*ZVbtpz)c@P8m+)r;@YYTh%W46HST8vf^X*^y(zabavP^~z}I|$5$YfH$s zC5d|TYlF1Q1-dB+%%$!>oX#fdhiiqHPcL#*b}X1HC8jsEOg}`85(Quk{`QE~cg8u0 zgxeJbUOQthb-f##;Hi(<>&6>asxOT}wZM0P|KO9f949}T#lVX`U96E{6D2=jck$cm z+kHcBs&cM)@&v4oR| zD4H6Yk6QNL)G!xrO+vB*qVyMQCa|7u3o8iB<#Ku~?BBj<#uD&jWY@+RJ)muO7Pk-l z1)^XCZhx2u^GEBae#NqsCixTu=5lF089YydMslwMTV*_t)eACD_ICYAiYXX@`x_z0 zXo!BgY#zPU!U)y-Apdw`<^bw95zZeQ`htwSHiPxooio|mhEF-BV2>IU7fv0Ym8Hh; zJ%DJmGG0%lE9m~}kCa`b=@!J+e+&#D$ua-gK?a1!>(%Y9&>zc>P+VV(!1@ug<6D&8 zG$@We3(2KuUN~$rT~KD87PQeO9a|mFae_wauAwX0%Fs0dn1T_wFA!30aW}o*I-*yV zv$$jPc)Hr>nKnM&CjD^N-n7mMSL&Y6HXU1pkaxoq^#&`3(NC^D7~B3Pz}!_l=0v+s22mHkr3HOu-06C(>y_ zgl=f)Q$)SM%+nSIM1Q&ko(mF$E)3TmAa= zh*^ddk;|)jDKQxwhf!lo6FTJ6y9R#|zuoF6YihhsRH8e?-``8GkZB{CQ!a_uIC#~E z<602+`B+q+_*ZT@;jOF0((xKzmGRj=jg{YVMT`mUq(-Bh3PJ2-7bVxv2M`ZJb6&#Q zZp=N{pWhkMfz@_%ksTsU5=Wp2M&P&>`5e?+Z+-hO-ud@qfmdG2jI7M(wNsnu4eUyZ zNukclS`>Rx#Rrog6)NgY2CWtI-FzgrC|={Lnh$a)t}nfCNDMv+z8yu?Fv8^GOiepB zP_nx|c!vIFGg}k>R;=mSNtFh>vOx!qpQ}qsx!_yPwE0A*C>~y;kk>D<$dbtg+rh60fD{}*Bx6_ zMf@ci>icf*5(NqrRIH2p6<)&=k{WN)T@jq9t) zZReAfu#gsez7!CtVKpi5T~ojRL6bN_OU_B3+;x&Ex%|kVBxL&pdCi9C=XgNW8#ZOUgio)>ZbNVLwBA-6S{N&HnxtttvsX}K_Td2I=}xWY#zi!& za8`hVCh3+v^xdKL0sVg`CGvj$7!)opEKJIFNb|1JO{a7nOc@OVmdvR1M+ z(Ib>L$2C#UKMqdwW#xuP>(4e+6(u8QXvNM=rYWwu(sA3U?a{XWaQ38Ib3L;_QJFgK zkd|5o;`hh*`(v&HX%n@SYM|5LHqaBt=@IPB3{QPrn1{p^TodEd70spUcuHQ@0K}}T z;cPFjrGNDDl9&sl)t-3Us|NdIDIjAW$EJGhwfS?A(Bk`h~%Hl@WyzSSQGU zxU`DdmrfOjTlbTA7B;5d)=a%qDLMKqKsh%eKQkNYQ6FZotOq5e3C#d_&cLw&LdKTr zrkB*lvDnTJl&FD%P+|bDyB5?pFYm;!Z0;Zpe@E(YZy_~mHPdqZoTOr7Sf`Q>_xz@_r6A>gyUoH8EP2r7lSm zDJkX&wR*909ZT6v#k8rzByIy2_uMo!eI+GPB{ZcZGJ142yD_|yx#z6@3IcPbwRxwN z@|#bM=lMW}{^|*PJzHl-s`QkYf)U0eTl%%rbZWG70EGSMyKLh2_H3C`n8XwXq3Cg9 z%vd(N<`UXvP?R#x@z};b2IAE9&(ZjlabiZu7-b&B-cI#bU-)pAzuO1ixdg~S{T1tk z(S+EM{JQV#uPnvOQ@Z$+r8%=9dZydJt%Uz+tG0(;XBC@t=M|fCzn#QBioE=;eSQXG zJ4pP;!%?p^mRXSLJKT#a;~XPY&oJ{sCd-bhq2JzLQ7RN91D_QW^3f%?9(1XOzR=fR zrn=Uo6DL6=&@wpyb7B49%BLqb+WUS&1-4fdfAtVNN1Fc?ZL2yLwO4* zpFy!3363kL^M=n^;|5igHpe>Q8bZ{$$85GRFjBvr=*aO5iTg2LOTf&zaSf~eVVE8e zr75cnj8HQN_KmyEyzK|*Ndb0dOu-1X?|LM;>#29#^&=Y(3T#Cj3%_46n1_5T#};sW2Kw$PAAOP2Fm|Y3b+wnExm}&l_hmQIpL~AC!W%vn zxL;u|H9~*i+gqRe!a=XQ`j)_U$6Qz^IOZJCR6iaGYoG8?f%U*#_;dhHm%KXY@fo(d z$IoB|fw{012szNBklwV+AaN_WmBjNlp3l`?YMBGo^&x$_(5R+NL0~R*U9!S{kUnME zZg!=3FZKKbt#@!#m5>I${q%0DkFlc>eG~-d!Vx4wB6E+_=N(_h{N6lNVoMl-qf`*n zU*Joh^r^tB&wzW+B&?3-_*%^02kwrcOdd6R=QNzjRajP8xaEpd5h%yUI50QBa>|t* z%{LiN!_60uWt??tDrUQnRS*hS*L=RKMFlo9b0Q#Cjq|1Q$3@Za+dxUKhwU?Gm0)Q{ zA~``^rpo!WsTodeurJ&%B=;X~rU~I|#gT*&QlTJ(B9Fuz-^k`<&*wKjN5Gn)oA&g9 z7fZS~MadR0hAq-kUsPi$r^kbgPjlBWuL(JtOP1{Y;y<`9rEIifs&?^02cw5AF|;qrd&L*7_Vc-sJCaAqp?ZCXuw|6-CL z3PyyTEvb>Qc8n}&2#9j;TeHAMwqo|IXhm~^wM9J!GPYPrR(f3>v8)qBCNKpd)D{fu zLs{(H38MRDn4NKtLkOiWka}lIu*ane$_(3f65EGts;hZAIxr(Y+)q?&mB(g@#=Uj< z*$sT6QGG9I`im0JN?ftR^g970l`!I14K#oDb1AF+Zi={D4dy6R6Wn7=i8D3NpH3{x zKN=7=9+O#F&$%M^)gcN3bE$f)syv=e$~Z0hZB}~;MkxA`*27?*7Gy8Q^_Gg}M*j_( zQM?Et{V2@ok7z8!9K=VqjA zb&k0dok-VX-Sy8^I*8iFQze@UXHcoxJHzI;&}&B56B$iQNSp(uaG{(j$nu^Pq#ut9 z5^e=cE4fh^VQJigF52V4jPqWgd815Uy~R}~o*l2LATXEl(3ie%>&c7)%>Xg!xrcr& zrij=P@2em%mzo>3WMoDC&TB_8;8Q~-{|X~;mK7m=`d89x=eHO4oEj?mR~TVTsz6=N zfgWAEL9K?({mgDoyuigph(IFWr{rRxOfEw9rv&Sfms5q?tZxF_2WL}lJlc#lx>Jf- z_Wv*w;(ej9?&Z2l%o}$){ z(O*2AB?>pLE-?iouoVcY;Z{{Y(SLzxzaFyNP)lJ%YGfX|tWSAHigtopc}KhGd3z*_ zT6_H!1m;q$`!K^%U;J{4XmhWD#1xD$RV38%R~2Rn9sn{r&&#iO%M&7gi(mzza4GFk zqj!5fVbOL`s`Gt;+W=?4U`xX*Hyd@`bLI{~O+_W9I83fX{R)?0VY5neYz0D^jCR*Y zwmB@?B~+D|f)U2Lf;4DaNoMM30zFQ*sjR1!-X-pRsI4F{7q$W+F8mB@ci%x&y*xna ziKOTqtz#_QDI5qHu6W)hkAFI|R<+#t$8B-y9ED~dWo{?CyS!(W-j)!X2dceY8AV7Q zA$uKj>$QG16ASuwkhmrop|lMdJp3K&ZrUq6kF=K9*DBg7UNrZQhwM;pJ9&M5eTn_6 z(Ka_VxfEigy$4r);=Q`3S>kkOS#ek`#fxGtjD}aBetcz*+kX>|8E}Gy%2nhkEvPlk zrSCmP@=UrD|0aMC|!)5{;J6d zr`=Tqo~gr9G}8A0L`AlPFZnXNCSA0(g}lD6tR$F%5XwwMdfJp{B^Nf3#jm?6a}=I& zl#cjaqwxIkfvDHuVL45jXEFCPwrVxy`-RF^I}lJwv-Hl5K6{A-#QF)b>cbs*&UOpf9DEaoZ5G zZ+b8b@MUtA541UMTZ}+`0p26K)}F0()?|~WRg_*rFanPPGOPA2<}$yMyt4#kpq9d? z?>Hv_PA$VZ+kc|E>@o>tpmG&1bh86y&cwX>yvEMb=THe%b0kkelW*nHSno$3a^Y2| z73#YR7m^KkMm?*rqX+6qX7xUpf@`8`KC>RvA2~_Qwuw5g~8s6Y`e&Kx5!SEsQ-^nC9IG-aU; z-1C}Wuc7`~tE>kUf66fhBh*N0_oOKOcDH_F>b-9q-x$F64RDq}yw5q8>zQF7$$754HUR6%!Tuw2?;zEt=}4uS6t`_ z3%~HxE5p?Mc9iRib70|YyF{G+JZOjcv0EJlfw^!_Iw8$Zjn#+R*QQl0b(MT-jKG<> zgm~@hqz{gJX!hBa4_5mByJLVe;&JvCWLZ23(OVt$rT!ZnB+fiixRl&l$JUkg*}XK; za6VJA!W6WUvE}M}pM7utRebY;y&B5#!Y9f~4jXA1Ra_UNO3C#jiYj+y@O+NvdDura zsj0^v%`IEm!KpsFWs13!^&Iir)I$H-DN|T>yb_p#_icEm2WLgs!}PRvtAtaz1IjH3 zyf?%*VjyPubFdz_V4z4!Ua#Cl!dy7o0`uUR*0Pz$fq?V}@Olz{{|LXBR4J6tcnSB) zcGsa0rw*zw&y1@|Ux#|?1XB4oN5j3l zu&e1w3#ReD*86HdUI+9WGMxumf6u9r0oe(6>&xgKjcyy<{TDWCW*&d?i)f4>qxL-~T zYmVCn_ZUL_FDA&%)l+x}Hc7D+=E8P^yBUqviviIUWS=?^x$C^iOs3^wB-DeG$=T+x z>##p>0TGY9!_8?Ui!d??-uxk_%Dc-FOEf)~eHCF@T%Ery(i856Cj=yos=y}{>qkc$ zHtAPKw&9*F{AtAf-;iy%zT07u^3Ge|cHU9C+j6rhKV+BE$HxS`U1Hk=Pm^}isZ4wRNpcfgsjUj=ST%7h#S0yn)0C!OK+H7p{7RR3ru{RFhd zz4{P=eA!FbOmH+;-VPD^s@u&ipryhl!>PsQa^_9&JL~IIZj7&H{yNT^MGTn=deA2e zxOe7Rvvd7KsZbC?IcXx>syoPj?UMP33vdIpTvZ<2!x!F^?9Pp+1^EPP&)6Tq4c~(N z{T?5 z&@GT-gi;b2f2@HVx}}xYv$2~rHg({wli{}P2Tz{bZ4m!zm2tX^iYDD02Fj|wjm+UC zuM3A^lejN%8T;3m6-1Ze+%f=4N+}F_Jc@{u_t)q6&2_6TuwTMx$EHcV{XnQ~unG3( zJDSHy$4Sm&*3}vO>2G);QdEUAh;kWtq^dpfRC26b?ABbA`qWQB;J2bMnh?`U$TBS5 zOq|^m#&f!i(Cvk7(y^Byq(E9LS-N5&@uV^A=uwZuJrVb5 zxLwm#liMCJQE+QjNm840qY*^=PkC{L3y&MZ%Qlw_+XRZLc}hxhV=xcOsKZF#{2a@} zB@t30BS_kQND{t1il_)AFU7qDAG*$!g}sH*MNZkakShb*i_dF|DPvG67wHFg+^e;c zGpfuH=`-vkE-PzaFYa9eBIcXEnU&g-g3+C2fey){$fd^ub8WmfoG0z6!iaYIKZveV zBjn5`nLHrRMiHh@;_0_xblS`}<53$HV(_7B;O`HtFB|24G*~Vh93^76u2K+~D>z^r z|N0W{pWFHYV$jNH>DpxuZ*qB{z#c%6fn>wY;`$?HNM?W0D{Gj7z%^7y?T#CxWq3|& zar96pfhicF)~Z{JvGPe|InnUWOO9)W(W>`pA>w6^_i;S3&|3w8xv=Mh%z^eD<@~Ox zB4Oeqfm^Uk$ws_HdU2Mv{+GGLp!WRsf`ZIqzW{7C@OX3Car1sr^UexYFhr(YHr0?mn>~Bj0^NM);og^4W~tqJZ}u1%bJg9z&*thTgZtFUvpXo( z#Ryzmh>I2l9ejwA^>CL6 zukDCUGY>hY;~cSP6}-2EWaQMU!Cls_qeSno;gVpL(P)sgacd?v4L&F=cUtqDHIf<) zmT9KKExGB(Mz~QfwXhwX;f3Ix)M)xnBV4H2=wD-X^SLk*sndJgNv zb3Q@d^MhP)U#2xDk+4P`d>atGcQuku8`p?;?TScTF4jY>)!n+mGQ4qBk)BUQU@nWL z8MicEPKn2Hka43*h&&clMpP_SNMZ^`kco^N&hW}$fenCQmD|c969#e5XT=nR!lmdj z=U6kDf3}4e-CIs78lrNIcz%(!Ir)2@KRue!sXn8lS2k2y{&q< zMplzy9v5l35|E2iqz*TIo(8W=Pt#1^@U4zxBPbaU86E2&#~?n1k|(nOF=1(_%pGm8 ziih6{g37{N7!6~vTnE`bW-2>h?W@3)oWh;BXF+&HV9sF;mjt;V_v_1+6F-?PH$339 z4@t-J6wUL;SCYn(>UzW9N0mL!ytTnR?1eui=OzT?ri@#{VZ|481$Hb^ku7A>&yxCV zH&>Aw8OBZLYr!6eYNjrf8-Cp=iLaqyG-R0GZY{fSFR2%uHkaf5(#=B={C&fMG@{J! zgDT?H)ULAm*duI2bef_$x!ID>Tn2B_ZAL(mdcYxAD2A)C&79#oLj< z8c}jnhZX$ivIGTzxv)jx<(6;VB|GUXp7nk&aJkrbVKgD#jWM$IM0f31v1tNROnLfo zQYoBg< z;K}@oc?(Rzh?bp)@ZbrIy3DT(d$ncDu*$ z;Ohmbsmom$wYLkIZS zA#PCwZn(v1m`n9OeP<4o4;Nf!1?mSX2+UO~Vj}nZYr9r(jP=B%WW`bPzA2S;9{M8y zTNl?|MHKOimVNd`v-d^bYZ!sK)V=eZzY^qt(3Nz<_&O9*@O~NZqanMwUA(+o^C0c? z%T}rU@ja3 zg0)ZeMETHeF+Jt`-Ha(1p^m{fB@^V$a-XQ*lA{U&b16|HQY?R*ob}k9<@k@Jn1T^X zYm&&Ov2vqZCw6A2gN6|b7wT`22{e#AMR05c8sCP35TZkgnML+PyTYP2h!=929+-xRqu2K@( zUDaHPg@0dhNVJ_yWN)WHHF}P@HWuPJ5unpX>*{q|vuk2}Eh)b3XeUhtO28L~;CBDo z+S<)Vt~{aC3Ock&4~-~@PIsL5S9UCTpI~xz;pFr@O7`}IS{-@nB7>{!;<;`&k(h!JSU-4w zH)U-SOVjqNxSD;<32n+vU+M~&L%0E{-8HZ&(4m`ii=tpbGavekU`!qeI*C-^2S zLKwEo%=Wz&!>v|}f+pnEjwIf=L#SxACPt|hMv#fU%tq5Sl$4zVGDajVG;ev^LyXCS zlOJpoqzA4c+^@~dt?j*9O(sp%)p3rki^n{F^ZgQp=pAJzeEFHHEmQ8LK*La5@ zO|;LD)O*d*iRP!J_JWwbbeGBF!3jpW*cD z);#H3ygsV?3$7qA7k-hL6s=o}FC6WuuX3v|iI1x}!fO_+Hw~qom6Ay8LqD;F*4Aeq zg*y!hfw^)nPdBGXconK+FtmrATa{#2XBk?a~CUvTIem{Z%~Cbs&knlC@@E}m5xt>>IEM3C_! zW58&5@p%MEpWbAeS>%~Q)52`haY^tR$)-p#wso{#v|&}H1u+841JAHw8LxToCA~2j zUcW$NP3cR@s6Bu5z4=DSNw%%Q5Cx(1E7Yb@%?)=eCs%m&z(sGhpnvBl!2 zN2(~kwZA0D*OG9HIrZlbIMr>ZdLmNKl2_Jyw47h544JaXzhcj+%1HlESPtlSj@~>S zq98DrrK~&uJbnr#?FL$-2Hkz-*0QebwY`UeP`FT(ijZ5cAY*y>Jo?o&RN``pO+oH7 zbS5?Rs;VhyGW%&0S?A;x_8{h?Fk<|;%di-DDP)4eh4(&?pO{@*MjYA8nt$<=n1ahS zDwpSP|C&Haq%Y_(FsPh7*HW@+aGL`oFqdVZBlr9QaX76EASMlUlT8Yj)SEZ^qU^jd z7mf$Px%1^f=^k{8Jt+N5i7jEBaGVLeXp`x}*m9L`x;Gl`#GzRR%|2nfznLG0&!=Gp zibAb^^nEPm6)VT|*1aUQDCRP9e=-{-VVviJ-5Gg$e3QryzM~x+JVIhFJi}p+0a3Mi zQ$@peI@|hKMPM#f#)f$(#nSk>EG!ykXVlJ^3)>Cy8N&V&1=@XPJ73k8n4%!2{;RqPSGs-n~#`C#l_30dp&U3m3&(4P;0n@Ff8 zO7@0QtIk7biJJ@a>Y<-nDl%}ns;9oZYKu6(>@@qju8V@eTv#@|Qc%cFO#5*%fS&@N zh*lPO{=n@I-*D?G#O_@|dcx#i0@od9q~H^5LN1-kD|YpsBOE@CRA)6jlcAmu_k_1C z;X~hKh;pIB)D;;<;FSSc@v(_G)OI1S6&b4{5Es^ukgRIYdGivCExrb8A2bhQ&G9Tj zNQ>URMf=i?bo1$Q$~=hYK6O?bwR?cbY~`Wf?N~=aU@mMo$iKQ@S&s3mu7|EYBnava zI9o{dKAjFY%O~gZ=}ldVNsPc;>iF1yd8>I|)c|>aL2Y$+hxcvD&TF-|w`f0Y0JXq( zI51FL?%oykzSF#v-i~`B?mckRqU{5bwyK%lN8D62$6RW^@`zs}B7-CJ zjaPFE7qqg#D*&870WW!0StKe)4cAwk=%^qtm)aie))P@`NpJn&<(nK+FhZ@>`Fwfh z#JZjJvOOTP0%daG>y;Wv)fDHhdQ#sipMj zGmRac0{OdWZGdZqqZANTGdGd-2j17 z&t9_q>-%ilvzh`^FapO*A*;CYAo<|v1@@+>C&zIZ%%w(gLgP5!wPh<$g0Jh6l;_@A z5w+N*I`G=U;X@gg9q#OU1NfS+l0jF{&ERjEx$vf~5*38Ph2Lr*eZx2N#HKN#LhmSv z%OxkC>>+O}v7o1uxe+)mV@@7tcDOb~L5W{gH<}r-K`h$^?;2nVM))4to7S!jb10t( z2-`YG%%!7hix;)w4G63ULMXCHr5oS)2ev8pf#kiMS@HBtqJ@%;57Y{1Q!Ux=RDwBvjj*+P)|=4i1Ia;Om)9HjXT!ZWPq& z`NxZV#HSoVM)g$?m`kxb325Fx82$H%eH-CrJk%Z-L9i9b5Pd)RL>G~79qd1lw%7_} zL6+IL0^go^5DT?>(0nS7FjtrRzfnnWgbqjUkWO$?{oxaj9a~JE+R;WT5jwo*#Cs8v z>rGX0X~k91d|hA2H9)%*jKI5Ba!0Qs2L8MvHfH|^fw}NHm_&?yBno=W;p58#0#Wda zOxb0Sj^hgn&r(HXmo{ysVo|KEl8yU%=w05)#!cQJkS~fU7=i6Z-v6#7zI}yn#Z`qE z07hW0%3aKs!SH&)8Xstn54rY;+RGs>T27ayNQ;>~FTuz$xM7dcIA54_trjQR>D8r{ z0Dc#9;c{`dF$oAZ#N+M$5|Y><@8^!0Tz>%HaGGx>7=fdoq+r?2qC$Z(vcwUH+~K@n z%!MPKaT=ero2f6lLP2FzYdu1hqR|9x%haF4iMA5eX1RlBzJRHiv#hY1 zcg5jWKY90>;C--XK;A&jr(S>PqPRSDhuBaZUb>xs(`%3NB7^RRI<%^@G0m}9kQ zF1@qOrgvpo?wDTCccXt>#JJ>9qGk1d3PSNXiWi-dViphgj~C9jVALWCmVsr%cgfD$ z%ji5S#drp{=uoYcnyfF*xAv*bOtU&ct%hW0io!q6isirBNn9=-T?(4)zF9=>uh2oX zecw{aBvqVdp#~reH+QgPPpG8RVpPhuaF|N3t7ag++<)L*X7IDof!~G{0RfKz`k~ zRoGrAEpfRxms3F#m&abR*=Vykm8-nO6pX-Gp%4onULP_67m1Nh6%>TRg))rc4)4lZ z@`deK@uPDc1)*dWD|)Pen9^~_gZ$YTuoa>x+0p3k0lZ-5v0fB{)4M^P+N(VgtrKvs zgq*vl%f;G9-^HZ^!OCo)%vadw6U&<)!sg*S(dnkYg1~o7a9@BZ&X?a}@tP;1ZDFb) zFqb+$J{iSi^pFE$#bQlj3P#|*04vLjM@7W~Rpj!j)g;-Oi<5e`j2H#fn=i^7b;@p! zh%Qz~#>K<@ff1Ms&t2q|$y*k2e;_8mE~NA;oOy(M46Na<1j_J2=S2UT9|fjhgqrWO zwe=CPyH6#VQya1-@jQrfD~((E;2ZU~;j53e%n-RNo<|mnD=1Gbagz!KA(Zn-qObcT zcJy(SJ#tl15%|;+)t3r#@6l2!0&`&-lA9IsN_NvpX3i_6S{ET)Sb6T! z0CI=7+QT?sH=u@`+dM&>_J-3}l*Nd%Ce<^@WVWanO6aw=(LSQbuvm~VMh%z$f z#5mEaXG7)G5_4fR?Cx4V5ivt=h&;D~lru<$3uU*$UhTyTa@>;d_3__hPO3xf0B;g-<1e)7iE@#4nEeF_3|;oNGtg}o_C zsHwl)ER^g|yl%spps*htyHZT)9il&O@KNAM5svlYC>6v-JGABZ?#Js} zbKY`%=B1o-DQA#l&PK{XyJxbg*VdSEWCCYa;fyr6-S0hAZrwSXy@f9$;%pIx3+3{{ zIS$-#J1`-PRY*UeWEEos&e#J4zVqO_PBA>)#8{g)@^A#b7!fH!X z^S8nWRpI>UM+J2paFv~nuVc~_T_fra2)&DK3pzn?aaFWA(E zVhaA|BrXYF1+JE$zcSt9w~IBP_}vGLz$L-E24my({8zs5G6Rwo1m=o3G>MvjxHD37 z8r15yeVm?s&4ZsST$|y#V=jz_S2kyj(IY>9H&?ln#4r~|Tdo*%=_iokZ~#sAFGVfm$j^UkyHmRi%%Y^)~eKl(R!CE zlg#J-nx`Nz7uJc8{FAEbbt*5=Y>(?YY2-sIT5sfg^cgZNnod{&E)nCf3&>aI>anUNaH1p#^EaAiap=HF_&FW3t{+zB!&%<8A->3>0N2&%=%7Pyn@Xv0bL9nEkLr>5Dr&BUuRH8%C2mgyxq zIp72`K1>*`AN|-%^lsW5_LLLgE2oXk;QswK}=&RarmU=TzkKKBP9xnY^`C>NyPGCfOA8Oq1 zP05r5kkQDYt=@e}Gj{4;ew};{{eNYBb$C`u%x_AuA}xhtg@xkIB8A$SnF7V#ibH|o z6pA~%6f4EOcyZswYv-IP?!GuIT^ts7=jQEq?WHR$+k__fwVcuO_ zck%pt4N-E&L6N8Qd;x`PV=UY{0Z*49V%I!#2*E+IO1 zxh(EaT`r(#h=7GZuyX8hL`)B@rp9cJlK!I+K`0clwL RUQ}Ds>LFr%YI)KRj{Kp zj+R$&(pSI`tQ4?u5WWHWOCJ3a#;TR7rg}YUFUR!$4_F1yd9@**|kV2tm=aX;fJ z=)2(*jkOK-k5{RU;;hh^2@FABGpA^P@`Wa-Ci`8j#fw(3m(eLAbE9s;;j&#gigd>r z^iLeGJP-Jbf))1*s(tirNUn*KSK~ULa=_T;Qcq9{MQ|D6Cq^r?O98RyVSTnf90f3D zrCCA{jFfDx01WLlLOq#2$^OG{P0$>d7_7Nn(mY<;HEI3DDfr$p*0^(TY1BVFQREzX z&ippjnSVauWH)uW+jG0p$pI#%Y+f)#jEv1>L1alILwpahZl8}8Q^*w&%loufV_Ij> zn}hyk6pDB?teYs_p{V7UH4$yeyA=)8k`4v+pkXNtLAmXTHJ8plWK= zI$vFQ^(TW;sEwkw3-fEYR#aCD1?gG``WTe5+$t~Luj_2ZtxT6hzl3!rRx0(w?V1Q# zR!ULJNj0Ba(eDYh)hg?QXuP?wVidZ|Fm2y3AV7KL?;^JhDa8?#i&zXimw1M#YpGpi z?^E82*(k!rZOMoVE!3N-A+q^KH;y3Ij@y#d?TysJhec(tI$q3PQTxdH2ln>%s`rWM z;>TlaZYW>x=qyR3moH6KngrFa+JNxQw4=+pDk{*=5BF9KpC~ zpWyEEF!k-Yy9~SZL_*V+xIgq_o{H(_n_6TyzDa$7}USwYKSZYja#PtSkC!f2I2_Z>(pRvJ(qM@cDRP4pR{;#@dr=XO{F^jEjsko=X~!QlFRC zv2VrQ{nZ^tTEA4{NxvqBKDb+=ix>wgf0i}ne?Ms4>RwbWR0x0hrT zf}s7w%3pOxt3NNcF$O#cWjzOifTr#6CHoZuhN2~hZ+nKTb^mS@g?ytpf^gAs1K7O0 zpPGMkx=}I5aY=hicQv}(;rkzLd#a-MJBfAMZ!-krqAi3RUXcn~mlIuv?3A?a3_mFJ}dmjB;r0u#)N*C?vGI9<=KF4Iad1p{E797 z$UBPk?V^;srHr`?l8q5Lou|IQgSGvutS*UF!yKAYD1uhsM9;+6=H}V`#e@2M!AK|K z&7^NNrY!$AF!J+hV_=$$g^fNY#gA_hcne!aDHK6l3sB_L;Dje5e@}3>%ExVvnL2BM z*%!anCSNb>x+rXo3{IDnBQ?Pc9$D4wo+jg9-Tr>xJ7vNOYYt5*6p{Z^ly&^|5i`dz z=Lxy!6+gc$!Nc}D5su~mCSiNc0r;)83loyFxzDi7EUroEiX1a1=A2~p&+iH2#EjCIp7B(!anCV zi|9gC}Hn&&2VW zm;W!ssd6Q)`|G+}H9n+EqG-&)8t$8T^3L}(1noJE<)q_=l~qSaB}`Ep(q@q6bMCx^ z^`dg51P;c2oH^~R{)G9AX)~BBu%o~2v#h#v1{>@=VQvkco$RF0DqtM(p~J2C9ffN6 zIeSjEfociu6Yf!~_wHY{*ERmX2+BoQ0p1B;U7IjJm&l+9KIbpoy8DealGAjTjt?DaK2~KL z#`|XUEcHKY@N;ehwcT`%?z``Mf=1qnu?l5%O`>ZPtXe$i*z{I69@XOQYKzzyqce1Ssg(zJwH zIBM0XhN3s>RyY5NZ_B0GL`tCuI!_pxIjCm*?TaV&IW>`v6&+nVZuqO{)ldK9ZQas( zPJ2j4l#U3#$Kt!K`q`eJ(q@oSD1yrAZwH^J$#CvmaIciv567LJMd>_Y1)78& z`#H|ZP7pp=RDhI_yPFC*W~bpMet zwOmO2lRp=w=@qqVbPe)Y=b}-bi7i*Urmb^|pj^~q02Fe3-9PH(t!hp!p>3z5z{e{0 z(;EJ@5~ihDQQCIeC)7{_t!vQ#*xifSzF^sq0%>#ZlbV3`}&g7alR&*C;=N;VLQgE$1Z6!ea#!ah-{KysP zvWTjk&S`m^~R=i#OWd- zc&6@ULGELQ!})Uk`c4*v&liwok_hV=ZiNM6MX1{o5b?FuFg>=~5>c_?ED88tH8c~# z(RR6TEN^SU8qC7Jin+T44G?|1j-JsbT&_5jN42U{-D-LMy70P-dEm$DSa5uwfW-?0 zr21h@5#Ap}V+$d2Zgst)!&n*Pg7*eXOJc>fD;GQrRc5jt4uaxX{9DkTds1p97q zaSP@;d%YL`TAplxMGAAtN$2w_M;?WdTCD^`>=JPkammhG!te<>1CK~m~qv&@jI^`?MNPp3QZD&zN zhGNb1$ytTPlKtp`q%z(iSC(c*>hSaU1{OtZ4QZvn3>;wY&+ehZYL&qG7$4-5@tlYw z2&iLNa0_!em5nkA&1tPO2MsaO7s{?Eg&~M+XN|2kI<)a3D`2mif@c`T9eE1tN@(FT z4dqpupX_j)7F0G?@_gP#hm4D{68mRn2*$-)mHl8#J$6whTb|9T=y$2SRG*S4yQ&G7 zj$=Q<$F$KdhXU+u71Jq4&Qcb{#F{CQ2Ls0dQ6|m_Po}w86s{C%JaQoLb)W4h8$x}9+ppK*s+|#R1yBFige%KM z+~Cp{Oa==^@5Cy0zhvVpF^O$;c+^_^@qrs$20>7HnA5N~RQu*VY`+gWD(QNr>zvBQ z>c;Csb)_8#?JSRuu~tz8Yax_MY_8ADcx(6hv5wgiDla$%D{fAyXhB)D6wv1gW;^B2 zs-wn4NhpTZTN)sxZwC?C5V^Wzk26ma9PticxhbUfGfJ3^Deb_Q>n+bETv;xdNKs%iu5RtRZ2oFSW+Aj zP`Qte{gz~7(@;reu|r=oDR zRLQxKeKR59z#6Y-b1@DoML|%#Syem+`>KY z-d)$Jx6|IYXF0QQ6v2CLee9rLbbf93>e`T5AIe47Kh}HA(@yv82>R0njG`eHj&eCx zhgy!6c;342ier@}x{H?k7Fd1HeUNNtq4UgUFtcAb{d9hLd&R0d96`C*{^8y{LRZRv z&58(4;PXKd^vno{>h;sz4<5C0&pN~rl#9+kj5`*ggF4o;MrSqIiejsX%7fD7sXe9=1qz&+LW^@hnQtwUmqR zIFCMu>gN|;+arrlmy|*gbY`)du2(}HdOVMQ{RCe(rE^Z^neHW+w|!!SUj2HlxR?dk zAURVrOHC{|{t|9FQZI_zWz^0yk|C&_r~3-tC}tj^L(9%LqJK_dI}Sy#eFdVuhiljM z53TDP9XRK|_9DmZu~tf}P!sM}5?sdntHX8vg4e8eU$IqmSEC5J=AoDOFkSrXLCa;z z42EF#gXxupby62j8ftpA$2li5nDrrJi1|^KM(XWHx|)^ZM)R?v-=%sCSGo?>>sOo) z^c)w<5rm8BF`Vr+NLPC{T-;f-i6Iyl+i`~O9jfoIUM1${p2raM7ZU$f^lx0G9#nOV zJ^1Tj$>xAqYHGXCzq@CUesQ9$eX+?zj-Zy4&Bxz02Iwli2aCfO(K66qkaUk?{dn@N zpZ@84NmRrNG3*x|<)Zs8)c&)9_H9&67TlJbodD=A%1#5&;i={PHLp@j-b$b^k~eAh7%{jTcjmgxzO;#sZT_-0UWham!H&o&dC5tKgDL~zc3l9%BB z{u_^=|EJ{b!U5=4Qkz;v1kx97E+m{a=Q-mc?|QQLkpLc!ubI{=ai&m$)9btdxzGn= z(u^~nujcg}(hx0+Z{5$NlU89kZSr#bQnxO+i^84UUQVyJDj6Hd5rhl9wSmr_J8ysR z4e2&ZoPIua@~@HmX{%^U_*i9JSS7)UI1|*+k5VXtjynFXZ4#H(s*U>wR%b8V-1Q7} zj+JxF_}ewPca(PeF;sL?*#I^lZzIjwh{!Q^qrqQ;y3_q|ymJPR{97V{z8^&AgTIJS zG~h{EKW?th?N3|9=7Y8n&Nir=HdYN1{))%>{nd7oKT5|Cdwz6l+6~u(yy| z&4E?Ia{9;AnfclM*-Vic1dmomNz~Be-=cBO@9(UY;6(hn+~E&oeCW6_?Sbdx`=qrh zva=CDU*W3PWM7(AhFz*-(085yLhGDJ8>`_zk`pKweF2Ii%H%)e^rEWBi}T{?xYPNd zuWkU;j6R!&$d)%DJ{WHfqj8>{w}+IAq5-nUJJNc7ZuAs?+A7*7IwI(GR<#qItym`m$SHDCH4+Xvkco;SN5mU>6&MKHU#wBGEplPj&`=Dcb4thc(4lrHyXk4W0pvLJ+X~y|D`sVMWKH?iR?i#(C?b zj&3<0k8^D}?NTM2d%8a8y1}TIglvm_XKV53H(h8 zWdoa~tthy@2v-0*FVk10vlaje3c zUPxj+G#ZPa*mj6AEIK0SHE32kZ4Ks_G1)JA#W7=!vxjdVCp(S}6vv$ZXZ5hym*7;l zz_hWNl75CirBDPAc>w7qJN%sM-_0o16 zd#`6a({`%iYzF%k86EHyW$b7t15*Ph39lE}^DW6H9qCs?ri&BKyqPRDQ4_1}oSoM5 zn~pR4X%A`7DH`vcA3Sy56R9IDZYEL+MQ|A#jxJBrtHC!M2^2wF$Yv9^xAs@JMn}ui zuEiCNh^0~Y8OD_qtvpT%)o?Yg^CR6lr~^Z4+Fu&Jm%*b;Vl~Q+CcHW-;tG_)n#F5O zN1FozTnzzZw{wS-%#ly;U)@9odzTkb0)5iYqBs{pFYX0YHaMr>XR!utvI;$}v#2n0_ERnvWP+J*kfsDhVb z)Ys<3YJoQyj~P}vye{iLb#G`)@cp?C@>GJ>BK6VPal;rQnqmj{15Z>1LPT_k$` zlTASa&c`R5_v42!*P|%5@P(1m;Vh2Euh!y=Y~d}{q7_p`;XWQr21QVL_(pD%8fwFn z^s>Sv%%~zV99^(gX0UK=-Imj)qJk)JyeK#db*qJ)X1By4~k|H<`C~cR7H+hEuN}{l10jqn6lv3 ztx@~y35QsTTJkJvwCZ?ijre+~rgU8HCBQ#}aFmW_xj8h~0nb-IM=5tVtl6Kx9?xkY zc|P<@7Jw{R|N^ilGnL8^8Bsy8*ekVzg<9aCHAo!2I3+(UO97!_~;v zQIi_*5C$DB%=@nT?M$!>zDPgCJ|zQ%-{OHsz!Wxdpem^t@&W4_-jvP zdo9%%*i|)Lb)UV(F4l9Eq?*C@B{m;EBRZ-5{dU`sn7|Q)i|f_3qf)(WTUw8=beH8Z zP%AQ->qtNK^1yPtY49jXr89jcdWbH^e>=QwkIfBkJIenn7uUA{u?)+K%Nv1uLo?hrV zh{=ZWNug@usWW!lEG9>g7P3A*HJVDIJ{wn&bpY0#GgIl@&zcJM&O;a%PALSztSdAQ z?ximOm@WG6zQ%SOwj2!iEfu^g!#+)TXROSXt z#eih=o)ZM+Vxs_GG7MG2POTL!TP~86LJ{l~1+Cf)QEof(Tg$JlWI0$gmyG5?W6$f4 zQVRrv-}vEl?Ln64^p8syW8PMCNc!eU1K)!-1tH2`Q4WGmGhJN zilW~ox&ZL``yeG_4_S$ctC^P2QQ#};_?CfcL)1jG+sQrrBtyrI=mO>&OdqJexjM|M zqxNzH<)Y_Dco5%LjXLcRK9^6hRZDe@Y7cwdEc>u8uO$~d&;o}IOGxNcN)gP;_O zShX&_<+gf|H6S1zBJ%Y;YTxPC58tT9HGK7$=~LNZRT}rrh+lWdjHx}wimm(8plFQp zzJAPZmZzUyn{S$+6pDa_-%U6^)Jo~=f-)9ld|@yBqpR+cw22`o7jIShJhSZ}*I~MC ziEa3MW4@W{GuiTK`N^Oy3_G~WEFC_@g2cr*RvtU@*fZS6>GY%B1)~%yWbT|c4d4EJ zXMk5*b7$mKD<$g(M68JFZQD^Jbz z?yH!fm&>EA$+2&Z)ECu_@h_t-Xy9zs_HudUu_j}6bi@{hU|e%s8Rxr9wczo4M9gnA zP`({BQU}E29n^0-j2si9tn`VWjXDFPjWBbv)o9zt|H!C*td-22G)iA6yim~ZQUov= zQTnA^IkBsLHfNTIT$xw+%)l6oCCiLT)A9-b%{{HKt{Fsd&o_qS?-3Z0^bK3}Zm@@{ z+rOp0vE3mk7e%w38ixPKq$<8|qfZ=-W2ZifpgH3JdEGo!=f^E{lPWO=jaH{z6peQ* zPcx~fFWc%H?|KJO1m&WU>zMmG_LWR|(N$+o*=LMA_Q7bCYYawVb~h*&MdOLA&rUh8 zd8F>L^m6jyv$!gIqsA=@H)sStMdQ0WJ907lkBEG19bnGBFy?w1eJ|-yvF@& zpKQ=w+aH>kl#5zBn*W2=XLDw~q-R?_H*hbrmejU$#Kb*G_WnWx^x5sdGrLP=@K)V6 ztJ@-cj9wo*P5`lLl#7lCR@k_Fz{(jkUOz56nrZnSg3dX$kC?&pVyoDTFC*rPn2g@wUzU?1sD|SD zi0mU<>>sJSWkCe7iIj`36@b3}d*$nz1NF^q%@~4maSP|SZI_(4bD%yrq%*U96v0>R znbi;FYpj@ksCIXTpj_ORd};L4ev?{T6q(aW!RLHdaM219p5htW@y<*sUS2{!hoE=2 zSmown4%MK@D!F%iEmiHW++xYNYr?;79IrZ4GYeK>_#)ulV%%%>n_SBE%`#a$V@*~` zhoY&s9-w0aM!>J%Dv#YBsGzr}0srKZFlDJ2*=ldlA9r2k@w}TvaHpcir$#RF@Pv&h zqg0boM#R_sa)Sp)z}$0**BYjiBkOO%+6*elsGLqZYT*Cyz3@!&rPCkM-2*doi44j` zGZky$;vxC(3q>RZ6+NP7Go!_N094i80e;(=Zbb7pwTpVw;Ew@SL7(7Tp zvvek8^pcKUm^Bbx&dgK9MfM+vZD)vlT@P57T>g|9J7GTvg(8@2C}4K9XI9=J|8n$I z5Io%kBZm}#eCxqo2RH)=-B}Al(UaMD%LPv62UA7lmJPe?_@K zo-)seSCerkubQ;+5D4g4L{o4VWp??(7BeBEE@&toWXDD%LN!KAcy3 zBWSESu-9GnXq!!TSk;^%fK;>MGNw89n_c#OGA3V`pzd6WPrmucSI$kqh$cGHY;>>o z%x-%n7m(pGqZNE~GlNwb85})ZF!cPMW@M*o5{hER5S-tY(|-S9r8u~FtO7z|2qq&_ z-|Y6f0<*-K7aYN2u9%i&S=!w0l=rRhNFIrnVYQjkxr}r;-x?$>q_WZPGbFc;Z7@&# zmc1#{cB++Br?Dnr*_n2HxBRl1AL7-qehW%n#uCg}KwVTw^Gg7xG4+XJ=_ zXyFmxk0Zz)#bm?cEj#VKLG5IJ52sBeJtv3)J}1onjSI@CTR5|DYQ;PI_gjH7GuG{+ zdmq~q**bspUE4iMC5iGC`m)ph>Hx3((E0t32n8RWaXRofP4(3$hDklo%l zRM7D?zF(VN!udJe)-o$vVBt0UU7tAVyQLjNFk2gU&2)sl5z!UaV$TDY9le?FctR_s9tA?ec5ZLY&)0lIFyU+ zK2W!^k6wIwq->QU6p--Pmh*H{iXQ4s z$!=!q$C-)L>UwkeBX+&)xfL~$P#EI)Gy|T31bZDK zAZfE4_$5|))$PF$K)F)x8}QCs!UdakrBDQ`Z5UNGR{l|C zyS#NU9B;5l4<8>jpd8kQ{0B9hwQAIdw=&zl`SQat+;J#{AXsam;Os|oTeTI^F*B6+ zgCJO+pojZZ`&#p8S$j+bTOU-%m<!McYoT^PvnujxD8S>LL6kLw6te z7<|FbxFu39KGaoFo56LLSUy<$S3~>r^FgxGXl|()g35+z%gUR-b^Riea*XHuAmw7M zs=0KlC{}KzsMr2K=aQN|jj($7YoasSS{i=`=?X5FFT3m$>7EYe=Msuwr;O%rva0uI zUF2`~TjHs&%&!`jf^snncfI^Ixv9qk zakL(u6X}T3Qy81UYE$mWw^147{JY&bf^yMugEgTs@^V#A+505wE~QWe?GqHamqBKp z;w^hz!xI^$P<^F+f&&%GS%0jZDBDM1&nbm!JL`GJb=B-6kz?h+$Ji=LAqckS!FTUH z`>~!O3wCSI_9(jV($$PvzlTlxXZDHmYPKG1ol^u`!BDZZi>eYbQkE!&7LHnKYVGK{ zfsfnY%C7fk$Qv$rZl@H2;5IS8XJPeoLUq}>Wi5taT-1WYpSOHec+W*L?{a@drc=2&OIG%Ep7hR zNcp-d$Y(ivSY68^V#Vm|;>+Q&`re9H%u}?XLwrzd<7jL6wf`cHuIwWB_=Q!5sb@1uf$NSK>)L5dDZRyNcs9s6-6l&K_kSl62kE8s>9SlGUNJ2 zTn345V`$jCDT}I;rGgxB7JqG%R?!GL9^JOJ`)hgS+eWeLRG4D1bu>zEB<4Af^)+Cu zbIv!$_c8mr^Mc8YRQH0*a1kg_WYqMR}^70j;2 z^m}Gin}ItHq0pE__9Ym&%T>9ZmbR{kD=IQKMt|18%$l=;BIuVeZ@YC)HK=!lJ#>71 zjv(==3=K`XyQmCnciY1C~Swb@k*)$xH@~3Zn7CSf!wpoBB4S zp|0mPpUI%n$`p+&D)xu`HZxRzP3a*i7i(eh9KtcTy9HeZu8+Fu-Bjr}Ep+-&$q>PW zi^k7jRmVXts#wns`boA^EV70o_}$&1&2Fl7cx!!TnTw1pN0NLG4lP49>Cy`qP%dRo4AI{Dpq zcH>TO#y<_jEQKE77Tm$;V(2j_i@tuKh2FiRlB5(`-GScS1B@2m?A(pp=!H+irB9Ab zR?7aic!NJmPz3!FW^)WqrziAitbZ?w5fB+XEyumumgDG5R$GF82_w(!40>bkCi=(w5E%`Hb&|}KQX50Y90&zDrq_XS|@1b z9{MHB|LFhOZu>^+Q}Z4(85BX~0ZcoVU7sIVS|5l@r>G2C_k*JGRwl?r_w_EOzk26Z zl#8Mve>MxMds@)cSxKj~%AilZEuhbq&Cd~pi`N#(^(})o7G%_Cca&4KvI*lVh%)@& zm=I~Bj6Ho_^!ZZmdVlsZ3J8TEh&+57(9EO@KDuK6Tx=-#BMY8yQcU=KlvQh?vhnx% zAQxSA$4h(4)BuKHTtqg;i$;B|7;r&IF;n&nnt4Hna)2?^|AQW0v zhkXfBpQP7Aj#jf9W(eiAcL*BdGFey|Hpx-$D#~bQXVEWTzOmfC{(A44%q#mhM# zp)$K3HolSU(+GXYghI2TS#>Dbx;V40*|~!}JG8lqUF2zPDA`90cz2Z7qat6zw;;~t z)RQ_)k&CX>QCJ4df}*PgR7t>FD?ADO-E}9(^YQz%-S&0 zM8|-P8`hwEyUOmTx5%fS;fl6|aa~@F_2|)88h##o?rk=38Y) zP&B-pxYf>6b)NiQ4Sh?LLJ@7Bnvl>5PtVS=s`z8C{cc-Fxi(WDj-Xss4w{h9O{AF4 zp09ZS)xP|pw~Q;;hFKqKyMUtMOzNc7ux@|0$GFBwYYOfkltK}- zPY_@JjJ+*)yaQHUAnv!qs^B3RFR9ZI#| zZ}OIZTIkcK2+GCm?$qPw>@08V%c;X~1}TLiXrG|Y=@|P|t@`qcKi+>(ZJ@JB(NN?4 zB>T~lSHgEP-Vag)?;ghd;So#rE)!BMN0+Iu=~633dLAC6Kef{p@Qj*GHK42ezd zGZlS(6hXO4_BEm6^q|OmP8nYP7n_kcV&%cQL-9tjTM(pQfjNEWu+kJ+U3(h^!RfZb zvC64eWp-A!HgB0DKMluzPzph?l?E*rr?ZUty<`Ss6hknsiot(2t0IC>7=n%=v_A6Ps$1xZ*xU|p8VG`obX=8W_;;m|Fb+LdQ1{+rE93DGB49Wo zD20BPjv*Wjb+Lc!9cmu@cN|Ahu4aD85EmZQ=-U&NQ9k!q>&T|YX1{EBZ$K#&!RAA} z3$b6vFSTcv$2ghT${6*s#DrnD1$=9cmAT(02j54Fb8soXHa6UZj<-<8l2YOJ-jgYI z<0@!ND1vg;TV}%KeI^7s{XRRF3wwQhsy!(W-WyN^h`M&V)nqVC^qIpJeQE{cp7EFxe!D=%v{UtaoM(aMB}bTqkR9!V@AeKvtBL7SYGla z%$3>xx8?m|jBfE9Z`vq=axoblv)I<|HA6L2n}hi{-A&j!%7T*J1yHWS>63%qhFh>_ z0=6p4=C9VD2aIz6(x!wT$?j@HKB7!3tVhOls$6ZDwtsC`ajDmMj;5O=bH?HB`okfh=@iL zo?Cg&l+|lG85}{l96h?=j^mCsWsf7`^M%XS&7!6B0FPkBCk_)|2P5*-+TuiU>f4pYpare;U=in)WQs{S6uphneW6N-#hpIV0S<{O=wd>A6 z-K7Z1MRghmjQ!gRzWKl|;*Pg6ltK}~*utYLOgQPZa5b--V__eArV zcL$=rDZ9<;5js4_?~+jnf@wZXN>|f9-(ZAZ7~snhbbZiu1H10$w2K!UpbL0o6+x=) zl#6OU>|RyL-aezfUbOhDjQeAc=_udKg7#QPn4+oXLyqx&_A?o(GxbWZD1xpJwhEw? z#|%5@&`^D|=0AeodC+VHHX@MDZmok0Jhe;wwZdi;nqxpm9Y#!?Xy2baNPmdxAX6%y zG#x_+SkNnsd)VkGz_IKTZ5h>92V*`CMNmt`MgexlkFs4JG}8B~W>e7WmEEu(2 z&{5z$zZpKsHopex!vFX%1mntg9BoVy3;N*iM9AA`g8e8cP-j_NOaY-#1hW{Bb=_n; zqD3iPAX{~YU|covbe0o6AXN{cj6+$Y?9E?F=z*pm{<`}`p$KL%AaBT2yYMo1T|5c> zB?Q5^W*)&ab*c$Howj8DsHt|>1b2ODIU)#!A?W&t)+?j!Ieov{a~t4UlpvUupgSBy z&5yAUdk?iM9~q#a9^NvfZck20K?^{4PP&?53zkwy}G8)%8MNlrbpRcLD#NOJy zj^!PK=POE~C$hFDOo0ADj!CK5^VId}_0!lhNz>oqT`D;tGw%oSyx=>dwg0x0V>XyG z=HLl{AgF%^s5}Umw$^r8(M>lm@(1&aQa$Fn+gEP3t5oTtr@TyL2+BqE7&GthY_xO4 zHqgg zw%3kidtz)DM^G+0n-G$1hwa@Z+CG-M7e`PoImIhPPQ7&FCpDS(oFeGl;7gc~&)L^9b=URJbY%$2 z#eLxeAklv2Xs1(l9%f!=%Ef2UC*+9zqfk@*Fz_BjFfKB)c;5YXz)qU;yI$v2n9Vtx zXXf91e(bazu&|0=QVA;vPzte+)Q(|%`-(%hsq*P1Ue!2)SUc)l#+F_>46*cU6F zvCS=Lujsd^wiDknz9bNS(e594)t;9HJ&=?_5p>-^zs-N!RXWeJ8y`knLJ^dUdWT`~ z%VhhmJC%Ze^&oV>%53GyQGH*W6(J&={XcZ8#kT*7L0mui1~b zm$Kw(94m^TT+Ft&9G~7^S}~uU_v>iB(?mXtXnN9f+( z4JD;e1h{1}Qf`j5-~;~ZgAVnBFq>kSUb?<5RyY1dVTdo7E3AiNUFWWdxV1b`w#*ly ze|T(R2q0XJA8tnQ@4fI&*!g?#&FQN0!RZKH_r*rZC=}5%$#AUbX*s%2M8w>SEo5-@ zo;rNV5r)8cga6MJ{C95tcs^(>f^3@6IRn@2y#bHM;h~M!w<;u zIeX|6JBLV0q2Hx30hm27^|1VKu#LW3>HtGfE;ct<$Lpv(vm{hcet1Yy3PsT93-m^n zPm)7Yn&|Djo-+jHauh#qIKH4aq1Y+jvloG-?(+%z1~?@Y(lqXH-wi%4l$^RCR) z_q**oO>qR}qVY4ZKklHMa_+j_AsBrCR0ic*_}l>BF{Y#9U)ZXrem7->bnWfjS8&G} zeb9iggUR5H+DExaJQLo^bUG``4$fxBtV1hG5tQrGV*_@-3vzr$ZyTgPaYYuc*iUA< zgfcQ7Fraul0T=KrTJ)&_+l$~E1lMq1`4y3dwW$Jc%9zbDa>o9S96`ClO#?FH4OWEH z!!ma16*=cgw5(I8vjR$?2y$bFmA@K3mEYHP)u*z)Vrzm%h)_Mo`aU;b$kdL-wAbl^ z=!g3?w`|Vo+`zfTALK=>I<)ylW5q_4&IgII!uKHmxhF5Y=xk@|jQyZjT6nF2s)ckBq^OL zlRidfN{6@lbZ!Y3ja$S$YW~ZBzVi~~?h^x8b|$+Sqn>;4E*&Mm=iDt1XGCqM*#niD z8}Mz3fMkqep!x=W!!jtBusB)1I_Be$R?(L5`&zewIaJb`m2z{T5Ejcx5j@Uv|3zV6 z@3BReOvRf~dP_#`4OpLG=habSxlgkEd^CdfoZeHg`)HW@^}C4ZvtK^S9l>v^>G;r5 zfEzWM%LyO$$+Z*ua0KO|V+fO$t&kfA?Uugh@pg$)=!nuB3i#GANuE5iL+0{8ZKo89 zAft|zLh{~~b60GaJ#OM}1B#$r^j;m}4^5SxTd>mGcZ}1g-=+Pab_`}$nJUZmnI|(9 z#QC5Uig?!!J(4Z3Zl-fZo$579dj9AkUk2jc1VvD;&?N?R&LdL(b^0`xF zCgE>qYIk!W*V)O7V{8l}mwu;nMj6x7F8|UNNGmOn}#zx(Z@{>Ox>PM`km_!jbG;xqfkDYUzkLJ@4vZw?BQA!kzU{1x#QfFdXtJ(oiD@^$1Mm(_N% zL|-4JPz2R6sMEBT4E4%kuilGUrj$Z;mz`ceMb(fS-J6^HJB?95DHQQ7odFNx3|Q)kHMQ!ilAInr{QICZFzBG zI(Z^HA}EC-*s68^y}rynzmYs`;|(uGP%f(Z@adALmB02{xor)u4`OSXJtuY^PvL*> zl$E+i=*;V}0s_q#AhmGV?=~>z{vl6i9-u#5%PuK})|Q~Z05E#z#xhxC*8rV!TLXq* zT;z8fzBGPux3o6)(w&QqlJqwqMbO_207lL@IkA(Uez6ZdUSv(MbxzJ*=#5&uQ?ASW zn;!HJ`mYFrp3c}g82sYq%cl#x^s`c!l|m8pv`p6u#8=!VZ)~_{Lo)6kltK|y^P%+V zc-gh)4ZF}BL{JJv(6b%f7_?dbwS10!=VuKUpDf(Y8|!r(E=G z2lp0klD{_?p5*-yqbw+ba#1~oe9sc(#ZlLd@YT4^DTN~F*$zaeZJ1&DRkSg1SEC5Z zMKvG(y0=%J5Acw~PGdhPg(B!_5T4iGCf#G3$jO^=ccuu+MR!zqd18z4-gUfg@%D?L zSv$0f3;o@Ww*WOx7}buC)YFPYN_r2-xQJH-AS5otXf<$z&RA&@Lr~ud(3^1>?iwR< zE{@cRG20}gknb|D2)?lTr;#;Ve;suD2tzO~cB7awWrs1dZZ}=4>Pty)*%^Y}C??iu zAnqUNr1#Fo3(k#vn^CRw(4p>%BG_I_@6usQU=Fc%L2Dg-Bbx$BA>U=Y zHZ+UNE>4?5uU}J+As83EONTKvyv3FbLiY_TkGD&|Ztp3A?b@(1*-QNPvy_&vgBgNx z(YtgQ*0HdN3n`_i$J9W?uX}llVEa5|*_~Is*x{jjZf(gBjEml-W3pFaaj%evK9~V* z3863q-L>Jzj@;sUz$4qk4}aYe1l!x$UAi%*q^O_uft@!25tKr|OZR!W^wL`-E!=A7 zsED?NA{ZCFqu} zF!6VD^&v!13PsR;9t=CLI1=?#tS>g6BPiEJ8cj8!y1)3e@4fiz9>y(E3PsR;9$ws8 mYizIGMpg~Pa|uOIE_x1zoG%`Tve}nN^@N`Q*lC%akpB;Bkc5!{ literal 525084 zcmb@PXFyatxA(V-3fL7DD+nkmD59vy>|_)xB7$8}0i`NPQIOuHqgYVvU9lf~W3nUm z-h1!89(#Y2Vdgw5=Q-!z`{DIdWc`18r6-e}>`V#^8RusnGA=aO+rj+*!#{&olJ;NJ zocLl%N}(So?vuyWuPWOc+G_f4J|?g0I!(pH8%Ax>oI2T0!^0v0Es!{M@}zvfoW;uj znSd%CUGm=qj1~09!ZM4MHn#s2tG_IeU{BJp^!;->{vx1?#Y)3+;U8i(du6)j`2B@i z?>ujKY>;r?`-1@FK9J64c@Dn|1<1_(Ajsrfj?YhJU>?J<8ouX#MYIMHr3&s`qoxltA? zJ;9&FEu4fZ?psI5A^|Os;68Ov`kN0(KvnpP@+&yOQ!n~}77#;i|MR*Vz`GBzk zVQufmeeil9#)|hPdJC)V+AyynfR;r9S|GtG{v`gle9Hj1?q!zrth7a^v59Xj`dX#g#nF z$$w8dY#+d%MkJsG5}>7({5t_vEVs3>;&nnKV0?KV@wjupAb0;pKno;*kN+X%Pz7SB z5@Q8x9Iq)nRy^*E(1v+E5D94c7vgVu1ql!?;XMNP_vni4>i?4uKALI?mT!N{D`)|+ zg2dnQ3KAg9M`^8(|E^acN44`dT?z8OMCM`s6fqsp!mL^qk2|Of{{sP4pnd#}fbnH2 zZQMBt()2e1S|Gt=rb~w`rUMdC#cK*Dc+N}AjT zYlh_h^wx6T!pi>62%;xM%YO*=BrwD84N)dHj8%_5 z6Uk$xeHORq!+b>M>ELN78=Woh&QzwOD0OOu2!VhqeYng=wFAeM7qx=bB?f`T(4r6X z=kk2xb)d}0uCtF6+XH^;v*&yS0;=@kG9MM!R;7<04pCcm99Rr3`Y?YkFHK(dWj?On zH>F-f+|<4&Tm%BD^x-le{_E^$Q%5ItO!>~m(4r6X=kof-{;%`F)Ra+bj}^880af~N znGY5t%3`MO(Y0PNwCKa!2d{4|T{<5u)s&@P?I#-x1XSt6Wj};JS|Sior4N_+(A7lBYN9o?=)>HHt{&@r z=xRGPRlGnz zl|EeNLpO42324!Wb?M+EsxBS8SK#fC$4al_&tkFqOQjE&`QSYdZ-+eP(4r6P$^-m9 z=e-+mhin`a2$s8lsr2D8AFTahUV>~K0q>Q($%P^Ax-`QRfnZ-=~RfEIn2`(XWw%wnwb!AF1I4tejRSMg^- zl|EeNgU>K{JLEkawCKa!2kRgCZxEdiR(fjQ4%s*;5KyHLm-*l`CEgBsPYo^lF!#ag z?O*GRlEi0YydCn!B(TBMYHeSi}r}=-zK{cOU@=;B%;?IIA z9_~&PmzMe9^HBZB2`!M&JxMp7>tdxHogo2L`f!;KUCOmH0BF&NL3zkLtQ`k=?rLWl zdKG_`F5k2&eYngAFG1c8**LfwTJ&N5TwVF=eCTS4cDAHf@n=DmK3wKQR}-}}GHB6< zxer|p)%noXcI~WBuj0>wDt)-jhpt6wXO_^S4|5;7mZtNeYqi?ht6s&Q1y%ZRnGaph zpq(K@i$2VK=z0vD4_)u0orUXF{8>Au74i-a;KFodS`bV7)J`d%k$i_i| zfGT~s%!jV0RwM@&1MROOy^22zs`TM9AG#4oo$VQ03@!RF_W^(D zNfHT-rPu%1MaGXFgg^PFky&YGC0}1zAZ(dRLX0n!j6P|NYBfqBF*)-}THkd*l5~4b zG|d}26-i;SIAqaia{p{LdTW)5ZiJ5_W|Q;L`=(ha*2$Y>Kc0!k^-X3($MA`?W1Y?D zX6RxZ5H^CSPs~QY7w4e06+B7v`*Tn`l#N0RJ&D=dS!kzO4kHSJ?C9j5kvO|aJGDc6 zOA;`z9B%8Djapu5Nv;j8h~Fe;pe56s$msQzux`0~oo6X4Tvv=f;{R4<;7mA*??}S2q{Yk>(ov6_=glcB^ zl6`g?P}c~x1gh*2Ot_~odw zCBGy7U@?wtJn&uPjhdlK!^e?~`QJ2F{>{+$=OLu@*$d6hLNi7Ll_pT*Ad318uYjvw z4I(dpIHLX2BGI5VLF9Fi6T0~(67~Bdh#aZwhL%x(MwlK;pnV7JMZwqrLklE|jt7uE zEBl}uB{7Vs8<JvrJ&_*%U5eDjcZ8G=)dZ25 zDg996!~O{7x+FEL$?8?(V`#DA3&8@3@6*Q-iAbQS>SJg@6C?P`pv_D!qL2pF1p=z( zN+G1@5DO${hB6{{#X_^lUsWU3VRgO*at;s5<*LgnT&K2(>&K!idVhfNm7d~0>X3LEH18&Qc%`mDK-H#%3FO6>`e?$zU`AZr98W{r-a=N->S1Vs zM3cP}h=qSW^k^6-zTS$bExaC~CU2`_Xn{n-pinZ_q6u2IZwwi1rnl9ZtjSo>VD;D@^boRx#b2ABodKXan!iqIrM0ECk!o+I2RI4R?j>yXYO!kJ{&#b zXlbLpXyv$W0s&PCo1@9}X{%-9zI?XyA|;Nty?6{&7~KU!3nV(Piy;+m9G1rp>Bope zJ>ux4m`%vrpr=4URZ(&bDfl{9t`;|p5lLO+Xy(Q>Xx_qJ7+N54VrdL9Jvm2SYsZQ2 zadC82*giCKsEnbi(S}$;h7h@HkqZ)uHL-DYN|AzQKbJAIK%yayB>@{XvW=Gu^O1n# zXw|ei$a!pEfq<$y7vsp)oxbwUZoJITrN`0f`5Vw)pRO3H8g_^$(I@|qRZ>qR67w_T zs9Vc5$i}Q2h89TJ*GM2Y+pLk#j(280I_AdF(3DlkB2Xlt$~iNERPM4;e*LN|Biav) zqkohPM(dBeZCyZ$X5gQvyO&D~d^usktVknp*kK+3r-lbc`QGyM{ly9U{b zsD)pDA>~l@u6aCp{B^kOnmd3IUbEvUIk_0QJ?Vy_1rjiQlGLPo9KGB=3}u_U3j|cv z^N%N;9Npv<`*_O#bdIB+D*B1bd*3q6)b;A3Z}92c*Uvm z5!nYr3nYduParNWYRh3KcsuWXJeDr>za&2|^b!cD67y>0+E|)WCreZF!Wazm2c~wl zOA^T)yWVN#_#VthZ0$Jut6?S0>zAGwS|IWEYYIvJzDsp!b4Nz>Ul>b0#?~X(9DM`= zs?Itk5#za)OX_at?ZeVPhVH7kpY;9Ui>p3LBvDaYO6pfa$e?`^nH8K-(k})7?br6k z=`nQK*Dd6cvmb`P!y!?(a}qhLQkT>@#A|!hrWoqoX*G$MBoa{7o5kwpoEjyX89Y|= z{3Gd_L4%Zi%SYn)NwLIuc)G^J(;iv=h$YAVh}C#?X^*zNk0T~;CTJE!*fYX)dnB!v z-A}1sGzvotB<3%UBk!HYYo+$XXwE)LW;?l$U)5shvk`a5RU2P{fGSwu zBq=00jQ$KPQudzjiHA0bBsGrj(o`7I8ny9=B|}3uY0j22MUy&DBsU%()buKB$$Y#& z7fO$>TBJ-IsK(F&iJr-m2uePs`F*YtBiwsUpm(;eQVv{k76_;sa3GvCt9(YI>0-@@ zTGAw%vNJ|Gd#E2atQbRb4i{?L7}%j5o=K$LnQ5A3%}r3J50lB)zKbf&XbANot2trH+fC;TNF-*8y6@J6ku>{wcd($dcUMtl{G{koT#*$alsu5e`Cdg<>AlaB-l{85z zhnCjzB0nqFBdS9UnU5b9qv`d>pB1~J>KIxe5#a7kW-M(;<_+U(WYt|q(gjIBm42H{ z1OloCZXHG5?ldL18u!r_`O~n$7Zvr==Gfs!5LvbGhh~U*GZbbYM&j%I(5!6tQ{GGb ziSPM}M|&fiz+Y0L!zs&@7CBRO4+$hZzo znGgKNhYsrVL`n8)ilGG(Fb^fEUDW~fNTZtc{*Ll^ zR+UkeDjsBK_qJqGZxiO@P)~PS>sxK=8TeJOK%(XBeq?l?j-=NkBSze<;6|_4tVg@o z{Vott5&em)cNE`1TBy-Y41v~T}QGYgcBcp2GSZ8s?*O- z6@_&48#I_WjF2MFPE4r0c<&%tz{N z7n+veke++}Mj)U{Ec5ou9O>%8?I=DwM_7-B>(nD&Ig`S>JxTub(`=pkWVtr<%0(5m z{!xG?2HKLiOC!ml(O2X~p|-@HSMt6S{p=)Rrlo_lkJSV3aogLdTixxwW5JKjDV?mN)K6&X|bHD@&GuyT$(KERetYdVUgoIfdxv5LKBOZ|q)G%(*&@BxXzEJx1X z8c8mv}*x|8!=`jFlkeE;rZGdnu9(23?|y%sExc>Sw0ah@`WOl+LV2w$s~)ay-G zYTfLF3@wl#-nQh%mC5-0u$Z%Oy9=}HrBToVYWdclY>XGW7Tv$7enbV^%l;G&{= z(kGSshVCTA)rG9JxTo6ESWU7T_b2?#m?cZ!s#q`5AngU)DI5BwC2j7}mD;%vR6z?Q zZaB9m31>!VY4$s6kR>fO?@5C@3>FBeiXUW4#wlK8MeH*tNm^uNNoRWXq#uuDJ3$L1 zJUwiQ^+7M4kF*m#X@dj{Y7#g~etL8`Dd=QRB>T&%9aD#rHE9l7mFM*Sq;EbV_jcW2 z=}1WJM(fVCrmO5ftDprEQ#!elr5n2Ge9#s$b(`6SW?OfZApun|4<#vwwc3k=?5SVO zAt84m@q1}^VjAP3^RcNyN4m+NBQ<)e5eTS)IW0-g%!bkLTa4+ituy7p^@7RnclAiU zQ^!?~_r{Ydl}xqI9q%@l>>O-Gf~THkDKC0Eh`uhUL6dv6m7xU^H=2wg!t}0CRhgYghZ!PL35KslnMw0qDhtoxaHY-1(kH|wiq?3^edo@!_ zwyJIzq!a5%s!jO=zZ5bf;HqZ(qung!W|pDUK~th!j!clD1rq)DCX>al?r3Q?eq0<+ z*JYeg&Z>w&Ko!h&N!oTih`K$vs5mSP5y}G+7oy_G!gHT=K5EYmps%~$R^A>75(ub* zWg|(mCdJX){Rb&yuH?&~Z)FqbSMJ(p9VyNt8?Gd1!`t(-$i7x_ny0N-vy}H45=#fC z2P$4S^JHj&M807bF@K+**4mk8g(~=pK_b%F#pV0s&R9{3U5%|0FtX;Zw5kk34yPn_N19Qoo zcE3t^i_)~sCCH(Q&PR{e$+URKN{#g{wLA^yk?97LI@f2aYTt5+dTySUC~lEQDl9$j zxOofj+r6hJ($;@bn)w0&RS{M5NYvr(U53Wyv+{U} zlc}NUY;yGVAsJdA0n^9Uec0}V_A6_W>Zk&O1XTG}&Lf6DhIAR*cOmn!VoNgJ{H6ve z*QpAE7D(**oJ%YZ&8ZBuO`VfXYFN;N8&OBEs*dx%q7kH6+3;XGlmgUQ8N8e>#4?W z_DlpVYg*=#c3%sf4o({IHy?%llWG53Z!{rRxq=T!NPfA*EGNK8+2O!^eD-6piukH| z7?B_lP*s0TF6nOHz-d`Y9Y(CJokaUPeJ{xv^bNti7zG2f$vNlIDx>>5|F$m!;Uu~s zxRu6n&T9mBY(Qe+)oilym%Yj@bp`V=+9-(*OzcXUSw9yDsDimJNl(`^A5G_JGA^7H z$^#N^-E&B{f*Pv2bqkq~becpjIIYkaTO1Y$sDfp~W@L>MsbfqVdGs$+4EL=(GR`C= zIhRy>PkjE{9+o3!iM09AR`R;drWo#Sfy97%nWXN>3#v{BKCxJtxg^qy+diw@GE4*l zs=BdVFN0lIsc!q;WW;Q@1p3YXf$UY?2H)+LPL!N$P9v%`MQbmllWhSOa&$)%wE6NB z66|0oKfJ`}?c=Ny=)@L3xG|lWxwnuPmDXiM%bn~E@44Tqf>TQds^-5czYZW_TXn};XDvfM$b(WtGt;~REa4!afzq94-7%CY-J(kFik6sQc2FZaM{s-uk|%It2%cE4}f}sTxaJ8Pz z+u7UjIX^?tlEdsH2H;sx)#y$NsfwfIS-x$Vj}E)zXr-V6w)4PQc!SlpNiy+xHBFAP zcNE@cv9%2L7CG@%9twWbO?Wo}3B@Cs)bO4v+eGkHXM>zL`g>J-CuQNG%!*v5KtwiJbq9Tt+#bL3R%Ak z^*0J2>vxBuqt3qQXlp-GbTtq?nHh^}8U~QkGoi>r&EL3x&P<{PI818P`UF1(n%m!wM)2V9nL>hH$DTD1OkW)AgwmSj2^L7$tn?#wyJw>QkNI2u zdX1B)bHiYC@#=MffGU`8k~HmF5-nFe7R8KQB$NRpTE6uo9(B{u?=9ZUN34=W@0vy+ z&l}4H0;j-Ul*81{|L98=94th4iia{E86=6GEiy%pl{E-jAklci zSn?@;I_h&Ggb`M3wluGcMlO0WQXrseI`d)tq7WS};68qwOs4%3PnHzto1xAF{YZJ+ zwP@6XKB%OrA6egP1u|^nhVC93OKwbDj9NY6HPPg7G99!j(&>(wtzdzK`n@mN9}R%g-*5@6=i)5KskU$bN0J*;4n_j`GQ>-4V1vqLBHBe!mdqXY#kmHp`M} zTvmbnMeQLFP$i~(X=yUOIiVsswCt4(ca@%Q;ZK4~wy&857WLS8{aHP(*= zS6PRe+x1~S-ZP?ylbz;gcT<6YDp<1YS5ZMSl{`n0MlM7?elLJL%RPX+t=c11dH|_j zw-kNNaX&dB;YPxw(q%5GVM^Okc?TrL{=9C zkh$fLAjdw=$Sx^}Jn4BFb>D1_TJ&OX2hN^E4;r;%J~Z`{>Duj6h|AWIDED#@nQVR$ z9S-P-Y91O-oZDPSE^Qkj_#{b+X_ic9ozyNb8FO5hS1r z<_LS+cRi7|@vNY{ua_$16(sCUBS^Q=AJEF~-1eyMe6`j1^SDJY;(Z z>nBo&UZ%-7RnqFCcn$*{jR-P363vF zq~31#N$}V;0s&PpM_9c|kEAv|HJS(Qi*Wb0DcYEL^|&Hu7o=*#w}X$$YksodgY7MG z;?Yga$C|s7Y1GXc#HD*Ch89S4{>a)ts|!O*cpJ?9BZfYDAd^V{P=SD|(wHe)qMqAg zMx5ClO!MPL$`$7x!M`>~X;0Kh)BshjnW$A=EdNXnT9rupT(!XO4nAhY_THoEr*Q+3 zZFNZv&*Q)|I0*&*+9#E)HD}|8QRe|P;7Adw-M_Ya)Z?LAi(6DjbbHHKZ8)-Hb97?5 zFDYtnflCwk{*thkUFliXA+&CowQx!Zo(u|I&{a!6?Z$Vpjtpu?gByNE{aGaT*4cl^%0+kv`_V|#=vI;f!q5~ts(v_4k$ z8O(@&(RMVmngfPA?qR-(QS?$b)9dEn>lq zJ#0rCxtilQZ0!L0fJC28Hss)IbNu$#IObzi?W*z+XjlDoX70eMydeXQZZEIB( z=S}V;<;40De>-Z`yc_<~Sj=6RrjD;# zkpqot;n3Z2%*XQ89q3InXWZkIof=vo;V@Jt?(sG78k_NqC~w1ZH*XMbXWT&`pepTD zE7EL94O}ZLff32hcGTG;3>)lgr-rB6loqW>-Yi2LR3rUwC)`fAV`t(H2IHMg?A7q> z8zdYZTakPZBdnR0#(Zpw??5YNj>bN3+Xw_y!5B)?MCQXGbTqc<*~Xg0YRx;d9e>Z!w7WSdvzIkF^!O<{ zcWWj>hpma`)_Y_%ej4-PlAz9zA34m&lv#Fk+V2=#G}lfbpbDNuWU(sjL_e6N;~~b@LadaE?TP#0ljzf^xyb)w z3sQRQ5_)@ZKJ&3T&z|=2&BVj@*{ES^VJ@_@vnFxN9wUo{3NFYpsSB zNQge}46vgIyz{V`aT|evswq=iknI&OqjHyctX7zJrG-DjaMN~8)jNHh$(#$PQ27&6 zQE;*YiBCR`5=)B^^e0Jed{uOsLp+|i+d@b=B&O7GAc2pMqd#vJF&|g5oM=MlL|iw` zQXrrT<{Nus;@Xd97!AVnKi5=;v$y(wgG@>%Yz7!7| zhQ}YPEu;eyO>DZ7g(eiGY%gT7Dv9VrKSzwlR_=8L0;*OnQIX~E4xkt1<}hMn&z|(@ zA%CpwFjYg#sSrnU=>B1J{`j1~#VXOIJAHk3JU+L-q2L1&-`qM8qsvE;fZ9B#mPk;9tLklGG{9MU_8{3dy_31oTM@P^qi)`=_6On+bdtQCX zvpe*4mut|debZ1;4G$7;vJTy^ zQNVpn_oG+#8RAapCWe;6$L^$P&^mO>ya2%`Nz!_YvGjc3TKN0khk_4CZ0qGp#zkyF zUyXUJ%B}FGC(bp%Ar)Q;1XRH^Nm6q!Pa1Tr6>jD86GICmrUdmR1CMM)9|E|K{M#d_ z)i4{Jec_itK$VzRG1Wt9VujPFPO}|&QsEF1)_DoaZ=R1<-yTeMzFdk*=jWq__dLmj z+N+WJ5bxV7R-Qn;pIt(E5BFebfyCFWL8M9S3Utqfoz|A_x`fb^=Wn1#_Cz3{O3dBD zFM-rn^A#0)pAqs35*srIl5b;IA+J;1N05I2?do41zl^*j5KslnpUo_dC(`a@D|)_bKFt$|#8PjP#olDT_mBG9iS-?qqv_@< z>8SS4XbjJ?Lqa?ipK>~i_O_UZ+|TC-1XP(d8cEtOn2tKBvRSOkADT?-Et!d|x};-h zfdo8-FG&lo#?bLAr=j}O{jp`1H<>dm6{)SJp!}NNYU|=nhSi&ba_*)x zAFsE?&=)JFp*@B{7+N5ae8!8^Y(530KAggc3-w~@;%%9zd*)byfGQY6N$PbthQ5}w zk$f-^LklGS4Dup-cVwVj?itKSw^1?F=V}fL$_W(+sDj@jVDF>u$I~`j=b%;#T41=Y zK6#%n`8aS4sy{p#x$gEQfpf;7R^yYI53jrNbVT1d=;rel7+U7$`x49FW6{~;$-=5S zTU$CBPcz;XBC|=Y1Rsz{`g1IiKL?`o1u4u&r+@_7A}j}OCyfOHs^CgG`&Gow*EZjk zjdH5D#?S%@`(I;7yO1z6ry!O2Sn8cfC-o~rev`im?{VP!511p8WNVc`(>pCf9($S! zv4TWVQ-89|a46b5fX`mV!G(=1g*NH@CfKr5VjwwW-ehD4?FZlvSv znmA&P_V=J7)AW>{xMW{*fq*J;zB_PvH|kN}8QF3esb(Y}W(8DMRQhZOKr*h6JR zT^5gK-_o-b2&fWgeb*D6X@mZrc(`*DVGak0;J{wwRrxpQb!GnBVA0O*bY7`1?(?9b zKtPo^hZ}f!5G|O4aQl;$g_#VT0m3;7TfaKuK@Vp4!f$3*Q9}zPL?0!dgXpb`PS|0y zp+G=Yw^oD6-7W7?$2$Qm9T!%+(e2-QW24G7)zAV7m?lX&x@Q3Gw9F3os9RMapen%G zli2Su!U0)*nU7Tae)L3z&Nx4&jv87Z0dtytb*Rz+I`dlt9I>^!KtR>in9*bot%Z|f z5c4tPq$@Q!*9?Emud9X@NWdDyenq*vb1j*XpaG1ro3YOVa$- zZuINT?PzAGNI(@_L6RiTwteWujP0oHmnOp65+vZaW!Q`i4WS)g=b@AtRn>3>3a(kf z*s_^SH*5Zy2k38;d(&eo})c+(|h8mhDEBZd}8 zESeQcz85#dmG<+uG9y{6-uyg>&ebU|lm}G7+QU}p>-*5%$2X&l>F+VLK%&n5@g(Mb zZQS9K74xyU$4L6H_fxdxktEbBsDiD4&EdR!s7=CYG`i+H3@wn@Zy8AT4Xc9JmT%8| z_|lPdLup04;`dL1fGXIUCCRY%7`kN9d$d7*iJ=7&KaG9J!kjOtVqg9a^4Wz^G_a^1 zu5|vhKtL7jl_Y7ISRa3mZK~c+o=K2rroZP9UHP z{w|TEbz#1=S-vsOEW9iH{(wZm#v$Z4DM9{;eAYMVy)PXdSq1kSc3U8zO8jl$oe)b) z+jS*b6MZl|;|llUh^I`ycZs9s6>e+JL=DBz0tvX+h`mK#8B5z74ktNFJOu)(#FLY= z*xB&l#df6F-%U6N2?@A+i`5dhIJ%CVZQU0u5>N%di^b*)>B)3s&GKaF&fy5|5rjJ> z;Z8@Ej)v^L^P8!})<7-nHiX1{uveAsTxNUjYG1FVG+U1Z0;=FnV770Gy;r+;+Elr2 zDDL=$gt+hZtqGfp&aqdf)SM>l5r!(bKbgHh-!+L&4GLCvKkhG_&V*-%;kirJ@5V&Z zfUl#JcR3yyS|9<>53{r3g;6vuWRMc(+EXB)s%!sLGIZi-&3DXCBDuy+rXP=YRz5%K zkD&z;@HDU_Rr?-I>vgeGO01m)0;(Dsr<2p^jWrkDt1=%2vtnrAHX~)`xV{)#AOTMU zOH#u-vDDoB1-aV_2?SJy`Ai`dzV0aL=V{1%%ywYyBWE|cR;~wz7D$LSad@A2x~66U z+1{*^KtL7Tf5~nlVL{(8b-Uk^I@|0;&;kkZ3uYJX zo$08F&FS%~>jVO-Zf3fXN;|rcZ-vMCJ1?adZ8_GA4)HmLpal}}tQ`AZ#`C^()v$*2 z`QtqT0aXoRh7r>bw!|y*F!M31nmgTKVnVldxQ3tw67aMm`;yM5fz;x1b^3VWQGtM} zC%b$|@LDs{*Ka@bQF+r)`enQ!owWH0f)+@?(~fNYYM>{Tzn7;m?=A@hRL#WWh~>Rn zWOrMI`N&x`nx;MeqAV@?fS?5u@Kh_?Yw*K|daQk=G+c8}AfT#A#R!sBT!CDBw1@df zy5UP-M%`7Gum6pp1rqRdt|Z<35I~D>UsRkkUI+wKePO4}AJuxU@z34Ce7FUTqrOXy zD7S_gU}%AaeYwfxcAwiCKex|}SnL!+>E;q;v)g+F38+GH67jY?sTtK|3nMP}45d%w zHz}jGRmRW)iB(1kr06`=oEr3w5s%J<)7Z|-6{|yE5G0_=@_Z^uT(D6yWa$P*Y@9ri zj79D^ke8qf0ekdcI)9@12o!Z*I2Idee6V38+eHGKJimF-_C9?ixnS z_!ULXMn@~zvBnr$AYphjjXZZw)p)mf#E72nqv_4W(Mqo)-w`CBstNlt;uI$@O`jyb zBYw-h7&_gnhcbSd5r!5>oZK*lOx)zGY4zncBPx2dqM^UlbbiC8GCbP{PdJJv+>SK2 zr&oz1ZS#Do3@wll&q2PctfD#F+tOEddqe`9mV~G4*qdr&HT|PwYw9x306`0UuAhB> zvZTLE&^^9~#V@)C4gPLPAN;;9oYaFV@w{4-_I>Ei9%i)WB~t_~keKQ|oOqqGBR9Ph zn2+>cZnWb8Q(9{KT{y1>Rq%8jTW{atLDyZcLtUQQAZUSv``$66aj69{zdxDzSQk2k z+SaQ^?=Gk+5KtwaKFganoNg{}NbRQ}1TB!LHhw$_>sXg`afx6)9z7dHTe4Hw8SV`Q z0;=FyIkvBFmp9#7@L35R>4u;M5{HLPB#k;%CKF}{Ganw?eCgU+&y;EtTL=VHiD$_w zwF#is!MBzE<|7fbKw?K?Ea|ZLoo2@of97M&;c;|V!WpIBfp!7`Rq*5+``*%vU~0DM zpi(;{06_~RHeF68=S?qa#^3X1K9-w@(dt8XDBb3=J#`GV*h3mfWd)>j~)3iglen;b)(>6N?9>F}dT z2wETkXM^nP7Z$x~dt^>`6!{4RRKfm{)%KRIG-H25IzDzPf)+@?*`OpHTkTE{+%ut3 zX^8>>Rj_|#b2#@w^l7IWwC9}p2wETkXM^nbN767lrLhrBMY#e2Rj_|#?~0Ci(ldQ4 z(46$u2wETkXM=3_&MGgu;Qd#{XQ1rl&> z$G+Xxj(z!S!Yt*L<0gTCD%d}=@qAtsy&amR?E7#OK?@|{+>W){NT1sl8$`}$*1$$IUnqwD0YmhTa`v=y-SBKyiwBauc_MM^@f%I~h z6H1>`Eitq}0)8Eeo!d4TM<3rfsAzJU2n1BYUlweIrFSrGJ$t7z`>G9w7D&LaLrGHJ zo(c4O^9{WC_4XHq*8j1?FR+FexM5evS8x}`=Z>-KSwC5 z`n1K+0tvY0BuRFLF|@KvcO_;?Gl76ASYz0!-;*)4q-`su-hCSkEs%g~PV75H?5n4v z9@SDV&u=OaP$kwxD-HW%@0@p}))H$BEs%g~PHg|~+jzQUTPZuS-asIrN}MxzHcy~) z56mDv1~kLa0ts<7>W}V;^!lnlHCyd!3j|cbZ{V}tPW;yK~y zIqVzQeY23y$#xjNCm$O&hSWSd37Ixe6VBsFQY)i)I^Ci< z`?F_EBCU2XorF047S2aO6+CamcAlvdsJ(M!|)zYTWGXJ;DLA0WN` zDhUKs!80_Hlr}M*ehZ&NeBZRg&;kk5+(h!;r!Icc=??SpD>8u^9Xv!*%NYvI3|0aeHL z$C7RljqtncKUnS_`aYT3T2vzYR%BpkfdtGq_Ws;ElA>>R8k@+u0s&PH8=?qpZGxAa zFlM#A-k@lDY5G@9l$?&C1ro6Q*|(z)L{h^IYfC(T&K3x$nwuX%UVdXI>dg4N?G78F z>6g(LH7%~DU}%8^tj8>`oTF&3i3?O;_s$dusM=M+ZbX^*69xJ?FduR4W9ZH{BQ+sY z;xM#80=7ri&d*0t&*Piro2k;cqbBR{uIj>XXDKM%{>YJ_8GfduRy*{(^e$uxKU z2ozf-S0JG3s(KW8Y`g=Z+*sx#en$-b=G_q46@+1EfduU5+4@y5`}WSz8=BP32?(C< zg`*EV4J=7lixcVK>cB*Zc557z|RIeM=g_uEDwpep#15AnM32O8$V&wqS$ zh@mgl0cf6aB!(79z`d&M7vxzs7u}bGwjIkA2&jVldfC^Lnnlo4Q+J`o+gAzucOfC} zVr_Ikl%Csn1TD4MA`nmocN?>l_c?yFXjL6F`_m%~??HkmxZuta_O{Px9Gw$!Mn0N% z0YeKUV6Vi!HhnpWrWMpgW2#&f2&jTPN7%24niHr&lRa{~XZtX;KmztklJu$dI2viy z4LN^5ClF8tcaE_4QIjUnKhnyhU&|E?Es%h{k|b5h8%Kvu3`6^;o)HMBf;&gpuKQaP z=3Dj*?JRWp~R?+Zbfj)(+QiLG{t;ba=TEgH$jxk4L+gxJG9oDxH`zI8>8AHxL#s$d_( zZm7seppVa+$mq4T(3e00&b8T&#;b|!YwWotXCn;+0;*tN$@aavC)1Cyn7p(M628L# z3Gv$r{bG{o_4U!D!HR9d_ZgrHe(8a&!_7!m^E;9GosjGvMa_&?GUhkev3nb}H<l*!EWi(l-&o(Z`$NH{y_q&c$lZ7jNms3@;j0FosiH133el+)(5+jkon;E zLGl|z`OSrpfGQs5KFSDwA0)q(l;4gBEs$V0GHQLWTN9ZNejg;i`IO(l2nnd-VeX@h z;P*lD+g153kI(`MuH@yx|0YRX$!~DwBqX4Uhq;e3g2#s663b%;Es)?T=013=**jsD zVtx}X&jCn46%TVCWdzSvekU@|WoUr}FFEdm=RW%;IV(ASCo(TdNI(@2b01{{uO0kO zWPUd*v_OK_S?+_^BK8)5)j)nTFt3r2fGQs5KFSDQ%lYlYyw*btB*IseU%`Fw*1&pd z){^+0$h>7i0;+hJ`}m6>dIDM?!Jef0PdfN5vHDm+0;+iUKk48%(dttUEs$V2BLAm6 zSnewPPGp|Dkbo*4=03{GgWpTe??mP$2rZCcC9C!ES1nQaoyfeFKmw|GnEUvvCTj0Q z<~0#oAi-*=*2iD9U3(`oukDb4Djw!O{%TR$JCS*df)+?HrPc@g8!L0B)ZU5A+ae^O ziif$6GJ?g1>U#!gfdosj)(49<^TATAy%U+YMMyvu4|5-71j|*b@8O^Y60GF3K3MKE zAFSjkzZ03aMMyvu4|5-71iv|3-%~>iBv?z*`e3!FY&4+y(Et)q#lzf38Nu2f)sHyP z0twcVv_2Lm+LeuJl;4TW+ae^Oiif$6yHmUThtQ6k&;kkIkA3|@7pqmgEkXjSfNw^y zUWccAHE)a10tt|BvUVKgxx1RTMMyvu$U{c(66ALx^R@^rkO1Y+2wg2%&2P|#1XO{# zzzAJUEM_&4LJK57J!XWiwiol8z##!upiVPF*P@D9i=xm13D6!H!If+rEaoI6pbE52 zM)26Maj=-j4q6}q`V~g-6ti)#nCAc_po)iiz2fQA-u$lcJCS)VLklE8|Hue_FFC&x znU^Fapo)jN4_;pE*Bz@J{7z)v7NG?apr2=iZZs(7H4+j~#lzeOuXk)WRoRGB%xgWg zKtc{(YoQwl8NuhEY*Z^|WYv#R@gUmbA4JGYqYE=I6dp9d#*Ezk& zmZ0g&Hy$v=f$!YN=f;Or%M2>x(2YF_`*vG$E%ly@u4<#PgO&6l)+k@)jSgupIUO-= zj8^mxM5$9xI-P6T7`09dLT}dDu#}re8>y{SZt5|SnF_Q(Vn$|7)V5AID)`cz5xw?4 zz?(=1wd`4)ZZ0%NA11LKXvecvRdNi_O(`Ckt;|%l4m3bM%aYNyLHrwAPd6*Lbibi` zXHRFE^7M_of7ui?E4@TT7rv3Lq)c=j9akMG|3iM{Fa>=xI>U&zcQyEo^aUdmb{7w@ zK*H$4Yk9==Z1g+nJ|mWOn1h{GEW+cq2GWXd_vMAfxybtW4b{(Om*l~|`RKylOR9p6 z7v(D{1!!dI14j55FUM2=tfYh{gwru|-^rKW%|qmnk({#Rk-X1fA$lM6Tjf;vKwcBO z1T_eM&xp@=7vfp29?B*5eSVQY19 zz60HFyh6UvEgMzp<*n*deueD+F&m9ak5p~#uvs2?DhuI-lNsR`+65oaIgWRv1W>Ej zS+dEm0_2;rLe+HUa=F%msmQ6_8dcPR<#NN{dFa*k1&okPZlbhP!_bG8N!0FgrhKkZ z5qf2^OEsi*maK7~jmD1Mp}M?&xLmTc2t^&_U&o)O8YkOUAE2(fvkrZvjmpotU_i+}QP%uOF zd+4X7q0b6Y+sH!I<$0be(@urx)|*+3sQqaeR$uNXZ+DEN`%fR1&$2I^L|471TK091 ztnM-gH8Z@TT3WhW-aK<2%KCMY5r-bUKnY_i)4AP;(dZd5a+kv0s9&+q-ler>%bmLI zKxS4pPVq+U+i|@&A+K}xjPMxxO1>LZoi3k0m_Csj$;Y;BMknl+IXRl0R$U6%hR#h} z&}H1tW2%+&_o55-wMryug4ZC`PS>rL@Y?KVe zl|Fyh95u_Ck5=ECAh&dBhK8M8h~DfNCI9i-41I094E5ON!FsqoY30=kXD2DC%LY;J z)W+z~>Pt|yO|G)vg8FE8k7da4q?6odcs(>bd=f|q6nV_sJW3^{%BMa^$$~F15bhk*cfJLPyu_M=_-*oy#bCIGz57s>5BTt4wnb)9E=t$?aAK6Pm*`m^+VYW+M@m^vRJH!e(Rym`qWI_IDZ?F zue+nCJDpI$Tz6IX-NVs1%XVmXgW;;pD~F>#)$CBpE)~1qV7WsV^_Pxq)T1UH<=k}KwRMZMPr zq7iNh^3kel^rcfM!ZR`$v10f{b^Kvd{GrQCrPaO>Xve8Y)TqfXdCIk6NP3rytjvDO znvFhaZa^^lv4-C=wjn80eJ5!+{xzaVNeLN>+|nXZ$NDei6{km{_>1Gv^sztX$e*K8 zjfUQ6$p!v4{934kdcg0F%84^}^!zz{lz3wW>h(TVwpiB@rR-gX%=+fb2iiHJvn}SL z2WImbaW6_%SIPQ7=I6Gi&;p4yUsb5)mDz|~S-t#yhfeu=UrY!q7JS{@e+Pb+D+ z*$;ibCgJ@b+*CuJd7B#M%1@0d_oz<)LePh(ye7hdEHY44vsQR;)}JLq*-n@`YwWPG zucf9c`wqo(Ydbvq#&AX)ySWp^^eog&ev?F3#pG&d+oONwk}IojXv1|ga*0y!nyT4} z4mhS&E*ooKPMe08xGm6FUW}qOOtWP^H<)XjMb55Ut_`1UoO;Q=O#SkEL5~eAcR5Cd87D6%7!lFV>49?;0B*wX-8$XA#MWZxbu1D?MpSJSL5# zzbaPIs-lNR5WlZAwBZ@OL&@SgHBn`IN4(E`0wY{YyQ};C{77D~HdyLE9Qmg@;lV}! zkE=J2>*0I<|DVYcWhb&P5lV{EHrF|dqJ=_~N{f}d6p$R z*|L*0`@R(7cbc-)`Y%$b=pXU<%69epvow=48sZ$hH(=!v_n9Kp2I zgzShjVMO4R1bQy`v3T*Oy7;n376ez0B!?ECH&1Jx1xdCe$@4FF%yp77;qlgyB| z%C?#qOG9!%+H}lZtooYOogoi?8>GKQwXfPekSQ=zSZj}6PknUO%t67P!FTMiIM zTn~V1Rxh~!(?MW0DF8ZMz63+s4+W!E0dQsUH89Fleg`@4a{?Vbqez_dx{Embkw3&Q zI|WHYM}q5gf7oxVfaF1=;k>FpoSJ_c5*m9mVncW$&8rR)A^DfQkI!saU3V1j?Er9l z>j(Y4OW`iH0%;jr_kQp(I37KW5npa3()E>JInRhM6x+i<$?r$80r(C$m6%UobT9VG5Jd zoft8=D3c*A@J#+8knB+0H1duaQAXcpfV5G(KQ6DOnZSR%ZOs%#M#Hv zOJAB1?_M2A*yS*I(79eH9_tFxbHia~{%2v@lj*QvMHpn3wS#Fxlv_2nCXs%L{~`R= z*(~@CTnf3~w@syy78afKmckzEO{S`MUYj@Ho&~e*&sq$+eT(&?@*Xxq)~`hBZJb*k zIjg^gHghUhpGnRB);D+T|NWhkYgJ%pzm)Z`15H_uuwx9!QxoYe&jOCPU+->_+?1}GUBeq_`Iy9Uy{k@l1KBRbB&N2mjru9xtpcF zyC6gzO#W{_>ce-CvU#Dj`>WgKSg}7)Bz(q+JOa2o&RdO21wQTTkD zP|+{#zZfHmmy0(1g}=Y z1=mkY{)^FlND%3$9ZkD93vx_g7d{tQ4rK5wQm`kQy1AV$#|kFKd4>!5kJJB)(Y)nk z(y$?hE*nwF5!i*#7`8&ipL;}o)*PDj#Zs=~*Bq{PjDThn)|z?DeIvZx8`t!^_}H*q zwe*Xm;zc0saQ<;QRxpuLStImWko4bHNi~&Z(5GNp^Y8&jU>82J?AxV>?da1WXX@c! zU9S41CoDbf-}GB~9zEbZTLnXThCBc336D?tgG1sOGgbrJNrN8fJ)KUDtS-k2CJL5z z21643-&SSpZ$a}WxzSslP34%tF5DtAS=pmMBx9W?)$w~&julLd$!QKxzlHx7!*IeI zay{Rde#^hl5!i*>jn%m`>`YxlC)4J7SGhgMTey7U5Xk&6^S>C1y_z)P%Oo0jVwfB& zn6S0bfisn!P`KzZYpeaUdQ-QTwscu$WjQ9WE9;3NI2p43x2Z45xH^LWm9*vPuYcw6EfBR)-Xl4bz+sFS$7`GTfJ*&-W=Czh`tYG4fvklB#Jr;sT z^khBt8FgbirO}9XoswCO3GAAtZ391Y$Nm>%oM=j)ni$d^X({Dc!9?n?NswY=@gFg{ z#Db3OrcWa`-6_WkCN@cqP@Q20lX~g0tqQZYq`M#M(0NBEaRhdirMg1HfD!-2urjcv zRStb<2ltNUXZ<~4RFO`T66!w#CiT#7`kNo=AACBI4$$sS$L{-7h6(I49UlN$C0hT* zNI2+9XH8V2n+hwBjXMzlvY*|X6uoN!F!(`tFnZu={&Z{zywg_ykMPo(Nqe?Yq2tF) zKY?0&HWa3sjgfE$<`|W#aLC~OZ(WrA(5qO z7FfZAfqOKp?pZJV-+5I~}jHN2(2;SM>I!o zvA_x@8fK-y+NH<;i=lCIKJDpxoaFAy%KF;y1I zW00no1*e;}`7cK3k$BpYRVQn_ZN(AT6@4lLl4=}B>U@}48$ z@h4lo5dPolg}BvOzq==qR@6>{(J8~Z*2P3}Lly{svzm?#8zB!%qHmbh8*JsZJ6SMb;RQ3<=~os}-?Lzc!74NR!G|nXEzE+YhLDZ7zLTN-ZzzQZT+bo63Qb)7D^OUP1`kYIoFUlGO>n~3QOkfutowEvi5kx0etwvc-~ z7O;Ye!2wy|a=_bs(plxxwn|JQ?OUb>Yb?Du0=saFu&?Nf6R7P_1IT+-4(~r?z#!{k z78c#M3a=(-f`7QWMb5Qsp}->pynnV8&MK7i3?{b|=$O4a@cu{%U{0>x`u5u1N$V1Mzp#k;C{A*uBe2!D6W!m;9~FfKa{w3|5yPYPbM z82;Yz^h~RGcy?2jUz6=zzaoo(a^)8amRWK1hSx^8b*u~7b|VE`<_-`p7tmo?zSq7*Q#(G_G*y0I7oy2sHeKKo$i_nrhRn9$s{7*3A15`MTV*X`?ZHI~Nr zJr1qj_a&LL7DIlRt>AjLKlr_8m139V3QO*EgBJFSp`hMg_?|z25wj1)(#eJ*XzKPS zSiwY9P%^lh&lZv%4P`{MZY-U$=`IleLBt_A0mfL$g|^Fe;ki>HjP_eD44Y>Hi?=6& zVO5qe)oC;%b}WpggO8kt?hgl&#@5LYZnsbvr#>9UtxbZD*0jn5&hco6CII1cp3Zxx{hX~=iR69sE}_fOz579 zhf9rlLijm>#gKZ$(%xSmLg`YTz%Ja z{-Runwzh?~wNbFu@r|%1&Vt3z{}MyX%D=&eN&N{{FyVVB2ClU|ENHB?VMGh{Sh^!y zMwYzPB3nl+f>}Qv2_G*`fl#$bh}uvi4B6oXNy8Sw$bBl%?6D;yjH+>BHX?#9Ky#GyYC zp!&X6$ecKp#fWYfOYfMgkbi6?4g6c!h4+u;g;&MWlIV6s;jLvooG&|f z52})LC)#rRfr-x*VK8TXy`bss%C@SLQ!Kq|tV)(n?Z6S(h3B={TL7In+M-fMYD2z& zk>>)4+Mx+AXL-X%RyX+PcukmW=M62+&4=%8hQWd`Wo^T?1LNqPt1_bR@Rd_AF*k1k z6dH7e?lNyicv{BM=BDao&AjUzfnEGOoWrG9>Zz(qob8$stYAVfGX$ozY7M7Pd$1Vi zi(~1h!K!5S-WD8zU3dY)Y2StB|=jCU(w!*}X!$FV}YX~0el`&dBh@%UNzQO4)mpKBv z@GLI-rh0t>jTmtR?(g%1^lSdm&)65T*erAR5dmNoF$Em9&W1fZ=RoP_SrBca-1CHh z1o}2gg5Zi6PQgU`838c2$_d_WpUsF5(-WwL?hVNG9LEvZ#kcN{ck%SL?@g#?6~M8A z3E7bV@Yb9N#f8ck4^PF@)(-c;@MAtlU>82J?7iCQL>hTU5571aFUND0L1{Q_1n@lN3fi&_2l+x5zofsW@S(uG@GVC-%=M_|{9PkykB ztr{9p;>C!aixTOOISXJ^(lY@o>U(BG*WM8jH**%?*zBv6$%*v1A{Bz;n7@0SK)(#!4)=};+!4gY)d+uxC<_4HT4jv0 zR}$DtA%!rZ)|Ml%3!iVSHtx|x`o7P3dExTGB7SRu-)3}O><^4S2D{EaJ zN4eVVFgaE*(W0dvTsXEB7Ef39qU!aDH0ER*`COan9D!X14Zc7>Z-TsN<=MXbPa^$T zs#5OlJ3x+=i*J45(KoghONBGw*z8&DFU!^bFw-Ka@p(B`FfsM7FEo3V3wxrcvlydZ zCDKJv>cXtBYur|07d}JTdPSevSrWcin9|V30xOu9)5i~-wyXrrMKf58?r#$5qk+}J z#l4$20=w`VA@+`bY$6*|`-vS!OcC*WC;UDNA15|XeI$_z{)0q&gKKiEV8S%j4_0UF zgBcT)a7zJX`Ml) zcyDbhZa*+FE_pV5pL-md`6|b7hrJW&`Lpq&u(26OU>ANv$9mCk@if5jiP*&f1>dEZ~Ca$!d19|PwKOT{y1yKw||;Wv%! zy|Z~deZRJqbf_R%OwR~}4uOv##Gx6aoec!4cMrzs_WYl>mb!fs==c+_MbIC_?FT0M zXwQWOKd*t|>w#>mf~*s$VV}oh`uu?$fnE5GDO*=&Ry@6NSzU5(93qD4EP#bU??JrQ z0$fi8!A`Bmkn*-G;H_md!aL(>ZM~|L-D3#1ADEb97zCTh0~q&1`DJm7vUoZsTSc;8 zqQeo`h4+coPh_J$T_-_$ly4~Baft$hWHnNwlO=3C69sG7DxM_|M4?_Q3hGr_k_kVQ zl{}4Z$54knOQ~Kxl_RjL%f*H8rsgNC@;b)|n;-1?qj7|E`jM`PU24wZ(5$_TyefPw z@I;5nYz%i*M>5PADq;l_S2~Bl4$p7!(@weiX{cr#)#x)=(mb8a5!l7IZvDqNdP}Xl zwB+6}uB|Xp)IJ3EJAMP5`N|j}>hbiTZdYm6N}j+jd}L)Z+t<<5F>i{rC3cy(#w!U- zHM^1rZ?y!S4~YmL=d;XRB1Ujinz4jg^XGjk(sv#E#rp7@MF@h9>S|Tcu{n zo^d);Da3LVM_?B|n(Vu~k{J5xj;$0i$WnatZZRxntEzU&w-yW&l3|>UCK+B5DB!JS zbI5yQsEUW3G{D-5+Yd~k~m$tmZ@`a zEPZZdAywZr;Rx))IU%g#JDb0%In_++^Kr3=^GI-h32sA{E%Gy-J~I0$UKrDXYh6tI zdYTER*BBC8%};FhJo7|6UE5JrDp}BlBd`k}8&;3ZCXsgUzD#Ue`&a((R~BTrn3Blc zO0y@gvtZL*6Vh_yN3;9=v!HDFXcE(JU%5>7Q9F@NcibSZou(pU1rtN}WWmfY#w7l( z6Wc2J*aYge^1OI%Mm$Gg7j6-j{dqir+Ks3bXW6yn+6og5Sy}K?%b19>qgagPDG4+o z?3(!MjT%Q_7tZQoxgU2}j1$M?^|$2Wd6r3`%shJLey`kT-~atR#J{TCZ$%c=oi`); z0~Kt~8(CYG1|F7Ispg1S!NiGSOPhYFxA8zm?Dk5en}d=>bJIqyb#c2*=(-e!?lU9D z%onkDsax74(iU~`qVerTB33YgW6NZwrHM4#u8$a{_EU}t?5ZEV6rwyWNbjy`EZ1Pp z{zST6|FJxNx1NXu-#`&fE!mJfZsr0MVB-LvE@Z>c<*7C1hW-}m#9uu^v~y~*|Y zVz_+E{tR$>YewGnRepW8fL-T(de_S5huTS4!9=i>(L`tcbY#T)+p#q5$piV51I8SI zU4e0#O@#hvLq^z4TS(tNbQ8nOi={1pl2|U3IdQSPDj&Nixye-_T$JPelgZYt4yDFc z&BQ-9wsCuo37V1GM0Zi$%VHSa3a2j9WTNMhT#mpl+-_{1T6GrPSkXmvKk-r0y%*l} zTbgCf#WkUen*M&aTtz$>vk0!*nv*tbWFl*;1%A}?YiAL>UP@TOgne#Y6CHN^4cn^Q z@8;0u8FNLrP{R?}g7}xr_-NK-Ncr4Z4|nh0ZrTcWsH`X-Y>Z6@8HtTVq|UrB>S6_vrgUFp4*qX z(U3iwVs1%u1y(SD+mPkAubM~~FIgbozuAq;9dxXo*%U*6-jM%^kve_~O{wfAPCe9- zi-C!JaZVH6JFW-YDwF7GbaFyB@xw0-j=(Owf2?-fN-LTpD-df&3{v3C#n32`mjuq)MYp_3WLZlK)7UN;bXnJ_9r+DJx zNCj3fF)eX?6P@a6#fZ8jGuq7Iv{=ikb7KO#aEq|JTChM3s%DD^4(V}ig^8#3j!iL= zZkn+eZ9Y;OVeBuaUKqj=*oE6oCM*0hlm_G+5_9?!#jAaWVEn^``0a8Q%lcY0{jR(1 zBoVg=JFlLxwQ>JCi~XGiuB|ZfvYF6C_nSYFZPnH>2DGnyns{2@j3clMw;QV(v8gX@ zePfTfOl`cP)w99yyNxON>@idP@M(C{@0O&_5b@Ts1?a~cMYa?d3Ivz8%vJBF1%0dS?yOl`YB3ZT+_)}aeb9m({Jg!1&FuT_iXxm z_gjClV1G}@>tjkTq|atCzIW+N>4y>GEtssp3MR(a3~r)#{PtwTzx$drP;aw1`T0bS zz%JY(>@AsQ4|=0s5YKmW;MxikbC&Bg#h4PKj1fAn7nPNOcsJONBd`m%8>@MCsFsXe zr!EeCIGf9L#`(>bd3Ty}pnFVAVlm#Eh~%N`U3uKud5U3?HBHLJ-Um6E}T+RAw(z50nfpe{;*6->lC zxCtXym=c!&CDE|XhTM*ElH2!*;y{-}&CqD#3)T zztEq>DCshZ?#!$fw-$6&U0j~ifOZ^#U0)3Y;NL70;^U^tVodTS zG$4PmR6C-NB4D>Olsf7Wuc&_Fs6STF`Ia8(-Y{D1@_iyK>^zeAW{qUTl4>h@scp10 zs9sBfmE9%N!R?tL>5{1<;$LEKszb(8g=U=OwV^W?0~0SFdBWsUL*mlE7mJ~N*q(a0 zrAvWH>KuVxqx$;63rUv@n5)K!=<73SZq!1tPSa^Nt9|{v{c}2w@dJc;CMq4 z=iWi&_oHnmXX;{^Bo$lA6j;H8B6A*`9B)W&)8=feGE-dW<*^ykt=XR>Okmehn-C}& zs7t2kK4PP#B5^iNT(d~3uo9)NT8Uu2*?_!^mCNU9#KEYn2KB zrY|L|U;^(Gdp5W>i(0JQDBYiONKzC0A#?e8by|^!V zRd7PczkM#%PTj%4YF(M0X&1vx(!O*ajsv5jBF>4!kr94QLl>!V_e|-;_zXC|YyHTqQRLP4l`O`Cx)>U`r;qfc?_X{X0DtqtKW&FpM^pX!-qO#oJ`z?if#b1! zxOQ>$<=VgEnd`r~r)})QPps_gOwCxTNxq2@4ZS6-U;^(S8}AN?r;k^Zh`}nqxLE`2 z!cVMh9`0ut{bObaGT&57ayiTjkWP1lmtx-3VEQ>rOtY8AS0-J#x z6-xD{xl3!#MR5dn?KWHt8?Fx}`R(Vh7&{8X*n1ow>9)3;gcVHSZ?o7OnZZIjWp9%7 zIXR3YuxsD6B>261AW0BRS&SPE(NyTsGs3>>AvnZ=~}NKNZ+GD zoJZ!Bx0o^uQXaP@X*Vt9+p0p~$mZ@OCc~2L$FsXWwBzfY(x4~B5>_yA({eU6tLjX~ zXvH(a+0c*nuqu+)9o#J8FX!+VbvU+6Hbc*cUVdL9B}VSywh9w4Oh#6|q+`ZdS+<*oC){jr11-{d(%1^!{Fh)IWCubQannJ7sFWv=Zg{e6 z$fPl#Yy2G=rJgLt`*;hQ(*A{{;jgN|E=;>fX0XWc3aEUqV8)}pWQ8m*`()jkO9D!Y_f2^Tr!8uqkc|0Rx4T5Op@f>M+mn;dN zajjcLLt|1m(h#(<93Ln49sS23>Y&J#aw<}|BZ!HB!Vp+CQ=NQI8O-)$vT7jxXO|~A zG%n=`?Bb7L{`X)i8s|y_w?=cv0~5)o0^!W|zn~)xVf*o8P9R-aw?PU>N#_Xc!eNx-F4FLx-5>sF8+JYgDjKd>I@C3 zyj>3w&ywSLaehX)y-=`BP_5ISeg66xk9dyc>^ ze2%f&2}{GN@2pU1;Cf>TE10lZ7XU9$J%!J6lr?MiRff`56JjL&C`XRKE__z9_fb+9 zUDwM`Ix>5@gcVHWnt8+RzbqHi?+S}?EMPuenw~0sgA|UyF8*xa_|%*pZBZmyzv-@c zx`D#BdB0}HPlU(!0l?R!1r*iD#p{Hdk#uj zwapb+!NiTV6nchNLZGiLi!q>t(%yH@N`nTq<_PS<{V~gk|7}9g4X&2V=XT)wT}(LX zn!&k@(_ok0jm5b0br^N7eJMTP*o`BwYt6o4a5nt{v=&`hFREEPhPuy7lggI%Q0RFO zh$K6qG+`sxx(=3O;El_Ec$lc{ueANg(D>qYlI)qL0xP(6@o{3K@Q34R+o##msV(g| z0=rhGSVP$NLvZxk8WzLjEYK~VlBN0W`tn=#+Z@ttc7uU;Hn)Xr*5IZo9pbrEdUtz( z0&htqA|6DVfRAkkp_R)<_PTK&l2}H`gGH$%~EjiPz6>n5qoVE zytdiPGFih}jOFhJ)4sF!NwjV_M_|{FUV0E=SioV1 zg^B_SXOnVZfBt?(j9TeH2M_lY-`Qy?u!4z$&8*?cgB;!ybO-d1sH zu?@IZt^m7u6E}d|E!V%aN z+IBLeR$d0jJJBpg;}|D8PW`ClzWuF)6-?lf6B}R2r_u1;2c-}1?{WlojodH=&gb2M zl=GCuFvxbKx&f!8=4Q_%tY89<=UA?@i4&D~x*)x{eUBrst9g|Jq}F_fO_NQ^+1uBS z)^z{EXHvl4HxgDb!H-3^dRoy1%w4_g9Yum|NJu)$~Gm+I}x< ztHMqb>GtS2>Bd%dj=(P5kFj(2s6DNF;weQJci{RfOx((|1Q)~YFnixF7GwWi8=9T$ zC4~#!I0CzH@5-*)cJ8z!ua}hFw^72|KFnYulw8^XEuP#Ea6C53P? z!+{)uUAUiT*N3e@Cl0ce2LBtRzzQZFd6~hSoC2sQUCUx@>}pICWN}i*Z9_Q%yYQWX zJ>%R8psBW#q)vKel3$byxQ#7^*yYa!+}m|}>H@m2<*>0)Ifk1)$(O#{v`BhhbWXww zCUDQkvZGJXIc1E11ANAIk$c;zh4L+Aa0C zc#I>kYuwlAkTd-Q6#1pGu}^HnH2PrQNhw;oAYla)xaVVELAXt!uU1`=TJ*TW5!kio z-DFr;q)NK{8zpDYwNGqmOZ|tEdiz=lE12N>#Ao3S)MieN^mzP3j=(Pc4bEU}-J0C^ z62W4;^;keXzFZcAdKF7=PPl-6(oPud(jX+UnogUy=E1Ab7GV2xDoCRWVW3?tYu&`L z^Qq)sE?Q4IB4Gs+#?PH$=b_Dzb@mG*Qf>xNwLR)mR>$)kfn6g@93lG7K6pLlEF*MS zHHWdTs?y-U)e=@PVV~s$kw><|74aS;MqKx%Ua3aX((UZ7hJFjX@Lht{7Kxk3G69rAg1%vdSG_+q z)4vL>cGhqNb_sVJpxK*DC>?N%5to1YQ8k`w*x#oLSsn&w5H zR_ufL#XmR#yYM)Oy+5DqPQU$`29k%W0xNjrgk!TWs_Hyw#KCXEpg}4MtYAVu&K~+3 ztb~*Qs@Yc6cJ-y%PuQ$k!5eO?unV^#%cnM+O~-gSLv_|uuB|Zft=S_XU>82J>{%@?oSw;^M_%*;>4@bVDBdvvI-G0=xOP`Pt69{mVJZYP z>j>;@j|-(km-`UY74s#mU;xb-;@Kv-V%?+mRTMimiH2|OaY<5rAH-? z==nK_e!HD5ZgV-s5!i*V6}DF6;XqpCyimMhc0s}lCaw*g0%-|r;o=eH*?zszl?LB> zOYH6~k=&nn!@n9cIJ|$m@O{Qq_+(%Yo`=(f$u}oM%*4qstt^`nt#qeQpSGXLFTb4< zRxp8Uy0ItW6en6Su8zdaE#nC6+W2HVSeyGo?_Vof3%(<8 zIf0g3ze>*9e&Pu1S{4Q{ZFB_mD_Y88960GqpM__T50^wKew{OHRSSaMmAAO6b#-+U zLHl(C_@|y>gw9qUY8|kgq*8VtL<+8RhwILb%i6a3)diI>mp~H(Qb=}(R)LUBwPWpagGi22^tUcU+n&$YKXm6 z$Iwxm2GWm?`Vy{_h>2}$UE!enNci66C>xjD7;jC_Mf9b?Z(DN&cHw%BY^!P((&9~d zWMXlD$>g0M+_18QZO`h2@U^qxL%ALMisO?IrW*`PO-6yHeJj?Ntp6QGb$+*&*4@mK z7I@8s76C*ez#~ppBfd{4{j!wRDuI5Qt!2}+0vK*G^g>-tHtF&ue7Dr$g zo?B$kYWczRf^L+wz5vNSn!F2{*@U}ww zR48%;cHwtZEQh7}bZXz?jASzYoP-rj@MF=njczpU>TxNQEvAeK?Bd^fIe(6z$C4w& zXhjw`dL3Op6WYAp40UI^!q3(oFez~jY)Mz%&xI3VwEdb;v7sc7Bd`nKgJrU5YZlRC zjveG@Q!=@`GbWb2n+ftEnegPcvUWoCoe1h!n$Bj(R&WG%;X5^pv2zh^+|vtM$kQdP zV4_NN2l?J~Nd3@`#c-|;qY<`+LPps}j=(N_r)Cuwmxa>AtCd3Xlp@m?dEzVkjNU-&Rc;*RruPf&MQ1?}^D|Iaap z<}uW@U5KE)#$Cck?I$L#d&A$=sgO8R`DNI=kZ4+H`&4+5?#C0zg^vwu-HS2wtX&Go zw^>P8`H6@>17^V>ckYI`~RH^lk{0u!4#4 z!)HRLqGU*@Q&#eHI~`72jG7CM+BqD7UHI6r8Lyl$y6AQcoC(+?zgCY$;4#{DU3ygwu0r z+Z%!~YjZV6U>ARuJgbbNJBIs_A=9^rho;Sk(p84gp?N>Rqy7VrgWz@oz)CCSG0(1! zq^CR2B1fNp6|sT|`~<+}$XuhT&N3(B^Zf!xU{}VnxiGcD7AoSD$2@6j6dg0vj?C!Z zQNju)_-BKXJJB?1zZrS7>8FSZ>@xP70|Uu)@R0_y7*<}v^oC+TcvLDR{3P_W-*o7` zHVqsze{q$LWinm;g|uDJO<1B)$UO;TVxHs%LQxX*KB^o6)WwC-&5q5_ygaKjTOPK$)LddjDwj7w3p#h+HBi{5ySz^=xY375nPWhJG^_LEo9?pf)@Jg6!Pk>qr53B8=5%@OIK5x2IHySiuC} zy807hsKymdGI^PngbD1z`^QGF#Zfflmp++vaR|2`n7~Jqjr6~TQz>1aB!5}R5!i+2 z9AvWe+)(;WBxLp5RIZ{mCh+qoTmO9Ie5!wX1Q{aj2(Z-LyN}1&BNv_#-D?+ z^p>ju>3=Pfy(#pctQ>Klfiykixu z)drCd*?Am+UAUqP%jN78N4FR2k@;>WTwNSY;8th-6}!$I{rixX*^wN9U3}#hpB-^D z@9+TPcK5Y_6-?mc#B!Zm#MAIEU0CAeXs&V#cJVb*o}0zfJ}zm+4HmU6oOik@4fGqV+9lZF@HUoReNiE4aB+F0u$K9SJJUD zW0G|u?X`cu`OUBm9D!Z9js~mi%&M_>e4&u<(tajl1rw`g_<)hac5rP}ju}RrN}!Ls zXo}M}m2m`i;ffXPeN9GR;znv5HGFmKFgV{JVFeTX2mtJTsN*`8rXgSY6KHb6F1L1d`sqj3cn?b($+gbqNG1PI=5DS>^Apt9{6!{hKAMU;@7pV6z{A z^XcroctXlEI0Cx@#(Kk>!_IKpSNV(sY{u(}OA;~3nkr!h6Zlz#Ws-jkqYH1QkOiR4 z5!h8yG8bl+0yIlgXV=GMqewb9ZxK1&_MC_nOyH3d`(|`N6s=1RC(q47IRd*B&liG8 zr@`<=RQ4rT>Z9rPn;vBNo$_+5U;>W@SQe{$40YCWCJT<<5-@>XGd@Lt?$fp~{FE+> zv1xEDZKS5;Nd0QS3MO!kJ(=v*@K`!-{xG7eIL8s#h3gTrReOfSQtPc6B>#vySE&#a zd=17ETUx+C1M2={T7G8L#>`r6Qaq8k>3~5GdfF1-JwTvOkh{lfJI;@b%3g&%2|Va zwP;#t8%%~~?iH|tiLhN!&@H4H^zv2SqcnF!)0p6yL^v=GFo9jIyko&)`bXiYN*_k# z?vJ4mY)-C>ItEz51g?z9X6`=6(Dy+)xUuG zv+HJdog3LsqnaMYq_Wpz2`iYuZ%<^hDPB|Px(j8bWA9pyz^)qxHZaRE5PE_#17hQ6 zXFBc8DRTMYWeF>o!0&Weo=l1}oi)6gOr3s;Be2VUm=macW0@pL$~wY7L)@uRcr_Ux zwpGFkCh%J)Hd-3$MYVrkC)Q`uIRd+GwefUSH9;w;JuL6MeiepD_3v?cI~f@fNqKHfm~E(C$t?KPN!X4Pu6Rc$+3b7 zf2&yNH~x>X^11ST?aGn}8uDNzxqD}n1tzfT?*4da{r#dx73)d88dHPRc>0Z@GFf+Cz!3rjDePK3J^evVyY;_P8 ze(TK<*u~c>Ht}6RqoyAs^He>=*Bj=+kBI(o{?<_;pgt00)6@W3T@WgMM8oM8u z&RRDyG>lHQ&nJ5#JIb+wiPk?7!P(@YVASm)Bb)|B(C}F~BX|Xu!0F(g_>0a>JUeRezYgsjBauScH!FC?1|-B99=%93=(>) za8xB@6X*Q(6foTB=MhyqPP{C#St1sfI%r!VPz=1y1*-mm;_9s>_f%{{Ym+@-?onUf+xZL6i?BeqPuG=|K-()!n zw*Dqz1rxYGW?2?J9O&_$7s;&;uQ&p`aMprM)<2J}9+`ZL*mb_ZWhY<)_s49GEOsh& z$$vuBZXV(Y?84a>tfHKw8x4~^ChxOzxGW1y;Qp9pQ~jJtmzz8$_unnz2<*Z+A?(gM zYc{>_TuriH7<1Von85updn)P@Ku=X)Bn4aBa|CwbtC_ubE}BPO9vvskM;zv^b4=jg zRVJ%AwtyZQQcC)(E#wI7!q+^@dbt@!=Um)K(o{p`SiuDDkJ&t&A6uK_!YVS)p(WSj zU>CmTS;m%m6!mV1AOYXZ0V|lm{V}Vg;}%WFWO@=+DVZa%3t#i>S&dcAR-+@xP^;5` z6-?m%m}SoI}r)3fzCXUEZ&rCY#i zXg7|)E?j4yy>ahhM>qO^A-!eiB%FVN^L=)5xgRU~JJRLte-f|qy<8>-CU8a)dmh~3 zL|fGUCAqiPaRheZOcge!{^UaM+I=HKmc?-yDVX4|kK9ALFpaofK_))V z7O{c}e1BwDZS;Kl`_*x>VCis5)shWQnJjfC=mxsj?XECY%;hRx9(6XN-!XX$u#T4V^3iE11CdNA_lPSv2io z=0SSrhjIjVJ$;o5`8g|v=)aXL#*me<^zLCDa>U>uUSw3DMdX`$)NwG}4%6{LVoi-W?6;3X`^D8nfFL?@Csd+KupcHwh@ z<;k$`Aj`(BBh#(s3RuBJ#MuN$8}w2z8WqK2yxkm1XM1la)#+=>Fo9k83}v9F5Vyyd#YpNCL@hJUk@x1l9D!Z<+GJmhSo_gM-=31)_sY3z z5EE0f{6XiDHuQ>eWHBZ#@uBs%UXy9-8#w~IaF4;V!p^zUZDUpFHv?U+_rXN$)9LWt zK!Ds@3l<~qrZXKG+MK$HjvRqqcx7T%m$TZIh8nh~rwvoM+(AsVU|)t^)Sm)F`wV3< zTHhW=yK8lzabq@e1a{#(LY5WA*5G+<7!Dtr%enPA@j6I&#UQqla=QfDb!R=?%FpN4 z62b&tB}yjy{3edNtM(@ThxTv;cAZ+A0atcU5mE#5Szg~4mIn}g)RT^d+%4J^X)g_^a>b;Adb38T6h1*Cl9B@3)z0mr;^EHta1vZI%ZeM2agHmSiuBd2aVM)X*P#iEqp*ahp&-i z0=xV-E`t1)&0u+6Jc}V}dC~EIev#K*=gF~x3A|<;%l_1Kr^RiW(-}+qi>hA_I*do%I4XKaBLOyJ|h`ou9IbeH8`GPs3FIVP}cH(O~l zd*fZ<-lcvl#tW4odZO$CQSWd}julMcZt?vAU4v0ew{?A%@UQ4k_+6ng3X z6bNcV$qgu;8^nlpBZ`Hjj;4wuw+s~<--s3k)mK2QG?!OQtF%zJJ_kPa z&E=m4sBSBXy9|=nNJea#n=fQu8=;ug%v`Z>#u*E`v=Wx~+*!V9!|SbGc2~hbzxr}a zvv~$GSh)PzNHMjuu>vcYSmLCzt!UpRXm@QGi%~Odu<$Y4L~%WEBu8Kuzg5R=?!eob z`ii^JW{Rx0D}`wWr{KxG_2rT2RIsGyVb{+V^8B_dgdQC)fX?23yrt6n{R47WRuR&=d0T+5*EfRUg*LV~*WJp{h4!IOi%sl%i< zQXg$?1y(SzA!is2imZf#18!Te+6gtCX>oajq`zK=Be3gO%m6sG|1>DVBN!1mvkNsj z{Z=CV^b}aZ#D&(nQ0;ykw4e79*nIoi_H@L+caoio0Y_k0=+gmESz8Vd6KYwEcd8zA zBOH)yGAkuq!3gJ2&o*}f&*trkllunNy0@RZP@DT@QuX)q5>_yQv$18e06$0S?{{8$ zw)zoAV3&5%csL!}hU7mu$YPYdo~giyg_$`wps}sj33iXt89+bl{E{|r z)>2>v6Zk4%vubTR&|gMsifax1IRd-z)y&qlJk^FqZ)>R-dXc|sF@diFHUfAqqk^K1 zqMs$-Ghi3)mDn0?Gh5KesVWLG(17cGFu`9RE9c1QlkF-B`;~kThh4a@WaHf>F=Ue0 zV8st(Qw8o{aldQv_oa|pbQ+pB4rNF1-=5WE$>BbV0u>7dRxt6a{U71EYb7jMlEsck zZs-P5^`wg;EWnZ{kZb3xzrvKX6YzJ?2zH(4zu8CZ@3dAFZL?Nj1^=#TNNf06a|9fc zw=tqhx13yG^<6q@?7$J&lAtzRN+2eRppO{koih#`oFm{?W`ajZA3uOA0faroaj&KH1(CCgqpHs#kMZ zjIaIu$QVm?g-#Dgj=-*^GKFBYP7Yzs=ak80_m;boaWB;r2Nq0LUZmTeHsK;wz zS{D&o4|&b%={sypBR_mJ6mMtQa|CwbHk8RO=B*>0_BL1K_)p|o7ZY1<$zcE1Qs_Tu zA8V@-|M$R08UAU!LhH3O3^3(dUWEDJJffY;)x~>Ati}yomn`{PgfEvrGh)fkE9BaWVrh-r4251)TX>$k6OJWo3E1W0puxT@ zF9fHIHUfJmJhy_Jd~j0wHqljq6-?lG?0!zG$S3y;QYx9o5!l6_yB+@?Cuc$*NaxC@ zDzJhH+zPDsnR1w%`SeLD>gmW4*oCh&RzbiqpXlywsnEY>$6ZmFz(EK&*mqt#BZ-9c;cP3&K}@sGGVK^tLAo-EI#DqaQorp2q@q1T_}+qx*f6C6yzB z0xOutos%Pny1Hxb(pE z9apmke_xF&y0H0OcRw2a_c5#KRLj+R!36%&ip?!m&Z3JZofoIUD~`Y}T=#|Lc=^nx z!}^RAed$vPE12NFu6YsTMX#%^5$Ts79D!Z9?hDHtxWsBMdk2eJ-x?*XU}7X&Z|`_? zF8s*2$XfSW&U6alN5qRKTPrYuUAXQG%REb*MuYAKh^2a)CdJuFoF9RR_p$p4pp36E9q#A z_IRd+OJst>JEe?U#Y-P_d zcdjN~-F&a)QY#R2+q0Ctk6hAzlV>tr5^!3!B_^k+q`_);DH+dj9 zy!M=g6-?kt4{T2VkvCm!=|Lh>?r{WmeS2vS?_v|d?PnE>F}v2CuDt3_!n=Hsu!0G` z21LMYR~kKukbWRjU;?{(SB!(1pHso@j^ERDx=AM~*=DM!IL}fjJ5vvm+V8&KPbZ?kQn{OGA%OUz4fn9yH0Selr z!J~TR3GclVj1 zk_|1Id5j2<+0!Fwsc@=Ye+es?u#L6_k0m*`I4l1a@h>=m%$> z<%8X%6h?fced*Ky6Gi7?0=t{z|0$Tb7HtD5cI%;6|CNk*eycluc;lSHJ$nR4U{_O{ zUa)X`5mX%wW5kpc3))F-i1;^kgtY%)4>)9A3U{jf1zh2gCtP%Fs9vWwV!zoa}A-kyfsR0~;UHJ2{og(#tv?9x0@hyB9_c<_ua~;^}YtRr{er#Wj(Wb#1 zfnE4_V&hd?pu5Lk6QWl3;eHQH;Oq#tGhsi99$K0XcDt-N0=sa3W3{O+I8%q)TjAj& zR>KtaL`>l92$t{sbTXYiyb0vvI&cJb;pc`$l8<(yt{Sb#uF-9{=K~WsJA!3xjrXJ- zY%NK@gMUT*e_=Lqb=;}|>D zpXyKdwss*&H;!}T6((?Y1iQ;LD}d(egps1C9UOsOcs!QLq({ND>%Mqme>{sDcQJvp zBV@7~^@ViV$ZVqbHjE>%3(qU;%`1H|P5hWidLOal<_}EZ>rEm^GMiP zT>&eYz}XS()bdLd9eU4$sNFOHOkfv|z-KplK8U85rrHzhE!zMqnBem!p8k!dJgzx@nxZdu7pk3g|;*h=GMbp8}pTJSF-Iwfc`#JE=%!j=&Mvh1YhhD%bK4WN?9sRBdk0t>G}i??67zSE0qJZ^bxW zIY(d@UZcunUG3EAqp){kVZ<*-Cz|~I zx;W+fKyFQq34Bh$GLZtz>5Kix#k~FfI0CzHon%&pRgb#E?ncA#RyNbrH^J_62~}o;i`XQ0-qtVCo0O0R%z9UvQh(%z%E>? zn(cC01GT$#OgyXJo~ucY30$R{RmSV;NS7Lxi8kii9D!Z9o-JGNjvYsxSCom}Lo~R$ zwV1%w#@X4#dKXp&DqZyOQsD^f;_D~=95#*m?9C9P{C{wJ8JNJeky)nq9xr;qHBbzh z{Ej2A3)gOBC%hMDQSBEY;#RlkTvbO*;Oe9-D}IU}o#8e@Jhl40K2 zH?R|p9Zqu9DKUZTRI#1yoDkY^SvzrLpS>J`U2jn>O%|6ibO|lL^jk4g;HwT{0$0*v zzXz*qG)rx-B3v_>t5bwsxcUvN{B>>!G0;$v%ICUEnLEx1?j3hSn{F}k{yDpZ*b{pp zd`x?}v)>LOxc&%?D?ELKo!u=oB)98yq|tgV5>_zLJRw*3Ak>1k@h7(5Zv31a{$bb(U)xeH-5Xvy>(rci>LkF)`$tgAkc^65=hl)v#E#kNZIPRd4B!kH8Vw zg-_pEB>BH)`SbX;(yT3RQvY>pOC7sbL+X$<_MT66l&)iM*ju**9vg0URepQ^ez=}h z$ad)42+eY~jQKXb4daU8UN6P7+oyq1Jf0blP?a9(iOl;=!dXq1#a_N#pG(j=(M)OTnsg z?dl}#ztdAn3LL>jSzw~H@OtUf2%Wo}wE+q(*uUeFc<)f4 zgcVHSw%N^cb&jB;SuM`%5XuqQwJ~*?FuP?7G&JO}HX`TEhd{&q;)r>RB&=X!$K|QQ zuT2#Y5){LTA7vY0ynl%}!E*^mV3+BRcwxYnGWcV*ju9#S*26gsU1?FcD=R$UC^*#A zK;;6%8r6~&!n>_|!Qu5``(c-y1(zEKAj78M4(|Z7phS6d(gxw}l^vizUKw-OUel7S@i-@*q6;LfV4`c~K4GA+4aU@O zV#Jw(D%f1mUaF09;XZjpPNZO$cLXME^Erk;6FXzseH-R(RgSuy)QR(f;=Wj=-*OzcvcD zrf*|617)&LK6;!1>AYVO9YO*ntYCuwuFmClC!fo9i1A_wM_|`_mjlA?b7kyb zr%aJl7$ac?6Y6bt2^RmYgVp1&Fygz9H8BY~s(6>n6WBHP^=2WdsR(BKC>Zf>{ug12 zf2r92))FcGv9@*_}#R8;@%i!Hv2M@om*I2`iYu&p(TfK2QwBQHw?I zpAj5^U9krfgtU$&VDq_RczU?Ou`B#_>tj$+ZXV1_DZphQ#eOpm-@a< zLZ5&VxcYK0YvXU2tK4Do7BTSB5-BKTW~t4)a;UbAlp6+2mtXj>71m!0k;`peNhXqUtE4YOu`B#uD6{bAGx^{vLZ7WQB=BE?vWfOrmtf+tfK!5yUsY+ zmBz}8;edM{BbMj17PhP*;^%}I2`iW=igcG(*=~ZCo*Nl4Fd$d1cf?%md~-QRVArdJ z!KM2aZ-$$f@)>c!DpwwA_D{j?a+0uuiBEmHmyXsgf{1>~HV${}BCK1wU-4VEQo;%* zUK@GHSA5tN6`B{7k;QN*gb|B_7F=LVMls{E_$C+Q2v+MOV83`3-gVfRZa z@^Ya~LYiFvho`(lyIgiRM~eKG`=yeNt8(Cb^=d|Jj@}^5*0@f7mj_5#!9<3ImwaNY z94H7|#fbZ5X2SfP|B>fy=5Yjeg&Bw?+AG(9=FV_Nyz{6KUbi%p9ts}`E11x6@{&K5 zt$~`X#f(_i(noNr{X6$bTC zr!i`t9D!Z@U$wRCRl#`KP&ztnkmT4Zw)`r=zt3t<3{i#JydkHI;uyHRbxfYQHXYM*N;$h#h5ZKO|Zg3vO5!i)46N@P_ zJ}$IRHKRYeI!Rc;g!S2qk|&R{;P5=+30-+gnS_Cqpjqx}$Lm>7AL4A%>ku!0HP^I3IDqYfYx?;_dTLpcJw?riXs8x75a zN1v409Lbkbgy>&oq-XRJ2`iYu&nDYvkpGrPKFlFw<}Tw1>@rZiE%9qv3nAIcnX@P_ zKzNhG?%~nUl3pH&E6LcI0sCHR$)%%S^0n(TKr>rc-f3rGNyDHFsQdhst-`OXMhY)a z2GF+o*Tfpxq!R1H>2SoT(7w!PcFCV_>Ck20S$o-4FS+6Gbg)W%!icRqBZR04e)MtT zYZ1G+|Cb{kU1=1|kItlt;VKgTzc7LSLUtxx8wUE_XVFn@WgLNB>c{HkUD??}WWF+v z%%ocZ1Xa$U-zwTjSiwYARlQtAGXq9v>9Fsr^NKt0f<;02{rDkb0=s4uSP3?3(_r35 zWgEMHuM#R)^%mpJNn$s*0VNmar-Np?h5eDgBTJ^Ir9=IPDEl!_yyVZ~(?M_7Mn+ux zn2Uay~t zeXcEezEZ+73!ZWKvAytfe<5^jbereBo=(JZktHr4~3yt0UU|c>= zU>BZ=SiQdS^}@ea4G`|Y&rz5-Kkb3Mw{t!OyB4xG+SPStaq?ry(HGI&9EDwdk3Nw5 z4qgjkCCcaH!q{L)n4Um-JPenxf{6j&ErpYMz*O@BiRc0aTh0@$6JJBpf#)RcfUkrVOsviJ z6do?ig0}}#SR21p?!cTopU8#+ACADTAV(`fw|zFa*(gUi+p*06P5;QQjb0K~FmbBV zQ_$X+2_Dr-!r;Pl$nn*n3j$_v1a`%GS_#JevfyRmLPpf+tB@r_b?J$tE)rHS(dM|P z(ECgVw2WNDh=1Pdge>b!T`ZhA0=rh;@DzIdNQZN;JsHvcSfX%#{c@U>Yc1j)j-M62 zw~y6TgMvqqH2Hjph!srmPn5hd0qhbZ>7%S*j=-+RSL)?G_ou;P4{P>B-3}^;KVQSB z>`j)46-+EUQ!h9Dmj;!ml~3*bjtwAfiJ)n)fFrQWXOoq%;eIOouIF3^F$KoI+{B0hZ`??W5JngM^5h8Y>JXG7T(d}qeu_biu)MlTDAry| zujiGBcvQnP1ODD*vJ;*D3PTCM1h{^3EqW!S7zmao0Cyjj*flK=Ez6p!sVIan<6_o^PtX?O=-WMt2kbox6WE1kAC`j^R4)uxrHWpqD5xxPhc0GeONsJ`xfEYc^x=^Y^8)1OuTz?U%t(M9sEpE zevYDc8bAi0g#Ql2as+na*+(X8ndt(a$IOU9@^T3)n5aBpDZIM97WSws=h{>9L~ssV zO0tY2IRd-zOvI{xUq1vF`xlbr=S#Rb3KJbCdkU9@HQ@L``6m4Q;5|_BR}h7BFh^h) zp0C(V$|k{Zv-L+suRANGXZ%XpJyY~Zo%wPJ_gB1o zihHO`HtSYblId2Ucs6J`*LN|2_hH%SV_-oX``)N+*~1gqh5Iqv%TTi>SI%`6+{%|r zSi!`kk0nB4+X84|WxLpKzFwEO?5>uFN37ro?85z+RW}}|N<1ubg~EF)B&=Yf|D7b^ zdY5(Zq2poJ#-ml&q4?>*T8Hvjj=(P5k6AsL7a}Y_uO_5Fjg_#1i91#9Ld~IdublTq=CqoC~|VN{krj(Vu*UKd{s;TEYq@ z>NR!?msjV(#lM#r(Z9M4IsLH|qFycM+Q6S2(`+reu_Fmty$UMMESIo?3H;lz+n`v* zx^ovRAv-pPBe0AAtI{g_lbn#=VD~dd!U`sEA7izniyVl>{A@U|H<}}`D@mh9INFd4 zx;Z!5C)b-aj@+mo2l~~~5>_yQPc~RgQLzu1ubvgIt;mB2?PrW|42UC&{BGoGTo^}SSN5)3!ri!R@LKhP5v~eP z^6OAB+4e73(ipNwkSAuty!Q(Eg;BLanpPIXuR1ATxoVH_>%UC660Mv$f4`YeUIy+Z z*Ng%rtY9L4ZLJ^=&tNmGa=da+3ntCE=Sj(5Uyi`8$G2;RrZ;IY;`}Z~EEq+}Ar`a! zb>3nLk81cY_Ciu_s$H9vf{(MZ_ZqMcj>{@nei(vdO9X>ozuBqK?L&@7iEyQq+yMz@? z_-QGGzy7I^-%+`GRS)qa^>#99)X9w_u&em)7U477_t~*kxtDQrbSmkV6-9;>E|hR@ z_)~gYnC6=SH;>(x36IElB~$NbDI~I0&FCa$MsCLQD)^(SO|;p}i4{!ntBgGd4#EDDW5`oWHeR9s z3%f@D^$?oc=Yr8`<@?7@`VpRuNhHr_FO#r>3B0Odr}~@Q65G68#G+#NDRA1;oo7KllSi!`-2`R#ftLgCMi}E~5(SHQ7U)q*V2N#aO zu8$-|$Slf$E-q<|7}#bC*=%f0pKlbTsqQJlD2;R|CX3}xt;&RXEh#WFK1{xF4r^m< z8q7$T$%u*j=90@fy=k?_5D6=oIH^@8+#Hz#>W;G+k@L`$FnAAqh?IySClMahIs2;=n$@Sm8uXE`>npL;`1Tr(z^>sp>*e|dY2c(4&f54P+Ya-(tf23g%S5bT z0`Io5oVX3|Afj>wZE3$ofeGviWV>n&wQLk^U&Pv&Yo<;XUW=i6-Tx@Cf(g9a#@29+ zJ%~X=3_U$AizBe>VY8<&G&2PjPddZe7}aSwIr1)wCS`w9U!q5dt zP!AngzgqTSHJN+MgKqfyR>TS>0vDwSF)k_a!A=<=r0%kas7!UCN2=8&Okmfu;1pr& zn-u8Prw=2vPE8<}ua2iMw1b2dOccEL6pkgPfz~q{Mttfyj0E=@NjsKz;|S~;|IAYu zJ3Jju_EMgVmJL`!8n=(2?_5nK{N%*yl?lSSWEj>sR=z>MOmO_31jDEHV?;`G0*Ur^ zpt`4xB&=YfZbY>(GCB#WW5+RK^06%PNOLURJw=ZruxsWFh46e|0Abqb4q&oGzC9Gg#-=J#2>q;_^BIWt{pQ;2BzjheCx5b(x zunYf%>@4+L1{rpBIQ@`hAz=j*nr;eVl~W?vj8n$--J6h4R<<2Y8;^D12<+lN`HE6;Vqi&6 z-?ZZh?80*w`#si15|=7-T0IN6Sq&3-W?=7Xt3!x>Oc#1L-hm^q3(s&enc7%S@>R`@ z7V3U3>bh#f2lV3&(4)Og)u{u%pqKCchuY z#bscEKf9Z8;{rT;XGK$O95@2IaNLPZHl(fhSohhzacaz-G?3SCe7)*ca?v z?aJ#&V)17d)nEHq#0npf)E^*3g=%}Gos`8eB!XInNZtl5>_xVsQiv_ z{9Q5_!vRJZ|HviJD_YT4iIX`3yV|H;6zcyb!}b-*_d%bz8%TnW7Jcb3PQnT%D(mkE z{Z=QzBSYn0U(v!MV$scjPP;yWBd{x8^{(*UIuU;5DI*{X9_JCy4ZFqa2Y%95+APEl zsDRB~-^;DMo(RYCE1=)OD{@VTN5VY29kA0-`8gV2t|Cq9wW6cJJP9k97?FKWxVLf# zTq;n;4(7^3NO|vT;yRei5!i*ZRoHWWY&^Nz^`Ur{#b03s6J;az2JXt6<{7tDewndkSP-U&x4S!9D5FkBi70yZ@U% z_`d{po%geWtJ;aM;e7xjPPuE+Q%8r3YHeL5zd}PeGP)GnT(%cxuQGuzI>pd#_jqCY zYg1_TbR#6*oz4i4nD%t{1$8m@<75ddmhqWzC&DqQ|d;0Ww` zL#)7hK^~;#1~a0ar8!lME~?#LHCDn3CU(nufqSc5FqbW7#L`*aDRCbHU5NunV3$sz z4FtZd>W?UX+*uzj3clM-yXx(?f*H_ zOVvTdu5~BwUKvb`IWz*&yRCwEw#r%-^M;S7HD{8DojZRM4R+x>W>`hJY8P7XmO}RH zx00}eiNqo&I9m__*9R$YD=^ibPRG5^C*`{QEo0b)?+;_o`Fc-U)uV_syuT}A1rzFO zQ{nF;U-%QCU~L@uI+HGWwUczQJI)c;h9!AHrhv}l}Ay zm>s*fZ@tG*GGFr?U_g0?#Wf!gP}j-8%9c z*trQDfnDc@^#Rq!RLJyJ&QWPP1L%$IHiR?`lCXjae#Y_h970#G@gs8rdUFJJ^;tI% z?yiZ4Jy(?T$E9`;$m2bt_+KZ!;$o?-0sP%k2^T|51zhcsMd_6`khvFkh{7^guBsy@ zoZLG>e&|-XJyuzVK3Dq%G4H-b+*{$s5!i)mP_lTqm@mY*Q--*FiW^s*5)*j6!lDfe znn?FH5u#_RJ4aww$V+`#=~E2z9t>fB)%+tW^uuyTakusi2`iYu{f+Igjb32NO zgLwkG%x4=znBfK(XfTPjaY)gQ*0npK=w9b4VFeSohq80$(2jJ~>89GP3#V`dcI|&` z4kJ(HLQVY~)`pK@Lfsec7g`^2mau{e+(X&PXderD#l9K}?vLgO>~fgd1L{ID;7Fsg zx91u4qVpbWk|Ui!!U`sE4`om7!@jh~b4OA>cnC*e*PE+-A-@~jNwtY#ZS34Lh`!BS zLOy@(Enx){eBW)|YZx8-aV?3vYrzrNmELzS)L&Z(!{u?Tjmzink=+-Ti!ZEZOCc=6 zSnb|ch}F;#oQ~?il-yF7V9;GiJg5a%ZWcrO>~4(cG^T+(n=)Q>S>P>U1rzwagq<7s zd?I7M8;Kp;&gKa0dgV?V?MfoSY=AV1j?g>1u0E?dMG*vl~Wm1a_@#ncJ9v+*cDpW8~iq}f}EMkH!mBF8|0sN zH?ddCJSp;v3|4rTKufHS@Fz(f?1yZI`E5*uw-+?PZ}mn{J7>X&@3)?jUa_|o^9TA# zSiywr)ON6Z%z7BRygwsGz5PJOWSA(9M9$?1>@wM`1G!uC*lptj8PV&+A2Rw!rVumH zTfzz^4j6TWWH&Z4L=Z-7SfNHAU)u?KzdSesyJpQdfJxV~AWT(BeEigwrq{G1lY(3& ztYBivbz^uNngQo-IWgkhK0T^AZZdg(bOJ|US50RV&}o|r9}kRX#9LQGT6Hmw9Oyq< z!U`rXFYN|%*{xH*jAL;rn_jJRYPO&t2&6$c%e z&FwQ7+tmv?4ZEPYOTquQUvl|Q7AYNaNpz^6&Fy|*LPPC~@V>bchPYj4dl`m4h2-zK zL*lQV{C){`;k_Dm50?5KGP=A{{A)gk+r_~I9+g-YwwHqJdYdce51-2s*mcseHJtoY z3W;Yruur}}tB#agt`vv$nj>Ka6L=hBxiZ!dNu;@h=>LN!uxn#0ZMY&Uf{Y`|o0^6Y zc0K=P@1a<`-?*Lu?$??N^iAa`h=1V55!iJyqBERiIX`;7&a92q(1GST)xqWXDH2vNfyXhH zYq`LX+Rf=jmTEe41a_I2o5R-DX)yPsa&KvfX;<1W+KV(C8Yy7~6L=hBcR^TK&T@U*4O9{z2-(SKCCioGqVUG>Hl6Q=J4(ZMj*!A4J zFN{?zhvoLlHcV9|viaY5aqLfj>2=0eVbSs}aM4snz~ke(o~>Z(einf}v=bvbOuI@} zRCN+h5Pu0Pn80Ht%S&zlfb=-AUD1B~e2&1bp_-boqoDv&Wj$CM&iCGs^rQ8)HCuco ztY89z_R1rvCzWRc4w zHRyoB-AOz5=^TMwlgm1RZ*V#sQkSzfR2+3^?{Y7)X!Aq~E11AzC0m8h>Oc?MW|CId z#&867^&M{td6yF5KnLa6UJ_?SH8+(Ld59ok1rz)z`YpQ)jTms8g!LZ85!ltc&JtqA z#lg{q%BQwu({6I%zPD&+8Ym@<{2;9SQUYCde#voQax69$shac&Y;FoAmyTj|?s(jT3}NZ5?Y9D!XU zE*gSnpA?vpseCJ1a#EK*nZ1@Yu5*;If(hJvWU_w4^r@M~UZQ&qI0Cz#_;iKj{i~t* z=U~>x!)HeHL-1Mh_3R)CE12N>)%2Rj#j$efE>K zz50n?E(CEs5%)38KEDJz=R&aUpr<6Jog^ECkBa}k21;1L1nxa7TXxVD(v&hu;oP4m zu**DA4d#~TgTvUatPPLMha}-eo!npDU&0C|aPMI|6MtWk`-|4Yk}6-0z^UI^QxilK98ll)WICt=cp zP4N7>nlNYmXW{ne4WKxq91~~A4w7?O)rxUT7fM*cM2i0(q5S$f_|mM;h{5bKoz$U4 zwQV9pI0Cx@lK%-SLi3<9+<+0sUR@!79L?ZqpFjyKn3!178m5fOg_0^|-?iCrm)u|f z2wtVm=Lqbw*sc!a|71bW3KK>o4t_;O?dU~%?DLVZf{B<2ZRpN2i=W@NVuV`5N77bn z5jp1P$r0G~EVLcSOH#pKFk{4n*x#h|YA&g8m?~if6MJp-!G3l!RQYsg#H?p3)cM;! zvax&|M_|`EgN~pvHv#taGGzoSwoHNDaoBW%N?5_fjZ>Xr42x%S9BIi2n>$*xcED@0 z)@KMuVAta;W2j#r3x@v6)zY)DZA8%7N7j7yku-096g(cJz`xk%^41fd3q{+~pvS*@ z`JhS91Yv(B6xY9F?;mll8_Cl-x#axA1rk;;f#b#5oiE`z#Czgoa_Q|Nj=(P8gqy;P zy}7W;P1#09VgiY4Xh*Ib4wJBg37oCK>Ie^yB-ciVfX4d>j=(OHq%%U;#dUC=D6=4( zKF=n*Ya(jQuS7{$!33^Z#m>*)P9YD{ixtKQFM7)sc6w>tAoNZCNx|1qu^5V~oAyd^-xY%R#J+;|c7-Rjydn%YtoC ztzj*8yb!}xv%&<u6`R99PLGrW_V!dt*SCtDBIDeF# z6`kt>4~>_JhTiPELN&p#3)c{1M0yqZ>Yl97EDDw4ieC!H)rz2L**`fRQID232|8;E zz}i=vJ%g*YkCAs7ZEM%8SSVoy6L_p-b5!{$l35=G*K~q80=tHvkiqI6IWR51BWvTg z(+$!zrUmx;`b${B1Rg6{_VU<`emGi6-?l< zlEt^P_o!Kg_sGB|$`RPL?|w&6O7Pn_@__S!ym6JY_?2$txtYCs4MTbUcQCWf- ztvl3%pg+%VEOi z$MR$4x{&oN4s5IcvauxlYZFNw(3YNjWGi6>6UB!$p}TfGe3|-<5$`^IAgQgt6Ke@L z0=rBsHNod@BAmUc{Hq$CJ|la-JRyHKI!Rc;gr$`#6un9Ymwu{@*j4&~_|H<1I>D7A zu&XYt6})(w21k>XcOu*R)BsaH0@i%>$gcVFol+_70Hx|L!U&>6qUQw&bbsa-- zQ$-j@V3)7_iqN1^0wZnjG2&xK4f^Z25uJS2SUS453k+Et2F;(|$Z@Zn7i9od2Uox( zbLDpxsnd%32Ix_}E!`!oU;_70nXLN7UsAoJ6|G-6h$FD;fR-)<9f=2(eC3$v8`ebX z)_)@Y`-y}VOyC~MVuatkCw}>Lr0M!Nj=(PUkT$U4ObWanuYAtW_IXOiE$H6hKrC`bt>A1n!}%vXQ|_ za_X8H(T@w@2<$RQX%VtUt%Wt^%J1sQ+x=vc*%@&4UnpS(6S#-6z1P<}$eXk0g~7sN zj=-)#xvz!urR%|ciSjq^^R9@vO>3vHOuzfetuxzP>6-@Ab_u{D)q|@iw;>V)J9KpHfToMA7m9ag5bF7UG z6Jtq2L%x_XCs=wLbwT*kTmi+w`{f;@p9zY8TiD6mbGeKoUT3D0J*F|DZl8q`Rxp9z zuh?AMltShl^b}1~LpcJw@aJQDOGWvl@u{`=c^v;aFoD++EVBR7dNRx8m15f#R^u0a zi`a#KCpL5LtssrN{S=<1i@9GA6L|H(M$zAU$cg$H!e^gQj=(P5-`Gy-c z7G4fcfS;PmtY4drXUU`uhP0_}u!I#%bg*m`R42!S;(@Z(%h;IX#3-jd-8o6l5!e;i z@JTpXngDC#YZ!4Y^cLwFJC@o;G>RiK)F7}S5>hHXcBmo6O^#Hvx2l8*?8;>MMlRb{!}g5Htc`P% zcat7n9OZ6vH<0_PjCsL81n#F7TDtQ^E7Fa+=(Nw3uh9r z^_A~-(luR=T3;L~VFeSXb6yBmUlO4C**4aO(6fSQy)dFtXXPA$U3`YZG|#=H-4}Ce z0s|$iV8U%eqfo868m?$6^Up)-_K=4kdeNOmHXMOnpSs)?Dj&qd$f{UIG#@=iPRa(* zDcj5>tYBifU!xFyD-K>AQPwKH-T53@VcMUz|6?j)1rw_d{}y(7$3f3k$}EWSnpcR< zfWdT=Z6}VvuG+faLc0aA@NQEABf@_~kT}16xr_)IGT~(UgZwmLEV*+Qyu!zRYRPy*vJKFxxIF7(BJdUxNvgh*1 zwK;|~VeJTRyut+TZ|nr?zrgf>(|za(sYGz z(k21^ed;Ku-R=s08&|=5CnI@J@E1rsCLQ`>Lx z3WyqM!k#Fy;}+@EG=u)0u$v>W%X*a>e02(kgi0ABy3iM7)?QcI^-Q&h6-@k>qy`4M z5isYbIU~HZn}}5GLI(+3IRd+KlJuaTekf#rw`N3-4#luke<3`($X5!%HJxw`5Vj)g zcM<;WDul@@u@Y7=fonan2<$ZtP}A`zga$6>2<*a@#@O$nrAr<+bR@SF(GpfL!B;%V zA>GLKkTK*(V+2QF7p~&Na@=c%k>=jh$cTaATzwx*;0h~jy=yRvR6dU&zcQ9`1a{$C zKkR+b&y{?A6GK8nmvEJhFoEm7u*~8avq@5NHaRhlf?u&CDXI6^BUe zI6scSF1%i0@uF+ilXIt!lC2tZxs?ni@F@^m@2VG*#B~>lMa(RYz%IP1Ve?0HCDA@} znT)#3D%YbG5+?9D728jwRU|j?32D4Nog=UduWHx|;K*KLuJ(~UTRla>3MQnYPlA;! z2_C>j_6&AQ*iCMoRiUN3ojC%#@T!KrLDn8%_YSt9BaV!gu!0HxjU{HuUQ%#Cms$EkCMmT&FG5#12_V^@EV2Pb|ao5N5@)F zZ<9U}RyYE^>9N&P(FHQ)SPv>{TXO_{yThv*mRD4GgUD>V(-oI2C9Gfqzge=e{pc;y zm-eGRk;WW>U3e~G`Oc{i$b;Jh=}I+y2`iXro2mv6Wien@p2U9hh7pg5Mh4K)msB|d zyZAXO+Ts-%GKA36ul{iFoS3N2(}L!u5pdw5vNHG1mQUnV`AF(e_=Y2}t1d$iE?-#; z#~00E#F#fabdbwXdgJ|lF@Amz&|B*ZM$_}NYtOb4F$3XIRWuCB@`iTVJwxCg+OgRF(KJ?Ingn&4xkl$y7 z_JjY(nVp^Kwe!6stYD(VOby=8SPjQCZ!scn;$vd)Ta%7DJDel1%VEDNxUsy{Y@0?# zIQ!oqiB`W!jQ?l}E11|m;FoagR}$_yA^TG$=+O2fB5!TEIv#f(8YJMJhnCr_C*!3pyyeiBiL-Lc#4dApEC1Y1p)&n1odr6YKt=9D!YayB`aiwesL! zf$}utiY%8n*&KqKlfxveU}9$P8^ZiA`A~8010$y8r;`4CXA48K!#M)G{%pG@Oc=2N zP6^5#;ra_vWXB>warAeDgcVF2F*q$u>{bZ z5b@&%Bf@N4$x4TQVvpV75>_yA;PpX4&$9#;JDz03vCU&hV04JswnG?4U>AQ6)|FW{ zL_af4Oi(P5u!4y_bBct{Ps$+gZYgWy;b&@DL9U|1X*wg)_uY?s$;94E5-s|5NpuKM_eOheF5!mIOZ6#z`q{C8AWlfH+ zBRY_#>`Bz3wu6KfOyJ5JYY8(PE4$ncmTs@f?~#0n<(Djq4F4-kb; z5Z#e(&k@+Qu+?4ReqJ1uYffTqG?(2Vqc-_c759lERxl9|r3T|GmqG7QwTyW1{5dgx zGKbm)S#Sh)?O&t@nF5QTTQiRlz8Aj}+QW+upF3E@3MQ6D=t1983n8W5X-3?)RHLI^ z-RTWAU5>ym`*tSKzF|ISpN(V0>*p*($jyU#-+si^Jj3s}xcUjZi6(6)aXsTj9X_7n z>Z)M^zwfe>hGmCIuIudel7QNZEK*S0r@cS;SU}o}^cyyXY z59!8n1a{%?jm5*wZXs7^Pp1nnW{6n91pg-dMe8pKVFYcCQUdd-_Ax38(F<#k-S3xw{}R!ACm1?pY=rwagVQ zCM@F!?85g#uvMQ?Ye>E6EB?1QO2P^zaAXx5cO%<^?Wew?aW_^k9NkKRUHD!Iw)Z-) z5B$z(BMQq`NLaxHUx)tNF9TRx`dAUj?z_VTcHw&=SbptbJ7^b^rD)xCrGyns;QHIF zo~6Ad*p0SSTwli%*oE(fV0qhp$3e-?PxhCpS4vpH1g;#*cF$7=LE->oNX+F4?85g# zu+!JSGvU6=c35>XR>BGl_h6-|vr4*G$dpzK zI0C!)8!B2K?8G9MACuYyUkNLi;7@)+4rr5wS6-7{DXcaXy3Yx_@Qq6Brj5R)#O~!c zqMbNX!U`tvNfWz0+gG3Tk5-{mBoB_jE_|aB>sN9sGHbLZE$lu`!U`t%>U$}BjfvkT zUHW@G3c3r8|c??Hj7p~*Rs<-wX zOk&1c)8E61gcVHS3b<^w^w);u59~{=3x{z8cHug1Y%KXIkYN`G(d(^jC9GfqSNLRo zcg`qcG9KsBF(cTzyeY;F_Q;!n84lq=ikSL%X%*2<*bu zP-U`&x0!^dOro|0t+_g>n839yS%vWp>xl2NskG$hcWzyRU3kSIliAIvAPO>>dbEGDcH!N676G9x5xqW>ss6+U5i6L$=k@GdZT)%jB-Vv) z9DkQ1unX_jvp28*?vP;D3H0E&M~(O~7XL0{FB;`Q|mlNR!U^WJ$}uXmhcHc-II=1+tjb z&T8~xdJoz&vK<%qiV3`f#P)r%|B^i!=Cox+XO6%w90SYxu6Hvjd2UK)QgaC_n7}(o zGFklIk7V5>_yQcaT^A;omC4r6D<_+0wI%C6ERwK-3A}^EYDd==k|4)u z=;ytZBd`m{z_NQ9JhI5;xAyi{4a+2~U;^(TvHdH}Bm(QR74o2Pj=(M)HOtN>^p=vN zCsf2%Z2t-?n7}(oGTDkr3(0zyA>x#}Fpj`3E>=c z`E46T;v$cUweA62oFyhYf2|gF9NqzDL5XZEnbcfDyc|-*gDfK#=kVgnkvKb-ML_h} zLbN`u6E(KX=W@d_!B;{sJ+_~i2nnKT08d~S&J$;G0DToCZ2fAnpXA5Y+8u_8`=|O!SiuCYcfj86B43gu`d;DpX)Z@#7p~92 zo{!8H^5jpn;$|lw2`iYu^$u9>(lZ(DGq+l9Z##=4unX7cV3jHMx1kp*!=du!3<)ck z!1WGT{X{Dr8f2$J<}R7a5!i+6bFg>kQ3h0h*ibU;qqBq+OyGJ4%6iD1sk_=Tve#=A zM_?DO=)vNa9+=Ul$2ml+pS^??OyGJ4EHf;^oHpxJ60@qo9D!Xpd!4;)*ICofDYeAs zgpGt1Oz@Qu+B;d&F^*TrL-(E>fn7K+nN>Yi=}FC89+SJ@OeL&f;;w5yDA^Pa(x&ms zi1_Ok^vTt?WY5#C9D!XpKg* zDmB>06WGOPvXUliy01`^y6I|3Si!{9iMB8~EeOK<_hxN$Uu#ZV+3Qi`N==TyuEieR zp?*jxm}%)UqAb{o=4BYr=yrcatY9KvdjOc1&WB4u%1k7qwr12}mI?jr`imp5tK?~S z*pm?inoY_xmNEM*=<3bpbd>ii5i6LGHV=T*K6ByWL>1P?j+v&kJh=xQyYv}HVAn4D z9#A^nALLulvo-=&7lOgEu2PYilT=&bC^*#AK;;6%njzO5gvhj$5O2AyCL$+Nu**9F z6SnyrV-<;e`3Vv^RK}?USAqKbTUU^S4sPPVd%(% zU}n{u?Rfbv&?d_lYfG_~t`b%-!PnniZLdRS=*T3A#Q|UfyJ9rg3wOru2Jh?2`we=% zG9imjG>U`cyd|t)0@wRxZ+F|wNPF#PV&Aa29D!Z@9Cb33kk-Ms#hSA$n*+^Wn7~zt z*?p!T1IN;91tJo_;WKSCh!a=lMT9%M0Bk-i?hG;b1in^ zYy~zlOj<{>mZXUr*91yf!33UzS@h?h67p`HhdBFwFh^h)&J$-bMe;pl<9I9al}d<& z6-?lI2dvIS-chnb_l&~Qg(t8J=ZUk(nsw(%eyOFxU`mjL6-?lI2kia)?F|yT`lV3Q zGk_zo3+IWmcbu=!$ZYRD@TJO6!U`sEy#p2}ll_j2-eXG4AI#~E4`LqW zMw%MjC9Gfq*E?W)8G0&oNJ0jAUhKjV*oE`NWisz94eH#cf}E{#lCXjaTk!Hj*o8C8SsXHp_Vp^iPmXmNB4Gs+xZVL<=}*z4m3?Beq#R&6k#Hhx{{w?K97-5C>jmSDO1ee`If8jI8KtjZDCh2Nvu zehKYJQy$vTHitfOu^*V==MU#leVW{RARV-}o+Gde$DOd#zM=p@*Jm6JZrxRKsERKM zy_Es~^xDfETjiFduo`_|KJ=4INB<93=N*@0^#1WDB&4CCq$Dj(?RlSbRD=|TC?jQt zP$(fqG-PBXdz4*5Ha+(_GP3u`-XSuxM}Ft={k~qm>wN#~)#vkmuIIj=bD#U{Ymoo4 zl?zbwd>vj>?>*fS?d#ozZ2NA>paKavkIPqP>gJ=T6w zB;Y(Q&j*?1jNQkLCdaGJ2n2MA8M=G7jKEoyV@dGD-4rU2fb+P#Ups#!t~!%Q8g0xJ z20s&oTKi-lG(q^Gj_dz`4)bvv~@W{2J$qCA2s6YbF zA1M&fr8c4oy4)%mHR@i-W90o*ko^vW$-0KkGE^V|X94*+MSTBN zW=s?@U*;_k(ADp6TlDC}C={A;ipK~(uSe#L2`9!MDrBfYLYz_jGp;q+o70PE^~w+k z=<4Bbi%wO>@N-xm@ffSz%t+6PJ;>TgX);tGvAv}mdhF33_5b{n6Y9g-la#sL$ekhW zl#qa~yeFyLmQ+3M69O z-B8A^foQk6DnF-RwG(+=>O}aIj6guwtq2K~EbWJ=-aSqz``D6{5@%w#ZySXQBu1*a zq4lmYD0ijm9LT*LoXF2oYjV|UKZS~BH-A*Rb}$-m-d=*A#Ao$GJ;*ZN!&^M9NQeOm zKkHzGGeXdy7BxJ^ltG@P;h8O&o|h#M&;{=ZpOra*NytVEqV;-^aOIE)MN#Olp(lz8 zQLQ6;`aOtrb!taE&Ugz1bQKpyp}m9L&=&($HuIYPy-CHRRwRD7HiZf#%q`>5Ip=mr zcTO|jkHW$H*%)d->au>wkbthB!%=9Ar3+f#CW^=Sb)yf@BcwwzcT~wxfkf$*cocKC z4bt-(%ZY%xP%<{tm`vH5EfCPPXLA(luGI<6I;2`B^NOGHuiU9ePCC6*LIo0zSL2b* zePiTtKZX;Av|@H}i@Q}=30ik;`t2@iTPs6b-(J9G5I zv~T5{kGBvA=z=F`^W08< zI+L1ROK{V*Mhq&D;0fQ6-{v&5BxW%$SDLF4x#hG0H=b!M5YQ!_%$<2TfMjaz#{06g z8B`##U@}6HUdgC^$$TDTlQAZ*pHyJWL>+;Eu3@`9QRMSf^r0|?6Q8OBNWjFixO}=g zg9;?hv?S=e*93%@sB)!@zKci&y@{(5nhFGTEpF|N-VdFGyiCV(VuchyS{pvWUC|E; z6-cP(bw=GvMx*GkG*0L>MkGz+EiN$oB@ob6IK&6V1t*|UR)aV((Y!M;==&8{{(VWI z0*U;Z0A#r=4ki6ieXBVK{mEqBQ!QInD-h82KEoFcUOftVo$kSjoyC|uyx4^JG^(ah zfrQc|2-$odgd(~Q;DldmKN4Hff}kHF0bNU{`JtCX{1v`EB}}^uwdy>?m= zOpd!76Z_Rs0s&p{Evis3+dkyk3QaO{vlE31B>LoyLbeaBkZEdf9>a`A631iB$bvN* z0s&p{Ey~xPw;M_-zJ0;{3eLz-fkfK<$*A@CmMCrea2}(%<1iAg{uW34SSk?E_5MII z8rQffN}HlO|EjcT3>j&61-sWc%TR$t^67MxW&J|(a8KpLHYtJFRG-8H23}G^0=l+M zoP`#zxg*`ZpgM7J$LAzc+j$!{O`qor6-cz-Fb4&z@0E@usB$}9F`Gix8m`7>I<68V zplfy2Tr_#n7OC-2)#;QgJW|Qb$W;8?OA|o_5+nEt=HtqzNh5Zt>O`$4(}=U$AiV2O zJAr_%Nq2L2wy9Vt;g2sT_%1+#_092coQj|Vi4B8uQS3J@=`>r-iD7v&c`LjDc@Gu| z=<2?09%^b?>wjgs>ZEk{L+PZ$hFtWmd?kVkBy4!z<(kSHe%tn^b0XI*gETa5jRH64 z3j}n1?wE%*JSgz z5?7|%qg>yW$gWcckMU@i710hZkgv515(wymS+w|AhPxwqHT<0NcLZWkfrQI+7Zg2d z37WZ2^;Wwgxsmgl`Y0*KTOgndX3^rk?WaBj7j8u%)twkrATf517n-^z4_QoI&SRup z;k&6?X=7d8jsgK)FpCziOVYZKf_EKp=Vk2}R3NeA9!8xrv(T6UTX+oZ$vp@*?TvpU zLxF%Um_>_^2z!N-Ukf9#iKZrl3MBHk2ctLqwCOQ12Y8G#X8p*Mz+}8{fto--7tEr? z-?iog$;*T}xV*5ILIo04pL?U@yAn`!pW{5nAFUx|4OxLh!>$ShbipiIeC{qkjvSs+ zjGHXlN1+0VuFs>;rkp5Lk$axUFq4Lp$nm@J+QsVx0=i%pExwz)cRZ28cj4DYX?%3> z|MPZ1!n zX=H!!P;5A37=i?J!7N&Q7xsqf!)Nes6c|YzT95Yp%D2u0%Dv%g*?riaqFngSYR52E$Y(!QA8ss&;GZ|DMvHZ;q|Jx4s zI6p3z6Qqqb>fo$HExXMozV@Y-zI&NS~WA)P*R3LFdyRSc+VvW7| zS*JXY`<`9Wu^ayM`N|mr0bKXLQc#3O&AY47+)%xBs3cMtI@f z>2fmJUwkOe6#x7)TOO(x;s2ePJc9}(*o_0l$x&u_;iF7W zln--5C3?H)+nI?10bQhVAAi@w?fL4oxtv&bX|Lp9yPlSfoy?#DiI!t4if_Mek2MXl zIPs~<1*P`QqE&BF1OmF?UEsZM=^ZzFgUAOggLHa_`?$WSEsFPp@b$sh+5E*E|`PV}+u@Mjem+ z(ONFsI+H;K5?$pE((+^O_z_l>63;7YSo>#=oH|4#pbM5t{zToe!#_Xmk^^SXU{Ha? zyz>6i!@JIybySrS_g$v=_|IBdD?}uq3zkZrpR=MTZnC0>eDHwyTzO7Ol+<*eJAV096=TxbN%-c-ZgRijsSGNRNL*Gd4V>ORVV-6|!uC?9vI)TB+kCNp?{M!9X2Chc&>`rYTqiMQrT zPaoOg>_)0@^@eVg43BHG!-@UaQd(4eIHwi9(K|uzTDzrq-E)212Tzi*|h8ai=(aa;jP&+d^UM$ufBttKAJ?m-KPrAASA{oUi05JuRT6#rMkO$aeGkv zb=mZdT8cnG7p!CWiPrk}QS64z)S^03s7oMmD*dXz&Y8A2_Mobitk2(r!uPN^cm#--P<=qnd^cuut#NG`>Xo4*(_YYuD zfyCpKGyeT|w!nRx_T$9QkBv~cy8~12hy?<=_AOgc+=|C24^hRq)-xFY=+}}Om!}HP z;D*|MQvDx09Pl_xhUJZyl6k(k?`l`7eRZl(5+UJoq@7gjYmHZCsopqxfAw+G-a+(w zeyTt~7c7+u#qO;R_{N5*^lr%%1{FvI*PBV72eik(UaH=lPG5|063eCED<=yCbiq=| z+wCq+c=w5|^m>O03@VUlA(=_RGuz_(TU7Ox{&yq%JK+GW8<-#v&;?5+U#))J4)3$N zNr&Gb!Jq<(6J1TE#;i5&JtCRM*f~=lk8S*%V!vSm0bQ_E@^PO$3%t@-jlJs<&7cB_ zqG}WAiH9C8upP@|R2XPtmrok(uvveBfG${$c}9c-!?9ctNXK0Pr ze3>J|--e&+*gGEg8#0rcStl{5Ktd;@k94a;d+gz(YAr2V8i_UVd|I8JC=k#Ee;Z!f zn~lY}kGIorGsZHgK*BRSLTc&S7LWX*s@vnkBC+O#Lp1eQyg)z~{B3yIbsLF~Uc5#3 zd&DuQK%yrKmlAnzLnADS$5?x(7v6iLhDx_$1OmF?Z^KXJYCI5EeNkgNha(wOAaQg^ zFG-`k6&_PKlE+x}D-fGjH)Hwd`v?Sd!C#Z_qc^UW&b1bTURv)tomrGLcY#<=roFCHVU;|Zy6c~{mbw*%9eF}iqJ(08QfWFXuAPAxu> z{}-j_+Q=HWsDJY=3QTfrInk>0Cwi3a%FdqfWM4mYmrSMRm>;q)e=|MhU(`ecPblju z!0eeC;_u z`Fq665_;gzNCp*19NV8MeSB(yqhnHd3_JZ?e9iR;jXyC$AfOADd_K<5G#^*jR#U&5 zgBesHakOT(Wc9%iPmD<5G2XtIg9m?lL8l!XC=k#EOFqx4%fHo9|3=KcID$b15&?9U zG`3SKJhNjgk8$B}DlYPB&JO+RB@oaBpA}x0Sd7OjTDE3UCxRJNAQAtlr}Q#h3-|Yk z;xPhaLvY4pLpHQq4}pL#@fjR?%N_eKXv?;Q1T&~W;>c@bsl$6MyuAAm9%DJVV+2{8*8{ zlR!Y%*jrsCqXc!lHNua7t7p3m@qlKYY?iSr&rA0I3MAlrg^&Bp?2Bgf zVgH57m#A6S>qY={iCUDq3yNiUx^#wq5GoEWg; zHXi$~kXA(vVzB;rmT+0x(9s;X4^5EaGtW=uDt(OATJ533v->fqK*FZiB`NiF8$2X& zIFI32UX4%QSJH(hA^~0SnO7*5+up~gEN|1YuuujSNbLG>L2^E1fH!tgy+0NtU&Xg3 zy`UBDJp}@~;4{z1eMViwbxRd&dsQHV3M9U?KQFB**TDxqgzy+1ldACEg&Hi;F+d=o z3)T`m$KeP|awMxi?XU^4Mt`i)cIt*h>Y`=4au;N`!VPEL442<_?u0t@a>CtgBg@M52CoR|^ai5Q%mLUUYQ1OmF;e+MG{n~vD{hpH_) zSI!Hb@a|*Sq%|@zGM+_3Kd8gnr9*VJzn@uSs^D1wkMG_Wi|51SL+1=x_a)Kh33EW!p#nz*fGhRq40N`oH(spsoD(B7Mv=j{ zLa5oCGZZTDbC2JdhL%*j;Mj;;oUq?CoV0A~LJ#QN5eVoq{gsR&?7eZHr@uMTr8<_} zt?flEA3dN@fkaZnWHeFN73Y_|=Y(VsLo5!vQPWxP1OmFQ$4x}~-Mn$H{1*Hd4DlaC zM)ioGOU`_vP=N%SHy$1D=8CIH6HYwWi6Yw7?(~FGjX?ss>Rsc}-(lW3ZeVLp#JEP1 zf^QMjadTq^6-b1nk3tDEU2)nVT~4s&5oF0!cN+UgQy`$LVL~j@NcYAo&slJy;Ycr1 zQXfu-?bKpWfy9f4F({(k6%Vj5@FwwgvV^KIPtcbDB3NiWhb! z_+bxf@}oV23M9m5kj?QY11H+i;o5cr0bS%-SJd;YH>SG-c#N-?d`O#jLDZD@YoP)O z_{{TXu(LaP+{=>guyGRz=vvf7LSc`+an4v(4fk%13wbnKqFMg#3@VU-H4$&`F0d!H zuiH|?8b5)6u2(x^)$JYuVA?bJ014SpFsr@utw#(`^Q<32}AVhW)dV2 z(53Or2K{Q`gFg;d^(LCXXh%%e*wLq*x-h6f0@nFFMzs-%xzwEA^XMrM(6yngEn3yi z2cOGPjZ9Sc`Hufa=*mOOhq5o~P5#xQH(Dpl4eFZz{+`-DN&aZs1d%`=T+(3*Ckp#1 z$gstk@`YD}8B`##USAh!xccB@?Nwv1J);|wrdMCd#TTLl0=nLZ>!6aR?s(W3RZD+$ zFHNGEphx!<_hnFl#EQEn==L)=9GyIj6Io|<$*vC)4LTJj5YXkmtqrm`>V!Ml$8f^5 zzcE>JA(AGQ1v98XV$M!0bScXTH*${T#Nllw( zz0-nhn4d|1PV#3^fkgfxCv>N2NBq{OD<_8R9ZIC?HB`Ifamq?kQRQqaJZ$zd8QygQnip=3=N&l9>)lT;qe)k^k;Wdbrci;zyvH%*Bt`i}> zx~-v;vWx@*x<;A@paBzY@v9}BIFVoNMc$8ELpx33Eo7iTqH||QRKK$W&dpP`OV%2= zl1`16Qx7*gfq*XY7d$$}mdxE=K)+vbV^D!a3Nk|KVV2nTcLa}7cDFq_H*^8jjP(-; z=z^t(&&vETB7=@)(@$lALb-xOeQPbW=6px2wp2B0u(#ZhObbn>(wJa@fG+qH@Vo$@ zw20yIp){c&OepP;crdyV8fWZ`jl(DK7}_zKWQT4Lz0^KJAfO9A&HU6l(wMmIx1;Vm z1_)0rBogBrBOP0J?0H-@TD!SgK|U+hssGM_0s&pHR^sbR_C%5CYzM84yh;0b#v@eH z2HQSerMz}J8dcpgz~=oADfjjojAHre#EE%Vd1-fU(TAAC@1gUS)l#THqU>8wwC0u} zc4+gC6Gnl($oc2HXs;9B1OmF;^n0OeOWNXFS&jL1oQMe~4_+Uj^rkw43M4Mx^G6>} zwZ?_bTXEu7`#|!bA3rZ$S4$wE>&Oy>{1Qy@)f=i-M$uIt@~-(&TFqKBs6gUxjveye zVubaG9VcqFJxG1veo9)m6A0+~_{1KCdYa)qeLOhP#mSDezNe%w``R+7Kw^-MAu>%i z#^*x_Cz@ZjBtx$5r#p{03j}l-xU@!}>&&oMQ4dZmtv4Zjxf6|j>BXP|iN!XWs7qiw zyeYabCk&4pkxzSz=z?uXAfRi#Zc7wYXo=r~LHnun`=~w)Dv*fT^;(+i zYlq*2s7m{QPQS6*`bg>?8YK|WRg+OC`3E}V{Bf%JDCcdjao8S2Z|BA^s6Zlc*>!0| zyfZ#|dj==^4|#yI+qb1Qi-rpXbcyQ#G-sZ|V;x)4sAXdqR3HJ@1n|~t(q4SF;HBK% zZGu2R7hJW#=LZKY!>c+zkx%nX8&H7+T!X;h23i@oNBDl3zDyAa=z^;+__$9)2!7IY zy&P#dU07uS3Al2E&nRlTV)V^XK2SSDAfRh;yw$%oA%#0tYgjtz=;No~cPK}O%w$l3 z1Y7~bb1!S1##ZefD7PLT$Ly!x`uADqXU~!YR^9&hw@KJ68LrXbZR!oxI4wU~K6`F7 zg9;?XI?;2~T^zFfkbHX7D1m@3_{%C3ht9phVbVMKb#R>U3qk_c!F=pBw-y&PZ%wZq zh!qIvf+dt^+R*-m@4I)RbteZ3B@q(v&A{J-y%c1AbSOQ#aDYHS7ktwA-Cfs=xDFXk zHD84bPZT8J8;)nxiP9$P!e-NyLm>hIU9iSbDC%w-lB$IH)O2=`P%}URzNz_n8Iw(j z)!Ehb-Wy3EpbOS~{5p^&nKyYoeOBlp)Nqi1Ee<}y5@APPjND2mwR92)=z=vk-!t0F zos3r7L=Waz3Nj`fhNWd1L zLeb$_R}wjM2W9hH2n2M&H!AN5cM2oThHs@IvlYUd6B4i`%V%H1BFJ{v?eu~9Ckj6c zx?szI_aF-fkide?wD`~ip#=a5*dkZGIR}v@>o(Imlgk1DU9i2v#}kWV$^O3^=$7tB zg_aB?T6!d-%Ej&Qw(cpsUDEE21}Rw4Uf#byijDZ8^RGv@q}v4f+LAW^{&pT1FT*|+ zFITmiWLD5(*=b`Wg9;?X9;DMHEz<5zgWQJp5eVpleJZ|(cYq;zHmMyAY!}L)0twh- zbRT6wUalBMJ*Hv?6-dC*PrfRwiw%j~GmB0-=q(V? z1>5udq^SYUB*P$^rs;GN+U<~lqn~`#Il_Y+!;5ITkF7vJ7wnht6Pk1o(THC}ll{$v z{s$!DxAjBiy&dt;)b{+16K)qs+Gs7O#leOG0bQ_v#mA7Fgph#vWpqwW3!xtc33u}m zsD?V=4r5ev6R#qA5u^DlY5kW*0s&pH*T+|$O^qb|DhgBqR<7C!yVz4!DoQ zLtb_}Xh)OtBUe(Bt&ar)x?q2o&n~SVN|LRX(r(|+3jJD0jA@yM+%xR)qJ=wnjKGD% zNc_+OI(z+5fq*X93s)#E=f20WsWQDVHH^Xeh>i&_q!vrt;G-FXWH^Vw$1I1{e8I4W-Y^yk=z?#*WvQ^!j8B`zve@#A*Gxt3H zYtWtzeC;3*(53tLt5k8mIZhd+>ZRuBJiyZ)8nXT+ofuRg0ZS#H1(^N;tNqkw0nJ1L zx}H`3kPP=}<9FYDc#PJO_4w-WChUr@7lR5U;M2ux(a#OoqQ@_4qv0(O(6zStZ%O$` zA6LH*<}p%&{^FF?v{WlOqH7;v^k4yf=q%3HLKm$0`0jzZAMoFM ztLVv$enOoHiPr3;r1`iVesy>Rk5Sk9J9ZmbP6ro@wJ3CnSN`N@BjSBpra=>f8B`#l zcju2Z$*T=+eo?i`qSe+W&i5`kwjk1-$8_C&Z{hcVM6^$H^f^%< zN4Tm+2mhuvB^iD{==_~-0s&pH^zc6C-xeg{l7c-la}-JmB;FP3q3}Ig_+&RL9>ZXF zBO=dl$<`&<2?TV(r-1i_W4xpWSBW*vc48koG%ntqb`jAwZpz!Kt%?(#Tt~acj8m?8 zE&Fe{atX66Uc^B%te) ztG{%x-!0TyO6EjalTqm1%^;>ERtzeTfNLrEo`x~2khXmn<~PJrAfSus_(`RD&(MsD zgFJ>JB@ZQ#ZfxX5a|RViz_k=SXIQ{tl(sRLh29kj=(4`&FFmS!k2;R}!ea~`eG?7( z+m&@_#ZUhR3MAlK3WXx#h$$W%7{nazi3D^d{mPe0Eq|aMp_=?RKUvou$Noj^o|YAZ z3M60+u2B5GI0uKP@%QX`k$|q#OHW9CagFdzsV$GOe&|}fj{4;w(#n zfUap@bp$95A*2QOPuPQql_@Kn4n%Jt#D`j78KXlQo75*Nt z8sEhkZe-4jm-K|cHiHTz#28M8oyq(QlY1A&09OS&D=9|JwCYoi+9RSUKtC)$0X z_VY~{R3HJbiLaXUG$Xz>@92d34gvvPt$ynx`d1I{KciY@vGImJX;9SDHQM$JDv*G6 z7e8;w*?=@OeMoc9x(Ebx8Fp@ga;lB-`eCZ^-OS(GWVq!G+Wd<*g9;>I9nAaZGquQr zb29C0Km-E1zK{GX1utudFO3+?V{B@yK@N@HOZ&$JGpIlUzDsykt7(nNy^^)`y?2;E zKv!X#TIsim70$Ukj>kxk{D!TUET-{}{TNgr0pE#y|6pYuepQ%CzxEy|5YXlM`Kt76 zj2*5rN#!xNe7%dEb`Pb>1+fe&kbv)YzR#n);wI-aTGbcAbZ7kZn`ivZrT_7*rr}YNQrgc(?(bnW9>eVi^1m zPx@ua0*9Ik1awWU{2*mMR^WiU8a#%p*L6JRnges(X~v)eiTJ;-r7n9uA~pFukJ0hw zZk$}^&e|R~7YOKTSVyH}lfIyj;q{z&=v9CfUwv58(e?}~kXY8bLMkSng8f*?YI_D1NF*O$AjRIjf|8qhbK;G$ zDQS6Kho8Bu!_H(lp+UEs;(+E)l-+yTp)j4FNIPY%a!yuzbfoAP8W47X6It(c`Dr9Z zZ1{XV1{FxOQkbD;_iE9vmcu#mGQAO*yw9ACE-?}a=-Tht0$sfE7KQfS$ccl`Ug2+f zR_yylGX@n%B-Lx6J@f%8d4oAI@!3h-rm-V?-@JoBK$q_47gF1-r>F(WujH!`Ii?5@U(``8M%FUd_tZu(QT95W%eZ|ku1g}MwX zkbw7)uLIz7MU|2XTYbhrAfOADd_Fo@_6MK)YQf$OF=kMK1iXg|MGx0I_`(N!HhHC~ zKtLBP`Fu=fx)Q%PcVTsH+cT&@0^UPDrvG9!>#NW;=Ee2er)sy9i+6e@7!IIDCggcJs8Liw{x6MxcgxLRo)*xZ}`iK;%bq(pP zcHqBx{AzDJ(b9_z_#hI{B|cFayIk;rA~)9Rrz?XBBsM)fDmD9g4xKB0QNd?l^^9=L zHCKj-hd@BrdaXs0Nvm_nw)8J21}p7x#aIV+wYx8a3M7)3D5WFUP9URh(^WAB>*HOE z?AQxmK5qa%3%c^&>2RnH?S+X2H6-2QsKYV!nb&9xIe+a+A?V`Of=0 z=J>RCTef~(H-UhzkP#(P!o9<&$C{IedHd?2FFp{f%X0jCF{nUdtkH34V#EQYWBHJu zJIE#n;IphTyV|C|KtR{Rl2cNY!7kLyVun92S4W28<-fmCt4C1`DvXglzG28I*M^&`fg24^7W8wY`n6>E_eClOh3K-H&La@TEm4)X;_#8}_`$(=$?O;NyV|Dv%goqmMFT zH=vPsJvpIm`W*+o^rw0CA^~0J0}WA9>>6aH6iw4&FI0rC$4MrWmb4 zZic-$v7Gm|WAQ>czH@(pfUaxT+M>Q4mLrFvzMMGGOrLz%oUKgDieONI#J-2^QNW3% zsN!B6C*}sVA*;J~M}td41p>Mb#&tk*pDaRI>r|(U%~;c(DEuySFFB#* z7TIWz{R~d5Trzm41Q?TuCf0bPlg9ngsNv(b{l!+4At&pk=B))72%u?d3;B;c8ce3iu#SCX;u z6uwa2Rv@4YW+>rnw$FHywkL1kkU6awR3HJ*Jmh_YPOfCE`V$EQ0aniVE3@VU-XCCs=4__Bz)9xpJ6x3WGpbKUw;dLUO`!q_c;+E*mxMbIvv@NSzxk#>Ko`tu!ZT+zwO@DfWCsc(*y3H^+roCo3sbAOX)`=A$@%ZHdt|4{|43 zB%n(?9pCD3J91}{FS&GP6@>~U;5pI?#VCumBqSM=bce+P0bRu-ZINbNESm7#mA`Rb z*qf8YkpZM;b6*M-NWk;3`I_x7VZ?pkQJSRwfx=aDaO?!GbmM2rw&+Us4XL7KFVq-R zAOXiwc)zxD0Ld{sLBqB*6A0*nE8X~sK*zjD)0>y+DSbT#6-dBw6oul;3O7T{wFjg9;?z-d48B`zvcLVd)BHEjA4zI6PT^TA6 z&;@tM^VL+%OEAm0O>1rsU{HYs+zrg%YArV4?xSAPMtc1P0=nQ1d49IY>mqzbzY%-T zI*dUD65`x;N$Wz~!=yPo%|ZkMy5J6Z-dfsOhzoKI*}JU)3@VU-bLo6X?$=CQzN#%# z&2K{jy5J6Zo-cK9JdVC?&1&uZ7*rqu_w(|#=U;s=d2Y=N$0C7%F1SOUw|$lw;LyhQ zETEDng8_T;ApuXU;Clh0>(MGrYgQH>AP~?6_tf)RblNVI)ZU6&bq-=sfdoA3hmZT9 z<*2cH8}^BW3IueCd-XSC6BK{Kh$Vdp6Hc>&1U!vMp-8IQDAlbtV6h{@1p>O@*;{o*K4q~{fz|z zy5MXLUt9Z3n<&QUu}9C_2(vPffTPj8_F3=;w;SD-turwf2dPJD-3bPew3$@e-Z znhUc_kbtAn3WepDlQ^W%fmKcIAP~?6XU}+#WnBrb>g~?XF0~M5$shqoqxo6`+j-da zk1wnHBNEUBX94+j92<)N1QBMjue~ro2njeE&3hBiI^urXLCiE#B%lkLk0U2vA1m-f*qXu@f4_Gp2tFn=cJ)LUg9;?P&xc46*Y=|Yv8{P#pkZ4&p+>*8Sr^@Y0s&nw6>X)n`}Uyoor?H) zVqnB@^mJ(>c3U}!K?M@#AA3pb&zGSoe{^{t=TS)jnv+{cHy$1)5YRPK(N5Yjcn2y; z?8yo1Q?aOP?tNOkW)y=8Bo@?#OMU!GP;93VPJGuNhMG(`OVi(t6$t1mxzI=YwQegK zKTb8uX>U`A6za!miCqGN3M8iHW=fCjwxM&CnVismv=d!kT}IU&OcV&{GAo%QxfX9i zf6P~K;(3b)Xv(HdbXG$mg9;>e$E}sxJlcc`s*5-g+xQonUABO3vYa9i(A9MBI>~X& zMs%sBoD)?y+Ty5&3_AYY6b2PY?0Bsqp4vBt2KDJG3$<-$QH|R3K5C)B-ux%|JO<_jBT*$4gvz#EER| zX&?~LwWpv3`aF3m+J7#W6U!HV#6yWEIhfOwK?M?r=joz%m6Opu-T9pGn)MCm#$mE| zQXPc^bX{Jci!NMDLdPb?apHWJMx=ZQCbP62Qm8VlO-CMa$zp^*KyM@an z;;_n*R3=9Y1az&Xz0s9iU)0M~m3#TMOCXut&4#>w-A{%JBw#Kvp3!q=7jn|biX5pZ ztAGS_9i1D6est*c-<)A>V!M&cJm>bu-X;}LfyAUy(WsY+^M8qvr>2v7-R@NTY@mGO z_8jzD#|$4h;Uqn*%S7`>n_#{5U8S}8ndneLTioFq(XrG)${!R&^vEdJ7 zs6ZkocP!E!`w%6CHbM%;v?Hlx+41hQ(G3j>3Fr!55szM+c#1xbzQAMXq)a38w|LX? z(Jd%cAo1Q{6nYbL3uWx9RS|ts$RMkpl$sNPfUW}HSXA9`34I%Ji4%ugOeMWM{pq6g z&J-$;xZYv}^1OEzmCCB?s9c#$@{0WE-W7ud0=m+7#~{NG$I-_K)wf#FBbB^OHKQ%3 z1yHC!A}n_pD(NJn1$%XPjB@p{VXri zBNQr-&|epa0{ibl2eR67!fa70IqmXHZq+$jAfRjF&>=`Yz6AN%wd6!x!*pWqyjk|w z^r29J#FFSZ)a}I zQAdqJ1rmQshofWbCZe5%Hk{ZNI-OXnokR1>kU&6JH>V*;uVgk#f2qrf?fj`7x&H|o zIJ-ZE3MA66$DpvtsYuIFj}vh-lgVL;p)8Ym0s&oZE_3-zA&lN03iShBCo3dK)6ClJu}JF_=h^(-H~|N58{2TjJ1O?DnA zDd`%83M6nsH4;?sE!wF@Z;pD!0sQ;SYbpiohZjXDQ!_x}T*MAvx=G=)T5AhNI z$CaNcR3M@3(i2&@?vAP+93M5Ws2BWCTMJOb!k`wGz1o>^8uY8lLClJteYy&~3XDvfz>&rNi)G?fF zGc5MEYHY}$0*O%`0jOa4BINtDoD;g&dyxAN_b4ZhFcS#q+Wx~I=~gdC^6gEWC|w^+ z9M`N@Zk}ktpaO}byM2-I@MTD8w}BJ85<8QaF_UE-tBwKzT_;?8&=s4N=$ZLyPPCZj zPkxQrB!{Yn^185Y)*90 z=|t9kcBb1_@|^cTfy6*>7xblkE&6&#mGwMXdbOkZd}Tu zeTD=xs6YZ{QBx@T-q$2ceOJ?Hz3u`5U7eSkp-X3Wptwv|9>Z{!8gW>-m9EbYWl(_x z%sI>3J~KXJ$ID0P%G)9VUDG=nAlvFPJ1Tm;U;-}7U>3LKo z%FfO^!rz>9AHLd7pN%0%AfU@UK?CW$JB5}!nthb-$o;VilUAmz+eTjo6-fN7s*wtv zE}&Cyj#cm{DrFbeI@FFWd*>k%z;)VA1I0eQh!P7HaiX#1Mm(*-nw9TzWl({i3s-{j z_s67t_|I)CcCwALKtNaNKn+xM`6lw*p{C?(KXxC&`cG_G4=sBJ6-dAp#(du3>pg6s zVZo~ITMGnq9o=ApbWhwyeZ5cf>u8=`kFT6=$A0cIXHbCzTq(^*iacAAp&eT@YicYI z(6#5d6UshTgA%G#D@=Vx8x7a4GtSc4>8}L>x<>j9Kru~paQL9rJjR1D5hU<>1@*Z8ltKj( zaQzHl>GUXyoHj3~S!tI90=jMlj6{v9^l|4lGkJ^&+Ji|^za8}U_|p_Bkocc-CU(S; zto6n8{)@c=0bRvaN$9{jV>~@KfX7hM;biI9_4L}$QVJDFh$mC5%!(%?&ll3uW-A2( zx^_m+Lcg|I;&jP}$GEN?Pg*=LpdOWLDO4aK?$vKxGnTO61vDyWnLt3-HrGtF`kEbH zuQQs*_&7J7#LSpab(R!Us6Yaq4Zu$}ib)_D4%4WQ`AUI+uJaG(pj%ch*kxM|kI{4R zSTfyhBF#OvjY0(y@FZ8BeQ5jy(sf1{HCnVrAfW5T;<@O+Fn9dwOFoa`QZ$jQoa;t4 z($-R_Kmwjf%ikZ_$>d2+OB%6grbvMEaF2A$MTaJO;oPNxJjTiesigO{i}KxdF%&BB zbK%LleAlmM8kwoSTHYv|2?TVFSd@oep7q7fmW*==g+PMZ4Dv%hPHt#=Y znRvPKZ*wDEsZLlOX|JXAATG5zhwQruYD6S*|KhkX1?M?A2+ zE1IyT^S{4e1@uO4%LC-B_fB|rWGL@{{7eXA8NnN+HoJ_8?)cI2{^w3Oc&#aVxGqwD zRO^I;26>`#qXF`$H*R?7dpAzlw+Lci=_aY2Y)zm7iPQ4}WmNBm10q5=VNgDTMMTKb z$#XThVNdeEZ=zsLQ0AN||Nb8Owkfh+l_D2Ba>Chms*#C4Jo|<1Yh}fz;U)M+ZKkX` z4|%ltF$ssx`S*9?unMVfi#f7?tv5C-mnGin%gkVFta6kU3#Opm5qbYy3)(dJuXy*L zzk`&k{g)fhmyebD;v2Vy^O-n@rx|Sa$OX!8!_G@kfy9%5`Tss?xM?FkI%xPJgIQm# zQMMk_;0FolI&3jtc5Up3pPX^yF@Ar|UT;P9VEY-~N;^*SDn#M+E z8z=)Z67bWD+5e)yid!i4*p~C}?`7lDB=re7^4@3O*zM~qe&q$e)0yTkBV~T8C=3-y z=pD%YN86t1&xvgsX>8l3oyxWY+ynx;cI)QJHV?hAX+L#NJQ_HYT^gUH{MkYeLj@9_ z4gPbd=XKNLgr|2pqvNM4w~u&_AOT(Qcj7Y*g;Ut*@CfCZ#w#%VZQ*YYua9R@`jE^D zu#PfKXOVCnkod7Y>pxfCN!2TAQazQoVp=H=cAO;;&;{>0ABT&X$jFk4iio)fgpvrq zVNFKHzZe=3s=o8-U*lL^2VEr{SB0Shi63>-5lssL#?hgkC78OkVSS~Sn*@K zxQMM`<7ZR_aK;M+C_sfBE^%c0JJgKVAQQ?y~sc|GDzH4|!j6mUV?z z|Bk|SKtg+G#6Nm}u`mBtONIrr+%NtWX%{R60=nQ`=kKVe4lJ$G%il{iw2B=6eb$k? zLr}LlzW@Gqnb`-yZ_8U`Rc_3v_ZPpBlDBXjkhrul=pWsFZ+HH!*c2~zv1_HD=~8!r zfG&7V3dOgV_N=J$Z>iBlOpX~l%DsQP;lO!AQI3_P+@;zJdt}D^&$s%JW5*I79+aY# zgg}>M=P2hl^1;oA{V(yPvmMh3+A7^^Ai}qTL=R4HQ1`(H;$rx9%=mB5vuGW5%|6<({q%2{dK{0y0NH&U*DmhZg@ApKEBhUxD%^OS%|XY zeaRg)M|t~KC)_tCPIx2ValqFBU;e;JuFOe!!=gO7b)jDjw z#S4Qw>ov%XxDs!fUeJjX3I`@o$#MQsyP<=V=_}7JEDxHQK zZvO0lpZjp!8A&9P{gRkYCr9PSh*As{NCY|0`bWofspc^>FD9_=xycpDImZP8y2O^u z)yd;nxIvEpy>DkQR3On(cjmtsHyWwtSZ0)tW|@`Kq{|2I2n2M&RupeDu$k=l^DDBo zawl4}BIn;{`Drwh4E|>S`@6DdH|b@UT>1VbCv3agfyb~)oXNh%Ddoy}&>pM?=w$~Yd-|fzcklJ)Mw#6QKQzyZWB(d+F`fm* z@r>WchqGQBxyr2*PSx+oztyN=8BF!YDG|wreGGxd+ zW}e9q>h8UanI1#td7kGf!{dqHzC91E{r&xSU$6Cf-*tw4_St9ewbz0c?n!jQ%_cJb zFRW^JAe&mBvzI^IoX+oHS&JkvY8*tTbX3XMf(h}7(m5XsQ*-Ok4$ra$0;}A7GU%Zz z_Hu)zN4XExgDBAJa8VuGYMG2Jn7}}*j=i{@3--Doe^1G5tUY`X5s{-uC)3%T8<+w%7`1@ngk5Ld` z{7!me{9eXijZfZ8sCq9A|8Dp{Uy!Ez1EA~nv(kscUqUa63H-gwqeYBIz-L!2sYgi- z6+RNI5|7Gqtv6ih^I3T!v7riEFoD02c`H#mL*re!WRAOqYL(THs$;Kr#)05(b^IO8 z$Gcg*U~5S@+0eAD3R^INM+3Z;={ExRk2N5-N7xDkR^jmqf7dqX3Tw(eNNi>|VI+eI zJYM0gB)lU8Zy!k_?m7wtR^f3F->61umlV-xT z!o-NDzEwUvVl?aLtMgrGU=_ZzJPsg*=lrS971x0mr;nHkq@CB2311p=$YmRPX5H)wxb=GfZ9TA0Pb1pXr9(Vyo% zz_e3I$voLuAg~HQ1w5));yc^goGb0TqJi*yU;=-U@p$TwBf$5_i_+e1S^|MpxR2qx z2g*l5Lme}9zS#$%FTn)<-sNwDit#`W4^pe>d4a$x+*k5hoHr9;!R86-dgs(apNI+k zbS95dED62>(-6wHx?d?S^MiroZdp@G2qncNHC8m4sGTySZD~2JQwMGg?G6Rg~!O zicGvd68&8{iPtWozw6TRtE;LBn))AI|E>Q)e^&tF8Q#iBn(XfZyf(4L@9OKkX0gTZ%Er9LWohAmHIn(5p;>Ec-myLlbxDDM z)2A#Bdf3R3B$uv%Qx=TuoK>((AT1a{j0s%IEqnXfcDor_=a=6yUW0)C&%E zk?+a5lr_0gYJR4R9N#XFKEHjn^!<;HvU9qol0cvCHW0l}Ru$hLNqLMY{cD{sF_#s?RgK-p_{#o!b;rmQlHg>bRGD8>2QQsUUb`AA+cv+ZzG*X+gprSYguHxG5t~rh zQFY|96=c@DrvBDCi~J~BDzj@- z$8IZ0h>i&-u9&Q514o&$%FC1BUGzKkz|a-sVY#;CSnx=_DPa|9Hu;k>ebp27A?@Yl zQ_L@Zbu+@Ju(+KTsuD{H{`s;-ZOg}6S6*Z)U2CjWkFCfdBQm3vySwaC4?jDd$jf6n z(J&!^wKv-;pS~Ifb-L|TE3@*+*w<8hM)>xfW zpFPo9RrhOeXkE6!?B1Q(WdGP9N}Hjp%`U{vCdaS2D(h$6D%H)HMHbEN%L$)A6ZU$~ z6*_o964ZRKRo%dS8PTqLN;&%3N_95h^AQ+Cm7o7vr5=~Mgsi-NloR!*_GiTd@+JJ#|vAuo00<*y^pr0b4M^bMnyY zY(0Zw2D5{m>jO;lfNeLfsLc!ylFB!89C?N&_3zA2Jd={TIz!Xv@9|8oZ3Zvz6WG)I zh1$oElDchQ^i=+Qs-DK@wX`eSmGV4Q>gxPg5#1Ev+o=|;X<`Ta6D{b`?Z*g2$0+CD zZbk=QJV8o#r8}PQ-kcVD0-5kkvkPLeRT(SLYXEJvl%UdYNKbA#LgEkq<;WvP=k z9;rgBV_3#c4Pth=Hc*k$9k6$NR6IkMx;pb0&rQXC=cdAEh|iqotWsBJvpTW(8Z}V0 zfj4he@Oi*I^&3e|^qRjb;n}m)zw>JGJ$UNsy?x%(_EYx+JJ{Ty2Ve^(_|8Ce^^U`$ z^d{Jl$1APgsrRZN0k-A@$i=;U z$c2Wfw8-U_l(W-_)Co$WO5b-#_9mpdam+zMgdV`!4aATUs5BJ9$YIJPyy3-+eG*QMME4j2>M`6Zbk~=g#po zpoowfS@lS0pCI~j?+|iqjAo7HO=~|`+w^ZabNFOd!7DMn@9a)S?#+_Ciigl;tDVXB zI#E)wQ83ME){zW6qxqtbRQN-3;zN0h!5rpp<4LtX`w{>2rIOcWFPiA#MSM!;NW&il z(O*}4lD*s4a$?+9cj()1i9BRXZHO4(m)5-#Nm>}KkZkAorcG}rkSP-ir5$w~sSe2? zE0)dYgsS-@C?1_c>}~gI;zjB2*i#+}N`J?Q@+eJO9sTKbW*`)q*vPw1HGuYdgf7&{ zBX@4ClQ!RyX|IedGTv{!l)uS^zH&<^<45k}KB5YTK}B-|d6{kv`25tJzD`Ob{$Ivpy zdF2LmLYJ}a*LC3GQWae@aX(pHnkeOGI@73%J*2pNfz&11nLhJk#Q(e|r&G6KyiQT8 z-ttsGJt=p34%KfsT$8>d}<{-e^68)?9tsVOP-$PBa^m241E0$>5Dsi6S_Un&yT$ zvVC2pO>OgN=kEoM$D+I>*NwTfw&e@ug+v#ARI?AJK=X?sr1<0)GR0{+^%=B6xuE=- zM-}k-eH^Q={RRl--Yhk)G&g z)6(24%91l*rM`2rs8x*t(t}l1QTI2KASR}m_&J-(Y<&hTa_=p@^fM(6qcf=ebT?_n zQF9XfW-3)>7f9LHoAT!)(kdCY?6qYd5vsLw(_D{?MrwBok<#8I<`-3?7NO$s{D5)ccoKasoA=Je~kk>#ZB3g&sF z3C%n&5?F=DrF?(Xy{ptKaDjT*48CHGMy#0VwEI?-k6SY|KCZUdP8S;#s1NF<2?SQ@ zweYDTvYXG~MDFZtHYRtmddBBim^^=t+CR}jzV&e$ePKPP>dcd;Wm9|&`5c+oW@hNH zUcELi5-#hNSE(KuPNmPk?5g^Gv)(j{|B0`E)LF)wmabBVzl{=nU_xHIriyNCmc@^% zoz`5YXti7&7#|}LScQ*}uX(ADvGw-1)h4P5np#`xmq8A4jW+4@%*3lz|NA33o#LbA zRg_YHvb+8nG&DCrQ&EThuB2KRSEp(fv9W)YrY0+`uF2ZZ;tMl)Sf36V5TvQF`p1Ha z*SgwOw7;pQPF%*#*X+Eu0gX8|S|G4$Y0&$sBOKgIQz!1=OI;XcG>49K@daL~hyJc1 z8|>4h>VId(glTFC{W)4bNA{vNIQB53n|+1}=Yfe=U+Y)VefnxDNPY;c0ew?i(a5GF z1Olt@Iq|5MdyQe?mgRJhzNe<*E&W|Rmm0RL`d{OpV<|pb-mdf;!1tRSX{z5~;XE+0 zbybTh+MptYAJwx;eduM{kye%t5eTfp=cG`~-_;6g@7zR-kN4Bm`u+3uyZ^aO)&G`0 zA5QVn^7)dMEg)bJp`8a+Rqp+B9+-$ZWnD!(zSPvOz5JpHG<%_>U7`mHXO30)ocJ0` zc_(NY_pSObT@Pm(Q=zQ-y&%wo;_r4oYw*<;-X9x6N3|Ef=rQ4L=uk!1 zs^P_tYEsR1&@g5X{p*V?%mH8(z9KyD$DY=3-mgEsUD8{)R+u<7->%BXkukp9$Gh$3 z5Z94MY8kl*1Xkhe#^cB$2g2@4hV+SXQ#hFtTJ>M=9GcPB!-J}RkEzv~9v(ZCj-Bc# z4_VZa`)D(;KbXBTr2Tj{U957A8D2$vNwWPPqVjw{NWEo9Q;(Vg{x3|7bNDyHV?>~) z8g0+^eZjloD*C;zr9fa6uft8ND|9E`cLIaZ5c*-3wWi+o9}6bh2YFT4J-5h1z1qzz~cuJKj zzn>0`D+r}iLmcH3o|-KGdt!%y<>Mx_In)Mh!9-%CuqyiG8%sfl0#pU=#b^r7KM(ix?{85d4^WNw77}(p!km?sc7mf-Ozd~cH{wXU*i~BH%7zHC= zbK>O(fxs$!gnVTAD*|#y)}zBV6tjnK{*9X3@3~w3q3+bG|Lx#au3r65I?c0nl>MB} ztNGp~y@}9co*pfneu!ZUCh++w6c=;jp;qNLwa1hwHvX@FBg_`-d8(sz|BY39R4+$8 zD=~|Hs^=)XjakNh^cWip@3vK{(`w~0Y{A5ctbZf6rjA;{iJPyZVUd^2Kxs$)%}jPW&U>mj$T}s)m1;b_wNxtbn#I0m`m#Us;B(gbO0wh zJx_y95A)Pkd$+1_G#(xY;pjcSmn=687EY^4Cw~}3u>}+2Xlcm0H29WbM^~ADQ)2?F z@R}!Y?X%OsHQj^mD*LX+7EItZPo9naLn;I<&7(bI<0!UZ;+Ajkgq$x$mc%tN2h}B%bWD< zFI|c)m=NcX9UG@Ye%>`|`ZY};unHd`-yd~96|~a!(99dPD7IiioOO0=k_HRvucmcI z*ANJ-63^V$I295~-tsT52Ev)+bHc03d_J*t3LJ5&%RcR$MzIAGdi!(e%Ql_l1-FLs zYvnUL1%@ef*ipx(0)bU{4Vq_r>zNG89<^f?XKX1R-Q#Eoaisrud@>Ytv|`>LtSPo& z0>?SaMNQRH_=?q<_OfeP+ ztP;;Wu_6g-mvmz4UUtGa4nC*at+Hv8CzkTloL78K#$sI}I4JwD=O5-$Y{A3=HjVDP zW-d!#OgYgyBnhtVR8^=v712qvSD#kz)px&|2yJh6Zj$O=K4C zrW6RQ63@Kdu0&u3ZY;T#vvB74oNR-q(xpF)SbejMw%u%dgYiTNE{@wz$JDxfma=AQlqx)`0a>f zcp{!|Y*0r|yGtdWO@LNsDF`J=aAbsvHI3~;u>}*Ibd%}s4tjEXyY<}1{9g(1xzdy6 z+sqUQtinggGoGAEgz{JYSOMupu>})NU#HQB7aPhDR+T$pMx6D-*#=XMlZ zFkxpLNu2^dlXZQ5@H3z2kqob`+A^)JB7s$xS47jBc?!9F=p9b@l%&A2JT0c@-G(+e z9!7h2xJlePwjft+!l|FrZPN9ZG2vMeXmz%Q8aq><@No_HeM=jPEtr_)9!^KSzD-ix zjS0{4ACUqiT$gn$X)6#|g|7%70lZCt&*Q()Gj^?oqr(2IE{4*p|C}fFA8BF@=7y%g z;sG_-?!)O6TQJeJPAEN>QBJz@Y&ZOip2rl~H@iinA}s_0t2(8I(r3=+NS|G8IN|tr zDzqE6kv^N;m~I~!LXCR@d2ZjGC^JK-fze^|J+~`4RWpPhjW|Y9D>c#4r7u(A)#7dR zLX9RATQG6@K?r@3ca#KLRqf_5NrjIquhJaTM1jC6e1v>w7@sF;5^#pLT-%aj3nr{x zLh1Sof00Km+VP`$7L*EZv#!yzea!^|tHd+6ZkYyOuP&vY1^U97<8z7_GnOVlEha4r z3HPzPEEU2t*3dAA@f2Gy!Da^20oMEZ9&{T{7=))mTzWL^UsoXzSar^NEDb-rmkgSr z;zZt+G-&$hjk>V&4s~g(V7k?1EzxP|L3(%x(;DqJlM#Zb1sgfquSsQNU9 z?r>j84)5^fKHf3zfQpd^*YD{1iJ||u`qmtjj$$OO%wV)JRFfoVw(0x@v%JMZn(l{}H zg1bYQR9}q=tP-!4_K7qoo@++ltPYj%^}$Ej_I)t*G|C{qiZs#cTWK1sTiSy-Rz{a% z3nuP`kEPMMY2*TUaKf2?6?Iq_L{{!REnxzybo9p3$1~H(D*qr(q#sHJySv*+`WsI& zq~ADtf@kbFs5h3pj0vHCmxPk`_r{P->&MZe52Hy!56wM4$RlMF?bebXe@TJ`69emp z(5(j|$jRQC*z?{b4Yr+LOv3C}Ncg|73LhcgE90C7M{;sVd1`%vEtqJa6G9K4k02H* zjgK!OX>gb(5~DWXBurqHc;-h(q`<+uPsznodr6zJFk0s6LMqmHk&ygw>UhYWuMY*2 zA9KQ}#}`N97&?~wxVj|;Hiq0G+orD*EWYYcIxl?yF)14>{1bl$@1=m2%T;p6c!^-a z#DJZl^n{TIDFls=!yc(%bmubJ{?Jt*unJ#8K1b%C3WlE#k!@Skh5LbtOCv(*{^Oox z-9n9z0v?SUU~`bHzc5iCunM;Yp7pd>3b0o%$cxn_!u7$|ZA)=DJ)dMpUd{>TK5mar zftS2C*zTnZ3ASLuYTE>=-Q0l;oUZAwHoQp&?V+EDZ==%!fmPi@CeU%^wxmY`jgNDd z$zX6tAvZMtL~5OkpcT3{WKz^X@_qRvI-r{oNq!wj^ruXseFrrmc^x#Zy&?Zrdl#*c zVT@K1alXJj%QH2+2Py`KseOn9eGq>&da$>Fn_-5fsWlVSSE zTJq;tdj$fk@Hr_IAGasNH|00dVevJBEtvS6G?5;8U`diLXnZ&xPlituzL0-TUla(e z60en2qhz@LQz1tOe-*9|zHS3@C)4v*^@&HeWS+zR&`3wd7EFY{jii&xYm<^snz!1xElIG} zwx)c`rnW#}m3ZdQosvMotEUcJ+DJHad`>xrF?5LcOUZ4r5BFirzoQOaG?3%x*O0LV z6X`aw)P9>5sd3MV6A_J*pyLTG*{`OtKw#B2yI2~gdr!*W@68F-yF}1l@`W6KU?%I| zkEex$UP=p+m83Z&(2(tF$#$e0X|XMVQXeYyTI9xwc5f5GGyfYIs5FzYrN@?dTJu(! zG@9>m#{a}4e%~a5PMd$o}(k>%`I5bFNBlw`qExF7=Y&#d3u_<61L;z$)=t1%2jUkZ(Sb z?_vZMB(hrI7 zDc}upYicDBSY=l~ncnWONxBfG8Cj~0lb~YUUD9nqYq{Ui6#DeX5~=kmi42&KN_#n} zCH+~pq+`o8>iK526l3SW3E4UcA}`z|>a^A}wqSyJrqTL=vn1Qd9-PRiodop;J|gqi zi#~$xCQ~hsLaFs7mEcdIi2IcYlEV{{v$3^|{}&T0|4ODa9~Me?^m=h0t(qr+vZJ}VtqScR{GLUHn+M3~;_1(};~C1VRFdS@roIz87(Z{KKqczsKR<_lkvlT$0@LAwL@@nK>TY;rtJ$QO~oD)G!y`z6CKo%Q5z^Jenq zOPO>}h=ml_&5+dEo=HsySxYMp8U0`@HB-6d`f+L1h#VU9RbM&*np|N+o~MFKH!Bh&Z6RZI@@VS;8y!D49wk}% zp67$PdlZ@R82J1*F?T+tDBOn=z3ZpunM0a&m%lB4VqQxlCGKILc9--@oBm#kM^-^ z=2%#&iDF%JCJpZAev{_=Uy*R^P^8`r8dKJ%r*Fbc<=n}6bcWqo<@jNn`HXPSBWaLk z{6k8<@I%5DOpK{BgX;X_({ptH<(z2DznyE>{6`wQt`@-rRvrABM=g)e=vmQj4<~f* zr9oikM`@0uqY&wYkMOUXdDQUP2BjtfN};e`kO~94TqRx4SW90&g>u-sa%G3+e5Y^w zT~$8ZbFyf^dMm1a51E%mm+P&NiVC-IAInv-@bL8vIdkPrCAMJVNI^Djpq*bu^ZcT* z6Tqq6F?m+=T%|+DG`hacy(-J@I#cPcQx~d!A8ay}e%^mU%K5&4`%p}bfa75$veu4y zN^HS|vMhr>7zO|NIM`+kENlK+zH&iZnZGBN?&_gM4s^*)Z;#|hmDkS) zY!~UP#)Pwj*dh>{L+P&9#{XpnuG?lPw6v+Kdgs0A04CZaRnCG*G@zEjf5iSBF3@O_ zxvIm0mZc}n{b=*2ovSSKrw^r@TmPG%m}eoTuKJxw`hF!pst%tmVe8VqDzkUHOL5eF z&DVCcf$UpFKdaw`Y7O=I&&Q!)8>m@NrCQ)!SB(j*5+nQP=68g+UP_gj!Q4`8!Nji1 zD(dmx?LQwi26u%q`?{(A?wcnNSY=@0Lc8$X(f_vgzV}VR{9QklU*Wz|eC+rLN6v0d ztttcmBX;vxiJj^FRdKUS)!2dwalgTgQ$`T9WRPl^#qm;1VAYIkEoeb;$bUXQ-);nJ zw|J?%{cP3Pf{7u&TF`q(L&$)%<9tuUws-nqT+c_fH1a|zCa|imcT;-h+W7x`ut;67 z8{((R47*T@Etp7&Z9pGdM*K${Dba?!hyJRBS`KP#!Gu<@Ha*`khSYFf$d9VlslQqO zj)AJ&o_9+zfmL%{wP|4OnE!mVvb@3K%g3pVN}SZEK3r87B&UW5BW_3WQ()Jg5L$mRJ>dnWBW#uJ8SRQ)eLTE5@;Be3<}6IK0eZ3; z|94cIHlAV~Ji=AQ1Mdk0R^fBv74p8#VAgW1s&~J0r9+NosAmLDullc9@7Ab|Y_h6; ztu%^Kg#}y{2&}^A#Ovccv}KJ0 zl2w0yEGeC7RaYI>_51c`e|7g+IV5u6aR(mb)!7#!$2Fxi^ zp26&J9~e+sL0=hK0JdNPMo5be=u;F(gL`iW$z# zuT>ks7EJ8f)0d_=*~_0z2q*M<^n?ShlUa5bYk|P3F8}nVjjyzqjlXy2#OTmLaJ<}} z>8t9)C%aJkYjh8Jlz$WYGa`uAN$nvoK5b5)-W^H3itJ=Ra}!Rqcj*sL>J4J2%?trs zFtKr`FZF+9CmZIr;l$*~egI99S>V#f0)bVb8;8)MLG9(hcr#AS=sW@md)!*QJol=a%}}$=6icoRA0m!KGJT?4g+gumuzSQ$y&4 z6gxS2cmq!8HyQ$dPU&o?lSp7y7t>(+gxSg#<8?UUbixU`uGqwSr#66ta|v~vU?P`a zHlg;72hxjkTgX?lYSLs66}A0gF0XiH&56!2&M<7!dS)M}2iSs%i`_k`+8v?dqB5R^IjXr5DA8D+K zRkPYo0G`id`cqm61XhWy=3jR2&}@-CZE|J<_hyYI*HZ+$f=as8*i%}@bZ+SvQ^m?{9tAb$*CUW^c%=f`&vTX2z`>3ox0Ny-b%@$SG z1WaHRZZSM#mdzlj{a_{g9P*1{3nuzyjH2xtTg$2DKe>-lL;J&`HH%mam%4xntimmZ z&&fRU0G|#8Ea!nXU<)S1=iF+qI|TSoXJP3)gDdKnunPBleC6lUAh7?K#;!i8E%b1h z!2Jr(nOVaNw0yjntx8uQunOOQz6wys7mTiSVf`A`5_)P(;NFf$E)N?HCl>vrZ;TZJ zfmLF=IxspA!lzaKzj#qh;QpBJV`(%L2IjA4*Y$5P+%kC9Q%bfpliNI8qQ-ZVe{F+5 zTz|WU`S!TTumuy9-NUI>hN=AgnI;RZT<8myr&qJO#*YO8tMJ|Ado81eLBozK*>JsE z3|lba=^R0GJzLAU`%ZBm*Qfcw&a;czjoEJm0;}-dO2CTQK3yBerI| z?JnySpXNk|rIX=jnh`TJSt$@$#q+?@>I|`K&rEc0m4js_^*ClB4-B8feH34e1=rwkR`+04Eg|~5E)kAA5l~yIHr(iHY$z*+rQ%3uG953HIe=hSjFox(dybxyc!f}szJTu z)u6Bi6F5qfe+m1?z~$rdZ1k{Zn%Yi({tK(bGyh~A2ai(5vrf)h3|laPV^w)fsv;H+ z?+##YO=tMGl|6%pFRgV%6BR$x#=xF49n(Z78CV_6(D?C!zd9x@dOtitV0q4@bS z0hVv?%37aM2<-|JI0l-(2g4J98n!m(Pf=3&Rsh4ppp)bKI z+>h}%86M?r+h-OnviX~03nuVx1^xv&H3b%>ThsnQIzpd_Rd|;NUn?q1g^1P%)!UrT zQEb5k-qp%is;9X?bI)DOH>r*=3dbXFJl5uQ`;rF2k%%Iu>QW($!ZE>f($li5hO(*e ze%@c1>3GB3_-$-S_G^K_Dm?Du`AdEdg|79tvbQ>ygb^7gcn*A8ogM$vtKndLX9GK8 zbXp*=3Xjfs=E%*X;CFU>Y{3N2flsTmVSx~3xsVOMb3!1n3XjediciafA;5kU8=bI%b>0TO>J^Id0su)s_%0(ukt{D z*MGR*#F@_it}SO=p38|1iY|~`Qvv5s*8pt61g}Fut1DD=_}&e6AN%hLBwEPj0eO*+BX;WZ$*xRyX*)#U*ajn8~Q zrrRAU;opM}VUSe$i5{48T-Zw%|928SrPo8AQ~$9VkIwkaw)r?%{;C5@?|GVG3nq@- zNT74Cb(Vv?uJZG^xqBS6$aQ16H4X~|R^ibZf1>DENLvug4)vxCTQI>Z7tk(gHuCIQ zo4JplS>qw-TqfH%_&}>`L9|d$g0UIX zSj6Nh0)bWd{m5qrXH9}i-8@!#HdJ^IVxn%H1X`KiRQ?{mjE^#AmPEoxo#`z7q?vq>qc%Ne;baNz~8BkBI$h78bkP~K4fg!HhEPj+yAg~ILK6u5D zUXkGDlgr{a4iLsAn3#Grj2>V6leA%)tV7z1qagTRI?I0BRUoj6S7iJ%ic%>0cAWw> z^fK6)10I@MjejhdcyuV3?!NkzY|GGO*f=*Y5u7d@rrwo38L!nxf7bxywE^kxnuEM9 zA+4@hczt#pBpd3pdqan7>JR?0V1idmq}6p4XReNfqkKP(>&ZNUz^Z3YhSFP8PLiT} zd-zdB+fRf$`zNw)GZ!&z!NjB}f4bz!CGxi6B2LUZ7Yv_#=CMZKcL@Ym*)R2`r3anNtNMQOrSpB? zk}bhmyp`;88v_^1wy-DeYZ$g*0{583ns*#x@miVFp?-+FpmlZR(0eVR=PRYl`nmaQS)!-r*TkV)Ry(k z=*4(tO8UFvC9i}@e^=P#RXC|opA%4h&Oa7R@LHV|)c|cC4F=yvu$TUP1dIL)tHidu zV0R3}+xWAb;Yx-rnBetC>C-=zNqbz2hN~UIS-ZUs0)bWdx#6Qe>v&jiJcP{}E`G6K z0`DH;bA3nSVeK|w)_BBSO@-Az&mdOeuNNL|SThOMn9KZ$$`p1~VM5$j^r0XLd{quC z@NFl7z$(1|i^t;ho&bS|7qFo{(i!g6@cSJ1L<&V_$1t$Fyo}Y-%3;`o3Eakbe|2&K zyg$f&6vqn$R^gsVp-8n2gFbXA+v%OlumuzNS>Z8v{U<_$8TqU{EKMM=3bzGb|Dz%d z#_8v?8DVpTdyWbG%=0QSS0mt%NithBC0ih{3b#=H&1pCpyf%$yn_lJ!Z5I=`@8WMx z<5+0U=k(Wft*S=*=lQ@Y{G=%qv$`k1x0ZF-Id7Hl3}OQJ!F;9Ru{i|0?_;$`b%rk{ z?P-kNP7-V9CMA`3p)Xvv68mk@(&@Uk^uq81#Okpo2i?cdtsz;tpH0f+m@u`lr&gU9dA7JYC$>Je zgYDTR%1?)McFL=-3;+Hk-oA z$F>j%tQz3di@x;RPVS^>MgY_O?ZHbslkJ&f3l>|t(e#o+V%mSEbUUsG9p$!}@At|Q zT8u*R8M=Vew*vM(z#4GNz=U|_&7O9G-4oZdk&8tFt8j}^D0aT?06I?(vM-V)U<)Sj zmF96|BQ4>d+)J#sr?o&}mDm#PA6kQP(Jgkiz8PQ(Ch+~|D{)OM;II2HSiu)lfxxN- z+id8G>8D9u>c?BV&QmLx_<0%Yw5p5n3^u*ifp-0}p4=QU>3^J2Dxk10&s3KUSXB~uG}hSFl%|! z6+)(3sEziu0&Ky=p;ancT`BfxXJ;6tZ$)RnwGarb;?-UMWKZLDm)h{2;ZO=~-_T4` z#r2N`6Ukj-gdX741jvUwV8)U6S%U3uP^hxQe(GmkSa#^qN!b$k;ENa zrGIwzp^6`iiKSC9C%(3JhjTe+sowf#fGwC1eKfu;!{m!R2ZTpkz!~1~5#pzrM@!$u zyxhBkY-^$~v_zbJ54SPC|GcdqB$uxx5AEv$wqT;Hy(`_mJ(v7-{20IIbf_2DwK*Z# zbZ;yWScTgd@8Q}Gfh{qcB`cfynwrIbS~Vtk#ba7sNqO{T52!t?A$9!NR3NYl-y8m} zz2XU81B~gsBRrcfYSozFRh(&cedho^57+A9LVD4DjA08VW=|PHt!>gs=Bt<7$2^z_;XMrHqQ7G>q;$8%wcj(;|i~m`I=COFc58Nw=o2I5FKb0#4Ob$=1hL3j|iJJvW>tT^>*7jMm(b ztvC3Y`}xSP$F5=6f{7PdLutHW7-7kpYgL&L0Ub7l$md$m69}w|t_+~{n+K9rm;UC& z(kBxjK0jIJN#Gf_VB*p~e?EQ)B(n^ja>BG<1RQIVCGXD96bP&m^SwH?7yzfEbC|SF z7jPC*oSoEB=|ay>-%K9X-^zVl?BoXS6SJBB;QIVsRc*n9*tdK97zAXo2g|q669}wI z-P(^%(&5>yJ5%l>D#8N>G<9ar7d8NF!32Jn@EQtFhro*13flaBHX|kR^nC%Pu zi!Esj=X!uGn83X@&v{mV1ek2^CiN++ArM$4T^~SeyyRJEEv|4M9WsW&hxl>QqR+Jf zTQGs&C49zf@kmH=%OY+&{$`lKs@97J(puZ65%n2O1+W8MM!<4qK4C+&09!DD---Nw z90-DWmY>P1>2DY&uxf3RCtX`3jcDDx&V7_dj)Ycg6movc3WhD1!0&dR4bgKnyuZ^) zHk*G}Ah2pt_7F%3ohf$?{K_zaRp;jQr^kOp5ar07+{eN?-q8L0 z9QkwTPlhd+z;~0^H}LX-iD%c#XTqKc1Xh`444?zbL&%Yro4Jp^N!}2ezeT<`=rzL@ zOyF$Vyehkm4?GJ{%Z;915(upNGHM`AH4h}U->%_4?l$*_bji=N&P+9P{7 zd4IiF!oGP9p_3!Pwd-E_ic^W;0~58iz3I<8V@TzAP2cXG=g;@uZIxeqI3o~Pg|8tW zE$Ie8ar`Rzw(S|=T4AE>^B{U;#{_cC`v~{3Gr=FyKNrZGCf*SUtipGe=j$sQ0k3Q4 z$a`1b7VbGFo;~xRRxe^m$h70!huNuNP`Dsg9?|WcKwuSap***G#ZZ`M>?v0m{9xFE ziI#`@(tr=si2wC{+{c4$Ua-#0QqF9qFSK^7!q19A(e#r$6fC$v&SV-3dCxK7>Zzo3 z>uln1LUYg0d~|{*o?S^mv9&;8mG}%w^&Mg5#=Ytk)(Nl$6A7#B=pw_#q~7|O+{ca9 zGL%2GQ0c_^Fvr#|R8H$phU-32R*rL_t-||}h$kDBYZeZryNBD83d3SPUvhAY1e>4P zs=l1vPM5Pm^g>QgGSI}gro4l4gB zJ%%lqcpB?MC*SN#lxh9AkEpAipo>j6RnOdZ0)bTxyYs3m`}~O3DhE#Fy0?RZG2K-K zo|752U}9t!dz!YxpX@YU#)+V7t)NVssG53C7YM9cGqw$_H!6rkJhtP+ZqL5Z`F2Cq z9hXHcq;+3fvz%9k>F*@f;@^O0I(n0Kt=dUR4}EDxXNeTtSMsZyZRrZqug0omc@o1G zObj4H=`W*hWN3d)zP>=>1@E`&tG-)W2?SP|T87fo9b1tGnL6A@6mf<4G*eYjlP0Bj z=N#VWC+?!Noah10M~qcZ>Bv%S!35sH$Kx!I41g&v%~bJA+fz(nRi6Vx>3GY|WI?l` z{5RZoe6h8;}Y`0zrr6W%@BaOO;@iTvS#|wUJX{Z|6Y8u5BOyKLrYq&k}2lE1L z)ryzpYD{1i-sj2t-323H(JL+0xmLLcu>}+2Udz9C1;K3p3SO=7p(7@+3hy7~^X(0t z;N{L1s*77w7;dk)m%y!(@0Km@3+~}2sv9?YGi<>GzJ`2d)OQe+-fO4|9b+I6SS7ah z>jMYFrW^XI4fXC&Y{3M+hJ0qC@dzG7qouO&nJ*An6|yXruB=^y%vzGd@1Wk`K=8@^ zF1yt+q1b{6d=2^P>+KMz)#;Ahd3G-~Ca?r4UV=S;bv%>ahKEpd$z{PoKB{Pc{53C1b1QE><1D-{#_ zoW{`|>s(2LBL;+zkYlI7JFPHTdq;>sU={uf=R05aMT5o4QF6b>F2dI~CceE2rY7G9 zlh7IsxsR)Br@-?euCniwbb-JsJe$Dh0RD~!zrxL^dn4}S z%hW0GXo98u%3-!ZU=^Mf;a{mgqIuO&Gx>9?L}B&=6YA|jba6;H`Dc^HNAu&+&^}XF z{-Bd35LhM76z$I*4?ov!qIXlzGWR@B8n>^IoTE3T@^;=dD|I0`v+t$U?eP%0e$NV$ zcj6=OuTH+40I4<-4bMBoumuz4OMR(Zt9fMkMFl^q!wq@)`Zm32Lz`V9fmG?dZ(mWk zggl>8ixZ9|Qy?>IgqqG|SaZ+4bH9lUK8(HpGEGcl%34D6bnqu$bWzCd8r*SaI< zz_bNq^>ocWe{K~A2@6L`-riXZTQHIRI)JL%=8^~3G?^)^hsQv7(<`)tZVtn>b|wV| z&|0Beh+{iFBF?0)x-l7COH7$kZ>ccLiHSxJ{iy8=HCa}vsp&nIgo1~A0DE`wfIwgs zp2bxtQp`q!RY?w8;(T0~-^IifeJ?ug@L4kGdII;6x5pP2_TR)D{O$?_Rwd~5qe~uK zB%{E96WM&1Q14HS%_?}pumuz51+KJ_#T~NCV?FQTCg1N3bHChTEB1U72&@t#=oZfH z1GTq3WKjX{8Ma_TyKDfRcJ%{U?$x7|uQc?L;rO|C%whRwfxs#p@5kr#qx->ME{|A) zRSy}qU}Dp2FFJWkP1*2Q7d4+%Yt|RmE_lY`@4gTStin-15eTfp(Ug3?@N^lh1)UTiF7*&%)0r}Ev}syR^ga3k?3Qb0F(Njq+S(13|laP>)@n85L6{EgGW z6T&LaG5?^e0)bVy<@0QBTYVwcp5n6009k>NEc{D#9T zO$x>NW8-1qy;oG~e3D@cCh*&iSG;wd2tVT<)3lWR0)bWH3f4Ei@{{bimX?p-#;^qw z_-&_9xP?bU*JiV6d;J1|z$)=M-#jxG0?t`bLvQgNg$ew&<1-U_3Gg~-zk2eWaN#+} zD%{8L?~iZsFt>@GblWsS=zTCDzB$`yCxX?$8N~LCCo7}Fse0>lGVQGa`Nv{3-83qh z=nQU6zFrKXKj%#&X#tkJ_nFuy5x%}JBIQH-GOWUM<<>Fu(27Z9+d^wjWCkR|%ECtS z^F@1Tx8QNql4olf#jHsU?J%0eYklWGQxcKbr%Zv4`?ckp;WH_=U_z%uC=KsFoP4sE zxDTz8WZ0VWh!|PF6bP)sN6TZ+7pK5^ld~jqKBL%z2~*p#)GQ#DmFl@p9o7-dkvo6jK2F$A zfJ5UqsQa})E)ZCSN3wiof=3%Rc%P;0I`9C)7EBnG`O!HZGsz67$y>>+)>B}udml;G z*&q;Dg-5aq#WIU%7_wJ~__bWZumuzN>EfAH*T=%oO(vw4db&VhmH3=LdKM20Y<$dgU_xxWsX>YGFtQ2lXHLS>fND3sWHJNqcf> zL@j~9Dm)J2E7iIoa6-RAZDetu;ronZ4e-6;@rnHXQSXu@1+BQiumux1YJtB8*+j5) zTrcS^rUHRg_}=hY9KJ)LR$y0h`rJ;2Etn9a6LjS$NDJyuN*AvX2&}^QhR4=w$3U-M z`6Tp9zR*)+0!Ksex53PKuy|5LeoPM*2&}@rE3YMVFdoM4eL(!D`Z8?6g!q;EA}|qR z=G2o<&NLSYtipXh&uw@k9*p}mleZi8WY~fU{8h~7cl8n>+qIMY#zI>luqtQfcslry z8#$ERnm>a!>*JxFPj~tJc5{X;n84raylUvu1eoT~kMFg)MKOU@yY7Y4YpI0f_tv}z z7t8T5bBd?D-bI&T3nuWK1J9t$-{*pC5ew@xvSjJU0*Wn|z?E=$_6sQv zP8`UTP3G4T2&@w8@CGOnpk&bmS&jq=TX5xG?3+h_UQB=udc);|ox2ij!9>)Cc-l0w z1~D0BjxhT1;VCmoL3 zavz@_B*2i&k@E94H%l;qRk$tiI_}F7VZM&1d`D-Kge{nO?HWZBo;M>mjqJFO^AU+~ zd-Y&>{fB%tCa?;(P#zU#o&@%#F7myool0!M#J7^k^!s>g66&X^H_=%;30{>s%jItx zh^-x|@RP>#r0!0F9r=!O)AO<#Tk!vm@{FKq1G*5?TusJaX<-s9y5Ch!Sr8~ZwOEDw z7+x#IIT`MZvXui|zNoPU6YU#LpnGC_k;{8EqdvE}$#8Xwxjd|-y)b&kDm*UbZ-e`x zu-9#^tkXS*tylZfg8WfrO?J8D{CFr`JAEiA<&iEuUI)`ly`9LKN6+}UMBgtQ40dmk zkJpC*n)|n*-`XSa8vT3qbA17ds{S&IlDkk-1%LN39Jg~okY$0{UhZ+*32jFei#Gq zQ)kP!b^DfJ3np%CPoZ@yUP*II-*X>zhsVR2$Y}Y{$4&$jSao&jRQmDzereO}8r+9_ zXaf9v6d-RJnMSY$6HU%!&|X(INegek<37x7lc0xD2f3HuA%VauoSl}(>1!o}!}$jC z%dD$HMq5nu73w0deUS_ovJa9A3lu`8Tdcx4bNL&mTM9%z$|Tu~>Im6%1p?J!=6MHu zx`6F3T~)hr8<@IzA8P%1IPr4!lkj?Ey(d02a8)ldFkvV^^CR>6LtL4j%KBCg!xl{7 zwMiaR^kFa*-mk5C`ns<`V3l`X2yJuMikQR?;yyO~@P$5QwN#()HDTC-3A|dv+iuE8 zAp5?_c6EVb0;}Hbi=p8)Ym?+?L++!`n;^L7_EA=T<$0Wu1rvDfg*SE>2c+z}+{Lbe zKw#CFpXt=E(?zMjRxY0xU7QgHUD}?N-*m`RV+$t4b(}$SCc~3vJLOA__8r6oR^iOC z3dOaNk)S<)i+n4mOvovV2{GTRUE?SyUb0$#sDDx*unOn1y4$WSf@YlS)+U8;Mn=Up4TQD)@ z=5+dId5|=rvL`2=txSfFl_v7#13m(QRX8^?-=T1q*ElTvMtrO~5p2N(&SA_)$Vy&U z#xj|VOHc^}R*5;6Q?{kSofs|h*4mt43ns*T$ZL9zgFs&?-a!ZR&Bo!Lz|}6C-Rw_ocLa6G8os|DOVhtO0fkKq2J=D!bgYvA6I7{ zPt_Cu|6AI$Y0*k$Ns35|#JzJ4EhLq+2uTZVq9`gmS+i3}Nu&}s z#_0>TEB>siXT;N1kc*t@(^18te0S4@|gP$LKpl7vo(;PgX#9`W`ea*4fm~u#5tEpOfH{S zghi?52Tyqh(e{}h!cW^^j({%MGhkoN&<*r-$F;)jg9Euf10>Rw8*oOC_Go5v2UbSe zgmv`w*(5=`xR(U~7j(fM4l83!AbrCYLN2y9;d)DuFfUz&^`;I(UfQaDiS>{*w6x6* z!Mj5}M?e?s+p(48<$kn(c&|sS^P;$u7vb(@cupW2v5X9+>G77NW%pz5#6n2G{nawrKUoOPzA}Wo zTK$A0pbMVPCzIt~45Fjvn30a29SKw*0r!cs=kY9r?mn(TENh=|=k`GtJYP>HyH*oS zPuKM!LZ?myDv*Ht-Pum0YoXL{b`u`*$x9C->t)tfG&70olN%qK`4!zR*9`m+7PHfg5O!ZBO#ocOq+_oW><6P_CXgs zsg121xDiH&dN^V0o-G(EkbpCPtlvI3f|{Gpm41ip;Rxu0r?au#pBdrQbf1-U`2B4R z6-dCjNp^)KHFqE_lKj8{_;4rwha%ipYg!7%Gt91DB{{&PZ!H;WOvy+t1 zW@!k4wc6ZSThIm1#9}M3`-V}=$9;usMR5wKKmv}V*<9+8P&)W~KS9lD0e5B?bitFT zSdNsKP z3lcC&!FDKAG9qY*pvW)b2R1hIQ{JeW>@GEVsEdYn672@)`hCzFlq z%;Hx+^#$|fmmC3I@N6Eog6>E#-PglH*x2b5f(j(Abq~jfY#S5_2Yay|K$A%bZFOmo z5T)J35zqzC7-Bmu^p?{X*AEF*X95U}^}ulgjL)#K+B$D4AAVHGUoH@+Kmv{c*edT{ zt7%fq0pZx~Mhpq)g7F#FG92-vrfo`v{I|InDv*F90QNja2hhNYxkB#5G6@pU1>-a9 zRK$!xT3DDaENy*Q4i!ki5ddpT>^IN=gFxY)avXvLbiw!xJC7wOh$h~57aVqlBB($D zju~XKbaw8N-|S&R{I&l$0=i&)M)eM|xX+JHLX`Ri1QkfYF@sD-&BAD$>=3%=-NF&j z<-A|Qgi-VDYf;1?nE(|?*z}6WvmN%xA9~(r#Em~L)aTY4!QoyU zak}Y*gQq#6IVaK;Ev~chM>7ZHaU@m&*FCemgSPH;-R-wR!bLX%6-XTI<%JXanWE{J z;#nCj(>!U7{UhPj^IjYQUHp3L6Gls@k=8@uVEAK=vK0ux5mK3PkD?b$928M#3Y6-ZR9ipBD^`HI`wn^|m0 zM{fh25fUQg+bvf>0=iCTC*a!RnTiVQG!Ijngo2L*zy0KC3G}{eb2o+ z3!iT4as+h26P(ywQBDN?xMm@;sPIz26Pe&?Q2eiY6&gXMy0xgmtDGwX5-{4r)}(5L zQ#0us>UH1{M?e?6hwQAz=b^N8fVS{$atn8_AOWLBZ0_z)5FPr>O{g)x#Szd2pDc@) zOx{4{_3MR)gI{sa91<}4C6l=?3ZSFCw+gQl4LAb2U=3yaITO}UgjNdIa)Cag{};od<=z&Inz@E71i1MZv@raemM z2~T*M#Lx$VPOy{sn1dlQEaS1QKxP6Uz^`XfjQI z+yhx^4B`mrg4tHsD({!m>5Eo1=(kdn%YFd~xPyzW($kzv(}(mDG;mvvfG)U4m5sIo z=Fx@^c0%CiF9a%(fIHDx>~;7eYMHrG_&4?zM?e?9_tkpiB3ijIPB7bYfj|Wka7P`B zy;gft-^J;Id&7Sm0bP8Y!8LagE%eC~BK98R=DZ*QcLuUmVTqnp({i`qnOe*d&;|QM zY(2Gn5%oEAP)J|0k3aA?gezl$}7SOSqgy)B;YP6nQW^0QurN;?IRstzPjc$7C}{Ko>mklAXl;w`jcm!R+E%YN z|1~PAdM2@mSJ4N_-_ee0gz8YJKw_=KF=dMM3U!!N$B0Xz(NgOn_SAdoK#qW}w5wC} zsvO^a!$3f)1>og(f2m&I&K>ckv^nb&>P;PD0IcmXr)(L zb{TcOZuCEhQ%mwCtFfbK;eQqs{x3-Qxz;Gfq-vC;wTJDr*z#o<&TJY=qkC9$1awJz zZKd%_B`R6ohY>ZMUGQ*IZJO^ng+c`q7MG?-PB)IAyp?WmwWExk;*xem*PBMCEO{ZH9 zrLZnRV*6{X+(cgu68;LI#U>(h)m0=i1SDx@oSt|GO;3P#v0TZdPjv!IWX zM^dOjVtu?Q*@zd=-fwLgu_($HFYp*eU$nQNP=SQ`weix1#8W6*znI-!qb-%#=eZ$$ z_*vu#=xUytDZNujsB`}h>|V8BqeoiTjiZ|0!|BrJNz&3W57Fw%Y$@#Orin;n>zHT%Yx%(g3@`906Sq)cRvbhij<6yAC7Tmz$BQ!cnyQ&yf_~ z6L_zR9-fdo{Je-R?s~}x@6zF9`3Vym-^zkQ1rmW7l63sWY1GFqm=TBGyOa1jUD_BU z@C0yG_HUBrXkw&3w28eR`Gz}5+gq>5*7tL$cmKE2NuMh8A$7W3diFueKXm|I&^#6-e~A zY>>J(9zZ*_vKcWxBZ++Iai28JbLR-?YTxFw^tQPKnLDfQRl@09l5>WV^BD^%R3PzH zY?i`D?nU_n-!j6}?l75Dluv$zE#?U5I%V4ypZZgXVrzP^D{po1Dv>^Sp!P~c#V+0P z`O;HpL-l1V)8QR(`5TN%4s?>=dE6aO_dJ10-Bj1H=wsZo83M9t)tK)CC ztI*V_U5xm6ppMkdYay|tZ8-wECXDZi@2ek1m*pQAQGM_md3L3O?0hth7Mk_Ke|MFj zi@pOCwuc7dH2*yaS&ml(57oqmcMc%)b)DFCY@05lbNU}7?qLoTDv+?w8h~rhm!L%( zM>1kwr;kJkzd&BEp288(#s8`mpY9MtyJsY7$rK6|cpb28w&u>{I(g9YfH>`(#+3ny z*;bu!MCAcwbM!O2a;G7WNmE4)No{cC2B_4;hlC^Ly`$^>9uIwDp@f0eM*t7VrG&A-%`fD(PJr9FZRm38+9bNWq z5=TH6e3~p%`jQF~koA|myX!!q0*QiKGJK%$5Yja$V`WsH#ANf&MiOD?$Pv&5pQcPU z#rh19=H4J`HM1yGATf7pXSRE}1kFh3$nKT8{{u2%XcY;aHk%`$3qF6DETr%QAr9Fj za`7Ar6-dCR$?|0!RikrAI0@-FlOv#uuUD(1JJ9_L+{s!$Ckhov!1~7GqH6}zp|t~v zxxO{6tTMz$bqdk#{mT?zIt;_B_T{1d#{(2F62h+hjVax2?M4nbWiSqcGJkbrkYCR@MRnEHKvq1f4gI0CxLWy7#b>rA90 z3uR?AYZ|gslr*F#pKK^pAOY_P8%_Mvqr1>Ef!3gO7tN7F?-KnRLbb5{>|ib&NvDcNYoD0 z!t~@(^z(QlBYy5|N1bw?k}IDqIRd)&KGMhi+E$_kO9rxEbvHnb{_wd)JX>2+s6ay4 zp^c3Pm7@){Dq?R%N7`gciT*jBfUfco18ml}6q!<6MjU$Bg{|@~AvI|eC{!SEAa)4O z$=idB#;aE2j=9#K4r@#znj1xqfG))sQ~YXHAsSw!dZU`M^=W*CJMn3UC{!TfW?_a~ z4&|Y*^>K_y+G4`?j2e>HYb`hex+Y8-gYT@~hO7hARoC&SE!{Y>BVBrSD22W4&G-A^ z={L?HWksYF?9a2&_SlXz*rp9N9Aw1x+aUq#0(%~}d(s2SA7sQa zQ`DQ;i6kamE^kP{+Qa76)@jn{$mhg8$dn_X3uet{Ekjs0+QYDc96LOQ%Z?8TSbNwk zKwWRTQ|mm@?_|yq&;@h(v)yMSHR*82bJg-#ICmD2@ z#@U>(^&nc@E|F-ODkxMS0c#K2&5>Mic5kcLM2t!JI+` z5`4XK-!YQjUS&#Z@Hz>O=ZEiV&r^z zt~@g~PPfIY424H^XKjhBd6m@hI6GH%)G`VcNJx`zC=Wc^k0!4g$cT1JTa=ILyHaKNZ{%AdVIk&A3EFC?G~ z-VxTe*A5_eq^0DP?K;}-@D6GCiUL&o;*dPb>pw~VOCFlraz%b{QJ&QAQ4!j5r;y#N z0}o9|ddDT?0XzEzDv&txs!HnSR)G9%PcfqUOFyzGHJhB<<E@hbb|z8^ zBUT<6M)n(Kk+6~e6e^I|>U2aZKUaj_njB`tP>cEGx|l|Ef>u*c`4y?LRROXwyDOJ1 zx+JX#EJDpc&&dat9F|5YiqWKo9jfb?Xv=nfR*)3am6THe(eG=8RQg{j8njY%mQee2 zJra5ND(Ss?DMvt8i27FPwp}^$xIU5**ApG^gZbHHI-B)tm#ZT^R2HI-MH%vKn`TQ3 zT6Uqv#tgZK`ylB@)*j@yIFu33ikIQ3KE=c!oSmQr6iAd_o+u^0KS3}J-Jn+f=O zXNkPM=*tn%6($=f?Qt(brG5^K_}+6dR$Fy}gunNuP=Q49+ZobKt5URZ#1uvx+GB&q z*F7USAH6sNx?ah&qzjc5=+cNnRuhL#T7=)udr$7N{5Vj7#Gp^prTj|=P{5yVtc(dx zp7=>-Yg#YO;|S=2(Ma|Lld^Eame#ax$vg@bNT?NrNpJQXLgQck$9~oM*CjY*aA&&3 zWDZ9_7a!&H^_ZnR>TsB3|5#1?teB&`@NN&alz7M8yGbi0o{fbcd z-Dr8ucuU=I`A&4iWs5v-gNt&%*$&h)bQ>dD2JBW&aKDUu9Sf%~W5(zn_RmLkm$Kv^ zh7Zx5sF8=(n{Jc8>g%cu`?L+s^ib9IE8CUIkX>OXUi^)qTTTqny;QsnWuDHH=hpYp z?OB$KW?SURlS*8bmkw@4y$`8~pM^?gjqX^~pF~ioK%({P!K-Pg`yWvu>CDODeuM!Fsgrci+d)w`?gcWMXvJxrA| z^Wsqr-1M*?>BUx!Kmxj+nCeM~Zfr+Y~Q^o{y zUjs;_YCB6kt#_id-l}hH#IrTHa6%Y)x@A2_Ko|Tnu$=u4J8{sN(L%g}t?4|XFTK3A z869l5LvFFdRZ@P~jGpY;D{t`9mtxtyni!{wSzf)AjUyL+L{H6mXVn_z=kKFi*FN$3;xP+%^76c!axe!TG*n(n$IE=)orCQ)eFgC8bqN2 z3BC-^kaX#Q$td!=ODIP`7p(a#mhtPXv}E{ad_pIjLIo1=nq)E$cP(6$b_hSK=LzV7 zHJ`Ot-zVZ-9VO|-t_TVhNWeSI<_*pz;2sTCGSiiB;UEFOMC@!QKNhbypGDeD+oASx?#MK!p>TUy_bK^Uv*YBZ9%31TjYFC<}zEQ)^p1`AvbUXg$g8k;nzA| zEt`>VS_W%HGwvlwpDnV5iHF&#o1j+&T|IxeDSLFuWLcmR7}26-B6S$>N%($!5xwbh zNoQMB2KrvHQ6A8X=yZ-qN9twkTBLZ87OOvHPLMvwv3SCiZSm(vc zbTqDC;Qt^-^)iu08MYHc+PG2pzaUXvR<2{aG7X(lTgb{dyP^}m`b$G>3Y*0d&~?bC zL8&z_6~#HtW5m|OgQTkuE(-;@-t3f>dY!#nGEs+^L^-^sWW9OHX{|F*c0d#(p84#R zPLFC5*4_1_P=N&ewQPNR$#7g2_(zy*?7^o57FWvW zP^dtHzmA|Ef28GCSBNiOUL}(r%~L*!PD0%dY_pQp&QtdJorDI*KC&uWxIpL6w z_$(Xa*gcDqR&QD*jz4&uKt(B=u4C|D5<1p*yA}7JWcsyH($3Cn#cNv%xH2Gd?5~Z^ zoWvy5@Ggjz@$i=#E`732Ec1!u2oelQwOGl2V6d2#?Mk3a*LkGQ zg{4VIJxR}sCx)DemCkPs6;m?}2vi_3@XHXLf*DE3YQS9YIdYTPBW^$zlxRrO4e8Vo~xm3>8ScKA@>H#UTm(_d%Z#IX~kho#qJfwTZR_ z3FwMRZyvN|LK0ftL+u1R(;{z$q_NOm^l3Yg+P2QrNyth;pWm6v$M28U@w=If{&njv zr^n|hH*ZZw>S-FRmZZp6NW;52iCvENq)>sxizAUb$z{pt@QaR&Xn+2rRC8;tXdI}{ z5u6Lu7?#WX^Lhz|%@=(gWfayWNc1lA)@dA_jIMrq%%0$$vh`BXR4?&i>?;BZ=z{f) z?NA7~FJ0TN5TCRRr`-}Wbq?gEpc5U;b zs6YbV5%xXrmWIpkI*6C*`f&twrS5M~wo*?<6H~jgG6ufz#ZGJIiec;2DO4ZCrgEd??h&yI`a|Cof zywac?TA7IaT@6?nZqwrMW8X0Gy+THy0txsQuoaDqUf}t$0pi*@$sEyo`(SCQej+No zx7`Zw1Wq-M?{n7ZM(6gQZlxB(&B|RZDzMT*o6qT*R4L?I`?T(8bjSndjP9SiNAH z=yJRlSFa$^I&QG!e<=wK2sTpH_6s$*+fX~v`r|;3fG+qJu#AhP1UIx;iH8LfuC_x$ zBep@=abpU~$(YE>nC3GF7a5Hc$&8U40bTIjWI2~DY9-AbBSgKSR@_?)2_u&Roonk; zQO%vntPHKD3T)glLiGJqtbAIrN$JAssH*L=#tll}*#GnQxVi>q&+J4rx#K$4ihf9V zgV)-Ji%M4$2`Z5A-Z5Bels2KP?s<$*U)_$>7=?+x(J2@b(6x{ex%HdSZ)qs2CB`0x zF^%vI{MiZz&B6wATbZ=Qa8q!d}h=zVAr5XGBifg^6QP_JiIJ;Np(Sua<-;&vK zz6T(g+u=t)bj1VplPFXm0iO-qok_0Z?e0cmk|W{>=yG`CCfSWkLZ^nQYRRv)UvNvb zh4}l?2nrQQz&gfO8&>rtcV>$sA_g1*UDR1avvDS~A;x6S9j|eFtNP4J7ij%fulu7YS4#0oyJXd;N18n>f56OB_9E zb6l?U`bsJ4>EJDgQRlgHq9p&aQdAl}n_b6d!xEgk{XO}`c6C4n5-`dwlMS~l#ctuZ zh)&fqj)1Q92^*zH!-~W!=nyPPbnw7Et8{#r(%0tpzcm&xAGF2kF&j*%&^d^rNT z29!oiBX<>{KZ9~u8Hohq zBK*l?7BMdlqELYZjLESP{V9rHe(yq@y+Szxy6*LileDU~p-IE5SQ!JZmtezhJ&BG_ zD1{0nV5E?J&kN7u;TsO)P1nLW0=g`N;-rkmt;pc3>TIW{2P$xnb4r}`mF@8Z3M62} zQzo1Kvlch4`z;x<%np!%t`WE6r0ZHa=$+<&tc*=xkKs`pI^y)&a0(Sj@MGs)AMRqO ztY3<;emntPbBy98$uSEpUaY!TiEU5gn@P=zdN%(76-e--?QyrC;~VGBqgRGu906UE z0^_Akv73?WVbwD~@uL>UXF;S?C4CDyt8u?vcTKOac?VGlRmGOvuYoGiGz_d>& zReQ2u>gKQ=wNbwyZ~nbgS{BY??{`nj+jTe~={?Uu8y&7N;&d-PVrz0kYB?B6p#lk? z-~uV)Ob#+^Tf>N6I;O;8?@5L6Xr6$shW6#s<&9g=#lM#r@kQZA&iufF`J!bsBI=;@ z>v;;g5?m!8n7K>pzC8t5neCHjZI&eYx@1&sdYlnQ4=yFnC0B*=bBifdAo1{)Bz#d@nMna*v>~bR~rfB;c=Q{lxfS;xrBm z;UP;n0=m2sE=YyViRjD#%*se^h#{M2)(hS}JSbEk!C%L@QR!sO-}gdpo-;>4*XZ51 zrIT;sQGaxVl`&+%Q1Vg3?&t45&cD zz@<>qn7sv|v#NV#5HpUX7<3lo?m-*@UGT26^Eq8c6R$mnLRrEF?s-5W5FIFo!0=jav z5~O9esi<$@Rz`Gr)0G&@h|s(3N(vQ7Xgaz{mlf&A_MK{;v+{u^*}e6ape$L!5zrN9 znjo!Soq}dxR>ej4;ts_5?JePQ*QFFHknr$#lT7BOp|xky7;#~Q772d#UTCAafFq#m zy^tWKI74h`8Y< z8U9E@=U%z7GDa&}ky{T8#ffPGM?e=GU$ME=R`+qq$Npl%TYGLC1&MIC!BT(IRPLm+%^H++bUIR75vh6}J7(i{ z)h&X%*+PzhE*QUNv&d>Xc>M8tK|ORC7pH~Cug3lP;) zda<}z`0>V{i?>4p&N{FeUgO``wR5=WqjpFM$NkBJ)un}F{!i2Zj@8+!`=mjnxFJ+5 z*BT>11rqn!cyMe=0`i|;!=eVA;>VFg<{{$1*NGSs&;`fptQ9qMB|R2w5T&jkF;pPY zV`YMLO)nmq;?Zn8*j{THNlsZS&fe!tAOT%`4B*tKjU;T=YH_PpD1izj26Qcw{5Qp- z<(0cx8GdJrlpnvY!l`Ky6t3}sD|z_!K3^Y?kRA&e(%VlF6e^H_t9n=zr~ahWep|6( z;A5VEt~ZbBmBq_)(9bwk&vMBAE7GlJd(n*U5fmzrfU9~~zkPj2+<8)Kp}HoFBcSX2 z?0ZV%DOt#8mTE7C=1RG+J|l!e1rl&(i|s`oIuMt=_Z50y-oO#iWpezU(sRsa z6i}dAA++pUd))uwR^iR?016dIz&?rF%`NYygDJywC+wrwrS zz2{M=KmxWaY*q1>SNOw*&f?-uvpE8~I-GQqjBAoni;Zdq>z_wEA_Vpmo%E(qs6Ya? zk8DOU%YY2}q$m1o*l+}Nty;vsYIcceZj3uCV~?#B8B%E~{!^G!s6Ya?^K4BKI~zxl zJ606W8*v15g?B5G6glz8;-l&W;)YR+$-kST_@H(Wg$g9#_lnJVnFo?1qb7+%ruN|o z=*sO`B-wtCL*r(evNF(sGg>0MI)e@W=wz3uXycXmmi*t}Zl9@WTe)QU`Hw_`e_AIo10*9*c`fpDz}i$=L? zNv$`%#8K|y6e^H_Ee6YFF?GMxFDDp3T^GR-&;?iZu-H=C2dQsvt$hDee)SF{V2dG> znQW8e_2*+z{}DU^U2t_0%g;dV@P;8W!L*!Tw*(2;Vz7+w9Rl%lCo@6qC>u?HHBit6 z$GEDo!9pylEfKm53gT8%K?1fItS>rc6An^O7S0s~as+hoW9Riz;rN~1e&OJ8KMEB{ zz!ro3s(;&XRILxu`inn2QWr(nITR|8fGq~=Q-=>A2S#g(J^oJR z21*)CvZ7~NP-!mo}N)5?ZZs6Ya?7%V^a?I`k6v=Zw_>T?8iUA3-|Y=YxZMYugH zBfdF?1bd7ZyPoMwp#llmVz8M0iB$4H-A*i@(TyXZ%Y81Eo*s@tU8am=We6F$F&dtk9u^E1dzV>ocNY?Ur(o$qdK^05Du|WQdEypA z<$5A18;r$Y!;Lut zx;|*#kxK4GBb)uJ?CA$Cq!YCIB+rklOBqI0lx$|wf?`=BXz?olMQ zeH)7&jd;cSyNAzblCBqA#V@H(2vi_prdcG7T^@%TP!Cqdn^`dg|C%rU*XkZeK-W7q zDt=uXkIL>dI!}K%FGQ+)P^drx#GhIG`2VUmI=WPv&htOYZ1+ab;Mios;fHl%h-7+qm*rT(l~de621f-~5+T_@T|8}7^cb~Ffb+6NQQlp(lhFh=T2g$4L7mH}Y})a*lwm4WDH=%%cFc zgsV<7PqwKh2aU&&!(=&y3M6udwq|GEv)R|Ny%}NA;So7eFpQjvSWIK9I^rvJJ5kaC zUB#cccG${1A1&>mt=QJOGrl6rL&?X6F`{wbL$dW-8sxzr1a!@s*#(DA+KTK#M=)ag$dTldb_Y6Am`$g6l}bJh$B_N@Gsi|` z9FW4R521CFy31jX92OniIf3*&`jb38?@FNp30Onfh`y&M2_F5CG~aUL20L(RzJ^GhjIAi>wfCE+(oZfpmVyM!m83)UDGPgL9^LwfI)KE*DhW7XAhX=66p zBr{Za%~QiW2IZpU^;!y@*fx0a?kqIkPL-v=^!Z_SD%W#7%y1P|AO1_SoU$F6_2{Pf z5b!~ozI+FIdcBQe(biAWtxvfK*QnmX%P)G3pzei}69%OEmVF@qzZYtE|yxb@?0DE7`A)s^dYqE@qYNbiBOC{!Q;bMmnH!Lyy{ zs1Ysr^Q74v0bM!^`s08;xoA|c>8y-~$?a)z*jJpUKbJxU5`4CvI|tg+RyAzDjD`zG zK-cz?-gwaZ9JC`&l|yLKaSJ;1qq<W$qsdfG^#^73J$X72flZg~6 zkbrqjSmrPNLDZ#N7lh_a<_PGje5iwMPG=%z!y;COLuh~M{b!TXUUw>m3MBZ9C;!xY z)408hm6ujJas+hUxS@q->183~!da}0R%M;3NyrA}f~RvRe72u@^u_B+HlzL1>=it5 z#ko6eO6`fl6K7JWK;rM@0r=LG476jZGb>}eR&Tm!kS5AAa^wi;g4f3~g>3Cl_q@+V z_w*gO>wv`3MS3{qNh*rnp~}X-$Yc=p`;>$9w%Tz7biwDuG8Ou;{3SD9ph3;!x#t0i z@$QEBs&6tn_EGiB`&~AqjlUlwpUEOeKo_iUES6DiOb2B45jhfG+snu=S!zqp8-*tTEJD}KbBbck_5S#^Uotv(bFyOI ziGets?GYH^qk86j#`L8Zy(S3%wb)UpKtfwb2k&W{h!&qx)x?=L18A3L;{~lw6FCC9 zRGCR83{FCuG8Qw!^_dP8w=EO4#0vjAlg|HBAhFTO0N+ZDM^`U;Fe0hKfErdU5xz!Q zaRhW-csUdg+n0b+udianBDG=kO!pW;BWnzW3M9^Z8R6Q_u_*WL3Px;AF`?gAZxmYM z%s2wNnrcmOmM)8`8HK2R)#bi)lcW?*9vVw;9@NA39?@vTVOxcX!vMVHQY<>sLr^?g zI1tBIZe;l&#xNo)UW;CFy(Ex6W*h-s##i-mhhI(A&Cu}0tir-pF^bn!K@a?42C)v;C>dZ#ZOwLTmHUCo{&aPnh6^dMXHer(*XM~|%eBCNTl zMWF%-zP7L2Fodq})>iCxy9-A^*UV{V*fDV>S~tR&m9gSYH#)JyHdH-iCWT*1*rLKO z9LuF=-HX00e2o@1O`}kO1Z-Vddo{E_O%z|F{gb9}1a!eK9P9g752V%Kw1gKcCQ+zB zf^Tw`i4pSd_Vj9}W5UtDGLC?*Ix}0m*wGtlp&UlIKAKE7y*MxQms$u^AOYJhw$|XL z1I_<+L+EksDMvup_9u3Dl9eYK@H35-v2(;^I`aNQp~Ck$feIvG>&iw&Po~h?w=adP z;Wsz}x=aJ@@xWc~s9}-noS*1UcJ!kEXW{O{Isz3)q`k1g`kNOa{~z9r*p_Bb2UmR; zPA@pc5zw{g#T4AM$r(lVRDGST(kIdO>aE2mO{WP|AOTOjmdT3R>?5v?AMo?$)fA3? zBX_=#PPWNIUjqNh`H}F4Z@WqTtzxX{=TD&miP4#_r1OPak;@u2_N&V8mJ#z%1FWQe z906U&3%^KR)3cF*XJ<7Ri>vUR zojU;u=)#x3OE=yoBljn58S&ob2q`U#5uRHvrBH!H-Gz73wVO%kMnE%*avJSblC4j+ z3om*s;t1&aJK(2um+kq{a`?lDG9>|b1ri(QHArjrY(r`eEvyXuEtlMRd>B6(#1qg3>zGVt zmY7Y1qto$?x$I0KP^%$f-S>esaz+li?f8?G@wQ_=Q7rwgJRG)`BcKb`F_!(pV;jjR zYlFsqUQ3|@39s^pQhvuR=wG&~jJ4MaNnOnjl;3j=M?e>>V{G4D*L+eb`-Wr*{uC;Z zDD3lC%D$D36wg)n%06fhnRU@f=(k}NM?e>>V=T__u#gzm&J)B;9|{#njGq2PQdFj( zoeghT8IP?>$n>^x!Vq?TA0(g))-jo^=Z`()Lt}w(bEOxB3MAT2dn)A>CnCdt4XljL zHV24fpX0*%6&@S`U9eWNlN~ISq@1k`yPfIFMF(MPm$2-QwEKDv`rO=;y@Q40j*%<= z8o2u4Dhd@yz;=wS3R`xPT%Xn?KWyd85zw_F{+|@)w*{4~>&40#Q7@6ulyN9#zb}Of zBw#znGO^u0Lp+*}pdz%ABcN+swG3}G%s{iVG+7y4uAC$rN2m!okG&~WAOTw?wud+L zJlXqtgy8ADj3c0{-@aDZ_FD?-rI>tw~ceTAtS{6@MoI2}Gp#lk5d)O|z1vkk~rMIsgcKDNu zhVIp7Wt61cBrab@3I1tb6e^H_wTI;?8hoF)Eb|bC&0WY5&}Fl=J^pti3DuA3%gT5j zb%%s##t3?a9uz8&fVD>^>wEMe8L>WBsG9G}5zy7nw*$_tNkFgucWvMEyq*Nv9TXz{ zoheix0c#J-lwS3iq_;UEOzA&^BcMxLUmY*J6N}E)sZOZ)^{RpBU%w{|+2=r^0tvoe zEpvTJoVL6dMwn0J2wgJoN#+8oo!=E_?%9Iy{!xn8 zLPtE&do!A=9I80?NCQXdXP|qIquH-&tKUpe@@-_dash=3BxWw@gsWLB`;u%ZBl@`i zCY$Yh38q`;aRhX&?%o}%SEr!H0M)4r{#(A2x4jj@ty(t<6-b1v?~I4AwY5)g4Q526 zmW;X%Um^%v&Kv<<%_cptQ$!+i)>oZxkXHJOxP6Tks)}Y)s6gV0Ul%Md*o2lT1~DSm zxfM;X%oUP#9618I4w?1DRtw_M{)Iyr5tR6c^e{RgJi9-YLIo11r**|v+vCvl;e8mf zSk{`h`ay+f$+jE;UFUjf;`WPU(7|B?7*P@Tm;9-!6MouFpiqItk&YU8<*{hgDofQv zUM;Xpp`I^j0 zUhN#&n!bJ2MqGM#1V=#ElAvCAe^nTouA^#qd$xW?q8%y}ZcCPMvwg6&gLRC>ulhVD z3xD{dG384rR3HJ{F;;g28p-mG60jX( z{j2+*$@|{g68eb-JPA=gH=z1M=LHg6Y7wz<^WMzC)pG!KAEGMRWy(v^60W&tU zxKFnz5|ETgj@0{d1a!d>8O!)SF`8U(TtR|1_;F)3NN^dVWx3xskqb8`kg|M!bO&8< z+{RW2^^77_fo3GHW-WyZB&Nx(N_E@v(Ai(l*p(NzN+3-WI*_A&0UQBcaNNfB#1+So zxrt|SOzU+NDv9PXv(Vmi?^qdO3(|;7^9RNG-GLkdU2xpSRvR`Yk%)=e=+CA=3Kd9r#?(pA z4rQV!XVrB)(%nqZ%@$NYaVL zqg4(Yt9b~04OVdkbir{Oi=;+uAzoQY!os`W6e^JTQ+P|7?U{_~PTXQ;1m50G`aIn& zoC#mT5zqxkdMu;$@O-lDGZi+UUO=G&iLOVVN)E#}A-#jwSs5pTOGxLM%ff`qZX5w! z{0Q>-J$7nO*>hq3lvxxikf3=Vq`|T{bPru*WwhR^Bx}oG2~Tuqa0GP0aRO`GgHDnD zMSp~gf9)t#AaSnsZ|TLD81z&9Dl6mRvCE{(f8T@`Q+NWpU=NU;yJS^I4t#1WwmcUo zR3K3>s11HQcOyEXev_5ajyxdU2C9j1j}S*d7i>{wvboouk$qD-i$`afQ>Z}Vonc2D zvmz4hmDjT}j6&X%#R=-7veg)lfG)nJcGYYq>6f~T>wMTL$DscK34?y!@Q1okG&TPr zE2HzJzvNIS4e{QsVH^Qne7|J%msWJAcW*J)NtZ$e61tyzVZF)?$inP7Dn%t7acC#;M<$`G=zQ-(CT zKTkjxY>C+VcCSFPeaAh8`E?qdfYb8fO7i@{xY(`EB(F`sV-Y#S7;XvC5 z3AOgOrB4qMQLNWx)pdmDk_fHS!qgWFI0Cw0OT=Q9j|#{im;1uu0v8GuNUYO%CV3oZ zs}uIBGKJif%7|Y5N8uQm!4c2}TOu~|^SF{Y{ZkX|G$vE1Kq9j7gLJAe25pX3vN9Sg z2&q2RK|DHXJV!tmY>C(y=U@%V9n(|nRy>YE1rp9FzuCUIDAcJ{IV+=U-Br@4=qawg zVa^fI1zRGvb8^6KVi2hp#lk`Wo_`n!U$A3>kunrYWX8l5z9lL(@Z{D z4i-lj_oGmO#Dyi@uvyOyXnxQ!Rz~NvzvN)Dj@S~$6VS!CaN}l4WOAUr=(y(((e(Z( z6)X-%g^8B(6oWgGQ}IT$FWFJvll?9A--yCGnzJ&_IhGScEnD&E@eUL!kf@$^Q5xJj z2H8!Y#)z@(BoEv3lf|W9+i?VR@w>K$Wb7ahnkS0Q(={kmAffJzrKriV$jIJ-m2q!s z776b(QT%+O2S-2`++)Vh<~VqUSWh1!qA!NDhyF)N%`qC`d!=&csUM{Z^^NF?`c`?= zf4`+Nk4Q8$N_FZ&g>;ETULGONkhCaNAR%4-Ep=HQj^6BuVZS7-&u!DaU4yoZg1dDqFMYZUy5TV(JWYqxl?Ia4B5|!=;?PPW4i`Z zc=`+^U^XI_i&avPF0Ku@cmPj8S3&hLsUkBM#s5|H89s(skgq}{-sTcQp#lk*zlg0i zjGjQ=yibw}ta$>u3V$4zM9XZX+u;r?!*`ZQ>}48AoD)K!0tuM?hJ9-XOeIEY2T;ws zAdY~pxb{lvcw;8g$f#pwr2E*Dp!1r7vDF3&6-e-Tab%t6l6F20!nf{$906SqUMeN| zo;0-X%>`CQk^X#=9T+2oxAUh^fdtH7B$I{OttD0dc|woQJ{$pE9_AOM6=BJ!X7)K& z#zu`O@@d8~VOaAL3KdAe{6%c{Kw>g^*5#^j#(4opK$qqG+mijlO=ya3H7jFBpDo0F zcayMxtk1A>CwZ&$S1|E*boVThcgAQV$!8ORpJFs6Zmr>!Y;pW+ZxfY$Ln!Tl3D7M$6Hn_RGE;0bQ__ zVDDhwC1NpGA?CVurvHno_m1cCegFTTMu`+kD2iA+Hj?5N-R)ZO5%nnA#;)v zLv?Scw~BM5b%q`I7)Ht-IQWFuTwdB=AgGJxdGdNoQ!C-0&H!cHu4Y08C?)m`(`Q9t znUcfY0elR3%T=)a(na~*eh1JifgSV<#!MDZGe9TCJpf1{@j`t-id%#ZLSqzB}M+$QWO3=EaJa0Q) z15QP$5YdhIn;`w}sEf`Y_#RpMb9Qb_e{gw}g;b#gtvkxIYns=9LYw+j?Ku{O0vB%HP3xBZFQHxo-fs=&l zdz7GcM|o6na$Oknr<3YEStO{7R^roW2K3Xw)#?qZn6-v-5qWsO^WCj^0e5GX# zM1s0#B|iS`98v?^RyL4EuA78Zp#-fvs?q50vWDYc*QEIJ2?9Y~v=Se$8u8T#Li?YW zIwnp;s!)Q~9p!s{o(|A?PE&bkqj3U3U9=J(k9sMo2fA)v^4bIAkSdg*RYZBl;W{_S z9+fGF*2okH>Y|nS_}Sf{1~8;;mVA0dCQ^kGwC*V11F&>}*2fmfLkEly2Ype`||I{tTWcw*C7nY+COQiT$_}MwFvBo1Ssx-t^z?_v=W9!lXiLqjI9V&{#w~0RVYDM_ZrQMYinWf z?dHn)E)D`gU1Eiex9hjS&jLxgJHi5~LJ7J{!6UY|9)N9YWhKwtR3NB}&V6}}lS3MJ@13XiNAeiiH|w^n?zJ_-bN(b+OTH_&{5BWq-(qx==<+?l!#PB&%m zkB*Y=n9k%gVH%52G7dfks!-zMEK_#w{0QmDus)pVQlN_m4u>m4Y_ACfbwzmF zu|S6m$*($%6ALO#(CdYVvirwx7_D!|LVpaCl3N}L-5%1Il_m|8Lf4-TJyd4P0!NIN zzJAcgi?-fpjxGASDMw%Y1gcPC^+PwdbJifq@QXI0ao;;r>^0R+`8KN#Qi8gM1=zBg ziQ}Yb9c^TdPkl?&D{7$RWYk8gP+~+^H+Cm*xa44D!inC$>S6u*b(PdQwgN$2_h;L% zJ4+@@Rs*$}_j=J*c=k|j#md4OsX~eI8(o<}J3d2R;mC=X89X1y_L)3=eQhE0h32#@ z>KV-XL=ToyUAl8(;4dHC`sAf-bif3uLJ69!!mIoz1mMBS-*R!Gu0T-NhwK)t$FfwZ z`Kh*ijOF*daqY6_;guUq9M;c<;oR5)^ z(hRNt)KhXLJ3^y%cgtvmF~uBYgt(3+vAo> z2j%yrF9Jbb^!oFeWtT>{dZV3U%J+GxLWzaOzRa;SRXRIJ8zGe9=Zb?x`=BPKv)^i^Gs8ZUIK1eNj&B|9@x*##W_T?Gt zeRinVYlYyglio-bN*qZ#T3$QqwAAN^J|~LY0@-Dr^^$B7BoNdUc&Vj2cE&L&x6#IO zzE(@>%c@SeW8n`4sX_^LL$unmyj5ll)H(DU5>udY@>bo#iGPe0} zn8)cqN9I`E08P_kkSdfAdlr8>{en5>nqfe59^*xR7j@B?5I%d2uVnfCYGYmNBq3Ua z614XO|Ic&Yun|Ezc&KJ~fuJrLIl?n1pS@>x)89e>kL;%kCFuH-ucK_u;c}bHP-|zZ zKv0*^xm&Z_zzwX8_CiksUZ0wD`=$h4A@lRvu`ysdW*#It3>OIMqEQ|EIrr)S6Ix}# zfBO6+j&vHQ1npDKW9X-Jh0kFLP;Y^FmP%dpl$6i(Pqcxf)nTxI<`|?3CFqVfk2XA! z2z}<7!?tx<0zqB$l$7s&%p}cb<uY>Y}Hl{9JAOT$sE1jGR{1 z8>vDGy5r5`cLy(r%iSKz-_w%?g1YD_DSv9OtcCNftK}o6aYz+P&>e3+TN=0%f&ywP zV-~g+2EYyPneYiiA|5gt!;3d*vuxoZCP#9TgxD)J0E8`KP<#G|V5~ zNQqnMfmERcJqzQ{dC3*f__!&P&NdPV>Y}Hle4nB3E%3b5Op$%9kt&p+yU{!vDGI@i`{cHaC5KGVIGeg1U?g1YFrDvyW{ zu7Wk+0+p*7dPo&Y(Ahb!(p;&7JA#`li!S^CN>Ep66Fc_h;~;6v4{deIpTlaR@eWD( z)9E@;g%aYteckE0xMF9R(joo0Ku}k1YGY=)pr2%&w2+TcC!#*qINw2WoMjHVNsZa8 z(B4vodM)IXwH;gAdZ09==v+uh9XnR&F%6u6DwGg+Yi~8u z$H-2}%4K~MfuJsN*SYVRAD}eut_1fD0IE=e?hf;BHOt3vCNxE{G-)jm)FtkP=jL95 zw?(~`l<$SYUN|M_o;BaU$~*vLccds5)oTQTx@cuY9$PziFP!MwU3okAh)@TT5{lCe zwg0jy(%UxH{CX7q+yeFwlNH;=l>$Lsv?ioRbMQtgoF6!jM}<|C(=(666I0chJf>aS zmyVuO@Y?D(a-m1pEXDbitWt#%v;VG9CwS#aR~K0EKBM!u6v6$>Oy%^usf-fTMb9aC zB>AiLFrjpW($h1SQH2u!eY&m|Pt1|F`giAJ9G|iej@}xg^xkztAgGI;Q)o1gEUv+W zm^9_Ym!XU*l+fv~&o0)>lyuuH;$wK5KZW4W{gkQ*6bR~~_Z#22v(mxd+j}TamL)K% zP$Kc4Eqic0RcfDI!N>R#QVU%xx+oJ(*9io5(dUMDwtiP1bvwr^p^*WMDwJp&+L%=w z?Zvat9`G@yD3+-6IacZ1rd%MXi$2Z#Tdmp-i^jH5?51C3RG|dA`LT2BI!ks7AMoeA zyYUymRq={{*m|Jnb@a4nUcM=7W;R@!^TUYms163$NpJ09kp$7i) z?5G6J6bb6O>~603Cwlv{mluAaJuM?*HH+6PmVCoNw^@&P1Vvcs-gHc_7RQRql^;6bS0NKPZ|V_|Qu7bpOV$U}P5` z?A0z{4M1se@e;P7H}? z!E0>!D1#5&EvE`4>N-a=e?G?l>kj;wm%$zIs+m&tEma_>EBtm0yL?9aKSF<}C6*_q z%Y)}eBdr2NE5*>tJv@`u%LdJ=^5tDG!jUSJpjBfu8mB}DywWva-gGKVAgGI0?%^}C zJZJ1TXt8Wq-W;hy30gIV=k}#FMhDA9a=%%A0zqB0J`3;2*47i(-CQqMw(t__uuy{5 zOW~&(*}j+-R3>jc=Ohr+MeEG)$bsrWv~PG;Zm`Q-s3$`STG55~3@elHzS%wb-9|lu zpe|ZRfp-AYlW?NJJGr>wFQG0DCFo8V-}i9{NApfq^3i`U1cJI~9R;49xjz&~nd&Ip zm%ak3P=fAj@o3yNGTuM0uLSGf5D4lL>obH{hG0s$ks?*!0IE=e?u7A(#>Zj!XMG(d z{$qteP*n;SUP@z?z`$METOFD9*vUL=m&U8=)zcCaD z>S}c`nWZ=Kkrp;c=ETvKEz#cBRk^0_WmKUAeY^5#s#lRXz`v2A^VMG+$SwD^{=aPlQk6x>N@Szh1op!`M)={yuuj6 zD!p0fbz)6GTJ4Wkl;mf3f%ULgO>fq3R)SDDk`lBAA&-DKZi+okH?sCNB0*iWGA6GM z<6?mcT{f~YdL4xdn3Nb??#!;tTOw_!oywn&;7oJ8yZ0;W9os=5sEbzkT$hIZalGG; zRH1~ylV+^q(L$+3heA%=sOg6rW+$`nV}b;Nx(<2xv-(pPNQcelaiZBSUR}&*s=6RL z2&qB|pYcAd>&SW1q&?a?MZ2q;W19oZ!-}i@1cJIe&IhpFI&-9NhQ*xtJU9q%1`LvN zs(q0vl%SPEd1Pj%P`q@#T)OGYkU`wvz8mcSEXBg4UDbrx}WZ&)4^r zHDetGg1UAXgs@uDRB1)Y0zSrr`Qf;GO1|81mkm;d611L_wj)9t9N%q){N2n*AgF6- zdL%QvH$t+tSi#3I?A;#2cI=T07W@RNP=eNz;;}d}3Fy-AsQe$^76|I9>eGQucIqwF ze7}Z|@%BnQRv)-1|FO9URG|c|C&hCuT@$hHt?TlDRZJkLE53r=Xb<0`C$1uMg zhu4}umhYJ%P=yk-o)pg>(Cvi#@?Xep#_kXZ>WaS_&&J2bOG$^db-X6d?udP+f0q5~ z?*gh&g4UDbeF2uo<9~@fYPdN`auR`2C5jWObBOZ7_S>yXI zlHJ&jobY^`f=$1^l?wttF-lO^#Ji)I z^lC~IM{6s$yltJ1RwpjYVSk$l1a)m3mc!psoUs459@McLk3*$y@_W@lAgF74K_RPCulxTIJC4}0yq_!CUZZSG zdVR_HN*!HqW1anEn?o}guWk5o5exZSzz(aEkt&n` z%Uk76XZ_`|9$Mm=b$xasI-af1$rcFe3OlvO+3AMA{QZKKI5oEub9$!Fe&l5%RVZO> zn^ZpUU6`D2Gm{ew?oCxEub!%Q_#hIZ%W=AvNNc4fOqcIaqdWJ4m}}$kT-{FPINDVX zN-ki<#mAh(=eWuaBMVqXIyxU8*GTTRDW4OW=))er84m_uvIK&<6upFU--C|wl6TWM z@wj}q>ac4D?CCiMsmnN{-1+8fN4d6n9utWL7j~;n8n1-y8KaOYl)$U|oHLUf%0&;R z@-fQ#`mwF`cfh+z!v%u6de@IHe^Ad({hQiT$k%3kLKeeC3) zf3$>JRi+wVy#Tj)X9r49*CVs-&VKsV@=nb}PWU!;WuYl<;NEW{uEGDDH%EKQCqt$S zpYFmpSIciU@s#KEDdfbLDHB;hJsA?}PC%;A>p`y*uf`s8l^rtZ?!sdb2HhjO)ksblC0L;<1fFcD&S)bjhP4j z%_>+(*l45*C9V{fs)2L-<%99sEBIwV7Ia&d!y=z$2?TXbYTr%un;k57Nz>lDk#+aO z-zP4tiSaPJYJ6GMzGa@6PhrCstWmp-50>wIp2i$9udA<9f@R&tIh?4~s~k43Uctf&ezr6S3l?HLcMNbkoagMQiT$u3p=TMEL`Q1Z@HYv-`5XVaeD}i8I4q-1bycD zoVrmWWbK;(qtZtT1a(D!X{dhf;wb-mq5b|?obLszH%^D66(f-oVJxy_G|C<@=JG^*RwtF(|RaUg%aXB(L~+Bil1Bt=kaL*L0#7> zI+pL6XC)Wi9?!>kd%78W?(_iAEfuLk3GqAX&9JTNw;Lazt6g7#psqI?wmR#$S;<2( zv}1HRzgk`Wpa#Bo?S@o|dbQqp#ZxmmK_1EKoQf@f7i}hg*fg9IZ(y}*eylDY8lH$$ zp~QSBbv{^7Prll5Fem=_xv@nl|6uCcp28TErvD#5S99IS0x$iAdL})E|AP{KftSkj z8(YaOipTOXTD8B<45A*xDzp9qL0$AZ@zcIP7VvrCRoL`&fN(u1VHDO-jhV6<-=V^DPKjopR;rDdhddRuW1P6W7Ix*jz-ohG0zqB$9mCIrmmdbh z+fFe2eTMM%p+w6Cm1_UAX7Y)f6ZjaT$M1u!&vfCK(-486F8U3}d!=k#pgQ$;LZ>a! zm~9kOz9+;)PXE%M9fOt52~{TY+I9okl7)+%e+3!K!5zBuF;Z@~XVTEdSQZ+ARCze& zbb04(MslZ`iH!axjV65D4mRA;1zo~h31d)V%ks13dh_ebcMJRQF%nD5naR-xXxuqQ zAgF6a%M0cA%InKEw}x<{oBMI~#KKm1)Wj9d&89jZiqMtgnJ;Vnd#v;EIsc@|g>KB? zI+PnmYGkFLF(=yo@?|&GC_EbIj8vh-fYyi0l`mhUr*mp?qM&pmJM9^bzxO%{1a-OI z2~{5){UEugep7k9C0NYX9BYl|e%K>bC^0JLV0n@HLaG&2$%*!VcCjgIqH*O92Z5k2 zGzn3+)_)>RDBsVC>s!XNz-v)>>3|bbg%a-vA1WV_bw`?fWf3PTXD(m??m}7ql6e+o8QtFC)+YPBg30k3z zXUpCQg=vY;;IdwdKu{O$EXZfbr{kcc-5F@vVE|Hv60|}akC{-%LD$!t;Sb-VM@4G{?HqP+-tyw8d?aK39xu(~z` zsX_@_JDx}B-Q5Q62@*7q9xM>lMSBtQ&b?v#K=+mfJR3I{sX__bsg37`Bf`0Vrf_0m zhComk?HR}Ssb`#qo2xIe1`RThDwLpAcKMsSc_nz1onlw+4ipIL5_{48Xm=ORMy0bG zrKw02O3)s4JR?{C1!&5@_b@%z=)TjWY3MDeGN2ykWYseeoLpafMWDIPP}~Z2*R)agOS%|fuOE; zH=e3}+MCO#sylMRbW>lr(BnB=nA8&k^W#-xUt4*=xABbLV=+>kI=qXeY!ItmZO2Ep zfm^3^@Y~DINEJ%Z`;GU`tV)85wGDCqlz4%luERY$s0L;AnMSsuCxa+>WjEKa_0c;r|Vu749Zhiw8)TSPv##pMM;3T;qPf{`wk9APjhx+( zDwH@{J6zSd^jp#`wc$iia}W5jDjfT?Xe1ESHR9JCb!($)scrk(oEXM@;O^xJJlNg| zsX~d%)9+!rOzx=}`1bauW#ZYPt20T2%j*^kP>kCr)_DV0bYYlQwuF zRVZQi`jDDb=Za*qtO+M-Oi72+8+@?dEpLIKuAe8Lsf(JPlPcaE;WNv&Ig=oLoI4KZ zU5KbciO|2#)oEK!Ncw*~IFY`79(evd1Xhmyuw!DbYWCVeUeI(hqwkd?d#9?O9^1%W zdyV1OWBKPiNI7x?^4j%6s!)QyWB8eHmm&yFegU^Uy9xw#9ey@Nb@^x^4~y6CGrV`s zhUbzlT2>_>RRltK`y3gX2aVeq;^W*{fuL`q2*^=0yz9x6+*9}%Kb?laVq;58J|2x! zp#*)$@Lr}>Q=x3BE!G|tE)di;CuoV9Xm2dXt%%`cTp2PIhIMhp+Hx>bg%b1~!{e4R zOTgOL9l!kNBM{UT5P4Glnpac)?_Lu=M(dc>u=!O})P3QBRG|cY$7nQby4_GG+k~OT zw5CYk1|8+;&N!@wywxe3(I=Rnz6Qjyn`;#`3im*&P=c;S`EHa|1$%WR0@tUz3Iui0 zCz!{>Ro`QkJtHyTu@h2-5_B!fqd))EgN*mBu>V#^fuJt>1Zy-;Ch0-swn)4`(-Emc z3Az^L-yg^7f~HqXe5E=I1a;9Tn9r8*9_uYd;GPm!qzWbIT9mIKQ@^rs2*cn|Pl2GW z%wx0El-rl2%$h;`&Csjx2|IZ$2roSFMygPPu0{E(sLBFf|7wQ)cm^mXs4H`xsvf#> zT(W9Cp1&DZZ})`vc`lefOhKwpg04mR_xYk8&~&E_zUmt(5Y)BD=9QXc&Ll(kS3JJG zTz>A{zJzy|?_-Q_`trW7W(Q{b_rkF^HIBULEzvF$Cj!^$#g-phfU*ji8ouls)nQ=85LL0#&T59-Qe z+ok`^cXOgk+5#xqb{p;t>5f#Pgn|BN_3hWqQebCob>sO{w?O%06~4Rl5(w%VVxrIV zZ?2an8)&oQ7rB?iDTfts;9Ck(g%Zc2Yp`Q~N~OGt`kXKvb_GKIO#}D6y#<20+8nCO z;^vo1?Jcw&5e_f919cr!q067%NEJ%ZKJ^-nWzWX}tu3y1p5jvJR_ONbycS ze2o32FF|h97*c#vkSdg*o$dKEIN~!jZt#!YXx>{OsOwq3daU=+rBY>45Fevu+s|pM_GFL~TDv^VdINs-2~}piyt6 z3MIt#;8_!0)Ys9KCU@;25Y)BT+ME@1=KYg`crv zhF*nIm!d#E#uUW>N8Vj3XSa<(s!)P<`QYEq1x8rXX`6htO_V@TSH^W~7HXO&6|L5G zB{^}|0Av4vY=5;SQiT$<%ZEmD^Og}#jk_dwZW1OC)OF=}0~W<=u|`KU;$vk0Ho&f$ zC-U3MV5ABqXqOLu&UwHHm)H3s7Zv#m1a;9G7rZ*mQ3KrfT30EyYbsQ~paiX^&8t(k zGQuyCky0G)DiG8~YjyBl9KH&Eu-Z&<&v6iHa!^97TdTjs5O2BIC>AbO0zqB0f(SqD zYpaj%nX~fae0`y|2qkC^CchrjYN9mKU3p?|BoNd^E1~dck?5NEZjY~WH(jieLJ69+ z$$Kw1H^KJD{gk}*Plc)~)J1Dt@F&XC40j|qS33J#5UO8LLd@qp0JgYnyRTwnULg?F zMJr+OZsxJ{&?m@_`-f2ZtMrW6RL?DT}6??%m=0s9&ZWUR&*q{<``Um%{! zG2~tcFzRW4o5^zqW%4=o&APwfuD>_DJ<&}dsO#Q9T{g(N znQR?5R6En}hM<$O1CHPAf#d8~sD;}d}sLZ0=3CZnz5`t?Dcg)b(WWMRk?CgY4K| zyN>FA?g3QJWpL(NJW_=cZXGVDV_!Frdk*i%iM~TWLip%1xcs1_Kv0(@zEEpFw3lBV z?9YkAuHPZa9^kBT3{r&>?t`DJM)MoUhqJXOakmEPVaBT6@cBR+fuOD*1OBPe3+&|! z{d;htYe7w1-xHwAi&jV#O4PsgM;+O`foynQyK}eyMICgWz6XwnMF<3S&2_8IB3s(a zYk9=1Ml++c2|ig{2(>P>!Ih@Qtkt4M@`pCv*%!+?tmLe_tTVq4t2ar*-rjB`r@qmC zR+p=c5O!okVCz_<3MCBt>o8T{LyoUV=R`B>8aQKBE_9k1ClJ)NsKG1sw~dQjaC;CZ zu1wHicEi!I=w>2Pg%Z7XyjG{R@Q~lM)9&?MY5Nt7o=t?b*IfjHx|S@sqz>-vBFEOz z-ig!azlQpWX;7}$1F1rZz^|9pC+QyYNt>~paDH(Y{6~$1N4I(j1a+OCct8y*a*@3! zjN`=YqgP=6f*$a^tS?f95{tGUR8KGTkYoA&1D}_;oB$oCG^imB5D4me`*wxe9rk{i0?h6$j6n(dZ1UXjeK#Q2au!VM)>9y; zi++ZDCbRJ&R1H`HWp%m=pA{wOv&onIS^Mek|8j`~*l$px zz798&<9#J&5pKi^Zdl7J`)bc7`i(A!xYsvftxY1*cP%|bpzlY%j*34DBYM7oq?a9# zDwLq-2|Qmd{3^UWa1&aEiUf7h_apz$3vWTm$mj5icj~4JCFpqqe<$9315NdBg3Zg; z0zqB${m5s1OFzPdZ%<(`pS@Cr65>h2H47bnf_xqRYaSsG)J5N@e4c1;gpD2j!Rtl> zeuy(+TWb2tebX}-{kB|u+lJkI;wN{_?8~pm`#p8B=9<<}cS#4N3MF{A1m<+OsqF39 zixZPuTH$6j3aSg*2n2QM{&8iSz)x=XwkszNW!mChO*d%rwG~o@61m%4*oC~NvTm~^ zPQ*`g#I(K%VAd~OAgIfu%!hd__LK9j#c^Vuu`_OyykOSI2&Br(ZN4n9DoF0XA(7Fs zHJUBS_IR(q2^@JJC5%A{gC}n6mr=0%sfYILE_$6c7It=m-P76%1a;BRke^2_F-Mm% zH6XDfR`{$av1+?5TWTLHpDECu;|#;PIC825EcT5T2#8~RVXp%KvQIydVbZP~7_mPHsX~c&;oi)-LsPj;sdk5cd{-AdI4Bj0)`SWKbaqIV3h=nxT%E1Rzc zeAE!BLWzm73TyJqNnY{BjgN8hk1t-{y98o*od!x!7rkTn$xn^u7zGtg-xZo;M#OJ-K^s!+oJcS~k=%}chf z)}Gf+=<1D@Cq~0`Umt;>E_%oCjtIPW+o)d|FsH2-QiT$G_C&Ht5q|PlJMDAcY=S?w zog{;63m<`?E_%oC$bo0Uc&5q?=9+pTRVcBsWk(iV79_8m7{tfeXxIV`BTumQ{@wyX zUE-bS^*t2*_YYv}`KL=2O5E+*@qhQO#iJH{jL(a=!?L#X;a}zeVQoOqJn5{Tchx<< z4&G;PgS=^dg%v#|==mqlKeyfv7sr=_7N~zf76|I1F*7^@qDdLp9%_IAvx1Q- zlz4Ufw0i!Fk-YO`D8J_GADw`5cQc&!LL{h*M%nPc>O&<|S=Ps^a{`enl<0i^vAWIA zL>?U1l8@o_<|+I-T?6fJv=9jDqO)aQFZ|7S@V)jMEcVj zVFE#2;w-#kNo`!y?i#Fa9)eV%gt#i|aM2W7#RAM2872_aC9b^wjjf5On z+fVDQz7C-ZC0ue^vlAnYjwfsT?0b8uwMEma$NUiocKJe3tnx>pu+n!mz|A_Gu;ZQI<62wd z-i=L=DwMdVXTv(iT#{^hIP(AeN3YuukmP{ny6yr&T_e62uw8IZ+VV!`V~lfu2dAdk zVp@PJQiT$SSJ^Pr<2R*FL8tf_2W_50{ugI_;mM=h$nT=Ay)1#kq;$T8e z{5rKE`YpFas!)R73p{qvu?7bBZ-{NqS_uSo>HC_ntb2O$&LP^Tc4$gnj6ZCJGkBdJ zs!)R7J$&wyW{eXuEKq6NKp?1VT$L&NR9Z{^)7G4i(Q&Z__B1rXiJL8vDwGiKtNNDa z_|CxyTdlAY2_6T&JNDa>~C zQ7NNe+px#W6t-r_0clD3_%My;K#7D0JMV$aQ}vN5l(^*5f(^QUSPJOYjuWQy6b$HC z3N3lx3`$T}`-pJ%y32OyUiJb`9BdedkvgkkhK&tUg%VkZTd)GlGO4)xSWYw^C1X&7 z8SpvRP9Uf&>sJWNi{2>tq-ZOiOt~72?!9Kh+Z)bE6-wOA3SxcQZkB=)@;Gs$W(b~K zk_H2Qx(Wn!-S6Fk4P3BFI#RZX6W=X^@TXT#*z4(uRH20PmOz$sxKwgzr>%u_yQl?* zc{{M(CTgRu73y6}mw@~A?IR#5@$#;|2lc&7G0mt30T z^XKQ8g^`~?P#3Mk#A{g`=QYo)s#(#D=0d$CN^}eIVc*J@OI5e>`50@n-4Qz4!-th( zO(*Kwv#&AR?^r5b-#U;Jo?RXA@7-QtlNpXwp~Ut)H@0~Bddah8GAHiq)W<&#b6~;Y zD1o4^@P!T8h0~j*K2v=;F}b}VmZfinNnN6mDwL2{*s&%KJEXA}>^b2dPz|Y(rywJ+ zjX+RWtCnW$uHkO!T<8ZLO||yi7syGt15KAkB2_4H!QPhPk^R!oLoYe8Zpd@EyyFAx z+ul+jsO!eVdaOgg!_t;+i#QRz=N)W``2`g$45>nii_LA={y3BdztDC?yz}8P)GV%n zy_bXt1a&EO>ao*Xj!9#Wp5xJN#bs~dRy{+U`Z)lpLJ9iq!|$t`x8QfR33kj06bR~a z7;L~y-d9NT9!%l6WP3GNpy5#q{B7@#RG|d@e&n?i5_dsGsUt?5^b-i`>Y4sb-MXey z8gr_F%D-_&?twoyUGPMMW=IuE&~H>;W9#lFI8fOH-M)AT1a*lsORL2yoc!j26HDBX zDwLq#k9;OGem}TJd1J_NXMvzDIuGVM!i~{?zJZ^lmp$PAeh^c$6TE6_g+BiA&= zgcN&$pe{O}=auW_M^HP$9hJ>?!n~al^c$7eXXyA4945P=(LH;Cpf0*D;d4=^FHqUs z3Gb#f6xJVzc{CwXB_`SFx-fQhF5Y$E2SNzN?Lk9;9w!&}c9ffriCFnOQ->v=j z4-)L^VM=LZfuJtBPUNeJA%^(I%?KCOa1+*pln}pb&-^pOAs00GprMyQP#0ajYBWz5 zrsK9#X)JoeMF@Y9^S?c$=!z@q?(t*T#kL``(LxPd{X2)vXc8iKiMYt`_5lS0uzQaS ztoxa}Kov^Z{mNwVoKglV0{hQ6NSUA1E2~eM*JPchMD@xbGCorgl0=$>}k+}*So(i5Y%<-);KorhL4;Qf1MMGPj6fp zHVFoey$MvI#Qx|JY-gh;azc~)oX~sI2Mc-6)YT=Y1%kTLjVChyY)^T1(PmDVm-NM! zz2`!`aSW(J3EVQ49i8GL_noqU6FH63aOvPVP#RP!5Y)9TDTn>q*hron7R-stx@l zUN@H=Iv?O;OuUhd$D8bdO*hU71a;B1DDMFFBOd*x?S~~6&xAE6CANQ$VI|isLd>52->4dg{RUUU!9~!Qj)7pKBlx)J69O z`1$$cAl!TNBvhR=6ZQZoLC;0_ckMx6)X%;Q`HQRsg1YD)2jA;E-xx2&orki@M#5eO zCFr@KMiWuyh_jP!L9uaTfuJtB^TJQCKIyV}|0Y<&T^1@K>{+nbxgM{VP}Z(HqnVl- zO$!{y^j~=6)6OlBDwLo(X1xE0!3P$xDF7S2@Dm8?qPd;CcJu}#=oTA-(GFfbQuhDP z4W$IlG2`DKW5eOms}?w^jfX%`7tN^S^#CTs!v6d)+}7U}sX_^wW5!p)Wm(X*c_>yz zG!h8vqPt&wpFwvFEHjj_ZLAYgg%UK!jAx~k7s1~>!KgdlSs=}T$et7x~-{mAbbks#>YW!SnZ7vuLZH7;Vc?&Z#O3)lLK6`z= z5*p2Kgv-1G1cJKgjFa!yelLNeKkf1D!(d@%NeMAuE$;Rj7}dQ2j^nFU`n#y>r^#>i zY4TAiKYzv{zRP)H9_(&zjSku2NEJ%ZOcISIbm20nuU8NEw~rJE>RR9TubPl|Nc!vQ z&1d?4+l#?(uMswU(-x^h37UJt=Wu4L!QWK}HyL&i2CA`MgVNZ+KO9!Sj;KaGd&tY@QV%V{`i$G9U{}L;9FtSvtbuNSx zO?}^i>ys&PHKi+3g%ULPM5Bp4Qw6W36nNcKB&ci1Gc%T*vPv3oTbm28V(ceq*sCpc zs@nspLJ69C!fP}R{009K8$p!ZT_C9IY)cC^BBexfHB|T*g}T3COUf^{b43rN3MFXn z3I8_uu8X0cw=k2p-2{TVN;X?EhpffYiu@=(hHJGhUjG%$c5m#CRG|dTJ>hRrG{9De z)|8(&>M9V_^{Ku!8?$+Vv^7@SL2^|`1N>QHB$>N*MXFGO=AQ66!k25~i>k%a&!tHM zL0!kP8n9!(=18Xfw7XHh4~+1~-RDx5hDk^jO3>UBeg*YR@WmxtSveFZ5Y$C`MDW#i zULDNt)Kac-u%pmDf)X_Mgnxguu7?}!(&ayM+X)19(M}RPj;y^2-fCAM4>W0uRG|dT zJ<(_y?Wm6zOP9)-aw~zLuBI^!S@GFCX>WaPK2BAnDL%ZuRUXVEm#IPtntQ@Ca@(3= z>MK<~c|SxTsOv$BJuBEVRr>lffR7=~GQ}V21=%<{7^y-DntQ_M?U82qI`6(bZ-B2r zP#5d$z$O-EOY25zdk@6Lnc`-zk8+e@Go%V7#HA;@D);gokSdfAyKN@rIiX9WfzonlJ%OMu+NG3dVb^fQsnPY69jV;9$ER`mQp8_SQi*{h(yUuYI~LURP>!uS2vnhjm@&c<8snHP%@p%J8wG;8Xa@$qtLEu|qb~R> zl_Sc4DwLoZDtwk`LgeXC~D)XwquKIY&t*vr!!VZC;F4`-J zpJ3gpg8a{|mE!?tg)T~zpuL_onhSkCLaJwbWkmH+fuOFZ`TESlBuna3>BwgQ-Ax`q z%BmPeul$D4+ldmiXSGK2{N_zaZV{(E@;)aJ)D_YHquOl5BxziP9Unszbqb2gJ17gD zJqD^!!p!xCs`3oCNk)O3C>U@ACT@vWChOi82^6pp4f4AQ04rNlZQFIZgWa!JHF^>MnvK%Q`4GL-dd;lvrxE zR*n9VF9jzwy54c(^@RdyN9!ki583EgGK?M3OBq%F8Bm21 zG1cAF#2(Y7*0~Qk;nS%D=ok%D-ak7g5Y+YlXE*i!$3iLQ*$PhVALs+$cMno>+wTFY zP(ruFMNMrqLn^&p!ifzJ8$rW_QA*Q6g#tlcDJxvmrMIR_zg2fmq($n()%ID+y2t@Q z6-wMcf2Z7i&kSiqS65Et?|9AXB~MfyANcgoEc&5+s{jS1$b`kgkh@lz%% zN1Wy`s!-z2kM8ADtY=Em-y%7&Fkue+-91~0Y2~U?g1R2>nqHp#Z^r-iO3_qVF^4PJ zN)ywSw7Fj$id)V6KVrAdMC@d=P5OR@*C?Hy%f7wx2&?UFCBgcstSqKw*y}D1 z(%$B|Y*2V^Shw@W5}*6Lnt<8Y?n)WerZQD1(f{2PrsNlg<=?d8#O(nS@a!)exl-?i z@Vlt%RB{f3bEm^5P0^0==k$1-*(yN(@uWhc3MDSpo6O3h?}QcZwBUr*h;e9A+)J*^ z87vUgHMe{$n^)gJO88of6VG>##eK7f%d0H)C8|*3r1Kco4osz!9;TdVe_#x<@IqP7 zXRS&J>I&R4lsUKekow!{a^lU|Oe}GoB{wY}$f!bzQB4N3nL+-NWsCtQN}r6x4>OA8 zkA@nc1a*yG)R(<4ZznA^`N-!bSJFq|#h-KKcW?ZFDwIfTmBL={O_WabtK!6z0fTWz zVXA-t;xU4iOmLsa9is+vMaA8L={R@?(4<^s(MRBb)R!$$*zI; z*Rn`{{%E~GP}iiziLA8NAZg>#Yn(`!na(3PrpWJKtplo1;#FQU8*82+!Ngab=&)iS zb}Jb!Tff{V5Y)ACasu1%aI|#R=O!oWC#B=XbIJ19WqW}tl*k#}nZ-^WEd^S=;Y7o_ z12J=HOL_053W1=mwG-mlTHS0(=eBl?b!*eme!i!?{_Sy~3MFQbOk{4J*;4MC*POWW zV*r*p)RRxVyebgX<+`{7tFe8Wq@KOOiMpc)Vtd;!l8?s~pb8~=tx90Fzo$ucEw!Ij zYD#~cSb12wSo~NZs4MJdd#3w(x>V+@y&mV!55PCoMbgHL_kk*u`1&J`l@6I9?K|*{ z6V=ImF}8_|G@-+LfuJrmGKM+%%#n`$yTl34v;A;J&2?d^X|I4Pl=wZhBU}1pj`X4G zAt&@}q~IniH}x5O7YOR|d)Ss899Jw=6`tipz?&3YG}?=epZ5i*LJ3cwShn-rGO5O+ zN=_8>ypQp1ce9gEG)M{Rn!L3&8&+$T)WC;vVov8C7&t-~PNw_@s!+mnQw)2xVZF5Y z$}vt%OY4HcoxPyZC_NMi;tC0kW)}-KOOH*qa-v&QGWx!ZfjX`K0#)emeR#he>pgUr zG-l!sPPCog38()Z4)g!$A|c6e3MG~tZ^yEn z%cU<}7IUK2>^N-Lw-`<=)*vOQi^iSs6W&!xSoCfo9Mb&&RH4KfojBIu-Z5#3@e)49 z!?JiR3s?s&bG`@!bxr#n#cWrdmWIW*=0vyWariA@7j!)J4yZzjamKCL(nnXMK3JC% zi;uTN!{Bq!+C&d2L0w&-1smggLDKnlgwK}z3PZ79&qvVky*^Tf5?9-Yv9Y<2qypb# zhxxpHeiOV_{|9_~Vxb0p$yAlU zMeVF{XSo@69%dpC)J3D|crJjo8*aK`h^sajB2_3c=|do!5n5Be+T#=-W9(5k?AhM{ z`$g9l2AgGH*R%tY~f4JkV z$G_pu3sa;DC1~s@-~IS#hxq||xamy;fuJsWKFl+{!))=mDZfk7oRBJ%5YJdvUp2$O znlDgN*Ha`&46JzW{HK={E}V4_4hJ<8;;HHHrDr-CjmJz2JP}(7wy(tqZ0e%%+dOA9 z+XkOMW6*wg08)h#G{=muCXQHP%f@@**60=jL0w{8_{SSIIFEPE{&p_}sX_^wW2VuZ zjCs3PO3?gKz84;3f)_1@KpMmd1a;B8eSWT1Y=rUg-QlTg98!f6G!K?v zk99iudrLR?aX(2QsEg+9^GZ{_tD)ud)?oUsD^i6Lw5|oO{MG3ld_LYDf`0c92AgGJh3E(FtmRq29vtH2gcZQH9L7p=a?*Es#t;hx_? z$Xqp0s1QpD+PQ$AZF?ucsUFv1WL95+pe|Z1mhWs^xkKspr*O=@k5Jv160`#Yj~BHy zfh#vO=n>mZAgGI0I_CRu56-YpziZ<6TFFQiO3+RceEo5_guRM0!;zVB0zqA3mH%EX zY*>p-3+%MAqfoP-5@HvOCTka{bq3ksey8>VL0z;D0pDlnGG3`S)LL!+G)XppR48e) zFm)z%40G6A@V}qSMobK=F|vv_Z<8ox>Ul}azcrNy#P#8;RL@+0#rxP&=|py*LKRB*EsT)zJ~Wl5B(>+n z>$Tp>{-H(E$J7=AL0uF17|B&lWxfB6k@?$838?5IWrc((Xyqlv{q~a&P3tWk=0BJJ z^phj~q8xySuUbWA`%$ zz3=au&yCmb@h>jl@7G>4JLb%uSR20CTfp~!99iMJ0Jw3{vh@FZO&`RGA-S#5X6$C= zpf0XR6-u~1b1Wsw+xc*!t(66~Y&=t$7Y;}jO5`ncEhQA2yK~|&zf0zA)hhM(I3iUj z@!7`}di>%$i_P3QVSLpdZ@f}FKC`eD2A6uuN9sv<)*H&3d&*s!*cs z&*Y#vtn_ki~eVc6_Z@cdmTwlrTi;?*pt zKTfVPrEtW?YDg7I=ot?yrO&o8;ly-vA8c-d7q}P+1a*lu|7YwVw0<|a(9T>>s5!0EIJ@Z57}`}8 zc?_eufq3i5+rkdpKQO9L;>(M8Sp2FJGpP5Ow?0pshu}gsukgZv5`myDO;|!{47XOg z@hhd{7|aT-t?nPPpY^Gl2Fjo_-sz%N$j7dJts6vU) zH&vzdDtN(T91j_ebI;E$Jpc2$Kv0)hs%*P>tbVP&I^SXxqiwBu_22F8yUgr=wY#6v zW6>g~j=JIER7P85O3dDpURtU~hPp9;I{l+@>lYvO$c8fog1YD#;X7GXk?6HqQ`o=R zD&bsF;=XHIX^e0E3VDpRMdR?KkGe3t{1$YS`qI z#xSl|jmNP4q(bbnRc*GuDWeJ{w${#pHn%%5!@d0Y|6c`>7*jcD#;ot|)QuX$~y9)`?YG_?p+eLpqZ0e3k28!<#`&MG$a^P#mF&x9!=vMtY{BGi%Bh{Q;mVHotm{ZSnz=W8<0ukyPAB8h(|hIY%N2ntl*p)%0~6eB zSjj(E`8))7zq(QtUXOB(ld*c*BRMS;fGU)D+$9Tcp0;GB3(PqY zsZBzYhiB!pg_{I|x*GhNR2sX;LpS2(z9tSe>uuywN#RWSA+1y~C|oNQ#if`2-LU5p z>2N^?BwVy)7SCpIqRqW{+*HX=p83L;QH2u6_h*#SLC17^e#UQ2#BDp%<+U|C2n2P} z5-Jouo~rPddab-Xa)3OjipQQN!CWmKWW`+*a|^13DaG4LcO;vFNfnw5q6 zmd{3kpf1<;6G~$QbkU8_A7~qnA6=~r&6n?HRH1}H?W9s-uAXj$erj$Qy8d&@!8P|7 zqY5Qj&yRuGcP!Z?Gu`Y``o`gSUK=m1-F;0UsH;YPbZLxxnhKm~T@ZlRHl31gFaO1A zj~Na-ODtK}MTYR{<>*oue5ntV=IedF1!0}tucdPaZx~f5F)=Nwlpg%D5|7b1KNxR& z%Tj*vLxG^Kf0e4S1va&615pwn?MKsIKkY5^8QvlrEO4-ZCU5MKDwLpa0DR3|b%rnY zUXTojnF|DUb_aUepuE zmN-f6-37CW~wCyvbPjae^pq+nGYqzWbIb>bPC!Uy4+#i(>`rza59 zwJfW+p!(M&o_f`7dKs1?qPwn2w?g#tlc^jCuCRa>LNhG$aca`PH7s!)Qq zO8lwyOvZ)d)pE6|Q-t3S>Y~4Pyoanz#x_fz$g^*~6@CXPL4O(e*sIbFD{sq&EDvK` z+Ny8qvsUdyXP|e)NoN)TSFj(5CEmDON^gdQ7HpM8h%G)K7Wos!A z)D^zasWiqDXD=Qj#lJJ=yRCw$;Z{f$O3?8D-m{$69ZUMAg3_g#P>-lb{Y#JAA-bbb zC!W7#g(vQw5DsG-Hbz=@O1#S-T1xlp*qWE>Su-ERee`*mIW^Ji1m{AgGJBkGlP}ZEL0$Ack*~#R=87WK13k_d)6s-=pT`kHLwx zgVYZd8sV*o613&xnLPcY5U1s-cZSUq2P}bj>E6sM!fg;aJ>hQYd_ig6yfKBax7V7?9V3`Aj z$37Ph4w}#3yzYgkV7&@I)Lxy(!M3Y8U_7qaL2>AbvdxGb@ZA>Z*z2gBv}bZQw0`iQ z(81H0$FQuJj1_m@DXe|r2h1#&1>phr`{U*iC9t-UsyoACAO*r9NKM7+zYisJi z_lG-eCqnqFhHRDdT50w7B-rdwo3&baKr(%m0;4X}VeQ7}@KR-A1kTFYRjB7C_Fn(f zFCEN#tRq$@LHDc1?Cl}l>K(nDU<_Ve4<>$m$Y@`U_Thfjh=iWW#_Y3sOy)+_i8Viua$ES^uObUd$bh9&9U)+2C1%kmmJ_?J ztx-QMgB|H^feuGZq3V@)5b8G-f;ySP@wJbj_3c?uqje{UnEMQ--p%I3oDae1G^8?H za`HMGa@Px%x7q+zt51XT8Qu{2bRA?BOoi~qec?`rO|bi|j#yGP64TY&A#vR@_Mo0W ze2mV6lEc}M;^7b3#dDzLylhxsegL$-p9fZu#fc%~BJoz8ZSZ!?5=IqDs2=*m&DXPF zRAXI?nulX>!;+bBvU3_s{5k-B&7Tg59kbwc??Es(YBIELk_qvSLm=zXOc>cCg%dNb z#-Y>dsjy;t2>TQ{1lshQ2+dliLwolj;M*`AvhSur%GbfrsZAOrEl%e|k7E8l*!+^D znKPIz+N=U){kqbMQ=V|FWfFwOnMpp|dqBeGL|ByKB8{!?%?WQ+Jo+o0WWDi$>`}L5 zSWsBGuzG zF6hIEU7a8$%tziFe_k4Y!XBI>d&$SwRO7_!5_^nzXsr#%T?{$N2qU3o(jPWHFF#M>W?0>(C5Rb2jcelbl`JJ_2YR(Z9O6(lV=RZ36%RLY2 z)(+0N-T?zl9klx#W(WjzX~$SV%|rfj-qP}%*fOv)CV5+FO)hK%T3%X@K`~139_ud8 z_^De1nf=xQLrdCg=dW7;RH20bOBa~Ud$^OQpXN_(|0#gZS?#nZT?zz(x`Gw~)F|#M z&)-pl$M|riD}K*!roCub0&VAbLO}P9a@U9Yup*-?biAaLBUaSrSub25{h+gac)qSw zo(;O-Neg4GY0zCkp@g!Y3q166mW#}5abiKV3!ZaqrPVXMArREH%E1}N__@d?CAzlc zd#Bzwpi51y@$(9-Wz)X!NMkDZsL&ADCT}PiWhuW;t`8I4`@_c0ZRJ(1bgL%aKY3%6 zR9kB?S&vbL5}^j(a8+tA7j&)9iD%us@Y%<@T50qb;aJo~&j=?f_QY~E8*0}!`X-z! zN`%^a!uCV9a`cJ1JVs)@9ys5ni8gN28<8L`dfxcA&+G?cs}nyo2C4PgsRn~#Rn>;_ z_k&H~e&isC>)cpg@U$_6dJTaY%bLjZeRXg2r=R)bs9t=Y{$L$O6-w0OZOOv+&E&(g z4LEVPyD!$`8I&fEt1J-IMb9DsCX%Wj`oE~6y@}O?vrCCuQ~N>V0j=eQ>l*SH8g(D+ zbiSH)#MR0IL0$C9^4+q}2BCr5C(ZR1213ngovd07g`s9OWzTztJcfRs!MF+DX}Ywi z!>B?D{iVZU^W^HXQF1v>j6D>H9ezF5nEx;m2C3)Vbid9!Jwmb2`i$ms zySB{1e{Z+jpq$R8~842G`e^VcYmJn_o4vF=?t5;e5;LqTQ7NNMd@>$IejVYrF zCCZ;20Y{epQ0M;Ay-k!0<-a&>uWRyR8w&(=(Gv36*Pg@h+LfD{J!ec9RVeZEKnT3J zSWyl$YR+T4xf_J#tRHCR=Clw9>Jn@2w00zpzq(KJ*g;}0@uOjXx2Nj6draWlv(ZrW z^tt-x?B=k;C>-9+yRL4xP50)NY7mAY8+T|F;YvmoO1Pzr2S_=k{&lV?Ct7zOjTLKb z(&#mH5(w(Lkv0yZ-kw$O_}YdOHa26hxBVK;uB9%FDwK$Jj)bYN4yoVFY0HU|reksV z#ig39%#Bfn65e0O!?5am)h8`P{PtX9{P{nqCQ(r_eAZQ zIS#u9Ow(jO=q?b{RqPT2haap`N8PdD#3v~VC)5qn=uh%yc2yJL?Dlx|amfbky2gX7 zKS@2hoHgtkkPKF5rmB~>*0ooP#pCgw-x$rr`MnrbC^7qWEF5i|r*3tV*;3aQRCDTyz|!9;mV9F^2As z#((a0*2MQ5$f!bztY68z4`-n+TB$p`C*5PPa+`LVCUXJ=g1YLAS3&9;OLYU^PMjFN zC>Gym*VK#|=g+7@31%`8MpwO57;sY8dsR%1L-DEb3^szd%BtG zWmDqN)^LYxi@|KAOEO%lg@t2}BX~O|!~34Og^@lC>NK4IaoO_=+ugO}L>K=!+|}`j zoPTo|qY5R;Ur&PM`2B@9vLsGCC?ALB;rHb_jYWdG-Z>{h{Z3WY4+|VP@%&6YMpQek zblEn94fRQa!SF~qW?v6@J|YPseQzlnj_m>Rv=kU-UQX&e-H8)DFUOu+bZyLzxar5UV!Lb&5ls7Eh{}p4Q9FL!Ft}E>KGmz2aQo`VE670V> zN~w6$m6xi}AORgW=@&j&Hb5Y#OYDoT-XD+J-dolG93H}`LWzw7lc84HbVql)E(jh2QS3ql6qC4;^je%_MK^;diD53uo~M_DtAoRr*7(!fRBg7 zg7bo2%=T6Sct;PDHaqo(%Doan&gm;va`6H4gGq4m$9yU3nC_Zan4N&GtCm5v70!$* z9~&mY$jGIVbrS@7B))fPS^}m|UICrvI}0%=QTL7t+IL$nm7LYRdHGIFK&k0UD3~P@ z)YajF3hXv6m$E+422zd{099iIhRFM0^|psw#5;$Trpo;1IsFDFhVCg6xB`{4X_U{s;R zupJ3-uEtKOdYAZy;=39|z?w zACWE%@Z`kX9toH~pa3$HT^Lm;asGZR+-SZ^8uG=D6R+YEu-0)kZ1w|2qi5}phtDU} zQoNfx(9-g@Bq0H>4Bijphe|>{C_!WMcW0*rj61pxTFve%5Y%-wI}XM+m@kD)(48y8 zE(xgEz8Thn8>0#(#CjY_Pr&&t&ceO!orH50StS{7upNDdL zJ2HBHD6zal3=I8vTY7z>H!s!Qp$X`;_z|7@5J;H zSlq>oQH2t3_m79+^FB)r19hdERg{4GdN<%fL3@Fqu8?aHz&?DGjyDeG#N$s182QCHB52)K5t5};xbh{T@yiI`pOF^vCi%&0<%=$r_6^Q#JUKA>9<7y2s!k3G5t z9gN!w1a&Pc4u?-)s=$T9;hgAcn~0!#0vD2+GpbO+B0Bz0ToGw#60 zJ1qo)x^~YEhjZPk!qx^OIB_Z@5r-|h0}ZzrF{)7FOW_#siE9Y+1Hw2l=vN}D4?TeG zx2my|31i^oDHF)QJrw%IjRD0S6L@oPD6IHA8kTFCLgL}koLF==5$CM94$%|qGpYzg zrO~j$+ZcLhjOB#u5`M03J%-ii>oZysyTRcQx2hpL8X5>9z!CHfW^bQl3H(Y?WQc?gU*3WfZCdO{7;1gPad0!AM3h8HV!F>YQ~p-Ff?)Lv7O zQH2t!38C=pS`S#-JDwBOhbQ3}557Bd${pcYf{T=puLC%t!jSVjVcwaFjMk76^-qL? z`KsesTg`?!4GMv}UeykTJ157&Jie~>Si4}Ddv!QGo~b*#_gf{QQNc2BTV0OPV^Ml_ zuMmhE-xta~)WvY-s8KVSsEjA2+A65H9sqqVaIdI2C@r4T6cm;SfA!A}8=lB0B7v z0|y_Qva5l^AjK>gu2r7^|bpr5Y$D_2w&s1F&6*vm;&p1#4|ce(k(jxatg9w zLz7AWnlTyb5r>cK=0NcLa7O1+C~@0hFes-?f-#dac&U6J#NmyQOj!OZL?Eb(&bR1t z0>~>AQ#Gt3!IM zMPaRzvmMQ~os*x8T-r{G9L=t{*?c=o}p-8V~IQ5iu)aqVp79Dl@y0 zc-rbMOc+%x5Y!d0qc6OEw+y5?lR4pX&>tUdG-p}Hzu3~|J>dQK?XYFc45;6^2b{aL z9Xvy3KyI)H9K5juf@@CaL|oqixa_eR8>jlgs6vT$rXFB6CLgNm&EUj}r~r(xZNa>& zy%z}Tx_{6Mrg?9G+l{7iLIpnPs_(|KD^j?yP(fTPA zn-BQnxyROQ!f-vL3MHD??E$T7?f|byUCpz%`D4vT=4_?kFQMktMbA2)y8}1;a6N=| z(HP*Dw`dTGJGW|3#x+G6OnNi5}+8PfS> zN`zc&14YL#!J9)1c#JvI?XhO7G?rGwR3NCU(+6wVcKRe-9W;*8?z7Gh9hL#!S2N-l;Dnz=kiR0j#qd&jfGUt0kyIQswnaGtg^VhZSs0_*aZ=<{j|GjlOL58yg`8C7R@$fjYS+``RLz$B2!wMgN+9 zZ1u4A0zqB$I`MB*we5iEtAg2~eb&PDphQ0}Gbr$^%5GlK^<>n%R4tl};yD3Dg1YDm z4~3$Ws}*jqUV$~(ZjWw@%%OjAYxcN8D0G+1VPWT%targk=)DACX-Z2L+p`~!aoorX zpO{okpLy*mp#K_IIpl6+bRkwX--1__qtdctj1a;AMr2P5lsYKre=V5f3g|Nbu5_EN| zZbs1)`~6rCiRTQ2HAQqC5nb2GbGPLV#}BU`No}8A6IMFW)lGCYzCz*mI38cKq4Lsm z{TbcIK=)0o`;iJZHYP0Tm@W^?l&x{twnUPFC=#B`5V$`%G%;SQVr?I&kU%XWWrW=eXFE2&vIj!gf530X~y2km#9LCP0c2OTZsuv>HnOs zx$7Oz-_H&8HJy8#3H6{Zu~hlSN!WFtf#&LD5O&c};xT_~x~ev1NxQc581H?Pu%u2s z&7tsIfuJtBPlxB^;Ahz)g^!ilx{DqK|AMB|S$BuY@%#j9!Xtd1kgUK$BZ*4NOZj)Zy7TAn^!MWO$8s7pisg(c_MV_+K^dp9mQijuAYRh?zJ`g zu|tKmgVaS!$ae|lsqp=Q)|$PUITBSUar;FoMqgc5k9_Jh2`y9X^ys^CJ@vm z*4)-J34?O$X{^^LNmcqrfnF^Id$RtH^to{yd@fgsb^mxk3fdnH7Z#Ogb3MQD7|#4I z!Ab_2)qydBLWzZk<6uth%53XRU4|yJ@FZL~tdi#E+I~QfMO}0SB_9L0sKTWWnrrm) zlZ3UElvp)85nPk2F|(9)JjToQDs0f8m1c@}q(D%YxH9vDQ8L;&+?7|X>H~C@CtdwX zOUqYm6(-?>=an>bPNWMpr^M-c5wL3Td-&8tcdi`rk}#)NHBF9Nnm|w&J?nfWVAB)~ zytYQpzcpKG)@me#e>w-&PfZ}_@(74&aS@J$c7zV+N5I+dXQ1W%*8CS|lz9rKKOQeX z=lhMRLJ6E33iI@iLg(%-oKU-_;EvC8c)Jo=eaIZ;p9QdnD?wiJ~TH& zAgGJ31Xd`Lwx{69hBftinY!}V3b zV~iV{g01f6t1~}O5EM$(=A%aY`6|}b-Ts_7b0`IWd3{lzeg2O`k40Sro(DtAz9mBJpj!(fK+mhrNb2dvYXpM2#5-}|L4G~F9hLizb%2VMf}yxzIi&XQ1$Pe*g&UDe!0hobu=+9# z@a-a)AMe9sB=aXqzv)V;`Bp60_nFJd?1VF55FpM;w3Uzu7 z06N0T(+KxT!JSVUz^$GW1cegAn+1dSvT4vTM)!Q|T9=F;liI-f2Kxnqy6CmxZDLvq zp6+^8ayJYHs!*cO&tahVWHzje@6Tg&n45yTt8bM0+V~0tb&1zJAtV{==}m$7t~-H_ ze^*-<0u79!K@~9cUn9bAmhxYm^C_^n)_Osq#NIc-Fu6f0L~k9!OBGrn8EdVK2HO+2 z1%kT7vwQG!GFrUr1Io30^*b5aro;^4QH2t&W_+|cCqtUBPq*@{<>>^x z8JGo~=Qs-lb)~LM0qY|vJU4D{zIvz60H_t@ zC9K||1T8Jk6vAiqL*7h<(Y0L!g1Sn)Q@}oWiqvjQCtj+nhZ9h>hwuHr?98Y_39%kq zLK88~#2w6MII@Z!sj&33hxB2IF&qh-2!4(s(uCV)|618^>Yj+p4)p^^b4gemMTsB! z6CtX{IH^lD-P%E$yL<&ih#s6$x(ft#(QBhnG;frMm;MQZh>c8G<3)+suM?n2^+>7L zWL=Eyl@hUaXcXKXfC52X^lI|G8C&A;S;sZ<$0%`?9$kM&_c!o9^{RNhb8?*gcIf~{ z6-ul$NrlZnhASi5>QIWHvnM)I0yuF(JQM^Jbaaihd0%O^?Ej}Xj2+^1hkP1wGH4^Od52) z%(D{QYXmf&LJ@N=5m&@FgLxJ07*#0Ia7`*4uy>I@4s6a#)qF=HE+{gCauw|bg1Tr4 zd0x&@Dtw?hBW3MxE9|JEyQro=OowB)DoGv<^m&XWqmuAl#SO}R9zmU zzlc@*P1rfkQkwqDfYD=7qU)~=@HlZr`QnH!%gx;eNq9)zQQEVvu|QB)>l+!cE%dfB zCsem@Td_SEVrmwYSjvS(opfJ{ zy}g+4)T=*J9U6TOs6vTlH?zRO!%C^1v62)2^h-hKzVFmgz4%URvJdW^Uk+>vh;aN8 z5C7T|*WDup=f}NLpFW)nbhjKO-nY$xrMG4~c8c)fF=}i|#-g9Ga*Yvd1%kS0Y555K z_higmqEUa}uvMrBCEBR7;bGB5$F)0?d5j+ylksJT&Fbi>8iAlLdJg&i+QJmbL0z=8 zeCOn(1RQe5N8|Nqvb1w@ChRv$P(Nw6Mj6X9%GJ1`D&2R9U$bCRU60bg`JSJV@mOLK zs!4dAD^VAvw^?Mu*fp7dh-rP}aN6KlO*6L(5>+S>otFXk%P&$}s&wC|8nHA67wBhe z)&*q?1a*zPlFs{Y>;J?s^^HQ4N%J%hrA&z`l=$hF2DNq+{vnP|8jmOa7Hd>RrzEOS zqQ7k#3{>q?Pbt)mM$P&hfuB)-Mf4U;a;wbZH!J+p$e!@0}`9g%aw=_4Tkpe+oxkKWi zC*L=t+nvkjah?QY%EuDT)Mwiys!(E);dnS|pf9_>ImBaZt~?aed%V%ySNIDAb@lBU z0a4v*$iHK(Iv0TT(|&1g8TFQ^LWxN&!XR!$qd&w-`$1R~si#eRw@ji6CHgiDgFSB> z$_-By^HR;r_d}nqRkS}xISB-H1$G_*IW~rWV$AK`9~Zo;rv24mrbHD=jOsZQcK2;1 zhfO)lV-&je#>}5}v{7fx1%kQ;*$xKVmF@n-C^*^+_dIH-RchKuRG~z*g@YjKu*Dyu z%lMuMn+>$8>JucYP~yokKbU53Ei0@q^HSk}9$58+p|)E{eSx5^;v;?#m~H(h#$=Oj zXndoEc4y7n5>+S>zRL%U`Z@j~YzKD1`JG#7r=|{&s6vSW(|bXW$spe=xWP-+Y7#?( zukEzyt6wWAL0vf&yTW&Cp2NNLPVBbW5!*X-(3*F*m8e1quT8En!NXl%Z+wr((A4UL zQ~$Bi?%PtNqy%+UTki^OQ{4Z=c>lF6HuZGUuF83#q^{kAEMW2c!E(#==SpiI3#fE( zuxzNf(n+D%7ix?8OYF4~u6vdASd?xy)d42>_4yOSWwr&@st?+!n>Hz_LJ2X(8Hd(5 zEyq=x+H$BPC8*2a+XC7i8vG{)cIk+1SK4XcR=gw8I9b7a03{nN zQBzsce!M+RAgGI$mhbuLWro)jPFnD2Ce(uxhj@(9{MzhV@Pc1+=3<8Dt2t>u_%{{^ z>Y`VZ$M9*7foB}GCl)3F-4D!$TY%Tqf%3VwmnFKNm#@rxZ-Kc=Nvr4gS67Puf%(pI+g6A0?E;zU=|L9+IOE}K=%r7l?OZXwM2(el4}SaiGX z>0BC}G2`oAzaoYmz5!{5rbrb^&{;XY+A!1w*Dw76%_f-$1aazDfZILRJ5NAd$pEzSyz2;2mYb+4dRq1?B=s2e~i^$WBk@-B5u+1_XR{W$5 zQiT$9CZ5mAtZ>G?cO97Vy%qvNT{c}jz{j)->&L&B!dH?PNH}f2C)>|>PFA8&LYzN$ z{pyUJQ+?Rc70m>Ky26Hcg_nA-;Z_PSaAzuqzWa(6%dPeyW;$!VXXUu zCIUfSbTtfLk#f)p%Z(VzPERuu*2z#pT>G)b-4!G6j$%s>G!Y2uqHA>cyTR%nxH{dJ z1>UTSbj=N2!z7lkqw*6+cpG^`=Spafmd#77{Ny|DVs9&F#IngT&x^c?csxU+iW znu8AP?H7IFTv5W=tS{Wne+M1!g!1e0A=wk>&Sgv!Syv#ai{1;I2=u|CzNRcrSwpzy zln8Yh0M>i;S!iYt9wYs-2ezDJ%9b~7AQ03=?`gg&tbz~LzE+oIS=JKnT}oVy3xGUr z9mZ3J@ffC$Jn+Q2I?Qx@LxG?!`fT!doH{<({o5BP38^hSgOsSYED((DHD(9bTJsno zW}Y~$&MVk3rIA2T7j0t{idrr{SX^`jMh&VXv?Y`fbBi>M^u}@bH$p*;dICXR;yQq; z&<|U@;(0e`R7a{%g61;enIq2xVa4kfaF)GcG%pIxenM9f@T|bj0l0X>7}$N`7o!R# zXgvPq#V14XR$vm0F#jkJ)U|llSopTK39EEKH-pu;#X$79v<4z}=^<4pLC+gsu~j<| zwHsEznJ(`cC8(?3{ZSD2t}e5^)QZP2u^osx^H0OZ{BlSYO3>@ihcY|^(dX#_Fn#%! zQG&V-m<)&gzSS5Xf8sG71`Wi{$KL=(E08Lbp!YHFksS%dwXr4O?(vFIg1UZG<$H3n zKSRYHy?6}6DueJ|Qg!Cm_&cKtCFt|W^Q5i|!UOpg*sbIz0zq9L4F*7o|8=OX)a@}@ zX&Qj`2bwVdavvF0C_&p5g~IXVP+YpWI!n8FUm&P!+U9=nOD=?vq%-JH4a0z_YRuF3wm?u9T|vutrPLpauNKr{14>GSm9mr&*QB=LIfR@q zRbj(>-xLVyq8WDhUI0@SYFdAnnwD$NXvQQu8cE0f_?@^r5nG)8rL2_T$f!aIIx@-g z+eAq7bWNzAkSu1i?224S5s4-=U|}6qAv4K zeC2(gaq0uxd-A^Mnp-Mt?N?bdcjtPb3MItR!BIP-&@0nZvt`a8A%g(Tqd;>5@Uhn= zQ8@mFzs9z_52FetXif#5FMLfj+Pv}&n929y`IlzBnQhE&)W#kASLLiI)Bdjmo``5EvFvJEChnO#94s6 zH!AG0J46~{XT+#N330srX>Dgb`@XgI>iWw-^AXXENn$RfPdSJq?AvPlz9|$k8&QJh zUgFRB30J(=&_vs$(;U1AZ zw0_x0TQT6GKv0*M-^XlKPqfZ!s154OS8b5IN|b0E=L-h!E#$$Ij_??6?fc@dq1Cl> z@PR;37tO=Na}GrJ!$qH}YU9IB2^owi@wgxm!qzvJdj#vgkhjxsAhwyL(0*F_Mj)t* zX20PpO!Eezo&HZvf79zg6-vxxBf;ce9eGcC4UbWLE(n#!pJ=||cY&ZTn#G6D4^|w8 ziL)PSPIh=GWd5OqQN;+zTw7kg_HZwcadQ4}bZ&H36Z%$9$nQg4*5zX0cK6%r;GUm2 z@vCSA-rIOmbJ+bAP=ykoE5^aYI?vQ0IlDOVC4V%Ys$HNdT3v}zg1T1gtN6DEwdzxS z-g3g@)EN9ae22!%;R8^G5+EhR5R;SYK}PwUxMmoE`llCb?3(E_N>EqP$_a4j*fRBJ zx96OA-!>8#-kYx(dEg6Bg%T#`CqmM~&FX&3HgRIZttgxwny$I+Sd~$Nx~kkvg=a1k z)kE6ozBzgKN;IalpP=zx{SBx>iDaX6xHn^}x_txPD!nD2V=>@XKaKjDKBEM6o!pcT zky~8UW}k0!V&JVf%suL#1dp?yI4FArbqvX{_lp>LXBv5+*U3aAR#VwcYI{oUrs#;Wq!f^1CV(7$vCd zU)d?IC^11}sqJi`06JPn$HjuJd%@CPk_`8BUk0)RhE`VQ+PitjC8|(@j*;>)GCMbH z|HW9lF0VdNg1V-7`N7~*9psxsR6Iug*lxJivxPQk;WLRUl%Qk1{QI@9dSZ4#BdyaD zQ=kNOdF=}V!y;q3#r+r_BeJG9&U{&4JM?Y^pb91EC^tX5ivBpFLUnD)1qXqkt{S68 zL3qaovV(gBk8%3DFU~X4*Y0wu2UMX19p6_dE)NU93YULr&Q$Fo5Y%Ad`irJw#}+^pO3--DC2!Tcj)w3UiN{0G zf8$+EP^>vng%WgzhG%uGJqojePw_9y1q%dqZMmER=M65ZN8KC3V>m4h!-kKKXkw4s z0aYkLXPWqG!#?47rS}fajxl2dg1UNdO@+trcB!|Q`12Uo_Km~l^EPRAK2ri!C_!h; zcs8pWJWZFQ;{}4cs_65T^4;dD>s{=_V|-~Gjp_?CG*{+20aYkL=L&iD?{%?g zbTv_P^iGUGP#5h7>*^7QZbQasnoe;MddQTZv!wj}V_71;YHF{Ua@1KMsEhW_`N}hQ z6}CBH&hrkQm#9JsafbK9sw9j}(bwEj<_ZLL(Y(Ao2gGo5EIb9;+fki>jz`mczv5VU zOtK}e`l{3}KiFIt*`|b;75M%1j%fGMR%=lxj)hYf?K$xshbf(~LQ5O%oGA`K6-v;y zl8?Pgh^v##wAR~V1cJI~&x!xy)OW`88Kzpct1nQ6611)4?@?X4W96)7+Jnop1%kS0 z&xt=#m3!c`bVIGxl(9e+O3=2Fe|Kq>H~O}$r@d5eu0T*1?KvqF89u#nccnVo`@U&F z6-v<7mAAXTepsV_W$gy%l>$LswCBWsKVJD`2a}50w*#jFRVYDQSDtUlZwOuv`KXC) zw?!bRi}sxOD%NX(7=7}s=5~vDKov^R)|KxoS{s7XvuY_a-{_b37I0o&x zs;M5m45&g0+Pd-;@lIigmWMRInrj7ux@gadk7djpjs7jQnsIH`0#ztMTUWk=r}a1t z4BMdb-G4|RsEhWTc&?X#2<+5+wdSbaCZGx>XzR+?_4Vg@&j(D`?Co$&AgGJ>ocLbk z$Y@-DG)I$oX$w$=60~*YGrSjLagEVvjoS9OKu{O$Iq}i+vvIgFFi>-5#8#jRCB$~O z$MOXH>DWnQH|?lEP#5iM@lgXq71{^a*PJL+9SBqv$b>KRal65<-KJZt{-p|wrb$Lswg5Y$DpoAagT6-VI1lLs}kYIYWKf6@%7 zG^;0H*JnQ*v!4`e+J0)ws6q+xJ*s5mNWAz~qgg(uoj_0*&A7?GM!RejZojV9^vr0+ zs6q+)?!(91JB-D~v1>Fb-7N)zx@ewD{^j>(;b>yCN>j_BrI62(67=1N=L)MGiD56M zX!7Q@7YOR2V?g{Xe4it6f_tv!b+)mPmy;6o-G}cO=@*SZ&yCV_4QVeB)J4aD6pAM{ zF(^L`)?Dmo%&0;M`tHNuwkyQp-d_%yML8A%L0xnVh<^|ALL6#CZ8gv0S}>|mg1-Ck zb(XCX__rYRHJ$FY6$t90V?cZ?{9XbsHPh2L7aKCFP=dbuD0nlPh=;yxmot?n0zqAL z42X|q1gWsmq7`y^qejBYOiIuvjjuw2BV6V-SvjrnjbC|T zO)4emR|WW+aIp#>+U}Lv_zH~f^rSmZ>Fz_mV|{5N-t}52SG{D;s6q+4`;_-yeO35q zyDT59SX&^di|+a3UtTmw#Mvct0rq2UOCKr$oGb+aOjRB@}8$Rzo;hrVfU5CXm?VDlchcK>V*{qg1W?=dPYwY(J?+jj`1{S zRG~!IauIOSvK(7FyfGh1{pP`U%cjkgAJi)+5Y#2^KASK=g?F#Dmi0|d8C59p;PXgW z67-m7``2aQU&(ViWj_NsZuT!>$02pmy>bdgz&sW9%but<-q4y+g%Y<@f?@y16QBy# z?RN5il!Q>MRX5$L5D4m`d$af`&Ri8Pf4SVTD7g)z3MD>_9twQI10*Nij**pjl5oX| zit4U5+E?@fx5b__CORG~!Jr9c>bV=MT2>+&;9=I83({2$8uO{xe4 zb~dx> zs!*b!a3pMw`~ky*?RboHF+7h~(9nJTm&FJKboFse{uL$hIU z{MuazY@uu6^mfK!yY%JKzDE%PL0z=%;-ffqVzBLCgvFM*j4G7S@a$r>&K`s|n{_)t z_wmeM-A>hofuF+#g1Tti#aC?AiosVa__=V*VN{{SRU8D5s_p{F(PhS)kQ0YNiH;Eb zY@9$)7j3(E{=~=8Xjzg5O(*6ss!)Pv9pm2&bBV(R<%2+;FkT?2i?&?~#kS?qn4dob znorMVRH1~JkId$JEc!1?g`^9y0zqB0?c%$B`$VHXE`pdJlZD)Eln}qcv*~m+UT85N z%+6&C1a;AG^C%Px&BL+!i2BMkGym@!pt^4@(R?EGnO7(>W5Up>NuG3f*D*#FO3;-< zJb%gO(HL=Vnlyf5kw8!vedhVz@UJ7#)TuGp^t-^QLJ7JKh|hocj=`Oox220gT7jT0 z`phd7H~8*>XXYNT+~ORg3MJ?|ApR8$c?>4TH-eiV)dE3X^qJ@P)wYr78Jqwv+fOs9 zP=c-l;=OR^v1sq*0gxW^N>HERU=rE%SCFsf_o>e6z9Gwl;!Pcm40zqB$ndfUDw}#=xbr)gj z*8Pksl%Okzcpq+GI6mE20GHQo76|I1&piJ&d9%^@i05I*Y^PyVp@g`mXyBP}{zYgR zE*;$@5Y$DVd44_Kj>ZGmFGCdDCuAz5gqW|db@j10zQJjzWU)&isEcMsR4C>%L)@{| zU3);W9@<%$!-p;d8er9|wQ7z?$#e zv;&5%5eVv{=a8?t`_>Y#6}xHURekwR?EhQGPU}Hu2lyJuPfc)r9}lgKWq)DbfD-6Sn0H{I<@m#f<+7!E0^3bv$?FE9m4n>$lpSc0@fs?y=jOD$W z;)_-u+FN^EfGU&_&y~5RF@E0Wsg-`YE1&H&hZ4mQS^Dxr`AKUI5jI0gcZty5BYZ|N z$PjUB5ADI!){a!6#3c(0$hiBTJtoCYEwJv&ZrT@pn+pVWiMvvcoNj^xi#@b`ql<;J zdxl@Nw*G_VjF%b0mF4pW@0(!BP7m!5ey-^?r^LQ(=Ft4rVA;*ahM%h&+0F3d$L`v- z+oA=6y6El^{+z#QjE^!swccxuB&ty2I6sHp{2Z1{)9qvFy4?t2t-JQr!7oZmP#4{A z!dstTjd4+ur*_ZeuS%*=f?g+{)$y1SHpz3>dd9sH2$(QSejc8 ztl8*N*Ze_E;5g6ataF_@=_zd*lwSrxkDFF>S!xzO;r|hXMyJG}k^ z4@ywi-%CXmN;u7`0QcWVl@Wsy)J4yTSgP2eEtReKE@IvJc@%w3*=>GK>EB*YZml?V z@?;t3iYk=2aQ=oec=m5vj6n(N+Tb)**<;)BGGb7L5|Kx&q;eCo%cwaesB8Yk0n%$# zRvCn4lXSVrVq0l+<&jkRUXZr*Z+=gyb=T^D@2lebi_~*grKxqw=uTnsu$bSwKKVVR z=4Zb2|HYb9g%Vn)adKguTJrzKpagZL#>B}BQht>YFRi6EmwC@b&mLAu){kX!nb$)D}8mKU0LlFRh;A-g<~>)yXcYr9)lA1w`CXl{VFR4Jr;G* zwo;5i6-uN}f8Ttz>+cr)?*w(xHeV$4dpD9VUEw+V__<1osV(0(8C&|du5~N>my;@# znBKjDJfu=|8CP&trk}jNb%#>rSW92I$s?=MzyGwZrPoO;6;&wVblpQfR}5vucwEa? zF6Y;;RQb~mmL7N8MU;EKaW8|Q3MFW4u~d|xuA0VOW!ssqWyGKgCH`KI-3wymT#s_4 z$I6-$E(cVsS^D>%Ux_l#75$yK5S<_|I`=y#1N~hQ>p>Mt^xBsqFL`-K{lD!lC8+Dq zFJ~D9RVZp)RpU%CT~CepX?X9n*67qxc#J`{BY{;OaV8Hf@I%iZDd{9 z|D5SEVo-$=o$rm3t5q^6rNwha3F@N1?IMwHh;pW3uhL`vTIMPn#QomU|My>Ks!$@` z-a}rt$+?VDQG&W?X~j}eg%Z1_^q1GA+LaN564XV{x)_7@OK1s0e45FvdyXh02JO8J z@V1am|6~oIv>1abl(^wyBdgB%ml1;!)J3n87=!jjUTxp0zSAhZ^tgZTmr#Wgmzou; zeZ5o5C>15B>)!R->V~~0ltEA>Kbi}83*)pazD*b=4 z9#o-(t|zE->S&Sp<0{Rb^yyZX?DEp9wCw8kIWpK)EB#v}sM4`_j+|%pvy`Ss5(%nM zqQ=)88RzAe(tjtY>+kiT3MF_(DEU7bp~M)Jpsp>-T={Hjxa0qxD|(%09jYJ~6~>g_ z8Gpa#RH200p_c6C6;Z~0MG5Mn&!$)ps!$^4qJdm6E3Awdl%TG^w?6b9o$`8xxf%XkK7?hx{KlefzF{na`+$&Ax*}Fr_h(QVJqP<$N zRJ2cJv3`WS?S(<J?JjLGM1m@mShzYzuIP58l>R$GU9<%kiN$NvB)hENV+&V) zI!kW&`|VfvtDtLP|F^xO3MF>Dx0f=*|MKqq-($HB@mF4N@_VF!zUhmlq6#INU1+*1 zx>H%>43wZQI!YnN_+nEibzGVz>uSi`72U{YX>Hp#zbRSFDXRxS6-p#uy(2BRD2t#O zn&|j9e>NrE9rV9vmnxK?Bk5v2C_!Cxv|c1=9xs}2ibF9(&i3C+BLG!KsouDpy)*H;gq-#}m*MQ~< z6bY(Og5SfE?lQl?f4l`m(+dzNlv}*Z zF5`Mog1Tt0R*XRvN*rCADQ~)>DkBCZsEhW<#Tc{=|F!(H@>=-s@mAXAiv(3D5fEFT zO!za_`*(u6XgeXl>dy}QH2t`$I0ik%X*`~xhx0VoqqQ@Cw|ER z>1WP=dar*W=&>k4vnlIh{a>jlL0z=8BJtFGJHHFLzJr-)*Lw$Z5{u? z2bRt@6UH)+61h42Un%kr1X_?dn?Ie6Z#n+|L7)mlD5n)#keG00Jo~UUcfRz`1gicV zbKDz~?`{<~@ks8h%D>v+e~1TKkeJ-jflYW7^v`|jfA6_L)xUZl|KI~HNMzh?z`8WZ zotctjjs&Va<~3ne8umzC@|DWS1v>@^B`cPi3B~1<$T99xoHi~^XpZjk9OrQ!| zYMH=XvOldS`&zT!f8-dMz`TUSpa?(KsdC+a$cadx>Ue~>jeWiSKM-hfX(#T5-%{!S zN2ri!voDJ2KIhJO{y83~`rqC;68GH137%TT{vjUtEL35BlS75&xk2;RENn$P({uk^ zYSDs3_gZb)r&<5BMvnxlFfWLs0F9k#$}~L{GfZRIJ)QY`u_HQM?1-)s=ggg5{J7nb z!fa5aGf%!8z>fx95q;7Hjmy%5q%L&n>QWZ!?!@!73*^0b+}BUFbmE)EzVHVLg_(t; z6W`y~pYKS~c1Jg~t3r#acOc!kaOqjT0Z#n&^FVHRaz>9&66b4cSD`KUJ*nf336c+d zt{kch8P;^LV>^0uZLZ`433kwlk2>MUQ%!re4O{GK{nVC}S#hRBpbAq&>=90?Nj$`z zMo;pUh;AZ%vTp_OoZ2~hjFb2(V!fKwd8Ipj-`<6x1&QbgXFjD`AWyxhjS-X%Rp@5r z4y2CkED@->C(^C>n?SzCS0jc_twNcfJ*iY}g`owBk%>#-m{eYy4>-i5cS)71xU zsml~=h885OL!Ei)IYGS9$~l5~F|soC|J;G9|M;ax0##RLIPnQRgLxU#zVJP1))Z6K zgJSnz(WB~lFJ~TlK8T0T9Iuy&(~YdDXNU)#Y&-U8ltpzc(Ni|yAqCGWy9j-?U5<5jnYcnvIPoAjlbvE3sL_219 zk>w(Li9l85?M~eCdoYhN?T((Y(Ta9$XitSYeRV|(5;nres-$3EX|(nQV(a-3$!4C zdnv?yGMSa=$q6s&Q!msN2~=VHbUNRo{U~^$EpHonOrf2ATz4o^fA7OmR%c@X&-bL1 zzWuYs?Dfd5+|TuHi>3$Gh}vg&jTpLkzpVPC-yWr7gC0D4im&ng#5v-7Yu)*TM#YS+ zdoN~*KYQ`h?`G`pzj>A*nkcd4*Jy>xwslYjHygxnJUU`*JIjG}Jv@NdD0JRvY;MmA z-tW(gEjn)WI<4L1U1fO`RqCp$*JE2N9R|j5YWdWdxyOcmdK=B{R=hR(&8x{;ruF6B z^$(3XU$pb*dp~xgrTL1`Q@8TU!;J2HVh>y1YeRYF<ny1qJ5_qJUF3%4&T>4eYyD zDgMlffB8_EfBv4yXrB{rw%3veJzmZlWi;ev_7>wy`YaX1wKQMqb=s(Ad^@Y?+dFaH zw*vg3*9K0)qoE;`N4Sf#yUZCKGB1op3hXRs@_#rtaRib$KElP z{$hw1$QepceobS6WfPQ`#X1;{-AAcnTexwwzgn+bL_i^x@t5bz>jyrLeto`|zyl z-t3fn3j4Y_oa^p)W^?a~uOsT_WT()#6)VNJd~Fr9AQ5I2!N0xh$ZFar3u0aO6tcd! znhm*FPa;rtq+$f`T|&=Bju|D02U}9;c+NUj?5v%F79^5VBY58Ho@}+Zc9ONr@DwUJ zeE}O+ww}^qZy1l96Uu5wk7Nl4!uUt;P*$PmNV9kxTbx3T_AO@q{hXvwAu+dFAHJ-x zFWcI6nD7y*rcm)7%h<^bdx=05rlI)K#*#!T@O&X#-X>DfcMajCcX+VwB_=Veh+h0d zSP+XByX{B3>&^9_BiY5NTI#-SoJdO!Ph}sQ4p8u|jXWRBOWCHeQ4iA0-k?4)kpizw zVM9OnQ}Ep)F{xB9{@iX1i(Hx}e3Y%5NUhGyV5J)kkO)*g5?`V5elw8uTRdJ6LoyR- z#D!_>agDwTs%+AG@i{$4F+;61CKK_7Bs!6AIvZ0lSV0RCz59pqQYQwpingPLkF05l z)N}1zw*6z2M4$@OO`H>6mqgWn&1A2BcURDYM1xh2gu{u6N5N z0#%qI;f_6~VKEz@IZ=da%e@#{ekF$mPTDUKsKPjjGI+HYHHfdE{GRth>D944 z-%w-~>-=&KoAszOpX;-p-Ksv7&9&&lQ!LlBdlplLk075Adit`Q;#}~#f|kY`y6|Q% z*0R6@Qy4x;r#qGtO8%8gE0D|NE)v8ZYobySKgSxfIq1ghk; z%3c&n4>G>7$4|1Qm?QBu-G^HxtzdWCYd$tUjiOuWZ`qH1rzHYa_@2Za5YzprPFE-8 z`?cT7-C$2X<*)5biJs2VqCC0x@$KwG#B{Tmm#g4UPqx=qJbV6<;(^4DwjFrif!o;E zqSHmFHZ=>Pr(dm=#J3+L0#*2KM2nN+M=j?#DZh$~P9}s3-@!#!PhLj1gEdLeeB8?8 zOP#MbRH$wN16q)n_k{7E^%t`X3Cjg>H^qlG2DvIu0}D$8stUQcjpWf|Es1kw7t zCv`67tL#fJW3X~+$ro7?OWiq()qK&CTeMYK{o%8iYgYrmSYjtT5j$THh39%v%!aN? z%T1*WXhCAYMmHYbEsF*0n5p@&?@VQ;dMZB4N=O8%6@StN20+npba#EJU}b9wYXe%4$X?%wkNa+#K(luMKeRDJ8% zlo!c4!E{~b3ZmKoS9TXra>*xkas?IhJ6a0$I>hs^T?< zixj2Zyc!0yAklARW1ced6dQg}^O0GNQH^g&%C(EtB?47)sJ8ZNOyi2DD>To+(C3mJ zKX~#odvjy~!w^nxW5++FA7o=(R|p?3SGmwd@6pQMC$$V{K>|ao(@n12jLttEqfF^+ zClRR1pT~~-6xho)Hr7THB|=>(=tGL)zqY0UElA+I5xv)Q%_;lXaOGRuS`vY(nMPZF zu=0B5cVMINarklz@|=*QtQ=!wKnoHJx7+fgW!JLWQ#T1>6d9=X_Fl@X>eUU~#7N?N zi7CuFY!CYuXv@c5p327T-_53XZNLj(pUv9EYDATIalU;}sIt<#x&bXntO~c~TcT&M z2S;}aqIG+Px;%_jp4-%r2vpUcX3H;@S;kiRZ54!@LmMj6xwR7IU}d=5%9gthj$-n0qIfv`>sLT|$d!6QE4!Kdaj_yk1{#FLGAn~B3EidponK}G23S!|> z51PZPDzmCoHWch>%RL_JS@4CUOz&gM56^WIK8~=9YwGhF`#sszr5e%sa63A@w3bqP zPh|sIkeJ|R%bSexV|$Ap62#5lZON&JlhRPBA`z(SDu{2MfvmxjgMwJQP0V&}E1|6a zRNk=dSbgsKr2+dsn%MOIw!HZqN4D(FakEgRhqR~j?aL`Kb1O+ckeDOlS9qwN{k(Nl z_^`O_K?C*2~=TvTLx~w?uuS`%=FneRccBR$eV9 z5valx5jXIQ*5F4(ekFKdMJcV2sGDTV^H;TDfA7(JR3}ebQ?8J5XrWA?3e!!ei!RWS zu5G=-IzKBf#T?@ly~UPK^(e@`^g1nkys6%qiXS-1zICxQpaqFmAr1KTL%;QB&KwrR zr*fU>vt1UuP_n#4pz8DmTmB{gYkjrIGlJ+J(uHOfk7Vw7Ee#RQcD&r`E&5~S&oN_V zJFaug(jU2Smi@fmfPZOxR$s5Q_Ribi>`a%djb#T@Ee&WvBJGhaU)lJU{&0b_g4lbf z3uWu)vi_&bNCc`dggRYzPABTVb0v$8D`!9p5;^y6`Q6cf>s{Y!@%Xx|6a8@Bz# z`VI}xvB59w_|&$x`mny|*inZ@qDR(QzoftRKHiM>p+&CgS$CS2GN1*C^Eq}ra9=Zh zr-@pq@=xwYL+V-R%damf5valx5xu_I-n71Hf_^|+X(_Fcn7hD^f9&30KVpjJ$JU02t|}oBsG8Bwp5I(Bz;#=g=A&wsFCB}{;$!<1 zF?jvmSj=*qX>Qx<5Ytz4-~)C~&YHXW6f5-8p8M8pmF3n&E49rseQAu-4n9RKVnB<> zXL}x(SU+o42wv6yVJAwf&6%8aRXYAC@{^QFZ%tX#h|a6k6B*b$=k9mH|8%P5vY>WDlktE zYMXVQmmOW$fa!y=-5ub-e|X-_N{l%vd=x6;N0;Mo@Ufrr8_FZ5+{|0-qmX;zx zyrdp9^jlta`LzNPfvTg^9QdV8WsK`{sd-!zbx< zp6NZw<%*q}S}d;tEl5;8SsxVGET}X+Zl-H|_ zx-T%l0WC;0+vC8O`8pYEH9IbR)cDYY;%*mLZ{3#(RLN;|r&do&elk+Mxb>Zq{-ZVz z@!V1?I@;-j685zjZ#5{x=v-nKGmNXv*Swf%410dSEOl+a^`t4aJ=M=m zen@W+iOxN0^B0cejCqr^-cpl0J*oJfmTIMlUlM^TeE&LKXSw4L6>_9&grI( zb>u!_SBWMYV`Y_{pxbIj`XS_pzEz-1WAO_uRk9Y%cuNBVRgLX}6j;=%RwNsHIvUB7Qj1gdc6Ufj#Mpc^gNo}>2XSqiQd1aETU1+B~Skxy2bts5M@(v7ItCH2ZW zuHcFS63KI%cz4HATz6!Z2vy7)UrL*HT)qGKkVK#g(@>{-^t?M&u{x%{U36SZD6~VWH5S7=_2Guq3a+cvcXZ~3(rtL$ z3G+3U(W|@Cn$>UB{Wfb9Tzx^}x}7usU}?j@RMzH8I^^v}ALcwz^N-jh5vam66yK;a z_|PxA2kL;m+oZHYV&O|CzA3H>f4m}7_-Jv$haT4aTirEgmqefnSA@jZPYqpY&!z9` z?`N6P>JrB3WnX7L+}oM2Ox9+jj#lbQmAt;I-;{+4T9BwHW+{$rwC4%0G6YfCuM^cP zo1gZMm?aUY+CSErM<>hx^1f)*rbu`^#SLY7ig3su_Aj`Xrr@3TNNgYP%%4B2&tF?;@yM6mku291piU>IO9ZOqn7tI{8zUtA;o_FmsYZlEpbFDa?6L^LYwCU)7ZdO>8EJt}#uh#`1==zW-&`{i`!CXYb2DI#{uN;`fCjzWmM=E7m=$ zDQ_0w#bYC@2;y0xW^{ONeX7^(sboPSRQL!h>CMZm(pJOow{@jOBb~@?PaXxIg(?i8 zm}jWdf)c%*X-vl=3R;i|7e2}z?8;vk)8Y}*sRg~QDN(5it)I_P}Sy^D?j$hgZo;W6EE(xAhkpt zTIPOEdKMB2YsU9|?8xVwC?-PH%C|YqK3SL2ww#m*RAIV_?;=DqJPKNnC|0Zs-|beH4{m2Eh}}Cn(LBGhGzm;mIzeg z&Jpn)le0l|O?|6A_O?_0j_A!_PAS2ii(0XzrGxp;Lgl&Z(aNlMr9eJW~j+zQuknr9f$lvU)$dwY61>yYBpH4sip?0lZT_R8w#* zGVX-Yw*6OBzby@v#y_I?szpDH-K*DN`*|N8cCi4zP}Q2{&lAocUM|F&a2r9CNb5}@ z1#hb^!|Ez%L1K@4IG@nG2=CjdnjmhC38mU&?x~Y(oFxKPm?Apeu&8jFP~k7N$8Npi zGPE~uQ#KFZU!esn*t0JmyWpF#R-YPXp>ld3P7mf>RKL14mV6-bp=Mvc>F{@BFIGc@ zYQ^Pnnrru$8vDJGM4$>&MC^_Ft1qQb-J@oM;Xa~(w*C3t@N35JIkv*b-*$1d z;`bu;c;imez9rnNY)On6JCGrzr2{fzg z#qNI?q{O+O^?ub!F4=4u^5l(Owl zF1Mzu+#*mSP=z5B_s}~GAa{o;>ZsQ~3R;j@+AM+B`g^7E=}l+hqgAK=^mF4ZbwEm2 zi9nSc^V%^(C{O8*>W5;X%7V;f{=P-DadPWM%;rZDKe;8z7~H%eYh{zjv&#)MhHusj zA2C~oQ1=S$)Xi690#(}zq;Q*<5aY#XjRcW*ZUVVoD5@459;+08IGo4FZ_BDskg+6} z;kzlbMmTL<<1fIbRZkhmB&jAyQ?V{GK3wVdVM;%S?Ab2Z<@ zFo{5w9CM$5M0#6zHUCm7T4~o}1iv}QBFi|vB`eo#1kZLgWR*Q?V6V>%<0tP;$|_T+ zjqveIpGYBBxA7NG`zmNbB7egXd}hC~Szf7%AZ#8a(wVYFxP6^i<>-XreCp#puBi^~ zS+xhld7-b-uJ2y7W#KoIxZ|$X`vV-h38IQIk?s|5#^Y|rDriAsb^8%KqxXguE2Fhg z9cZ0Mey=n5jKTvX0#z7Vu?nytk!ssb;_J&sOYuM=Tck+Qd4;md?QAK0jE+ns&l^km z$l5Z2DojH$?~^BqZtgx~92XEH#T?@_!D~1#^5TK(gAJa-$N6@NRDEG(erQU9f)*qS z+)m(QlZv_0hu(s?@g$MF(%Tv@Fy7v-jK2SAFQ%MI<`-P-^@;bi_u;-l#6zqJuIT2kESNEr&%G6{ zx7;7X=8jC{Q@_sBmq_lxPA^U570=AkudCNX5RsWllro|dtJEe)K}*?7$^7c>F#YaU z-VC3l)6JZiM6WX)S&@_w$p;c|ZBzK8uRZl0GP(*M&XGwpylx>Dn-VS&sFLH6yd;U1 zRV%`x$A>6rL85%06yDUOqkhGKF2YBpg-PT&`iK6lYp6t^3e!-G=yxX3gYikM#gm>2 zrVqw;*w&$Z+LYD$qMm-jhf7!z1)mRL54}PZv>YYSk63y zf)>AX1G$USXMHJ~aE4FP=|TvkFcvw zjU)n9a;V zBKW?Q9_&U|BE!AIVl{kI3e_#XjeWDTm39>);j=c1zlv(XZoVEOLRBkY3N6-eWA|n@ zmIzc~iiqz)j!U64Q}?jVrR}A(LZbN9DE{Jy3p+GL^U-f)3K_=jXVsqBNd&4e-NYK? zi%w+N+D?gWR?>ibxp3zh?!^+{+A8QtI|g=ESe&J_D+~$T4I_4>bakgZ89|D7R3(W( z74FLs{q}GJz1ZJZp|#cqv>+kxlX(&AN|}2Sl#7*YBm!0PexJRmy(qGdrE;S0D`|h? zz1ki;ZSNFT<9DXnZo|cedeS7vT8dIGp8@ysA#u43q@5@t|V;+9}IsmX`=rVY-PgzmI7{pT~JB zRu)yIT}VjCJA^{=wW4hcdnl*8tR(_fxMxayq*AQ*W%eknj4x2Y;CoHaSMCaA565g{ zgO9Z1b94jP!Y5)M>^D7cd7=&L7P(WTRr?zO)cx--?8(_*3R;jT=jg$k9c;zkb=e?@ zb#wgaXW}z;*sqARbH+KLTKSSEknk8Q1#8rlY8{| zr1x99MG$jZM^b}LQ(5A&s|s3>h*;snl_r+#V%3#`NcHVQpFV`LD|A;PP_?FS2fpU# zG5za{nvcC-BB@$xAj^L)M?nh`kypF%z^C8ztw(7-@_R`i`6$*dl1@zgz@sl+RIaaT%WKwfGI}-MD4p%P=;On$t&7Zxs-gL~wkDbu zSuEt2KA%v~f~Udol$cJpV_OUbg-qjdTS+2N)kmC~{I+_CD_zpo)&A-pK?}xpQ5!5h zssz{b;14WE7)#z=#kPF!#ETAdH-@fV#@Zd|!qYa7H&z*??Zz#W>QB$MUtn}9uK~+5 zmdCwWj7JArvWR1Q1@U8P5S3hTjM+zgSI~k4mNc=4Wp4nr8MBc+n48Cd1geq)6<+Sj zXZ^?;+Di3{t-<6!UqY*?1a@roCj~7?U`Z3>^ESbhT*{8Q*8eFHs0yjnlAqo%Tkm*Q^HJ?*2vv-$!fb}W zSI~k4mNc=uZAmZslpd|mvHB_zs9ICM6+b+(y-Qp@YEEql8Zz_}K{$B?46k z9o)Ik`c+v@J+=uS#|rkRzE7XhGsm-bjAMGT1o7wEDWJY8)kGcUG(JUL+Bya*Pb+ zwVzEkc33-F_?VazM@L)vt5wryDQH3BP(WW^U7ul`nJ-ol>1r%J%{y4F_H4RDplb1y zFz)wat?_&rZJpB)6h~IR!_>>0CMak@;{D2geDud<#=n~Q3!;W)EV-V@P`8JUlL%B5 zUEPNl4>({vxky`4e7rQ4wj7$GUavJwK?@Q%Co6Vx)QX{H@e9=tK0_n|Rh3so@`0h3 zjL)4r2p=ui#ZZ@}nd*p{VG3H1z&Tm5pW$mXooc;7?Q+OpB2a~M)?zklOFz2abc4FT zO(z8{NZ?spamutvKT-m=sw)q9NCc|nx$x>=V`UTNFIqi@6d{1B)5@cCl1< zinAJL+#sD3MgnuFPG=Y2kG>D>tahooQ6f;arj8%Kk}=tMdFK?7y1Tl@(B0{Q>WQ)| z6tp0LIaKUoZPJhao*%DwfVa2WXx#H-tniWaupjk5ovOZ=G*>|j5|~59 z4x#DMv|`z0b&l68i9l8Us^ZlB%VWk~7D>WKRqKA#>HQ2ff8ay~El6Mv6(iwked+1D zCF-4obcsOKs$b%qzQt{0{JU`BV|>AAa!OjM#@P;6(1HZ!P@S%mK8jM4wy7!NyNF1j z>c+_s?z;P}(OR726*+ND6rC@>OPxBew}KWVFo%lvV?_jQdvj1-oZV9*P=#wq;=6s- zBdJe;BWm?<4{3D?2|On*dKvZ+lymx&y3fiW5vanICb9B!wikV=_*Avu;ViB8;W{3! zp6PUblX{W9>J!y#h>Nryg~Xc!{$gZd!3WuE^X+9y^ri|UZm4(Hx=948%*nJtv+tZfdKY zGR;3ZiXJVUrG6~AKq63uPQo-uz;b4aTzFwUc^1TlJ-* zmr~V9W!Fdqs<0jtW1P4sy18SJ>i1=_mJO??n~v<{nXGQJ0t>Ca!tK%a1@26 zwpZ5&a;e@$0(<0Q4%w$Kl}c`)ezPEnKo#Bxq0=?;=|c;4^i^N9IV|<`(MK4y=b^5v zj1T)}inPk`i=a0-DeBJAdlj@GfvKR=eJt0978aeT1_$ht2vpVU(t$^9JZ^mcbhhwO zB&QE8N|>pJ&RMUZ1qpncqE+(sJ_dB+g<9#jb)?oKyVo*|UR^Y*1+6A4Xh8x? zm*~Tl52e-vPpOUt$4dmNZk_JTAC4-A z(eHIseZGx?79`}I9L`&P=|{1GbbNayi9i+JYa&(wrgx?}n=O=LiKV3zZaBjxpA4Iw zt)ssfNX~Wzn z6q3#rA%P=(aYpfE5BlrIas8f`(?Sw~Dm--~MydA$Xw;&5#swDnq|-G>;7DJrxWDzM<=yJ?HO=x%1gh}djM)1T z7etF!H0R?U{8rF{1djAYYcME~DnD7x_b2G2lSrt-vnOH|`AIOPUR=+I*8HNN1qmGK zi=DFPf@tZnpWJHYXNf=+o}m%rbJq}RlJc8>T=q&j&4GkG2Qcq`FnM;XqaH|jArYv; zvnM*;Z95;zj4DPY4^&Zb7aQ(w!&*u7uWor$)`FtcYlgE_`yjD;aC=@xoPMcZN!zzn zPUQAeJ@QjT-R2U3Dy&^asde%tWlmlSo#Z9eqDah(@!*Bq)#SC8Yb(_c+W64|%P(q& zqJ9#ADr_Z0kId7L*0y@DMr6cFtpO67I<@0gMJn-G>Dnq;d8UZFRTC?S3i9i*$+B)61LBSLg zcS;=}J5Oqzkyw1a4PSmu#|vgn6+X5v2%$GajB100izNb8*!vJWmz5BzQE;akU4EU^ z%Rr*tBsbpP@4hi=@Og|4s<0QO)2-|mO1JkeQt!6eC-s()nB25A zpM2?nu~*yW!pFCJy{Si~scI3iDH5NBD(nr4Im>sUl*9HDl9hi9i+3MvFHndSsOoyQ+mIUXpsRNZ_oxs2K|Np;g0}dbe@5 zM4$?L%i`R`wFtWTvZ}iB%{c`vNZ>rYIGdsCD{hUbpoSJcCK0HTd*Lg__M;0=|K`iL z98l1LggirUHzby_4_x3EbbBQNRX86c_7okArtt7i#-mlwD7YShx69#-r&tYN*q1)G zYs|Zev_cCKxauHsNrMQwes(Rl&wEoMP=)oQPPakVhhjf}5WuprUT9Ck;FU~Z02h*t+v(z8c&PoKT4%TbImCzf;o8?yvACqhJ zqBhNzs$mTeDri9hOR!FNp??thciXIf+iR2vRPAo-$}fKYX}tP&k?^5B4x%Fa_NoP4 zw<>5s0&601O6WoWRVs2^bt|+%B2X3EP0vqQmE`=PHrlTGBY-w_$W|9@%T&;U1lFkH zY(}adrOmpn4!b{3B2ZPKJL8=yRpHO9#|s~~2l~;GNsrW-uO=yIK>}L_F`}R4OF45t zs9QIUlL%BzbXR!kLU#PfY;AV%LAWoa)cLMf8K0n_1qp27#3`ZrKJ=kaews6=uSB3K z(Z;|Jl&;6a%l8&ODu4B+UtbGS@_QczEl6NXE%p>8cc%9vOVFs5Z6yL#)-Me_Prs&o z!uR&VM-|`B6dzlEadFmCWgPDUQ0##Txb-LOaUFg8N{FDBmz}fSBibezkF%V!)vPR zq>WOYh=hFh^-*up3vYZ{-5b7LB2a~OzPO*k#*aeJkh*3+Np(9C^2y@KKycE2*a^9pcZu7f0%RV)d;k~0`Y|u2BMq4gmWdb~< z8%dGC`%^`qVO%1;w^+<}?2D2JR5_0gSTS@_7vNFu+c%UHg9-4(PTA@BZNb8{%=FE*dm zA2>uJP&NKwIDg<>lm%SX;?d7GiOz3Z%I>=aDQH1L-u?M$#ZbySVyf6FnG^}R`k>5F5`n7b?+5TVqiytUj;9D8uR{~*eBFv{u`XUg3lg{+U(BTP zp;R?JkKX@Pszjjb=$*lQ>GK1w&t0^=&NL>GD)kXJ(qA2-pals$t)SBt|2CAIpENUu zR2(4@sKOH}VviRk(%;+rxHkAaP(ce4cxFS)c-=~*3gu2^trPEGG*nb|xC;F8)9@-Wn-r%9d31mNH z8(;NvltiEkQ(f#;)A+QmU0OaU8lwJX{8Hg?VdVP_!w6;fqv_)`Q0%SB?47g3dD`QdE#m6 zS|9$SY;eFdi9nUyzp{Nhi0oYEvjZ0w zNxdZ`R_g-zdE2_|LUYYWNV#}QS+j&ai<=@5sKVRL#aXgagUN2vayBn{p>&Hm5;+C^ zx$c%5^ZTy7bI*`?IvTNzd9|A)5vamj+Qq2IZ7?OxT*KNtm@nPNj>Nexe!T1uKNjCu zTchu^JD%#NEMd!vWk>|7@P2x+Uv$)9aw@!zeQz;Ox`!SKymMWrYra07W_V_@*r6E` zfhzp&flhbu>kxVsvy^SAHdXo}0uu5~>Dg6>P|Lr4)J*FT1y4oeIdMEctkcbFF^JYR z>9787DW5Dx0{0Q>bgu>vqNGhBYUcC)(#c{}Ve2F2srdj}7CTrq6i<@QJ0pSnAw@Ai zG>GDByQw~(Mo9#!u=UaD_SG3knV#L$!EeSXXh8z^b&8XdPX|%{GPdfw4;d1HDr|kk zE{o`a)M{p9wc)^N3R;lB{i$Nz;L#v*`&3YMdNV^JP=&3J*ljpyAl1BNsfHJtub>49 z+-ED|v40Tl-+qy|{U{Tt!q!K$gYE;Vx8-yG=-^TXElA)FN^$p2ti{BQs{b=%AzZC<0G1qpdhf6v>2bgG*>e=~fQM4$>=AK|0t0IKd5#Y69IQqY0~ zt|91jOG5_I*7n@^(Qds&pbA?bQI~A!Pqu468aKAzp`Zl`JbNHUsRsv8@n1oErxo8U z5van}NA!1}#!*P6O<9qT_9$pU0@o?T*x7mjT|6wl=~{1_M4$>=AJLPskE2rcCh8Y2 z&Qj2V1g@lr8R5zODZfk#RI`@*Y+3i2c>UwAc5!O z#J2~k_M-~Ex7mraha>`3^7kg*Ob;j9dtcd#54WV#nMmLXKJm`QN?iYvMU;ytpGyR) z@T8_rcd4P+k@C_)Ir33wKnoJMPfDz~=kujIC9IUYcM3`bs_>+y7z`x<-0M zT~<{hP=&Y6>vU81)S$=L@3FPfZ4Cau9r>hR_DWRaKI~#~Cw}mUgK~dDI7|P_i68#x zpyWK%&e0zojxw<}wu{;YU zf8q_EtVu4hGnA>Ln;G!ANQ9NN=WoitXHlQD^9E~|IM7({$;ztwjU)n9{0#%Ju z9C*b1JWAb;8lh~np#=lRDK&n%7|?=5Y90qZCp@n*?LoRA7Ui+0oKvHf_zg`Z0#y!I z9QZZg0?O;*+FqOzVK(&n`zXb|WD5gYkO<%4z~gcXD?v761TnRwJtaO)QWmakCK0Go z?P~LhGYczG78=3&+tbK%@k+5(%?xNk!o{UFpVXy@Vw|GQK%V_>L&-i#O3r{522}mr z>%fQk7g63E9L;3nah_VV>&8&!ct#5YT99~uUc{q$Q6=6=^U36^Cr->x#b0=0~muv>*{Rpf>+hv$RsaxHiifRZPP;%SZz-9782jDEokXhCB2tJ=Jnv4XOzyLQ6u{zp41SI$jI zyX-0vs2Z5)$ZMUfpcH&PND#4k?dj7{apgdHy#XyqG@s_kd;O@W#H=4Eh??tcXzewF zqCQs)XhEW60Y^SDUnQl3h2~?(5PSMwwTUvJjb0*9bx_<@JaS@H<>X`SY~S6lHL3Te zs>@-$GpDWqOEdumjry0UQ^ zGoS?t*~g6vHZ;aiTe+6iQX){b(A$xhA84hFS*3-lUw<1?KQvH|zBd@qf&|7%+{03} zCi(1t%WSgUq*e`Evay%M_Zu(QQqFm6x7;jjWlz<t;=vXpaqG& zEuDDF?{yT*Z=r%vwpOEvchB@&$ivXSwliN+z(v^=8qDt4 zGVn^UAbz`9i(4bV>9@Fh7|?=5dM)wY*DFnx#-lYtU#KdTXjzdh%kq>6RFxU$#8;ee ztW=KHPJm{mSEs_+F07|zI|EvfI8f1o^K76EhZlU;%l_^c1N*m_U$DCRWk=T@!y*p zDwXXt9|I57qzbVE*wupW2DBitsf;u4^t-yhS-k@`ZTGXY}9M*cCn*l9IT+8Fk*M6#__ylW&yZDB5K)F?{LalZZfhswdRQy$o zF8*H0imYyJKnoI=g^y<+>nJNtKGaLLly0$+sX47A0#%qp#Z9;RDpYsxYkiNH4pJ^D zxJGQ%794c<1wXQ-_PLqD%)DBYKMdJ1`al?E=SEW!}Q{H`MMR$hv)2|xR zULsIcoH_I9FZIg4>)KxDE=wv?p38?^ixl)SpaltIwv&k{SXc9r`x=mx$Z4f+0(k*^!u~# z7}mE!antXQgASMxU@<=VwAG}#UM!7YDt^KA`@ZEUF8gTFDA5$#ke$EvOP=>P{T^sz z!NfP@O~lzVUS>YZ>>6)U*`M&$i&&aeBG#@SEHh01pU|$18G#lgwsg%UCRO?+z6gym zUpBOm=~-p{2lMBjElj`N+Qe}Y8k0XQbTWY!B*MFwH_?;gqs?NDX>vL?$MoFq!%{h> zq3i=KNGu3>W1@XprkMFa0#z7V*#}yXcu_RJDIWgT@n$}dKozE;>;v+saaAfag?)qT z1io*+zv*}B;p5GGU=H{0(#)h<9QNOGJNVEe@w9#c6K&l|8%O2-<(5GtQ1$2Xffgjb z-rQpRYW&)aqY3RA@mW{-mABM~i2{WkMY)-$ zE)uB1RF~ti-`bUF&kAVYiF?j%VEVl<%9o40V2a0o=Bsl{-AuWm`gRZ2ZcKC2@A|{N z8RQlokD$XBAEVkN7K^$v)761p59nfvSye zxuw>xu{QF`{mZRO(1OID*r!0bBai#AoYG zp&Dwd?Y}}FNT3QrYgWUd1&Q5v_LzKBB=i0i5~#Wr^xQ<$OEV|1h8z1Jw~zbWK0&JO z29zwNh`nGdue0p;H;9!Q|-U8#O1A9-GsH}ioOByemf$3yWNV|vzr z-dXxfPe+@6M_M1yi_xhmtwhS0g$gZ5JRCXFL>KCM=f4oB!Vt=#LJJbsG07$$RqZ~R z`9K0yI6{_vVEchBgTJUxv=Z#Gu!vD6(1HZCa9MvQP<8+B+)?&ytW1dbhRQjH2-Y{VzYp+XB1LyD%G==;USoB2QjRTwAP2U?Km zdnPyL^NM#d^MM4a{+w1=276`Y&iibCTwf}Wa;UJ}AyIN;S5wS)E^lsDqL4rp_MBuN zXh9g+LX=&x}9|5^sx)GWn>}^}>H4P=#e)jycY3dc+5qp8F}q>A%c!Lf$nZ@gg9^ zM28iy<+2YXP=#qI6KFx=#PBGSkJm1h%zPk$D(pGSK5(pma%Kb5a}R}?#)GCdN(;42 zK#4LU(ZSNiL>I{0)htvrVy69+uY0t5~#vi_5bjp*IGy|bWbgOnD+bOo+kWWht8(o zsh7-sI8BH$S>Cm*q>Y43wAQanuO4Iif6TVBW}!k05>D5Ln27TG^P3Unt^1iQ{vXOS zmnFH+y}r&;n+yLxe|k9{XhC8?<9O4PXk`KRX987fzho2PUdy~+B4!Fq7Hys5#-%!@ z-<_rfYBLk2P>Iwx3l&G!vSqs$1j{Hk=vq{@6SQkzNr_mkwbLJJaZ5uZ#%wbI(2iQK>3b`S|v ziJW30wD%d3VmFhUdi;_y8coB zV?2-u|7u~Pr?-nUiwA}TRhWiy>SF!+<>s*5*s>RTtifdhElBh^J<3Gq)G=SLMFLe? z9jVooT27UHV2guv-kM=1AK7*`W+e(ONNBCVzgko?A4s5T7(zL%(1Jwf-kv5O#~#)<^MM4a{v7k8_j2>= z62EBHFv7v~+_Gyz{>PXjA?CtO^ndO(z?h>7+j%+WSe{$WziN8Vl{=>Xk0lBT$Dz5c z^XXBkT=sz_3RPIU$^=@FaBsiY6v8I`#+dm)0##V&%RX@J=GB|rzR#94Kdpys@*&=^ zS?z-sBqAr8 z-fu?&RTx@1RA@osQC_{tNA)=K@dpy9!qqd`2lm1<#h2=|8pmo_WvNFl6HrGPk?5SA zTl>_Fbuh~%NT3Q+MD~FeBw9Dltr^k->zVmL0#!H`k$t$W&8_th=ud0&Vy5>j^0Uz} zKFyR0miacAy>ql6F+6RoiD(tF*o?4Vmu|9b8#qjFd3U_&cb?&$wK*A+Kdnz8hYBr7 zlxUb?qHC5drk4q{q;$_!O|JgS6`v#%XhEXHuUuNWH1WTL3RPmp(-aT!El9JqJ8UiQ zxs5S}{d@N;Z4UYWQravYXhCAu=G^yDq3VYJLZAxc_ve@+;Z!{LJ-tt#VCDm#g(`fr zvJV`klzN!k>nr47TK_P`Tq_MS0X4NA2_?IzDc$BfXuG3x|8hq~NT3SJznKrTAo1%% zMU#)&52DR{Ab~1uQRPr!Ie@omto?MH$w!@v8Ah2v3lfm(X0zu=pz87U+&B34^bj*2 zm|w+uttli6#j5U~^DbJD*yor_TQ#vU3l$Qm!VtZ~~ zp~9SjM2A_qz5c;_pP7XU2~=TAB>O-M60-*-n9}Y3Wb+kwBv2*KM*Wpu!*FEf4Ypx> z8^ed<{~uXz9aly3{{J6DY(*3m3=|NMP%!}I>@}k(f*6E!hbU4?mw;Gc7YZnLcZ0&& zT@h@>7Q6Mfy90l7?)QCvKiAy9|9tp*J-KFQ_smXQGiwRz-C#9rH`tcTmZ07ZR?c>V zWp=QHl^@NC@>>M^4K58crE})gK!##4#R?`;G_9bNW&B3Eg)ySn>~7TB;1IlPGmIm! ztD%D>l(5|MmW|cf>e~jH&`;GHU`)IN#jeTh@A|TAWli>Xd16p!6Pmqi9SkjWpjg4g zgr-*TsjwH(u2<(%hhOSSXWw24yEL3Q0=xPLTEe|lYx3ucn#is+reBf@U~$W#6f2mh z=wJnvEH8ZU40Y~#SR(^!6rKfJPCIi1cC|^g1kK%jiDM6SjFNp_XyC3Ws5fHS>PW#v z=M+n5#j@4m@4WDKHw~%3ZWw&5bEMcMvy!;6EcnCILx3kPO){hgi9S#?U>L;;CWdyl zf^Q-H$?lfw>nK!op-WCXfX%hx9D!Y3iY#G%f-PCEsV0KEbfb4YJ3`$wCyEtJG`F;Z zb8IJpl%URz*51*Hu0Nv*KeR`11a|3dv;<)L4KAHm6FWDv&%-=Cp&YwsxH<#-@85xX z&JvGte%e~WuMhU5@?#Jq=G^T_gIlEwy0s%HRxpvmV$`s#^0ZoY44=YI)Gqj~u*rM` z#nEx8cp|mHfYy}05Nz%_Q>TNmo+StTqC7|s#cg-gpa`!871 zM(yVl#n0Y!Y;#i>%64ZOv)!4t(@bGUqiZmP?XL{8GlNr`pMuF<^?5QY_nFYcGZ&M` zclvV#cIj*|fz_+7fuepnBMz-JrUMM}$+5QsXw7poNZz19hE6E}vrA@RQ>`H9&1XSz zRu4E|tUjNlOFd?ikgQEQ3u;i3FFT+tZqdRl+iJOrPM_`xx zaWk;L@ewBbsP|g7&oicN+0IEPwsR6InE2Vj3_AS$$Uf+(CUkC?(P?xJ>Eh9!Bd}{A zi_xs^BaHJ^6SmEa>E)yaWY#@9iWN-s*<}i6oL_;_*+q<)^Tdp<%$P^U*7f5E?7}sz zP)v_DqW0-aNc>tmiWN*;UuXhl+pob?whxx=B^zc$XFMq+YtncEyZAf!^Sd!M@Xa7C z676YdSr2%@_9bqso(jcVdqBk1Cd9JqG;p;uht}>*iSa`9jzj5_F`XEiNoIuFQ>3H!m#`mZ_c*?viUvKcq}0gYFNcSiuB- z-q_y04rcVgvZ+M1#+D@!(eYEyY*%HN(F^CNkx{K|DONCnpHQ}UDbbkj z`7(q!))CrF%L05G>XWB>iSXx&Idl-(lU2WxVO^R93_jU`q&!sbyNfq6qqZwth-EJ& z#R?`oznDY+G##?6PbMSY#+cDXtCGmpYkXaKxtc@y$Y$hrT^`{3#7=yFZAudk#*_2A z2XJ=~6CL-OgDR&L`Oz(h#W2q|rsd_hX!mvXZd#Zbp$o-PV-|!Nl~D{5!kgP&K%mB=#a%G>J^g{@n&@VFF!Ky z%0P-0Oz?G;@XMIC85}^2P6-@=U9pAcklU&)8GKc}19asrW4bKWlWYhBiWN-Yd&BCA zJy+}h63Ele0(S?m&$569JM_rQn+brQ1$LrCkQp8R%AVNQE4ilx6R^+%mi*8oN9L*b zbCyIH(`Lc|@@p042<)yf(!SWN0dE|>hh1GKR*oxi>tX+sB7tYG5gA`95ec81=_ zQ^&AyV6A9&2eMy>Q0%g>wS*3A&uHn#3BVJ7KA6%8!R<)fL_)EG31`6)RtzvC9_15Q zj2Ui5)Nx)r@_d{FM_|{vgBCF9qY(+LR_6%MV!w~=znYTf3QDnp3CB`P@IGxq{%Sam z5znlR==oV1Bxl?Zj=-*U^%iiSosf{KjAX>M#%A=d?SDc0E0kgd6S(iIP#h>Xr1RKm z3v<|M3z)zz+}CDjd3Ow>fte4axIF{Ov&#WsW6)kq3N(YJ2O_|GY!k8d17k3;3WwM0 zHAMTt_N-Kny0J8-)kewxls_5Ye*&y2daBa4u!VOEC&G@tr&Qw`_Ju(+;=ulMxvGA% zI(w&nQ9KNRpsr#ZOo<3n6~9%tC1(%& z)4F57C2y%KY5T+vR`fCuj}_{{!^A*HXE_qfpX&oItwP~sIG&0z$ECB|3E5&i0e;s0 zRGk1r80a?vJU9MOt&21STv~RL=bdyaC|Zi;$#F#QeKs6<5Uo_a8wPtzvf*U6L&{q{ zhr^Kd8E_)+LPgY8^%wG1C1p_1xTPG^XdL_QYc?eM+)=iVcY$#CYzT&@%D4&_Sh_6} z7B?^yH0O9R!e~+^byzAx=VTzIrzgVK?@i!x<#;G7ng|!2n!#?i)7N5gJj}d#U3j!r z-NL1x&!j6{s-ZlpKWVu&4kohod5zo{SobX!)=Hfq>sTyw*NTNpt^NqDQ`MQ7EoNuY zlPi}(w+6k*_0R~&H6IH%T1){kEds`bhr@BUqfT>11iWYv0oT}ByzEJQkU@+3Ed!r4 zcM|$59Ige7hw#iPQ2#y*^2SbtvGekv(ZCQm5*P@Dy6W88TM_AWK>Pw|V;4tqe*}Y_ z=`_e*IUQCU3Wg=!r^B=d(;>h<7}oBd3L`7jCobL}<3p)^Ut-!pleX?K9B$m-0M6z` z(6x;VbZ@mEToV^Tw&gHbu5}3Zo>ZTHp~reKlaAyQo3`fE?sFg5Q+pP!2Npx*6;r4> zbrs&#EC;P@Q}EP219Ze{Mzl$!^h8P+`Rdh;?iz0bH^wgpH|Zes3NwKP7Z-r_&N8qR z`oN6ZrBI!-lM%bwZr_gW8k3+kdUR^M2}BfHz}q_~U_gcm9PD5W%l4jx%X_Wi%FRA- zvQTD32h~VA^~YUEFz!H4E;j+K0Xh&GdK!YZu^wxFQ_y0i(SK_V&mZf-sQM~KEM7gD zYM5?^>nqz)(`zQsRP(J6KJF}pzA%9?OYRAcUY&*JBl^I>segpLyVZ;^F!Z3OTAUEp zbZA5K^GxB@z8OO3f?Alr$`pcPCkndrYC#p$7s~rB7xc@HF=C52hBi22q`GlSn|i-C z1sw+yfyULs32if&HM+5or>uqeHvJ&%!Dyjsikg^J=1mhFD#TBTO)0H6gC%;_l_UJl zK$J-j=ovb%Qd)HyZk*^3^+ksVX1X6`#ML{#H1+Ht$t1d-INO-R=iX_m_%+qg)z=(K zdd^hUWFCciXKW$5lT!6ltYAdZc^^7fSSdZ}_>k02vw-%yZ>T;xm%;K93m6}LPxZ6= zK`1$A4c(j9s`4H7G2(lXC#_OllR~6Qa({;<-0#*_-1KZc>^*D=&1!VTeJ|I6HD=X0aYAm)4C%xdp0n7ex<4b9xY$#rxs|-RQ!|1UOq^@n6EsD4ae8w*M(n>ZfKKVxOD2U1j=(Oy zRF3bJwB;#tdH4riu2eYQZWbfr;Ye|R`Y0A-@GDAdbGpl^hDHP{m@ulff!quSvEZtj zDDF;ayQ|%0Vq(b=*tJrtC+PkfA$~vV#)vJML#b&>C%KEK2T6Hv1y^tG~18rc%8U?PiM$IRCw#D3q@*D)%b(!hl7^4v>S9D!Z@ zm2WQ}PD9@5$cF~U6Z|{CzYlzU?DV~t!>B=Fd-*_qBzGN{*!PIlq3&SO?VI|`Sr5RG z=KR!`i>!S)0=sanD-@oOM$!9I8_RFqW)oLMf4IrMOn3IfY}l~K3cAGf6^jnd`OmNR z#BUcG?$A<}Mo;Ii0~7v7tl*@9y|_43J%Sv#Za58?(^?K+IGH1`3%3}o?~^~8X5?wg z;Zv8AV*ys+kYgeC(pv)Cr?dM!)mm(yI}dPa6^g(!qiE7@ExF*tBJMgcaWvlwUVgC_ z@3oo7O4VV}C>rhANUqwmkRz}QUlThoLtzm zQZ5E2to^LuwULE*Doj0#^T5`Xz6sQjgG@>|0=saHuA_g4-?#;FFMb9 z#S1!!&4ji8Y1_N~8bfz>yCb#MDkr$r$3*K_me9bvlX!mlDpsob(>!VT%X^Y>+r1ot zUARWrX;vW~^vmm)($uxvxw^u{HZ}wK^SGfHVX&OVn03;fwkUch^;T@*2<*adB6hBG zkvARTQz@C$*OHdKE#Z83O)c@areCG@d-83;6BGV0=sY>Dimq{UUb0YbCRC^QLe5q zVLQzdGHP3j=M6Tq7{fkz(t;D0q;)GKj=(Pb)@Eb1ojx?E%{s}m_dSB&`W6@1$h7*k zs-4Te|MUR%&hw$8uWXbYAKfOnZ-9wkS1drU$y?Rbrs_V!We;EKM7BuePaQ{K7p_BA zyT81tt@QyZVasK%t}t<;izWPgt`KWwbwBa!c5gbMO@%b&!g-FsE_`R%7uk$`>HROc zQtbW@WaUkB_`PYns#&!NzCX+%D(HYJGff5M?|Oq@NO?q7{J@TFDXXG$kOykRqF|EFxQv;glrRjS&UivPsO=;BLf+|QS6 zliqMKFwv%$1q94Es#-f*9mDg3FV$Agk-QR~a|Cwb`@~MV{q92zJ(o$@#!tEXfr&M_ z7I1dnbye@IG8QA}rVlkQULhs5eZ&#ih5L^Rh0@NC26YRT9vXioqY}+wgW-Ht$5mDE zd8Rpp{8^%Ea_0yH(Mf)Kq@Edx{ZBdwuA-GKJJew-HBRm%wHqckFDV zax*^3h>b6OsMhi3Qul^h6f6GwdcgFh-Bo9DPXLb1`V4=3==bm1l5c54E(Ru4sva=d z)>759{|OeOXB&SSHmkj4cR;}r*oEtjot`wsm&TWwNRxXupjg2~-jg2C7aUcynjL2` z=4|q%UGDUjy!A9V0=xM8(fW=Tov*h}wQOYzibp@(sOUjI__6G=GBHYh2hYy&q#p{N zs?O)NqVY(Llg&3FjE`et;J( zc|}BLtCo~g^30%ZML*@a0p|e6Rwz_{UUd4@(PG78b{(ix3Pi*#F$2egzwHaZoMkcQ zNBdCSckyD>)TSJPUHA!QC(8BrrthCF6AwRY#yz{381Tdl8r`X@n0et0i*atIHzm(^ zh+iA<1a{$(CF{2nPdfQvvaq1NHpSytJg&v}iJkpvtRB}+QyLs?&D}vv6x}q1tqW`f zj{^1maG5%W9=^Y@a;F_nU>6=CvooD8yHWSX#W3n-8;Zx_czm99tPk}0a8{@>QjeXD z;$7*%vx`CJFI|ciOtgAq0z%Dg!Kb16p5M6TN@ue%iP2ZMZv#iI%yhV4|Hbn9oti82i$Id(&Pc>6DsRuxJ5KU>BZqV)+bLoM`)3#w2KGM|#u21m2wXhP`n| zVXd19OfDJ%Ki;xdZHYB}S?L1)`&2B(gw@XU(wffXlR-y{6-*rQVslxE0(`iue%b>~ zM$oE8ZOPlP4jh49xJDF;=re{2W`m8$5*SAMzj%K6j>gP7lxZt=VM_7p7-HM5Ve1&}z|Os(Wb+Y4^c^Vg(aF zN0~r-s{*i{sP2*N)Eq+l*}0JDPhB_yyM_%ifxNP0X!2EL#Hc?*Xie}Ck~pjj#fl>} zfzEppq47uwaBPL*RNtZW;hn)mqdOl16XzN2mKhIQU#j~hZ`L`{>Y~1+@R>eWD$d2- zbF(qS=(z*dK5QyEbgnza z3MTG;=m$r>ora%xi&%^~C++Cv@zcoqEhZd+U3eazecf?7p_;2w$?EK`^m+IIpbw5i z%yD+gBb!6qbLAvhk1PTlk7aD>0Ug^UlPtX6jba58+tT{O=$zBgTT+**DHUi&i^=54 z21Aa(E?h#EEi!cwt*cHT1Lk$%N`>QTHwJ^zKGNtUnX1V8X&|1enL|g=P)Z`6Z6u z{OFs;7G%r*dV&?*0WR#+@_jHea?yWc%ntLTpKn=`?0yPv>9C>x-bR^%7Xs+XGyrjnLxmJh(K& z4HBPkfr9e+EJp6<3Dm#u3%C$-f^3NMf>@i?u(``z2-@!nZ$GX9Vd-4Je~Eqn<9rmI zZ1w?$nw{lhU_w893?!tkhrGe_Sd8^ilRAguL9E(Ru+AM}N{e^)VWc{JJabDtwIRjIG!W0i(h@s zAC*C0oSF|`(}Dw4m>ZL5v*(+ z9SP}4o}lq0>p!K+*_}l{N3Vsr7d^Nbm{{345`H)H27M3pIrOV?vS{t%l`wyJFOI-2 zy!y`OkSnt2?dlSkz1^H(1ry5;vwe`>VPNU2UZZclEQ>B4x(uG3?8y<>#jonG%*>)8 zUCUwas2)W7b`g|H)za)NdcJZm3`sL5 zSiuCovkJwXmzlKlgY7`?*l`4Q87am=>Rx+DX|0ZN(LRg5$le0u&-Wo%!32I56biq- znRL+N1Mt10Bf*&tI0NEF#RSN1(H2$@Q$JTd6u8S%gq zuEtq(daEi}R@9SV1rw9@L_@O`mQYwfiN$ETAd?Q%IS5{pfg`XB*CET92xPwxGYNtX z`P#*V-Gd3>uIvNaIf*RBx5O+uVo(Ll=+T3#UF^blR-tgN%b*&wcEX(UQ3U6a;QSI? zhpbIpok{g|YQSd10Iqg1@x3w*+|%1bNl*+c)w1eL8f;tx=WJ{^0=sag3d=UUmO z-2(F-j3#>RlHqyjb>V?lC};*GfX>7H!l^dNAf~3kvAM^Dsi{FM#+iT&y6$~G?3f)y zu!4zVuVm=6c%g7(i@H=(t21b~heZ${GlnCuOJ`gvbl!AG_*D_W2p>fz-8pg(IR6;V zmFoNKMA&lcwcvO^oGT$aBVI3){`{~XGDbTQToOza1SY~u;hiwFuX=^I-Qo-yeSS4e zF81OG?85g+q0ltRr1mE(!7FnpcLy;Mc_RVH=P$x3{jn^@q0yPt$wz`EQwDJacHvwj zg`%%7d*g(D6qR|K%DIpxFoRtAl; zphAgDBnd~kW2HMMgHpGRu6UdSx}nmAjG#&=K*|P znn5?kd=j=-gmDCR;k&6&eC&}YQWzZXu1PJ@do-7|+WBJoEWm4}=Z?N3i2 zSiyvweGYsYHK#JsoiHNYI-Ty-KPZX@(HwzY>m737sy3~RKSdeQ%OjmGG20?~kBBB% zF>=ZQ?<(!e;=)1yDOFN%I@N5jUTiv+kAaD&j9y;ZxUxn0AQt1^?=-r|V7<6+=OnIF z*oEtm^>-7}soRPiQEPoXSG$`P)0wJRjXuz#E)5JFQdHkGfWj2S0)^Ek5=s;+K&;UrZZ@cPwpU$yFaWx^r@)bJBUDw(TtO#kGECjnQ`OE#om15FZZbWx+eX^06GyOu z30zu*Vps1J>h{`Rs+kqR5!iL@dnR15k5C0j>QYTuo=iU9-O1@{sV%$C(Pc_FBN(0gZ2v%@*EY6x` zZDPNPv_;fXN$KOx5!mJSBMBl}99EsRvS2aVG>fO+6)UA*tws~9U?OF3BFukNqk6Zr z2O}DHjG{AatE8jmg9*-#b;yW?BTmm%_YWEWCsVd${{)&L9FpF9IdU1lnAqQCB77{q zsj}E(!eR_<8AJW`c1sN}kK_pK!X;$mkG`?A{kN@B_D5%e6-?ZkHVKm7Ur_D;Vaj5> z(u<>c1{);JH}!Ni*Hh1ni0X7#OK-t!-i(<#b4DO|C3c*zbS~m^7$ae z=$LZZ(U`FA9uDE=t;CTJIgWNw9(m zlLlj9+nuJOPZI+cLlqcK{r2CLs_lDm1a{RQjf7WMw8WS$T^TXScMQF~uem(PtSuos z+~9F^Pw`WZE*N(5gr}03=+dw~+;kfQj*-Tq)oJx}wegB4onzlrzNp=vU^rQRF$`?3D#e6#tzlfhk+83(pO|u{4Mb>;fCr!Zi(Z%8 zF=Ca#GM)0<$$MUE5UgNgoSqw87kY{1!*m((Hf1n%aWj#7WZi?XQh=7HhlwToTf&Bc zgCUNcN@4uC6v=}*%9=Xy>j$L|+Q!wF1?BL3mQR3AT%~_0~ zO18^sKupej=HW15as*&fhm|n9bRCOv|EV{f+185aj%>&g*wy2+6MUIHAH0>T8FAqC7@GU7 zC+Ty$3B?K~f?f*n^ij22^yA8gv#!l7|~&hH(lMl z1NmOih++j30sGkMRcavAZ{5p?{xpDgXV28#P702|u03Czpy!yuFn8{DMvR{AOD|4U zklW=ADRu>47GTrNp%60f0Pw{0WIy_H@e9bmtI2k6{omih#1aF5(PORP(r-K#?^#v%P+ z8hW4A!GRwH6WFz&*KoMz+XlKc-pz=hmjTq)buAps)Sy_w#F_pC#yNZy>V~N^gnVs6 zXmI=-*gfnU!31`x^jttU)8Gxg!a#olnG|v2v#uhq0wM)>hCPjs zYqz~J_x3A}z%GMNqo94Yt8n7Add;iKFO2RiJfjLN`arOPiDAS6j?Ar9E*z@9=hH@y zrJ_e$kvw|J5!fZoa|P{Qe<@>9)ld7Ins6FfHc2$x@sjPH{67T~TNVug`;!{>p>gW9 zRGU?iH01hx@yP6Z9D!YPhPi{Y$$9(9@71}3J3EY}*P7Ib9pMqd3MQWa918cdwp6}M zRsU*-o*GA62HX($)n4NW?7FWv2HHKERH^BvURP_>Cz7@p*-VNFx1*A$=eu)6B1s(0iFcI6j)#!&Of%~HFj5d@+FcsOzAIq>DCf_58nK7f(f&8 zRsDZ&1pa>5IgO{vO-_=-lxl(%OyuUf!HIRVRD;(oXEA2_PM{-d21&&OD>(wYYCd>_ z^-Eus&jI!N;Q6sp^xTtil409}1S^)PVjN2iMXudj{nzmUk)qk5wu!4#5@?dx~;GSw=k4Q#z%8#OF@9mIk zu1)3$?7A=|6t3L*pekykp39hM8cBm}s-)6RNdzmH=-S8+ESEJFx9;|2#Fs(gbkncP z($Wqg9D!Yi+5XUSnYI`^Ts_Z_^C5^vjeRD`+dT+YFj3pn1A^Lj5obF%FygtbKg%8b zAq|uSj=(P5b7nhuSU&YqWn;N!&jS1bpF3_r%wK&qE7mH!|!kxOtwv;_4>T?8k z;r=|E_nGBQcaLf$pGnjwxPOj!QSznA>FP(_yfoyUF2-C8Oz?XxKX?XE2cvJ&h5Y^; zfnB%`6$+0=p>#^~$5PjegSooG1a8L^imZVV)S=}i>1K*IM_?Cz7T9+!e~+X6%SEYR zbr^TgF@f7Lg(7171Uk!OyW~*MKUdg=pK117jf|y=p+!>hF#g%a1mD8V{TWB=I?RxK zq#4}Pj$Qbd#%8vchtcBgHInDAxumAh6+G`Y7jtG$1pG@)G#w2Es}$m*O!XSe3hS}7 z)N_yY;qfwp6-?mYJZpDdBj}x0d!*G9N;v|%c5EIAlk1+Uqga=X{%U_L}etsuqs;m5?4*If(iUCQ7H0myU-+m zZ=$ok4VTG*^F8pGN}>2Lz=MeCivW__OC|J@)r(d3v#7am`++ASVMPy8|@X4-AJkryU#-XiP0Huj)t6|G3Gk1aU@yYMJX zeVUaU4Vl=C#9Qi6PC;37d`4sF$}!aW%y)?1(1Ihd3y;FsX$$4<)NuG~*mp{sVg(a? zzG%L=7j=rd1g@i-a|CwbQ5ahv3}d71tyR!8h-IszaUUl5OxfGJyy>9Bo1n`hmKTl) z?82ikwzsc=7nNKWf#H=F6f2nE^N_Xs`O@OMF|c(+6OOxJJBr4hcJrTFWAaRheZF$2pSc;`!% zpPZ!LCw~#VOC9eR!Zh1m^WC4ivO9AA_$PuDOyJ!^Y^F#*ghm(&(%TEqI0C!)QtewD zN|SRuCGYijxG@eUx*Q$^`7f8N8XKzT$ZBte)177>Qs#jx9D!Z@JF3;QFgkZamNYNn z9Ki}EHfuY8DxgZ0@28&Yo8K^kW(QA^zMneI5!i*_k8BRPFpU0LvQ!H8l(;u1Ci;vW z0@v<8Qhl0U!eXo~45vLd7D;a}mvaPm;rBdy5?6%Mp?W)|U!J?T_cF> z11$(vFu|_^Bv!c6GwwQahq0|V0=xK8k$$;A$$JaA=;md>^XhmFfuGZF+Md$%hCSpC zJs)s0^q9cc$7Z&T9q6Yc#`5bXUEXqzD?xqHMRsRn84#tmW`|H zOD|8WmxjI>#Sz%`^0gZ*8P!f4F8Hw+CLaT7vC#`DW_AF<3MTM4n$2ZDud z2^@i41xY?|=*3Uf(C}y$BV^E6>NM@B^k(E_f)z~Q`2g0opB_gWTkMtwY|ZBg>>_o6 z;L`D=>hOpR79;S)1iGQ+3Te*DIRq=1!1Efcy();IPumqpYsN0&2<+P2Eevuz7pNLv zP>eya!*;T2y^(Tq z=W+yg<=FvD9MVZNH!ol@%-RLe1GBG7gYt_BRxp9vd4<9h{Ao^Zon&-q6-Qv#emeo2 zoLh;_->K*NPAP+^|F|lttoJs86-?mw70Z+H4W!-Y%2Ml^Jsg2u*DRFKX;i(+_ID|Z zLCb=vuGLoQuc%6b6-?mwF1zQdAeysalN9Z6lq0a~psqc*mEBS~8mrgU60<^RpOFit z_{(PqRxpA459~a$h+ul7$vny8*d>m@uGT*WKv}bcs^50ISd8Y0!PL(ASl$=6+@=?1ob?t7O%@dOk2nPz8luya2g?lhM-9i7CTc!FK{v=x?(JH>;x zOw*80ubRP~MuG|aOtZ6b_qfxyeKh1}>*sI;cJb$abiM9HLla&}E6R$wQ#>$%pJ_H5 z)xwMR`13+qGH5kNU>ASFM(BKB8rAQLbod&7!UiVrGtE}w4*5`?7(k)Z8tG~11?~(8 zOyFl)p|IZ0POY;ol^!px;|T2H&rUdO5J;E#&5(+(-set2zy$yMDE;J5L!VEPX5apc zBd`mfCc&~S+WXV)){`Xn%D3E!4w&FiLdZ1orDMNjO5YoN;t1@*XI!woWRC{YtC2nB zDR15bKJ5wjgYaohY!C0@LG)8I6S>!&#@z256Sz;r)>1u&(QUUn%l#DHI0C!yZ=Rjr zS~HTp{MyQ`71rE)5EHmhq)^OV?M~mAHj_2SICBJc;di1!aY@IA7By1HNiBT{RxpA4 zL~NzHNdP^3lj{RxpA4MC{b;wox>-XQ{M%>{5=vF1+f*cKz;&ru8!lr0dSb z+CYC)xP)bV`;DYu2Mofenkha3ey6Uym?3!pAzj=>nHRc3IU>9EPXX|R#v2;Q6 z6mgk;HMgpdiIwpIFj{UY-0P{HpFgBI9b<*V%C#(p-P$OsIsS+$HT)_^U>DB5U~NgyXu31Tz4B9CEth41i3i(! z;KJ=yg6Al8cEa?m@wETcJmvBAH#q{ka25&6fUufCd&KV$sLo|BTLcp}&Ap*TeyY5z%HB(qflrKV!zsmo{%)`8khBgi4Uth;ZWXp!T!8DhD}%` zeez-i2+tmH1a{#Z9hR4oIG#%0>2Rj#I+wkJiJ<5)a5cXzM8&FO?3z55Ha<27F4D&w zfn7M)i0$*L8b?1gDFrKflgmQF#Jou!(AvQQ>LS$lQBaPAj7k#ub&bt^mv zg;BS;tT0TN_H&2d-aa60Q|H{7YlPF~@?T&!?m0(b7tWJo^H;~l(q+S5L6P=df)z{@ z{pAL6xANe&k@|OjaAPR7Ue$~-8y1bBJ1rsYj#z8BqaY8`nX^hYqkW4?hg{xYHlyC%gX|0Nc`APkSM;jJ0 zV)DQg+IG2~F#E5?1S^>MIx+_GwMv8|&D8Tg$rqDooy%k8w}z!0fnDE6N5HMuQ-v0N z)P08gZ&~dwxg)%ULV^`cXw^l*o5@Fng<7*2(JMBII)q#l{JyQ^2<)0@6$W*mb_lbN zs#o<>cPG>O7d>Ihr$T}iOavB>1K+041;yXBd!uy{ZTZszdN{1+2<*}oLg4xBIzfsm zW-)f>B~z`ea42lFlwbuDUdzV9VB@ABjZp8SuQ`)Qw~P*lahF$f1a=LX76b#=Yd{}6 z^=gI?mrRHKnE@IZg#;^@$hjI0i{EvDg@@HKPOM9$R*(-z4zK12?7Gk>5ZWYnfPD_? z7-=cV^q#O3O#PM+tYD(hFAQFs?F+Su>KNNg66urbA~4Zh%@Nq;ciJB;hxLTPYt(fW zx+0m5&|M92Ws3+_Fri@*3IoxMg!&YZ zK{t}AM~4j%RIz|y1rvC;JnNU-Ok}e-Tj7~&DMw(}d3`_FyU`cOs--N(MY9z8=#j7z`HgTim$P0bmg@YA-%;k zj=(P5qAC>j=IJ!Oq6hdqO(R&r1l|qIcF{Sf(PCR|I5%V(M_?CjQQ0h~aXM9Q2!^{$ zQV3Qs!S55EYLi9-uR6h%%~Lr7yKsxj`t5e<)b7=E&{>l}u!0GGZ}@cEG}^CeDh!Iq z;|T1+Eh_tJPgpv2sxJgNCzfCZ6L^0;YZFJN(OtXe!eYx@j=(P5qOv^=>(l9ZpVcrw zavZ@5CitEABeT+|l~fEzmSl1ScHtJ4-SeO6v~9-?uybAr!3rku=>_aPSjFynz-pjY zDI9@axJ6}cVq^wQS-2jSb@wG$!32L2!u8JVX|G-b4cboR2<*ZwDtn*b$)K}3t^x;F zH-Z&R;PWTgw+CjW)6Armure=-Bd`m%s4OGCS0>FIQUZ%Qjo?l^!36#e1v~x1G?Q*I zE{5z^Jb_*KI~446vCESvJvBpejSb@VTH;-;IIEns)N2xGvTmkSR~JFBf(g90lg%@X zokZuG=Snx0CUOLJ;Vey-zZ;!M1DE?s>#wB|tY89<0NA%6o=l>ahM|(L@pO*BEOD`s#R*qFd00JgiPUji*~9VA7vud?C4g#G z1Repf5sOO#{pQe(?fNa^2<*bMUkZiW?nK(*`cJW;$1;KyOyCiKLb1>?f!a+`NV%-n zhY9S$vtMj>FfoxfEIc9(>9vwz1rvA#!1CMcCegCrN5!~Bn>Yfy@az}cG17|l6EpI~ zx?bxERxp7_0BjuPIf)J)lP^xz+sP5wg=fDMisQ2qXyZg9aajBof)z~Q5diA}Y@bM< zZR#SD8~Zo{yYTE6o4af0?;ybnCh!P=tpXg0r5olsL#b&MM_?D8 z{bFC7+8j^E%}Iv)n&M70y`lLS(hI9O0=w{uc`V;2T9YoQ z_LsBwuZ3eSoxuO|Sn=j6EpXnW2PZSei6?Ef;8v|3cxz1%yM>(>*c`yj81kS=x*QIb zP|2jdNy*JD=AvVt+&%*|CMYd|Y!aEYP(S zclr8@k5ijKn4_hr;S?x_?|&pLTWld_m-~y8f|{`L;O|kb$o|XM0ah^4qo%WX zvhi4P;9V_7%&>hcoh}ZO6Amqg`?Y#v6f3U*D{s51hT_-fN#f3~mxNX88;VU=Cy4O_ z8!%$Rw^lOQG)CUEXf{_8?*L2j?aM%sK07P$F?Jeh%N3<##bV zXW5m%@NFt5boY_FwOPp#*tK(qp6Hb{PHZCX2Bs=%eH{JXH4lYXe{f6MS7c1TL2jHB6HAHkCoA zeFs$QGp35txNCyv`U9$G8}r2KpFf1_dk(717w3s@TK{BMZaQ$Yv_m&RZuxlwM_|{z zllN4;Nw#=5?Fu8b4E9P+JtoQnLiPc6Stnjsd0m?TPj~ zxUGi(wY`o|Qg`jt-?f9(Cr zV$3;fBW?SXDVqfEg;uX^Rj;<>iynWj3pKU2s#EW0iYcQ%3z%l-+=+uEL-$PCVW|qR zf{Dtt!79OcrdVhBg~f<8_m}oH%#b%;s^kdl;!8zzE>&pX%8`>JtHAz=>w%}^XNlYH z-VmPse05;q*#fb|{iATz>d@hYiv{AOksn!%pxV2tqK7&1!&PM*fnBpFmseJNEfBYE zy1|IgNzUT@c{%d@Z$|*T`phk@9GhJrhHUyM@I+XnrQ)1kIkI-m5x@#20>_qDe)K31 z?_XAz%J$|3@%WZ(dCQ9f9D!Z9*4bXmm+wU%-E4VJgv{L!OzhmzUX@s!FJ4*kiNzSP zvyF61Ia#iJCUFFI;d{gKsqIRHE$4IOpW#)2YZTXXWbsVp#3cn{1{ zL4Fxv1rrl9%9a0DyH)4s!*(G@K6w5JM_|{cfO2K=r~)zdx;n-${X@{qSQS6)2$6~ORp*?Ri{zzQbzytEZwuxEM^yOOhqGvu0$djP-h@Ou!`Z2WN;h$1mlp72NntYE^r$W!PY zI#UdNrjFrb*`0VV%#yp!lsE#r_)) zb#uwf0V#3^{q2AiOzhu#Kv=`te3`ZRY(?=^G4Ufw^5rvS9D!Y5R~!)P*5rw%8tS(} zi}o^EmmVuOezXTxmEIGY2wCF#QGbL&_U~rw-|N`FSDw5lbZ2jadw;(TwiQ;Amlkny z6S^0$f{Cp`mj#n++2Xoqzgdic-Mh)&!in-)Hdl=a?7}5fD2_f}M`o{0kj)<)1gv19 zo?XYa|92h6+RMq&)=BcRvNDdqF8<1A4nIb^_m7dk8t_++OBlpX*9a_46*V6#*!$z~ z<%{I({wR6dz7>EKOlVa#glDW*vzzs5*!*sh%rb;;IDE*IwQC z8MCtiJ=!lozV&S_*V7YNudkN%`i}qqdVLF2zsdIrLGobx^;~}t6L*I;hc_eQMLz>| zFJt+u4@9#xRQBz>m?N+Ymyqp!UBSLOR2U&Q57-J=!NeJM9p~6}`2Bqy7q34gF4M=# zo8RyRcJWu9Fsv2r=uH<*95-5>$$cG{j$(U zF1f#&>mg&;yu}ufzrtTrHS)olGZj6!lEiD%+_E^`FIb%MdWJCLjvg4+ zM2ibr7qF*fQkphx{bG!4=Wv}f}Nw9=5MM2`xvt|FOE2GJ+Xzg%M`NaTN?w(`fFIMYQ{{)I-ebqhWT;EpovZtp! zn5~`R`oS)IpV&9Uv|7_P>&D1KvswzL4p@SlB1C+=Kp~_&(gW8SG2-zM4dDg*|HthA zh3~(WY{jIkIm_PhmWOmbro;*+PS`EcaE`#Pud*d1 z^bPrk(Es|CEchBCf8BduS$DA^L~KnJH%`$Mx}9hVft?focHwv|JK=-|Rc#HFFYgOh zVg(cXujzqJQOrLvmRK~Rq>;b8u`-k+unU)vSoj~@_RT1*$OU2MdjlJBM4 zNNG@lT+^Xgi4{!r>UvwSS~}&QQgx>+J8!~7Idye&0TbATYlO9;QWeqo5-Xp3Je#X4 zOypd@C#<#lH^z)kXGrh*XgO{JPhc0WHQ!0V|kr_+u*w0kcHYt4-8x$&!KO zR#ld~XV5MsCa|lnez4$3XZ=&E?S+3qKi?er+HW&q&)jmQ(Z1Q@6Yr+NpS9nVHzv;h z+l6U1JJ`Dwv7VkS+g0yYVg(cXKiLZT6aS52;ABJ|9Gxt$ZNn4T#g}TCYhmTc`dm5m zM7i?ChwO^;bk5%;F}U36V2a)U{ykqS@IVujIima2rtHc`#bpbIUvuSUhsu>$!Niad zKjqDi|DzQO_Xg}s*44SPU6Q4M3GBi(!g5jrXT#tLxpH&ypb{&X2udqgX3GDoH-%!) z^L;R>VXi#bgD0>H*Bje|)oib7+uL0E?QZ_caS45TO{#pa^Y3*$S!XRK%DM7|NtOau zF!5tSd8Oe$cb0v3Y5P1;BRp3&E<32i1a>`4FR$$O|E}XzO_@05dyd@O>7WuTm`MBH zK();G-z(RSe<`+c$&poG%ml1p;-JD#rDV^p$=}cJo{p`hJBiuyv;Di3n7}TV_qM9y zn17$EUqd~lfd!ee)%R|K&-?;abN1`J&3>J(&t|F~`TXx!glU#xnhsLJk}P>hmt9J% zV4}+lXVrTBe`Cyd>MmLDnk<)U?B)pU;!BlAk4kT^#mZZ2h6^)q-%}|^5* z-&6gu{$H#1;O1Rb`_cclaQm|kN)av-Kb4h8^}Unjc8(=VtYBip zg)OROy8pI`b8pX;ns-i>LuPakFo9jT*4c^gO{PdXchck$`!*=Cf{8t|3shf~|F&@Y zjPC*hE_`p;8S%T$NHcCk%MOQzb2W-*-g&NWwFN#{O<%l*#T z3RuB}YM{30=$i0PsaBbMlLBvt$a-a41*~9V)*U_3l=Up<{oS+d-=u-OcuJsb;%~$e z*p+%kPb^;&^G}S6`eX5LeZMPH`-VYYHv~Uo3Lh(aeF4{Im4p^eWDXEC) zxX)75{TVFAvfd!eK0pyvwVZaHmo0wuaBL2nyM{F zvtD?A<#kTMg#8jral3!8n8W(;Y;3SpTMoTFM$Ve1;t1@*wZM8ZQ+G>0Qzyya)BOef zOU1uO{#Q#3*GqR+CdwjNC}0H>_?O1MEqiH!w0c2`Y`Iban82=i>=(6uHJj_xn9r^w zT{%sXLepevib}u=Ch%{Q%?O8jNFyUNlw5!OHkP=mrT|Jcm-9ivqMj0*)nYx9tAjWbWL#RNK8df&^5>)I=3p zY+z*!mdj|?>!$kkjk#3sz-0kiAOS~F7VXozAv`$A<|QMVBS=71)AVAM+>ZSEc3AA| zjoxLkP&KvANBHM@Bn{KT%JSLNwedLtS|9;u zYV3OS^271_ljy_kItUU_^>b0Wkj3t+JN5U~)4WI=J$WYWt$9*_7D&K(Da*2`UVz;O zOs7e&G!P`9s^Q5(K_1oO>PNLHjaTB4>!;H84~_`X0tq-HXIV(fT-<)aM5+< zj~{OeDshvsv2^+8bpo_Nf?p3>n}5NMvxm`R{^cA2RlJ{JhT$Ka;5(R38k@@b86W}I zy9z~AcoVVL(7se*x{M>B3i>#hf48o=IB`!e>TT`Jc|RZleFN--jdVSFrE_n3sv-oz zSQ>n5!}u5T0ZeL46@`82N0l2FQG^8lZjZP4C4EX5OuIA+=Lo2RF(h_Uy4`1Kc*ZdL zVYV9=D}n?ZcUkoH#vQ48dMs^pIff&k3dX|NX$!HJq$00)svm^8m=`4AjDzK6^eB|F zEGE!qjc0HKRKZ9Si&_rdBe{;5NE@9G<)VF%fTIN4C%kL96d691>YAl+1XRHo5<5|@ z&jKmRb2^=qF@TE|K?05v3PpTIPsy?IOsXEfm?NNykFhjJ^p$ESC(#cmhKra$0*(^Q zL$9wXi9sxmb8+(tPo}>nj-D}_+O!$X#XlecM+vs`ezy;{3Q3}U zH!k4_sDhCVmdn{X0*Cm_r24&va&a6;z)^x-^Q-gmd4uV+JzdBVPzB=&> zBG&Var#g${I0CAmAD+EMWAEbqb7HCM6d%q*4+%J~un2F$Cp>ujF#1;P%@I%q{k|;s z{MavC7(19+Q9I5f3<-Y3`98C;Xq?}d1}|{t2&jVoYnGGRy}5YzPcJ&fq*j0yNbtV! zVG~2?;Hr-$0mse7E4Lg-^f6x{jD010@;e8zqKmySBJMJ(s<0>1|0;zg9#@!${##NY zHEC;3e^k%I_fNTz^ZWhD)S?9_^PC%*l&vCuQ|F^nwJZ64M<5}2^BM7=lQT^%#MIA< zWm$}OBW`~E*(ys1RrGTs)xrHq4AnvDececr)Q61sw`PP_ZxcGm)k1nbw1;>-#+LY~ z7M8R*cnPiRWlQ#S2`ss9cNw|7v?JG&#gY%3FEOIt0mQ1S3K;I0C(SS@_vO#Y%(%*0xEqKC+!x?DWf+9wYI$%xL z4_=DL7$6Z^AmMw&mRvr!4H>x?Fk;&fJK73yhYQy9^vXGSidqzF7uu19-KL_rs}eFU zwjpiD&p}}(5<1+%mYhGb3{BBF#>!~kRY_NEn1g-P9XJB2V2>yiI%+GLJ1z|$pqOhp zBu2KfCGL1R`glh^fq&w4MntFMoAY@Bs^E2EcS%Ppnzu0y2YYoAJCC*{^Q;G<=RZqP z?NA#M;XVwtKV6E}t+XY|B~#Ijc9fN|*4mu<9-NHx4hD(P0*U3DY{=-+sc2=YOx){j zPFvkh#JY`n0;)oCY{;f3iOA!z#E1<~%;>40aQt&hSJBARhAhqvMDMjC=Hts5u|vn4zIN@4jjnbPp#>7R``D19{RW|+L1m2iG0Tctd>Mdy z8U%6#RKXr$C+V;=0nzp>rR zY~+YdVc!@v>LRXUPt@%Q7B`)J4t?%vOY-g+pi0Y&sF#%uX?>4<>3q?7R)$fT8U1~t z72eS)M1&Sdgj(1T7Y#$yaKS}JEM~;k@m}~xR4_**u-`3Q?|@!SJC9)5?93X;jH=hS z#rOP!xmrPDVJjPQe~v4f_xKzuqbkXYMilzv{f?bE0;=G3QYbE+Fr!9aJLAUo-MH%k ziL-5N$XsP7<8J#yd40|r@$`Mcn?;ds*YrYw6lU0lKZ+92Z$Jvq(4L%7~ zK9|v5r46Z4eG*hVFQeO*He@Q%M!E^|h;#Xk71i6*5D%Htl_Q`E_B6|r*<(gskLcqT zO}mTG0*NSd8!|noDe7k@moaEL>s>Ds{N`;4M?e*S1siuZqtPGOXtgy|Jk`;Lj9PU} z_}IAu#fmn>^lORGv3&)K&#)!KFO~?WkILhD!ZI^z6S)V?#q3K*zygWE-ZrF%bWNzt zl!Kt3p&MtqaRgMsK4iQ5*P79(8n@8wWj(mQf`qlR4LS1msc>8=mytTjjHXpS zN7=DF0aftYu)SnaX4L;c3hGtCw;Z23upL*t_rt)0*V^{EUNp#>7* zS8T~mAx&^dm5I1^W>oK~1v=k9j3c0G`zRZ-cl1)>)nAzyzS)$nZoXXovL;NNoohoT z2P*~d23OI@9X4cev8S+F|0*(XX-5vuQ3|FDW#Uf0DNP&{q~7^1OoSFlG|yyDZBC$& z#`HDUEj6E@<5f6QKnX{$p*(`_5^?axJ-x_Fqk@ z!dM4&&g2QG;#C}k&yh|mIwpF3!)@Nx3mSu02qCsS(T(P<5HwlF}Lr z_2gQaI2dkB2iPP_FU`7$&$E zT7|Ws)dwa@)1x|Z1XRKD*qb`ln7;2nR%-W+o%Rpv3kkDwHm9y=rA{~_*J@^rF-^9N zk>;_}{viQXd^;LHG@=f<8zkJflNes5BrBZes&_m%jdlulXXCE(OYLb@^a!N z^|)5@=)9!PlGdawmqMOnj({rIBg|i7XiWFETPCec58_%5iTh3M$f6Ge)Dy$bvNF2V z8PPngbZKi!XO4g>*wZX~XR0MVMC0(^Ckx zkB!b#ji_sJmQ*yfBi9Z{IQ6t6R_^KQH(O4#TKQxc(ZxPnr3PZ*XNcW08S)qGY{XRm?${4-dkiPhITk?F@ zR)iKv#9go>-zOEQZ}mRG2!r<)RB`IObUW9JBcLjFo;^8r;E-B+P(RbJGNexP&q_;M z`iam2i7lt?NWuI=>UAu;nPr8wwWO~vlt}mHwC4z@g1yepd-XP=chZhY9nPt^>j8<7 z`F3Q`whiiuE9E)$Dr`h;t@5Surx8a$6}&bq*V)^UmR|oM)kQmtU1uxFg)cAE7tR!; zk||0uc>Oc=tF}kcsMZd|eceO#z>)Gg>WrTu9eCrLq-W?NLJK5r$0|um)5mI!+cHr$ z+k!rDc`Yrv=EMj4QHrIJ*Rx}=`(Az$;eD-Ef);S(v; zjlY6W1@9jAr6w&y8alTTUAEIk>~~#BQd|F2kBd5t-m8^l^PL*?iETP627Xd zO$u2V@2?xs{iq>T-L@5>1rj^*mBiblT3u-^e~~TJ*@BMV_Dkxu-G(Ee3ict3C^j>s zt%bi*k(ndcSCH6~t|XpsUaPCy7PB&%n;Oz_MRk&C8Q;551+OeS?d`h(ZF;#e-SDs_ z*K*jVtIh4no`YKCs_h|GM#~H4wECP5o#SsILJK4=oOK|zgSE)UgoBKDJ;#6=9cxZE z{NxF!`eAHO+M|Y~VWmub8DmZ_EH$L7d+LiftsKdiFS?|E@?JE5ygg}jM~}>Wvll^{ zoi(}FfF=mWwC79{5n3SelD)@__UaHlGx?<3ulWYl=eIt6vca4qpo*_m{9k=~;muB>*n=SK;{^1Cy z3YzFh(ke~K=*VnFC_D{l*=sxcal4iXRU>ZOlXGv)N%J3Bh$kBT)ThD}TN=Hikq9l2 z=zYPSgp`_*U%TZp8W@<xDH13Ew3nhv5(x$6OmJsa%F?_Y)_ zZMy97GMsEcJq}sYgAJN<1XRImqfo5K)2G$ryl9ry3*0EzfjkRvAx&e~qrGVk+S{-T`qU@Ng?dh{V=cd~r3dv-+|=HQMM;yH7gJ5m1$-awJp7v?Ep;D;RO%u|CzLfpqJ=EqHAsCt{S}kxXnj z9~pmhB!|=@(ePY=HU>EpmugHV>Mme}_I`bur0PU>Kg-6@0*PbG9LdeY9Z2{J`73;r zr<>Blk5u$QzXKcrRj`I^PFQTaQ6M&p4CCIbF%F&+)8` zU|R!PxV9V3bX$O-1rilAok&7{7xM600wYx2OsUS$Kzgn7Vvc|+*oW-wXd46CC9pI7 zY@5mT6(oXmoyaGn0J3+fd_G*|TYY+1Gl(`Ax|t)O3SL>Zhxe)h9h@CZ2aHVMS`OP( z{mqFSnbU*lAC6{an7WzLnDt%h;ekUjv_PU#a3PA~*u7 zUidhZB4s#<8ZQ$E_Zrfs<)L)Dt`gVma3L0tdy&S&ebIwc&SY3@Z?bEeFOnuWlkkKH zG9j`nBN~L8(uZ*&^xO_Fj({pyoOo&@LKs>gK}I7s2&m%QF(c22p3@JfPNUwShscF2jqFF}kG4i5JzU7WH+{)Ag$)X+aUoqF z^(FBG<>->*N+X)}DU7yw@|CkdqM)%0QRep{g}%;=@IPouzjp0G7w*u)@VB4}_8}Vw zM;g)VE@3oymOj^4kT`hXnVeBYkzI}2vNAsD8PSvaVKm#poFkwLUK@7$-Wwx&jE2*) z4F%l(bGWm7RJsc}J8l3GUNm84>@+c^yDY=$)R#B8zJhJyi93%>sqU~)IO+pbvSMWzR=81%U==N4zI14T(M3L@nEA_t`Wg9A-!l~)0aa0~3=_vb zq{d0UOTsp^qb2RU>Esw4JUG~mjF=xu&bj!a80|L1??Y{Bej`Xg6)can*_|@zUx6UzxQNi zRH-`9?h{-ojdaD(0*Q3ia$lcN;%eK25fusTsI#sYRnNBJ2&jTR!ZMfHx7PJEJgM6q zL#}rrF_M+BGdqF|TH?#fcz?VdjneU^ma4`a0aftYu(xQAKW)Qe&&PGzb1jE$y7$YC zyw~YQ{$vc1TRzE;hD>pxD5eXB7D!zC?Ml+mbSBNl$zxQT6F35@U=3M2+KP0cuMI8TIRHZoBx*mo5#`Px^2c0m z`KBaHcg?Y-ZKg(X1XS@Yk0}VEUy@B|dgD|sa{#u9ZgC^Ko3|rLO%}5P+LtSY}e_g6U)^Y??@wM7v)rBS~b*PEuA>6svg^U}aB#q{7KxJ**NT-HMvSG-2 z1Z&Gqd>6v(u3)p4cgQ)cLzs66>JkbF{^th zjhg#KvL1gNH+$lL}XMr+X(V=!pIYxW0mf zr;8iWPO~H9&&ubE*39ZoA0AUs_s4l00adWy6pAM#lzzziARUP%T+3mb=rLE~d(@Z= zdR4y?wh5*eFMpNNex1e80*Sb3F2rlTF$qnOGdUiw3!^7(UPw~c(;NX+gY#TTqgF;_ z?rS+)Wc7)j^rZC}>3s4%TyE=1R1X!T-|;-uyuB;=)?Jgl%-D|(KXoQ8TpJMcA+isE zWcH+PK6EzBcQ5;;A5WoS5Ell?&2 zaQZxk7D&uo>q??r^oin>>;urO45Pp2Je7h}XE*|?_}-2B(~~BdmPskz54qlj{pMHa zLZols)N6uePmzaF4{DlnM!IkP4nqqhVpltp3C%yLeLu=MEEZED=6Yznsa?kV5syiL&oCBOsK1EY6hHjcv#gPz8I0 z?fM-YNvnIWmKtCCiJ=7&N4#8!WqhgnXW(&G#_@Egm#j({rIZ_EQZCX$Ap znJ=wb)qra`Y?GMkOmg0>R*$Hv_s|E0(u$SIl0l0mBD6r_S$8KgduOKl2K&MUvs^g};CZhH&9&<$tx+0?Zu=Zb*5$5h#jA3peBwmb zg>+Vr(Jx1kX8saIB;D1&i{x>#u?Q`YnC0Y5e4Zz$w>Ok)HPkwi)+`B^B1?2Q0;>30 znXK+XQ~J0|3pN;uGX^nl%~fOd$vU%X~wk! z5|*V-WK5*D`f;_K>4c9*(62V0QeqRHfGXG~=3(jDlUiLmL)?j>sJP%jVo$X%(eu8D zx_x&f<7ar5tcksVw0}F2KDGfRfj#BOsBcDh8Z-U{NnB>m5l}UcdDZH+mX>@!ah?%z zOM22Ll~0MkWFSJ7(2{v>ik6kE+kGDKME2#LG|lNd@xH4sLJK5{20D>nAx}zXj6KK7 znAEZd9qp(u)ge=kfGXJQ3Plh92%3M{KzjL6kGmd_IK9$|+{iOj?^T{B}O9bQP|Ta%+EXOz*hf7m*hzGgUcbbQ=`pf<6ldW zvw&+;+r@!&pEyos#IlpvDVsgR>4eZ}WadZ{j)1C$D;>$^zrXw^)yic!7ll&gqCRTl zzUCs#^4-+jk(>+D7P@=?JL7koNf>>x;E;OHX)_V#0z;xbawIz*o>1L*dx@11TO3UD z;+vA+!>u_2s$dOScH5OOI?n)+^J7d!Xn{n=7)Nq{V}dGwgj|M4t8i-EbSQDVWWo_p z#kX8#7)oz^Snhvbu;6l?VVl-%bRacR6NEX-<=%~T?nbGtpAeAIN`w|j#Kp1vU7Iw) zR=mQ9HOd~ed!ur}xxXbxK-Jgj4rFO=n$UZtT*kH~-Ra8R&Czjo&7lPnAKE&QO}YDo z=e9EO>|hsau`2-WsBJAm3nY56=+efKB|_qSnYg?;gnldo+4b{`bV zO=Y4(NjG|FWdZsYYAs&4YEOP>eH2>8UPQN^*^?&=9to+oe|ZN=aJ1zJsDd?ADAZ?zY2%~mXx?Tk z5n3Rjwsas0mlEOBRk@6iJ|Q&Rb3E$UiYK6oZ+Wh3H@a&{DXKoow;Z-9{veCEcWZ=x z43Xc79n+b|8Q()kzSxS;0tvnCO0sRL0ovbCCj7&?(hIGgqSH<-IRdJDa_z~S^v1~C zSSG$$bf%Mr>*DXTTZyYC*pm)xUC@rlXOMfMJ<+nVLywBjq7Ji^r0AXtTAL`pug>)A zOgkKGg4^_IB|-}%?##3&qbh8W^8=ZvlLBai^*T80vK>c26|5nPpZDoPgIm_34>wzi z&;p6HjrQcCp8?7kDvt)vjk?l5li#3M{dfYZ_?GwVA4K~#G{H8%_?E*qt?g&e&JPmM zZBaAU%$4@!!frxQ6P)zCih22o0K9*vp03CPBcSw!&I;lp#>5` zFMCq9E)ezmD9Gzz5OLX~*s-qsueReY^x`e7Q~Ck)>hVkbWDXipk`oQa(NsL_Z3 zd$P1(3j1Axeveah0?Ko#sa zc3S8ofsS_Si(mOExt7B=<@dEGS9F)7RwLv!PP3VQbgViC-`92$p#>5SdzIwGstk0} zMP7fb9q&(Hu8YG%C)jfYRMkb>lZ7`|pycB+@$ztc>Ue)XHbhS1YPCH%X}K5mKd~Qe zDzGP~jrJht6?v%4(w^KC_aYy&JVrd}@034S}*jU%9H6F~^wRqk(FKPP&r$XZw?RTXYbNn5@rrC6^-ml40HDC_vL8Rrm>~BvQVom4$>Ox)g8)ImJ z1RwJXJ7YuV`E;U31zV1Qss<`ol3Er@g6!oOl z!k4;`+RunwekAX3v$@@x{ucb{V&`QTS|Gv4ojZm(Qt6u~y>)vFM?lrM7R+~|)t1~f zUe3x`5^PI@M|jha@_iUuAOU0dES7rSi8{7sxgYFwd`Li5JoAKH&T=DZP2`-3AWJ)% z`P7y6y>Jpk3nXAR1l!X{kj zS|96(SD=rpV67+N3!b6eP1 z-s!INkhUo;4t&EAQ01@fOib9n%j|q<=2b)XwAjU*2ClBb&;kjVoy2xpgt^gRL607K zSIZGlB^`4jE$%lX(YkwC8AI;b)22rHbObxi99kg3=Plj&qKvk556LAdqqW-b? zFe@YRodaET>ZgR&Mk2I80%p^((@2cmY15T2rE(i%j)1D;<&NYPxv%!VDv#%P`#I8g zRj(xC*+PUCNbuQ)pQgA|{~On&k54Q)0;-&*IuieZ~{-2Oa6?r0ddj%2<4L3NCZvNC$qIMPjJk`%1zBti=$V9qVuZ}8cj z`X1dYIR!az1XQiR=|Ch@IjExpKa zqS+4zO8avBL}-Bo%#>$4SzCF~D|&+Ttf(DFK-IWBR>ry0B{lQp)!q7SPV~_=AIY<& zN`w|jz`X}7GTO|8-kW71O{wtV2&nQHV^1#M_AlA>N%s2$Wjj&2+ek{)Mk2I80`9tC zQGhorFJtjT^6ZWuM?jVR7bV$|8Lv`*l)VP_JDq6%i)wPhNfe<468x@|U77B*wrM0e zcG{mKplU=Kn}rjl(C4Y_VQDtkiRK^EC!13`iqHZHe$P*VgF79b-tYLmohpuis%jS{ z8RVHJ=)aZA=q<9o@*FFydDBsZ7D&K-Q*6Z9*oNMl;)PyUs5kw6fa;24;Cb<7te~y5v(lK_##KIL#RmjiafhY$mNH$n80E^H934ULy{stG?`-lg= zNIP%@R6UQeBRlPb(8*f)eRZJ7o(_Ma!WuD1gceBf`%;xf&UDz+u6S+p4jchhU&h%H z&->A+(MtKf`%d4UmOYNdXA%SvS|GviEWUWji7H!1c!QJa@_wqV(npcp7XC4d`p#>8BzU{rK4m83j zfG*A|=FWY9>m5Efs%D##ri|@GYbKoIGMyj+*FFk`3(NI+SAuBhj1L?EReTmwe`iNJ ztcgfZPtoFXiXZ{kJ_?2TN;jI^tOG4R)Pf_R3T6wjbLeZF>EBiUbo)*|n+g(e?Zei! zzdh)UPHpKIr_Nk96;#0-9fe}|V>f#IZ9A%M){o1@fdpLpuxzRYZE2`6YfI#0j({qd zWy4OhdhJ0MA8SLW+)d$fiXZ{kK5TW@z?XjYv!j)NGB^UNVE&9kQS{uKW)~>wL-Xxi zo(v@5N``$4VtWT_l4?l{kLGd&RPlK-4|lbrY1^!6^zy@8)(a%y+J|}WoK-Y$jxk;Q zs+c37iqA-Ks%=kSEjFX0W|wmLC6It?AC{B4R-o|;J-SP;oFkwLW{$A4soML}5|)cR zGw~{yCj$w%_F?bc2Z&zy(TJ|9VIB0aY+3M4`CZxdY3F*PsWMf8=sMAOY7t?7PTsMCw=hK{6fqi6fv2W?ZnH z#isuBtaY`tTJsN=!vYDo_E9ME4s@iunmv@d?fT6TPzCcR*lv!K{`CIFCsOI#h9a~; z0W+Jpe0h7)=IPMj5z|TU={(36@5@q?X-1L;bbcjS|9<}J}i?%s}pU} zexc;xWWft_K}<3g-7@`4pdKoy?{@QL+R zv+1Lx=Pi|79snfZ+DG0o5;-leqxhh)zFi_I8aO7g!kbr9+mO3~* zfNpHzAbnYA%MnloWA`kFWxR^6zh*1VT;|Nh=pg~uK5UKCB!KEH)RuA&DLH~ufyg+U zg*&OJ))-C6Y^f`kod5~A_F-o_rF5i^d{2?;&kh^`RWKgSc1~{hr|VL4$lSU%T-+HF zaP7m+ve+cjX~c)L9pTIoPz58(?9_4xMWf8BR3 z9064@KFlKSwSH8H887&J@)V&35^(LqzOFI_(FS)N(4R_Ij({o{m1QR`{`RF$x(r5! zQ@yx&EhOODhvi233$)|?O=w7*8%IDDjH@aXBdUDp+S^5F?oKZ*iVO+3_F;SVtNiJ; z+Iz^0x^VG#x zCi}4Yv_Bp*rVU3x6(8+eaLbF<{p^hA4))?=caVT<9~O7M-HvYE6Nbb0x8Vq=f>Akk zKEotWnm4#V_UP-y#ULTUuZr&M^rq$FNOqE-J4ZkjjD@kBZD)5n?C)gkIl+sIc|n3d zm8;=e4_dNk9zJ=~og<(M#-`ZpwZxU?j7Y`v*fob1NWgQ-*i7c48{O4=F%B*B;0UOK zu_+eqTjNaocU+G9T6lAjI7q;g-`JO86J6-BxD`0Kffq+W6^!GtoV(wSG<5VT-1vvL z2rZC+XWp^zG#vdQd4(=U@#aIs{_G6(=*8aH_3c=+{JIv=j`zm>l4l^}DlM|8$`_xx zJ&moMQ;%7Sog0tD5)Bkrk8?&w_69h^J_(IoKGnBa05D%isjQIZ9 zNUVOj7`^uHDYj!@=Xo^E6aT$26d6u(MVbe_ac8HYsNW59B$w^R%9g*EYKH?CUJ|`IJy}VuqNUn5LGA z=zuh2dnvvCZ^0!EH93>6EQ$XP&O`H^AJ_l= z;M-jE&GxZ+@&jL7)>GbbIJWmIDZe&DSREB3zFG3SUgZ&;h!#HABK0+Noc6E2(mupa zrkFP$y-DmT7EE>}nt#0UjV43U>I7Hv_kcIHbQp?YuQT70v1ZBs-v#)dW_{o%tE6c9})r={Xn}v%du3eqlThR!UlYzW1yJjX^fste2iH7E%G|x zfG%`J-Wf=QzYB@ADtlJ5TWBLYACm3)nPMdl_E?V#FQ_;Is_v|`M@9Q?p#|&|NtXLD ztdTe)W*e@)5F%#J(L~R7y+$7@wjs@J`e^x}r|69B)_=8Q_VlKr&7m#$;l8dSY#}7( zu^#!xdZZKU5q7s{G!w&mY{8{Jx^M(k!9HZCU$lIR4dQp>p~ij05!2oYS;7b89kB!X zUeiE>vg=TEw+*OoVx@3@`DZky{Z3X!r*rqQ!g)8=P3bE_3nY?iDuoHNYthEma$N2A z*ekfp>|8w7bpS^|m6Db5l9e&8zKpZ`F5+RQb8%tW01;XsQFY>~pzT_X^s?kywHf^e z>!f7knIXNob_D5t5f7&FY_ZJE&TYn?xN!cjlalWwUTqE47ZWEf$ z{y+6U|Id5?&6nYCp?k6B^HCzSKw|mmR3Rd%5q8g)@7;qRW?}!h1NfI}G)F*Hen^UN z>Eds+VNNz9NOcQfK^aRGWar2x-*HD2^k7pk0X z8sW>|cA*))3snc6YT&bGIp~A#Mb+Mm8rZ6toWs&_MHTun=@33LpC_Q|yK_6iD6kP; zIZ%E+?yPKr56sKQDVxWMQ1vp@N_gB-17{xGjd&uv))t#t=Ht=DV?}6zMAi1TLTaG` zXHS#c5x21mZe?%)$FCm45l{ttfz26`y5Q(*2XRKg7!g_^@rRYM@PB2z_wI?~)*i&& z%Huf#s`%a=RPtQ7mz$4|{F)%bu?UV)u-DlR&}w%SeyIRA*g1i_9*~&UR#f%yYJjH) z$k)Sq?n;!msQ{l9cmk^6)ns4#>$Xpw{HuVuz4(z6)^JYpl#q*Cq0=(XtC!lJ3ufmdq#~OH+iCl*L#-@^~ z(;@uw+BnhArJdT4-9L-j{Zr%as3~l zi9@m^J&k?1&7Q$-w&jGnxUL3Sjg;?16aVAV@WuP^+4+M-Xo1Aqno9L3HfNY! zKWA9l>x>lCb1%O7Y#>KKRo<*hb?}DINZCPt!!_;tMY0)^h1+RGihtT_5Q}AR&{c!& zsNcaK>is2EXi?5~6m(64^kTD`4s2G#P7!o@FAZ&yjos#+8~;EWV7!}sudy#jKox8gJ1NAtLh2cp zi+gDg5TOMU1+3-W{@3!4W3EUel5%kqH=ckhzOQojS+p_CEVixZNIscXqtV}% zbLXDJ^U&GXhdeCkpqZ<2-AGZq7G*-lvDx-!Hro!fbRPbK2c_ z1CA-f+}Y|+4a|w}s_%No;e{kP)$2i>@KKq5J!3CW!L0yVAO%C6vBGc8&zZpAgpJvaiY z;Jv{7aG&ZVFZW$|a(*~>%^{)DPJ@{J=MH62{g4{TzIGS>?Hj=nPzCR4g@S5YQgO>N zyzG`J&eL!rYhxPVmCw`A^>>cs^DYfMdrmsyTdrGaL4%vH^?4zG1tD>NizC}T@Ei3! zznHar@^lM2;>0Svb{1~= z7iS<{T{AM1t+t2MueS3fORDoe2CGS+2rZDfInkLEdmCVSaW@~^=n0l$?ecNVM+Cz7GUGf0V1?O;`dP} zGHXC%{ORNZM)WymN!LGHfKR#b1XRWBW98k_!Gr9Q84=`fLH+u-#X2q7$*OVe^pxW* z@tf$eXj7yMF`a0Qle5R6)Cx1wLC+cwEl6TSkJT3Rt&xB|`gawf1rmAGb*yPWOjY)F5VnxPU?<1;tyGq(15?}{F*NLcAY_J3=Q->1l#veH*`=BI9h+wbhg z5l{ttgzYObFs9Qstw6Jy_Y|RTAuiOF{AuffbNdhbm!DxuiZLx#?m)ugaL(@oiK87| zNyndUuyNfmRx68j&Dkjh=TP{BNREIi*oQ33!qSwI@aO3Ds8Fu2AaSjkD>?bg2|rsD zBe%TRlx7XAL-&{V;0UOK*M^slde(D5Kcr4 z6tj^Yk$pW6I!#2$>{LAY?@`y||5e7!Av$#Do+(1&)_zuc4>T`psLyL-}*J!^!gp|PCD3wi{hzl`n36-p#>B1d@8emv(@gPycE?xfy# z_Pvk%oZGJ4EM1*bEG*qOS$wfFx8CCLF$H~YdZhmEAVmsF(mtZTb=4Q=MyD{seaKGf zfKIXSpm>r9Es)^Ln40b=36n1gx-({pFM9c^|LZr5?CD!y#+DI_P-*9o`oG^ak^PCs z#%GWdj@N~RPIJY`)^khb>-?$d5>$J?xc=`NX))4#Rb0|b^2H-PmM{Y25+Z3_7Y^Q@ zBSH%#-gq{wFQZkM{1)xKFCC5azAl*bn=975ELQ#Zw~8JYtK{;`>0&gsLa6_Hy1iV+ zy3oyrqXl^ZfHUz4y}Wy?g&k|e?N;|;;~>0A+7AhF=3x`SL^RiI47IX(72 z_wI&p>J3jomA7?jJDG47Wuj+qZ9Kh=FKRejKoa@pYl%GfzMj>^Jt^j5t4h#O0E(u_TG}A;TJ`OLGOe9oq`h zSQ(>!M&Q8Fp2#C&rU)&N&^ePX{NqDj;5Qb#$D9&$8zyoDR6Q+CuP?*CwOqzD{dsuz z?J{BZx#=RbKq7zBj(Vafbs;0(g)PJTV;oS|TT?}7fkdMA5#gWbBdfzkoSIiG+;1|4 zBcST_pThbwY`@9R;A~Qai+-7-oG;_WueOhc|N6YATHmTy)is)rAkDIhZ{^{8x=uXAW?a`w4P49E6)HX=wxB{mqo&$gh?C$ReY_U1>eQ~H+4|6>{!vLN(;#`h_fsP z5jg5w{qMFkNJ6l-ENUrT#20R43znJjTst7~$Kr84z4iHAR;x9tGVD^dTR6F4EJr{U zY!lnNB-Y`)$18-|kRjrqujWX;e=?uPBV5s>{_hP=lM$>fI}>pD2YliADq%zNaIPJY z(0`#-Pis5LF_s+x>=cqNtA+OWVmJb-V4K+8{XfAD7U7 z$3E{-PWAt9lrxl-v2TKbm{?8)uXT|kw6O8xf5g;mS9FSvsM9aYqrrevrecv-C!yP; zFphvKHh$EX@&Dt8;~^vQ@!a|728(~dXphxYSER>cAxQt7KN7(*zV-s=Lra~0)G>mIGB(yrY zq77^gr>i}jm0>o*Sfo=nql81@9064@LdUYHo|%c?42^N*(GcO} zTu?$a+h0~T`d{rh+s#b$eyELo3hU?8|7#&6cK&fekJqd4F|K4y$W`Zf+`fCbm($EF<)3U%X%_pJs3Nz%()&@Q6 z*9L_fEyU`-0#57PRfHBuxO8r2K(S-2k_{*T#jF?<)F7}99gD1v{T+HjInIkg$S&f8! z%l{R@>N?Rvyj`{mKTZ+3_y;6}O^#??+HbV_oIG;gy<#E$iCKZu_VEN%IbL%_?aLJS zinBcTSvk{ER7$Bh_;5$@)Eh@MB})Sb%}Ym%lek>%r}X zmg3F$WSnUhAVLcy*5^8*5jPp#s(y7>Y$>L`T!7!Z@&r^3EpkF{*$Q%RnLK{Hj~zgk zAK8ZvmCO-K%8N@z76rI|iN7mc~ENK@T3z;s~gMvs$(j$^A1a5q;6~n%UfZ7ZUtjG`Xjdq<#L9 zFg$=KpbE~G*}a=IP%7>3g;$$S6BkCMtDpaLz>hjCMX(nxr>Cp8EOEoOO1b4)NR--) zGsP|U%@Cml60k?ubDq*)TCz?HXH`$<2&k$%kgmRK?~QLRO=o31FF{i6gtJJK&EcR0 z5`15k*7TLy>g+&6$0u?GRPmVue?mG*;cGn6lom-Mv_OJiP4vD!P-<}VlrZ;eB1b?K z%vw+=3gSLVnk!cc?sdaNm|pYeKi{N!I$1&fnHat>5>- zD`t%s9ZL?Yx4B#4rxwc*yvOnq3e_3bj(GY*`I;}YT_jD;@WX{6lSF8N1iata+{b*a z)Y!raTeqCZ5m5E0uu#1|+YMj5m&(dmSeYh8>ov#C{HBP|0ttA(v7Ct`YosB{I&`sS z5=TH)=Bq+=wy!tt9VO57-;h+v=_WygZ%!4V1rqRnV^Om8tEG&#>yR>b3P(T{Tp_b4 za-&q~TebsQTRDweJ3|8I%&`33j1^Mtw4*|B?o^I|D!6WEy*uon6wt>4^^Hsr;W`}p z0Qg$;CK2pbpvFE&lywm%2ZJrc&>L7|Po4^rJ1^bY_OCFU- z?jF{YZVa+zl_g#W(;_WDy5W`{ zvhUSTp+#LSo}sIA`-{*53En&Sd+Tp$+YeoQIej2UKvkP0E%IQNBTg!x!^-Gm+lYRx zw#OR!eMD%11n+zGKCGbU9*NkjaX*fLs+-lCbe0afs>WGl$BCz5g46|^Tb zMuZkfz+RX4F5Q%R^!tK_tsTV?PzCQwg<`+vbE#*RF0P(BT!a=#z+Pvb)K+(-*+*OA z&U<1w0;=F$$@WLReJNei=z!av93nysB>3xbIP#u!zdRD3N5eP*s^ERhR(I)^)Y&B! z*PZMr!iWNl>A;u;^N~dx)1UgwaX;rEE}8)eKJxQxtPcB@PzH9Y>dp~Rm9eS;vCGlM zn$zTOTC}awpc}(C;M$vEBD6q)k9h@scq{o0-h@Y($=Z0~40FZ!Da^@pD!@e0dIu;*D3lw2& z3r4eGER3BI|H7Ca%9();PITd-WRT$Rl0Ir3x^Bw?d?PB1BcQ6Bo%Q?9(hzUyEzfr? zW;dXd&Mm=r?)Ma-1rqRHP$-fnR!PwrOL4GgKaPMZ)z}B>iem=&%hwgGjEUnPN=qAN z;?(v7L}-BoycZOTy${Nytqn5qf>}d30;)7B3)BbV4Dk2$@@XXFhZRXGvKc363>TpV z68v4F`m<4L{CE@I(Jq!Fpz5n#n);860XFuRPlE2|wM_cM5B7Gl|gL6)g6`=(ZeAY|*-g=VX{w%!f z^aPH8s(VF8N-Ce~^?j+s0GRT|3n!ms~b4~=L&Y%@0(-+Dh@ zgceA^JUN#4y15JfJ8CC3-aU>Zpz4ubn(&+5S4Q>sRm=S0I74GMwwN?VgceA^JUO-( zz-bvib$AP&Y#GN9Q1#_*fsn_Zk8kzQ#|xcJ_~EPV_3jB~?w@0Kwlvtkgj!7AJ_G)aUONc{co zRZth_hP_6~wbHzPU+tP=jbGiH#Su`&Mv43iJ#Reb*iuF)uiqE!{zE_uBobE_tNy7~ zN!38~D6biIYCBsVasKyPP_?bRSoL3@EIT8<^d5=}Y=I{(NfMz25}68L;lKV;<~2B? zgIh9B>b`+I0aZKN`U?MeQX3!0?UH0;RyK6=dW11*rKEG!h({m)Z${m2^JocVn&Grtccpla2tLP7TXMAiF! zHYXm$n#|7-&-@I~0*MgyBjF#<#N9_F_}1~4=m_&=Kmw|U{d^?+<1cCc`z9{$`vr|) z>p^INL{**^vi{$S{&(pUd_43D+Q-(MkbtUX*R{}pcZspH6Kt1AXHQJPH^1?oJNR@# zpB(cucnp?$_Zf!&PM^&AkRbt|G=*aDpN>*A3cxnUd9O26L4PtEab7o;R-Ev~LSiE4 zp@#%~(%4zWrT0iOyLS`Vy$gQ}s-U-??WwLBNZ$VE`G6Kkz~_cVGaBDhpFeR8B`^JV zG~=JA3&tr}7Hi{sLfL-^Xo0^ApETwRj~##({wHDr38>=pGTIwgq9gx_O+X7I;B&*y z95|(o2mU8E0STyr`4h|!SAy^Z=AqYO9(rhj1blAflUw@Y7R*CGjCtrG0aY*?g5{Tx zRNRPpQim{4DzrcXJ~wO}T)!I6W}Z}g=1GMFRKYw4*1NUrn>EY>If!{6p#>7~xlt%0 zVvgf2%*$EAyqu7LDn6f~$mj+>$UH^MnWqR^Ai+O_J)S+n^O-m59rH#(0;>4zggebF zM6J^vICXM25ymrNv=>H96^hQOhT_;~N*sDKl#8W80!FaeX+4)3iCzmj;M|?PIRdJf zM+ZG+ez@#md%dT*`M_Y*kAaWKA>I*KEp%DUvR zu$9Fu9Z2JScC5!v24itV>v0?bRZT9X z2@}|S#hA@k*l9h&VqB~kh%ZJZh|mIwq^NY^8H><8WDz=+XK6SD=bV^^?^{pe2&lT< z&_|HxL72^h*y+ZTI^mgtG1%wK6cJh=(M;_l$g?Gf`q@&xPBUC-J_n~Pn931QHF15B z>Th`qT(B#Xm2t!65&A!_&N{5B6S)8<~1W;fNP+l zC}N9^Eob)Fg581L-QDl(``q8XYu^8Op7s4OvClqdW>yT1?kDY9JqoY|6IT=VM0ozY zzH(mKg>*E`mL8^y1Xlg|vb|jIfRl90VzZ%==p3xNPZX(I|nys$+|HS19Ay@%K1>cQ%B#<40%)N$rGK92_l#qe%FToess_-Pu!DYR%87F@aV1eN?G7Y^73H?#DUD{W#cy z3A{SvYwCdQ(#1di(lhSI!30*}_mSs8IxdvfIeJTK?t{b@OyE@}k5zNclm5(YEbZlf zPE24Gejj;U-?$Fa2=1d_$bIzKf(g7@R;h;nZYmk_^_4qcUtt2P@cYQ0`BP)517BZB ze0_y2n82%kp3SlU7Ww?7rKGb+B(Ms|OLhZ5!NH4dJR$^=a{m#HD@tdLMo4a)A zj!9Cd*pYxOn83S9l`8v5Ep~WubE(6EmVk2?a4rb;X7P1mtS#&OAWiZ;CgvMpLOcuK z_0^Eg>)b)=aU)sCH^3_FZ{hW1Tx&4*k|9z({WRsb_Fw-QCh&Qo{O7!Dss&2`RbEinp6Egu@Fo93Jc}CUtL-MdqlcnxAy9)$XiGI%IXLrei_Rf?# zoAwl94KRUEyt#MDaEZM1N{)1KazBB0k&WQpLp}w^C9N)Q~SA+^nR#7U={v^DmSt{ zpwqYq%V61K7Ob?eQS=AIZX5LktOgH5={a+vU2iwVBp zL1*Do%6&~zpZSumFN4m!YTt3_{5w0SQ77(`Zzg<#Z z*i@-m%U%M3Rd}tLx`bwGjxc5_d&2+8Tk;n10fRMM=UQ2NU?j zn@8hzw1xWmZKb%v7=gel9No%KSeDfWE8kAi`n2Xk+$$z<9UlH$YhwczQl)HQ)flpl zx{=0XwrTs#&yScK zv8ClNR+77${K#Dw8@iU?c)Dt&FY)B}rPlrXzSKVZk|5sZxIB6N4aq#nkDPVarJX7^ zk>hpz$d6|#dWLN#ukZU1HNXAzVW%y;jW2zZL2q_#d8WMuv@iE2(+b_SCnp^znnm7Z z6Tj&#$*q!OWN?K<@%u`8n0k`t8CQtg zizVcFV-FHW50b~*S8*aYBnVo=Y-z_2f8h6gkpJEDfoc5-o+QokB!Si?oM_v`A81;> z)HNpvumuxh8%quaf*dhhnmjN-Ah7B)coLV~gXGxX_n6!oULP8r%9EBg@CR(c#9x;@ z$eyFycwAl?@0HVef9U^yrbJ7E09!CodxSfgn^{J*9hJLl-cD@*xpvc~f6K7cKlAlp5NCBMN(;y3v4csQ33=y`Lhbab(=Kwy6vaR|7l&TQJeNhdWtO z*paCDZC5JQN%N*WF9oEk&iwv6^uMsmGtz_fi0MeWEmQ7xT6nQ31V=WJnmtqlwqT-~ z6R%IClkHhb8}Ba@`1y|KUCj0XY{5ijA9v#L?|oh|0g-TcuAgMnSS=7(Rhr~M#`C+j zzW;sK)~?j%Fqzp()`l+7bG$owRqaa(`8{e=26~Y03w+6&TgS=VbPtk~6hW%>j`3bK zss^Yr-$jB=?gD{TxIMo1X&wawJgTo=F=OdM$AK}v>d$otzzc^jd6QQTkPE(LED z39J&w;bYVa-Vb<2W~bMM%rgGJa*T;S|E8&2;z9KJEo@!*Eo_<c2E`XRg=rj_}zwvlKVk7fxs#}hrA-tz!uPGo3XSq zrk*fYm}or4gY0r}BMY}H-@CtTT7Y{mbE)2Rk-#eaZ1{bUJzBwp^t&X=K^!?Alk;v5 za=t>BY@BzJw~<^D1#?GUC-d*R0=8h{-UWBkuFD%u^51tH4oQoKP3sSk{`qwT0;@c) zco1XVH=1s}PVqK8^J1an=|SX3wG-sj_auuv%QXx2&yaDhp5%a6g(l+cX)@i`gVgC! zq3QYeU5z>hv2ZORm)uEk25iBE#cL0uIdW6eR_`=#BQv-K+?-fS7X48R1Xkf5@;9np z49wcOk!W8y1GZqI%X1HsI{%Kw;H5H-KKG)bx?4G^QMZmjV3j!X(mk>8E3Z4*xlJ57 z9#cb&CwWabYKGN1!`rCd-4c$LG$W?(TmV}zv8=BL33SQP82)|RX8+Z#VY{s*DZ5i! zAh61Ok|*)7%+dJFQrggtiw8aZuN8GSIYRm?Phu76p@FP3WKp#z*-+3>lahOexSaPO zvA^6k{eqNx8rIZ`hoV)T!XGxM1=xa#{NbnP@4xB^1Xkf5 z@{`nvI0%}3NV7JgHed@TaaMrsBx)nEKE6A}x0P3SaP9`Ly>w6btM3 zET-0VoB&%e(fFh%(K*?$;$E;qxZX~Ly`47FZ+C430;?K7@*)PeuI`_4PWkq^5E%zc zuiMEkJL~|jIq_O_zqJ?9TY0FW^6#6J4_G9FeWAYm^pz!G)rNR)av}Ig#n;bcdTF0x}7re!um;YyZ1r5{EtXrl{i-?CM840p}O+3jpo9-9nYIq>rI-4 z`Du+qkMlN;EQo{ONrCdhMK*vfnCQLHi#$BrN_*>2&oe<`>Kou0;{4M`jAgSqqGB89Oi9oY?}ff1`LoJ_SJ`aao*%D zzps5czpwq%3?I_@&wQ=Xtpg-}s1I4K&ezsnuB^yTH;9J;nFHm$zsv*zt8jaK?Gu>- zU!Hc5=d?BiY{5jm3?EVyFhhG}tg?pd5tssgXVT<}^^61ptHf~>_elY#CZpt4HhO^j zj>oj+tPdHmcD=TBLuK{4Jw6_`pUjc(8W;n%VB!YPC3GIXSz9?>A?6KCfs^%S$UnFr z1QS@btlEeCTDwtea+q==6yo8~qeXJF3wrSEjW;P6cSLJvSV8>i`I0?jWbN+H`w6Cb zCAI-6P;>iic~1X761HF>)^igZ& zpW3(5nW?_Se(QDZhv?m8#Ux*HYR)xn(74^?Ml&CN?`XBw-cPwL?G%3=ISor?qYED- zY{7(epfBk#{gAdaVLvC_o#P=rZnb>4wGLnctMH8Q=aHTQs>p@%!Qk%_wqRnlpD#(j zbx?bzztTowyA<&4SSaUg7YVGw^Tv1dPg+Av`U&|;>~jh4_3;_Ns`);o!1ArO#v5fn zXwfPeqUTk}{&^21tonJ$mpB@|(M~ZgCn9lVYBF>iy<1*W^;p6dO!%JjCG!uz(%Qu; zZPd+=gP~9N$qrpV2?SQ*Ipnb)y#C6fZ=2+(>o0}pfr%wWzNB}*JK7)a%AKs?suZ|V zXT4m)-UtL%;m-n(9QYmskq4j2QPVF-_#_3Nu(aXN{N*}RdM9@SZ{vMjB6KslDbL6| zC1F+AR6jE2j5$49cO4OlMY|H=kH=NHhv_*9TQIS=w;!oaF`;H3*DK>NZw+ITtL5b- zw*>;L@RQ|Lhx#W$g8M0XzWSQ*%rSANz8|^YS(mmf-o)EzT$ThEqbudC%4&hYDtv;( za{>b=}b#8r=9Je-Ga(5Lk7~!=E%V zbEB;s72@vr7BJAlgcUsBBvm)?BQ5*;(S>{Glltxa$tzc1TGe$v!8AWFxg85HF4SP> z$CgRhf{AQ@f1>-vjhc5*;`CokYYkh9RLrCH7Jp8-hxPNeKE122AoNcaHDB-?iV&gP_vSdnq zYClPd{#31rf*0*-GS`+X1Olt@ljRvzzoX%xzcD-YXSwjqF>$nmKZ%^^O9LI}^EO~- z3>-EzWXpH16bP)s&!69jkQ525tTv19JzBzZg6FFIfj_xq+l(fC9nRb6u}K5viLNaF z_#g>eF!Ae`AL)I(1${7}A16A+0ytWz+3;2!1Olr@yyI9<2kWE}r{#;eve>4F*EInnoEV`%=(hn?>mEf83Rd&qYaH6+MObz@AGB4Gi(!m+EtEX&12!WK-NcbFKV^%o*Ji-49(;fLIG1w`c4)Rjk=y=s1<~NIAg<}pAY{7)shD(D$aE}US z&kD)~0;`5S^ylwj25om=>6QA7J&fxZ&pO5&CpW(Ml1{hU(x47?NS)!nWZ=VgblI4i z#Mj@Cd}`jF`i@tKV{W!EZBinOwAv?FFkzDCOQw!!Pu(Aza3Z&>JskWI&%RIFE)ZDN z(9VyjGul(5QA!&ocWl7^cp?icDJR&1i8=Fp$&fwm>99&lb-vGx&q$`1<68Z{kw@~o zAO?<%XPHBMgmGXZVWAI+rYY3;Q&Zk6a@88{UX5oT>$nI6R^eIawJegXAoN)@>$-iS z6mZIiOkCZHZhPC07?pUFAHAdLZTJ49a=kavdlXIguIj64^^ZbfDZZD1nSmhbLX#M3=t8N7{SJ?vrrx>oFGolJqi zDm;gLE&9m{93Ho3k3$lK*~LUexDUy!n@AJ0l6f0{Wm`jPgE*%75-AW^g=bo&+G}G4 zO%AtW1AFI4cz*C`e|UM5!9yZxUZ)AXjqDco5H~E6T^dv%VGAbGV|>WzHxfN!rqnfP z(%1@Y-I_D~(j@|cRs9UT$=2mf=~EqL?X%=qO(>lb!Cb5lNqQPD@^f-19biyErbT&? zoUftuuj%>Z&R%a)WFJcFrsi{^*5jIRK7+8V{`)0t!9>tDFS1Y@L8pW(mGMSzvj;zo zhTT(b5(uoqJ>>q{vo(P&k7Up1t&*?>6JI`ikuT*yLj#qOe|E8g7KKslw7g6puu2^H z>G}@vyEu?dImz$n7{JdNXaKE9SwMz6dlQxHN$&ChWZs z!hUYQC1J~5>Pd>u`q3?pJXah2CmwCMp(ZRo*pM;rt3n$B@z|4eTpUQZ@*{w3{Kd6L_6ooUL9mE^p)Cn^6?k9P80LCQ~fkrTD+QRmyr z&TG}9n(*_rFDsqi@dpFPoE{N;Y1HRD`@cDmCd-X517EJ zp(j1a>^%;2%1VVe)zS*8`njhQ+~pp( zRZaBi%&S{TSX~b?Jkfxj$kXuY5beo zx;9&T(o!I>N*wv^`&Q7YkvS`U;UtV4kLf4(b2_{J&>E)i;NzGo)q=V84cN(=PJk_# z$Q$cPMuvUV8rtsUgvQAl#tb)L#S7H}fmK7b?qtiuPgAI<@@d21OlsYdpxG7 zxi$1jt-)rWbO&s~#MZs;KU=^Neeon2f4OfPp zkY~*g1|c#FMQq{m@q4h2Si|?rm*r{0LxpkR7%zWace3^RVQo$Y<-PJMwg&5|w`7-Q z4Fm$K@Vs$P+{oH+FKef~*R>HW4EG>~lNM{;j1Q9)*>0qGR*`nk^uzxzjx5H*2Kw+T z>F4zg7si2!`@7x9&Zir-Ysf*~tH;hZ5E*?;HlN#AAh1e^VN*Fhvw__!i)2TBLJ{KQ zMqI`Z)y{Q2PI_wG$g!Ns+7(@nk#_Ig$yfCxZQ>0jlH>Op8~D7uMBWzP46p?g4Kv-y z$Dgyc&UOmnu&XxwNnR;S^&$iUtMH8Q^Q%oZkZ^L7++d(2%oQfQN4Sv_QlWOdh2oDY z=iae_JGaSg7ZZWNDm-ue)=-r#MD@)$9 zArc1i?~jFJ9kq@7oggF6x{@!%Tl;!AwAg^wrI!6Wv5#LwqT;+16Shsw6XTC zwu-mWzmqMTtTk1xXCV?;CH5-do-G_}sFA(z#KMpqSF%rivf|nPQ)K!aR}#?wYQ?#~ zPLai4?)=uQ%8I*wiWfQKw=D#AkCgijhy`rH#O6|0GGV~aiZd@1U+VXRPO!i(TE6$R zxj|l&lE%{Frzs&>vFRW^s>Piw4qAKFtmB;}HOJ47FVJQt8kN`=O-N=Dgy(69# zo+YlI)nv`~o)O2L&XLhy)uip>b`j^T&vD{S4SPuLvw?o=kO0_HqUTCpm)DMH{O~Nn z|B3G=zSzO)afhjak=O<%GW=c1){ZCkjW$){OKkf)gMt5jnzt!h=oMDsF{xDNx7k6r zABOUbJ8^(5nCRKkm2A(jtVo=ojJ#!>9jt$5B^OkP1XhW2bz-+YJpVFByOr1YeY-+U z9_+5KIcIU6_-;@Wr)YQ0$v@{vdp9?dG{If-a*8rnBf8ncq@btTRi=r6EtnWnr6%hh zKaMzcL?Mp+is(Jd|1_}*69SZz=T)E(l8QDuxkU=?nU|3)=( zfN{=s$=B2bz!pptbW@WBCkr&v7p0Bmh7Pc-r5R~8O(d{N9LJB@4sdqP6LPCn9K3K> zlkViLX8*b~&a|aadt7mKuuylRA^3zDI=fO z*#XX#FC`6fMFOkvv*BK{>khCr`y0{Q-&zXem{19bcU2}o>IT(Ed&Cqa1VK0_fGl7Df6!Q;5(~XV_`i zUfQ4=1qK6LiM4YkneqJ)S=~WR2Apb7LMjduO!I2&{*LfHIbAY6(h{%*6MhkDa(sSs z(xK|_HX?IYBY9Y)OCWduYlPjs2WLUZq8}(7`2==XdN;?mT1XkgB;}JsE zwcy9sJjt$UGYGYIBWV}s5${X8$%sf-(((B`GTL$v$u@K)r=QLu>Yd8YYv@X6uy&d% zO(_I{z$!c=yn5>+N4UYW$z5JW3M0qF+#PCiyZ=OT&rXS3dNI=x)^#2yE#Y@zFrCuF=XK}vdED?BA=|&EYDI-oLn@P@ES90gfa&mKCIl<%Od0xEMy?I=|^p%O@ zz(j`vSMtlen4BzDP7QXhsRg#Vv!w%R+>egt3ajwEsZ@SCb-`p|p%kDW0dFhZNc&NH z$!Lr91ov>|Hh0qR(m}H9k#c@@qP-I^&xKNU9U>5>J>1BSdfQ2T-;DyzvmkhN{BTkz z1s@Sdj){6MZbVa1Mn0V1%-h&2)dsK5^QBpTNy1!V6`loNDddeaUTI` z)$%$XWc!*+WQ%?=5ebKr&QJ|SQj53mjUO>M6i;utD}J2gi2?A}yhbc$kB@{cm=L|;2WI*~LE}cO$-EeWz^d1; zd`UKIN$+m&$J>}&Ss%*V1T!zaHWIdA0!I|^dX|3$f>mC9_EtMaAh2phzAv$OOK8_S ziXW$Y`%rKx@L{W_PLZ$$6F5eLuaHZFp@Ee*a~QKoAh7Cl9ex)`jS$+xR`L9_z0?Rk z*KlEtcNR<7f(aZA!@sF(g+ikl^;qD?Edqg6rgwbE-j)9Jwz1;>$Ttaxig}K#)%`6J zwqQbxlZhJJ5FGgZfP0=%fxxNpxuOI?aJ6f|w7F5C(OyHO)9uIdU z3>MY0VHtN$2?SQ1O!Fb!Top@6Cv3wBoUHX<(Yy7i$uq7D30BT`i>)KUWyJ)!=iu6aEttTu_51{~h6Zw7hsa|-x(WnVW%8`wGV54v_ch9n zWz~yj5Y?`O-1$x&z!ps4+ynmB-iiRJZh~Cy;3*JT)#S4WnNwk}Jx!JUpy$?RP?Z=i z->7l{Y{3N1y5O}eHbj8SGJn}{ySG4KRq!?s5^(%z#b1+@Q_e44`8W>Mmd7@618l(r z&TrxIaJ?g7YK55`cg|NJu<1*+DuRHUqtx-{>xl2Ve^(aDIzQ)!8}% z%56_jyO;g~fmO#px|5Q5{UZ9lR?gwt_H7FEVKLpk#|y9p6FA3+pBl6chm1Gj)Y2nJ zAh7CHo;y)#-8DA%l+%yWkpPbh?`y|a`2eDqM?z=O~_P2oultl2$Wcq2>T4 z{$H+sRU?ph^p~0kc?$$q;R*?SSM<^ehOCNVT|3G`L?hlIiIITX_jRGEK`Yi}^=Tol z4-+@%(5EX_Ayj$WqSjB26 zO=!saohuaxtPiEEr zP%q{&jS5j=n83Rw?v+{R2E*QXG2_9f1p=#Z%oN`b+WEqpC^c*G{In1og$cY{;$DD0 z?l7)c%`%H_3j|i-s3-2**5i9;o^Rkj;Ifi+yC5E6 zgW{~P3diUu6_f+u)sgpdRaZ+P76%h}x5TRgXL*6y&sTE)6OICbRbph#(XN4TyT={5 z&t!WcP6iWrx5U?1XT2bI-F10YRXu^gDltx`w;TxSyp!_nAI?J53nuX1hsWa7^M)9m zqjIjXr$Atp5Tm1t)C+M@?MBOQE(Hm(ADFt~Am@J0h6W&#s=6hAR$=cu_eUKIgl}W@X~OMr zA=UsBc(=qe+;(`wgS$8Oy_wxqAg~I1$$9nf)`8G8f4pYbhzP-djtRV5;E2ToS4A7 zC6%iF7kAj0+C_@bj}Qo~!hS=QYV2umxES6|dh(f{^CC|!Ch%^F?>RHvp>X3!=_5a( zzywxdFCh0|6?;MPxbc$V^Dx0bhzW5Y)jh`z)|TZ;oAx&r2&}@sLhivz_JqMMGo=gf z8VbHUOyHVsd|&&=6{39RO7gr$0)bW7v!znaYT*HclIKd5lNt&hEKJ}kdHlR&yDOaJ zcm4daZzK>{g*|lquC4j*U~*}`lv~nJ@Wf#P*C6B(zc#Pr>2@{9ri0y}ON9{~(PyNl z>gYAn&*!&x>GvKQgUlO*Z2hH$FWWRPDysQT_~J`Dc1g8NinnVDI~#aVU2=suq%S1} zbv>vT_b9H>D<-*{ZRnu+7s$i0iud*HL31`mZ6>+3NP#wvYC3A2DamjIM4H>XQ`TY+EZUMzvg-3K%J;j zUsugoL#2&nNA#JYx)~eX`=pd;?M25N3Z|drxny;O7ah?*lsfAakkXzGbVe?rbJqUF ziP3uuS=5|F)}rx5>GLvg`lC%W^>gV@ZXNcfqn%=D$d4W*-Pw`$Gf1O*4)^B7oP8#& zU4t}c7iJ-Cz3D@bN3@}<3_?h`u`hMso=$f*@*&6a9ckB@UFrBCew@fzQzU!t8_H~# zULn`E?b7Q_y}{<+$aJ=5s-?O!w#`s8ZAjG9WXbhGBf1j$pbV>XWY{klUcN;_#a zZZqgrzt5UuXTr2q?`F^u37<6g`QO7APNy>+Z8-6w@rC^}`%Pr`20b8`{rB!0az2+1 zj{Bf__x0t@zfR@SqT~;nsq}ZyFIv?MK<-+`JqwG->EtA@9bv! zn8IJ}(%9StT?uD0;ylPh`HtkjCpf~?2u5~FV)xSrOE}jK=k}#KJCgrCCBvubL(r{; zZ0P%ULJk(r;92|Ho=3X{(g+KsqC=BxL$G$cD6c(70LRVac=NT7Y)Md)L)w5eC5ENu za$`_E>mh$~O9C8$i{p0_cH0oChpYD0eB~r{%P%_!c~vZVnKgwOn{CMd-e(*|fTI>v zs`1notOhTWo;_;{*e{R0`uIQbsuA7oU|Z}mslgDj4NTy;1AYeZ%nl6omq{KDB7s%7 zhrE)fkrh}a&X@XcZUOx)tjV4RMI>X1OltXSR9Kx7ONdahxTN>r|IRIVN!ADbE;5umHVNt)!wG;_PA-j=$t9%eCfE6{Rc5R zw=P+F)Es6~Gs#nv!fyfp&w>dtUNkh?7@kgbkUCVP2?SQ*Iph@`?wJGJ;`dayPZs71 z6F5GVXDH}efXxqYY3dR2d0-WOHhe`^!yN8wXOa2u(*VaCKf7l|eEwNe;rMO7yIX7o z9#hiDv)UPeEtn|su_pgpo$=_MLuPP%OD*!LxQ#$y6^{7kr?oET;Q70hWWS-$I)AO#^Jf1dhh$F?Sz~V3X?wvSn+!KwuSqvOK~x%N$mmd_?SrrV39G z6F91z-#0PC9Qu#@NM_d)39Q0V?A-6{Z3LNt6Dl56W3}Vmz?mI<&2Y&O`Ya2eH}+--1Xkf0;kT>QHiPB; zn3nmc3v-1DoO{CaQvJ;!md@1%_=*Hp;d$fdaQUWiy-_Z$eA`ACIUbXk|M8mFG`xOq zJ6#o&0oa0xxcAm%!>%;bGZX##;&c;0vv(lvd!^&>+b z-Z>TU+8M8@@%Xqmp)p|23d`@aWgTBz$%=hs#1M@YXrV$3gm#_Vy|%SBW{m-;_Ue^=lnd`|4STT3np+D zC65bF)Q6;o)8z3Py1KwuT# zU-2yLJVS73cwUZ9m4rJjaGtQZSNpCt1V6nK^7=YW0b4L3=GX2xr3+byD&=cFQ38Qg z#*1vpFu!%$1Rl4|BewL6;9J;!IrvT#U<)R2J}=KP@#mkChP!3=eys!otMKzzslr+s z!Hk2O<(qje0b4MEvy4@$n7&4EWY9Xf#i>>TfmPz?>WHo(*j#)eC-Z35o1u0jQ@W`& z@@GQsyqFtqV5hIfO^uV+$s5F1ku()yoj>_P;J0 zI%@<%P@xQY?z=0j0rEu^i<{Q~&Q7%>%^f~z6Bq6m>Kfqj@!X8F2C$z;v5xB1Ko|$k z&&PTDyn@+t16b?uULJouR3NYl*9PF3-i-}lF*Roo_~|pQ=zwb(tUYf>o+R^17z>s9 zqB_kC0JfR2@ClxPEttSn5x6%)T?5DjGdA&&k3e7*o)P}J$~J)QtM%E(KYqeoVFK4` z;8j(M3}CB$4R)|JP#~}h&l|rn-Q55-gjummYg~nq<1yiSAiTE7ejT7%2UgL{MW~m7 ziTQQxNmef_IxBP=pR4*W^`Xld2X=agvp`@Kt{TFUR~I*yc(tZbzXVtAsOn`; z#>-ALV3ZQ;oK>z5X}{DgyMr}g3np+45dMADR|huhyRx(O>;(d=a1VI|_H}*mx#Gk= zA9Mt4!33^M!q+~$D$L`rj%@W}CxO5!apZf}>cfFT5B4lstlWafgsaBz{a~ODOwI6P z?UtAd^<*%yYLh)tr+Lt@-b(DbalSrCmVQjlqZ9D|!YW+LMx|;qULPi{3uST3K1ukr z4p-|DPwwhu>qER{2%8)7UBVVj;Ce#bgJrA(sY^mw(+?`Z1Xkf5@>AzreQ41%ke%78 z3)q4QT=$1(rA*fc<3fMd^q#&zV3j!XxRd&Ddq*>-cCQj@Y~gxK%X&JH|4z?S59&i) zKvNd2dsf00OyK%X{L}8E1G}$FtmC)a0)bU{M)-NjYJIqSs0j<6@<^CnObB(VRGsJQ zL-PZT*aFL!0)bUx^`s>W3}8m{ST?#xsf4R<;i_DoCmhI-nz8ioG^LK$oFN9#D>#PT zsk=_X7EItOVB8B(z$5yb$FPxecL@Ym;W<>P%ybN3>Cq^*tjhsmt}ubCnWTMWsMsl~^&W_I^XCvoeuwt2sf!r`fpXop`eCSZW9((-T?j?a30hU;@{T>@{Fok;snJ!tiEeS#}%;)^nL`4BRbsE!b~1#G-`lc>zbU~MOhj*U zB$Z=&(aJD=-p1|_BS@UpmIV&nBM?}HXM}r9(%(r_#&==)7Y>k=JWCwoBf&~*A-m5dbSI7SD)#tz(aNDB;d%T|t1Xkf5 z@~T|YP05Y*WMl0r$zk5B^SoCXyjSrX^oUj0!PKhAf@F67r0G~ZlIlKGDc_=l&q-ZI z_F+|JRe}W*%Zu-5j5Oous`x(|zOU8pmwLV%z_y#5BMZ32gj-f}%bwCZn#{>#=m~XA zvLW-L#^cHay7K8SPMA&GBDqO}Se-8C1q&vAb6??=|M?14cO&OWKNk#VPCKp&9!2a$ z+;5z(NgFtgs{ef9Z4?knRcRAg$cX!7^Co-k(8W3Q($bHb%pQ9xKBVN*yB9xb#&z0L zapYgmXy=Fpw8w!7%y{#Cf-RT`o?TqgV?r+Ny!Hcc<3#CsS;wOfyB2$zl&sRDMkPb& zz$P__`R;GpH;YHmGH)I7x%7^!=JG;we;9hB1Q|HT@- zw=-c4C%HmY9-fxs#}BfLVay)i3Ukiwcji4x`t6SS8P)pbdxkN-sTHnfq(%>HT$i|R=P z0;}-6@hqVw2JGw1ST^TniR632fe!v>J-E=oo7!w|N{8rYlji2$^sP-ZS~hz!Z{tOi z8mwkmBJ0?2p+I02o)Mng7jDSgDiBzOpAFwlOw(r)kIU%K<1(K2^`zZfdeGHPi%D6IC*4uv zMgQ;$x@E8J>3?w<4QA`JNpX#s@03>(wqU|wgC~8^%$J(>R&J>H=&Zw1O9i-6@uofinK!Vyrs0?h<{ zR;e4x%Ex>WM~+6jxrrwoHA+o?1S`4W_4RcaF$!gtom7A=cox=fvZw#;wy)3N<6uGT z?^Q?$^7<)>J{`XUed>!&r%8MU6Io%EowhaBk7 zwQISD*bh@Mk;tz7Sh5;jZIJr_Oe!^{1`mZ73u6ZWhQgx9JK5R*55Ty;+}q-RR2n zmRkuU$79MK=s^vxSP#Kk!(e)huyj@X86W1ruLwJ!nIsPxY&nIGG3gbl5F^Mivn1 z0@#9y4d?CXf9HvI)&^|QJR7!no=9NTc}owveybim@2Z@tt;#oG7p!&JyO#mL&-ZAj z#SgSkLiUnY6Wr;^_m8wEkMAKDrrOb{e@x=UH z;{=u+b))6k+q8=c50Jhm-RPI0<=QK02grs;w)DSvIH`*v%N=$@cF&6dY{7)CgF9W& zuSz@gl+wmN8(kI>_DpWU{RWu8D%?XJld5aT=5pUeNA8=z7EI_lxzpdJC$zJQl{OxH zH()6)ujFr?L;|bCk$2l+$U00pDQEL~OL*kChq2jiG_#~gJLE4V67W!!E+a=OZDiClVh7E4$s2WA0JdPl zJIReY2j*&@EmQJ@pGE4iAwlKxpr~lT7ED}?v8Dg{Ajb_dV!ywxk$vq&0;^VP-016> zleGuCDHY6i*cr2^1$i>%9>pyWTxqWdjkRC*SCL*nU1{3ocx`!gCE5MkhBo-eOUmDm zFGj3h+kCkVziAa)Fmcn=jpn^>uN{)0Vx`>sYWgx-Ah1dt`DkLyrfR0jM<2%vBgbQMIOa;v zoU5lDd|dJH>h{uS8Am6}IVY0V<3;Tz8?%gKS@Ocgi2{LDXP7HJ^r@D1 z*f*t(g`Os?d}o+kz9I!K_Hd^Qvh2qF*C=N?zK8u5w=gM&(Qs?J~Q2rB3JBA6$q@tJ>+%hPZ+b8v2Eosuaf{< zF!7_*l~!l`tT^^q$<=>XY|I#stzGLb5?CdU{6vBYE79?n(|H609yuP0;|j;U1`VlpY|_Z zqO@^YWytm~d__-=ZVQR;t?7<`VpXDRxYEb*z7Z$ipCy>)G4!uYSce;*=;?E5fGwD~ z>hDT_tvj*L&RmHq)^0IjW!9$h*7hQSRbsCKcAK&uw=?Otn(45X-%yuf{3fE;nRDb+ zm73mr{y5?suh<&0&zgq+8-)~HV9J)y&!MZ{wE=9w#L>@c`e|p+h`>7Mc(1Bj8?t6R zdPmEncQAofct-elJI|Eu%%gV(^5`9G!9=}pYMMT;UBq--r47$8QZGP8RupR9UOz`x^itEZKC?AXcx7F_W_WGE^s29h8+H@3 zAaLeG_y9G1)gnieucyS~EFWjdqLyV4vjwSu|1ZwEIMP&2d(GXadDB8^ql}+r%yXMT zTGvYlY{7(>o1t=zNeeBPyUCAsaYCe3nn@>P}4a1f~J~Rh~~SZFmq;Dv4uGB_(V)#l{j*vE9R`> z+?vv4Lortdk14(u&u`JOCi+v9Z@3>R#%xzljpsCA3nm8haqL{|NuG>U#u4pk!3vuNOCHf8fmPzj-<-E#taX3sk7pcA z&b6Zdi(}u{R!vJ^XOgzjhso7+HQk$$Nt$OW>#MiVjala#-6RvcB!R#xJR{2e1{TcW zQ9EhO3_-zwH(`C)3X>E1B!PN~fn7<%qe>l?o!2Z_ zlTHJq!4~3NVHKV??&nn3WDPgYl9umo1wHGz(m*Mnyt%fQ>~M0WCw9#t!;SWl$!D$T ze>n{aH!RuDzjCD}L!$v(Fk!n#O+yAwBnf|4J>9<4gstXz6K*_j0uxw;XN2GT+S8K# zD9x5?y^Im&3KOyG)O6{+F(l}&QXM9+jV0S(G+ElIjui;3!t=&`+vBa6g?FJ8_oq3$ za(AP%XP1$PlbcDSU3?W*RYGh6%gF!>Yx=)z6&?v_ZN=UVoG;n0XaU%QiS~uAw8)~E z)GShVcjGE+vKHBMrCq@-1p=$uv~s0GU(6$)t(1N3>}(sh28yM@wIX3yusaQWbdWqY zSxr*+yV24yd&zg}^`t+urvGKW6xOz3U5_r6j3-9|wqPQ&#Eo8UyPFjJT+iDm%5z|r z)k~#vGk^&Z9<<}#D`b)7Qi5{{?^`+2M#FBCQ4Y&Ek@b$p;Vf7#O*j(?*n$Z$P#U<)RuCY#X0 z5s!%JHzm)jdWaDlVZBnSx*IJJSS605q&2@8xYs)A!OvvCeaBI8<$CcMW+h{R!w>TPW#FH716Ds zREWK|@~pi3EGKTZgYxm!+UTNp#J$N%(z*DiHiEn((_B^(i=hAG>dfP6`r7w@$~ng#(B5kkA5)Z2k;puc$xQv$etysAJlFdE z=jFQIXLZim`|NwIb+7v_loyVBC;Cp-*5NWe&QKGxc(T6pG-+nPM0u?AR#YsGiDrAw z$?3noip^&p{6EC;2bXBssS`vwJypWjLgFMFd)R-+W@~*vvZ>jV<0Qmj3P+#||5~=^ z)ps>Dy_7_3&(D4zQ?imVcT*m zjjNkPE}6}cP(k8cy9C)j^oO{qp7zeaeArHp86}h0FgK1s7k(n_m-^-rnk^-e=eu3G z&k704!bJH`{~zLR18s~T$2j`pMm*Uc>%tM}!q1JZS?;%^voh1jR(DV7?Mh4eYxZk# z-N^*;%ev|Ev4iDejo+**4)@OYzV@Xro+p#7#DjYuNEqLbkmqgrD-Q8F%>Jr(>C0%@ ztYp%vvpYwi3qN(8Zrj7N%5&3Gq+K%~>4;rwhTkIt65JqGd{OUJMunpWq`~(iqD}LZ z3{(HtV)~dQHpVNX56a+|Y2<^Sw}c83U(LJ7ZJz1K$F)ZoF?wxvy8U`OS?cM<5$M8C zgmrQK-hnQDnM&r}n!|loNIZ_|ArCmKBVmEs7)^q#>F8~#)>>Nw4?aHRH zr`V1-|IYC}Ee#9E$ZTaucJz*AV|1TGlr9EmNCOWa2^A#j6c0>kZ1-B+b6@+c3I?2z zb5EWkgBtmA1iE(i&py*~lp*OdRvY8_+OA?or8A^%02`xOitWFj`+^>l?a1ziB(Pts zh&0Q3aqt(aC!Qk9TKY<;AhCGI>Xe(q42johZHyW(4Kq&0pCY3=@C3T}zp7gHeX+H{ zDKaV9TY537x$vl^0ojspMEp?ey6y4n2Bdk-SP}nP)<3FpvRJvtDH76?e;-JM*{9mZ zKQSOz8fkx3s~hXYi<8;=SjiLU!uQ0gk&GHm>U2mY8!F6}l7@#1H?IE`cPu?Dx~&>7 zZ0e{Z-MSnRx39DmO85T{g8y>7{fc zj`QLObn)-}X?86l$E1;sXiQbjT`qOEo|2LjM7k=t2>Kn3yJqZ$t zSE8F_R5L;7$A0^=*>B&zZV|%2znskq6NPc?_v*-hey`$#cMwu3nOygFlTbloWWPk= z-=_qt%5`uPxhEu%cdKV`W85SAgj&hJM8jkJcl`daIqeC%bdeyT+mA~Iu->8Ek|5=3(I8ILd zh$mYsxk{)YA+YabB>O%N|L6O-Gc}e}wn`ut5j=q|{GQm3NrfVEIq(?SQg@Ox(5OUM zW%OP&(;X1q7Q7P<2_HnuaRo&%dh%@_Io)v(ck&*I zL*43&Pv<@o#s5UFZ5vmTqG}u>o6?7K1iGST>coGeTAeP0{;;$be zV{eV+2y`7@T0wkz@Rj)CrnXak+_{WA_dZN+SdNxZL4toD_bL_8{3^%E(%uddMywd) zV#KM_wf=gC#%?=7?B+OdktGrsE$egxx}Kxgp2o9WGDnU;7a#R?E=-~)J(9@Iy3Sk- zheVAZ@$!ljH$2_+Cn?hnoyKw}%_!zEH@=AJidm6bd&g3F8BpmvL%MJEi z7a!l(cKfV+rqMsk(@C}uAN8S&kCv>@^`o{ir%7lIA6X(1Cv}(03$w&?8?<`iaR+PA zd1YtF(9e9dgf5I~*e<~6hl<&Tv&8%oAHyM$m7A1dFe^(u(L-TltSNF<=8erDJ_UT7 zh%Ss*SluYw2I>o|J!I?Vz7p2L!Fe>!`q-K3S4Qg3YWs-%Wgs`ZLjvd2?40n63aWSZ zK~ih=2#!D(&fC~C%H|gxf9nvj-ZF-pr6Li~y<9dso+4&;I>p|(+4m=O^X+4#iNyqt zKo?$PI^E_Ld3504V`O-;gM{AyN>dd^BGS5|p(1iJ95WP7P;^;El*on))w014M#aGeRifA);Zsi}_j z-$80evz}qFzJmm=IcYtM4b)`&z2rd2D2_lEe*bK4u=N{t?YNtav>z{_g2Yx`ncQX0 zRxy9{dG^kSPb#MUZpDxjODAyzy72pFW9V+tJGuMF4d@5+{9;%;g8VOM-9lOGe~> zWMeFPDfW+BD4~MH`oK{6=+f(g#aivJ^6w*1N2@KOX~`mvK-b+?7V@Z+2*ING6(foY zCeliMoy5g&gCtatD31x1`$Vh}UL1bGh5-wjzCu-E6snut-7$iSfmu@{jDsf>*3I#-vD*?rptBnfsk5(B+kn7$qgq~7nho9_lKov zI=#KooP<=LBcXzX-|{@U=B?Udw};wq$?&q{bbo#=5*qKr5$O686DMz3ohRHL^Mnz9 zHmB1n{$*mrLN5swB+TRUWark81v}G+jOeuB1buZWQS8&xk0a34`9Yi~yj zC;UpMH>Rx@n_2rvs30-nd!FoX86$*j(0;FKY%x&xp0E&GhdN4Foe*m&;?6JIaUcDI zo_BN?-96d-9BLRM!B!P&{>* z^`q0Bn^H#o1A3EUx5*rVE`DdUGJ7A@o%@q})g8H=Q6$Q0{FSFSwGtco-)3VxTU$mq zH-`P+$|_G!=Bu0P7?gZKsHN&g8P zfi8YWas09`v~k5{q{FL8-2NaE^9KKwuPvJ^wi=|x46%F5=^LLYV${cuBhZDrnXH09 zms0vMV>JnR#{MeUGex3&(_cCIaFqCD;UzXkbk<|Kd&w=~^zoSz*87|=?~VMn*k0&y z{=xsL{b}4jpLW}1Dy|srA>p-z1b=^2_;Q~POFJT_+Row$xQp7Mk;gsL+*0$q5;=yb~U94dY`CR-}IOQ;}$zbmYA{o4Dq(-TWF z=H+ybKo?#y?6gxv4z2oz5Vz(tB~*~W-$!<4bisXk*295B7rSr-y6}o&Ysh{%w4&ff z#@BR{P(cEJ=h;rfp8Iq`Ss=N2bs9&Y3$GZq|FJ!XzWTh36qLG1s33vQD@If*qP_dC zBsFA5jzAZGCB{_0Nl&G(CF9;rlTbkdpS!HzUB_^GW9WMFWP_K4@h3jpF=k{lmf!1X z=K9qneC8Yp6(sOE&w3n|hf&ve%gKdfJ{*BAj2T(=@5k$Dj$shl73M9Wf&@P2S=?Sf zobF!aN_=noaRjIi1bp`A2y|i0$aa3F zY@jLEI+HbL=1Qm_fzNrJu5)fUU6fXpJTD612y|i0$YRmE8|dtVpT!l+_IzqUId9(7p25$M90k$qP78)@l}MPf;AfP@MX_?&0YkMj{Ua|DKo>@t zY?ZTXz8trA3wfLoAZ<)NkTP;}v^c>0j=1qiLWWDhQgO(RyJF$hQzOiIM}o#LmQX=rmVH9Tl~xAgW=DL*8Ba>CKg*k9`P7plj&-w<&viFB9yJ zzG1{`=gG>n-lDk0DMUgAiBE|M8OygV7j9T-#PgDSa^?AT&t7}Q6X+WA`)f*Sw=&yq z0UEJp`V?h;XqFrm9U`HEL?eU5jBDQwgd+yV)u$>+pYJN)yDgPaL1K)1Vn$29!`9U|XvEh6_hp+FooVFc#TV6$^HX&Nok)DTR{P zCJQ(MU3eYqbk3v_eNiunnAcsv`mFu$&OriKEOfeur}C7-W-err<3f%=7hcC~zc#oM z{aVZ_#12^~p@IaiSm<=Ur{*h7jIGF`m5Vq6U3eX{F-j}Z+R^PvJ@-WtDoEgp1^aXz z3Y1N44aumbi#Y;acpbBB!yT3B!3mGVb$u2~s33tW7Ob}Vg1btB!&>qDmn9s5F1(I) zy2Jgd(3kUuitGKCNT?uzD;Dg1EWD>!&-!HJxOOQ=pbM{Kb`t4U75bq)TUCxRiQGk?@r}x4o~2^2449r1EOP9TDw<{a&gvT2^A#xwG6v{A|1TOmd2O|O2_JU zlbgJrka5iPg_!0LCZD<5B*S~)GqK_LZn92#o$+de_PcB4KZ$;CGlZrLoG+n*MB|lV zvip^58KchsXSRJ!pikO+(WzSlI09XBw{?^I)$Ae1Y|)5Xc@ycIh6`!u5Pu03B)TeL za@>)&^4UUd)j(({(3RuY(Gz{lRjt%|}87i8G~P za{H>Ta`75%4PZ?(Tl!8qMuV$)a|F6JSag?{&EG29PuHHc(HZvirgH-ISvOlk1qn}! zaQS#_wA?9ATg$lfxDS1ie1YEk;?5E1TClvkJhn7N{?$S2p-?)=jvl*zmD={7DWQVI z3$JjwYMVG&NYd71`pvec9ULCgFP~jG0$q#pyUSM(-;{MB+HAY)%5l_S`ZGGQma~Kk z5*cyf@`zhkd-EuQqGrEb;Kuhw=Pfv)06OZndB3QFgXTGi~tkWqAg-$d|S>SB7S3dExgghS7Cl z?bMoELK#xUumB$-o2d@&nB8}7GI zCobwCp@PJPpAmAuaqSefm%@mw`CaMJtlnx?ff+}j>(9#`a#qD2%3-4I@ET1WMC~8; zQQQ6QB%y-D5SvK(fVG9PZK9S{T>85U4VuwUO>e_$>A`EEE61j%Y|>j)78oWo;(6g< zCA;NP)%^Jr5i6Tu?+L7g!eY2>_vL%Pm#F4je{nTZkl;I1G$|daWM5mXcI)4S;A^3) zSMT(UG`n!6lV1<^SJ`=I$*rd?Rxgy95>$|Q=P)q!6%AJ|?$U_0PlqWBmMv0~zK!Gv zbj{bLXEZ8ZrYx>*#|V>&S7eX$AoWW_7lH~B?OREy@s7)tYl23!{XAIdQ!7y2Sro<* z==z&}Dx?3PAjPAzKO@#h{UdkFny=2-9!*d|!sL0MRJXc|l&)?XacS{DWs|YL>Ys6l zBhXbi^;E|B2p=V7>@fm1V1Lf7n$*1&Lg_RcfeJ7p3_(jaX?tOc{5f zr+PBKCr6-b!nKr)D=%6qL*{5Z?wv+nlhcB`tIb`lB~*|Y)3QbC*psc4oc$W{YyJpj ze37XtHIq03UFCi$8L!jpDX&gzPXniY*X2=TJE+ye`b(%Fu|1?|>fsP$Wo(H?RLdKs z1a@nwx;z-l5$JMkl#+4%T_r_~)y`VJs-7de`88GlsWVbS1&L#i8l~<|tE}Wc(}>Q! z$0}DJ*Hzzq8^;mo@}S8XS*<_Ib-UkY#1gk$+4Eg3)#R(agbETN{TifJOD&OW&C`fw zOUEl-6)UL&Crsf8bQ!rPXLNDOlPiudV8n=>x8?C4bn3u5P7*3eG>xg3Dt^wFw{F*n zBfIRCIY&Oyj67G4Kv%PRo_5YVnon-aPrlgqO7G&>0dcNCX+yN%fP?%0uil zqICX5rTf!6bh@txN1%(GOUf8+x=WrvPKy)sM;FLV1Fln-U9%-rkk~W5R%$DGw>H8l>Kp8y-!fx66GcRFH_wtezTLZHat8 zR3n}Vla-ar_R$lM{W$_%R-KYED%%Ni-~HMSR>E0(; z^$+PpP(cEp+B)6Xo4=JwUlyuejE}?f$U){MJ88m>Qs-rE3W)NZ?bOov5n+ zRmnQ!r=DMTkR#CbILk_Q@9w2^DT!iZglxE=wCL`uZn~C0P(cEp+N^?djW5dNBv198 z!4-}`SKJgU`D#07Q@7WxB_V+>J{B!_e?cj4 zGDa;5sxP5}1U|J{|Jw6km6Ab&RZ`xPBhZC$Fzebg;~yp0aG+|Q!$-(S;8UAL05`uY zn~X%YXSOL9Q=%8C`X_RXO^so^sO7pp=wRkKRZTnGe{)xsm-384hD4Xi`wcOGL9qA zg)?NfyVUlk@+zdJ8pY0rqk;rJwOQU$h9R9&se;;M$z+Z|7tZwAKIf!c%65ZtTG!i= zo6#eIPi>v<1V^!>0FLL7p{b{e9_dqN|mddsW5LIx8j8aKDAku z=HMzcx_c;n+;2WdpbJ;@*h*^HJ>`VM0&4en0k?981phpr|DX!>3>{C6tQT?wx^SJ5 zonxssnT8!*sBTRv60y%Dc9Z0LPS$8F(cIV|^}*~fA}UDWbDn)x2S(8E9T&2?XT}5x zblo1lLUuM-uB0~5B7mbCy3>$T3so|>JwXKtj0{+In>>`-)LWp&#t!BPbggZ(LN4+O zR-P{!$Hs8}Yff!!7N~n3O(Cctfsuhu*YeFE>U+~)9TL8bBhXd$CQAPM*{NKRs(za0NVVww>p{CHbeql35TQPclI8N;{+`NNIB4%T7C6W zOMaass33un0n6ol(T}dE?XH%8{f8sab#QEyykXK*Woy|MHpYf$B&~^Q7q`WV4gp%-|lSogOnbNpzQ`9|&{}5D=z~?;st1|o1 zfODigbEV4UdG0d*U`a!0@Q{f1tNBb#U8MH zr`St3L+SOi^HuxZ??hCPz&lN+J2`hX%VM3UIxRLLNT6%;oK(3TS*$F6)s4N6q?E-h zXFEV$Hmx;51qr-2*>B03m2^kmTy;ZcUyeZ6(4MJso9pwH&{kvF7|v!vR9fz@67LBF z6(sQ9WVxJ4QS|#cAN8@kh$GN7=xvIu3-DILihbA^vkK?an~!|dhBa3bRFJ?sO{cSH z9!V$Fnypr{-OCZ^+7_K6UnrffJX;jW#&~Hlk1h-LREhZsf(jCNZ|Zahsz=ZRUES1i zC7B$7u8+-AF z-+GLV(YuyE?cR8_`fErH2^A#p-emhxGb3oU^ANSZaXpSem)V~rd3NWXN`s#XY>a*8 z^Qf-(V0BEFh7u}B;JwLu(V0Zj>z9b?|EoDipsUrfBst=PsbXQQovtxC9Y8-$7S&ls zZ6s8X;P3N|4Wek@-d1WYxg$rQ>&N&cc~yB!rQ?GPHpa7q3ux<&J=9C5yGW=Yfvfeb zYPQu1+VfIp^>JHEjzHJ`Uy1T1H)CbnnDcCmhJ_31$d{eezSVk3s33v64(yj<-b#9C zQ7g5ik-!n?s&pVx9%WKR@o>}f6Cd>troBB|s1qJY5-LdG?g?9sy0nTOUTmyBa391G z=xRPBQ7&6kDlatF@+_@xETJyL>#DisLnTy@z+E6#W2@B~di`f*)$-#gjzHIw_X+an zv-f20san41NYiCBC#Iqr?>tUI1qs~EVk=&A*3!!jOId!@1dc%0z^w`L>(`20)LUD* z>*chZhDsmlf@cmADoEh2oKAN+CYnBZaF4E>?Z^@6s@yL@K4X1AeiW|d{8*uuy8*;`@vH}1qs~kWoH`Z zY@lO)tfoZ+=WqnNCQOW%<1CEi(|+3O;GGZQG^#=rb-e8@p@IbNTC)=hh8yY8d9 zP#=y!*ZDf}@{2M1Gk#iYyWzwuf*K!oq-WmxNvI%!yYFnR&wC@?f4dibZ#b7D(AD(j zNxAKZ)n|w9(^eoAmJj!GU{|_*=sXD(BruDBRqJ`OkyiFOs8n(bkh+_N$t|m2u{rAT zT)f})q#Pb^CIp;%D(>BUQeMBhm#y1TEpxy>=P(^seUsw3e6EBF61`nBWs4;qwuOJS zcP@QQqMc*%72{Pt9D%O-oeJc$W({nLZME-XkO!rQg6b-j1HC2h_vhu%G;6`*!((y3 zW4?T``C#Gp=VCGRLB5<)Z@p~~6D_m9`G{+@&M!wL|H5nu6(pPu-paZ&@wU$!Xqf}~ zyYlF^*b_>#0+5Yqti`Wk9*o@<=nrv8W2)f-1*&3!m5W@&k$=6vP#ek zYN=QMEE8PpSY@NB&6K8FqlNmq+aeP98M1YsUe(lHE9M9b8#! zM>+1!WbXV2N5Ch-cKaq7sPws`?ee$$i4pwV@GJARFJ^WkoC>* zETIj2-ey<^yK)4&Fyo)qtVw)F&3ac=eiTgS&H^C8e;LSdc&STU z_u&Y1S$8g$uk7+shPjPqV>EO;Kuf&5)t7BY6I77EnGCBIS|g6CPM&I~mHr%ouE^|% z@*m$>%GftvYz)`&`)FjDr`pOof}nx~&SZ2tm-ff$wL3G^g~mHM0$qKlJd`gsbX20< zBG?!=Pwt_HXJ@FVrpFRgkieM?JIPvjl;%~OrdBSc9D%NLSr6n{!^SAa`J31n(^7WR zQ-2-R(8wDE6(n#b!{#6EN9kX|UR@RWk|WUd*5rZw>8hjz?L5H7n7w^BecfujdePuJ zK?Mn%m#{7vD~{5_Rm0RvL6syV&}H^dk^K5cFQuC4Q8tF-z1`Hj8tdVfQB6Vx37pBW z`n!#e(d$Y-wV8VzjzCw5Ymsc=+f{iQ5YNU)58gwo|LCjMIa*&r1qqzV=yc4PQ5<18%LmPTC4kV z#_F0%g#{`b<9y4@{gbETklVLTmLr>CC?;5Lt#x@**uJ#Fq@*Sd6hPi9G z1{I8As5-on>i$KPP(cD`GHfsPOFS(Z(Gn_1 z;7o>{t|>~Q7iPYo19y+-2z1qPy(hQ)mLPYzq@9+%Fy;t#-13Ch|208E1qqzVuv|5( z6ly;HI(=H|z!B&g`R%TpJaCgdv8L8zz2=TsO6FgoOFFXpKA<3hGZ~$3jBhHfGA)@N zn>vjn(B-%8uAG%VM-F|i&5E|4Jxa%T$J14_T_seIz?lr26)jGqX&1NCE)S-21iGZI zcjdTL3)#U=n-$GVI!2xDZ)T@iXG*9bfioGM?uqj$TK!fCwPNR;kwDk*n+0;(+~*lx zCu=zqTb3NBx_S%g&S9PsDoEf=hV5Fi6Vgt_W9W#fJb|vJK?QQfPj(qAerYqWRZUJ% zo%v8&ubP*H3KBSzVJC8Tr_;nAZRnuzIUIp5KGNU5@&sMy+ms58eI!(nz?lp?gOzxK zPTlxZxyUNYA%QNOm#|(C$s6fEi>lF^cm28f2NL|OsMD7Sy043l4l57f2z23WiRCTj zOrnZYV;V9ckef##!SBkPOMgM{n7gSa+b?lF)vyB`-(PJ^b{?fQ-PL-13b@W|NMIDj z_MKzy(8(ufsqyQ}IRaguR#j9oOXnz^H+N;<`NWr(X|uZ?YD`{Tf(jBCcd-b$*)6IJ znyIEgx8MkLJ$I?7yn8uQIX-kG8>5@wKh#<0u8uVsL{LEj<1R)V%%KO5Pgi%W@!$w_ zZ8WW@oc`>j#I2gm#&B+NfwsEgrcMi3Mo>Wl<1SX6GVBH&ZZ}Q6_;WKypey8Q1;zD} zo$|g;I2*%MI8RFwrm?O%F$5JPFz#Y=&YIWhl&zE0KjmjQ0$mAfD=0#fA&NL{BO60* zbdDzfn5bI)zCutz0^=@LmveCz{ggUNz4Q19N1&^IrwYpD*xt&=@B7#okuOx*?DGiK zC98y>f&@lU?D-LyMSEWBukIaQf!%}udo6UueKb^h<(n({-bdIN?;4+@)nogsGtN|z zP(cFYF4kYI)^)n_vW+@*pbvxKw(rQS1#bj?B8zcGbIl5??jXE}=o`eb#7f~_Rj4abWlu3 z)ux~=N1!XLr=imJYi;FXbuE`OIXRO?oM#!04LV7vAc1igTm7hB`DOIRahlI~pivAI{1NBd@VB28_5u`~P@H zbq7aCs33uH7yG?Be1|T2oJY?;9L*8v+VEVbEUdOq7P7S%u6z1b+OFblDvcd4p@Ia) zUF>9-VLrWENv4g{?KuKnQx5ACvq_<{$73yq`&c`Re(rFF#_Aj-RFJ^9i=F2jR6s{A zkD*VtPv!`81-t8%zn_Q6Zc*CGc7uV}>BepQXxRlv2^AzT?qZRp%UxP+^-8L4b>awg zd79}IljcTpOs017WyIJUw9bi0YI?{;LInwoqS&s!!#(Q#Z92`Ac>-PEUX{xeuEu0^ z+@|HdRbi-$VVI>~MlDo9}5#k#n5D5NIOdeY(TcmiEjmX*uqb@!ibRZWW%TfWPt zv7!b2P5ROC_t&k6RH&0#~5fiK@vJ)LQeWsEzFut^+Ohvc(>-?2fwdgLWT3O})_enurP# zd_*?>#CO`b;WX90?R$XYrFc3N7M>&c1)#$Al~Q%WCwb5x^xx913S z@%>VRHoc;O#95saZNqgxMFQh4oo?{75;`VkiaP9>BS)Z%?`0ZW?*+{m>8MWFH=pZF ziUh`8tcOC2PjvJ0iE8B6XpTS^-!(L_`ZJn4b&|T{?QX6IC=wWV>2wuWeV|th$EeZu zQ#k@%e1Fc>m!8o1C&s8G=mOVm6A6sF*wdisJ$+d`NL@}Ia0I%rk0!f60-w;sfdkcH zyZJt&NMIDjYC0+J>FBdIs{c-%gs+7z>|V+CYga#^QQvITb2gQ@E|o}N+{JRXJAa_D zA(rZqy)`%jUD$t;#c++D(v|*}>Kf}hT(?amFz#ZzmN!1o=q{$}-4zWv0$tcml6Aqj z|CBz>@1%%53A?2yP-Ykxkc*B{kW_u5-<9VC&!xQkW5yz-e=*j+^(!18zT zwa|rq30anRua|T#t*oB+vF17!B7t!iixYKU=md*zv{)860$tcykX3?S^NQL}DWx~J z^yT^}B7t!i%d!|&O6MIYqW<*&JpOs?tE-bMtDmD3(isX-6*aL9}*aMu?RWm8_gJejGj*$!x8Ah{(5YGF!CL( zI3bq$*0tmM4`TWo=&pRAS-xI0cIOnX3m*~~cd=ZYCckKhzx`;hT0DU+>^R3( z2j!3S=3qjL+BtE(=#ap;i$!FAf6;x<|wW9SFF5+rgAc0xs>=*9q6y?}}VYF!sPoRsh4pVJiEp!W)+FIn5TBw){<}vysqV(RH36jxAw=TMWn9lJT;~60FFRcjW#QUhx%;wW))VF zdY}B%{Zs4+DoDKUkt(#)=hoh66G$41erj=xB^-gSkT+3+uH@fr^`AYXh_{Qkdf{~x zK?R9dZ&HK``rO*6jsav#$Q*U(^nDzGt{#V@gpc}cbvq@3{HfxhzBD{eP(ebBP7yBY zb8Eet`;(gcW~c=Q7dZl5UB*TUoAuf12MWWTfx$o6Y|eB(^nA5u)|EwevmZ zl6ya=sOwDMaRj;?-bM-s^x5hyXSOAGO@q~f>W{>$*}VkAl1QcH$ge`TZT5nNOQhoR z>Z=faqn9v$YlO0@u`#=@?E49%^0grK=#noYDoAkGo33T7C0Rc*NZr@H0YL&?Hb;61 zXZ0s16P^zzVQT}`o4?xw*?Y~NnORsG4yLw|=5>z4D? zp01M#DoEfJ%1%LS>`ID?=Bd`xmU9HUo^q4gJd{xulF&u%eq-$1!r~c&R=fC|)hmUjA{B|b^DoEfJ$|_SlH6=6Zd#FZfmpB4l z;ghX|Ed9yJ!bAN?=k7Dq->+^FRFJ?cl%0xqH6@*wO;bw`eBcOl4Y}P@DAu2xytKR@ z>9T&Z8vOJ(K?Mo^+FjA0GjU8Gr}m7jDItNbGktmr?etYVDvwDQN6%cMx`#Xw4^K_E z-9BoCvf%C)VX9S4VM}I|ve&Cr2xR~N&x1&%cBFQ-8$Eq3I(RQu4>$cGqJjio(`=5@ z{f4-*Fjy__(U>5CuE9OiZBOZ|cs#sbCf<%*q`I8yNKion?*ev4(VVT>?g~=RDACMRdcge9D%O;^HXiB=&N|7wf-i48$Ce1 zvd2V11&KE=dI&f4)q1W;m&7|aMAi1MDMz5IV(U~}Gkq10HiLhN=dSlrXHDrUp@M|L zh91IYebpgriz{Nf+(T`(p(jV6>-Xgp+pGF29+fWs5>L;xP$P4DOQ<06(wdE-ub$*P z@tRouS|_zuHsJ_#CHkb;zR_3lxVH4K=-IBF+UapW2^Az(6=rWU& zZExtSc)Z(ZKr#>3P}7^(OQ<06)XY-&t*^@UrEjkIyQqSi&bn-y?qxz4vmYlrvr$}m@sK-b6G$+p4zDjp99R3wYo+Ne=$ zHwhIa!j^Rx?DSRA4h_l^+wZ+a>*Toe1i0GJB-^q2DjxTyRU$6sm+7qGo)Rkfx(Cg> z3*q`|Z=dexi#=|p(@}H0IRafqeo3~@`YIlmhgT+Zolerbkve|da6y|8xkbY73Etj80s^AH$1#e zmJFMvcIsK1pn}AsRTaex`WzP9$(P8EGyK%%kfqP~t#6-8Dz2QNuB_Uh zpn^n!OGWX$K8NMt=L^KQ(oD6Pr58t_Yh?CAp-i9gTlg-Ugm}5CVL?j>DoBKzRus?Z zb6CDTI8U1FXHU*cTR8$RKdJ&}aOv7;v2&deK`Q z^t`Tw3KAbu48_*^9F~d$&XX0xd#Y33H{l3$rT@GyWau+~yEnT*t_7K^s@d1G~< zpEXCI>uY?Wkgw199h7;K)Ok=-t-snvLInxmcmr{lK8L0HpiAVRFF75+dxd#=dgI6yG%ZZeWhW2hH(VC_GaG`&gnCLFC4l} zHXFaBPXdNZs2~y1(LglU=dc{MxJo)~xliw~uB%9(>xs)fp^ZM{cS4OkvbV(zdgtd@ z2^AzFp6kR#`W%)D(bveno#$!u0TX!wT&=#{6;A0he(SsDlX2rxXwcG$5-Rw*V-D*? z^Z(_rPODy?CZU4FG&7ypL7&5te(wfpzsHLn%9+j) z=xTMdK*-c*{2q$FM-Dt5PtP24l~6(A@vCydNuR@#wm+Mg6^L}ew3!@%u1^aKgckaY z-)f@^$*aZf>GFIx2^AztLdt~^`W%*rKZ3!9jnv&-!^G@%UM) zB)QF$P(i|@Ww{WpKX=zRK8HMG87XcoBLxX`O@5Fs#OhB2KAd!)6dE2<{5)n!s35WD zVwvEiKd;uU?oDzaWt8%LttUsIYmsBVK>vICkmcfBxlh*S9F*-lxl5=ZG0C({*!F9N zP}%7}IomyNl9MmD3(fC%as;|8zUK+P`hG>*p5G_Gj$4TyuVzW8Akih^uONO;6y9cN z=k8Xp_i^UHe$l0dCr6;GMtq*&sPDV9|K@#?J>j|-b#11E3KEwl{uQq3yANHsl|#lB zRU|3f+&KbWW0vO$)%E?Ow(h-8bYB{h)*WX^s2~y8`mgX?-+gFvR1T?E&62D>Ka(TS zb=ogaDAD)9>g02uv{d>M<37_RRFL>k$;K~u`3XaJW_UrqSU5;g+)qB># z#dw;83KBC1{}uk%eQ0@B4q05Xl62bW%n|6?|1?jS$U3L3WS!I4u4R`ZQr~_p$*bik zp@KxoroX~kefJ^fH;>6Qml&gB8Wxy>k@@8$&UR{rd*{_hj~OjL2DixKZy} z_j*^=<4qQ)AaOFeu~_NsOvU3yP4-t=cYQ}18oR3Lqf0pgT^NzGn#+0L$iu5nYGha? zf(jCu(TzpdRj$h7xn0;8FIT)KP3}9ZpKVMz0$mu9>vW^qmJ*Ngj%wG6y$LEv40mcQ zwxv@Q*IUEb7*$GMkVn2wYV9_z9Dy#3$aT6?+dh-Lg_BkJ_*{Yt5_ZiSi?b`+E9n>9 z*%*h?o{=d@F;)M?8imlOJHb#xvPe}9@QH_Z*kdQzZM&zs} z$KCg2W@~FTtZzjL6(kPEH5A*}w^w?(Yqbprv26R1K31yn%9OfPncd9Pf`CRGfi8^5S@uqik0d0&y?UT&QwbF$ zHnnIdde5q>tnQh}#%LDwjEsNVMr~?r!V&1gh@4&RUp|ss=FL>&W$h$XkT{atKzuo_ zvT|)}8XIHV`sd{Bm4<3SOEZo@7e?ePk4*QOY>uz3(n01DDoEsnH4q0j`YMmvs-01E zzxaZr6;)TAmRfNHx-cSVD-#_`$k_!I)X-tQB~*|o>e)baB1LjlGwqCGv)ZpnXyzYU z#M;*&fi8^5Ss#;`Ux@Yb_w>SeNkRpQBhTxL7JV}1uJ&3T`a`o{6U&}Y>9Ej29Dy#3 z$k|!s6Q#uJ-EA5)d9Z{E64kcV7w2_}l}Fdqs^g!fZ^(ynS844kBRK+H7?HEzt9M^X z?G|TgZwE#|bdSWHVfDpp)~n@4c3KX7)9UX?*q#L1Cwv@7pbH~%b`G-BcaoX1pB@-B zPC^BVlrm$nM>Qwey0ex;UuVF3vdUvC-Bx)bN1zKMa(1$K%nwrKbrj7XJ3&GPiP5Kw zMKZ%ge!oep4pYPN0|~toOb;EJ%n|6qh@91?a{5U^Yr9aF00#*bB+Ta;ixb0dWbEFQ z%f`rX_(--q8cDzSIC2EKFd}Cs*6n_gud6KSvYaUrDoC8RFcurQn`RiBYkB(XdVV6q zy0xYkmrdgcbYVo!&Uu;sCVRcBP!i%Op@PK7l6vB?zng6adT8f4KfV1#9zA%gM3p*o z1iCOHXXm3H|0YK-DN6QkCkYiKx}B*fT9@s!-7!Qv3t$xXnZ&Scswpg+3JG*!M6T1# zS@MVc^Vv;l-glaW3KBcQ>xqW?3L7JvmXNfmALM)ft{j0bjL6w9gY{n`xrX<75Hd|d z1&JM|^~C6n;lj_~+WW}gP(tD(YKu_=U3mgr7?JCApHu%5;aq??H_u5z1z-2|^jtQtv|GU8gJC8?G;MM4FMTWjlz!w0t%H-~HISOW4($oJS@ zq+W_6N1zKMa#kRAWEq(L8(l#GK`I#jyc`SgV8fTe9a<2`M(1LaH2{!V&1g zh@5qI+)_rGZl6K+9hfMgg2d7lb;VqVDdI~Dtqy(1fnP{9mZ`salLJSf3nOw?kIcB7 z_*@SmsnM(g4a@xlsdr^J8kwMvEOUsRChWgjGsR*&Eba7CUp z7JWC}5}z$P$cRcCj3hCBFPS}Pkc0}p?x&2l;*`MC;zA>>e#t4RzBIyM4{7h(k0a3a z%B-C@?B#j!Y;A4E@-fnu&h|e-j9K^7s=1+Z%XRC;7_S@=@8B+G-DJ3S-&Cekcf=9- zkdK545_mVW6QF|&l}+sauwnNH66ngxP0BFP-%&d*PgVA^d$23J2T?%+?@iX%lGUS0 z_s$?K+wcUs>J$%5X>9je+;d;6-r9xjXZ=f{f&|{ptn*2cv*~$7OX2fDoEhn%$}SFYY^YEGi2E3IUIqm?JF&X((Kpbx|7;< z)#zM5Vij|mMC5o%s33uNGpn-cGmU&-o=$RoJU9Yf`?^I4k38Op3%+Y-s(&S|B!{-A zk$d7y2^A#pZf5sj)9u7GH-(%W?Zy%48rd(A?L)j36$`CeXr;m=66cXbV(L0es33uN zGdnri^&GkOG@ex4!YYNpYoV*$yiiy;?w#m6S-aX-S``xaiYG{p^&|-uBwkt>i2HZG z7MmIGXT+(JCuGO*qon(s2^@j0fkq|5Dx>$JnNF)yw6XdIvaRWQaxZ1JG%Y7iSo|YY zJb3k{NOyz^XT~iTgS_sDuXe@>ivrw5Pd_apbF3atR)1PeG6io56(qX(hYGD;xrxsz zX=g@f6|E6M9y)Ia+ z)w-*Mnrtj)zFu%%H!F9FvSG5R;AP-#q#Ulv|Bvg<{hzS*}BGw2m z4!>Z;?adoW@#WpZC}BQFplff}lfvTv)@x+XsDcR6CHqT8zea%)DoB()3>7|SHx|5N zwK0C(+DK++Iw*0)tl|m07P_WwJ}J!A*MYoX5J^&kPblBpEs#(_qOePt@TA)RuPDhn zrk~zO0xNt~YB|i~2z1@cIVnun*Rw1uiXcrk8qp`A0TL=mOmzqo?*6xrCY$3d-AFPT zbfgv1=W+zPmez?EzUk|7KH3vOmih}++3qi)f`qanObFC>+q7%Bk)-^XK$p$)g$Wz*hG+kjb7AM=O>|p#7#L&NY!`SblkjwJX{b)(*nIX0$u&~#|yLdby9;) zu=``cI@&$fOF{*Ssik2;SADn5K=xbGLS=Q&l07&AT`?cxg^T)nuYo0DhyyO)!M3KEmz!i6#VZkrD0*Aij) zTe`HG14p21`}+jpo4$^4^=HdSwYT4CS=dAg6(qjA4;S9CZkxh?x^4bgw1&JnVW?g_ zFqR|Gl{+|5sId0mddN@gLx}bBs_Koz(Gn_1Twu@h%KC1bOWLm{o1JQ_XQvG12y~s^ zpD2vc*LA*eWijdP)P{mTkz*6vsG+ffgbETC=@CLFeYee1t5%TO%{!_MBdj7vM^G3t?yPK zZ;Bwf2M4PDNewsxUA0Ff3wHYY?f)eDli5Fpszzb;Bvg>FPl*)n=({cqEDI;2HjPvd zU#rd$=z6>*S?H**L;v#+tN9scNvr)6Bw9lWaw3I z5yMTi`07e&o)~iJ|8;flaXsGeAHUm=(j22Ta)_MfR7OR*@9VZiIj2%2E2oW;PELi; zTG-5?P)$y$p@gl^l<9N7jplsHArW7UnPEnl)0W@$`8|BM*ZcQhkH__TcK^|*`}2NZ zuj>#%og8EWRnh*ty?*_ozh>XVGBx|}sdcG$Tm+q2Hb=(@66L~0-S6V9`EI|?#MqRJ z+9H=kI(}`oM4-w&mY;DxT+`cIPRQ;0)TR1EQz#-}mW~l5rd@YYQ^O``(V5ju%;g)x z(ZkE>5yxJju9lr+PkVT&Wp5M8_SfN zK#@wZUyT+!++Gs)!Qp=@b_{VYV_zKkF7X#h`8GO6kih?Wo?#m3P3v7oh=K!+B?490 z5yAQ0o8I&d?_)X7`&cl71ip!Qeo1^c%8T?7dl$5k2vlK51m8cp`%nkZ{=)rqI~^lP z;2V`^G@k5ERV}^5^C4X%0#(=%!5PTo11WX2hsa3ju44oV{AN%T??@Lqey^uEQqfx? zP=y^4>;mlYrINbc#l|}xI!2JdZ#X90dXn{(jw1YpCK0H@jtD+e?;TA4$!#kyJAb}?i?xVMJqf1*Git1Q@ zi9i*0MDR`|>k+i>g^frq4$v`z1fHC@PUf*YH7Zj?tFOjL1gfwjg7?we`&0K{pBd#d zLUoKFfhRzoPFdWCrnLFhXz)|GM4$>gA{52tuTf;ouQn#?6LgFqfhSphw-559*`M*O zyQZH=1gfwjLQzul18Mf{1IG7U-G&h)@I=mY?y~yPvwPnfVRNG-0#(=%!FNvE(d4@9 z8{{h`H$CoGYot+g8fvJKyu}r|Hc*A98va&W z8bX__`xy7@&(<-51m0M=)?l(mS?{+pt}UA@5vamb4d=)zLuizht?}dSIXXs=z?(N` zSiaIoX~!EkCnZS)s_;}}nJ*ebcQ>Y*>wcH0V+0AzAaEwtO{3c1)5^YFF;5~;g{K<+ zdrS(UB;Lo6?46`z1PRQ9D9XkZl?MJ2tTp$UClRQ^Q;nk7tqrEqqHL`uBT>f)5}489 z$@ROu$UF8It%Y@xM4$>!HHuQWeKg$)vZk?)b9Ia$fte|;ld0-QjvscWR_-!^Dm>M2 zJ;RwG3R~NUJiE=-F@gkU*f?9;rysc(fi&DvCQyZ^8t!E6A4Dl`6KI1C=g8n3g#=~_ zxti*ZCk+{vNJs7_NCc|zRHG>KZGuSjN}=bMc)KH5r#C_-P$i$1 z&i4+Y!*^HF&iyeuMv%bFEq~+8Y@j!9kws4$`{_%*an`P%-l$zo|4u_6C$dpft)y4B zHYU?jxAf$kmA)@%Bkimiu44oVbecF%z3xw%);Wj91O>J%Un)} zkn1$)TrQO)hv*o=-;0hJZBQbdp*V>^Rk~?Q@vt>3v;i)bdY`p5m1P&+5*R@O z9e&li@-{Yb9sTT$0Iaxa@E zT#J(kRNb?8EsOoOHQ z;t8>tsm5dL98$MN>KH*{ck`mM?f-n*Gd^Bz{P8rCo=%-65vW>rW@p)gx2_Y<#qlgO zItPDEb=FPRF@l7dD$ADq^Iv;oYl%U_*3og^D}w~8_H*A-2v?FX{l7|b`^#sI(D$zG_4`uA%0~LL~xKZ!-QaTk%ird1vO5uKj6O z!k_j}yqk!g>z31&S-uj1swqy+W*1ta{ZVD9vS>Rdn|k~dFRThGwddZQ$#&7G`X ztF`=d<=dZe0ug_%!t$xk*RkTSqnz1*Nkd3r7cK8l7@bEIFJi=jS?>}OsKR+d?0Hr1 zrZG{`;;Rks6Go80zFXe!?3zpW`_2$i4ONLi70wglO&e>AsL7{MqC9OVVFU^6yX8KX zrkknVkSI~HdX_|>3g-#&-5|Pdp zmM7hQkwa~}1d9*L?@9!!Fh9dpFR|MxUiB9)>z@%ukiaflMQL1=LqDet6-}F2>qwvq zGsS#vFWgRc&3r|?gRPViMgse8`TwKu2J$&EKotGeL?Tdy8E@V>lL&j&QzB4>P6}^oTDFsheAiYS z-r8GoOpw67Tb`!7bPK)qZ7JL<`bh+;(BI*^!Tlnd_`qJ6dufvMg9P^7^47PUxmmC?bJfrA}6;^ogd$&$0{bhUByeKhRs^mZd`)+w-$iqVFG<&&u zS8}XGpbG0wxC*I%DFw7{X|~zMTSK8D1qtlCw~EqiSs|r0|5Cf25i1d>!pb2$`qfql2!E3>_TelG7pBYBbz{w`Eu zB^T%V-YKDugETrkE>f!TLIV44`Rp^cfd2kIn1+Q%Nd&5}BF(bRV=uMqGKmKGO_eIo zkifoMMHxS+fR=hBQt$rLBmz}fS*Iv_uI{C%wTo#zXALld1oqwXH%?pu9cc3<9phX$ z5~#v@KYo|Eme8q(E2xFjWT_Gm3GBO7l+&Kss(pB}2#dX?J$~`PwCdzibM~kw>XfWB zub7ObW}6jH)X&lfo2Cz4VlFALOy4W7?5z#Hut3->c%@+k37oOVy)sFs)q`~xh+C^$ z5E7_*FviDp*GM&&ukX#z@OUyz^K_ms9{tdTFoFb5y36l;!#6Go80seD{RKlZ5VFkp_Ttd}YgsB-?r(=^F0$=qX7 zJU?U9qe0q^HM7LE=oN$!BycJpyBW)WQXl%piwnQxNd&6S6}Xv}439C7iCxOixH->9 z`(5Gbt?_#ZBS_#>KHj4ke@GqYA0o7%$H4tR;*ffiw2_ zK3IKF&2}3tT+$orNT5o4*};_M-QR5b*0M!u%cTL@&;R2uPVKeVF@gk6}+_ppF25Js3eZ=Jk?RAVGfm8YTcISCmomx*9BSv(U z2vk*+Ihj)2yO~@4Y49`Zx%g^3zw{C%r+VlZK?0}p@zjX+M^)Y0UHtv4n?#^$WSiC| z{~{;zna!4NjvqY+YrQ-_6!k{-)iHtuPUYhbc|(q?Keg*BtXy@8KvmX4M^pa7W@i5y zOLvXk%%R%JcRPvuGrV<-Ac0f)_|CcEqNZ^b;{x*oHP;U>bE23wGN(8DLbDNs9$CYL4vMeR9 z84`i2w1e-OQfwELRi{`gYc|z}X!}}xYeZDU=omo)r}A-c_?{}YsCJWa`@IB-K$Sc% zyouLXZS8?|hX0_MI!2JdseFpkwfwT0_~vut(CgU}fhwF;t|)HpLbU>`B;(qRInoq! zBycJppGEVpsE4eF7J?8#@i| z)#||yu9#C3k|hFFBVRu&HubFa>N)csKciQ@aoTf-P3HU6$vQ@mz^XU)qt0GY=ewUN z%R9eNB2eWw>wfWuK8w`A?UrXej0n{hg>~rTykh>KyM56r43*B2X1@?L@K7q_*0t)|Ps> z|8xk^7H)K-6`SYj7(oK7-neTkzfv7MB!FCJCP@UUssn#4j;YnPM!PNlgBc$OYfi7i zsc~GQju9lV>P=A&+gGZ;J0wzU-?C#7BBS=*Vb&aRJX;v8m+w?l|paa=I9tf z0&Cbf*LUxt`r`5`8jvtcB2a~n5WnGUgSAW9YbkQ}Ovx)k0;}G*D`i=*c7b!e$^Xw? zLKS*p+{t?7qPETXYkIMbXMci!h6FmliqdpjT?#$3few1fE*YxOq2o{c@P1U9noaG@ zF_L$OgzO^gmx8Fnvm9!FB3dF)g-)ZQydIxQT1pmm)@9cc3HioSl)9RF=dGuxBU2^U z5>@E2@-&j)3n;aICYAJ@B6+Du$akCvRV6g)R5mU0m?#mbLa&%BITFuO1G}|!eB*e@ z6Gj4ilsVT|{~E1~$fR4HLnQ)L=y@xOt@$ZMEJ&x+tRTtTMndj)c1Tq87Cvie(Kr4Q zfhzRwxxOT#zCMNBr8IVzFoMJ^Z)Yv+Ub;57vBh1Qez=KVwRkl-_8ue=s2aD@S^K+T Lj&>ran2G-d_<$do diff --git a/data/kuka_iiwa/meshes/link_5.stl b/data/kuka_iiwa/meshes/link_5.stl index 82a9337a60d2466b32262f01e2dbbf8ef69ce4d6..663ece5cd7e3683a97af1253e96d22fe5dc86570 100644 GIT binary patch literal 67984 zcmb51XINA_7pQ}cVgp4)Y*;8_LqOW>?2LedD2g2v1rZShrHB-1qlgOV5iHmhJBkGh z2+S^H2Yaums7JAjid~O4!@bYCqx{@T+GH^~YX?Jg8@ z{SJ4)l3tj2<9s1Eu&NhcwhRuYxk0yk2&+!4QB;PV=cdrV=S;sOH2v|?#hLz%(7U|zB{8|19kc|L zK%%5+ESLRiCl}Q~JZ{|k=>5-Jsg{VFeu+!{@v@x%SGq3`9pz3h9m<6?5D`L3>GXD6 z9ks-b6Km9G!p;lYTtT|ZsGJ+y%uWbzAb#1ca+oEX4bXxw_~67J2L3)Z7$zjIG#*B=Fe!sbm167M~2%5a*H+-NbC1c z6;J{RI1(Y`&v%gH4Sfjyus{uS0%L^+drXdkOa47{#5qxl?FE`~W|ZA|zvSrT6)5ph(J0!knO?IGmcwY&8CcnaB* zZ7pzHPNT{5Qwh_8s9?q*3N#x`^U9R~1EUxSA#aQ)dGIwdkGEQ2%2tVK5 zhKoKL$|1`ocy>V(TJjr4Djr=(AX7_A7%fQeE!)D)8=i?P=kk>B9hkuz#U_xX#<$dC zT%)55> zk7}(N=g4RQ8llsNHGJbv5hU!#cRaGmEAG^e6g*;7=ue5*vS$`0!Y=5L(6|8du8#?Zk{v=V=h`V1 zk9}D6FB^VeTa)t##*kHsM_uzmtniNfDHwg6I}q9n>uH4*Yo_2e4I@MQ1rm?e&m#3_ z9R-*!v?t9!$UU)Lh)dsU>&kcJAwJk5TGsdMD!A3|*DaMGVlvHIRJ zZlA+LuEUsgvCnHQVem47pU@&n?sv6RsF@tZp~xkovSK}#a@3LA6_+KRc^<{k2!+O} z_@amL^3w8sB1{(&aC}7Q$)H5O^O!{0xp@wg7R({EjZnp%C*lj!d2+K_R~}0EUm8W9 z?b)L0yB?E6gdC6d=G*(F$aiDYI7s{!3%E1SGsTv)2OmA9QEZrV7@>e?E&1}r zsq)58DHSkXNV7!Jug;Rk`xN=m+fA;|F3l7UJzgv(P9MtcGhHCWPG2m#8tZbt&d1bF z`?JOM{|u$I`}BAlX|8*!oV=h~fD(q-wLnc?XN#AHHKjz8Hc66Yk3>24l`)1kT72Fh zWUbB=gZ}Ez*h9$YORRKYSE6h&bSVdk`1%4N%05#>A4YSKM#v_3zBKwkg6#T_p}=>K z7Ut9~7T3_e?d-f&$WmsC*XZ9cC4^p^&Xvypl_=*J+Nq%g63`w(3r21f#=Jy)7uoAwJ$mGbg>HnFd}(HYc&s2@?&sWJ4YeQ* z>kuJ1$5z}VrOU&&5GGxy<;&ErGDnhP*36PQZm^KO{D(01e4?24&k|0xs#pkVx=>X8 zQ^}#LZv~|~SwzoH(p)9-ZRHuEqvSipitBi+o!Ij3OmWd9eeOm@JF#TpOmWbGDDH=g zm3U*x6tPEuJ|z|(Z!LegHb!m}AEt&9NIb5$5Zm7f6gOCDJu%X&sod$WiL&GVw%ojs zcB0vanPM~i7YDT!#y3~ zEWEBhgUcPeg+nh?_6U{aab(8nK4i;N2N6mj0q64wHELYLceM;9Q}^UEtF1E$m5MU! zvmDym*&e2ZkoB5tyf`eJBz;}YK?zJ3uEG#1lHBpOIqBr=XGaVrfw$JEbA!%v=>8Ks zXb+(dpFPC>ap~k+je`iaAkD6$e5PNMipPhOZdGdpxL#6zj1g9R+R32@J?&vi2suh zTy+zn7Np@y523lS;WGdB3coAe9zz0Zg^xNX94p$TK*hSW%`5LE$SaQ}@IHMqL@0p- zyH+cBpCq#(j2K%{Xr2*AOY8H2zh-T zB`3cyls{14g#^^1-Xo~SZV@y+XV7vS&Ew>mr~Am$A2;~!eqKg!agEf{GE{zC zn9r;;sV}Li?+X9VcmI!O@ZJANV7hR{icpg5E>ho>Z`M0vC>eBX zjbc^Mc>%Tjr1jnZ*h6URXAj&rE?vI;#6g5wkY-n@FQ;GQmyZvZtJMv@`=7O}_s1A6 z>eEgET{EzUDIwIV`Vn8!KU5z2Yc&TYFkR|n|49jKrE)?NX!S z7PQSD-%B7vN)x1uHW?z6K!V)^*!Dh+bgJ;fhpF#E0&2mrlJ>zp3FP&qIs6LhyHElN zI6flutL}(n*Un=a_AlI|n4rDbwzk zz%lVnbGmPa4~TaRz6piz>#Q@ouOD~5`|G! zG2Mv?%-rcXZL>uK0eck83Ctn&lB0i|GT#|FYWGW^m(=h5!dibv2ZWPpl^ns5{aG=L%0rk90y~N@6(_;x5C+C0HF09eE8RPH*5BV)%@L7bzY;mn zTdeOsNJPKh(DG^=i%JjMsTyp+c82ZGe$_Hs4ll`WKB!^G3$_&Wu_Ev-K`8Ec#<9z) z#0I~D5=hiXj1z6c2V%5o7xj|Yt3=2Bw^AE?7miD?9PGHO>u}epcIv5yT*0=5o)I;u zR{ic)wup>NXvr657#v&acCW#&V2^@r@N`i!PWkeIL&XaZBQ)cEg=1W8Zo{4>Bw$@Z z8ljzBL1|)B;|9OFF=h#_ITp^LI{zaXNjdoI<>AiAAm#{6iLMO>jwk9%{%5o-^VseaeHy$SN+1D847zi-V3lL}-)kC123RMsZP-58D{yVOC(d!! zwjh*1qRrh!T)ov|j0*jz|D|W6vd?FKHS`ZiKrPt+5gKW5*vZCpZ$rspuZ2Aowk$$h zuI4$tw5mR)%@veD0=7Rwg(qwVmiC+0Fp9#Kf-ML~JA{@u3q1CzOS^^^ge?VI@b0}` z!tA>XMWi&OCExtGgY(0MMh)eF1k{4#3PP6)%ba#*{9gjLIc!b%EkUTD*N#%vHQR>T zg}oMzAF%%;WHPyiPrEu@&X-;A@5>!=-yfl3c5ht_cR%3%HQf;oHzyrhJIlJC*D?F; zkYIO;+TF4w<7x)U}igtC|RCjA@n^6E`r6p(;gFrI+W zp<)YS(bioK?Oen`39Kua65Xv$uH`)}L*xxDOfcMaf;GzS&=0U{OUeUA$)C(l2v7nE zXb+(w4*KNp@e|~;=_^G@KrNVCglg@LNIi`xdac(JVg0~1fVDtZkYhW_*|pvzSdoC? zetWL3QoMf93y0Iz+!m@QE>E3<5750VgiKr5$*Gl2gzWvy!MFkJA3X{ui5JRxVbMuT zoP0!N>xf?D&C*2zB%l_whft>$7V?)Ocd}!-17ibf!Q3MB)3~v`;Kn2}y!BoI<`?e0 z!>9v|s}(kv3+Im~?W%Ja0&1}~z6KOasx47u=fRcuwDESK{8k2TW2=i{6ad;r$aT|U z>APPPY1MxrQ;U#bV-rq0Zb;1@g^{K~_Y^QKs0GV}(30d2(ztz7iRayY92}QmT!kf! ze^g0t_s%3`h8ZH1z;7Q+iS9bj?je_1c#!w~^F`Q#Pz$y{Lj5(S^3d5nWK{hcCb|S; zH;|@YLL=3G%f94V=gCYtAOXun_kC)5O4qlg5MP}s0?a#%X22*1or`uflUjaHAuq<% zF$C0tGXsRm*Hx(}*QFEJqeUFlf>9EdSY*9ax@R6wJ}2B^;wmtQY~-ggjTL>Nu_BKx z#!L(f60n^R+GkcIm3zhz@52)mPy)S#jr^Qy?k4#kpGU~*9L8UvAHx_D-TnBwK{|PP z4yj!|l7kXRz*<0Pa^2tD_h;#3aMdiu!Iv)-UaD-|h>joddk*6*bTzTH0zY`0MxKnn zr-l+3p@AvU-NC~Lg{%|lMAOC$LkT3lEvRT`mUoWSSsz=3YSPmHff{`t{t}PzU$6TF9 z40CLmXc&yX!ITi{>|w_5ZktN-b%GchkYIE5WA+k0REQ^Pm!Aq4gM!gMHm><q*Us zc^)yXZO*jE?&b%$f@KTwAlm-0ObC^=&*T^PP9R^q#|cmZ2{yXaW2cQUPLJIkDbC>|@1lARtWg_(V+HigS=UB-mVq4_(5G zC*sN6m)jMv4?JGh8YQb8dr;rXD=l}T{N!q4;R6q$NV2qWn zQWIYB$ie?S68 zNfGLLw2rrbHI{$ef9qfv*<{xULoFDIg?)wYm&}*=t?OoyCl84L zC6ItQq`L-Z8)38Jboqy)nF#k5U_278MG$J)#Tu(C)8$Ur3S43Q3`Q!yS(jDx_sJ1= zHh5ye(zn8~C+YH`4{z0wfLbudhETrGC_Hg*y4<*6K?O_~(lCbz>0i>ve@>;#U5;KC zpac>yrbkDHK27o3ed+Rnx1B{Ofu)5hA*67>jN2bblMS=)D4+z^8;n6Cx4(V z#iUR<`^OFilt2Qm6A((>w1QW3m@A(?U?Rfx8H`lJSUN)8T@UdO45H=di~bQH0kxoQ zgucD$EY-eFkr&%J2r$A6W2whJD1@CJS>pQ!zv?h7Tl_tZ#%nF7Gf{8oODyrAX_Xjq zGEI*At*d}q&=XnWe9~&vZh5?X-)4;~lt6-whL38Q zClxK2D@X43Qa}P~v9ayPTOFm>e<#ZifBC2(0kt+(ZWR^{%M|Z4)YW>cTs&@ay8LR% zuL`IIgVRh%H_-(IPP5=g+C=+kgIpzx@?=@+ z`CJVpkbu5`&>U}D@e_@>Z|u%-usvW8W+U#$-y2Co+NR1*f4ndxpcZT!gmSN+mbQ0_ zl%p2EQo!gmjL|dkVH7apmo)eI6#19iN(GEH!^m;;uxG-#PpRVBUfPxL=yf{s3o$?* z=McukouL+tzSDi5br$jz7k3%IzEuGwuLrq_vDZ9BXWGs%+K*68+7U^oEK2VGMJ2#= zVXk01(Ve1jS!x+EOI8H(ObbE+)&e~(61hwA>kunHD>EvGX+bUMp>$U*r>}HrXo}qP zVq*?UAOUL~A!Bq(N{oz@SIv_JNI)%i$16YXl(c4ir2Oji5dlgd0Z%GW-<|(a>g6z1 zcJJL6Ljr2S(-#P-&o!5O(6a{h`+75H4dD3#mS|k`QQ96bRc@KQU4W+(pcb@8zqMRj z`D5@XIniOB0NWPk5Yh;3*QCiEH=h-~NgM}v8Yjn%Q&|N8{gh0%6@xh z^X}`036OwVFnWSe-yU=1L-qxH<~hX4pXQ5gdYn%yAi9ymPBXt4i0KTT7TS3oVlt!UeqwQ7Y>*}T5d2P z8Ad7rO5koSOo_%I`-YNxpC9pIYm+&s1?eRZ7GS(c;W?#=D|-d_C#s0Hn@L}hv!IcZ#tH+^&$pbZ%Lfho~g(U)}6 zr`EoFHuW^91!?4yjXzy85quiTvF=(Lxv4lQI;zbCD1i|rm=cZSWW6+F@}!2-8;%%+YOUH_Kgvt1QKv0 zqF=Q(-f~{2&hmuKIULl2_D&VWiVv6Ri`tQho?%%wTAs1mNFM#uMSujw zoYX)#Wtx>R5=hirt4%2#>Jm?FoQx=FAQGBfEk&zW3j4L?ST>tiZBPsI>EE_CGkC)T zr-cmq_rmStD6#d?^ai4I$?c(C^7buZ$qRHr>q~y zlmnLbX*9Q-=Bl8Y)*(7IqhEs!lfBhPVZC3QaDlr`wRB`ZUbXo&cSTDaokofJzlJy1 z7!{u+=*0Toh7h8}J!Z{?&rcH`^1> ze|(6Ve=MLo18~^8@fd9xj*aKK`CME1$Z21qcDEE^)XKJ#m1w(qGDZtMFiZ)d%(3Gu934#X z^XusZ<`?eivisDY2BoeCOr5!lKUo6S52O+De7{nWxA!O)@;;qF2_)bS5Qw%!Sy-Z52Cwj zHY+QZt&1-I@-G5v!Tkq>+L%S+bUhvZ?BY}cO9<`3-8TAFOLyarw#(uiKBf~WfdrhL z(fIl11&Xy3gA`^oS5N{8IM+hxOhFSx#Jo(`Ta)afYu?w%(c*orB0P6;T1 z1oR%d{@A=m7+i9OOMRS9V4M^76}Epov=-Dk`)6}szOn?=V*B6-A0u`B6hm$pz4rrq z4%C7@jh=|t>~) zK4N;3E`~&R#R6>j;(~Byv6fh;d(73UqO!D(5-=@DtUBEYx1X3Grul0LKyF5J4>NBq9vAG+ETIXMGv(^Z9oYmqRKMy zz!N*TLCds6cxJvLxa)bY*Xwi{YQa{6UkSROc&>xm`I1I`kmd>!@T>OABLLrB*Bk3* zYi&$E*FteHZMe%lnkz^^t)CqeaHm;~@tJ%r5u%@^7(Jqg!sTBC)MCp~(K(R&YE{66 zyrnzO;F}6_1#Q#1nm(H}pR|j2`))0%rgXxNYUdoY@5!7DrV!dKq! z#>!p&=-g*nR2=!TWToVGbd?ARs1>2p15ZA*4bS`2lM-1r$z-f&H%a%!Gtqg4HU2Sd zC$1aYpNCqIrqNd;HxgoHNk)Y&5DOkU;a|b~v2uqe|L~p?OT&xs-|__BcE@0>3NOS# zo)f4Iqptp>@6RUWp3_ZHGtU*5ZrY1g&4=)iW(m{NNyI7i1^#BPlwMqR!KO3*&Ude#?oBFYdt%)%%n*!L%@E-!wQ*(K9BRY5 zkqL1sHxP5&N6H9Fz*+>s`868Tdnum~(wQ?G7|#+=3(oq{(+gSr{pAsyu;^a|)N1sm zBB3A=I}g*Yif*V^i1R0S3wfi{WdtRVfNLsr&GwpTJHeZKQIN(GQ0rTb;xn~zC5W!u zkY)F)QlGQlLWf=9GJ+CFfb}Orc6sll?p|H++F`*g0k!;=aI?22;^Gd`)Q0b;0di;c z2vM=xNk&it2zE8G`tC@1^Lroc^|vuYKrPKuHCIh-DCydeMqe#L_)4-;9)VH*^uZPCCv*2_)c(3?Z{&q4KxxL%ENO z9x(*eQpNA$N~w)24J+ZVRZep9)?vb~zIFskAc4Tz5TW5#cCyu?p`6DRCx&3OB11VJ zZCz>iAJDJh>rz#tNI}s(oFFKH>B5yadYW)ta$Kh2R(^Ju;=h#mH=AH=}UwnI{NtWL#d6{-v*G3pb?^8o)cjtfME6p(79M| z^87|U_bj~=LqIK$X@`Vq)P~~GNNOVMiwpskow|eqLD<6VF=5qxBsW>`jG2MY`#+|uIJv?9u zz5RcZD|Si3=B1gG5PQ3mh|lGsN3)&;;l4P)A_=Pw&g0RocG&!I8b)vEdjWgsIIxHM z?jia&l4n|zc2x$_%Uzf-T5;dGIK3nsv?}9Y#HY6hu~WoJq1jJ5?pikG22>_dVw&Dt}q+{m;^xx4xDRcR5N$bQG=M!W`qFKNxkELVtMK(N>5{h*m zL|)x0R8+mSlF=ArYtmIL*8Lm99?g z8Yv@~uGLc8*y|mZm3VM=sQ=9V3qe?lp>DYs?X1JZ1+cKJ^so@+9s==wX7 zbF~-#U7U#TOdHO_blF_3y&plO)n?qzMrS1`xf0-on`mfX=`oy#Dbbnb-2}39YBPMQ zdzu8b(z^L#uNEp?Q9kBhgz@f1r0U2XNx$bXwsv8SGG6k!Nxh=-fWAEM$^?Syf2h4r zC*miwXupGf@XF`1Uk_98{WALR$aBLi;`I2Sd>$EB2&!gVu_}$yC}~Jj z+3SWsiPz1=xt*=VMPmBbS` zxF{a|*w3MM64n{K=GC9=z&mTil}CQH;W7Ff|Qn8fj?rl%I4fnD9*v7=qEtprg|3QjCfw z(_Fnb{>=X}@FTVQi9CAP9BXtAVRVMh2ZQ_J0*9Sg%&-5P0D!0o8X|@?HD~uVQetA(dNKPJ|}qsX*Qd_F#-vgL-7HpdU61( zF4C_AswW%y<2s?_`i8AMf)Yr8cA_i#-R1n=IipC|gui(d@PP|T+J=!S^*Cq`ri6O! z3gZJ^XOQbNDtI)4zTeZM7_0KBUqLO##$IbjzQz2RWSt=`IV7N#>Y@TIDyMJD&=x>F zod@u{Hbju!E06F9N&vz7)rb!{{I*%+NOaL>wj3~5&^G#dv6+;YGM7BsO24BoItZw{ zfKhH7kCtSrRW>Ius*T`_7pxFe(`1a!htpgQ-tbj)XdOoEdR*o;%@+u0SusX`rSr&l zhZ?P*UKvDd0j7ke40M(T+l7;6W)e$4t+9fD+)FSb+I7^ck}c9P{~6@5MLv(NHWoGe z>6meg<_c=rJ`hw@{tRv95}9^KPQqU7ylsAy!8zpjwMVjz#O9PimlQ!`VDFP?j%Dn<$$?G@`I;R z=a+tDOvox8U9l83l{>I%OafCTwj70jKay67{-kKdYKDMXs-sR~jTaq{ug#_&Fj$o3*gFm-j()>B&Q6h+)B*0Oy9XtBLErelg^Q9p~cT)UJZ7%k9O=w3$q zGRZG+CXobZ9{LgjTAG-qVnHPBgVEaW`BT3iQt{x)WbCy%3<>xZWxt$ri@WgUH%F0E zeOnUds}Ea~X%D-R`U=MdcOJps3ALEo9g=cQbeR=E9RB>n5G>&*1>k|Ye zfM9bqdmxsQ14om`zgdFOVrDXtJ>#Wg6UUNgEouJ%5{7_tBJ|rSp!|AsN>FsH%TxpW9t?jA|^+h3ovAVUfV5u-;HV!@0-Sk-YXo%Q8mMhir+ z5&G1&Kj~cUMBarpmVy?TV->vtkLDHPfD;PrD^J74OAla}5<)3IT9Lry(d5b78fIr3 z?%bkJt+8`g`c=E5U3o?I-_NfdG@In_XvNG8nX#6ck@=-N@uuzKiI_B=A<(?8oNC%> zj1Ery*UVBe%N7^kOCm*ECNke}W)uZ9ebK?_k9ewG5;<+)$s;aJt?@sLQL8}qtIv$P z{b#M0JUYgZ`p4~g>pW3V2`6yS;_*B)8h}xP-sV`LCvVI2Bb!=ZQ)^bchyi`~;~MW_ z%$&NgZ5MI+ixT|iz4n}px4n+s=1~B7-uMd#C2$rF#}#@O=XzJ!d!HNmq30x_i7mvS zAi68xyc3V=yNc#t3bE=`4_;YfBWlF`^o#05Z7eLZly6!o$i#nqB~7cYB8pf?R}i`k z!K8#HeeNqO9i7Rk*fx@RTV7Po^24eY>u^vXXHm5*9HY*q*yO9Vs7#2Zv-3jgiCu%b z%JKtGGP`b)*eTpy99}jUqx}Q0^BOl%73GbQ5Q$-gpWa0-u#g+uxs!GG&MF`QwP4JX z`tIL0@`XbjF-g8H!gOH{Ax&Q?*lsV^890#9(_e~E0tvPpmy;XQ37|i@Vx=cR0%~<~ zX(bxU(O9*Nz88p`HkrvfoEK?!v6FGHdY$fDIVZEHQjljPz%1EXkP^AXWRD z3&lONv9e$iL%@{iSp$zwa_nq(V&&$?lmq6S@g8Iq>?FT0=|h}HJ2HL+3FtBO9pOVs z@|oTNeC0lG4AWw??0ShBUHYQr)VH*DH;kPxnSF^S!Skm}s?*&BWVs3>y|oyYi7iL_ z+!vB(g+JL^xtOUdSU=`^^xdU;xZa7Bmi4a9e$<#}U1 zfHEP}_}F$S>`erzn=zFkV9D7Qyz6>I8u%%kh?_@Cj0B|1)FEoy)KGRFKAKqFm&Bk$ zM&gwj$FO;Cju|=O2u@#gXxT)5^kyQtrSWA5s0BxGg!s5wV(s2Ua`#(=gnqqrsmr79 zt#q2q_%8Hmg#I#ZAv-#bAkmsIwj5wwVMpqeu%7bAN{&3S7|(tU00Da%y%X17SMKz7 z9Ld$~B*BuyblLC6*HjaJ+mLwDZgqsDlAJi(-Y2l8q7$!-oX%-}9LB0O)GHD2G1Sx` z9v6H_A!x9XgzjX!L^nQ%YlhSPGC-ro1JpISC$VOEN9rZZ*Jfg?)k#FY;V(f6Lohaq z_55&?ZAs*6bO1xZoTxVUS8F2ZKEs+O)W*ZJ_579nK_qQ%bBw_J1MU>TT`GFRE&3zh zDQqfPbFZ9(1k?)J+XSaf5^%xAA=E~Ehz^Oa4j@AZL|kVu1g|U)@;R$1ffk4 zvmcAF%0h?ka)Q=mTJUq`CcaT!B+=*vGi?rOcI@)fsly*urVzbXwM+{#T41cC`@2iN zVtgT$xE}Ul2som`8bRpp#)JIxk2A^O55t*qz>%7^`fe$ww%6&gS?U)hnZp$dk8T5wfN zW5ORy$rei=(lmv>7zkF?@Z6eL6GL2gpRNtA1yUQ^J3QtG1y3i|CsRczfdo7wPEXK9 z+~T*Hg%O{5z6=4i3fv{GawlCgxY5(nC|cgjkNp}&&bPfJLJ1_`8F6|((L=?XbV(rN zUgt9e)MC#LdQ`>n8*~!Mld44w0ksNNTXW`gm7)4JiRNl&6^{>lq?2E}=7>-N33yhK z?s6)Y;y1_A$gH-j8G_LQvncxgX!%_{cR7_5ZPUJX_}}>zB-qpHe(DTy`-C*o$?KLR*oBd$H!wp$Ex7)qw>czZd8nZ;85Y!Egc3-=^)7wcXh5};GIu(0 z(R;we2jT7@vlD`j=U$bL^$#awj3zJy)M97IBjPVfnJ?+>0UI9-C6G|I|13lY$>qHylIRF)J*?02kS=IxMxD;auoa@GfFn_>zXcD)NT zLuRz#&I_7#>5nwv`IvT&5&NiM37c?YnhcWB-r)GQ>Ve=Rk}y!Iba5}+GbXbpr_H3XB|@U zKMxZ~$5x5V8V3@v|I@cv747+xlM{$z6F-TOfR(AzVhM+0=t!+vOUII+lvw`wv=}m8 zh++t+1xG&m8zZKN_~v~h$j3SE5|ltf_45^{Y@daZ$tG%}H2)_5wKSMGw;aU~Pz#RW zbVc8&8R?xkp0v{KDnSV(;0`Oj64$&rd1F0>^gCwG5R4Z1uFyBOuG^FC!yJedeocg5 z97wRcwW=r0NpHguB>P?@`&9#_g>w{yntwgYSMLcSQ-=M;%o$)gV7<{_cJMsPf4mq% zGTm4LYQY%?y&qN7NwPSRM3TC7WA|I(_Z;km(9;R64~bLXrjmjM5{A1faOW1m83+1v zOh+oyq>}0%W-I};*c}%2EhG)^n@V*4Y!TsZ1fvD#LC7GirL?FvnJBWKGX$KG!CeY^ z0{dJusTQRW-uu1CNMO3mN;u?78~PqV0;!3m>sqjX!K{jzeV^gkog_!S1af-9M0Vc? zq|2^^)B3uLDMoWi(?59(!D_)3eVl9SsOCHSl~B0Pfp_&5&3F96(uf}=J<2YvFTS!HqL&j__Elt2QuEZvRjencvq z8b!W8n;}91YB8fW${(5}wGWLXN1m=>_Tk_T8#{_-hlGij-^7yF&o?upC?wcA?Bsq@ zc=$Y>Y-uq=V7w3bF5_b;WoiqOblHboDvDrwEnIoSQG!OpV>^*4$?oJw^f+c@fCQW^ z({p4)Cdtyw#_~@Ke?0O|7jfH&E%?Z=t~|QYQ#{pk7goAj^N*%<6>G+B#@}L1>DSrD zDoHlDsw1_fC)bplZN;F)v#|2fB^s@^5z)|0jOt%t<&uG-Y6E>Q-1sCNchBXg$iH^H z#pby$MVM}MK8;h1*^YzecKnx(jH)y__rxBtYjeE~;Kc6fI zSIiUL9@CSAASVdyG_$#?^G}jTcAG9G*R*78lqPl-t8><1!zZnIrbbX%X}a8dl~SB? za+?B1V&L8z%ppSKjpF4UVN3YTX)8o1fdpHQ#*Wc)ldHwNy<4^bC6It+qAQkFN%H03 zDSRJ2PbPN5lor$iZS!r(^4CoZ#6??dc_uATZ{}UPiRklRSktjFt=;5(Ve+?+CDOZv zfeZn)U~cIQ`FWgtd1;zdkkpZf5=g+BrfaqB{_?;kI z_uLfb&JVo7GwMw)n%d}@ z7f#Vasf&p!S=z4g%KoasmymD@ti3Kq*>zrxC9b@ESj%fd6yv=EwImo(8n!F zq|w3e;;|A;&j_01=;A!A8L!LK0xTawpCf}wPlH!dhix*3wFq+sZ(1RwXOl$2yH4jn zz8QsKTChgh)wci2WO8(5KPme2D#ixPA+$$dP`)2W9)G{ydWws0Ee?-9Cqyz1hfLc)y%uS`D;6TaFq3REq1$)8yUn{}K%69Z>h9FVyGG z>4V|>PVh!0onIL^NioIA^1W3Z87)W~KKx7QK6sI+8Qq_H;`3eM(s7(5t5025z;vM& ze2oa9Yg>z?V*MDoO&2{3C6IX2=&5itHB~I|9YAfgPdOqjKN2NxDcj1tg#@*jSC!C| zjXLtIlL2zzG@|Yo+(y((i4f~fJ7M@*6H8=tub0|=3X(JO$~Z_sEohIvH94l8d}sei zIbUJHqzmawV{Ap6vhkvFsx>W#YORIr;_NQF6unZwoIox3J_o&nfii53{9(q(38p#P5fTMbs-q&^)4} zERD*f$u-;0ifiY3RKT>L7JNyGzUBQrRel-pNo?Y2AwmfxriNsT8s80SWZ*(=nA7*p z8U>i~%HGW@y0u&^-npI5DJSt5zL*44(!TvUM>er4;KxaOI7q zvBac39^~TA9&+A|Ru~cJ>WiRp(T>zby{C}MnBUThwS7fMKrLt+p=mt>NU!`xvYO9h$^i+OLxeUq zNhD^)Dbh~kQUTsS&zhNq*UlI!pt(*=Zs}TWdLpT~I#&vc`z*j*K?0VE&J#`3NY;yw z;WnRdj}r>(|ySMBK>ZfUPU}Y6INDfPi*Zo7)>0Sw2><=GdY1bl#niS4)KVYfwov>a{42vR;l56`VVBdJX3jrG$juK9$3phl!SIkzEA`msPELoKG{utreQ zfu7_ti4lDw{&i~$wi>*_h4%NfA}cQ5msV-IvbFpCH>Whr!pb%Sc*ZvRa$+JuFK=>( z&Nq>n61rJo)mPd_f;k@62to;Urexy+Gr71Ay%`2di=Yjrk&by-HBkE!f=iEH#4yr9t{SnBC4d(6G5U259Yah8{gDRiES8{;LVM7s>AMCC z73BDmT50W&MobGLSaMiCv_gLxY4$sb|9Y#Eu>rmBist})CuIvZe96&rxQ+`ayW%@@ z=T}~1{E8vKO*GnTEfYv>{~cKOdn$AL3=;6p7d^=_eH>|XZoSl{^bM0MSPobV2(8JD zC$-!Hm+fU)63j2O!M3^7GKt)^_>5gN-b{~zy@<_~_fJ2v%5#_Ey!QSeyk7}wm+?0= z=8}>KD{crAJ*{P!cZPB>yq_`LBn3BUX!IbDqc;HmBG3Tz`TS2?LZlMKX$7EzR7{swinF{sh6x& z@vz?L9$8;KF7|V}yxD632ep{jHuV1ya-EWJZeRwrp}X{fy4$aGIdDdEj;SkHKk!C2 z8gg%Gg&uu(XIRirrae?66m(CNw&1fko@pE8X?WZ91ue&c9XDKHEyDZfOv|Eso9DO& zQKH|f9L5GD7<;IPgT6xhwol20`{mFEYy(Ksb7WmtxzP8uzpq@vGK<A3dVP#zcQ~BENgA0XhCg+tlYp7Pz%1#g1j%^R;Z|rZzbp1 zazFy+5Sgo2yBJa%{m&jyGw*(Y8}e|JptrVGHgeUD)E{cY%OL@^;21;4#J5`&FKDht zO!H7c0^W*;_uc87VE|X5eedkp;_M3M#RKT=jPLHP8R(+@ZBC0j1?9}UACQ1=j-WOn z8=SN~Do^@Z&b;CQ`wC-Y`@{+A0!mE&Jf?ynptnOBrTkM_ag!2c?0r}Gm4PEC`^DL; zL$t5r$?xaPcVWgsIEpfFAyprWR2xtt-+rNjAy%Ch9Bk=}7dtX}#Ehbws*D8x-|6zp z+xuM^0`?C`qx=(FT(r5G{Ad9?`hXFKX<3xiAy~1D625w+u8af_u>I-x{8DX2EhQdJ zFm!<<0IVxmhjfpuT{>CU%^O#4Un;_R8yrR1IoxIadF1NOiF{bweF7xlIx6j)C$5j$ ziLY2p)qd4}xXFjJEXbMNeK5QkR5xmfSkShRu2}v5byvUXI4^na*DfU6+8M(;e30;a z;3@v1alG6T8o5FL%*67m_1%a~mc2>8mf$`fJt^BaS4tjYOh(>zXKw>SE$bD6`Rk3iz*c*IFlAzEvg&>d zGGs*;!rXT?{lNv*Z^oLb^d2<4y^b86zw!@$SdheG6T(O!(bEWLm@=aLdN$UjO8HF!Mpvn?+x$SooV&A$EK~Yws zY9xK@!7_=xeaPH6-18@pG|&FZ?^=I}gB}NS$mU8n%$w*vt>Tqe-}4BRR(0MP=Qg6R z2`FNiyVf-3Rdbt9zS4^LAtyp-*c=*4&)X!^`_-^LV40B7$SQtq@fAM)_h^=YTChft zYr=J@?_QDL@@p);mkPWO`V#ap6kgd;zR{+h?>(bCL7Q8OL9UzWjGlS}d@lpu^F(F^ zwz5;gN&Z`OXO@6ku+~v}3uC#($^(3!8ngWa+Jm`8(jPza!;-#qV`uaH`CqnN_ zd8SaMZN%TU(RmOmn*S9aN@zi@o*qLGlt2Q$go5_(Pm(%YKH)QTC({;0|9#m6-Wi6i ziTWq;a^``?fd!SC%uCmm)CD~SSm1iW7U|tY-zjc(n z-xiULTbDBgye$pKNBXi+@5%C}7GL2YdqzF?Yfe1pG*;s?eJca zl2eM-bNA4Gqg@YfSmP zWy7s`NWc>w^!HMm&6M{%JjJ(WAXhAL=iNxTm$wly(KC=>{lJ{STA**rKKGV4 zeQ!_HYg;h{tOZEZQ^hF}a$%0Z=L|7mN)FFxu(>j=Op-g;jF95*6pQdw2&@H`n4A$J zpH@HT=e~2|d{dG|rO9&+m4snK^DwcdWe2Px@tFPHjI{14WX}_GKBZbu;3|A4xijB+fq`h(BNwlG-j;ge_(LnDNSo<$_Lu#<-|wM9&CwVv z3~$XF4n8Aj!WQ8rH%<65;ke*ikw(kdiV_o=4k34Mo6995_cA93;Ewt4wJvpullNJBw6`cdpq-m!xQ}X**5a( z>mwP0(R!TEAqx{xWxtye-80?zsvD;Ao+X|HK?z7#HRCd;GUr6(sI{^FU>^UZnSp%# zjW=N=+Fzr%^hrP_^feWj5~?jrB@0)SirZ(N!-;Y9o^FSguBiW5CfdWsahf`K5oP3B zDaED*IkAbJ{PH?1Ap1qQ=0Yk)J0=RMm`wWZrS~NUBnrw;+7rLCXN)H`RZ}I8?|*ox zg?3Rw)67LB(jDy%F&ORJsaEB!p@d=mSkkIZEAp=Rwi?!Z(9{`N71IeT7pXAo?T4$! zlH(4oh=0mchJaeIW$EcQuS7EGK_EYBaW#fLs%CTs4(hg)Q;o^MFg8Vh|2!jsy!|$x zk8Agsg9Oxq{gIx=wO`FEOfN};t)>tJ+CZh-9-}L{0;;92KixUZp?!IR%7Wf(L}!ja z1#0{C4_EQ-sSbGZ%fY`(U%IL1Q5_3 zLVGW~=cn{PD9y_9B}}@TJunJsCa6AAKL$CZ?XlniKV%yi|AYCOQSMd5a=b)Gg!ZRcGZT=-y9{?H5o{t z1QKXK2+hr21zNv@{{Ll+6;W8lO7?a1eNku~YQfy15BE&Tk@+4{WeDwqPyz{8BaEzH zacJNbYGZ83OMXSpQfayD#}ZJBsjJ1$rjcQ3rTjTX9C4h3SQSOjruo-% zn$t8ocG?dk+n!kEq&?rhZ22@2pnH!`f82-9{X7ik*3;KQW~^hhU|&J#yEuj@wzVdB zUNZ~{s0Di({Y|8zP?GrYCa>G*Jww3n5}T`%@L42gct1Yyuf05!Fa#(cLLN!!n``Kd0)F5i3bPyz|qgX#XRSu%NNvmXC_*NGvZR*(aYuU=TM z&>W!mu+X%kXfic;Egm;=FApV<(0rybgEL_q`lB7Mp4GaN@)3W;%YS+kw9WvdXEyZJ zst5Epv`eI~HPqTNeqJ-+pa58)5F45{Mea8z*AW`CuQKL5hr>iTE z%X#_!L)rHw6e(oMt}M|r^9k8Q_9YZWB1%LkJ(lQN64$<5SubDvzVv+NgzQ`Pon*_t zUvas9r+1v96_jfKWgLJH1tZexqDYxgOv~j)!KN%@-@t8Fg3^)vJ>;FQJxUpPI)Lq z+wGGK&pTIBo2>21xa%4+3pHFss;D`JtwgvE?u|D*s(!Lm+*^s2&~=G>4m@aF&RAA) zwVrm<;NwB(Amy9*)OfUEZFt{IZ?c!QiuRVa5Mvsu#2VLI+&8;!D9q%FQgNS&4J$?& zwim(5{n#?a=JsyPyRt9cA~KdrDr1;y(k{wyE{?C0uBpNhl!~rI7@awKsPQE|OC5_i z$JQvi4$?V~H|`&Y8`no)Q2NacwhmG%+FBusIt?*~Y{*o`DtFc@hG6FBD3IrxobcSvUcx(hweR!14Fy_DL2Z-$~J)?3XmM%)j*;g3t+kJlKn74&6<>~r^| zqO+D#Q8b=xmkcr@yk}cx#o}oc=^>-Cps!sEC9R&9P%~7*sQWE7%c~m8_OLlfrG)Yj zGwI9>Fk=2!O!eOTlOY%tsT=p4tveWfS~=*yOw4*p^%bRJt=hiFROiZ`(A$RLI!M>M za&s*rEic-LPo+pf+s7@%VtsKP`_ZuJbQRUR4)poW!w^pOEaHlfOdBDTHRTVBc+mts zjXz84^-UJhKS26autQ5f>f|SNBH9Ih&#r7RsU+`v*n2QB%g@)NOs{}GcE9RoW49I?0ec%w!0 z{ASs1v$>QIe{+u5UTlJqcWY(y+nyPUmeBnmZ7r_OTiU7QpF_Z5%ME26Uf1GNI$8#0 zmr~-+DvN7cgv|I+SY7(H$TBV8RJqF80eSV;{ab3acUN$A&)_8lky7B6<(?&8M*b|E z%iSL-s?f?1X!U4=a;^Q*5+mlxk^xQ(%@M(uiWs$?cLt{u5ez}8N-oPQkG1in7#GJWJC=~cdhVpPO`TZnvPJd9yoU7&m50p{OM5h)vsV}@qj zU99{EM{t?yV%$r+rzeUG=1I<|h%8{vntqN(~)@%-Lm6?zlw zy)CUJ@_7rl_ZI7^=ZKinpe@Y}I|t{n=x6Svb1R z4{rhfEn(lK<0K9r9-xY?EdV2ac4G)Snsn{L^?dnN)z_L29Gwids!;^vy6E|^vElk| zpRW2>CBsVAKDHO3JQSU`c^KI)xAj_E8O~k8Q7c&!amP|S#Hezpl=g|br&tL=(6tL= z8cu~8i%yi+g$|r!tC}DPx}u_Axa?;*6)a#>t5}oet)%uG-=$U=wNG!lQUUZ-FC(%O z##>J5EE`tNt9+vN*sNh)rM3T0%xSpHCT^goX7%^EBY38ZP6q*>-1-=-gh&jP1tA8l ziPpy_Wb0*H0}Nq*(k3dcvxq9!m|QV=6CF1TnRi+pSe=EZAGM38iak<_zlCDoCDMa7 zb-snt_efQ^e9D(0sEkpY2;W^=IZtVCH@I6HZ{moxL=jxBI`wilUeC?c>AE795+WIF zWJQf{l?}hf&hTv5H$~-&Qt?%-bMKzU#+AqQ#Elt>mQVz@Wa=&~pid2|0uQgCE+M?4 zqsjOt&R*-U%S>^HLyw!WSxXUYWJTYxNqYF3{9v~L&&bF)Gpbb=ZQ}h0+^gS1DLHa| zgLaHOrf1sY$sH}B<4?aN_G~|DcF9`~KIZSj>Y$o|_oJ9Rt(LnKgUMShe4Z1HO1X}j zdQuU??~Q;V>+A3lBnUR=#ix0VAZ}%CcvN(*q7j+Uw1~Ou)o=L5L19JXF42-{+zfhs ztqJv2G%KM9ex`qTd_!oZ8$)%!8Vo_H=uL_c2k$k9#U<*&g;IG~P%uJEGP*(}=3*}!tWA_~So1C+y&5MvF>*isSBZp}?ir}+$SDVx71@3WD<`ibLmLb@_Hs9NY zDm>EzW*x1`N09b|>U`n)WP-H6))IP6ufbOXilCepYili$ZRQ$~aK08tP%5I2@eH}N z)W2T(z?P|1n5L#9$faa=+x0qOVG|ht!Ien~l?=90i}?e*ptGfsv2tQ_lg8T748c6^ z?!)Mw;CiFD;WOUJMsHc^?JNBfz7=0P6b^s6tM)A1!-5_CfX`^xS z`BeH{|Deuh$}K~RLh~iBqvP;6c#@UnL_R>N+t*i?}P^!B3XP9DI zl+9Ws0PFap-~7<15EtJJhG7XW)Y8eglRnwQwBD(MCv<;EdS^~0Mu>pA zJs|FR38VbjaV!TmrJ`tzJ{uGQdf-zv{t1o_se|6vbHu$rLtrc33)ky_XRl+zOd*S6 zCh__Bno)o$#tF=yhj+r{OPJ|)c`Srhte`%eo5}Kfu)NNbT9|3>z45g32y*v$zDW>t zrk~tgy_aIyCv+-Rhi)*v8$kS0wmQ@G zoZ2XOC%o~ecA3=;4*#==At)8M8II!K!?lb7#oQk<1f`<-5n~#{3&F)>J`nTpn4%>V zL9H4gs&ps|ogn4mR-bpb_F3M}L+6h9ilcM;8{ozdJ zE;FZrok71VhSfJkiz-qqJ1sflV8aOzd8e`(eXJLkMB-(`S}U#}2m$NF=6b{AD~h#> zwuEpU->7Qb3yys9)*E-^Gw67*mXMLfJS@N7=mt-Cv2Cp9{jwz_oq&{suED8f2t ziiz(u+I(`eLWvf6!(kl0YuWPhVMR+Qg0GyFPxJ++h{DS2AkHX?^|%InL6@YI=>Pz0-^TTCA)6qahKU8ykF40HtPm&Ed>BVp9i1uB2-xr(i1L`t}3 zShsW-WZu82D(<_^JPfJD%GP;N&KeGhAc+oo6ga_lli zOHw)yGDTnk(^@O$KjV>^69V-%F4xyiZc&t@*0HEL->2Ke_IOFTAVl91Lt#r&igr7` zPSFyIpt=(MOCChP&z>Fi_vycL1ktrzi;k!}2@aio=Uv#bAKTqgD!O~YGyO*spuxnU z>acGX+h@|fA)Ak4N6~0_Q+S?Q)NVgRP%5fdglJTu0imI7;$zCOF{cPR{<#16-VySTDgwXo z?MXW3l!}hO5M#W0LujApdY1nmY|JSY9ZigtdDRUf(>H3r|9xQVAf>YQ4mO4BL7Vl+ zTokjY9TS0?L1Eorf2*SN{Kbt7I91))*I>E1$r8;v{0fwMdbk)XK0H4}0 z>v@o_cciI7ODICr^)*F`oz0qvQ3@imRc$ErYL+gz%Yz{p71fWz?^PLCJg~h!b_=yA zEur6KT69=;OPzIi1kB3XtE^>WZPuj;rnN{Lyqhg$vlg3fiv2XC=*;Lo?}=3>YQ7h8HzOtB!~$Tj8+9B`_AQwy3RWh9;IV$z@#gxWF6^;UqH_GGG@@-)e2jcsEJ=OuD@lLC0I(b%+hOU71pc3!GmJa>e-6_r6tD8gDl zzbP)3G1HE&M#Rn?2zs`k@oGO{aJ)BMOZI3muY9)nWAg1l*|ZsF;0&4h1B+y7=lvKs0)mP^ek^gI<$wLm=S`OP()Co zi_9$C*G%h^+mAYxzpDb!8~%D1%@CA|=h&L)WKlsyqQNfjP(>x2=J67H3`=B*1XB#` zj&=N9+9sD=9uK|$nZgi^ipsJ0aJH#_+c^NlW%N~}vy;x+*QIUNQ)5h@R@1PKz!Sdu zs(nA$S>-235UQZ=cz2sK+O&Qimy1Z4rCa>3G>ll()}RtDcAc|{5e3nw+}1 zt;!zJ!HC#i1di+98G=$#i9ucRrm_*U)DyzpQNt1Wp;UAr)ZJ)A3G(KJgIjyQP-A<*F$+W0*rGx&ps5lIp(}hd>+PXHe!3od9 zH%lt{_~w0qU8&Ind&0&~#W{CLtJr9YYGv{p9jbc5&Eq-B`Zb?StJK}JdZDis(KwmO z=oghz)3gTX&e~GnoQxN}8h~}pB}Gdpg32*k`nNp{$JEj=+V?I)P%1iCgm4_$*GS8A zMLT)yR5Y%LQqlQ{)>4xoW5Uy2`ase)hM-h5k_0WwF2jtpZEN(S39DEn5=GDzPKdp| zcj)4=PqgEGjD4jVr#tQe$1k;sGCTgGeb(eVuHO&r3d?<;C?*ZHf7o2RjWVqx`bs7} zqThjSy33IOaQJpYu@Zt{+Eq9l+Nxv54F%7HMO=##1hYPb-+)I!J_|MLUmA3s| zJyYy?ZL_vs^`CxZhucHH)vchaI-}~^JDb*&)}~J#tE4uyAoU@yetV$v#RkHoHA56F zq1jt`zSn2(e%Es@Ue){T2cn(0#U_$h*uoD3W_jTa^-|G|Wm9g9VxBoj*gBwlNga+pboU%587{)n?YMb`^5Gl;;zjR&gR{$z5dt2pd}PR zIgOs=^+&^We8+Bwv6bB@((^>RW5w(j`&&Zm4NrCAoKK4G&uGtSYjN+qJU?Vbb%yAG zWW{<*=LFl=I=^#-Uo9Iz*H2dz9zKI6yPwV!Lm+9>}gShNcPbWGH#EaiI>LHs)!OTtGiq0acaritRFnG6i z**FZ=97|BNgd(WMz_&~vJ=cd$_(E&H=S-K-xlOr%kw`h8b<_H;(C&~k>p7*OyCuwG ze*B#dA6yLl7BplCO2sY9@m1gIYIlmm;kOMKf>QBWyV3QoYFV%oynlLM(bbZ!yUgMc zUAm{La`c}sW%M4sHk-&-14+miQW4` z_RU`yV?r!Q@?B=BiDmZROt%9~A$3VZW>ZtUjaxE%{I8g2FFQd@y^hS1p$I{(8jQ}Y zqeEY1Yxfs{Y^`NfWR<{poL5Wr?Z(@6jX%(znyhMcEnyy;;^md9W*PS{deQVCgMF98 zaEp~iZ6f5XO;kCE+ztJ;O9fUg26cwE;xW}UI+w=XiggY#>W^`cb?`;>*(N0{(w9YH ze|B%Hy41|lwS2Kvq=X?(bhZfV7Mr#A5o}d_=uJ7k`$yg38S;uC1f`;V5?$)2%S*H0 z>q&oN9khfZVuQVf<-E;$D7WXS#ur=1Z6Ea1q`@3PsTi;7{<+oC=iD)!Z&$d%yx_(D zRAD`wDsG*Utc7BBhcj|>%|rUlZ=*PZwu<_?i)}aRsj#94^_2=E4dypb5R7kP$M!(g zD|4r=c`b|~7!~uO*VmnmPCYN^)lqo!Ln4;bMt79f5!p7e1T){#_+c?)W+UU!*eiN* zY=ss%IqMJW z(t}6yIw%$48=elfS+3^1+p15k4KZkR7UdO-02hl#?o=ny<%M=0gZhe=P}!xDFJkdE=*Yl| zy3Ek(ik?%__*%YKtFnEx@wQD5{ZG+lik46W-w%SvNTY3dRo$rCVYVNn2pRz_g!JxU zj14TP56*HjSe^kA@62-!RNh|MXqCT)ew5^Euo4=7Oyg!mKi$||z37nMFoVxprcp_R z62@~5x6`Yqf*w@$KbnD3G47Ts7^_Px-mV9Y9nN-MG**VMoc)79J2XG4Q=VZwC$$Hu zoya^n&YiidJC0nZJ5K%&f>KdG5Yar*1uniHsOtv$@H!|Jy~h;^=Uc<3-lg@?ORoHm zo>I{`Ht}eV0e74F>i#P*R~WsEr&QF-MpU~s2tHN)q@K>OXSd!NS=Da)=!Gi6%MddgaN zrKP=^C6nFV@&DzIqt*Rs1I<*I7!Y1b7LRJvWy%@Mpqe(#;&U)wy3WMkvx{3cXT(dd z9kmc~{LN9-<&4zBT!(W+t7DeUzs1X-+xVguMT;Z5iyDWwzq2hhd+|)^H21vgHOu?n zGcax{Hz#@M_`JrV#aU*_i2fjG2}RKQM0$K#<8$#Y;PlTgNuw8O#3_w-#M~ms4k(v; zp|IsJkIsx-y2(*EEMZ%RSGye)&WNqxk?Q_%jhR zbCV40G=DoEr^p|k%GE9whW`33m6a?_vV@&PcNvBi26_FAGz{j43z8krwU3aXer`2Qx5yRs@nW*lb7|t z3>h`YRrwroPqkk;Rh}m*D2gaql+5T#P=d7#t+*FbQufvwtA(PFziU7ns) zi%U2|{BS+45@(l!+8bH`ofAyP=qwOP^^Qs7#uTX6y@XBB_HMf2{d#+XY`C%p<00m! z?hCg2x8q=N^SpY*)Foawk0waF=;|u@$WpJ$4-#Zr{_6ih92rnZzTF!Qj}Im3e0I5| zzpwP+2u4L@Oe8)DQ)5p))A*neFo~nQqAe7Cza*%KW)B_NcMRth)tn5mzvx!^`9u*N zy*Cypf0(XiJ+C?YcgxeHW-xt-2jec|+u?;?X*qZ=bv{>0cARjKU-O5-^O{#Rl@dXz zm|X4ebyixxO@w_td^MGJCRbD{#f;+xog4Q2 zX)$-1uX8Mfd(~p!qEuAd;rw_|TMcOw2`SrFFs)Bl16nucXmm8?tg3PF^4B{_ODKZs zVB8gTjZo*3hr@&L-7Kz%W>}zKLcP0fsw{Rc48|9|$TYImanq5UV=?lNXAbO3m>F;K zMfu`z04%&93>wu$5iANyWS={KJBX6IMmhl^Qb$_`4a&d3|BX z>$;Mb&^qXsFu%{D@`l%q&d}L&AZrz+qG*(oKJ|@PE}qb{>_APaXrJghkG?qQZQrfR zFj$)8DQVj&nyIV!MGe`wyn4MVV&Fe~F`+&oL% z_BaTdSdh&@y86)hD8!Ns=`FU!!^>}7Oj<$_ToQ-=b5kacnF29$^O#gKP%19%x1I;6 z3*{$3jT04^#lq$XvrBAt$5i_};gDze1`FjCMNqEe`%z6dtMaEJ;QjX;HXal~r3XDA zn#RDY{iS8)uM@O?`}Sr|P`pemgnl68bq$yH{$}}@c&Uo^L|yU^zK|EQc!v%?Q%F-P zn*Ez2jz1d+PIZ^*e0eTt>t}EC$J}`7v)Na%w?IgJ7-Mp^KUiki*&g4t2hq8n`F=ej z)+mOcUqXL|fL2g_m7i|1urf#NC}$>ah?kkWnlUuKSXiw+lwO@?wz%L7v?W%8U~ig; z{?|spI@deq-(%8Q&ne${t2PcBsV8^X)#A9@L|oO#dkj(2Y^z#ZWy#5Cw=J@>*-Bfb z|H9neM2jOHI^M30_GmhRBPbQiT>oiz9vFS>clq>v0Eo(;Y}xJNrFCi}B@%76w9WWC z4)-7QT?p~nZ8V^hwsJ+9+Jk#T(F84iJ z)}4(f6Ey!neHWlsm`w!CmC4g*pX z!RraSNi^<^+m1Cvt%d*Qo2TEUS*S&w8B@(|Ejud5h)IS>Ogt>&=gG|piAvBc)(qhW zkL0N`Kc$)w%X45;w0|RuXp+|TVt_knu-YTREB6K{II6`h;)DIOVb0SDo68 z{h(CzyDU?Bx3-&9nPb^<*PuwuRM+*&=*x|l$9blNd{fVS<4VZ8W%Damk5$R z+c38XEunSLFNux;n^Z=%$1*7rN09b|wvc{FJYV16ICr6*tb54bU@rhwX(F?m;yd04 z#{cK_p>iGD8OusV$c8^%Fk264`wa)_x@U?MudyHWWhgQASSQ1yQ>uLAf!W?Df>P1? z#HfBT#@hMA<(~`j#eh3)Wk$dp8PsExqAv~=yzDQNyT(iZxDcElz5Wh0EG-tv8$GTo zLB7TMM81Ua&U3?!LVv%vylQZq)j<)oKJ?7oJjEF6mnz5lc}rS5l~*dqn19!KqA@b& znhagiT~P$1Vyzk&Sj}j=Vt_2R3eR^bujn{aPKy%|1Ltb_%ZWY0nTDh9U{QUHdFZdl z!HP?b<%)9O<=zhd=BlgnWyrNbidr&MSEBD=)hTfG;!Zic;C4w%D1z1}#J&0>L65C3 z&lbn%%tU2o&PpAN! zsT<$Ij&p-m?ILCH;?{;JkG?o5N$B&4@=Di4_7ctURZfu6Fnhw65^mWZ0yO6%rB^Qd?25J5{Qf~_Cw z;&45*QXUzMFQ+pET?c91Vxn(ha5&RgeyD-EgtnLVgRZDzc+LfVr}S2t8G`qm6hWzI zYsHbq=k?i^&*jt{yak{LN<~*xk#(jOlxsRzW=*foxl6~Hj*XBLvh>U2jnsD^yhUbp zkd>Ofn=zrP6O0S~C2fx}W|Sf*6&+d8x2H2S9pkK~mBF}FT0#-@oeuG?QA>D|sFY7B z%w<6ll#0Fok$-(BxO1$4iXL2^BPbQ+f@nCPFO>Lcr((|A8-kWl1e5mJ+Xupol;$dF z+gmoH=!+Qatqakse*_dgSVa{|S;r8Riq3zGqklaSVt=$ydcj+!8K_M~b&L=Rc&=0} z!b6p+nOD&gilDD!V2O~pRPdFtcA-XKnUcz*?G9;Ei1n6`2fJgnJO#b1A9qY_8oN7-DV zt9fh4LKzv>2X*`UnUf(VTB(lXKcvzUD#!Fon4Pj@JS2Y_ET4={FzM+4T{-EOglOOy z4^pPEM`i^3OV;o8|A}ZiLvh=11Cxa zsE)l}nzXl+iqr~9zuHpMeo(4`vb~wrK3UGQ>w>&$US~9{@)Bl|;;CAA zH8bBANXGX+S}WQr@ujZ${vF1JyIT-p*ESribG&q!nmaTtp$Pxt9%g?3bu!~YE~3)u z@i6#7mc?o0EKN%&f^tNNYUlgId)NP2hM%_wc4k3ZNKamb_;7d}6q!&`bxWVFDSv1k zyyrbujE3JP6)_L)J)~&~MNp35o8IpxKuUu#(*5WJhM*@bl%%*iYVJ@WsSx~XkRPmnpCndXVFjuW&H+kN}P>R++? z9=y_Gg_|iZ%)|Vv-iq;uNlE&|<}j$SfOZoF=?_Xe>$;R>{q+FwZ(2wUO1#rd?La%r~Cc^RGv`Lg`~=VcCLslfF?z(d<1Y(Q;1+ zG@Wum7x>zRz0^bzg4J;&Y5+{#KTZEt;SnEmGR~}p;!2)Qkg@o0{WIi{W+eo{>o{jO z8lL${J*CikrWqI&MT@fqCPAOd8K%RQmQ0J%-clVSFcfJBR1DA1Bi;^Ubx;JWPkh?# z1CAjX=BsIVUrXeb${5!^#&1=j$#460;^77$=q#dg%*Om}$NJFaX{>HEvmr-NDmDi* z4z`Duo^JZM)e+c?q6per(bw|Kd+@SgSRC|H(HkY2yN%y2ou7QdToX1N2EWKql>&R( ziY=ZhWA0X9IRV+1L}H0@dRN7PQ0LiStPYwJkk*Hh_jjD3=(hH-Gk&pbU#hU#&}Fe) zu*6MKN#uDT7dLGQW8T$-IRj6mQYxBXk|Ta>=niT`DTsPH*Fxt9MbIw^k?vg`_Kov` zwdqr}HR8LiaV(xd?yJe>AV)0dRUB$`*sZf7@kE%8dF%~a_72RV)fs(b==h7w-vykv z`)XPm<5~EtSLx=M3F=BCymt;iX!DOxl&%wNvsUps z(z_niOB;-WWyRl^w1l>beo2T!k6xIb9pWHEAH=*g|JFef)}sq-PYWf=zIk)K6Mj!E zX_+}Z3YN^>!0v15UGuVb(&n;jrgS}>>%Ft4{4 z!4|YMLAtKV_1KEdvg&meMuFp*`5Zy1NNaI*c0Z*LerXORik1R8YP3&`>*7$~7kbib z1sBqDG(*s_p%NPg4Z-31A)tVysI! z^U8uaNZVRKEy!H$wJ{m}WHPHNdaF;rgzMnCqGr$A@lbtm{1IA05v)GZZDvV*ct9vz zcy>_>(sm)jr>lQ;>j?nG9R@FzcqB(+om)^07y$hz9 zRfmRXKYP5pVj3m&AqYlA?{q|w$Aw|_*lm^xfA{7V8J*`$ zU+L=C^y_&u%^QQ!+mQB_B3RGQh0n7&j0=NzFD`59HMRBELa+HH6XcCOxxO*~_DP6B zd)L@J>kS9LaW^$BVF>CoBW71_Y6g|+4LNU%pf?ry7NN>JaiLf5ySW~Xx%EY@TxlkP zCv1_Z;Ru3KF}{iF-luhqiK}%^$w6GV(>cg`Zohe>K3u317*2SLOiL(&X@(=6;&jC6 zT$`jBM^Gvzm94XX*Q?4zL-Ip=3!NWycG3P}o{2scEuZI%gKhnnGVU@2^&ApoLg!ls z4jB*m4$Wo=rVW_iQiG@@op;DsI90c(+E#6c?ZAaua+!xSvpA^M#{AU7i|I<=V&UZI zM3a`#R&jmxN|%Q%HM>Cioz@nbjhU`})cU|Zj^_(~HaY+r+=^yelK6zs1wkiC9M5tJiBL>Jkim%oUB_V#Nf?FXgets1qV zAc#|apyQ!A%)X))68#eH&#im3uN(#*C1$Y~J!#u%eHd$LWSX^mgoDp68?*YT7ZU9g z=H&3(Z$`Bm3)S8&W8+K_bYwB=_nVX66)_1$S1YAx2}RKHNB@#D4$$^P1xOfz{?uf> zV_x|0u`{M2{37&LyC%8KV7Kh*v2u>gnn?Kv~xIL~p+3#%x)V2JsxK z{A)-3mx069qJl)3QF&SPm!W*CAOiONpeFTdryud?ZXwXB!=;LB(UBhf#pyuu5j!Tk zx@1=;efN>JYf(WWN2Oe>dnkn?TO8<4_?Dj!uEn}&e=g?bT16b%R(bvV|94^NWF57NPh6ae-L1W zqaaCtHXf;;dt>80pC>4&;C|1S%*6s#*I1pZI#TcOz{b~)+-V`u$~wBir?z^&U!&KM zq!2y&WJQ*?sd=RE*xa5|f-TM4-+2U)Kn02K`#=J%u!WK|4`{I>cAES_lqsm z_LgN;Te;?LlMSQPeETEW+HPAd1X|&omZXKFMyVN>MzR@E+Z0rgc(J}D>(bslZzL&8 zmr-h!8IkO5;q4Xzt?*2fr2AVVJ!5lu8>6e@EI})rF;)Tc(%o*)t30r*TtEIJ5b5Cn=*=l+l+w}i(#gaA;V;caPyL~P{_v+(&MmChQ zwd1_YEk+u@bj15|kUICgxY-WMV!DG+}=e`4=i{D@FK-pQin zsCYnZe}8mO?G3PZTYgG5db=;jsKj-f&7=AKo}+@qc&*g#Q;{ZZ9bF{Q3TKa%pq?ks zrO~_Rd+(>C`2Rj0=mQBF5pNn1L0f$wfmSqbGL2gb1S+#DmXIT+YX3v4ka!x$7f4JIr|&@zTK6Z`%C+(iY64ndmc%}S)uDkRV<6P+hd>3nhT z2lZB?@e!j){m`hlvSIc8s}CwjP|r2GVhGyWb0p9TuY6VluY-#&@6h)8b^ae(g~aS4 zYqXzQ2mO~;p;e8o%d~l8!&4w|j#h6KARn2#L0I9ewDtoPB-Tw1m-qg>ECnA(pw-R| z(Q=j8MJW(;$C2rdBNUorGTm|hhgKm$b4;dLnSu|zXDstMBilk=c>Uk6S4f7<-T%@mw4yn!(RDWk0u`FO8qN0q zp;buGJl1Hor{DwofmSrzHJa@y5O^h{JAg)a0C8={J$-+ykf8gDM$bfo{yu?LbQWmz zCm@yciQfeI3I@6zabPF#<_PoNcE!L0;d$tI1Nr^S|xlmGA6b|i`}57!Re zNa=co{XnbQ>B6;7gO&?_)>hG(s?nJ$lonH4Y3mA_cYQjWH9DJ9AW%UfM|*FrTFE^r z5O}p*6TV0;{ByLh!jZPN3Kb-5bd{b!SL^@x^$M--SoWo`BKL;qqpC`ilTx9%>{3IV-d8q=SZLxoj2a}be;l%3O$8; z(R2I%&?+S8iM%#Fx2NC(TZLBNfB(Si63r5g=9Sp*|Ly971kD(Y=2Z%@0+1qr(EYWM8hce~GaB+!cfKlz>7>I2Vnnk9CcSF*8RJcF$S zDoEfp=KBO%Ey&nUOM7~Y@Mk4ZLE`(@D|(ug>G@L}DSA$n>1k4IQ)^|qc8P7P4^)t# z>#$~3wu5I9yy_7r>|fmZl5C`o(%DWwh^(O5UUjXYk54PM!vuauX`-xgG7zdiNi6<(c` ztDLUFIzH{>Cu@_>Yhn{o~15Z-M_uqj-OV8eaYs>hwu^< zb>5y(Nu7E^5d>Y;DrIXdXi3^ytb&>+hp!ufR^f}PF}vQCcP(CzeC*6vNzK$p z6$DygpR7du=2Gg;?PkwWLBiVem$Qqj2dXy{K9E2w*S6WJze*NUD|Kit2vl6##^_>H zRgzY3Dyn+MyAx=2tV(6JAai$T&$qrTsP>C(C48WQ1jcjthdG+VW+S6=nd!?uDz1@~)>2v77ZtZw+J zr5k}(c>E=4K}bP0?ho?_qJjj*#U<&+$HHo}uPuZRB+v?vza$-=`atRXlfNLg&igF) z-#3AuQljKbt?$Zfa!eKHU7z_GSf(6fc-!Hb=y>?``=}(f>Me*}rLr(v+CXsyxT0rf zhZ>vP$r3bb&mruc zTHngTDl8x6oQZc@yit1i^mXe8T3K6_JL$8MW?3&mpn`;JUYTd@rGB54p_)5^RyZP( zbUrbadON;{+gKst+BWA^$J(zQ`D6R4#&!2EzvtSM7L%EA6|J!_1Am!qjM%<#Ckr3H zbQCjNHFo6hj<4AV2_i$2yV}dE!NLmZ3v)he>9j`bABe9hI*j%G`H2_L8+G3RozpbFpjM>o-uO4+>l_|1oVkjs#lajFF_4Qwr)w|1=3ykib<^ zNhFwSZdT>`=AMGVV!|^ej6Zt!UNVxEr8?MDDRk+WH|O?CgL;3&_} z=$~e+TR&VaH0}U6(vq}9nd8_s*=!XmNZfusT`Rjel9e19Pd<9Rk8#-ho2^0ut*pm< z@3COV^fVJit588=e8n*BuxAvj5VwVVv{^jdu_d=TuaH11oNx5B^f2BrDXV$RT}R3| z2CI+QHQW6#_RX_t@+>j_Uy{cDu))!{f;q477$A{R+NarShO@kvTN9CU^eRXC!q&NK z>2P4n&@%}gJy<9ayG zd@+xQ%gWdnTH$e$qyfW6IWk{!KjuhS=kD~%k&ctuCb-QKv~ zv*b+nHgfrm(d^*i=JME&esccF(d@6WY2`ejzH*T))7kcm&4}2!P*HA0ngl9H49U?+ zF1$RN^%`dQSW}{ea^$)>+mS%4Evp`Rm+T$m^pSRaMrFcYbF5H7BBTE!?==l$oIXyJ zyTo#CFpmckX!We*@7^1NTs}Jec8DeXY7(d*QR46(?^N+FA8G7+*ou$t1X`_sdB8h6 z%`5qObLx4S)0K1)HDfH zkig?FN%e9yR35i=Kjt+rcb5GpM6*g;TUw64BvsATMCnnn;CLH<}%dGG@v17A=&qZ-d0#MFok2dUrXoeKdPfz6}wH`8y~{ zGu;Wa^7IOnM>?Wd{hH~CI2_PTiK}Q5s36g5)dV@q+$c8Tyg^Lz>!w_)WDgC~H%II6} z1X@{Jb#QPW<>4`tnB3W4RtiS5lcPGxp*3UW{%a!H^_jV3Y^@~asTZKU`CwkDQ9;6c zOSJ59I+A5PXARyb~wQ}WHGEW!ROUGEwFO44l>O`5SoTH@rucwAahzIfHHN z?f%;2W776;Wk!E@0Helt#H(huUN+`XD6Ah>ftj=&U-wH zy?l96_H3|PZkNv{wvXi*C9nK5iv4wO0{Q5EJxa-R+4O-560YqCWgroYKaEqehMGQ7 zA`B}W5lI@qE=p;8!}Ng)?$@vUYPo9x8{4e(B_HEMq7O+NO1k!RmF2~_ygAnz?NW5oF2p6Kmv z@;AA-lRyQDMe8pij~vrZc^~-d-YT@}acF(wCu(8ky={rGeMrm3-82bQ zkSKRM%sb*@3_H-yIHQhtE6r}6Hi@c?`jxz* zvc<9-2MWkIB9ipx&KWu6iAkV>#D3egdPQ@@vPlDsRkEhRYvtFk-3he9aieF^4>Q;d zf0Mu`q)a)7duO;A!^+Q1FXNLltu%b-$r4tY1S&|ZURu!m<%bxSy>=FARlk?x*rDm} z1X|&U7{8mS#JU|f2~?06UU`RC7n+Gxp5`JS(`#pB2Y+)X&!O>6(n9%SIY(vA^rGB`RF82L88x`k8*?76P>Z8Ts1!^3s?6R zK9E4Gr`xiz`?E(n-)lV|eNu}2(Mu4hAmKAS2YcHrK)kn0Qsyyf)MMMayAf#R+BV;v zZ8t9|51I}U#FV>t<#X$T#d}|D--mLV$5X_%@1?u)k8^|B?yJViPtu<2%H5sj=%Ru| z*AgG)14AaVu$KFXXeHfL{GSdKK9E4G6@_2RRsDllLMP+*QJn_cs37sQdXju%a0sh$-MF8>xq4jL7(YymE)r;kGoRvcA5JR$nMt66gqHKV9G@|S zC7ta^KKz2tDKi=j6+VzaE1da~#OvfxdwFyc#2tHHmUsD3(Zi7k^0JTJhqB^Pvb>~r zc~)^+FK5q@Km`fcp3J%1eM)BabsIm64`bY2Rz_?gykG&g_Ud3~EaSzqbn3gxKMKNi zq>O#Jwvje{WJ=1Qruo{{;^TXSdCYHA$)RSdXYIK`xLRdcVgKma=V=bL`ks!$2P#Nd z`|-G4UUloMwr&JkjrJO1EZDoA`TbxF>DFoezSw2fv7`*uiqxNEp*6%uH5qw!I>RJt%{tE%5mQ2cL>6a*?r zxXv3hQsh~#r!wU4NxBg|rx>eDF@0`~D8>C`is_5(dp+mKk2*ziGp4_1=t`wSlQDvz zNUBUReQxaQbf3*~onaAN|5L>DWs2!@Gp2v)!CHl4`huXCezH>S>t1<8t#E$YjOi!u ziJ}Hsb|@6nck_V+MeAjX>GR~6zCtm5Hv+9FQY=$UU$mBfucpjXx>p}3hXWgZVb5&2ZR1G(s)=zQ+%<5%av-%ypn^nDm(B9Gei8g!BjY~!!~W^Y^x5Nu z4nr zCA88Y)9Q)ajFF@k${aqC@B_wXWo-Whc1TQYuCceCgQU3BbTZIH#;fP35@Sb30 zURw9DLV{KuWLlfx=GsKM>BE&ZdCcR1`$8)`ZzRd5#y(~2@8(PlE_zFDTyvV3SDkuX zkOw>o;f?<(X_;e^^f7X~;(OgX+l|?WM8Z_NeBwzMFW#yt9goG~tCjuF%rnY0x(0z( z*5i?Fac<>#k6>{;ip_rHozO8xw2I=!GObgHZHgz$6m=GJOp+dse8r@?Qw2eBYHx~Q z3#*i9^Gc0AT>CW?B&m6Qncj&pWxL*-O6 zcfv&*R(P&RQo(t-m2y4JvBFllwvBo0>XUgDjaBY5S_N<$D;Hsm0<8{s(@Fy$-8PDj zVD{0k*!wyrfeI22Y;5+-3Jo+njN$Ig~sswgN*2TgkuZ8TG*XHtHIJ<`}Bn| zyr)=cIFlqhGAuKXIjv@Bw3@+<)rQ9;7m52c09L+`i~ zXtg=Z@AlQ?BS5Um>qqk$k;Y7H-LQq@*SA4p?xKPOMb$N0 z1>oi?z_G9G9i?Zv6KHj~bfEUh5ydyxGGhA8M|X4dtY{LbAd%_N1TF8JDE=nNAaeS3 zb6l%r5)=#9Xcd4Ps{kIUBecT#qWBnd6#!cGFHrb{)wiGv8Me*-s#X`KDqa{|49@HNj>nBmAE+R4Ddae1EEDvE4tvyQI4Pfa3|0T$Bn*KJKvlS{>8kX&l*U3=5 zlkMAIn%flXx6>+sv*+3JU-$a!n@P}Gffub6aHEH_PRDySE)^?i+><0-Z+Tej^UU1` z?icq&&(s~iX%%m~`#>V0Xs|sZDTYfEMp4gylQsL3ukHj|g|GP8t3I{%@9=I!w74np z*?*V>TAdp*)&A^C4FB|gsB9$)XHCujzGV`qAhBq2h~05HhPP=rn0!>tc*VZj*(xN^ zYU<|oULUAczoj!)Gj8-u$9-;^K2Sm8N%1gy{Yx?Y(lLJ`R;_+v_i_3_0)m(e7$mJi{ort*hHZyN}!<|5@)gg(AyVA$< zu32&u(bc;%FSXGmP(fnH^M&?eJceIyYWV2Xvk3RP;7*{`@e}tF{nNzqONEW+#QJf4 z`K)CofeI4+y05g`cgFCO``Qt4C$1)!4!RR))%;6-`+^TKJk1(oUG2k!F}(N;lRyQD z8(mi0d&S4_5+w~EQ|2}06%*VEv}zGw-9GRQjc%av6h7@k2!9-G5~v{YrSMjJ;`$iA zuD0>L=&TC;cm`+BkwB}hdAr+h{~5#As~L#sHfa?Ptz-JY_j7#nPQPNC{TxMJo4xf5t*?RlQ=nxkk|Ge(xR>?Q5-fe>D^<2Jd;fSgUpb=-^Hhrlifxxa^Xt#WQZ7C6LkCMg3!)|vc(5gy_kJ_0b6Ztl=w!KNZ>1g|Opy&rGNYuM@R~s}pn7wB)Q=|}xtZAyRFH_y zb6x9^F@)=vjkWFjlg~M7H895t3ADnqi@s=V?4uV>S5b`Bu95S!v1Q{lV?EM`vSh8G zTn5HAW~mT_N`z`CM94&tXFdRha7qM})p&9X(L> z`g}_es33uPW@xR*-dC+S?UfsWRwpS(V@Jw6Y4#&+-CpYCx?cr>3KEz%jNZ04_E4{# zP9=Jd1X>-rutWabr?b;XREMtWRp1IKE4iW zq5jN^2m%!(@YqOFh2e_2pEL@JGd`sr>sJ^+JdZWGht6x-*z+7?kKG?jB+PqUE;R6Y@%9JWx9y@Hg)5o`J z#nmmr%>;o85}3hGlEzHTuQu-6#*IL$$Zvh+H0O-pkr{tWbFESyR~jRTZyx8ptCcw> zlp2(~tu|$ZGHfshr6ir&8?W@qYkpIN3KI5qx#fiBy3@y=qKV4EDdsmtNT3yFs+6Q$ zug@w`eTIrwp@PJqrrz?F(tDgfc7|qA|5@Kf5ZFWPd1J~Bvy?Jh8GWM2U9k-6myz8B zfeI3sU69^u54~6J9q8>wpp~^%*Pp#prZ?y#2vm^3jGL0QA>y9WG~WO>02;OzvKq7` zwI7<7^>cnHiv(I(Gpo*Mw1c(FZTdh3iAysAyi2b*<@E9GLpo*SnPAZmB+!bo{UzsU zrC+7^R8U&jrU(KRBt}#It3s5q*X+l&kXp)_FO%H}w8BiTk~AZ}t#WyLkRVV&0?!*s zx_4u|QfrL)B{>pkg}GlPsqWc@%Af1T3LmH-f#(fHybkB()lxVfm>U=8f+VdA+QGG4 z?z035%$P^lt1RgqIh@A>_k~uQDf8Za%3W-Z?#|{F98V(5$azspC1!)+apwwcER6(lfEl_bf3k9W)sG>-=oXtg!XQ~QacN1XkrRU(6a zCcwNhr0pD_EuFPNC=ryGaVll=G53KISkn`xel5}ZE# z-@S8G^D(asNT8K9m)@D#_Z(^-^U8n<5^*(4XalBbP9MJ|Ep*IWYtAd|A@=+&WuVPQ znd{6Wct7tdM{Vcb02L%KhZsfA1S&{ic0r0QeLd?q z)6={gAc0mmB9u3(aWg&F_~PPt44Sn;i|QO8dbo@-yv?A@fktmJ6C>p{XxBi$x22pQ zP(i{sYLS+6tMNO1ltz6RFJUdbuKq< zpq}QX`No0-S_MwgG*;92wTSW8zuF{y;*p`^{o`)YBU*>lPsJM+W;#9Ue^QG%HQ)K> z71d(0o-3rGAW%U9bEZm?*O$q9%*>qV=OKr0*(da~3;>%VO^-)m7p0<&~W z(x?pM_3#k$y%q_y!f_Mt=Q_QgJB(h@JEunP=bEwol`?+Q`?=Vrw{XZXPVeVBy`KvL z6(s0ATBG-KL5ufuo!-yg2(-fNy^=)l=Q_Qg3j!4+=>1%y_j9|^T8fcP4A!5l&Y>9F zcx>^Qr=q$8cPqZ|GHhscYfRNYd%j`DHY!M9=2*%J7&%QpUTl&ZfmS;yXXes7PpOK9 z@kh_P`o+O{1%V0@|CwboM4vur&R&B?0~=GjP&WdtaE3|}MT&Ha6zN8vFnWejHHuOsR}!I2A!UZ^6e$uu@Qk9kPjW2)JU2z8 zNT*1VAW%VqB09-+2t=evr$~_-fmRgV(I`^nJZmXZq*J6w5U3zQ5uM~JC?Zm%Q=~}r z90|0dc#uYsBBu|E6zLQx5(FwpSjUPYMLI=_+z7Oyc#uYsBBu|E6zLQx5(Fwp;IR>r zBAp^dg1{q)Iesx-Dk4QXMT!K03KE!KSVW3+iWIpKXhqQ-jUq+Peo&-Hr$~_?P(cFo ztcysIPLU!v0<9<>q*0{E>4PFgIz@^EfeI27*GSG6FCs-cMT*=Aw4ykQMv)??4~i5y zC{iQ{dNZ|Cq(~?f_t7X)B(~`-HM#zah!i;}QX~jekf4Z;Mv)??4~i5yC{pA`pcUrU z7m*?dMT!K03KA4~(I`^n^g)p#ogzhoz#d}HDITOzq{vB7q)4Yokswe(0yFcANRfjg zMQ#LISzASsA_ql^1c3??SR+70iX0RvawE_RM?^%5WQr6CB6Xz~UKA-3J-i)IdN)Oi z#5U&K7Lg*2B1M8g1qq7iBvPcvIaU-Y;>O+6xQZfyR@PkJ6e;2qDG~%KNKiz_PLU#~ z4~i5yC{pA`pcU4I5RoDWMT!K03KA62u~VeT>4PFgl+$Ul8-Z3>NkT-5926-M1S&}2 zc_Si44vG}H5oks6pycXGB2wg_NRc2=K?2V-5h-F6DG~%856s4nb3sIk7)6Q%feI3s z30_2s6p9qN5okrx9dC*hIY*ZwMG8fV1c3??6w!gq^%N;mC{pA`pcO@TyeU%T^g)p# zg(5|QKm`ekYb58^7m*@`B1LWlT2UOun<7O{9~3E4DN-Z|dNY+NQX~|L`^Xe265I5a z3OUIsQlwC%ND!zXK@lC9B1KLg6e&_DQshRU73SQQB#IO%6e$t}Do9WqMW#rR(+5S0 z6p9oH0(*!(r|6DMks>ESks^g6MS?&D35w_>*MAX_B84JFZUkCcTSbu~g(5|QKm`eF zhH;7%DHJJkBhU&*gq|51H&ZE6BnWz=mnl*tdPs2}nIc7Eo1#0ABc38fDn*I}feI27 z(UB=qx3ACc|tJq{#UONs%Iz zB1M8g1qph)Pp+vbB1I}iirfgaqG*Clks_xLiWI37DG~&>7yCic9ho9U&VEp&NTo=T zAW%VqB09+x8AYT>rAUz*fmS#oB2uJMq(~5`AVD!8sCP$^B9$UVZUkE4xQPghN)Z-8 z;F#c8Q5;342uq^z)FvVZjUKtZ_FhfmT>a#28c8Ux$_HJZjdY}Ck0B9c8_`b8nvMDN z+dVD8zjW@;%wJ*u%Y^6;4rk^MrkT0ZRl1Av;%i8#n zphOFSRvypaYF{e^u{mP4)A^y(`N56z0~I8&PnP4M-e{4Uuc$I!^aCqxU_}fofo;c8 z_&$LO5;=3e)uz`B627fIkU%SJtt933sppX^U)}1)74E~bYJB`Rvl0bXkHBgS-zU&& z>ra)qPn90d`UdC&6(q1yg4G8SXw^k8%#S@Bn1T;fkigmsRv$>9)r-Z2`NhH`V1!kQ+O*{DsRUNnCc-?Vt6g2w=l&8Wy4+&{q2S6_Mf?# z5gjv{W3F<#?$)1`u)NqFT3-xNDQAhub#GkZkofUQMJ;5_bf*s_P(cEH)BE69wWepi zbROu#`1MJR?!MaKoYR@HO<7z-?FsW&DM+A#MDU?*+S_@qT=(B2&~B@OH%a*74(ut7+;vi$3mbLjtJ!h{CdsfV%js}x=VSAMEwt=x7ZIH5i5bp@*lQo zX9l@f-LMkq1BtpPPH4>^hB{~B_gaNkSXIL60~I7}HEwB%L#8=>EKI7P#%5y7H@AtX3gO z%TJV5i?6KDYV2>I|2l4ow)L!yJ$oJ^e;qbQ>oU@;+G4HjQ2KsZHJe_a9bMHxM+GY| z;GQJOvraknLP0N9zq{2364p8m7sr-UpY`@)er2r$T9wbfO?%rng1vm!k9z*+-EwM+ z-@RDCQC}SuB&?tYv#2*aH`hv_RjC~Nv`a(68Nbw;d~E1dUUdxcW{-aK)loqL zN1AfhB$iZX|4^G{FWyAOvBJ^C8Y+|_FRwDk@00&PS7YxOAIGyHBT$E1Z6%@HR~wZdN#QUAqh`*Hy`#Km`fc z_0gR`A4o4dZP!-PmBF1r1qtjQeU}0KKmx6-JueVjUJw1ro7b)7t7F>}Q^jZ6@An#0B+_R(SJJ!a#Mp5(s zB?$>sFl##IS^qwPR+oJe630>|DI+tDB)Ogww=RDk&mjXl`oPu-LY+lpD%f96(q2Q-zU%t`)7_7^_;&QSj*G3Un6IYYujkMt50UO9%FP}1S%;JX3r%e zrjn1(Yd$9;aUFkXP5}3cAo_)$p)9d^i#}h78 zW2hiu&GNr~(Nz6zR2(mQb0tFs3IBboEJ? z|F@>-GiT4_h4bW4P(flx=T-8pg>?t<}Inpp~^wL&UC$`cK}m z{7cwi1r;R9_gX0j2ijN;&j#dUf__~wO6c#Kr5`FAxZO!j?>H3pUz8eou#0H zM1f2z2}f%=WCQG9utO%?*Ju!aV`ZHJH0ZU02@X2mrH6(nv2Etfki zu(6OEMh2QwK7)0hE{qSjd&NSa6;|Dlq)Ryl>8ZMh^1hjFD5xMY=k7AO$0{3}A*y){ zF4k9%%RYst=dUaTT3M@k9Dm(ik8U)cPtKcKMFojDu}kFAXKZX-v#QjOr3E_a7blJ2 zRTpNr5@3ZjR46B4LVNx5$)UV(k=!aOxZew%7t5Z1+St)*mB>fH{pNbL?EQGo!$m9v zT45C&dOvU1NZ)m~J3nPFt)ha&@4FVt#dAlp38RfHH}X$jdYLEf_?8pZECgC%tsKfC zxVnzsYf3AA@P(&}3KCVe&6l&*iDW*TijxoJZWX=PJYTL4ku3yTVXYj>@b|u){`9pM zf4b9GMFokxSLVpg2S>66-Hl8-drubD(*;!HIj*;`5NL(fb?6t}6Y}Yi6Dx4rwKgg$ zNbs+5a`Q!zZ2T%Clg_g;nRUmuLVQMBKMR3Y)~Y?%zNFUUw&dm)4|Z2kLE>6Ds;G25 zlHHx1i+sGg@Z8~-kdAL?(a%Dl71l?h%y^X_IC}pk@wZX_Dq5{r5-m4P9mR^Y$st>b z2Ia3hia&U%&8Rw9MFoiiha%dmX&u zS*`Kk0V*m;?D;EPp4~c%1(q>>b5LaOI>+7N`?T>LMq3E9!g^Ko%d(`Uj*me*w9==? zsHh-O$SYLNKR$}J*qe!bOzj@(DD&%Vt-;0#76PrTb+BHi>+QI|dy@9<(j*lXB<4p< zkQbeZV$Vc9uQzQgI%dvgTKKpr76PrXG8p}WCoI3?;M$5>$;!bhDoAWC94LQy8^!+c zG_r+yeLTuvZMkWmeR`^eKr5_pMsF-zL-@*^v+ehTr>UqQk$!h?IdBA3&WcV;KCYG7 zsHHD!Pi#rmPmn+>tkgz%in8X{5{g$$to3D@iV6}~U(bAoGoE+X@{At%Jc!SUSZPO+ zYQ3A`*{awt;u-ExjqH`V1dKY#XoYn;B&l}!YHGo+4cHgiTSo~cv0A6^H9syYQnNb)YDNx!dfw;-HGaIv5SpZ{LcCo0zh~!RFKF+SB6BoGMIM*Y!wn{_5D_% zf<&F%m*ioeLQ?R71X|&UNYa<|b@cq_Tk=;kYw9a2WnmAq1hU#`m&;fa2`ef|QtqOj zdh-!Y`MI%mb*veM`^7p>^sPbKntH}j&A8XxIyx#yJP4Lpt8e4kZcz=Y)Z?1EEwDKc z+fmy>pp~^%UB}ka8)j|6XP2q1qk=@Vl9nwjIgTYvHsWw^Th`XMe`&#Yx2$C$&#DlPSI@vaez7 z2}z2Y$98ThZHqVV=cpiowI{3uDo9u>RL}}mJguw!Z1}+1HMAZj(>fP7T1c^8QBlY2 z2NI|t;Wzh!{3(Y?i#4xgA4s4T);FOQllrCfvTJMe4tpA_SdRtkrnI@ROK!bCoc9zf z4Vem*)rVZK$M;gaoubP!t)Fq@?4+o3a;2WE^OEG+D?@ls5!0{ysEmGjZ9U$ZV*02c zfi-_5DPct!eOCK=JbI6nK&$?%F34r_hw=t>9W)cufs+pf7_UPWo$ zAele~35xY6*Zldu52SyZb3rbcJyiI!5~v`7$N&2TTH$=7NKrsJ^?g?__6w~7RIeQ- z)A|4pqxAu-?SnOcXzgxeId$D4FShZ6uZ2LX35k)iXMrgGC~^nQtMXbo_1w>1?BqjV z9Tg<75)oB?zfewne$0!#NU{=WwJ%kSOzSPYvZ#qfYb+|Qv9LC@#)1kG*5g6zI4Z5< zFk>AD3ADna`R`TKSOvhG?G*X9(>jI7*^XJ$X;mhvmilO73+8>emY%ibeEYt)lr?v1 zXZgv&h4w42VtBT;on*{HOuy$GpHE#qp#m#(y^UUK^D?{NlNerieS7)GDy!`|AH?vA zRocmz@0V(|?L%L$Wv^s__yWUL3iYStl);7~y z8M~r>f66S63KE^m|86h4z*WH|bn+p4xr5jDU!~mVNT3x~cA@p!@KtQ!zMbB~YFi1c z!Gf)&Z_ihzQYM$mCD(l(Z0QFQSSyD{cV=E?!|3wzRc0m7s(ao8_A8V-TB9mBlH|Lu zg(83KC)*wc>8K!4KK(xX&nIK}nd2>pxL?4b)V_8_UbU3IQ-u0Kn78=cxNY_z$_m`; zi}8-5{x(c0pE*LVmUohl`^73jRv-V|o~`7oyGAZOWt@%*66l+JXh$~vOJx7!I78c%=e>?3KE#znkp8a&!ui}P?}|_+`&SimGvCV%uA{( z^VencoLfnI2TvLZFrPT5`Oy zmwI7zJGRxky5;JFR;m7)V^8-_3}1As3ytoV!?GIoV@GyrSQQ-=Brr2O#Q>t3s*48o zWPd4{%hJ;?)#7N zb@Yl?L)7f=!`O?qXC0^@fmI%;RcA-4Q`AV7C)Y0)0p8L5+=zVSo0S z;y?w7MV4wFway2rm4?h<8IJi_2(+qEF4&%is$gvIGMs$WaZFap1r7o@fmTw8AG2%XhCj-jPoXsjHRiX;yl(-ktwtLUdG+ z7|_sHyO7mYC+>R$T46Of@w6mX^^Gqeuxbx|EuhiY5TbSseMOL5|A%r@y&0U)d%gaP z@f1$0`Wk)pAgr*?4}BS-(U%e8|E&ZnNPOQ15@>}jG@ts6FFB0w8L(BZZR7g_^k*ed zL4v+PfOf9w<$6(p>6;^x%rt;~5oNiKe2l7&F4JRYIi+VN5RX}qyE(V|nR^252=a?MQ> zR8)|_x^z@`X~j|{y|P2TeR+(9K&xZ-!nK>Nqj-;!#)@LP?jXQ?*~fu z_Y(UQGHknP5raFseQl+;hsvE$YIsi+`ftrPdIS{gO>PHxs~U3UwC zR%buOX;T(a4Zmf^+IE*xnbqr?3$eQG{Zv$tz`AtwRdHB8HLI-x>vExug+Qy@cjjn6 z4vOTH1C2F$zk7w%q}XaK`-J_O%dbb!h#3ZG4?b9#2*O z=u7g;RaE~_Ulu!2R#8C$tNuw+=G%4DqK8_sV?TRZ2()Vc=R)mC_DJraDua>~?d`4R zUE7`=&RJc*~*2H!KUAbW+=FAHlk}&#t0^gtgw? zKSg?|N5+h231?GT2(-$3dzrRmm5t94HTBMU^i>;`nZo?WzEV&@0_*D;wIBwm`?`m+ z*J*B82(;QWVYwEwz{b5qZNQq|gVklJ!`Qt~R}@r`z^Z?gwQR}=_3)brMnCtk5NK5| z(@O2g1oA=E3nl5BXP|m3Llk>kXOn^o5?H;E;y%U3se9{BXF1o+vJhyMq3=q~H_*lx zH8Q^Oy5Jb64xTri9cmJ*pn`<8(qBGpqMD?}vSrd>3xQVAT~}#8_p-J@co2tGJjblTyuVYA{)%kp@HTv?9Hx{)4zm=G#*1rXtvDZ_tnGjCLous$<cIapAu1|J;8V@N_C~9aKr4L0k)-#%rs+@K#qq794|!km zN${fYbVXG}tZO(nAl_>l{r_&+cpp60a++TCX&isl`;3eV5?C{k@(k>rs@GW*$LDJE z7!qjp=h+Qj9a${jmByG?pI-&*KUIq3wMJiKs33tg1L;>OK~wb6U1xIjR6zv^wCePE zjn_)@F{q&tjoJ}6S?_UW20uEuhJp$bSY?p%i$0pDpXnOQ!$1042()TmZI0I!C6;G6 z=u1An?i#Oq6^-E@jUp6OkiaT~6a$DGqi^gM%}@Nj*g~LH!}PIUsv65Lo>$06{=0$t z=%G=(x#v0s6(p>c{hePa2zVaB(dH~og_?^lQMMVT)s zs33ur1*yVnFMr)9VH&?w{=S7ktMt>_czO87^5Gk6k&iQ}`srn}1@k)no-3#zVXX~V zH=(=EK9A!s!&0kASgfw3_8Qe7mcJfh+y}4j?V|S{GKx1@m|2xTK>}+LQuMrcTfJ|M z!Q6XLUJHR%%|Gs_U!h?veaTmme4HrKN*^}epC?@}sG@>|wVI&vwxRxhV0T`Kew~5@ zTJ>oZR<|kn@Y`ZMm%O{I=$kip=6@Eiq@scZRxgyKfnl}vHC`?G>K|%Z2(-F3B5;2n z^6^)Dg3TfmTxr zmQP$vt-4XfXw|IydG!HF<@xRgZB!qw=C!;+x~#gHZHLJz)k1LFKwRL0nIZ8&I)1L1OP*FhwD>Bj=%j1oXlc_YV(9u8( zfmZR6h3%E9(zQf2eB9o=!qIp`ytcga7!?&Hu)ZR_rQTZLXmEC;=3yUeA<(MOovQZX z6=HdZ7~{RR=)=j5Khn+Aau=AWqJl)Pl|S0&=8xr1Sq36PYyIf>t=(9yOa34g6(p=R z4t*wKYh|WSu@Gq0px-$ARH`%j?WR#j(XsRgM-l&W+Oa0|WCjWnSW}TA6F(i| zj@#GmS$>^rA<$~nr{(sYv|`pgt>NQvlWDxiUvc)2)26AYAc2)0DU0>4#oB~|+Y$%A zwGwEBPfnC$t7LKQVr9?7`=6(&s33tAD=D(QDZTg4NAuOcNpT+}&P9|YuZS_d?mTYXXS{4GWu%6$)V|CC!Dc)7x(OA8A)dMuDNz%8foW5e^X3a_0 zS1$&E3KFh8{Y_OL%~+rDjj-`;Empk53X=5AEvGMm#n&m4v}ofV&wAy57vH@ifmT?B z(@LO%gyZMJeC)-6DfmDFtz3OFzmvgMp@PJmOa-{ydq@gCkU%Tf7@9s@qicLsj09S_ z{@=`NkP=}iNVv95BG2qWJBtho5nmzUzR(KmL{bI;AW%Uf>t-si+`< zl|Ch@Z(=>QUQ!!&{!k4Sy<@Ae(kI21cGp#x{?eNLeAz=q1&NIgiO;w_o*%0(Q>)7E zsH6JCv|^d=dRhpyvbHK)^*ZX?Pc2!20X0=rkm#S~llEfmM1FTvb@Fj>S8X-_n3gQ; zj+HpT54}hErhHR;UH!KjZ?zhogZS(FVKRLqtkJjCq9QPT zZ4A|c|C!^VM_+8hOMJExXjPDEnKrr>#527!zQFF9)tEZ!agte|^!{gQU zm**St_+9la1X|53o}|UE3*l?Ucj0;8R@0~6ZOFIL7uaZpwKJ{6wyD+hOnn;iyz~V& zDo9|hPFfRgUQM4;rXhb?#M?rkRe>Uxw80-kc}Z)nV~? z6fgExd+QU#&kl*Bemp;3RUbC50l&4tTSWy4oH6t}$Q@PmbzOaVjwQ0i2hvyrR+7$L ztE^`o;=^~0Va3s(QtH#osSJz7Vh(v{_ zrtiX0K_X3&ByG#u5ME4Fqs>^Vl71{$;q&Rca3s*mT8*|-`-*x2$|tjp^2wlr#94Kp zCXEQ^g#(N);&(QwpwAg1^MbQ|ECgC%eQ!&|OP^dMgr^U};q{OiG3+eQMdBHvEunf(i- z-~)4c&)XL%Px~QCWL(93=vE)7ATfDdM|rwETF~Do&an9-k3AE~V{fSnw z^OO{PU=5yH6eXxUu#m`4Oxa>Bm4RG-LUdG+7)`OOMoowBaap?lwGwEBRf$~I#=jvt zDoCj031X^Jw5i5b2>+h_+AU7=-D)x(6^Q{CbNSyPDmzSoG zNTF3opcS6~Rv)M!@$~FWxzzT^6nr3oR(O@L`oKKfpUQ=@$Nev8hJ|)9i2Ydawb-^2 zcxAw=0aib@5?Iq<%DTVh?w`#p)Hv!^0u>~@{<{q~_Mx-i$bo(1lrp|3*;GL{yLnDkF$DnwpD&1iCQ$u|5XoyGyweCyo48K|TBMKCdTGK_Y2p zyfpOkJ#{pYGl4D~4d@BHFXh^0Ek#})C@GGd?@_2A;jpce6#g_&rS&n8Ko`3TATQZp zCftAu633(M*-UCTGck}r7iLlW8$mhds338^v#WIBgTI*=NT3U|!RcdQe_s1k5GlPQ zxB9y|_wA@4vCU;HNu6q8rc_9v3$uLaON9y&8|Mrr7d*?GiGc*VFk6W}29DM7PW`EY zC7D@j3_-W@cenu+B-pr%XZh9m|C>Np&0~2;zy3jHVxWQq8x8U->zkPvNT6$5z!Sdq z;!ra&P(gxand4dZIx{hlKvxL+Qtv`hbI%|6M8Cc3ROwg91NC>=y&dxK{%x^v11d;d z8az?5{`A94sgOVyJKrFmFvdUy2`OxpbkU)xnYKa#UF>{=yvP^>6(shS87|$5DrqJL z66j**?ti(y|3*;GM7*}2FLRR;@AyfIBj@WJ6(sK8^pQ?}a#v}63?$H{&rhI<}&wvUNTQ59wdooI+^)Zk@7v{m!6R05Z zU`T}9NcOD^x|P4f4M?C1b1EVgZa@Wza{WuCcW3K;(5=Nl0$rF>5vgzk=6tE)7)$Ce zAEfplm~Tc;pn}A8DURImt!}3GK>}TvH%A|1@0PA4Aa?_z{A&~1kJL`KRsUu=XL**5 z)=Ug^oj)Hye1$6igTUWHqRYn-q}P#RDy=US66j*Nb9t7B*G#F9VAmthvfQdJte-vx zDoC*FpIF;fpzkYN27KfZ?Y20;H`xB&@t1vK*^SNnUIiGd0d z`1FEN!VQ=!y!hEDY2BoyqT;~3&w2tCB*G`gNYPazR61t@T{xcC6R04O+%`@sBD|=TpviF3ukoxMo`)c6(pWMizPLG zwK5X}33TN=Q^a~7eo`}Kr$F{L^K29m1};+ucm4I?>?cenTDoETPY3sytJ)0>N66oq*s9r`vvoTOX zBIo%MB+%7*#q*2`Vew|}AE+RK^E3LIvtCqWd3e|3dF;GF`+>rdzjSu6@#6SXFY&KeCnS0H|Kn01jWi!P@ zKEzB6B+!-f8!UXcjo@6yAhi+#1+ zmsxJ*fAs{q*!WRo<6RNm8i5KD4{8pV9?U7JmJq3M0}|+BqgRoQUd_Zn1&Qq;KF%PqzKm{{G<1gt6RFJ@& z)j1RBYIwgFdDN?xnVO@51iPC5%c`x9fdsl9y7VI>l5EYyKm`e$ztqRTJLkL|7u(Gq=}4=I&8Qpo^UgZni5=n(0eWL1L*}BYyNmbMGdQKo>i&+$sc} zFcSk6B#QhS!q?nx?mZ3?==#&}oLl|s$IQe)1&PADqxoOO&BZ_hT@EZ)yp!JnGciy> z;$6Kp{7#nN0*{{ZH_I~$zlAQGheayffC>_?oR07}I!`kb0||8HJim)~8TUkg>H7&+ z^>=f=jNIr`?5Y}N`(ZvSdSsHT=8aF7ZoJFdAdrwSx!A{C#`jnKo`sDF0x$l zW@4a%#81n{(*0>2&BQSN%YtorFGQuvMM zqTwg2eIyVPx0)yZ?hg z*Kh9wJnP}i5U3!Ld~+Ici&S=?)&Cc6KmuJjyMv56>-^um4-!rvr;+uGB{MPbx6p-i zKuQcYZ&jyTn(~*j?(ryFPno-J0fK8Fl{J@MY%Qnq?|K52?8M*IpO5-Ikgu*7U{F|G zkB?t=;Cgzt5B=Nm!os-|RRVW!#a&jH9FFD}REd$aQtc{JM_w^z3RPlYMmEgCX6fW1 zw)!1Qv@hJ6WgZqYwq=)kuH3r7JY$!wyd5tmdjXQnP4Z-KoAeBG`34N*N zTzMjdLmE`1?i3jmD#-u9chees?TMtreryzX#Y^k`ejFNISbYu(q=Ev7^OL zc&LO^4~L2JRQ@b%KyJS3qPp;x z*lur8b*ZhTU=jm~QU5rT!K>Oyt9WGu+w^)vy4kj=34tz_DVo$N;$>{B>g}u2amTzh zV!8u~@$VuHk*e@`H()ud3Co^sBwB2?rRT1Bsst)X;Qfm2hFG``m3vYX0$nUmHDP(G zjWMRZZa~w%x~K#yNZ@^!<96(Iq!-#cn-J*I*F3qQGxfdds1m3kfg=O9hfu*LH1tO! z69QfOBS=185Oz<|t|&ZT@r@Fmm2CIcp-+SXiP}|*3KIBkitPu`>5ULIufJL=c6HBM?XT=^=#mGnz^)vdQmpn?RxF=M*|pZg^wb~Gi>rN2IkUdv0Ju69>rpn`;c z%+PyhJ{sEAlt33=n`}4ThE{YzsYNU@C zYpU4LCf2?xfeI3M=5w55`ARf*x0WUZy0Wf+rH|pb^{JJqWknyAKm`dWxHj3|pBt*s zoo!o~5a^0rQlDfPx*F>-RQe+n{zvQK@cyy8nk9+KtKDVrPQ>%Qr#wJs9q%4$Q6ut;z= z%$)222M8d1eiD6EA__%CZ9S-t2&l;5h>$5mSR z)1N3Ki?*+-NWVG-sQ=D((ivRA@X?{QN}z&->j7&i*YklY&2d!>#S9Z_b}%8(b#Ak@ zG=seb((19c2r;ZrtY=aWoS(ruvE2~sP(w?vIx2w*5(9d5l1>$LG?uD)!6t@lKN^`3 z=&Do1RSI6?Pi_uS#teBrIU4*+I;#XKNMI{)T!v2_LkT--LZFM?uOxO?Bidc9mX)2s z>AQzYpn?P*C$?Y4rh9Tni-9T;(I`{A-8n?9VXlUmqIahd5*yf$Z}=ut{9P-A%yn0G z1zzs^Q0^2sKqXKqyymAk)Mg^dM`L*WCAO1J@7Hq2OZ`n^Ao1jIA?Zoj7~>J#xZ{sJ z`eZK?0$q6gId0gk{D#|0x~T*zNVEzmF45^Dj4^yH3L6srI-3ya(w|pXeG}z(|BO=! z%Ua2lx!J0bCIq_lt$SnjartZX zFqJ?B2{tYjStb!<%`X~m$j5dJG9l1~$Dd^kDIm#Do{vxo%>0ho-t|Q6+T(Jfu~eua zkrhwd1LF0(%ksQOgVh*FplfBPhhm2oQ;ogPqAjw#d7)M+RFJ^0BRI~oX1qpqOC&LREtf+SGB7rV^qs(zH_&;*tSK9S~3KIYN=9X603pUo{NMM@W z;i7h4VVmF=j@X85&zg&;WbbQ3)q0?Ug#In^AL+VW|BZHDA%U)9#WKY>#}H$w?mxOM z&)uW-KByppZ>`zhR8t?zH?9S$r9uK-`kFtrdM$r>s`WmoAc61FIj(B(Z@Em3-f9da z(1oqeag#pQG+2~qrV?zVFR^C;wT3uPJ=V)rI>qMOwX=O<-`a-XnOfhD3KBSz&c1Q1 zXm2>PgjZuAfiC^sc}?F2hGn6yDuD_T_(p(zN1x(ksMN2q34tyg8L+$nYbzR(r}(PG z=x7HiaAX&vJQd-2j4i@;T;$6ed`tML1S&}2Y&|>XE2|i8chN=}NT3VbjeRda%Gyw2 zNGp?4eM_t_1^?-)UcnfT?R2}Kyy4_|ZCrv15}Ov+k=*O`RB4VIaI~Z$*s`4(0||6t zkHPlX`erW+EwmXH{9eg{&4mvx7DtqQYO-cqw6mmFl{#``V~m;QS4dBVFcSh@xYmg6h19E zB*h!=gQ*u!NZdiKRHz_f6Jwom$3DS$KYvzkmQ<|2Rw^XWg(YPBCobwFT}{>qRFJ@R zSu7Xb`tH)4wWb8R^fj;Ct-U-bK16M+&_mtC%=xkExrArQ?s0MAi>J}#+8UmX;mW`E zmAzhR1S&}28Om{UrVf@v+D=kqAb~EQ=X1om6Qjw~*2-=@eNzMFx^WtT3KIBbAlpZH zQjA>tUa%Si33O$RyR_@0Aekk5yb4kYRFJ?g967Gwj%BjD#ds3}T`Nj$7Ece-a?Y~R z>xx8qWx6)%Lj?)Eqq22qmK)>;zs9IBkU$s9GAFXUbjGvYf5Kilcf(OCfeI2hs^Pf! zfb+85)gda8r6^~6+4)z*#;d}~V3r#WM^Ws4e)otR*>1Q>pn^oZB5C5ep^@aVnvreW zlMLC~RvR-Qfi4^kvJ7C2QsfgSwVI=XM3?is#n$^H$pAIq-LQmp^6+8W2pI`<*%jR^ zX7-y--o5V6&Z`#pSIg@QYR3Z=Bw|Wz7SjURD7@S%M!dMNMBdy{JLX8B>uS(4anqS7 z^7@Ukv(dcubL5uuwDSrTBz_N@D|Q|gO`?x0YssvBIm)W?If9B>B9seOJqH*zrztNJFYE!Qe5*(%VyJea#a+~xao>X!RT zJQ-hQ7$c%@#F4(kG@^9z6>eSj#*@;I+VXRqXSww{7Ek)s=*r_Sv9|z|BFXuQrZJF6 zZ58Y0cRHR7{?6uQvS7JO_mfVWR z7U8&A>voaAJX#D?km$dBt6TFm@x*U{^7YHHZySk=wJCuvEG^p!`s5-~+26DtNQ}Ck z?DlG7JgK4P^XfTxE=lZeN}vl{o$Yo1Gng1+H3E;6^eV({n^)MySg>A@jLn3FAo&g$x3KC_G`MWvTWW{jYQi+^B zYf7LC#}DjGJeVSuWBKltvt;(U`1DJK5=gJB?z~0mmgx@)Cy@9>jd>hDu({W>E*T=* zTU0%-AUbBV*T)b-PKyg)Y6L1s=yTp5s`p7;|G<<$m%db=GLDNKUTFj>Nc23kKK)0* z1X6cj8+JT49u~!AZ%hevVT*9wp0P7Ux6c}Z?NhArKl_&!O(5OQ)XvscrJr;ZCw@1L zfyDl(>rHK}63Cta37mEWa~YfO;@Vs${-*QsocpXv9F#{-q& zb+@{9X0@&Ns(7|iEls`PmipT?1`=zQmv?*jEuIv0Qr^0Mc~P2gW~Nl=!qt=dciLmajMxcTO%U#8< zdJv=bD;(!N+EMsyp*=?-fiA2c$BjSHRfuY2S`Q>19vI0dUx*=oLx-|@YFr|4TRZ=3XGy<#t%N7W zF$16oFN&9F3HB~)yqjdzhimvJSB z@hNqA%Xp#96zw_cdd&nr;6^lgIHx$DMJUfsE0@LcEpo?@ivCut9+4kog+iM(0u>|< z9E#>|RgNM3Hx*$-VSa{i+sQPB^m`WHa!E7^UR_2PkK-qr?nQj%647MBSleu+ z+VE_i;LDrFK;nF-rF^3YQRHa-IxI#|sRcqKD^mhpa}$>Fwx^>=kdLyW%C62rq2y!j z`2&@?4-@&GtE0$_{Z83RHQ8#BQ0S0GU|S(^Cu9ZReqj^||5wRrVQHBx{I0D%MWR;PV{8NjpA#BrJQzNp{tz5D*p6@C{m`cJFh1~*R2uUpJ_2rLBg*0Dn4{f z6tQa5jKvshu~ry$&6Ggb)=sPWr@f=d_D0H8J7erx;oeb=KqWA3H6Pj~id<~aHe0Fc zZ&@o?iKa1-__xd&p5@>nrv+s%$YvMU3fK3T66j+2ad?(xkSIC)IIe(aOJQR!)4Ks) zcX(gnxI+Q4!bgL4eV~Fw)^XC_TE4hGOW1ftJFk#H7t2e?vmA%Uv8ey!MMB**+F61M z5?S@oMz5U~uM%=m?UA zgFU5Q+d?Ll)Cg3NsB(C(Tdp1Pr1vl-hSfR)8Fx>+t093d{IY|s%u72)4xiKrRFEhb z_{?o>^Q;&ZzWpHOikcGW!Y@16w`l#X1#1iK?u-f&L##UT)+=I-^;k8-Qy4|Ga~BD8 z;g=mOSIWrtf@hp|cScwKJ$?8wBiI-&HZQLylDvBe=d3gW6(lxUkKw;%#*n*>^0U?r zXgfr3@ziDwkU$rH3&M67Z#7t$*g+#uL1Mx53H*}dG350*CC1F9BZQ%OObK*VaE;*0 z2FDQJead>Dw&wQXzpZeW?l- zw5DJ8Y41O z6)H%u9qoCxJHBzA`c-h6aPh1*Ba8&P^xsFFX(0-)tuz7^BtB0&&*v?WH5Z;d<(TmO zySAPI33TD!TkIN~bVevSS$k8B3KDKDpYmQcLyh(5-0hAKyHtDcj0C!H4>7imZ1p2y zkd?OT1r;PB7k}sXwwg%lw@}`H^e^yHnAg6a+PX-f3$I`{L%;ru@YAZVN}z&7a79aU zJLIE_;>pRvu_R9|#}KEyD_A}5bjd|uyzHqGs34Jb%s;Unm8}>3o{Kh_VM?Hj<=`RV7e^Vt z9_U#2lki>A&UP%-lTePd{u500u>3(7kCm$WOJVk)0JT)8Ai?r!@GOUl@gCJ}+ASfp zkaj$fKo>q!vz&U4{|J39YrPLDNH~|c$PfDwZjABD<$!R^OFI*hKo>sUt8X&|_BO+y z%nq_Q7(9DdBq^=P-eB8H)z{H2y8kZ3XW&j_9QV+6BN=ZKrV^+i!QOehvG?aH&E5&Ob0xJ! zQvzN1)ju0klM#HiZyJFL68NP*8z;VEZzCsY1bct(##RVOW81{=S%lIG`m9z-Zw~YB zuQdV{B#iUdlD0~(e#2Pt{by4GU9*Q-XC(cOm$c`oNq6dz#G|GJ=Gwy2vg6FYa7Z;0 zs33vaL^*E%gGlntOwG}iRVQr(u)b(ra`~86DpZibY@!_3=Xx#D`nX1*f*C~dmpJZV zYz-28(liDVm>ZPMa^9{=&YdkS(f9s70LZ`8i5Mt>eQF&)A+Ka!6nleNMKG) zHXBv97zw;)O6XjWQY3^N90$rHH zk!2<|v=9oGo@~-nWAB{R2P-`hdxCu3O-QPy_3fx2k?p&?OnYHe3)8+GU0Hpw7Gq?y z3W9a1P_Qjan~yYsEZ1 z;*-|8NT3UQR5rJCskIPyNo%Vw8@uuQCdEq12$HQ~;BO3#Q~%x_8_f@S94(casbnB_ zN$?O3_ScRFDoA9ty4ELNk9s|BUeVHfZ{_K(`P!`9jNjK`Qa6*IfQt$7nSRTd6wB z_*sc8Km6}--v9h=-fw@T)Jt6(<-d2CFr=VXb5xKB>72^{=|5dM>#6MKdgeru&}fF% zx=5g_dyzE$?9fQ*wYtX3=kxT=6_x4<*%Q>!Gkm<+$K6(L#&76V!U3f&^QI$e;Z%T^*fsTm|1mq3H2( zCIq^S&kV+1v{T>BLe-*UR00(w*q0srs)~`u7_CO_7xu2yS{Dg);TPF#^{01f`E_%x zzdAmoiCD8&oTRLW>ST8-qsGE`^>5=^EMuvTRQw@@7uR}GRFJsKUCy|;CSFRs;ls|v z4ZSj@vvo}gbX_iSEW>(lywowYB_k@fcq6@PrV*(0D19K~vK%jo?5#D%W?A@tJeTga zH;sXWUH-I;Z71TT)BpIg7@cFDNK^Zm66pGVYeg2jvZK#_tDGrQW|8`rcX>{UEsdBU_fv)cL)?^f8Ig4x8 zYs*S?quzDt;arVCrCMrYMwgfIQj_)VvX$!juglWPMAH~ZygaxlsYn}Tl|}dd z7bV~IrUbeQS6z^imKiUto2u;8T=MC8sqRLNKqc4nxf%Js#7j%=bk0_)8lBHdaXU?8 zAh9MRA!FFDcxk}S?kvW_Z>OXh>81p_oEyYvykpO5%}OXM=-zNArIE(54=T|zQL1j*xz@GBzkK&6^{c*dlH2~wYCgR_-t-isqr&-11+kZ`COnvthag0!Xca2CVD=ZMtq zqA7u{XI-ac^kYP~pwWz&-l?ASHS4(+o_KNGHoWTOj4ki7o`j`mJ*1E|+Nci|ByNpd zo*})8H})mHrmc`36H@|RY?PV7R%{vxi+6{mewVa*V0qaJx(v25Pg2(P>3fEhe-2Bx zjRY!4U}-tdqvua)W?|E|Lf6|O*5c}CamG@8`Ego$x>qAmK|)`T!6_Z(M#HpGAMP|1 zF`|#yW>l>7COR+QJKq>_#-|uba8%x4mE1I3PAsmC`j9{u?kB`?^=-$>VkybE-EpOjhY~T7-CAGt7O9nF)27kdbLA&OV+hbob0_y8!g4SCy3&;XeoS4 zaUORaD!m|9OvxQ1g|=4Kmwdf2L!MYgBTzvCOUw4M7#A)VIIrDnkwDk6N0H)fzZj`! zRb_Qsy?`mQQw6Oas34)QN2TToa{X?m^*HlmmN;cev@|TSjIK^>#>;1>9Ac#rSau}t z-JdIV9~3Q39;2*b$;drhUU*I$^&x?-L+cla!Oqdrjwu zJmQ=wfv%<&tHdJ{7!lykh z^7$~0Km~~@odQL+mQ&K!a`w90R<>JdN}!9a5ER*3PDxwK`S0|_a%8MlbF6LF-^vWF zzUH@{ER;QuYXmAtu=O({TUleA-|c^6ro8UEcD5sdF7^Z<{@pz(`N(9sMRl$BK?Mo6 zc2s1mO^q?ch%RyyPp#%ipbPI^Z2fMizr0)02vm?@Yez-4CRM#Ba@_TQedUI)O$l`2 zapJgbXS>Rzk?HY3f~__c*_u>ITa)_uc^7$^U`n71&o?%wf7MAI`$n6^VXGrWwkB0l z)})q>_Ymh4(w;@Ier$#5?S}F>Yi*7U6(j~U_Ylt))@Y7vnO0x^C72TE!e<|jb0hw; z#X+qec*e06rXpLDDk*DH^=(ytZ7aFLL(`fg@!)G0Q5q5}eVMEDCC{femlyhKHOJpV z7uJuxF|ng^{&0;z1qrs=RAg&XC2dXWENfmitTQFhg{`i^Z7s-h3>^ zr!m2jSDa}*(1p7~v;8vqE|)4b*9cUQsC{&A#<)}QQZIEK*~W^eq^F`bPDBD-xHBfl z`FXsS4tQ$>DoC_=S4i}?&x#TAxU_63XixM=pbPiUWaGqIRb{_(+Vz175;p=oM3=I0 z#(FG!#mk?TY3CIZ=)y57dmFyAnVjB9BTzxYgX<{Tr^Om$bU)lm9(G^5qL4rrj+WV3 zl9?nwo371Yv2`ori~8EUA?8)beCupJvE~u^_5^KSbY|r%;*NFUQWAT!UasOraq#zW z$+kla9`nX?-0u}zkpkbx@Y%CQL=+c+! zc-`x=Z?VDZOcCz=hkF9*i4)P+?I+fy#xcoOJztuyl~E zHNe;$*J#xzxy#DFCNYpO?zUnaUzO^U%dq3AX{pea)gszEmchbLIsKScDpZhQs}`iJ zJrCJ@Vz+{Z%A2~Xr9uK-#bVj+NlOMAX9siH7cxAK=%Ny+AYt4u$5;;sxrAZnk#;5o zy4adRiLG=r#yH=lq9JXsuS%eTgmDKVV~k$ul?}U!`j`;tVk-|NwpP*jron5(Be`Nl zZ3j#|263N1ic`ylNGV^WtX+qUF@DUyCHv&pW`watk#O$zRGeKS)L0MU$OXB1%n-Fy zNT7?&u!>pxT(W%)uAY_`tkkX#RFGKx=Amf2Gb=`&Q|a=x?*Gl!{`Xtx!VxF?T6W`h z*`kHk`=EjZ_I4cC+GCYm-cOr#Mgm>*xwK%~^a{Xmmzl#LA za8F^jcUz53a&2#IW*ZeG*s4I0tu{0sbNk%;T#GyHDaOC<`X6_MQj8Ku4r&2lMkNjJ!xG~-^dbj(Frhg{!3 zkKz2G9x8zf5?Oz1F?yc+BDc+}^>F40#T8)rLwuVwQF=I9dFK`T&qq0>l2#8?@OQCJ zY}L!+l7`y#w7vwdXUq;PZ?l%hUl?dS9=VGaGmKx=L9GWWNMQbA_9arjqK47GJDL#a znrl%`;`Hz{T)X+2I#`GhbVHto)66?UZ>?W!6)9_m4TN*|&Z5 z!VD*!)=3J13KF>MF~>b+Ysj9qb}=E)rO$=E>_?cP##tgNF;GE5`TOq<%C`5W8r)=q zT63%+*8J_`ILWn;wXx>*H>Vo5^gpN)s32ji6R)j+xUqeT!Oy0;pp*&;blvUGWk;!c#bHesnT#*FV13^hAUH6hRy&?H(ay>da;5gazuQ1j3k zmB1Xrn2mVb*r}4s{0GJu!|g^GBF`OA2~?1993Ls|f4$EbgS;MXxLbxQU}Ni!-&dbjt>~r_s2~v`HzYSkcUG@cwz_R= zEjoR!y9t3V{91+e9|@Id`^G*hfeI3z`qw2ky?Pj9^zT}cw%F@yLZA!3x?yiEPnD7#AaB=yU+y_9aI8a7uyZ9yRy4;um>%Z zVy64)(1lrQ*?h_7KD4yuH}(3!3a_&%W zV~jiNV9`P3MwAc0wYInJ=8GcB~p(u6=4mXPfoeYXwWJ*2cspn?SE8RodU(_7PK z-^-g2=+f6bv~PcUrsP|bnq!?Xp8{LAw0#i0apZ0 zP1t*AH?42~x_>HtTi~=xpn?SEwPpJO3=XA(x)oPTg#@~=)j4k9n91~EH+Pjl1qprD z(DLm<==r&wO$c=1v0*EhQ^M#lp@T`yv4ohJmhC~O>_j52S4WMgAYuGFLu;$5*TSgF z+G3J&S2IJXF3e2JzRtWJLU)a6Eh_|OYsDM=%}ssDuD_Tm^GH;8XgX% zlgkz`A<(6-M-i(q`e^(%wH~M-f!S}_{d{s5wRM|jLZC}u^XeNW(eUN{O=^yH>hU6) z#8-+JmDXW<2(d58Hw}ta2~?0UUQx!jnqPf9ZIE}F34yK_9j23I>$VtU444-{?@xW9 z617hSkQ3)0%xh4N4Jt?&?<>Z(y0O1AEf-*ELZC~ZG7csst)XU=ByN zr)-~gbe(@m69QfOn%gyNYDh|Js1i6MSkR@DRH3n>dJOL0^pQ?}ayK52VNMQ)MY~;8 z0+r{>+@!=ieyR(9iOsifscRrliAfA3&Ubc|E`0De#%MLSh9SYdxe0+Toa5lQ4@;^V zp3U%92~?0c9&OL&!n+w`I9ruB_&4@5A<%_0A#B{lAFM6rwPjx~3%r4! zsu8FlVSLIko>v!BS{T;5R8eCffiBE`%f2Oh>~F9>Tt+2OLBjZyVT{qKQzyfKX+=y3 zbYb>e_U5P85W}^}7uBm4v*KYEKI3znu}}0JH_))>%N>x4P{*ep(= z(T1;?J5&M{B#ckt#NY#!3?cU6}Qc<5KH{8Xmnas}eX?NPa2%yT8w9;ZMgM`~mj2 z+ub$-`w|I=u~KV3oGB}>jTM@2jug{R&LP{ZTIy&$fxnA{-L2N*MMjSc_s$jrl_NC^ zi*J}~;|kCJ&lpJb=`$SycZp^5vZ6W!bS|pMqsJ3j*W8svtkD~X`PKg1&OS9rsq{w4V8A!s=0F1@HpvP z7ZoJ3T3R_{awgD~b!1J?M4w>?_%rNCDXq97;G|m;FW_!<)f$hYm6?q zxo5UgA%U(ex=5vd*@&#RQqG2~b5}W+@HpvfjtUZ4*NSo;=S-jrkEWi$V~Z|4-}D43 zNMw~(>4|bC(3N$*DOZ7>z+;HS4d>_m8NHVmP;uwy70*AONGZa>l{0-ai>7kW!Nh2-Bk#3PT6@Lqfs!QESn@m6QCewz+Nb6}wJ@>`_X3D>fSNUQMG?BLc_+Hj##cw6YX)SNnFS`9CMa$hfQ7&)x5bwhHA}kEVWOzPaF8jYQo0%e-fSspQu+rBns(iNcZh zBdByTzbg{x(zk9LL3dW-#p=o2Aytu)UiFtZQ;xK}heD->pRtpvJs+nd(1pi_9gj8(rDg5H=<+w0 z(_+4!&XD@XlA9?u#IjvNMx!-s*W^t$M68;SF_P6>>)ZRc?;`bIA4bu5SF_YT@_1SrztW1d9si+X&Xk{l)9=T(1qt4%Q4c=T`tPz z^-u9}`@N2I5u^N~iM-N=6iH!uA%;a0$5l2YAft;|mtASv@z}Q4QNEOa3bk_#-;W9s zH@DOi*SC%#OV%o-T05eUJTy6!o(=KR5$M7r%Q8A1yC`w%rqbRW%Irr4iKy-8G6H+V z5|N!f99KIaRSK>gMyo7(uRG@G!t;&otv+X|e871;{a)$jejFzR++87_?;c6cEzCY< zSl)D=yr6RsJ&|;NKaM7lxJj0Y3)e=HphZfl`frbvYXwZ8p-(b&1iG*dIj+d1K>1ko zBsxM!(zg}-uG`izV(HycWMrZeV?#(w`Q`5rS|ek&jzAY4S$3V5zA5|l8$>U+shEyq zs&Q2^MVsZpq(XG|@ztfa7i8NtL+F7nrPFcbg+#Z?S4CPWl|9=YyLJFsKFNkW_+~8`ZUq?6_QuHt4bwup z()WLwrK5tx!rkShr*8(33ykKt9!)sI<@vqn)6dR20$tdK?5%$CCwXvUUs~9!fv&BP z=a>*^ZFm zHe}+p`jQ13m#!UUL+U2ENG0=XnNT@Sd|A%0-`|fuZrVK^6(q1l*jJ6SN*YEqYDeeK zX|Jm}5|941lR_@_AZ5oX^+?VvV(4bkiEf+ct0T~b$BFI9F~Zi+wy+od?L0(R4=iEI z5*I1?jUV|mM2T^;pPk|IP7fM+Yh*eqNUSZ`Tq^yKm+_cSv8`ip@S$|!sj)f&U3)B> zOVOvi$jCq?#^3+KDfaEg9ca|wHGXAmjFA)J|2vP1?dj9J($^yW*RQ;@L#L*i{~$eqF5})1W=e(c>wGMZ^XKC(W=!)hK=94he*xGZ;S?1l+zTA!4^${6 zHuK9~DkRW_@22!IP(k9fVIRM-0TGv}&uV{}aEb)F@Qu)4zfuo=Pkxt*r%$W1%eW(u zM+xHQvi+23(I9(0P(i|YoFwhe`8P^9MFL$HF70)jV|!fu)+l=nRFE(pK{GLsKv(9V z{CwU9hs1Nv*<+xB1n$-Gw-!oU;knf8_-Z%1<|p_+Y{Z)Ld4&oRBMo2N>fArf-*w7f zDkRWlER~sa7ZoJ7x2(y}FDddVF4&J^bz;-h8#3`V#fG&}Hn$ z)LvWPy4d6N8oHV9Jv%^Lz{;L;?}G{wBQsa>5!)k0`xZIWTvB=&bQxP+{daw-P(fmC z$ZS5M)&g;uXZ9FKpv!o^nTdf45{=(a;b)3##r_`IV<3Sp<8@;u1}aEYvgyhv`)(7< zv$+9%&5=M?&OIC|NIdK5zz@2-U!3WhJq8l!!roP1Dm<4af0FsR-7E1ATmN^jHFI9! z8HdD>sAK$0i)ZWu;q0YC0$s-YyqOrNAVD{u;_r8v>sG5x_83T@3)f=lYmN#MX+zHP z`R?6wU2hTt33TBKD6=utbzMlD+jEv*njV|JE2kJLfi4^q>0_XRM6t!E`SdQq8SPDC zAb~C%Iq72zDeozrJLpN2>)f~kLjBwAt(Ua!Ni+3tJ%I`mxH3Cu0$ttz?Jb3EsbMAt zDo7Yt6#NeYT?Zn^Nk9DZnITX?!nh{D%(;sMx<(z2klLI&VunBk3FDji|3RSZzHf}Q zc~Y<$0u?0i8w&mLKmuKDNWA3KU2-!WS)zgjehZ?Hfdsnx%!rqY?ii+C1$qL{M0_g3 zb4*X5f&@N=Yr~Gciy>0@q3DV<3U9FPkSw zU8V14VxWQqt`^hBKmuJiiv>#g11m|UZG{RFxc*Kb0||6(DBoI|G>|tF0~I8Uz0&_6 zbS~aO%DmLs48ehd1b$hruLlz7ivCkfx>k3DnHZ=b!A7<4<^A6%;S>pUZEnp;cQyx` ziGd0d_?7wJ2+CE91iB)=-WCILg_((g3KDGO{NGpR`WQ%{YoB+zxY{bxObk?zz^}~p zF_1u4@V15G6{f1&Me%KV#0TtlbbX1`_DPy%hiYm3p9p z#Pkz)GQ1IAukicWZaf`;=8)mfN z>5!NS={UQLqooCY&85jRyolRCW!8Co8wbPHqwz#Iih{*U1##yw`Q* z=VgxX{)8EDmJ8?0aD@k3xeNpE$2+2 zt3`+nKa}+hx0_~k)ww>b#|KA$Qm`K{1&r6vMs=+-kbLY_NqRRW zdkj=?HVS9I^z}djU2~64BDJ=E7vDx^kAVsjI6tS4fdsnBu`iKY+}kAzaoJ;F`{3Mr z&TWMX68f1UY+WSKwa?)JKlJxhscwhtr9uS>oSD+s90_z)w=PM(+KrI>`ecuR3KBS9 zrjLOHx^j1EL_E%Qmc|av9s?C5aNbWJ0||8D8LB5xK?3J5b0*M*=dqr^a|z#I<$PYD zf`opi2+tBE(Dl?Kj@)S3K|DMod+VZt1kOz9>wyHi92X~$(r&{tM$XC}0~I82zDyqj z33RP)kwA(ql-!(5VxWQq&im}U)#!Mdr6(sa4=r9Hn=)yN<`WUDnk@KAs33TBbGkpwHkia{& zp1^ldz5lczFJCqz^~V+<_})lQpn`<^%f4jPt{SAo@@9Ikc7(V(6{1qmEw=1iaq&o@1R3KBT>&6z+Ko|PQ8x>5*z_TxG!(wWF-e%2?Q z+*1i(vWf5|tsc3RnnI#79fd*5>k;=xsbuB{N48GCT=ZbtxY}vq^OjuliF3_}O=b$Y z?$loB_fsGblTt~vXKSH$cYzccu#wd4pnN4%yL=D&Wx_9EVZZWngO5##{nJgP=}2!O zCcuT%jon0?2YL&&zBML8XKx~dx+*&j)Lbxz`s`mT+*l*BIdyL`*L4FqR<5hiBFvku zq2E9%v%iD7G$&`BQpid>Wp|TQ<^@_XhW-2X(}Bq=R$r4Y#|%Bv=)Nux{{(UTgU|$f59=p zl~l^yOqwiH>d`Z~6dmNymR@dbBcX!Cr`~R)_T$ZDaPzi|n76wmt^K<#bt7j)B+yl{ zl|TxW-%Q3g?Zk*CzpUtlB^_v?h1>Zbw<(c=H<3|MU4O(Z?2tKh``z1)ON zWJ9F#-NeaxWoYIvf7)zS437#DHLN|zJ8lz6W;FX2AiNl@;?sfJk`Nt%u9SWP`DC@3 zqz_U`wZ^3!ZG53Mou9f^y4AZe=~Z|u8TZyp`03z81a2$2WZ6Q<>+DQkPTxY#Emywn z%RRj;ojB8vcHA*XLIsKDd76?Qv$v25Hmw*jt%@~ma=Imb_48lp&#{Ii-LQqMj&&F4 zCXJIO zwvuW?T?HYr9@*1iE4d!%#t6%x8uVzKJ01KdkB&eW#%62Johs6;YklarmalcCLc&vS zK(@5qN}6q^EXI3lYdY$1OIqm6Z5@FwtP{s=I#Hc|tm008xs{jk9K~}N>&Kqx$5y6S zzIxJ_JjHeOKqBUH9rC^6Rx<2!Q&y@4b1TuP{NA*>kA;pv7q%PwZemy^8p*y&xp%dS z?ux<^)^eypz7^j>8b>&=7%o25X};@}_Q_)>qk=@Yy4A_3rklzBS@w)*x~K~Mxvv@Z zajUB%&^31m+uJ90GZ{8dA;#^hLWhlLMo%BBFQbA)^TX9hT&K` z`rT1R1&Jl;Rmk;-jbzEwnvCdF*OmrcW-9^jHPI31>iD8E>GWVD;Z&kaJUQ7+4i!gaD94J(!1} zR{K_VBD?w@9*`D6C_b_YvEU&YUKv#=q)rjrdRFckqiR03nwx*VmCF!~EPBJQk z*3}@jhioEm21KO4YPhFM9UUdtqx8M;R3)BJS2CSH^E74b&LzGW*jq zwzq_VZ|my_bonf>CDUf4kPe@e82j3cqMlt=3y-4e$~}+Uks$%8W*chCs30-tt1YoFkV4M>P+K=}5S_K^xL_$Y z&=Kgu60)5(r4^L1ICsEtyz2h0IW6%p5e3emZwXxEfhcN1#hz^PAU$ z=(N!zgb(v7$>Ww+CkJmP6I$3#7~QuzxifkL3Cv?BV2iLU7`w(%fkq3>K3CPX6%rSF zRVR}sY#hAk=wots~G?eqv4Xuipl; zs#_gKR4pA!i+d-KX)zXZy<^o$ymK;<%Ge3pj#ek#X)>w8{?-$pk4&N0%On%t*HT6W ziK&OGlk$_2Nre(hJ$5{vOgk=rKwKQGbOgGvejN8`eJHJTuMA0d&!;OD#v6E+^*(FX zlL}Rp7_J*b>4#JE`J;w{GAc;SiLXgKcPEqg{gj$V{|Tk%_MH-&O#Ln)fv$HfM*b!1 z$#FGC$B&_Oec_7Ipaq{LRFEipu{!zFdp$W=Ln&3o<)PGlT7cBY?T>^C64ntlNxq87 z#CDicD!vZ;>Sf3=sjvGJ9f7VLY1K)Q0_(}CdPg2}lB(lj%Db<>d!F2u9F!}Y}qdEdz*dlBU*JlEK zR(OK^>+3#UTOpAcUY*?YTt_^?YFf_%4K#9K64N$yHIA1GxA!n6?o-DO!@85JaI zeQ+cx4O7T2XZGOAW$d3s8$=wDY>)Zs2z2FrOd zT*Qg&d%uCqUo0@<(#{ZCr^5+x>~TLC6(n|#a3+D1Q^;ywd9GczCWI!3KNjz=_SX^U z8noVt)cU!B{L@x>=DadAgj(O5M#}g0mD7(jC61+1$$XFI!n&JHiJ@@{xz9Hjkmk5v z$3y4>sT99(qMwWk5|suzlVKJqq>@^yC{~Yt;j!YuwJgUIlowt4Qsp^6iO%bHgM3-m zT&84S=q{MVDft&40_O?$Uac#W>&oXYrV3SI$JiJ*wnirWw_XL#?oV;A+$o7Qf zvrHwkNlSr!_DH6>q>!hL+28JN`gsU*T)sj&`qEQ+pzsjZ%AA4oqC!fOv znsTYL5H!g~Mg@s?1Dlhtvo?@oE88)``~G;^Vpyb*6jww>1quE9Ro>#kw8QO*g7b!a zIs#o$NzKXDDH}-7!pe--{(`~O=IbOOK0dFE3KBOqH79jLHjo%=g{WC#Jbj%qTew^P zp@a$&IK#$q%iaXhp7GO#8Yj-^2z1SQ<4s(qCX@P>%G^@?n4z>!@CjjFp7j#W4(561 zMXtQsK*rVVD!k;qNpRu@a;>sLO!nzS`@Skn&lxPE( zuzgb+8}VFh;M0u!4&O*l59lh)ZPkpphixRw+21Q>yOGX=Hk0Zx%6XM%Y!m9(y%Al0 z+d@JGiIaVslhk*qWNRm-RK@Hlb)Hh2o<19?BhZB{!upbP&FJ;*HE2`MCc3sl!hxN; z4_>pDR$~n8?n&EUv86PS=m>OSyRomy9UD-)I9K}O|8aHJVO1?(A3ru0CW?iffCwlc z?3txfk_IX!1`-M?sFZ|(irsxhK}0|h0~Lg`_W=t#u8G}w?ZST7mKUEjzyHp|`hJ+1 zy(iYptUc50x=?ajrvBG@vswi^S>Ir_9IZ>cz`Sl8GOpUl)ItfmUaHY}Ww(J^Nsf>h z6Q!jDRnhfJji!ZR6DV%)0fU$MYN>@1;@WGSs`cQ^`+;y{XKjfRR3)y9?r`f0P2+k( z-D)@GQ32Mh`Kv6Jw!n$gHAK4li6@>+Zwn%5kXq+n$ zR7KZhHJTdlhQN(?RpCL;stR3Wr)%%WmoxN3Gnt34S`&}I3W3I@tGL@$D`m`78|IER z?zoFRH+t2B{j}f7Z2R`&&q8gP>+qed?Etmkb)ORgu`Sl~Lrp9cYRTGfi(_8~vv70b z^grRv)<)Ce>W~QDw1th31|`JNps5lLUGDYa!>fQmP!%2RG@6|D=mDIm#FM|`yC8nADz=h7}e-#K*uhPCN>}v)|PhRHyTTCDb4^Y^@Y&e_dZrwfsf7|^FM9U0H;hTF28&u03ItW{Y2Akn%F1A#j_QchzxQyk zomm-5Q`gAULJ6^Nk4+s5=bhg0*;SVa1XcZd=E#gcrm@-`)xM;CRvep|4oZ%yxS|~xEx<<3`jW4{D9`HoVdjdgKbkx>pX58_E)GN2Rerk>|o>M}6 zA5|U)!ZqCm{w^R%AgGFZ19%5ZMf8?NP2;VWfpX$fSC(}+gAKtw$hbfgrpeD>>)u&% z`erqn#~D+=>C*;owv!3(oDy$iyRoG9nJmUqog3W!8VLQ&bllC%Mj)t)zJEM>r|LLp zfB7yC4=_`xg%WR!0B$Hg^akVidX zXO#Zm4Usl%bDu1h5w6y&*U#O-VQ3?mo$^U&=Tt>oFrMk;;{dygTEo&44~6lZ5_Igs zb6B2Au&JIgRK8p!5L87+YK`WVz6Hz~YX$jQMes`~A&!G-i z!eS?@Z)(dcyP31W2QygbKeJSbnFhBu&EVCZ_EM;Y61y{cu5c0zp-DY{xN5Zz@FoUdC@I#tOAi zLL50?Jev-8R!!n-TXYu)suIR_%}5>zRl9WHPkz}d)Itey2APl>1!SpXfWdd(Gz9hy+R8QmH5Uk~q8=dL@0>FklKnDy_0csI zYN3QUI+sL+z>uTc_`7|T1cIvQ>>ls=IWh?joIc14>z|RSg%aZYd~e$jI58%Z&sml$ z5L88DbZ}n#F$&&wYsej4+9`C`Dztwm=GZHp)m&@(Kl@SN?nZ;_*}ZIc?N-9>5+&YE z>cq^m(pb(Wb+z``#~7$=X3hc{HWmn~qB}I`$r#5%|5^v~1Fkk!sD%_furdC#{g%ajwotVM5RQ76*n#R`B2>6{dMp-St7WO}= zitZtxUotlgdZfiG#qB=`yE2q``m!TC5}L{m98%NJu9*t07j07fQ?3dGRna{JjNXZv z0_%okDXY5QlBtCfbmbmzQCblMSB@N3zOIo4f~x2q0^WS`ZvgE2_mVP!6$-mDln{3T z5(oG~Xr*ULmzPNbK~;1|2-m5{M?y!xZalLJjFQg<5i=0-!U7W>%EoK6BkRkR-CS(BY(V8Rc^Oxtu( zsD%*PM`B>`gp0QB_H6`$s%SmN9mV(<_z`9(_paJbp%zMvoZW>j z^-E)Vm(?_Qml&A&HbXW%-Bci`iq>O|CZa_&O|W@D{LC@64Os#Z2osD%=RmYBxi9W3{rnueJi26gpglxhyu z1%j$*J;oTX;AwE&XqhtJyOu&Nl%Ts#c*9Y<5XfGUs`x$mB~yZ`Xg$UruFWJkapQn8 z@qk957D|XaShFoAK(Nhe#b&`1VV8`m=#Ckl@HamiCYVa{0@+51JYd2);W}>L@0OhU zLB|cu*cK_B6&t9&kKgKOc1@#-Uv#{AG@OgK);=;3-v?FE zx`6)fml@B==O6aPZF*iAl4K-Bj)yS_ipx>YkvKBpk`oE}()=;b^4Q9aa zL7(NC4SEQ5mlE&Rny@ZS(%Ado>ON;_-w4Q!c2rKS!aK*wE-O{h9ZZepYKoK13Yd8abKsp;#;vx`KMb~|C1+rxncr5+Kq^|2*h;`ooUnl19HH$5&`oG@-ScjQ|j=6^%AV zAFiQ2cnxR;jZ-=)M;Urv##yWsN9XPTbY=nTve<1+cYgbgDI3goG3Np5$l2A`6XW6P z!D+v)0?}h>R~B+Ri@kHP<$4#pu;GU?*?U~$Ko4MEKXBMw2hP4QR;Yy%YmCg8Lqryn z?A0``ZyyR<&uL)u5KDoes(-wUSw^o+b_2gR!Kdpw4EE;#=5d?M6>6cxmThKia?LDe z!_+kDYR7_a;9Wl4&srd;>go|=7J3+$jQ@PcQuWhV7_s*bzZzquPzxpM8Fph^Hf6Gp z)@mBdmQ8@`g$2C#JX?XFs>oI*>|fZ)cHo+|MpIJg08JzDD}~th!qcVifIc_$sZDyp z9Hkws(Ql$q3nkuYELrO&yV#C!)n~{Lb%wf2nt|NTNFb<+J~zCrV18fd6VenWuWh1G z3ne}-w`3dSEao~{O(UHTfLY6G!{jaP1%j&RbHl@?9}fVB$F+b5w^pcy5>5@fvzDW> z*d%{7jVc|6!>O#Fd}WM@Ku{HZ(ij8j>jFV58iT)?r9vaSX>F&`*cy$+U^jSI%K-MD zHdm;H613fDG@IQA!`7Bnp-syk0zp+Y1{zn2GKRpekCkB0jqXCMGbL!d!P)k`(Gafx zly`sDLm;S%#&Y8s5C_IUc;Z7o`KFZ+vrP%wZtzt3FM-hho{k&L>>&_TMPrh2Uv2ON z7_&&`M-E#H(b1Hk?FMg4n;Zg-4A=8ZcPs^hs^|zqPX$qG{2mL1 zS|~wx7d4vkArnA5M9V+TwG|1nw@GV0ddPYqu;A@FzF?Q6Pz(LPqPNui?sRYqo4{+> z+6n|!i7l$-&Iq`b-JM@Q-&3I$N>J|%BW2e{fnn$B-11frfuJh7GNsYn+cEAihR_o3{5>2?SLwi7M2( zVmZo)m-T|+>;z|<+DA?))Iy2!`~1pomNPjr9)8y8W0QN~u|QCjgYRCgFQ!pOJb5%2 z>P_omQzfI8j#?-o-rMIh*aJS9b+x(vz)&ElYTWb9+WDA9+3j^kHn#A-w1th|PBR^~ zP=ekQh_i{EW>Bq)fen%ZK~<)i@!GwZM%n#?m>a0IuYwKcPDd@2ptl#I_nJ`)-lo2` z#wQ>URQ0{YUHbsjQ18*i7Ion;967P=WuJ4g!j>fvRQ2omz=JC=jk4QMk&ux%s1npdiSqkE|K#bZqn1=Hx%_>o zZEseEtX%aCQVS)@Z?F7YOBAdnxoRz;1XXR(xl0_=C?nLihcz)*t%=k^33_`a&d;&! zVQtS-Yda;V>Q`dC6oP4#wGXxJ=~XevQ(F|ZP(r+OQdMHB%~MHAP?hDa&C(`JqpY2) zxxt?BVj%9*$ZlL2uqfpBmrX zxe3mB*cJtXs(gYArE8eR-=12BJ$0U1Td0K+^lng$XTTa5IKV4Ut&x6MP@=p&s<+?%83%PZ z4yvtIAgHRmZI%(FX8>xUM0vkbc9SyceFTE4%KMlyLT!8h-@^g5P@=ql-1+BzXSMC& zIH>lb0zp;fePtOzdTO8+N|g8WW%q`Y(Lf-ms=UuHBhB9{UyprPM{V_l#jcAbA`m8(ODp)b0H}o$<^IFpr(5o22n1D?dmm+l z+V*f9R6QA>7D|-+L4RvWxwj+`R8{Up{jG`R9vM&zCCdG|zqP&G>k|m7D)$EewkW`H zQ1vWNk`s&eoAZx2`Q>2qqK zMEN}7Z!e19xI5dZJ}D)rs(hC5x2Gb=WQ6P7Ly`%-sz;wGKhxmeuM1R{ETKfTNm(7H52pv@pp?|3pfkfoVOhP#3pMO zU@yA)kS$~$Pf*%UX{{S_s3ptZ7Rg#~vgN}D8LW|KA1P@=+2s{zYk2{Rwvxp5lk;= zk9s$`zF9lyaUnrz>S+UQ?5eV%SlWoWbGX(*pH0KxR!Ot@&QM7ZBHC=HBIMrxh-;05l? zDJ7CQB?R)#%{`er{*I3G=h5FiS$oW3>xKSE*cSu=o>HYuu-PS)L(kQLRX~-|r77Gb z+MabndKUi175bzINJCP&^W=3KmKjbn4H%kiO=mrtw}E1-Y23+LbOb`oE|u)_EZ7hPk?_ zHwKA9yp{Cu)Cgs|)qX}Tlo)F_fDOSk>Qo<##LAl!VSOZ?ws1RHcqWZcJ2NX(?b8Jd z&rqXzt^~ui(Gkl1S?dG~CA^pQWj&D|(LET`u)Y}r(HoqUwBE}Ef~sg8!!JO$O@S3t zB9z^)<_NWq60iEXu|AkagLJhfHg6LO4aZ?QZcY{ms-m?Azu~nS2n#1fDAj!`<2gTF z*?p{iK5`VF^3#I7#ox;tNAiC%EZGTcE8oo{F^&3s5NO6mC|w&@0BWH`Nz?A^1JY}E zL?CfuTzBYxJ3$#9*-5DFw1%JES&zjbaamH^$J$oIU=fx)eDpg`|Cg>}PgWUAyE!*Z*vfkXK~=52 zfxX2v?iZ+Q868HAflC1qN{-_dPA!zk#*VZxreUyMB?{X3gBjM{*$qz$1Xa=YsL}ko zJsyr@i;6QT;?zP3^Ygt~8%)FERtTmsf3H6*!*`zUo+l7gCARatD(CsCxe>~i3uB>w zNUl_jv!9%|^LS#*JZUTTgF~y$=aU7F`pk&1AK#RCdVVud}B>$ zwkATU6zKufLW#>~UP$|iZdujuJmDt>^9&|aI zpnTly4Aer2p8dW{c9=$hw@L)RF@Tz<6O>*J90Y=@3Y%489!R{qG6#vv_a^e8Sx!o# z$#iIPd7{)6pJJ7534D>au~drVId8RqyTn>cCitZHzfVBo$ClRoWQLRCa61B0y>Htc zL)D(C3%ITQ7rU=G>X*1J5NM5NX^}Nw78jwkX*C__|D{CLon55Xn8vv(s?Tt;W9jXoc(Wt?eoCwrH3B8AFrRA80?+vxK zzp&rWov;_x#smliRnc~XJ8@s9!zJu}>RFEx#&bG`i=)939);hA7t6Ihy@bA<5-qQJ zva{%yw4See0DJL7pvUu^<O2ohV`sUwbGpT3ZKK0%r7 zRu{UIwr5AM9R&Rw!;QR6SPA}qj$fwTKWV~DJ!Y^U*)x!^%5Z~W#R zdVTFYA*t?Y#kXs1fuO3FHBH$*>`TJ()iho`9RQ2)4c5J19jJv8;*^w-dz=^>n1=glvuXRh|Nag@+j3qzAszAwTWNl=Nq~U z1XaCyuFn?Y)9rXjP2ai0-WkT~O~reXNV41(N?wf{Zo327<% z>;ukH^0H@hN+0^vkX6U08(vXOqfQ?ySh3Mr&KqJ0)Itd{jiq@KxDCZLZkY%KRlV(F z#5!Rb_dL{G9gTN{Z2`sF`brz17D}9r>%s;iai|~~iB=5ZlSTQ?Kx6(wkTc=Jh?8{FMoEXUVxA`nzX+l@x!;OYqS6l@=@S_$og67=0@ zG&^^=Ku5=}%Fk7e1%j$*`^S3qwGTKxcTz$fjD&Vh30lW6&hm>rj8BbFYNi?r1Xa;q z3BRd+DM77E3Cfr2MnZo@2|Clml7E~I!SkJE`^;6s-13F4FU!NXcI(pr&Oe5`PJ^YP z&T{&QL}4~T3AVV59#dlyzVmjcLg2xcVp+Fvhd@vj^*C|W;KdXeFxOdLa(|EDSyCdX z)Sjhd4tt$aXOO?A1;GFu4F+c)76_`Mo-_7vZWG}`g0mcQ=8WJWQ{r>8ve~`=LDi== zuUvtmLn-wgk(OpRLXf)>({$1`*Eks_Cx< zf~x3vh35#{8p0b~%c!020sA)mkosev@oj26Uq0rCRDiuiohk9WOZ*op2Y(OWt9pG~ zyz7Axwy2*z0|kPrcFw&aHNyXt_dxY`=Upk`-~A$#CJv(ozn%Km)Fa1lusXcp*A6); zV@!O2S|~w%ZH*@2->>|_h_CW($58@7RbsBbC)R)lW53E?9|r-oP=fl}c&03#;L%}K zvHan2e}SMX`V4V&9x|KPE-aQ;P6-#hzTkq1($z^bS-V8h_eG!j=>&c+-&uBl87cUp zl&DzESV}@#X{36uf#0lnXQfz9PnjVQR7E{!jmCLt4R{h&tbK3d4fL%UJu8uB<9j~z z?_5rw2*%c${o*wvi?vVM_y{GZ#H@-s$qVT%CG#*>r%K-NAH{3saeiY3f~x47)o8wT ze!#CUbCyd6`3Y~3687!$q`sKO>#C~vy3qb2zj3r!PVfj62&$rfFrI)p3xf~rJMf5ht~9>3RF9eNdrnH>eS5(pqXeD3;y74r1a67A)~5#oK~;416Hf~1(*%~D zOHcx0dJF5Klo02&nVNj*OhK`{`Cy#xQTB41K%Avs{n?RkJht4XF23i3uR8L|$4A+% z!@oCb)(PLau2&CckL~{ChTXe`+v&Ej;_LW%RWAJ|R7G}^?f#2vSKd~=es+^cDc=CI;uQ7b>ZJ%&XHc>?=cJ1Q%@I^9OZM4 z70W+P>k6o|j?%`xV;P1Z|wu?;?2Ym7vbM)BMS%kjHIgpU4S zn%@0^rqVV{qmM;rB%1FC;u+ZQzP%fvqZUf^-fk*=!)N8xQYB>1K74Yzv;3`kv_Mdm zSn`9G3>u-o+h~Z1&SZ=MtAV3%(Iji0oNB~6EV4}V)rZIL|FbqbY zA+Ysfg|7Uc?&`oYkT|`^h0mUacZuVQ@Q*YXBp!4M0Y~%zzAf6VPzxmvA1d>fqC?fQ z!Uk3egplR|!4G z>A;hU<&+yM1cIuXySuaIn8vE({g42^(NGoV&M!`vD(N+C*?jz82S3>JG5WUb4$g#3 z-rMsE$(Ae>{~qbp8wsm+BcTM-_|-?FqZUg1_+rUUBHhJFCFWXR;+3#PeYhQ{qxEOG zr(b`Q%>s}eiIk^kmult^Qw}cP!lO}OutYXjP%O`>UZ?k&EE0nII69!Ggcs| z>hZjrk|DnHE<4m+nE}DSd2vLs_Gj@Z9koy*<=G7>9@A)cTqUwQ)Pxiqo$s6+A`nzX zcbznv*|weegWO`d1&`LzI!fyMBNqh1yODai8;b?eDx0J^i`=jT8u~65F|>{E0^&a8kZj86mV< zN}MabEPcb;o;~?btF?Q=gBL|8a?6ndK~>$YaLh*{X{*{ZSZHqYmpI3%_}xcGE#u?! zq?4$cHt&CXAA`HscpmP`l*prnG$=92WS^uUt!=BO@vY}Id(^SEZP$JL1@2}TJqi#As-pD`&uE;ok((`xQ2N=6 zHL;g**=qKcz%D|q#M4OLF5%X=7XGToWWi^k#KdmF(lE?bVL#PpsF^W~+hNK5i>3+$ zRnfi+zfjmZfj`AJI4d+%M=g{vm|C{eFl(yX!ab5Z0<>so^*@mV z%%dZ8-{CAD9MxNh1E56M&^l}pjyUeWdte$X^;&`Bx?=erI0*z*(I^7kad+qdM(DR! zYu`&pEtFVeU59z7Bek9y0TCNv1eeio_vq^&5LC7I^$%$U?k)vyQzIbi4`~Mt&~FcW z$aK^~3HsbHmNTd&xS-!&8pj2Kssg@LWyA65P77C0N^g6v9W2N7_9}(eI%=T=jq1Qt zplSj9yqTbsIyM)gMQDUbO|#DI9H!B0oqEnhK!Gc?!3c=T=WFSFTAH%1xOV@xnDafk zChP{P4wY~|`=l|uhQAHt)Dy;SV+VjOu32`k*g)rctqb!)ALmp)fD! zp(%TZZ*bcImFPNTFigg^@QOaQb<{!$>J#A(*406<5ZBucD~kkGEgWmga_|ktYt=M< z*Yt+t=wD?f>*=V45~6>#-D4mOHted%gKG)|RnaG+(VV?A5bm@dt=z3pRd`mE(79N$ zclfN%j8T2Kd0G!hx|pCG_t6sws-jOC&jkG92qCzJT-vRTj(XnoNsC^1^Sy2`9M`YB zS2Wd83nl1N*J#FgI6-J)vApj~OM#%O;CDuB4nE!GjZ{xxZ;cz&#}#4w+J-u6p#**E zxX+2_I#0nB;q#-71cIt)t;GHF9(dZ~Gbd$DpGG=rp@jH8md|yBs~HhWon(=qDzUcz zH_Qbl;vP%K!^hi zG|~-EpfMc>t;a+tKW3a&7H0u#hVd7}!I@XM%b6km9&qV@BhN-#kAnxBoRmrJZzwb- zjS_SghW99H#)Aj$m{bpZC=gUdqu%hulZ0{bJKR~GYyL`zhoc0YC*sae{sfqf{Z-`U zQ^MSt&WdSn(HHd!gnAgmlA=|FTv5VjUs)WPzE+)WSLr+++^0t#~8%o|lw=U7c*7z!xpH;#AX^@ZY!@M#R2&xjF?%RW*ur??{S=7@{p_WFWZp+!K5z`z0P%S0Jd0 z&H(V_mVkOtGdM!Ao9H5V`jiOV@mgw+X?RAPV;XN))&?D}Ow63rPavp@&b;w%S^Fwb zc?QO$rVP+g3niLNy&+Y?H0It>=jW%aG%yBhd&03n0zp-Du8y}HH&2yTFTgbZeb||~;+p=eWpO|)H1?dvq~jSvmv*!Em`1Tq zB&bTy|F+#EOylzuHH{kEZnJe-91R>|fm$db?%jDt>GL97p?_&95>%x|SFUm%Y_Aeiv5bv6!p>@Z4}pP!){|#M8x`@gz2kJnIlVK%paY^$%t7 zY1cmw--Y@2E!j31QH2KHzF;!JOR+#t+V!-8nou&G$CW7k3;1eGvy zhWf>Vb(pi<_MV}nh|#FC$% zoF@1Tl<4w)0K0~1TntD5L33|a9Q@c?ET{Um69}pbJur}2;4Z*rWh4?ssWai%TxU6a z%~mb7P~z#Qf$S!xapMp1Ha8BwU>djP?3XA(RWwo_V~WCNLUk<1$RlP#3_T^zJ}WCn zPE|GP{>YtJD8)34&9el8s%ZQ^-jCxP2Nsyd%nsLt$bL$Eyjk`>4*&Vy;A-_4_>F0F zYi%HWJwR179um(fN{E5`Gtony*-H4Pff8l|%Ia0gukl!pCn?cTh&3^FS`UGsDjGqF zt5N47;3bYx`ZE`^vE;h~|EMxQadnk3TztAQH6vjzMyubSJWP02lyLob02_*9ZRScJ z%vIChGhiutGSBx{69}rJZx+u&@{5G=*td^%a~Iw@C2IVC8b|)rlBSKZ4WcKr_d}vk zuc%6_?Q{D^f+>132Ucr@x=V?p7t6|V{P1ur$M$-W5RP8P8J~dyK~>aS#@U2YP3KxN z6xO|J$SRiD$s41ySaHB`UdOqYyaqCvb=WXoe`GItwOJ->cU)~z`m6PHFMYgWa`rw} zQnR<57rK*;oi~cVsnlCuVz-mcS?9ygzh&~GrkU)8{b(c_eyXaQ$cDg?*Nu2)_g?b% zsd!dt!Z@yX804+y8En=CU+&(eryQ)^$#&ZNAyK7bW!%HDtinE!U63nzF>5B+3vv(7BON9ujOJP z=cVjmPgaI-*J@_+#Lj7~t3xOf;U``yJ|_o2$Qwi3l4uU70#t0TlJnSv8-gtXqwVQ!R)QJ4f$K`v$*V4s&2!2Z>>vphx z79sq0x9)833%o~f)D+&@!I+(%xRW{5nT$l*$e(;pg+Xw%c)nnvM9y0)RsnB>o;_WS zXk423j-UEH5VrS8;;T|jSV4^)EIwx%mrG2Uz3C1%QEwXe>)4j9?T7VvjoP9Xe|gWh zclH9)L5YHe66>a!vB$%Au)!UsB2g>x32)SJAk;S4FSIDyin?}h&!R_Sd#tN|?R3NM z3O~H3Kjc0;%k$ecWI-LbvwwfbaQ_O;*ust5*}C&HxY6_aY~%HGR%w|U-`*&+guA@# z4=%e;2o_2N6*OnP4sK^#`lvD6H&5N*8!8O|&4uFvK~+ocwP3ktwzHp?qL9!tKF%MF z><62c-RH$d)!D@bDU4N~#UIqvXFJcOu!MbayzSW<>`81ITlQOx5$^rw6o2+lKL{Ou zOR!MFyL$t6w()ir;~tB|nV$#v>Bku}M37F8Er?HH#`R_)p}&4JuMp-5n#C1BZ|E)Q z`Pgl&_N6)e{^`4tUg$P9FnbO^H~zY`qDDG9u}3A|wBN$rV?AM1g8`G zJG>p(_r6M0u*l|(_qc<<|4&W{s(N1Ut7Q9b8|xFU5`E@~OXbrB)-hv0K&W^2<`T)G{-f&0MC&r0%{n zmAAL@fb(&+fLbV#US*Ti*?k8aHcn0Br!=0MpLB=!N%{goRh`W@N?U@GnO-L~2C{|E zP`)J99cF&31Jpu^0PD5V*3rqVx}!?G?Anyi@pOl*kp|H4o`+QQIf>otJ)htD;x8Sl zoy@k@n9nyC4VLN;!Etw}T8_;6t$D&AcX)EQAy5k?O218%{OTpMlNHp6Mw5NUJh+Po zq?gtg2&!s*d!f|y)Hb$CPtDaau;yEHT)}vz0Z|1_W5r9HM|`;*wh`}28; z(<{3t6H?iVzACZ$@_6~0|*2Gl|c@Aw0@JS~N#wN=v?x2YD(PjLlv^X39URkK{Z?G7X+ zu@;ThG}dChJdo%Lll+?lwNPTxx;8zXHYBkbZB?Siw|F~?^{#MYW^yTz?=m@kx+`R5hy+#5S+lAj=u;9q|3)R& z-Wn^nAK?P$r?&uVp@iv>bp;72NvzSIcb>G;Q?B9V0;wBCf~st*Eh>10C6B7Dmi%_o zbvb*AE8a&ZmYkN!AfdCi&ebI5vslg5xASl1P8RMkH>5F83nd08_0>+CvYowdt-g;a z{VGbNx!{gc_TvGcg$tSD_w zBkZGY&f~SN#%l*}Ph~yZs6E`PHQkjnHQnK#TMd9(C~>S_q;^O1WM+0(%~hpJot3WJ zJ)r)q`T{{!G>5oad(}vhg5BV7pGH6}l<>GdQro&>GAn7RmLuP$o?_A84cr_W3j|e( zCAWX+rtEfhhek>Dgp$)T4G!I?-Qb_hK6Fvb@nGK|CEE)Itfb-`lj6V|TFL z4b(A8|He4w{wa5ORHQEuRCRxEvUd5bWS06;eY#hEFI85r^MH|+s=<|n^V(r;w&5ro z&zFoorrq&9nfdDC`S`;{TA!~wnC~ZbJg+M!C=ru9;N}fIpcYE>s(nBkE+?}N-f9|m zO=c>#EBistnrZ?;RWyg_msmw8HL7?(757>|EtF_%uvhzaPcqvWrlxVJ&Sa&+Yj?OX zp|(I!m00o?>$WRnjXfc@(r@#ikwcFU*& z3DqN8(k?|g(##VA>uG>mDB)P?srKcPZ7gA=>dAz?+^Ecz`a`u(zl8rqRrDF+O#)5U zDZB1@fZmA8!n2~pk6-7t;qA7u;t}dQZ#sL0Qi8SpXP>G9K~?n4;#|#Xr&2u06BhV= z6G~3Yls8f%H$>mpt&aN6&r8|LxrzOu=hL^GS}0NHmM<|M{dc;ie}9)VwEHDA6UPrd+x;g$0MHxzdFcDTn*?hvH!m1cIt) z4)H$v%Ca) zp;i0As@!t|K~-tXn#=FAwzK-K>RiqG=RIXeU_a=abeyNXZ7HX}*v?KhiQ;>18p#_j zZ)b(`qd2AUTbbu~6<@D@(4y-J!9s~{nJwfdh1=PomujwJFW*sC+V_L%DJKPjs>ED1 zO#7~kdouuH8m<#opz^%U<(YVITV12j|5=T?o&8PuesKU)AGATRP{M(Clh^p~U<-@X z*|scwP?CNOgwz{}0zp;c`qiYz@0IHD1L4DiBw=NX68eL>${c6+z3-^=^OF{Dlq#(U z!u&qz0zp-D?F@G_D*sSUo*4`kJ)`;eDjns(wVBLKf3mPzxBjiQ95x}1{X7(mX*_IF zN%x?`An-R4*Y_H@^^}j}%}_!4K?1GO915tY^S|!}o>Hh_p+x)$8`&)?jkOF?)6g`o zsN-k7z`S~xKv0#Kt5t;+b*6h$9 z(%HSn0hoquVFlgcOWx3-y^Ua@gt*E%VL(;g!lQ%X%jV7kK~)QrL2leKgC&`c$279f zBB4J7TspVl)Itfms*1Y+OZ0SW8+(I^`3WYh(0=YE@4BDCwu~6_KdZHU=jrJp9}NM` z%Bzg7g_ z_KtvIVZ)ebNDuj}LpD2bd<3T}&>i3PkUO`|X7@@*Ad%@=1;5rE4(}S0YiePNwi zT3l7PY~(OFIbei9P?cqa-g1NOJK5|6bzSsf|2K+P_p$J`b`JB6>L|C%+sii0@Zr^Y zCydG3%eoEr;T_+1k}D6~%WM+WeS;C6AC;IIW8h(h?TlI|A-y!0EzEbb&#`~fIQLCC zGT8@oO;!m6RnhWkH0uk0E7vVX!5)mfr4~vYinf&9FJ!Y~b2W{oxSL<`$VgbQa=JiJ z6@BU&O^nBF#j%DTMBIPEin5!@295VKy&hwEct}$@Fm6ASa>no$^P9^~`umy7F!i0^ zuz93>U+s&xDPI!^s-jN>&nk9!u6$fE4&MGeB9xpGMI$=My?*XxulJ}=*LA{crTT=i zkaFaJKu{HZPdI*ro>%541c28&Js$Y9wtPGGAUk!&mygobls{YNGMne)I4vLUN3FQ5 z98vtC^3oqdIVjQpkfFT$#(viOr&{u&=$p!1e?Qol_fjCJias}7r(Us78EzE}A=aIE z-=I=$$K8k6^4H_}v|FWG`yGdv!_)D6-s#_3kElGhW{5wgapmJd#b#v?w9vH`ER@Iy ztRmNEd8~%c7m4UTIz`)fBFtUgQXr^`J`s)P`}m{E=tUFYqCo@USy3YEbPajb_*~Yn zwwgxgvBipk-URscq>eyP6@6}aeu-tKvfXhKRJztxC^;?di}fYi=h^~xXPa8`AuV<& z55p$G0xjdzLJ7_L2im!H^O?t=weXd>n-#kslVN^C5D2Q8G32_|>)!&rL0e6uL!GtC z>1R`5cBumwEad;D7#-4XT_Uq{ChB_o-5o2G0jX0UDRKxGEQFAAk7=(+1#CxubwBE$ z`Fy3PYbaFeG)N$*>de=J+WDz6bLgX{@q68DWkXRYq&N2F)ItgSjj39nDGIZGs}k#K z#VEd&LLu=<5T_PO48N78tyV$H47BQ+zHi(_B_wew#IN%e2&zh!leA~j6n4GU1SA6b z4pFZ9O@|TMq5SgIwOaO{!uI}}z^`6kt<{+6Smv4uyj$Z<+M1sfHqlolvMM?&M}JNS zy~QI16{QQdOw;DHDr9xXsrw(b5_>9rYK6h;Qh!b@lt?t5qJ86{W6p!r@qAiLM`ie- zFvuJ@K_I9q!hN(>>tD#;Z&B0G+f_?By(0`RER5#kUzuxf*y&hK;$;5pgqb$BMiFx} z4dRr>Z~F!|RvKA^!=UlOf`t-yN_@1=frZQ^NloMBsy520yJ2wHexg87m6$6#wSxqF~>uB9@mDB;*!*xaSw;?)SnW{dAOIp+u~C1MOA! zBKFN+t%+6gUdhcjgu|JNkpe+gv`qLFMA&j!?{x(9I6a-)RN7kb3yN6b&tPub>Q=$; zZAI+S-XOl2-!G_>Sj6(P)HGi7l=D|Tjewz1GkIcX2ixV}i`Yg@FhA7wT5ccwz3g`o zf3#?6e&=C@>_?|5NX(ekU)%p-1Ox@l6fBh3ey?7E-?t*R?uVMj3CCaBEej)H)!Nwt zK~*%jIImr4CZDs3g#WhUPA(}2C0rLSEU0n0h@HEsrZHf6nB1*SButtcCJR3Ry`UcYsGni++ z2$&WYClFNCY{6Z-fK5d#E?Z3_`o9zG$c1pYx+aEG3nkLdc9!NfE@ERrC7j#-Vs)EG zK=gzl9@5cLYJaYfJzf#S4JKMkS6&seqs@YN#~Y@SuYM6rwpNMf$u;=hYvIsm*aSgE z=@|=rq%>@`r!v%5`x|c(tavO8T0fo2sf7|2O+qA}O$syGqV}Q}d^_+VQ^R0J?qq?W zs^G;_ByHD1)-zH~BX(^cKC0<7*ljtJ+v3R$roRfiI!>Ky9{>B7OX^fhj zEb$YC*o*EGEtFVdwoq!gT*u(O+V76uXTeMAg+U0mJNmz2cv{D0anWfiJbM2pmgSd!10yjGv?H}6Eg{M=;lTiZ(@s4BJDQ|ZaS`AqZC4+%%# z3?6@U5?D1h=B0CANERFO+3=%&{6PKZQt-}vwz82w-_-nzWO4Kmi)^S8w~p=Rac03V zszZ0dLWxdU71=DST-K|dT8?Zvmv^We1P8Vm3j|dKyH{c3A&XZrBFJ=?RV(mq!2w+~+s+L~Rr z-N)=tsJW`E|CpDy^2Iy7o-k^mgmq|hj5FBJ_D)wl{cgHD+&XAH%nkb@5LD&-sWIF3 zYd@Q8sphIQtqSbCHVonx1~D2zA({gWG&xsV{gI)E5Y<65HVC_*=aGt?^*w{*zG)CB*jeF6a|qGQ|t7eOk|HBoK{Z z5@U**Px-*DM-GOTmMesqB1(vnPLnn~=DXbSgyT`m1%j&F^9|U%Z`tgYqIxp-O&{{w zD{(cd>O4*@lvty0#KIcwW?rpTAI>oDU+yH2hL0I@1%j&TG}2=)ta8|@JL(wqU)>8l z{_I$|VLY8v3nl7ruFK|l<*@0-s?YH4gTh~J@`K}}rU?X9t$Y7L8rUS4U3;PWJ|*L{ zyl_?kyht9!sf7}>pGU9n?oR&v)kJ7MltaVH09$SMUdy|teLQ;Z`S9l&- z<7A%YJ{b<%ae<&JapZipA(hu~nGBD|bmi1S2|A);Jj3-nyxoWau(`O9)5t6uJ0?bj zrN!Uox;!uVd^A^x@uCEcLc^#@mvcOKy*CubiUd`ityP81iQ2_pKMlwCQDN6<9uC7H zb?q)rEtKdPP@8=Z$!47gPea0gT|S4OqoB@3k)W!d)n7~hW$k6-Ez}6p_djy^iD_e? zX-W#G7D}vc^IJ0BxsSOnQfCw0;&<>*7kr`0VUeJ!E6p!Tb_oZVjh~vU$WtkNPfLG{ z1l-7}g%abIKajE)9%T12)E3q8<4WG7*#t2DAA+iG{FfuG|B%P3|H+jhU(U~22Z7Im zWt>_lLH#+rPq@bno_lT*I0T6VRZ(9Xcl$O@=l7K<&TBal>Tw-+9_$Hn)(cLf@n{^O7}sZgx{w<> z^oN)C9|&=Mln|p0H&o5#<7RuoKOgQ01XVS<`%Efy+{uQ#QKJpBO!xCm^YDAJ#aB4B zP-4T>uhIg8ELJ;I-H9_P*v9*u83vIqR|SHq8dX0d)$-3~M|@+DSo~ruKe%lql&(6% zsf7|Ne&3RI^xDI=UQlB>+qYcCt1cJ~tJ|Cv2&(!Sm@PFo+s8t+YOZoD7xP0s$3c37 zBb-_&k)NlNA{yXr294ARQ*)E4{F)X$=1`HKD)+<{QpA!2%%Y;YKRCuOm`{TMC~kR( zQwt?>ZMRANqjK3@H?`HyPj%+6MooZRPm!Q1y_oS*gGG6)ikX_L@Vwr9-N7JOyf2$m z3nl(Bnk)5*%V&!ws;&0R?B={=$|OkIEfQ4qd1*&!L9+tp<*MfDzm!J2_J%3&{$>iN z7D~7&Zqg|OnYEpv_9YQrAF$ysLf~kINKlpT(j~itPBQz_Pt8>mr>kt>qp8sPpADQ^ zC_&c)G#b0aMQr@}X~3;Tf~x3B2!8F96wBh*hr#6^OE|Sqg06(%{Jdv#cKHf^e>Gyh zKv0#q!VF~8@ALeS0slH~9K5LXP#~ykVo3{Wp=%D?u}IC;UcWlLiIE?y zEV<69g%bAfdP(|i4zjo>YVQ+Se2G;a=?{&*i3C;6ZCPlSefj{qtW|S$Z9p;G`aBR` zEI-Gog%UYyDoJ`-d2D!XwfE_>DT1{-JOTchED}_e_ok}dx#zj8__CU-*>OIsNxNY1 zFFL}hg%YE?Ew;10hzGzlS9_m(! zB1uD2rBZ|vDJ78^A$w+TC1r%rJ?vHX-g}ds&F{KD|NPGN{jbO4^?JUq`@Y`q?s1)S zof9e&)b(W1lS7Bs9)v45v@3PWnI4Wu&mf_;hRVuxn zfIY7i3j}q|irZJ>`}PpDKCV4qO*m6ozJ6;owpVsAs!-xqNl3|{yE0_!w5!jMq`7jF zDWh@vm3)Dqu01=NNbVO)pnSEq=Vxb5jx70&!R1TWGpbO6uH5se%!p@ln zpst%PfzqtL61*O)Wmz;C@=;FhnuPOfEMZik1dUnn=iQN}${xcp*lzVAfuOGIMYE(M z10^_Or1ddbAJ9h0O;5rvCNmjTC?Uo_9FKY^o}Ux(bYiAJP#29G@l~~H-b%xcNf>b~ ziBW|TG^WG*nEV^8)VVSSuP=@j2`b9I##gN)5Y$EU-uc_MRd<$F zcL2&WY6$u5lsF`%I4*yk2mkW4EWM%@_1LT>{y6NDNKlt$Sz|}nj67((Y8oeUqHD5@ z^FcVLZ&joUB|Jjy9B-Kwz^13#-C#t;8F>967?ZO_g1YMI?QwYSwF8!xX-Ab4AVFgF zF#d0@L#j~1u~mgbgl-q){FkMda61ZIPluuV1(Bex=XI{w`yDKVEg!U_I^4E56zq+_ z+B?57s!+l!F3F*9>K^E2rQHqgZ)J|B>POHF1-~9>gu)RWJ!mFJuu8bJF1MH zCi1f3LvTpwV@4H9|Z2 zW^9x1#K+>Vo7WjtC{Y~nr{qXxF)UBj?gp{_KFdj)hT_1YYXU)CIlm*MjKw?;C#BZe2a|Ve zceUf?9hD8raE$GvFse{uOrP=6l*b3)TVw5RaA2UX(zMGk%$pzy1a%E%1=5Gs`=Cao zc2|o{4dOZ5Bd~h!-Ha-fFw9#eb^Uq(OwMTckGqp5C{qvxb{q~H)XLBG(Hx)jNBj))TNfblp31u zg>_T3`^SLTWy+X$!*G73WsEA6sFQd@TJ^XX3M#bSfX{~KDji&hVy)hb1%kT1U#%=B zS1E#_KeRXc4c7UJ{j^xTeQ7463MI-We32Tf`{8h^wnmoqSW^B?jKR;R`7SE*S=5!T zUr!!CeK&Lq*Vf2la#Us0j3Kyc<`_m5N;uBbmoIhM2Q7F7dcGq3?xHfY{b1BRi4zFw zT6xk`PTsr|4i#&wYPBa^QTF^AjGnLj8C588Y^0Iw;aUWJytTZ(8Y7-6%Xm+K%{#pW zg1TsqAJ0yB{apF@AOauccNg*nDdA_(MxOt67qs1`<@KG9{-&f~3B|E5tptL)XpWyw zcXZzm<-L6v4sF^**gH)LG3QR5uBXQ21!G_Rx&lF6bayu285UYqoy3CiR@pD03MFWc zAFnRvn+DyYJ+NVKahDL?D@FJJ@S11WvSCO8-<#2>8B&E3bl((ThdUGm3tM?%lLbu# zg1YG59G)F*XAfiM_~4@|4UsC8@E;!T@UufMBv01z^lLP$?Rf0G5B@X~3F@M|d2~9T zrzh>B>-%GBj3H8m5}TE;2WMt&hx2*b-Fc*6J-N7I0N!;G3F@kI>|)8E@@>2ujdoNq z`c`tEMnSl8SWTn~C016NSMqK44k$gU-JNIN*eKht3dGJ0MS{A5v)W5mGxNZEqIOj4 zZ|{=VEC|7uMtnCmQ7AG0O;stmVD*g&G*;^4oTX3ZQWOaN_I#nhPL=95Y+Xf`EJRz=?-Yq zUpuPO^l&Aml)t4WJ!e#*gxqDl^yT<2Xx~#?RqNA>-wp1DV)dR+1%kTjreBb-8~+B~ zwEOv}vD1~Ori1WV_$@{iN|>xwq}lg&LCdGw{rs`COxbod6jP5}7YOR=?DkFy|CkT& zZ)o>(qboVe`{&`f;xM!2hs6vU!AAd+6pY4R-KeYG3m$MHmt<4AG@jizHg1TBYfk_^Lysv}u7zSy!<~#OlnC~%CCA(-gl)sL`}rN^s**iD7;{7O1%kT79QvZn z8%no7A*dRNIrNlxFs!L;J){84j%aUQYsS7*9D)P!^zT(d4n1{=l_`1{zEMKg1YzUC z1wv*&C1`Fv@1bz^n=(DkA9wwoD-hI0t77ons2abO=(YT9Vo0V?FM|?dM*RAgRnTs8 z5YD(|%4o#{S`UIo7kT!MNoAZpAq0c7>k73KC_!VlJU8kYuYr9y99LKy2n2P}=%P-y zVD)GA*D3;+B$o>@dP>k3H2+QRmRe{!npwUJCOr8CQnXCxF9_6V*eFjR1k?PbgAK4qH5cCR8 z5eVv{(MA4*e7&6I_=aMu@F+$VO3-*Te@l(I&)V&dz(p@31cJI~bdl!)RKCj+vw1h2 ziG3MWC_&@Vyt9L8DNCC-1k0;<2n2P}=pvu1Wv7`Pi^X|$x-zOzg65j&bf#r0gPh@5 zEy!FTs7uUxIS$9zv4Y`vWLG0b6-v--7+&qo<24Hy>)I}qIJpU@;2AkV06t54;VN{_6jd}AJ zNvl{)Xg-}$g%UL8&DW{p*YfP{5jgYSG=ZQl8u{b*^AoGsTZqRkKN1;LC?Q6}zighz zmfDWO(f-i_L0w|zS(j~#*owNN@rS7gqY5Qx78-v`J$H`%JK~L(o8MxzA_%R1LZfoL zQsKUH>~kGI9ASP@s4YSXF&cht!%03mqER`W?&J%VJuD2yn>&s$s!)Q) zy!l(v#zNM$OBi*mJ^k{0HulyaH0*hRQH2sT=FL~=`>td=ensKS1tLLR zG%Ck?1Ewu!D<;HXS)W2i6-v;UH-Dzi$Yi@6W3g?TNKhAz%JC?`o~i6#_HcCnw24uL z5;W$`v%DWhvY3}~So~WgsEbDBc-;@n5yXw;nz)EkX~^+bZY zXjG2ZHVn66Ybz4*XWe;>DwLp^r#ug!q9$|AOu~0%a|MFBgs7aZPphiT(u2qDmQH0< zp#;s$KCJR zV`v>7T4#pW7u{UME|~U5~k?sd8?PnWUQWr6s<&1-?6E*h2NRiG*sv)GFv_Y`CO9xF;VXE7ziu>8X@MiolX*u73y zxt<;?=sp5lRy!^b)J3Cme8*wqpYUl>JcdObWK^L9jotI7CBBaSYTHQEF_EAy8kOT~ zmb@~6)s0cuW?&(s3MFXlp5M=Tj_BUZ(OCMcKp?1#M&)>xMOY(nojwND7aJK>C_!WQ zy!Pidn?s{Z$Dp;ZNKhAz%IS3Fv#*zo%t^+N2Fn>$C_#5!@W@Y_u5wCRGX8X2CJ@v` zqjG%LZ+TzYkXLT)b8WV;gNG7y?+O1tRxFWQZ%DzJylx2nEb5}Wd3gQAvPE*>t5nQf zku2;CqJ+2~r_#r%tW|4I>@dhcs5C_@ThSU){LL$2CX0E>>wc8fK&nte%uYDjVG_&G z_r@th^aX;tXf#WwYjJWMiy!QVkIMCsDwLo(2s~mk$e-o&I*@nLst5#i(P$R$qS6B~RVYDo5O{^A_Zz_ZK@{rE6A9{~(JX#< zZn+c;*2Unbz$c6|QBvKw5!h$bIYt#q&>RH529V+-pK%z08$Xo^1a;A9 z7T=e;c(`miHXgmJ9A#9Y1kFL<&n4#%%j%;ztXutvKu{NrX7QcHZO+N}UysC@Z}u^& zP=e+l@NY1#wi5n19`9}5D-hI0qgnhpaeRHHeQ5$djml$Gp#;rA;JH!Fdn!?*N8-N= z+XRBTXf%tz8`NdWjz*)3B8) zHyF)lRG|dTLEt;Rbu*Qu{CL#=k}VL_MWb1KRqfU+W%kRFm^pX~qY5SHUR#|mxaw-< z)bKcb`*or~P#2A6@j71WS_Q|%qv@HUj4G6%JDGVsnGL&?mrI7D{m3YRpe`EC;!l0v zMar0=BXE>OUnVGI_p-3RTKDk!ab;SkSakMu6$t90(JY;=dE_aj@0nPfU}njvLJ4vI zdFYIrN|tR52FdLNg1Trli(lcY+)-df48B}q$f!aIad&^OLvIwwkHqx7`T{{+G@8XD zShdR)!#k1au;d9)g%V<2gGT-SDvy_k;nW*f1%kS09Swdh@zANWv%}EZdYe!$gA%mT z1Ai0#QC0PZ5KO(jRwPJ`3|fnsuUYP^rtYs4f=))Wg(}VTbH(ZxvF=q_JLkT*d|*?g zwf|^^M_OHw|JO#;VJ%Y`COPHZZ5%(EGY*=kj!3MFW6i%z%wb#Lhlk9l<}5DDs{Q8}K`cxR>b z)Fm8m=jo6tl%TmSylUN)A@Vw1IO+`(3F@LzIsQ!Dak89W8i6mfDi~ELL33MpUSH!f zc}{zty_5GK4uGGdy5ap#;rs;d>NUFvaFl6!w{aPavp^M&6J9@8@n{=^qZ%AwRG|dTZQ)UwOY4;4+$d}izfT~ji$>-68@;qq*%cU#Nk-cl zRVYDoTX;Rob$gXzlOpkU(`^DlT{J4ke9xDcfSF;a>pe>#sEbDBcdiwKMeo`7Q8HnqpFri`=CB&>3`*FMn zcGDod>*FU7)J1Fg^SU^zDyyTm2IAi)u0oZ6O3>O{d{@c>7dg_GS0v3dL0U(YR#T;w zO8M^obLO(gOHb?{-%O}sN(q{;!Qao71i42wFI>8)i9k>ntu@Lk8=20Kg9Ci9<&_3P zEmlg_4(plopS$L@713j}qE)hR!W9IL!855$z5A3{}7O3-`_ozA`e zTxHlV%xi8dcqy){^;CV~yiA3)FoD2{Mqz^;@c_!H=R8q)K8=Y&DY@l)pp-eig*Oe zFIXg~i&lH&YXF(|m6Y@RsjvNhp$;S^#7vG(r(P&)C;6hW$3B6euEN&s<#7|Yz+P7^ zzocusH%h$&zPR(oPDT|<(C#6;7VFqy*e3BRGp!pZ|9$BO9lvY?gZ9DfX{0;&OWVN7 zJ%s6faD!`aw?R_7U_Qq5++mpf=L&-$UzsYDNF3r0Pl~s}TelESq_-M@1J0JQ=p)Gj zL0xYg-64h7QoPYZ8^f$;9QJB?noU>{Ayb7C_UqjtJ%e|v=%tNup;`h4j6KNqRGA?V z)U_kc9TwVegOg3PG5W6^g{vm*W=FfH$yA|)?+167Q)wG)v(v_i2u;L}7q_y86BY;r zb@iU)4q2UfRmcCvaLh@>kd|ASvSF%B6-r$A;tsQZZUx)_#;9>W32i?vV@{iM1cJKe zmAivo2JfL!OFNHhrYU%>N){V)cacmLO4tqW4If;$!X!)WJhDG{dfSXNJ0hRX^T0#Z4O{Q*Qv8p011DqwY#np+v)2H|V`97di%O zV;su}!o>SEu=Gr0nG)3X%iayDY|n*C-L)~k%b{qXr-#E&Hjt@836oqmI59dGrVP-= z=-oI9uWtCnLKnLU1a;Bhv`*KrdlbG&`NV4du@rvolo-3+4bl^GA@IL3%)iCpyTead zs51%#bssQ!J5vRMx|Uvdfp|F&c#kPg=(lmkF_+rmY5VCCb=eGc zfyeLo_Z$$+M8a>r6ZY9^jwKgINmQZ4*+>`2`;Z5PoaSqm=!CPXb-*_B%mjkE&YgFG zZAW>3oKf0Q9lv3Zk-x2wRWy;PLWzZ*&fqj@JFFU_jj^slH*~GAMYCF84pM@;n(cK4 zU!HT9KS3KKbEGwIJPY zYzNob+88sh8Dnw3zW8xRf+JNZk=?WxWL3(CL;sC2YP2!#ThT;Xd3tX;j z2j#ypBH9}v>+Ow?N;WuBg%ZE+A;>BDFe+0!kH^xx`w93}z>WEo_y3q3g zn^?F=AgJqSCwF;P?lxHWM;pV%JWhQWe~N{<&yuM^iSnmza>j>kuuD%HBjMs8b?EV* ztn(vp+0n*L{i_RLJ0>x#x*`h>3?IiIqR-wb!~;Z z;9`NGE;e@d8uw9==jj8kAv)S4SC0RG|d@Z{~65FQ86X)e)Pq$^t=MbB?&k zr}a9-n=VPn$AtW^)VMp?L*krQdjv1ua5Z_LKywu)akr(`l~Yy z8)K_U2ZjH0N*IK@%Iin)|8rMujLN*D^|f~2;VN8x z1ftYME;^70#{Zqiy(g$fjp~3^sv8SLZQ>HoJbH7WYUNc6cQ5=VoH;$)Lp$B%0RA@7 z-bOo*3(p3s3u3BZd0bPODwLr25+1?&Hb`|i^^;Zo*+L+wEBC6K{I5?g`2P3ib)$c* zY7uygy^0tm)B7F0*HW54w`atv>%ZS*flC5}J0~S9Bi-ewz1twiOgoQDp9ZTlZ@*!l zuR99_b%{sSrBbRoKV%AP@p`dLpNcN`=`CL#yA>P^LKuDG;QLs9C#(8l3)rHBY~lHe z5<7pm%kRH$g>{Xzql){Ls9vABiT#V8B@om_&xuzZ@*1Vy@+o4YtdeA^Py#Qx%O4!J z!K!NJ8 zv62mYOo2^RuR!}Io#Y;7)1l<%EwGC=m5(i+4Gj%$f=;KTTC1lAbj8?APenf1QcllZ z0znBn)@yMK`D58KFzBeq+AeA&CtI!p_teUKj5~ums1Z3m(PD$2;^}EDzj(g}b{wzG zpr)~W>hD@Gimk)ivj+0ubsOQ^MFUPuI#6A``ydz>1=Iz42cY*7+UtO?>2Dswa^@xD ztX^(H^;TN3b)dsW$0uJ7gMKZol4oG`->iw}ApB51PN?cg>ovA3vIf7{T`<~IyAK|j z)*kCj>V+FO9FkmrxWc`j?$GaxEe!bW3b_{U(CbrYK!eV(`9>g=#CGO$72{)q?w>u- zhwl;0zutqd*7(Bm&n9r_iVakq8VHR)n*0y(#dkitP%;+Z&B~CJNx6>Go=pYAize{) z`Ub~_fz#l@c@r?czR_{UtZ6XuqctC+>7#azF`p)(SIz>-=)H+Uv$t6=W1k6FR-0t^ z`%M;v?lFNedE@N9+s}fHb2Z|RlZ6`45wTCrza_aV?BuQGUhs9e3GA!oBF`vwgM=6p z2-bIzD|c{*{zJ9%cx%^GO{~kK0J~aAPj9!E$6pDB#z`hH?uM0IgP+I7Q6?~>xwZWL zav(H$ZNrHf9wutgHxHbsGn1%7iLOQ69T#hM? zhQZ@BqVh~bb^ogYm@nl^RG~z8v!?QkrbFT0B<-jc+}BqVe1kD2-&r82YgqTD^81ZL zU{#tn#-i7cmA+$#;PK1|>Fu&_(#u0*VPvKWOf;<|C)7xSkZC4xdQT;JfL{{WSZHIM z@AgLN7Z#1@?nX#dp~QeUHRRh%6X5kEZ48r@Ka|{&5tzNYR3NB}9wGk*ll0UZTSM`e zt+PZGN-W*mM1D~|1TOt|9#5WCS1XkVqxk}npf2&uV+Ir{=MRs9TY;Bm+LY(0*5LbtI*0g9Nbt|@SQ81^+3XO|L5Ex$-6t5TrZ3~h{k%6-La{7{S; zBofp`zgb?tec^T`Iyey<1c_%(&*_Y9k<@zM6!^nugkRfxZBoun8H1sAe&M(oyL;CLR4|WlILRe$uJ9 z8PIi|3Ah~(k}|z!fU?#Enn(LfzB^|?UXC_~*~&hOw=NwYuFsaJLJ5b$M5)oRpYZ=l!etN;LV{TL0xp#`F=GkbIFTecN^VbAkk}W_iBF* zJ>b_}tDXOQ-3>dblYOsE!Yw8XC3;1sL@nPrC0#aT!I^yRs1Du2QFXh#y1^vuP<4Ss6-vzfUREMUX2BgkZ@g2ip(6jioq^Yyi3D}gdE>bsV|1{B zpGQPlPxz~N6w7W^pD#%LXfY(Y{wHtCWjx$ci}l>5$rFDFc3%IblR+egfR z$^36O^DxJ%yJi3!*2b7Tyc=u%IvvwIvLvcdqWnBKem0#6-FrINfP$0 znjz8ipu`5VV#mV#DX``BvB&dr%Mezy(PaZReaYN9@&r>>Qq6f=r zC&6jny}as_UycX!#=`yk{1>xX4-Nz*LE231e!jZRUDmUCEC%lLl&C_9iM`)Dnr|Kl zyY6a7^)c)c)0;jVFIe3d2s`(mNaIRIMrWtQ-qDFaP(tQ83A zqBFv)k?hmQlK5ckW@91D6(v3uG=nj(hk(s1ZHx_29sPqtaE_-)P#2vyoo-NiOYD}| z8(Xav-wo(FwaRe-?=N0Z{zV(3aA6xu_+?8Zt|p#*&w(djy(1=h7f+}`I%2_>j& zQ(ZUcSLO!Z-?cGTCz|7}L??8)Vk^58xPsl(-e57WFKoK*3gzeB;Z7+7_YXF(qiZlM z8R5Z+&kfA6@?9rvv9pOx6-v;zCEf)**#axKWZ0n5B6-9Q7Z{-H3;j1nL%qK)Q0s#S ztgjXgp&2$%>%c%L@r&YPH1oH>ZmtYxAD%B$g%XRJy29c49#AJCf)iKHcfi{Z7{*qe zCJ@wRxXBep7WRh7WG_zaQ#zvQGDrL{pinN~YYiX02LWr821YlWp+mSA>^hYO^l14z zPD@KPd1H@f-=31!cJBpFPkq5?NERf;JHw~U{_rV(63|cL&kWN$;q%Q7c<+iVj6sPX zCC;!u*9*GzPUlBu9N7u8FFWAT>xTq_y66$|Xy4neXg;V5`ai3$j1KMqUq_9Fca8HQ z9qi%nwjnU{-VSiO>i|1UqhRN`EqshBW}UJ0O*b4iy|S{fF+fFjI0O$`2gVWu|Fgk> zXO_W;7M5@~Xc+XYx`Y#M%WV)=bVu)yzcN)Qk@|%}s%0=#o4S+}!^~}Pe~TWt(&C3e zP*>Y82$zNg!1#UhIdQXdcYI`Fjc0C}DckOJgI9AB!Ms9-27B6odC*iaI)4QG>U4vY zok_6d>0wUzcyz}@f30x0MH_`Gl(=PU3!C4J1-9oHCmz@BhU?GT;H$mOgfWKg?FkFM z42Sdcih$0cPS<9IEj}C98BO&X3$sg!ouziL`uR|pd9IL;@y^E<*Wc)j>7k7Tg1YE; z!_T7uKl5EyXne1eQp3v<96L^jR}F4MgIPAfmP~>L7cL01z$@K)cSpC4R=Ds?2Zf$3 zC9cGGhAJ=-zCS4AM`hyM9dDIdVU0iS1cJK6xf)liE54avgOX`4CE{6Y_&jhStnTy! zvI5&dt4(vEr0)mVnA;4d=`9BRymCH9#ICOB`qLWk{bmYPD4{NC2g6+FLgKLZoY-Js zi`({Cqum-12JjGn zd!ZegcJ~#|oD$Wa8bj*8wa{l;9X`gDMIEsD+@83+V9VGoYUmdc+tS@io>_?M&G83}fitek(XuG-FlnHGtmlb0KGN zQ%-zJGDEk9i2eF_DO90Ehj3$kZ((Cj zoIc$czdiB5CrUfT<(L`F3fKWhCv{>gY@5NlhPz?c7#p^5cx$MfwFBZ7S#n}&yT*88 zUSF*A%}k*RCCqKw!jF0dU^~Tz6PCy7;XXGXT(kV6%pb>LpLHSJjB#K)pLPTb^FlBi zVb50GXaQdj?*Z564xISXqCSQ__r`tIzROgh#LTM}@YA>u;wpM_qLQZ}e!IpyDaZd1 z2jJhvrFgARk4NwpF(inf!bVcuZ_{k{^+H5Ql<(ezWg?W$jU`fdwDNTw47>) z)0X?;u>(g1g1T^&4UBUygwv~>IFS}+h%+QV+`U$nsX~cAlWky(TOph+(unufYhjdr zAR4)^lc_?97mmE=)6+e0qE~NDJp5vSsjdC-zT0Ynpsu@vY$3dMAtb$bjVAk_~%tfy!gw8L3R1;4|X}(W5t~O@O4!}y@@iJ8?@!O^wFkK;B zsihs2OA`ZZRql@_x-5a9F7c>Vt*C}?ibHVKn_1GMU7g^|;@vPh(~phqXb*Ml3gD7m ze@2g%N6EI;M3)*t_;6h{;XEjDtce}`jxK=h1^xI@IT_T#_r-yj1ttPPUG$uEI`2VM zaAAW`3|utdk;Vs%J$XQbSHny08Nle#@_j5h`e-;c7-6nNt@%C;qg=s^O_?A!uCVwc+F1nxy8#wrRnP9xcCrDAmwv zNeIg7Y2iF5ksHO}tKkkf6dS;g>X}P*WW1Nqwgrm>g1YEA@v6Y~)i6j6!F~%{3mw4d z5sE#kMn~yk{p3*0yxtM0LJ9FadR5lp;$GocXLp1^P#5iw#iM=8{<4G(;aK=_n9w1Y_QA2KT3qe8+S4;8kdY8@NIN}>G02%26Iq9( zB;E@G7*!}iyFT)F&Z0?de-Q7T$!n}rg1R;c-5q)FY~~n|g1divGur)_Z?MXp1H$Q=(F0ps!w>>pjjZ>*8XNCwJNNHzMO7q{YXCqdgnub%j66*ox5{gnd*g1W?`Ix(V_bZS-_wo8s-w975+s_XD9uWdTU9>tBzYi{$EqfTJVa|dmp%*gk4jec7Zpj{g9^uj2d9zS_s_!P+* z7sp|fRS}FTwCW5UTc_J~Zlk>V{W!d|B2pNG5@H3KywU6A1z*SE&NCuGU1BHY$zuj7 zJ)S0`_Z@ekZ+LR@MoId77$*K6{6C$>XU~XHzN}Bib*=1@0Mt~YS<>C_lFQbE;QAtlecgOba{D7g$Ip@ccV+P-Ps!#z_4f2L7F>Pe zzDwZTWqrdYd6A|2zvc=f-4)vFu)FFL;DRvXs%yawL1hiW3^|7pMQ=ii@S`# z&HMEPg%UeTYs%p<#o%qAWxbRhELYr?L}C7v^)RASTe*L$BCu0KSae!@xy^yyuwwim zb|kc&?DS_hl<(5UcwAOh9pNw#ZI$nDkg^UG5)RorPSFu2%GcxJN+!`qBFvKjI8>i z^tO(~NB8Fmb47_7%v_$IwHs^#w7F`z>Ai9_JPOA?;44pLcBzZbv`*KdlD_)(P%!R2 zUKwcCEzK&W^Ts3952~x4Wx>3MaSfm@nv*ILy3^IwDmQ~MVzL2Hg%UIemRAcsSY2(! z^RK?wsw)uGMf0-w`+1Oonrj(=kI!1jo9A_tcf2crprYQa*}I+k~DmEDigUl0EV z2h~@-aTg>Z^H~ z!H7k71%kThH_LMeH`G__dwS!AIh7T&D;Bb@bs?k#+Oec*E##}p9^l28SmaQ1`TW@e zFnH9BkC9zqsMK=-h2-XZJ@2nHt=2_jF?_{b_!hN^3e88&^g6?T6EPA%}R8xOn3>|bvAgJq5QybYib0;+D z=FW*V9`)4DV|?*mUsYeM*|2&8TgZ(bZiks?+i~K_ zBO~>_9^bpvw6j7LN@T`0l82WTK;=u?y6A~_&DAF{Za9ZmgQ5g=joD=?C;D%PVeQ*; zVtr0y^?QW}p8M5aII64{X0qF?9dIVuQaD2XORU{kwa)H~qc^uv=#fyuL2e`8FerfH zXl(^D*T25HU{ik#dS@gM)J1bwwW|$pmiD~AQo5TVmdmn9mx6R;Is%r&e%avXVRVY!`+gO&@Z-Yf&OgM37y|LQS-4$Ee_7({0qTdaV zV0|@FTSdFzQa@LPDwJSrOynntc@RHITiLeBH&(B1amA!vP69z);&)yf%vH>>!`Q|H z6q+4tG_tweWbOti3#tDZKZX8Qn&`jdN*y=e7H``1S7^R5B|P*@ z#9CB+b`)-^I zCk#Kp?|Dt-v`UMi#uzQG<`C3X^=o5;cTV+Es6vTu)q9M!@BJMVzoP?XE62w#McbZI!0pwsNn(iID8CK-i3~vPsKih=(IEFQ~Pw z3z!NE79Zin@-E%grC+UZV_-XlDwKG2w~L(qd@SG?EhZeOn!ppR?nsv1sCS9+h+|~#AZ2b@z)_gfQBs<94&W6LN`Rm~N)Q)n%fMIa> z)M8FNjI>sF{_BBB)j!KSr=a}%lP?VP%7O<@OkOZQ01lp?|35@+V;eQKA&;L&{gLTs zQDRFl$X7cBLndeuclUWVYIat4vTWQMY(G<0jycPwJpW>unHQYnI~;E;_JFAv0iO!3%X7bHV#Sj?yP(W@)JmUMrjWId0>YK^)nPW7)y zfo{{l>jBSjA+u2At&<&2PK6$Q7V{HNU1g^Q%TdC1(z2tay zCS<%C19YaRT)!yIpPmH?p$qt#A8L4A`C2v@ak`g66-v-q=kK-MUn$E@hG8ws!2&^D zt>b@5wFl0ElhQUmM%#iaYK5LZ+Kd^fP=yk7*7;nWGEfcndZBqrgg{W2-6lhMcKz9q zvPI=%G`(Z2K3(C0BX9Iqs6q+x`v^YMMjg&KG-afE3IuhDJHtNK>Z~4Y-4z@6>7h`C z65^fnPHcDeQ#&gxs<0La>Y}^Scy>asOr@%4BF;z(RC;6tN{1TG0Ye-E^xHf;XRVah zWG-ZE(elW?zTK)=#K$3oM=DgI1pQ`twVqE06>s;UcxLxFfuOFVd1cb%#`B@u!mWG^ zyCHX!V|601=s~hV6-v-=mhY+l^G<2XW82RiCI|#|EnNCVvb(T=@3@iq7>U)YtJTeY z(O`LkLKRBTZ24w(-k6|Jg%b4FqtiXum!;gEHxeHiX9@&$of*DLI+eQ^dgp0*mJv1b75Q~6`r2hG zRG|d@_3-^_s;t1wXgpkRwm?wV)f%Uy$g#_SZI<{L;T{i^n!Fl&i)Ygns!)RddiXVQ z?*}EUbufnQo+c2~)$00NX~T{cFt*cGK8D;-U%hnS8=qWFQK&)*`s?8<+wq2KrzB4_ zHXbDq)V23?HTkvEO6cnLmXEPyx{3O`nls*e9@z^uJ3#_LUGzPX z_uv_4scvxThK*A^h4(>9h;KzrXW6J`$z5<<6%T=+F1ja{*Ryo>R-9&x#g!#}g*Z;h z+9au{{@A2&@ph&*4EqmfP=EKb{h8RTaQtN5?y)*NZ&V|fWBw6)${mSfr{bnahR5R z6DUDlHnUbrJM>P#{ign$xL@w5kM`okdizl2k8V7U z`m)oJ64bT9X0h~r_(_-)qOA^QwC|-{8k~-=Yq>a5g%ZQ2x=CekPQ&L18gam4kh0=_ z8eR*VB2j|6%AU@b(w$C%Y|1!cdeud_-Z>rjrIt!mp+x#;Cn@9jX>cB`5wllBDH%~| z_|Vi#rUZ4Ze3va*Ek6On^?PvQ;8%CWbH{j0_&rLd3MIVmIZAVyo`wq+8ey||h;m`o zIIR3McrQOps+}*EOrV1q{4X~4{{5}bDn`p!ph*wG> z6_Zzd5(w&wSTRFdYjFhXJ=Rv$DmnTo=AFi&)212?&4LiqTNKZS3DwJ?G>LN|;sKSF^jX2SG&=jT1 z$3&dx;x7=?)$~%P^tWX(d>mbq6aS)zD!VEtVLQDjg({S&*{Q2!%xeQI`&WY#CM7eJ zUL8ka*Q6AIpspuHSOMuG3MCdB_mG0u6+w$?8c|R? zN!i3Z3CwviTOg?GOI?tHZteis`my4X}&}E+d;oca$TfRo23MCAynAsg`oeLhdG-7#~ zf&92l5~kR%6A0>RmEOxPwIBx`%-qZgn_i2R;dY7GXtp))l=uIU+)btjrFGddobNPD zi2Ukw<_l&jWgU6^yuF2>P=ZFudCr8_0%e3#5(ahD7YOQFn}1PCG(QZ6ceFYaN4ic| z>fl&hv-%%Ug%b37%zufe7AiiW$!OAbpFmI-Dy33s!4X)gYVlg%tW2d%pA<~nycwuM z33>(R^>+s^R*dc^bf-isMPGkQE0c(m5*`vV3zW?C}fO3>>u-_Pl}T+vTU z#)z7?B}!0NCu>EjcI+s8+sTtzb#;nnE0*pl_=7(;Q-u=rdd%PG_vR>}2a*s^jS&dy zx-{^RG`jgwaKEj^?jHZlRx+lK#lF{O%2c5Qy@Km>RZ~|h4+_TM>U;YIg1T6xV(DO& zBe1uXH|$lrsNO zn0C}&p$aAF6`VgU)!L;PP3LO>JYqr#>N2~wOUg|yg4+h#j*;Bo87t{tykBz4smh~2GScmM9`tPFcG3g=f}rBH^Y3+G;z~vco?89-`yvIy~;R+DwLq_yS&a_lTJ#NMPu-y?HqxiE+xrFO8>PCdQ{ckYs(HL zDmA7h;HdDq3RNgU-*`ypsuoJ%cbidR>J0`C47v^^$L}1(h&6h zK3|~4Lg|2!$$?5Z{DX@G63J4BT%bYEe5rjN+&-+uIgg$*QLDN+V}J7?g({Q~W2sG+Hc)4J^~Ga{{RM)$wx#N1%N{$y zFI9O+&R2Cmw@*2Ji`S~=4X)3>)! zs6q*vuc6bmGSE}qyhE`0$7%vWUEhQBW$-@$TLx**4BM^s)xp+*cz9}6g({Sw`5HW` zKTD@dn?rF~^ZPO-sLQ%qE!p750r)%Bk&m%vbyYQPV=y`|yCYMD67+h^-|nXURt$E9 zzAHmxBXGrtD1o3Z zpNhKj``-uP;k`b5jO(2$srC38*}36^WU5etUXS@6Ug?XHcsvpt)IBdzg1W>?Y{zH+ zRX$c9gj+02C8|(DytZ5Ht56#HMdC|cjy)x)i`H@D&sSN7>cvh2@R`?QnPxQ6{5yIt z;UP#11NDA~0G#ILBjiR=g67HbN(d%3)Mr0~@Qsy`Ku{MwLjFY7rK&nAXCP+8I7n2X z1kJzX)vU~P>aum=n4dn~o)Xk0p81{P?@I3G2y8Xrtxy?{5;Xsk*Ya-sPWh2B822>@ z2KrglMYDAI-Ff(HZHK~9^i(nU9E~rEN(6$sX!bAvAG|+`RYZ@* zB@ZVnp&c9?fAaV6Ek=KU)&zWCJlpZ`Wcw>rp#(ib-n+)QD(jJyiYXlj3j}rfc^q^&F{lL2 zs@m$u*FhF6d{HtwS01lWg%WfQdHuw`HQB2wW3h})6A0?^F;*P5`0RttQ-AX_Pq3_T ztiE?5whFDPbm=g>=fuB!-O$K}(OK}`zpCf9+!IhbN?TjH`Y9a-)trD)JWG!%l%O-h zYt{^@1g6F5=qmRR2?VANpGE(vAj0p-=C?U>OzZ13LZ>v=Fi=QqK)HTMS zvYp4HePGjHn_b`OZ`sJkd>7r4tw49qtr>0!HobSj+_B+|?il0iKKDMcc}F90yW@0W zXBZ{uu03AWvG^?uUOpJdzYZ1%>MF#>Fb0c34c1nj(}KUVxk?0r>~3a5?w@bnBqiiW>89^CtT0FHmt?rKeE|6}=i;RqGAWU5et?$qVIojzBvi4_re?{s&8psvD> zb)b&zL009(0$4L>htC&n-x9?r!8J85Y$y8xE8$sc>wOM z(w;J6Kj@*ei{QY=%25_Cs4|NjX5#|9>ZVP0yfKu}k7i9Q(dI;pi%wWp=>@M^f_ zT@e0i`C6t5CFtIF{v=~k8Bg(!h3n7#76|HkIQf9=!nCJ85B(ZgJ~#l^Rn$_b zLJ7L}oxi18*2a}tei+}(R3NB})>QaEuFg9y$M65+x0#i_QYobf5v8H~oP#7;*&-wq zqFrd)o9vOYitLcxeXe8gy=C*U_ul-@_515}zW?=jyk5`FeXVny>zw!deGG=*m1?q& zA3L%ql^ZM77LdT|1v0YcP8~L7eS22ot-C^?3oAXy$o{lrwEv5dtmr{;irJ)?KZ^OP zGD3)4putHaSjg1d1QjII=X}uSGqmXZNY>=+PK7|%`Vj`=Xk#J^uIf7p#6G)0L*@); z=i??4RFJ@@S)N^Xo~HjC$^NYIQwVhN*1wD)ahy0gbeC;!yI2gvtlzdo-3KIA<%MtRWEA)tA zBnyn$Y(fHE|IK=DtU662D=+)#ZM=Ly6OM$kdEs?ADoEhdENlE$yg_TeAI|J{^;QUU z^;`4GxLd|v{%EDoi+-E(A9WZtjKvvd5<2xK8$r=dq*MARl@DD@!1L!N$j9MwUw&8 zq4dmPmQ?l|M+FIdn&n7l%13IPK8OvwQCUL*U0P9b()3ROso7co=KSx487ua&7dv>; zK|=)z^*L|brYc*-JG18pjS7J-tb}4P^mt*(qHFlFCc!>R#S9#@9{<$+kE8ib+cK-Sl;vNH#S<5LA%B9z)L1ciluk zY>s9f$TEdMSL&lP#?e(luV6Rcm_JoE1+BU>j4~YN#Ng_9d^vYO^X zK?3_2xzEq}8MGi}42uZfV?qL5uT$q4)7u;;xsCNWnGbiDQmtb=>rvf;qk;tXN;0OX z#B5sjS^_&{KU5*m)g^z9(P`N+Qoe>BCv$CdCcP3B$5ImKa8!`MUP*p!&z?)$%k2K^ zCATXCx;p#JGUlZoC662Fy-(l1+4OCIT$QPMilc%A_AxRO$zlyX@HUz?ee_!)(AD3k z!1!f1Cz+k}-p6yFpo7xG*_C0{G*pnlUP<;Php*7qH-@pwKU@?7UDGZV8Kc(7O!nMb zvW;S{pXjwF16bE>R6_*`?3Ls-uUC?}l#Y#z!peWLhLCqdwp{aK^J{ijD*Pd#)*Y z-I6V~?y3;z!g_=<#_Kzy?lxmsnkmgdhbeBb7=haxOfvGp*Wx3|n2E zC<+o-HAa51ob{sFy@S{1iI?~=xD5$ev%AI)FT1?zXs9|4-*;P?n_WX0{bz8q3R_@s|-zM_3oWDB7v?g zLG6tpuTPTW&-EUz*sdUIX_mw;m#k()1qtlOEp6T-nGNyjW92F$6=ab(b<^5@9izN25$y$X#*H;H`V~&gjyl1QTa84(~=#y6Q3_NWg99+Chscj_pnI4fcbmbp9?Nnb@yhdLQ6(q3dlhwZ)lx5d0bz|K+}gtPBmdnjiYiI!8R8Uu1n*qBD60_Y!lyvybKb2^TP{szB{#iL?sg<@ zA2N9#Pd!OW*3qA+#igpyNAW3a%i`?{fi8TSW%bsBPsxCFsmwZjx$@K^ardV1_Rc;< zZno2VhJb+;X=~e5_NU`ug+LefF)}i9$0HKjB8_dW=&bZUNI0b)@%HgQO$>Q@5BIc6 z1?oF9l|8??Ug_b`g?*(Q`?R=EJjSK54p}z}Q9tXzGIth|=Wf^(NCZ#5*`e_!Aj+{@ftzlg6>f@dK3_ zbV#Tb%-S`%McZEtW)@nEhCL3hhGH)v$5$zPX+Jq5{9|{Nh6)n6t|}ul+vL!j?xWef z8v_*rUD!*=Z?#nu=%SA?EN5m<4HYDCT~)3@t{FggY)@c$nVt%PF6<@boaIYPS}`$^ zO*+(2Lj?(3!IbMC{vXMP@5yXHcxi<|7xoge9)NE&NqV2kZeD)EQ9%ONSmnBN$_Vm4 zKaDMm*{l%g!d^no6is|;{Og|1Vlx(VRFD|>iFt0Wdzu9M>;09b*Dw;;Hl5A9(NiJN zg}sD~PDp)Z%-EUE9QN3ARFK#`rG}^DnbX92x87fc%om2y|gDA$L+fch%VHV=_B7+f}KChy+%9l>0RFs7wy~C9!61 zy%YjnSnW}->NwT7cXA@z9ym;?1BrxMIkNxYgS2<5%tdZBM;np5$hbObExEb+5_ukI zGR7WUM;d*8PDWWAFgCStZ8pJ-p} z18rj$$ZC|Bq!8$`>-Em)wrv@C+egm^yt~_s9c>}xI0~!M5#P$R<3+oR@q^Ih6)n6!+@;y@~1vKkZol7 z9lI+8y4q*kkZX%)l4HI%WgGV_T-dHqSC%}ZjfM&m>fQr(kuBMVqfJ>$4|jz?7w+F6 z=Mxj`MMST5%<94W5G#e2tkHb2n zvgp{o2lFboMj_BOvaFgQ!Tu~q1&MAJ#rds~V~KsML6Yb@ z^t)z}If$9}=L&(Y4wZ`Y`&vA4^wQhddi;*|-Zqr23V6X$LE>ruE2h&uClCk!fs%-6 zbWST@Y9u>;>zYEKE3e`elgEQ}Qk30Z66Rm?wGJebJ-ueoP(k8%i`AwUXQvR$g##q< z=g}(7B`Sv1y7Ph~fv(_7t4yr_WO85bhAC?m_n)BI`zEkKoy%#cAfYAoG0mtjgILtm z+sOPBqJ?T>S^d}FITGmdI@#Maa_%&;;u13cJ{@x`ql88MjAx&B~ue zS_{36W1hu$!$Ya;Q+Nr5Kv&(P(O&V6Gs&%udK+W9mn5`dDl^TLZGeKr-wltvKgr_= zeyq2#vHPgr#-8uR=@;K*)*+{gh6)l62L~G6&1aB* zM*VtBU2aDYXi4l(*S{PIbdB#a&{!v9nymYxUvuwCL+KL-S*tj=yoL%AgRbQmd!3s? zzMR$D2sE2OD?XNU$Y(xqB+&I{VUBTN&}6b~sNTlK+pB4%YtgL2hT^|^H2So3i@x%@(J<6NinwEBnrW{Jy0*SALEI0=lYL9{=lopu4?6tkKsLI^C5{RbPCx39 zP3Gam;kw>mwel#z$o~GU$FFS)fv%3umLw)=I9WGJuf227r3w@I-C6$f?Hm;(aF-~# z`dX(JODpQaJg>}C2z24zRdS@CWY2o`Z^ycq8n5hXg@n3)l*gflEYG4fn>)%+A<%_8 zYRNf(N_K3@H($1EWo3>#WZ`~Z>aQx1UxOvY1Tg#Yb(J=dPVUHodyhhm4sx4EP z<;S^7UxEbgEGhH6?2FMdFH>0f&AkeNF6{XX24n3BoW17z2aSqi{6)m*rA9C3V|*hqslxlmr5e+X-^jX+g%xpB7qgt+vJm zmq!7uP(k8-{1?+Gqm0Z9(IYbt|Guwf)Cgk@vtKJYKj^{?C3(#&Uej!IMlhaHLdirz z;#cMOCRzT6SaLlw^IOzoZD7$bR<0;kA<%`HR&rbtdQ)2%Kb+MZG+xQ5Lc*!oE7Rv5 z8hPQM$6uWdc&3%}AIhfGC{PG=Vg8rgL)z(%_U@zH!KLW|B{K|(O@p7B9&O>I`x-s| z>S4|+?Ll}5dusk%A<%`HZwAA};0N0HhQnB*>pPAL5`8;9G6iRvh?kqbnz3roNA3FL zK`ggvRV615U6{cqBZL+`*G_C6%(|PbluSJ&+#B36@y`26ovnHV#L-fJv~|b(F^};c z3V|-nM3iUu_eZU)(*Txb)>_FpMB-EbTc+x(cabaeYRNWclqe~7mgvp2y4@85U6@fR z*C2!cXw#1MWp&d6mCQ*b{&^Oe7M$EhEU)UTWLBliiecxvG5%(-LZAyXLk))LW+g;I zsa`C%#|R|@6p79;_e|n%9;rFpAlq>3UrNlb*n@TY5v>sD!VFjWeSY(e_GL;x)_Y{S zlF5q1lv)Q&EyX%=`0{f(((mu_KhzH)#kve`Jo5k&8qV z+Xbea#Ip#7aSnq>s21iCPDT3*2!&9tYk(X9RHy4l2ZJ2$YMo!2a_n)QI9CviZ z4SeKXAZxl=eu$BTg-;p!K}OJhTRT=m1qpBKAmb-l?X9YpUhOTvM?-4sIfe~%8LSZK zdN66AF|5Wc@-8%15(lP?rdIc2*tVY$8Y)OQonK>IVKIl)KCHK~CUpvJ-zA34-rZXv z&=ruCV;p>D8tG&oCy7H%^XS^hQLJ55u!af}MYXOP|4x}sevY3fi7DZ`>Gme!%;Q3P zg+N!mMc0id+D{_hjpHTZ+w(e&y)cAr?a^671&N*Sijlh~CX#_;^!lQYMn9&87lYZ! zi>?ZRF5~{z9i8Y)QK>R+4GcsrH^tktWxCXF*=acg_C zbxo`l0$qNQb;!lS2r|lUtR#j_tI4$3PR!4xj)n>nxHGXFmmIWY2h%#RCL>EI1iIAS znlmdpu>(g58+h=GviC9)>Yl~1rQ~MYH@sMGnd=IHF5D?v*6jClVEL`vvcMACmA$ZW zogb1hJ>f$|+|TU3f3Z{ExEt>6>Fi+0RYom1~X!&P>Vg^A?xr;67n& z-*+p8Ko{QAvTDTr9kl(+(QM1vI?BC^1kSL@8W0V0sH4nj=w;DFA<%`-rmU-Wdm_F5 zHI4=6J1Wm05;#*RBhSu+(esW8%(zx&fI<&|F6?7us`1p}CQ$KpyYZzOP~N$!_A ztdw~DtS>v_KjUQuiDQwW@sO?TtmvB}TU5*$#z37uMOAu^(?-SP55GR@%i=-T58% zyvMakxtj63KHJrjuvTmQl{HA*1>Vt6g^aE~ll-_Tu;jgL1jBmu|P$u_Qz+(r{bC@V_NPzZG4)s$aF*JjbV6-Kf5 zUl(YoAQ6_*$7uI^38_|FZ)5bE+4T3sa2DHpu|l9ry-QYisjuxUHqX*a(nGvm$o1POFuEnXS16@81x*r&4M!>$ulknk(GSePXv z8k2VFGmw$f%V^iirLv!^7Agd~uokb}<8a1pzP3^to5K?bDoD&}aHh~tMrOJ`)gv>@ zo0ZdU%t~dae}6S1fiA4YYcQl%xW_-nq_Md%nMPEQ82{l|;V2nln%_c?*y?evyjE;k zDjVLqoCyhZVJ%*{%UHRGyyNgR*1qQo6DmlYcQ{n&AtPmvt<@vXjy*Nk{`#e|E!$l= z66nHOyzm#g+Le9;+0>J z{5jtlmde~NY~!dP(b#%_VTz1gE~=r=^;xg2u6Zm;W{W4kR0wooEnZp0WB&(!;hQ9m zmex=~B5-3tVM$rbrcJUQfjwu6rPgX(B5T{iNg>dMwRq(hOXoj4`*I?4Xy>V+f`ob3 z9fg@Y4-$_iGC3)G*pmC`*76zkE}c#-BNGE;dln|ycf&-u4gL*y6iTc z^=>CC56}13>sc0Q6{-2E80Io$xrPc7<5#vZ{*?8Q1CHr!oJ(jy$3Kr^S59Us1iJjb zbuflxts^y$=xy|RJ(i|?9?dSuda0-&@gp$9*!uoPGI9GeNu(Jnk`766Y(SH24XYUA zSqQmbT_h6)mRd~$}x*_{4Jj$v0aGZg||_=c0CzR}I; zfyYrSw#5n!6(sQZm_%;WPB)BZNfj;;RFJ?5(J~IXXpc5)awOY0e40X_ z3)jEo7_Qr9t&0}TT4atRs33tAqGd#5x&4~Q(nvP1%3~uE=)(0cgJJEUty0*tUG_QlzZt@L_-n6(q3Uv)l{9L(}fZ zM6hMG8*(Jjh3j8(=C1ort=iTo)@%Xgs33tAq78;4eGX~neMYk~I~OPfx^VqV?)%zn zw^n;uB#Yda%~3%DD@4oh+WSYfA8*5%sqa~ZKo_om$=DBVpElGO!QPtR;HV&h6{6+W z#DvpY?&cA4KS(nT33TE5mweY|2<=x&I5Us0uAzbiR*06dA9Js0)2r1SL3KCc$TF$VHzoX6nJCIc} zAFmMT!u2otRx99g4Rt8n+JBmc3KCc$TE^+$-lk=pkgH^-xe9?UT>p}lZe8bSb0fmp zx#f#BRFJ?5(XziPK2G~mb2R(WEmI-Th3j83Ui4^l?QBF8%XyWpp@M{3ZJJIs*N&Hs zVMF{?0$sTNC1ZrG=J0Zr<5<~KSsE%x;5%4GA>A&=(?mQQSa-2PpbOW(42I92%}JId z-c?zwp@IaywG9U6sk2CoT)T@NF;^kbh3j83$7E%By7O!-n>k^Dh6)n+)|PSlS`!+! zFqY+fo2d}!!u2n?cg>JkT5n3Eto}VmLj?)^j+Ret$r;pPegvCcI9Vakh3jAPJ=lLU z?fGUnYb_>gs33v!0dj4E9H8$ygt34PV-*5jxc()x;&p~aQ5Q-wQ|Vsp=+{6E6(n$eMt(8&++tkDRA=R0wq8`j?DhF>_{v9(uCkX*D%ekZ66! zn{25YLh{e)^Cdg~G-s#ox-o~AW(t9>`Lzi7I(r}q9JERjzpVoJf`CM}fA0|5amI|o za#s(L^S4LQ+y_+(Lw_D3OMZ`{I7=b(=o?n#yZn>bW5-^Kf&^yT$ovoUK%TuXnN5so zp%Cc8Sqj;UHo9e+n4iL0{jNt*K>{;|42Ig-{dm}hR5q{1UxEa>aF#;OS*|NGjgwiX zr-$7qs33uvPx2dQLJ)s`JB`(OyHX+0g|ig$sa<%-^ms@*8=f(dpn?QuaLIjsE)V2C z$EGvG-iiu=E}W&1YukqVrV}^P+4vQ^jHn=inP>*X^fiO|zN~aMtLK73B+!Mk6b3`d zKMze|_tM!_$0;UMkid*OnHB$cC{G)f&L)3z;7FhgXDQ@7^@1lREhC-X>)(T;f&^v; z8Vv5=hI8^HjYZB{q7dl9SqfR7;oJ+;9z!}id~Xv+1qsY>lrxZFQT+G2RJOd?Q-wem z&Qju+hkvFsdy-k#s~#FE zNMJo%nW^VBiNCs@$O5B!D+Ic5mO`E@UWz}InXJKWhH9uFf%R-kU>(K$my z1qrOIYcRAsK8I|QGc0>2FH{J0;Vgxm_wlJfJyPP>r+srYRFJ^h$Z}649~WvrA%;C` zHeVsog|ifL_S_UltDTKxn`Y0{P(cFgR?FILH|2c$_fah2)og`87k;bDcdhRhdLwH% znV(KMx$ds4`p*MPgMwXsdE68FW#YZiVb2N@1|*}Ab~mKGPAhBTN*f{ zAIqtx66nI5NV#g6R*KE8+Jku}M`@@aft5F8E?JQ|3%}Tzy^a~B5a`03NO{ejE!ou9 zK5S>^Kn)cn)G8iDR`%?`3&P5m>!T3p!kkDs@AJ0_i$2(ro&4ERLj{ShydFu(Swy-| z)ME$NpKQ)XPi)T0igpTtuHYy3q)Uf46S)4tMibb45Q{;k1m^3CfvS)Wy(?;kXq zbZ_ump=I=E?-Ws3y*fQUeFtgNpasAEd>nC1JWqV>TJRxGiRAjI^W?SBjW4+tM?M@o zF5B2zK*jo@4s712M%n>i2i|?{9CEDEdxHCyJ{{G7yVaRR7Q4QZM7`HuqFXg*_GIs0 zj(bJp9@54=-h5j0K+i1RWs zU@GONw7#TY^<|Qsbx<$_o>HS4z3|pYueLqrEGY$ z!j;5%kd?fGtv1Apyw_{B2J@$w!Z+9BhURNY`EvF&=3_lRJ7X>R{?CrSJY&N%)~q5~ zZFItHQ=;f(5v+ajufyAxwd20W){?D1?dVM(JMI~fLu$OSqf;8%@*#e!iOE?fdVNV1 z=eIxRl~^3N3$o)Cr{<7t&+O>GP&>Z(XAW_=YeyqPY`M$l)nuN9PL%xEK>V84irL2d zYhzwm@`mHqlgl$L>5kyKJiOLMvU8#xJ?m%1`RY8f;Ip+P9RG6?p$0Fu{*kYS3KDf} z>+)o;jl_F`zHZ?Ew!T<2fUttHehPsunr+P=$802{Wz~F{&$--NG@93d-3+1H)5CSS z&!Y|G_hdV|=a&^<`h6W~w%C$ZZfe7eHf$jA({$q7qPAl55gWEJ+Dk(PiTanVdBdc2 zWbA57Nz{MZU7R(qz}z-9(XK71%gemYC5yIN(vk0M_!yTBBy^4)Rf(sOoy4X5>a62= zHw_ge+;eUCoRJ$y)0z6OYLe4lbSlirMAY?hNt$< zC2=N8I=x&yUZPVTIhJWh@z=_k)RnomSMBwR7wfjnrYYH9I1=dkrP=Tq zJ9EgZvw9oJH=@PYPb=x+k>xd1khmt>m?7KP_y2ADY!WFx9NtE~{+3Y)bm5hid3R~y zqO6Ue-Imr=t~nA#E$Z>3)_LS)wtgIGW?{nf=w;gFw0f7I3$MS7{aBMGmInKg;~Nfe z`vg1wH!GKnId4Zh#@X@PG8+2gIXfx_+4AtdYstP3`jL-(nJOCe+ep^+JI>K{yt5r2 z-(el;aqxeM=QmQstA8KJm+qH2{x2k|`rC2uz;&dw(2palW{T*0raCoWa8x1Ch1W@r z`j#e%+EGpE*0Il&D~LprrybW;t|RXI^)^;jOcY&8bf#r@zE=oz;r%9OKPse(n=dPC z$;AdJy(spaqdVF0N+CI<*DJk^dre1*1|62CO2F%j#{U%hzwk zHQ#eFi_FWeBZ=Wd{6vJ&N*rpeDo7-+x8gS{W|G65_0{llyV{AVTdYLL9!85kSn(Dz zf~N12N_6BkD_+uJ8R`43iqf9Ug6Qch?*6nANv~WK1&Pm_thmdAAS@UyG7m`Nz$|;UIk-kR1w_Im&{;|2p zSdlWPqSyI~@5QT&5jN8l0$riPhTmH;kJw$*e^mwQFTQ-PAYxBt&_f<}JX+>Q z{8(?GJto!T4?oNy-5wSDpX2zN>?g`PRTiE_vlRu2L+5Sy&$M~uM2_A@|F-Q#d_q;x zz-OjHpiBK#_bc}jJnpkL=HFu4tjK{kdN7>~D*8+&J$2-?_cU_$-FvcVnLUpjI*V*g z(PIr-^$Zi8_vCAZwP(_1u1&bb<_V)Tprn?(wNE<6izr0*ChPVJwmb?=l)k5zZ(-}jFvzw6y2 zUX7f2!uj!}W}SOv*O8_&f;yGFEq+V3kr)>v_8*GYE~i9OR1{)WGyWqmh15^fE9sQx zvBFR)L_6{(Tp@OWYkRw9{L}FiGBN3fBz8o{2_Ne~O{^PEQ9)wHyk>m9eF|}%q_?qr zT!M(sFluft11Ty>Oip{g6s35U(f-B#!E{?3;a7q%Ptx`m_ zcfEP=QAdS97yd#yhwPXvR=wN6MS?3u1&P?cEx297F~la}oNObpW|F8frigD@OcVlL z>XA=BlPW%k&Ltl^JtnQky7My4BFMkNf>;l7=jL`1WWx|aqPMiBl25qU8-1Kd$_U5*|N%!BN6e%jX#_mO(wrSD%%(~B2{#`7+RPV zP(>loh1W^8(KtzTtK5UqDTB!PF;EH+;u(Df(Eoj0BnLGE}l%3no8b>+!oC zibab*_B(0k=kpFAfv#JRz4?3=OvZoHiR+<5#gYLp>7m<}yumNRKTPOHj(5u@M^Xv5 zeA=JPwOmcS9SDCnD~JUA(dQY)uL%{cc0HtppGt95kO*-h{Mn%(vhnH~NmO+2CtB<+ z&1SfVDKir|8?n6~(h-K4w)|7@UiJAs=c&i zn-^trbRA1!e7{XEa?gAoQHgemexj124f{Sjhogdo9cA1vyceljOwZJFt>PylxeeRw zyHX+0wXJ3w9$dN`>9TQ}B%Ct5MU1U8d+;oan+~_(r_;L-*Wc+R!lw-%^tB7=Rg_M? zxV7aoFLxq~&*^!0S(m&-xLGsyJTQ}^g2aP>w*1McPNef1J*%x3j2T z%*f9F8gD`ciNG>Gytu58)-|lTByKNt79sVGEaL3nLL|_&ySxvddd8PT4%6Fc(x91e z7}APW?AVmIeA1S$-r`3bo^&PYXWMe?G(TC1t0Tc*E9c?*G!?cU-mFbP9gYeTYK4t4 zhNfc03P}Y1QH~s4cuWR^ot3NTCTsR59^1+f|7^|g(XM36@pLlePitOgeHYTlltk1F zo{T9jA}Y_59b7quW1dg9W^MWWm;NLsc?b!PZ_9@a^e1op^gGcm!bMy>>d7ikp2Sf> z;+$_=eq*6OnJ9Z}`8Ei35$#@kvL((@3V|*>hjMNyrkU`2ZZV zKr)3aCcDN^{)zP_LvQOD(ieNXi;v@)vtNB4a#WDG--{k!OWdqEX1@uqoGc7EI!jx*-?3)R{4lGa|LLR3>`Y5Sa`f&~6r znR##RE$pW^VZW{JC6OxcafNv*P1_A*_G_tnl69U*-oyaQAkU+yTJ~HKo{Qm zGP~xBQ4IETV)JU3)$ZGR@L4^>$>qBRWOPeUUe!39m}=w`=c%5&dQlj8*GP_u3<>j% zqT?AS=0D9$Lj{SwM?LwsHKAnOiY=13*v?0^zFLoY%NX^bt{P79v= zG=Z?#Bcw&18+Tk5Loy=t?6WFmm}ndA$Q)9uYN#MFV5%#(wv8vF$stL&)McX4Xh-(s zTV;hnmqmaZZ}T^X#LGSJy=9d+NqNjemFeZzQXG5c%=&uzYN#MV%31Lfe^<&HDHSDgdAPG+V_LF;$^P1z97|p=dmYI< zY@w|D;5wCzxx3y%JR9S}s!wjGtYG2F53V7}=ln=hu{+X@HAwMQ2z23Umdx7v)L&d~ zRDu}FB)4u$-mXLp**ssr+qVttEhdGOXFCTA zjtUaZw!82Xk5b6W`TD(U|8l6fckvlbFWrG>jcv~VTb4|^KRQRSy#rHQ@>e0z#C)&b zhHH(1V$t@0H0;D2jtUakwyYr}za}bHkUP0H%vK0=-E{NfFaL&;tNr!fXU8cj?tF7( z#fr=|e4erI!X87eO&n+~tQ;NKihXiNXy|2-zkeCLZGWcUn3{` z2auIVb;9?AuW-z@Wer;&=cpht;}7NT1-;0S&-y!R`F&sU{-7CDpbNiVWUSg0 zCh8Aq$Shd_M+FJ|7LniQFWQKNA_wNtW}QNyOZ_U^_mYX}eht|Vr)-W268Nl>g+8Q&AbpI1veT z%y7ZKg|I#C&KAC0pb+T7QLX%TPH7>g%dfk^t=1^xT_n^IGOK5l5fF`7NY_#tzUeWx z0q=a7``Vm{!xNnt|M!QZf&`A#WDV1bZN%>J4l-ivwL+i^?|d17-G_;4HyW^ir*Csq zkie0e%;s3yT68|($Swq&Q3!P5oiD50%=Q*DvYW8IUK&RQ2|RCd$Mim}gn!+p>|*Fn zg+LeH`EuOOTZ)uct}JLz7DojMy#8{pUk?va<5qLl@cjaXK$kjeuy%mEc=@6Q>po@@ zM+FJ>YkQwxjM!RpGyU**ulMC^&H118No2Rhd6Ip%C3oBtMcnRcWK0=1o|+#|4lUK= zWbBSai8e6>v_jWg2T(zxL2-9pYhV-^{$787bhAnj-i;U1b_ExVWgXqPmrp$TwC%X^ ze_z*g=Y5MuktK5XG&uqYiWMPObLpP^Mn+VyJ++O_e$k@F#_cqB;~_63(ABY+C%1Sz zlB9RhXCSw92oYCKe4u@=1n^_&UfgqpGq|$i( zZQvwVEtfujM(MU@92F$84ta5(3ZZ2AY@JxrBvtJDbceVUyGY75YQcMM7)Lr!J+DM0 zS#)vZb%)21Rd@8W+q`*-__^JJE(+RAP{9}`HEwD3!6b2|gbyt?a;ie0>tYXgZs{LM z);sBE*ZaaaQTo&<`d?Q+f(jB>jPBffeI(gYQzy<8jS;odrqTlY3JQU)5gwkreXo&Z z>S+D!dV9o+gKRmq%ad8ypdeAZt|#BIW+W*yP$$YJ#fUn;Hqw~D9B(Ah_56ny?=X89 zF|E_j?t-3?V#ebG)Z%+t6DmmjxaY+WoE=6QE!T-Y_rirk_!)Y7?k0smSJhSC{Qc`- z5_ChKd+oipr?9rK#P;NmS7teJE)-`b4Kfg*m-w4&&U&|*sLWX+fwQWzwushM482%` z%?n$s5a`1BOM@Z%MGvw3S0z@ea|TBRiPR@Xp7<$lW6H`!M1+SR|s_B2uJ2eo$f9^ zI87sX9wkhoOO1?47ju#ZmCFAedQH-*A5NFGc>(-E{QhMaTP^)y&X1)dS@mt1GK?37v z$;Mj_DUmt(_2bF<05IDJ)r?!+|FZ2b-%ep~KZ0MUQ=3o)KWj*#WA z>NR^3?>MX1=HyV@0>^P>C{?meEq$Eb{s8N%< zd&)J)+fLe-OaDx$Ac4mxcNq&v7K8S*)tvgZH6nqoZmn(jqV8Gb!dm^vmyS;ncP=|> zHwTbWA76UA(&4qE2Z-wJ^)M;U*&w_pL;o2bV#e10d7NVNA z)tPrbFp+%kb(i>$aNITb>?HLOe9uWdK*F3 zDPlmxKwj=~Lxn&W{z8LcfLVgLe0`zTwEJEYMnq%Wvl<=U_u&}f7&J{gw6u;16(sQ4 zG#GLZ#f!mD7ipKa)F4QpYtzlT{LzjTr0#zGsm+}@T`J#&-6I77Er&;dRm>nZb=ND`B1Fb0% z=sJ>Hk2^M5K-SOGpV}V7;>EdM6SNb3>rqsYP@nVV@;C|>OxAj(wpIvqo&Qmv*S|EI zwE6c-UUT=|rvbdGRI9z|%`t}_nc3yd<(U{c)6(rQC$z2A2@#ttZ(RyE~607Dt z)|$sBEGDia%$2w`nG^S|gP8Q8y0~__pQ0dv(R;EN72U*w6&1u72XBQy*Ryej!?!9+IAPGidPmnvBebvT^QXcV>vf;61h&bh57CG z1QjGO(oxm}Sk*}+x?70)Z;vPhy40x29lnFb*NnSb(3O6)L$i9^V#|E8Yh5WNcCgF8 zy1eF^CB)ZTe?Fe%28q-6-)pOz_N1s_v>`?X%8U`K!9v`5u6-KcKq1hjUh_e*1H}7T z-!<25bto!G;8~aRSNjGD>j_`A$MbIyB+!NTo2>D>p|2=^z)a+qJf_@Ez`8|$6_gF24Th!-U|l9zX38fD)x_e+~BIT z=fh@vQ(P+f)AqXZtzO-!1mI+`<(Of7s%X_? z2MOPEUm?)7q>md9{2oglf7IsyJjh8guQ`rYfsiEHJe=!~OAf(jD&6)vk;eI6@r`6bf@R*njRF4r!e+`RNi z@+MjTq8~OtPP~oGrdQHpji?}j-|aHXbWoh=Ua*qR>fB!;(1npz218fNNKx5fqSjZd zm{37N{i44zKSGS(s!`v5jTHi27>gz6`WA(Y0f)}gw_Wl~s30L$7M21433uB;VJ(=30#P=qvv>vCEC}sd+W*{Due9p&*i8I}IX-AGt zRI&k)Xw}h?`>`2h?}5+qSCv>1A{K2vrG42qMIq3I$0Yl!g9F9Lrq?yo^H~%XBrs}P z)*WmbD4uP2q1j|)CobW>aR0LZA!d#bx$@Y-2|BQqAh_L?x0O35>IrSt)g*g=yS)?JrB9_)C5UJM-<9 z6NuNJyGk^+B&x-WLyH5nsyl{J{J%)dIN6MEew;#T1?$n#W5&dbo`X7SX(xv$1iCQp zSw@9*NEEN%edBZc`chPo$gyd`Z8nT0ANT3+kA9~T#pLt<@kV!AD+IbQ+E~{3El3dy zPL}5HLT#0(VkA=gx$)C8V#)e4CuAEv%u>adMtP?F4eBTay3`oqawk&78kcchrMhby0yf(7#;KEcf=gNMgUsgGa3KIC9mn-huQbpPQrOC3uQVM}Cyfy~IowljM zamH=pzu`1N1qpo5%WRHvsp4tQ7xL;iR|s_BwUO0G4kd}Ie|=;gGQrd6arlslP+T> zqQ;8-_7myl6%~|dbtKfd@VCYLi_?GaYeiQVQp^m&o*HvcWG=wRfnsd0D_YkdbCnzu zB=B7#zwUyEid&O4ZF1R}3V|-{!R4L!ez<7%Y_pd4VUp6fBZ2QknMa>FN;F=(TpOM+ zULnwhy{lX?xfCTt=p=30tT?6LMMBNhZ%SjusW~IGyT?W;1iJ9ql+hxa6U37{URwKi zLCRB$MD>}@e9Nc_B=Md;@6#b>oR}P5UaNVxlR}^ipI|wYIxAVc&z-^lc5SYV^pRNn zt{HbNokq4e=x>8(?Ni0Z{yyIRZ>lQkIlGcw=}Y% zrryR{*)v#;n@e8y`>1?#pbJ<2Lnmi)v^V@I5Lq89i+e2&K^h>E?*kZw#8+> zCRA8J7p^YKZyft1F=l=@`nz$8QilNvTq~9R!p&HhcNw2WHu&l* zCjU9~5g~2OSl_MH6#`v5e_8Vhw^oy<#r4^!FPDOZ_kVwA(1wy4DoE^qRF_-HT@#%L z=xzL1H&lG`d_+5jedI`>>ypd>E!%E2=}=2=l-AM6Y@11nVg}n-auHRK``25^e#M)VJW0{=g6u(x{xEgafDo7l^W5cK2%_M1a z^fp}L#|k^!bXvc3f5I#SHD+Id6Q#<~o^+Mtjq7%tcsltB$T)s2;7eNJySCJ0<^ZB+!Mc9I`4`k7QBn(P@4m$WdAUK;mFOC%*6TG~$@2ugd&1C5cO& zZu0E!%@hJ%xE3OJye&)-=J%`dZx`xPRFIf{z?rY~o=Ea%>Tk|bl~ctMZHlQ;K3)@2Du2=I^hff{KV@LM1B#21Gy!TV0Zj7%_qhDxhFMkRVwEiDm^A1LmBwurs4# z&N*kj=72ft+vC0G{HmY#KMwW%Y|r%U_HPRAEYnH&e0M29_n`S3=UcjRwaPZn75RZ$`dL&(e`$P& zcW$~;{H+W0+xtmJEtH@;{CpJUS*AxXd;({y?h+-aijEjO-{5hwa=^)!9bYUS=ZdY5P7D|Y-KL4C><OD&Wb7ui~>5t0d6HPyHCQN3to*}_fCW!3`^ zN>J4g=ho7dt(j2%*kvX1XV4|wvlTX4&=X&$~a{91Bnt;<*yFMQ41xipJ*mk zX*~OVp0)pILrQ>U>&P}RcER#L~wg>dDw+Q#XNF^c<@-cnFD0nT+}&E*_+cI#tE0}TM=zhG7&%U4S7$8HQVS)- zD5Rb(QxrR!R_x1xCO`?Ql6iH(o+IbM$yRC`U3diDU40woVie9-B>!ij1dV#)HJ#kj zln}G6FePKPKv0!YW^>8ZX9kqUsx$p%Pg0f8khSou{RyBJN{EqX71h#|l4TdQciC5g zpsHOX?WKW@a=~_vI@ABd>wZiN9|sQM6+kVNpfP3qbopJWign{S*gf~7Kv31S{jH_@ zVN>AuBy}ut%}!C$gALhS*Zn{(l%P>>{M_)v$;$C)TXuiJN`auNwRPG_h8q&$d~en7 zwo|yHgcS45tbNRneGaJ`2AXq~vHTqvP~6 ziCQQ@-(5WSb#bqa5L87o_;`kN#wca&rO~k9?KN+p;xO0i!*60g4id03j4>g)Y>mroG`18zZXAL29k`m%u zZQrdCig)Nsw(rDPfuJgyMaiQL4~3zZ?en&Irp&4ny% zO3=!>yz;PHsGmuul81ws+gTPpmT0nT_C86zE^mS6x%c< z?C2R?N$(2b{Xq%pnc}OWS82+EMUS|P!)Y^Yc%ZwQk7v{O<3aYX2J}B64X=3tBcttDa)4)W>)LN%IIfN z6`g(XwVJ~uiNEUKdOE}jkOJVCiSYzuRF z6EDoKC_z29JhJ9+gp%3l3^R@@76_`M^GAM`(E2cC{;%6?t^Pq_o=6Gmf#!Ru?}jRS zpL}J#kKPvus-m-6UOW2UAjPC{6_iRV2{U9$P)|C~6SnHD?8`C6Hizp71XYPM{p>c~ z6yFmK@%mRwVct#&x+B2nC1;p&s;C*h-RmL{R7I;7@c5GO_R63OtuXA1k5Jcu60}YL zf7f0FrE&vX)OB=}X^jM0*PE^r_~{W2zDo7k7I=S!g-~sQ5_Ih1^^kk?RG#iKL8-2R zKu{H3CvZ>dslLh$LnFLm|3RV_O3*QwuOPn%D$Ckc#)Nh!1cIvQI)UfcE*Pe~Zu^bx zXuL_H7D~`}3HKq_3|Dp!xyxKmrU?X9(RBi^LX9zO@O3?jbji&0R6eXfXHCD1w76_`MvjKjpZg{HV;=LCR_j?G`LJ7Lh&8u=1 zr79V-OriemYK#(8CGMC+%}!MeGmRk0!+=o>CFp)VUwQF8`m2_9o@H+J1%j%?JQjZ~ zufYE@$>Xv~14b>Bpm7I0|GX$gSsGYH8s5i7AgD^r;MtU&tXwcIkenwuF>0X%ji2Br zvRzA5^35Jd#}9QB2&$slLmG_~m!RyLY%V8!>n-dqQG&*S@ci0i@rsvuD|u#<0D+(? zy3@pewZ|tabruhjC;Ja))ItdwdCF%?cVm?9ea6TugNF$ORneU$zE?D4yfSz0Y&olP zB%>Be(3o@{ZFpy#avF+d<558ZK~*$|hUY@MW|P=aPhXf$F-AF3c0}%w5-;RnQG!-9 z=WFL*=VxhvOFOvII|U5Q&%mfB zPT;#E1rAj?1C_4XL6^PxaBlVsP7HW9693WLFYkRjoz+zwpz@?FNdNu}(hORG+%yyR zoBsocOk2TH$4vOyK+Og`xVa4$XgqOQ>lZrTZ@zHHtrPfvbb*yuec{d7PH^iK1L)-k ztNl7b^i{@*=`k)ie}D`A)^3o#m3i~3ygi^@=VX{T)*IeW?FsKUrbEqYKCtaU58$Vf zaUwje6ZYs~fj=T|OS3IJ;QZupD15X9`XqY5Yty!qE1?2Il{&r2((+ZB+@e_4@x3HgYYRUtiTR|t|wJ=v_&8#|D zL-^`7;B?rUMGmrrr2|*OWvxn#k>l`c#|&m(@0)b9yEVMYT?6h%t=ZjTYZ%^i4SeD! zBAnf830*g@0QX)hk$X8A19c79gHD&E^_#5W^qbW%$6$+D)ye zKkQN;jCfW@=`(B`PzxpYOf!d8B}>5ih1y1FyMef+dktkyrlmko)w97?Fuc`ru=G{i zxbSokMqBGEm+nshYN5m%tp&tdF9ppFwT%WDLve?>Mw#^Pot6?*)h@&ezO`EpqkYsi z>_3I_ibId(Mh7h*<*Ehv>{tprk2Yaxclnj|t#*pKl zl%OiwZ~VNwHi?)sd$eq8uaPWvTEdohC6HLsgjZRyhWMr{p{}tFqdmfN^&g~SiB*Mk zy7mAm+Smq)>Z}6$Z`Q1DZ5wD%YZVmozv(CO(>AZAU_?t(`9N2YsOrH}Yq&jrB?KGT z{0}k3FBwyhq3m5@AzT$D^6yzgSdW#EUQ@mEBgsj)(xta-qcsr-s-pMA$CB3Rcv=nSD*PR-*j}pI$c+5MUg}; zl%PGrV^R%Mai_~G2t0UPqNBlw7uL|e*J`l2`@bW@rHE8qH~0#it8_%7V+JMO{I-T_ zO;iNy!+vYdz}axPfGxbg1lOsf7|V z7Fa@1>vd3XquRzx8&7QSZihqswDQdrW-y7@1RPMg39Fu90q5_ogS*SE*}WnQxO8qE zOkSZ9P7_<;aX(LN`NvldI@lEId#;5jTQfGp!yL{{Tn}>=S+ggG7I55nJsd1ii48Y9 z;Gq32acl<2^mA!@BC#XR31@$F!l-ZFGPO`5E3GNCZ?OinpVjj}7N51liW}~j_r0?~ zP!+vezWeIZ4(q>Yi|J0CVpQ|Ohv3jAj`Y(lT{6|mk=HkAaqS*kyyxyNQwt?-%rb|v?8UHnZ%s~EHEoZ%-mTHpz*``w$_LD# z+Kwd2^ zi)|LRmZ^mjxdUv$YUOk&>sGkKW}5vpz<^*%>=w?JZY$UJwm- zpC$0?&>j|8MMHmMbsg1a0OFDWTbx&{q0+cu1ti}v&l+^$5VT0u}X*oF5XdDXoC{T z-~qqahC$AqP5i1h?$V<3VS9A_Q$--Cie4e#SL1J-t99DqwZ+$^<{uF*g!PA{-7_KK zBZGw2gPyCvP!;VrUbDu^3BOvn zVb0;nQk~yEP_v>dEUPvWBER`SfTkPtTrm<}B=~}#13%v&EtubjZxt8p)W#Lhg%n8C zLJ4t|x^%rWe(djx&u!qZcXd@K)c113 ztg|TsK~?lQaqoF{8~obF6R({)CiofXJq7&qg>?>{!0WwwzQOeij+j}^1N*GY(NPN} zN*4HmNjE=O_05bEhCyv`#{^IObml-AC8%npu^;%K_JdwuRbo_g7qpOE@ky0ex;~|T zaN?mK;9UmI&hXFO><51actCKzAH*1Tf+sgs@5i`SF8HzB68OPg4GlWM{VIO2 z!mbr3YMyh(ZI12n!^CibpsIen-Bdk481`Mgs+mzP=sDjN-?sZwMlF=sQo9qlz4e9m z{T(>5b*c--WxAq%6JLR#s${E9Q015}{QTR7v5hNk9PWZ?{eq=;-e7sntZ-+sqfrTXu(E8=~R-0$(^&)D@b)2<2_m zbz|6uO_w3WUU zBBVqOhG7eq@YP922){T0HdkE$$HsQ#wNRqqWJgG< zJ^;K2tM7BzFbdme-Czd}9n)&(At)p+tT*!k^;7VEbtaCmwPiS^U0P%<1$+ZNMH+SX4L?a!+mrpJSeo zK4v6r$lMB_b)Jw_Iub_5snuJpi(;|z@glZl%oZ)RP{O%L3qMB>hhtXiY{`9R6s|kE zlNBGi<-Y2!7Vhr~f%We!R|P@_rj5|2SQ^VvB4Z^E6^dx9$-z>b8$ z&`CRa8$Q|u9K?5Db&u);wNRq!8+T|KJQ^0esLZzJCrvZ4)<0OB@Tkm&%Z^)D6aT8UruNbTIu}2WaFl4x(SHbL!*A zQt-yGYHZwsU4n%Y-nHG~d+SK}_^6ZdB{O-$#ysz4BlZGzpAP`h#mgx+3+3}D! zMkPA+Ohk`%pQMz%evDcuF?4b}n7w=wcurGKkQ{3`34LbPkiuaJAZe#W45CP+4s$1rN4M9JE=V3M2yO?|GZZ9JTawYb;WD|(bb zP?dP+S961~L(3bo+n;%?xV9ba_0NIF`tM+UmOaFjPX(X#uRw2+J=DK56>>||{lO$T z07q>9DBp~n&pJPC2KNmM;6v#Thze~1ww1X5w)zLC=h_02rsV=OSF0!O?$sIB=o>3x zK{MEfHdbIUZWdS$smgpSSwXs%S1Apx${x0}2A3f-;BHZ6?)N!)qX*jcucB-YC}Jy-sES@8KVu}P6IPkq zRQcJ>k~J(dgPIK&L%FvpdlG`4HE|Rhor4O!%-EJ{YLp^FRsEX-IPn_VARc&zt(*MQ`orbH7fb4dKL4C+U!e(K*nyI|ct zrZ`wnB&dq|GBuieYkFcQy}AgKn+QHjN?hq;0p4{N!@kq1mosfqcdYK&08b@~1XWRQ zB#(L--3QGKYUA@7hJx>v5=yBRgcTG)Agcb|^ZGsUoos?%p4Jiws-nI{UggFv04H~> zg@F@)O4LG$9gfXmbTBXWn?crm{J#itg9?jf~u%Tk3Wyn0Bruo5YMlCCQ%C| ze)q74&!h99OR4JXyL7b=Hn>y?_}EDc90C2^v4qQ_m4j zN>gC`N;N0$s|^GjWrAzEN>pl*h)sTmvinyC0wt)*YL5e4 znw1Ot3e~9lM@s{-#Pt_T%W5vuXaTzaB}NWFRtP>g`JDZzW-3z)CFoulpHpucjz|2S zvJoQ<1%j$}UowYDG0UKHs`_njaU&cjr(b4+M|_c}g%S@UEuid930Tch38&4WnEmK3 zdzbT%Kv0#>OAEL$dl5`~q<-5w`$XWB2|U($sv=PfB?=~5!v1QD;Q9}hc$6KE<7(by z4sN>yf~v-LvxdP9`KUcm{kHcANy3Pz{%k4h;(0aL2D;?WgXlF?SS3pvs9V1f78g`u z6Kt)(?D|3ocT`7ew<(h_x>X#j{d2yKS}38rV+jXhiov_SO8E3o!Z@pbtUTnMKu}f9 z_Lh*ga4D21YG3)iOTeEk64}OT10`yqg!e-W=z=8>v`!_aIwj)g4Z$p`+jN1TDlzth zImF|>qAV6at5l*EN{I0#waa5MvUNW5zVciksEWp&@SUHX6YxOJGS<4bflMuwpz$nx zKk7;XhQ1uZGH1P&Xxs{oPN7%Jcl8@5<8tpdtlhYS!c|d%?nm>=c)e1v$3zSEIwnUT zsEYPFuN&1Q4HwLM4htGP2)#>*rz3fk1wSV)=bHLFPKKr8`k%E~@QW=v`dL&(zdgM6 zXK@-Hop}Y?8IJIz7D_DXZUr&!3*mfM^?NleCKbDMsLj02=4&ZIRrEW}YYup);XHO9 zZXL7&YN15rWE*(+V=i<(sQx}8j>KU?TMxPJwZUv)ngf`9%7%@euY{;D<72I$NxLkl zvG*|_ubwuG!+kfs0Z4WHi2v&ye3t!eJjZ@;~-n1%j$tn>xasi5al0jXJ0P zbZj^tjXo^*w4cW443fsD#jj`qkuP$=pqe_fj5rX1Ta^{^&x2DKwNQdyAh>-$8 zRd4+5K#%8C2TE!i<@fty^~qo5g*A(WIWFx5alV^1ED&3czAsC4W;1G`1nm)xruFb4 z_^{%pyxVoUKv30?_~vl8xBznV)j2i$6N-ZzOXXnmsf=1EL3@P9I==|VLB%`emzO3B z1XbO7+#IZ`PJ{j7Y8xr~~*)JdahonU1=%6SU3szU!!k5@RAQVZP52Sp8NV8M1by z^dVyL8H zcKb;9Ww{!tg%ZmT+QPD7GvINSnj3y;O)6TR`2mTgVFE!_bR6R`MWxB;JKCAGxZFh; z;V6+a#{oWk&IP*&b$*psFA-nv8N>27%-7P-qAL1s=YF5plQ8#r1p5;13v}K_32_dW zc|IBMCbeWAH{}4eP=a0|UlpB7MXN0bz;sQiKv324W42KD;dEX-PwlJT^V9HqR})Cj zI|0-}3EIwlMvr@=sQB^lPD{%fX9|}{|@9x?UX&63ex-`W;3aEt=^qbF5SK)DF z<9A$^s!Z)C5L9K*%@UR`TnxGT>Pk2*Egd&Eo-9q#JM2j=9E#?ydQuqZS&INI!|6 z&Q(1bizj!My$m;Msf7~Ft60MDkBi`lxq9d0ytuE=wxvAY!T=~iRrLONeTKz}Xqyut z_g}CEsD%=n9$13w@cCd^q&~qKw#oRzpshT&_FjRYD*9yk9PY#<-dA1a$evXhwNS#+ z#s)I`&VhtlYJG;@^O7*@frVUay1qbA75%>PljXK2;q`RJ_%2jpx3Dl^C^9V&4%5u(r>I=?B%(r|s!f zJZ-oR=3PH8{06Ctju_nEemMo-HLlDi#OQ>Pff7k(j<9RY6bL`2t~syzBx5r(SJt6s zkw8!tU5oMrAcUHp2&7w^brWEqHAi6 z=C#`xG#b2dD5Q=fTs%qZ+W z@30)ztfOF|#N96zu)wDXx*t-%iM6alu;13(^10$*fuO2=C#~S)^;xi>yV{0hToATy zSs~9GHJDKgC8*bsSDJDRzzNqYD`!j-1cIulFOx_1*Yrm(k6KFSqGZ9#NeR&dx%`SB zdNeapR-DQc2&$q!QXXyS=7)JEX3F=mPJ&0!X^a`5&q6T&VDdlSLH5WOYkq60Xji!j z7D`a>C;wi7KkhNDr`$f#S|F&Z?L>3v;a&_jL)Fpe$nxIU>xiLZ+|83w3ngeT@QOhC zL$Laxukxm))&fCQh4n1J<4`f&>Z-P}{9rKFy!%Y{dD(_h3nl2&)M&ySM`IB?E$RGAlgs3Y#QKa{C_%rKJS!z+91b{GDi^og43wbp^z>@E zKe6c;>^=UNeE#utpcYEdNO``l^&f%#pFfiWD%}wXs-nHF(dcgs#tS7MRZ-m25szyHkTSHH!D{a zzE@O5J>Gnl;nNNG_in6o|NaQ5g%YCIIsbhJtl!WHGg{6SVx#CTyBLKOva&r^ENzFq z!?J{!B1(u65Eu2G@n}JNykXE?AgGE)3-PKECeB#Cwmrto7o({tLE}z%T;DY(OsM0A zrJ1XB^s}gn#uxEw3)$_^JiY^#e`}(n7D~{l9)5~aR075i&tQAky8s=}SH?Mm|EffI zCX0Dx+z;0{4!_ix%Us956g;Vvcw68Khug=(zEsH%AfPpJPT6c%<+ z;{f*kjzoNNl9}(HtD_c5G@0cNZ)Qe->9;+cSk+-P-mZR)c|3X~5LC5rfG14f9}1s* z)HZIEkHuakhnOyx>8OPgYc{!qzF!3NH&FMT!!M1&_&Uef08A7Js*)ypf?jec4Ct-4 zVOYxJ0GxB!ls?{(>4^~UqY~fxB;mQl?(E*_9D$&!=Oxb2Zv7&3Xb-!&SpJ7C=gT?9_a)HMrklKOP!Y-;KbwW25j^9 zLqIK*cr@Gz+Am9k@-UTH8k>sSb#uYN`-?zOmAjoIR63dg-D;`csCyGq@%5@=Xz=X= zPzxoF+B?GSMpNL#3w1_zIw%#Z&P>+Ux?hJ;f~w9vY6T~zXTjMys#mQdJ{7CYEz{n) zQj1XwCB|2@f{QP*;N@7Au$`ZR?6#5gYrC~TP*uD24p1jB2Y%F3_iN9;NkN|wSyx@# zlu-*M{0};S)xjLFex=S{r+X!%d~J`^u%xv>P}QEPw(#raGzhDwdRXFb#AC_29J$$6 z_cEHDMc-<4^}_un17or7ha$Oc6;GfRO3*hdKc&(p9$SXz$vJN(3ItWr)eEoK+ad;A zhAx%^OYZ@-P(pm4mu1AF=Z}23yy*vlpenk0;niURqH+GcLb*w`W{g@WLFd8Ti(?au z^?Wnrk#k!J1Xa=13m+Ly$KuCl5%NhVPev`25TD2D5s6s!Ph)xDnwA1VRdn^jtDcr8 z<2H+pQr5y|j9Mr`pFdwgF66%OMU%@~U#lq)R7F=W{CB=N6{qG^hHcxcGHRg&{Z{gd zKnbZBWx5S4+dl$IP!(Oh@H%%xQqgDfZU_%}0@OkY`s?Ctc&Fe??!&8od7nT~6@5SQ zH%@p8)^amq{{+gyo0AfBl;BZeQAyasrwhBub1&#;Q5AiQ^7naG5=sG`SZv`8pcYEd z(T=Y$@L zfAY^gJUy{;v(~sSc&9KIrG&PkBLw*LgT+s0@=+9T0e(((z}|VQ1cIvQyp-=1wf4c2 zBb(u)oRvcKCnY|&_JSJU1Au*0+c3T1hZp^=aM+n*fuJfH-OA4e=o5;GKc27^YpX~! z0+Ys$(uhr7bKqMD{!IA5ind!z)ItdwN6L4R^@6dW-*-0qkGnun)uLkzSf3#Hd`gWM z9oKjqN`DTpqlHa$*&YD**97x}3Dyb`pER11$K3fw^XIXVNd{LvsfETsiqW6`2GO`C zX%o9Yu2dkXibjQU|JC7e>|L=*PG6nRX!QdcQzlkIXgMhoulOyNjZ>#GYM}&;FXLx5 zMvli{CAqTK)l`9?s)v``K+NUIaCWRZlSzCRgF6C-$YDRnFlwO$jW6RhgvQ5XCHt0g zC(l5EpsLM2POv{X1u}1{^Q-d3lW_8eYH}aBJEIm#(1<<0x_g_1jxE+p9ox7G1XZ2m zGfQj71o(z(>|n&m6s+6ALE2Z{mQf2OXsn_}b3Y^%k4(DhSwpX`Ku{Hp*yL}6$*EZ5 zazE`ZGb2VVl%Ua+d>yqm6?+-J)Oxhl7YM4Nah*IOW&Jp;K$-0sQCaxz=FRYgLeEgx zH{^dKm)BIp;PkG`S)b%kA##}#%Wt{E#7(1NxvjdIIGq)bRjTE&H7V7E-vm|Bcv!x- zT`ds@Z6C!f=k*lgUMW%Kbq9#d9tZtysVlFx-;>a3GqAn2^96#cXp}C`oD5CD&2>%K zyh~e!C{{|Wx#i5?!IBzUGL8_wPH@=rznt}_emFxURSP9=NO1uelf^M(* z=|r;n``Fzl8CP7HEww%3A`nzXe>WP2~!?3}n zGjhm*O3;W_{`=5$#lT;N%KKllgxFIWZ7TYA2fp#gyN&df`V(dg-dak~op_$} z^SBQt22@gZy%PPqR7JhfJpW_nAnbSarTk}Cp5S$+1l@_}o}#Q_Sf}qT+3Hq`Kv0$F zZ{KbbijPanD$EfU5^xBEH@o(W2bu{hP+r($^F zRZpk+4FrO!sON=yirS`Pla%eA)mt`X)Iy10qnyAkH5F`EsAJ+BzPfwtJqPZFh&~yr zq8=okP0opaSLee9{f~mDh!XC6Y+vdy3A~Neu{|~{1s@gGX4f-I1%j$XA6a9*mwGj& zKC9AVm*DZD#G3Q2@Z@6*zy$Rj)$LRw&W#<&441_V1Xaf5aO~j{ngV|4ht|hfl zLb}xfLLQET569JaZOb)rnC(B4Sx*0?r36)pE0zy$WAS*edF=Yz^IB@5#MLA2VDoJ> zWH(gj3~ifFz}dsMGd<5=9+aRe(E~YG0Qv)ItfT zTm~EW20``x>gvw0Y6uRQ_nGxg_7w=Ky8BxT?;3=_!z?w6Zh5D{xHzI3mNm(csD%>u zeHgTAG6ekAsBLtZ9)wer%DC!!yg*P@bbX#n=o|*!TB`nbyKaN<@Ckj)?lwcB7D}X_ z@_=dU!r*aTmH72y2wD!&@N-Pk1%j&T)$ITqE23cTAobhc@8ft(?6j9T?LMwsaL5{J z6c>VfbQM+*Xbkye0 ze0?8mJf;rrbzLJ-3nl0;n7?b4?sz@J6o&+D6bP!Kqc%Uiu48Z9x7q}&c`THug%Wfm z;t?sl%4UXYMHTYLNC%bztd)M1K5EtH@mD)(8g>w}k`)xmxPa|ME` zL|Z1Xu8(stN-54cg z-cv%%CU5YhAC?TOg>WZIAgGGg3E;ik5pivQTikTCwoI$?(5jwv#=)y!Z1F+2$yU7L zn}JZ@hZ3~nkw&xkO?R}b(g>3`K9%TaQ5F3a@aWHXy>Q;ux)^)%y72p;gqXW@b7y}% zVOSH}&f6ytR7HQy>MrsCl~{DzfuMO_bad5d%%=q5$)6g0dEtsMic*4RqN(Q_ z3`3tEpO|m%Wr3h7ns3B&E%gF%!R*Qyo$^JSPS6{Tp|4M}1Z*JF zT8y;nEzK+A1^wF=f3syb4F<`{8LDzBYzKV&aE?E6xppG8$PuZ;iBheqS7 zgq5uB)^dqjC_!_jcvd5?pj=_QmHD4pFA!8k=MsGMv7Ly6*FG_71m z396#AOg>v$8i~rB)9hE|dL6Y;f<`B4G!JHk;r4S6SmpPPBuY?~ID2)ILeazEAJ%@j zrLdZy1dV6nF)Y7A(CE{9minrTKu{H3E%CYN%8?k^`8k_5#9mkxQG&)ZX*9LBhhk&@ ze^|S|rUF4#bk)aCKCvB*jr(6?ZNJP!-(^;bUU|6ztvERO&X+j!_FGs5g@Dj9yB@)*c(A54}7D zf~x3V2(M1LcM=}zR7DQ%*qu=eC1{2tKXWoD7Iz=+CQs=YDiBmf_d@uN;xE3(qGZee zI3+S_p#;rvFgFs&-#}bEwz008S@Lo)!G> zWt|JaxKQ$RouLxhJ=){X{mwX~;S`VX=bhpCU2jq7`T6()WIrU`B71^k6I{^k8{grz518tez+?>lF{yT}73*E>~dD5|!>Q%*QTgZ)O zr6@0?@d80rtK<;f>u$OKU6qNQk9?+Qvf|XeU_Z4`LRuH4dps*gTC!Me!@kaVxzo={ z%G&4a1%j&Lw-)OD`91Z&Hjczjkv~jJP)@Zk-7lz=e^s65oAG+Gl$bJehTQ9ZoT8U{ zYCpBa6QXEli4M)CN;!q*N7jqm}Xx z75k}$5(%x3>N>8@kXFu6+qn3+Oir*FucS7tR!Rw~%J_OmH?mUte{H;(ucvG*3Q`(h z@GMQ$uOnS+IZnbfGsym9{P%D5dwkr?K=QaAEse`i+lZ|4OP)4km=ZP9rIcDIvB_T} z-Q5)bUmIEZuVlH#Nae&CJAt68v_~&>3Bk$I^BlE}13z!ep0C4|CA-W@sf7~aeO&H& zQLaBaLb+1Efk05zB!jzu?|ekQ+Q!h+N9DFJ#wa82)heYHO3;4ebs#GYl(XFjDKn#e zguW`tG?kh(9woUYi~Yv)2X7lIZgm5cr~^GqY5!2-zO#eW!XZfVjZ?3x;#NbYUZbAM zN!=iU5LDW>(#J~!{_9<-rIj-4pH9lkYT>0+^}**~RpW{La|PnzpXN%|LvLlri?OBD zLWz=6cd7Ty9#UzPdR1x1+bFFJJ(c2#i2^}YYfb&7#Bl9@SM}Jwz0&xuvr_RZqm)`G zk-wyiR9A;mWTe{0Xv>~T@%e^I&4zPJVdn@*XJaWf9c~7aVxe|`gqSMr4~xiws{?|L#VV{Xs_sB%M}Q!ns4>*eb`5+ZI~2zD&0G_ zQ5IaDT1qXH5br~A?5jjHtE(*iSt#7cu}1&i$Knw2p7=~=cYkG8g`wg!c|j??c1jE! zJ5E}()kx|(RK2RNpM#V&pDQa{J}(vss`|1iK^i1|*Qvi?UO(~RaK&iMJK49<@=~gL zu8q=}Uq#Aumn-r(#D(MgKGdq27T?j5DnGS%bX z&ppxG4Cp8Ent&UU6|?!CvT5N?p$$qz%+8g%0_X}j&7)psq$&4{{5DW$xBm;SKO40m+vm67D^mDpC?(*yjHfhm)b`C$aJO2n0%>|*B*hOs=l-G zC1c)(#b088l&-wul_(=q_LLgN=S$CK1$#PiOE1WmTmvOf^-7!%SMS`l#HswoaexEO``S+?Cl&341@ogpD zChBR$cq% zZyN^&rz$pY>$0QAc9l{KCFniz+0v0T#VhnUM4Z|!5LD&ul`pyQejE6=4ToOoN<`lx zC~Li^lv*f3d!6r?hRzD$P1Y&9eg!U zd-3mgx9x^FCBE`37T0}iDYa07-V^uM?wzDq<;SqIleP;4RbA=%Z@)$JKIF4k%Ou6T zZXi3Cw4;<-C_#Ijug@V=34ZjH9lEum6a!+V2gQ1DDbNfKWKNWR^r#Bz^H^{{MSA)2 zf%fP?wT+sMB9xqMm)Oa^Yf7nw67-&UC7nIvlwbNXyS{Y2Kv31lWB>MBXn(bh=HH@} z{k?Xug`OKrsf7}>*Lh7@!{N%18XsAe!ezpJY%KWqJ{kv!_ry<~{>jf1*89Vf!!a7{;NtFVFn_hThl}FiED&|q&cP3LW!EAheJhJa%wgC#98Qg?9_53j|ep zzV(wOgz((=o{ zpF51_Z_`iGXh!sHuNdui#__YveaKZ=(a8n(Zp#n|s){i6 zmCkYE-*I=`m>#+t-_w;y$GLmyn(Ro8>h4qdicVG0H5}jhxn95Y_n&m-m|MhdYN15$ zb~%67gY7u2(fAji(6)G$u9Q!&?M4Zz>V9vdX98cPuG_EPhfBsRSU)6P2{JkBMlF=+ zoMfhrtHsZ%F?IC3*V+kmg=OpluZrMdsAek=ApC`E~%66a1Wl-M`Dh4%W!Jn8M#F==~T(_oOaZ2UXQ$k-+BH;Q$?PK1DQD@XP{>hla+zS4#YXyR;Xut7j+)oDBrpq9uAlk>H z=FBEw&|s95_S_5_o0!1Y7UQIZCuY#B$-jU12v+Z0UZRJNbAyxy7d$MRTvbGeEp6Q7LJliORm#2EX zckT%W!?n`LSbccjvL{sMe^2MWtfy1%j$*d%V8r z-qyIbx>jlRG{J*fC^7ViCxl<=A^rTQURCv~wrF|RTiNnrtUyqecpr|GfSyh&z!e$*{3_2FKeQNRi7;oR7HD) zujt=(;&oW8lye`Z3wKTl?}~viv3Xmm`XBW^dLKiyo@cLAy_PEwR7HE5pJtvu0k6bu zl~WdN^k@{21)cBj)UiB$sMjkCy70e8aWCha=aWIx?y~MjE%iROxQ@kcp-1GZ)7A+D zRn0z<2zJ}P>)vLn-;zHGqwvbEoALwu)gDy!{XrsZuKZosocmryV)^<|ep2ic*~5ON z2enWlNBXyoMx5r^nI^%Q+4_fkyj6)nP!)YnJkRTU5MHgQtZe?gSa=?k7#$Y{L)IHf z3Vf~x5A=T!<~cnu-*ezNoK9Uf1;^590-09`rv{62(#|9;KA z!(jnAP&+AGH?ywVMxva67T+h!gN|(z2&$sbiN`u0kHxshh4O?ATZHF9i96e};E?4O z-DdtYd5qV*7(7|LQl8Opvp`T4eg1sTP@ayxYP6NgChzgMv!wvC>zyw>!F|(h<`zH$ z&oO25`QOg-3-~F6W6H+=^;73ZrlYNEzSP-kj|a6-;?$*lu!F{RnvTa?Wk7>odpxM`o)Qb^6+q|K zA)XeT<~4qwrsIi^53~WrB0*KO4|!zfpLE=4*srwOCb4%ZarbZm{O&!j{ky-td;LW^ znp`-it{{cpr7HSlHJW6LBs^>z$f_sr@Sr;wm-X_X?}0$=y8mxCW8UE;tnsA>yHK&i zgYI)sV)WoVfD=8n_x?VQ0*oI_(k&s-k_!D@`3u#c5^L*xCBKh2Eva`z`qZ zC#!2W{k?PBxHL44yAQ>4M1rd5-V1+oeu+Z=z#Z(d=SB~@+jBiN6Jq-5v~}zJ@6L}& zn`nHnX(QWdy2*p?2~om+Ulxr1wMF}o(;CglgjhWBem;8}y+t6XiuNI|fVn&#iy)7U z{Iyl+D@qtF$>x<-3$+$}T;WkK4JYv^z!Y{-f4e|X72T)OXeL%4j>YvqvgU=$Jm}8Y z@ZRz8Y_T3B{eQb;+0RGd{_3yUmY2&t=>8cc%CnMT{p1f??cevu`TL`=;`4P@7Qb2` zsEYO>uMf8?5-Y`?W>V5xp|2=Wsed{=AMsF|Wu)Hu*=J+XvGO6drPg|Zpenkj$0O)g z^uSihjj)k4$KytD2tRzM_PG+%PbHYX^h>&aa+7_Qzp~rufEnjzCZqeX{(mmNy8$jjp2noL^NQe$EOi zmo0;sS}oao|7P%b>2fgO=fODgI*?7rFM)-_9C;nDuiZN0u0sxxyv|Np@Qd&4_L>Yo zOgz}!qh_#?|6N|@&bBNw1ET@|kFm3ktK#|o|HTFa3&o;Er9?zf*fXOdpomIX*olQ0 zC?NtO7=Vh3t)QgX`8My}wYwX;yA%6&R=>V~XReRW=kfV(ANRbT_sq=B&Yp>#NrF1t zS|D+5;8=d~Ryxd*SI9?hwuN`7+O^7`6^`|V*Lb}syFK%*=L0{hrNPIe?UC4AHH=rq z`2xcd2jo+yU7`8r3|JJ_iiKTvg->=1pjV?-%-9ql_xya=-`59;J8jK5-=foP*Z3+C zO*F76I0?2MaAC9Y+O2aEtikI^II}w*Q?&+Mk?>C*&ky=_kU!n_m-~b@hQc2OVDrkI z?TEoMKO9y0V|=ulLsqxzbPas zD`B!bF!$*$P|G9_4ird8WKEsOA3T~4_tI<0S3U=TCSVc_oZN*CY|sh5W6n#z3u3o6 zbpo9x6&_#df<(dF2|O&m5DKa^m#Kvk`@Xb?>5Eh0$h`n0UJQ=q!(SZ+pON(if~xX2 zbb^IdQX#%b^|5?VEI*lW1p4={FH;L8EY@}cHwT=Jzp4_qW>4U$kyThnpPF*Xxw&$cYt?F2Bd^`Wd=pl%T$G&g(}MAGxIiJJ--eAgF3et{1GIxDt9*P<>1- z5zVcZ`LpRBHDqd`#OqKmD4w+vDrc!Vk6IJW7Y(h(?xwYp&0IM&wl9SG!`ri}V>kp` z6++Vk?b+edt)cO=EU2HaK2gszqxtpF8Z0xorA#f9aM{7(d(A><>*$X}snQepv3Zlg zZA_4?N%w$lL4}YK;LZ3p4;UI)2vw84SyT^CFsz>kvANzz0DeispAv|iKKDFx>#PBV3!*y2YddhOeX0ZLuO2}Bq*pU2Y(D2(zI2^#4Z*nt8YL*A* zb2t*ccE<1nwOZ<$IrNgLg%W0=ZZN{I5X_{ONbHJ@;eChq)MnTX76_`Msl_$IFo8e% zkRi2i(M`w)CGxH{2gS7z?nqwfV{hFF{F2TOY7Fcw5Q2)7A&#C88N(}{oh9?)7IGOk z2Z*U#0H)<#nd56msIi~`@~zxh^b!X+I3X8i>~KRL!%mLnp$jL=Tk~4V)Iy0Tdz>KQ zbOA)0yCd;%^-#WR@KL#JwMw$~tu5sC&4F!2&g^5UMliEMJ_OZrX73j_f}Ml%;prV` zBmyG`@MaN@<)jiJeYRe5sAY+`tjJ)Z{(5<_UfpL z(&gXVfXl>Oc(mLOi6WO?+?AVLoXfT z7@Z4i=czuXzwgPXCpGk+h*6?DWopRu+wr=;7Ll2bVBW^0zP7Q41w5wX6#f-kI=yp-L=t3E~yat0=*D zrwcx|wJ?XOG0P!vx#$nyAEko%nv#{3K&|F+lTLnFjuNfc_t84wb!{e^u4eY zMz&Fjo_KPvQP0N8yXTYSv89Y5^;-sfe(K1Sv6bQA&w0=&!jXOMQw@ri&x30Q>hqC( zy9p0+b5d*?hs)GLiBmaM!ED9?DBi8+qePPye9a;|rQ?(4a?!%-@Zjk}2r_kGj!vfV zEq4*t4kuR7p&FQ#S_t)%RighbcfM_+y;65YOPN|IG5KLtD63rn=krzKMf1jd#nwj3 z?(R$FA4XLmAZ;!LpLb?H*%hI&K?d0Nb<)d6-K!4#vfNnN-yl`U2PF<)s|5RQWq@z7 z`kYTZ?a249Ypm2>Hbo$)ik2ast}?#?w;kxHL_S#~PcAaT^DF1TN8iTmomF|jGx6Yc zisx-J9nE{{fIkPBT1*lYI7Py4CppPYOE%-KrdWzq)k21AT;-F6%xMn*Ob{$qr z*XO1M|9rztIoja0Kv329l4arN;hC^GMI};))Z-f;RZ7V)Iy1ar%S^>`7@y9OEn+S8RmT9sanb%GmSt{ z6)iVhd%mv@w|H)#9Cog&oY$6s&GsoU^+gkA`m6-B9i0MxH=D3)C5)g)NGhBOP;;)m zQ-?QMQBrA=Q(K`HN(`=965el0fi0)ioZqmk%bjh?C~q2>3ItVIE-VT2q*MqgP>BkK zwfMOzm*iJ7ofPXh12`Nw4Ni1*VP@M5fEP@Ia&27L)WfA9c+E5@`BAMUqa$kZA$_jN zvrQZoYN3SFQ3IH~ZyM|cmB7<=xc1X}IsT-(a=m^jIPX0b&N?(@iRBC+qt#S67U#m+ zcQ=4zU#CL7fhu9AG3N%KK{kHXTB$iu1E-oL!;Gyito#%WM4m~8_*E_}B@bsY&n1I- zBee&4=9n38eXP6OBBYff^}rI{cJbuAJD|L!l|5DRlXw0SAkz zkTF>$nzS?LMXzzrbfeg>rG42G_8PctG8uXtQi<&k@T{%P2XwK+d&snBO5m)a#H znwNCltXutVh)gY%ps_Zt3vV6C+qF2TbAL8jAgJn)PcztG+FQc!)qG?4?pn8Cdx5{ukD|oZDFE>;u#e-~4pU`+6Yocda;(){ zZ;>D>+K0nY&d_Kszi!B!sx*^npN#ea#Z)zG9L*z`BeUAuOz=So+MC4K$2OYZ-B*>F z4-@l2RkYuZGrYzzeE4-cmj1?C=+RR`>}~JH(eryfEZOAaRRw~o=x74&$9Nj9@F(f(y)ng=su<>bd z>%7`a-Lo=`*WEM~>IUtRsf7|WwYVb1B$T_~?F`)>-V_L`qN&AQJW>bour4v+H~+qn z4@!tRA5wAvuMU&3m-|v6sEU>X?rd}>hD#e#p~XL)Wjdbpt!zj5isj?kH;~aWAnZXF zM{{lInQ%UHpiC{4nB>&~z91cu6M$uv)jgW8`8EqoN`(sqRn6_~55-8N9PEU|>|POk zao?FR=g|^jbdZ*=>&tfV9*Je)9gz68ZZyAn8P8Ojv|6TPh&MO4f#;~Ip4(1uJTZ0r zD84vi0oc~rB-8(;#G<9YX_vX`QyX`DBwssZKEyoPDG*de?+xx9J#skD%Snf7vyTaN zmlFPmINZk+#vN7b)%1Qtd7m+Jq0hSW0zp-@=HpCtJy$+1u(Wb}<|p}kUUjh8IvWP< zYsyNLtpGP;N6RV$a5x^7YM4NQ55c4X9&FCcAdP-v$8U(aV=;veimd+c4PN# zO(E?<8npcG#uhHF0^j5`So}%#F=&@NKe$^fFJ?6rYN14x;>yr9EER6LH$x)ds4*Wp z2iuVsrUF4#G{V8PwdQ7gkRca4& z{;lgG`A(-63bjyzzS}h#i!~VU#uUigYBUoFs-h7Nu9+BHm!GxREnm=Xk zpSAd#yC>yUTbu=gs%YGWtHSPC^1N%8vUt7hB4!W`)iJ*U%t9Y#ebsvPY=Ip=`s%25(IKW#3ne@qjX~Qj2`Uz=#6llO z{^Dwu{JiT9(*{(3y)_GfvLr)DB&4D{A06c>@7*r8B~(RQ37lyNXv&|5TFQG}Toh`dgq5E$$k^u`_(-i+ z^%D5`@DYD6`0bR}}Lwnhsz09ZqIrt3v zA6HBFTrG*eH%!xM4m&8+LWvVA>%lob71}OS@A=&=jE`>LK({W+P9UgCoT>hBs|`1h zTkFD|tQBgZ#9KETc-dkqIOThyj{_m?_;!bzyN{cg2?SO3Uu*{rJ0`)W6M)1&?>h1s z_Qu*fYicOeLW%TYc97p>D!kjP67!aJ;b+RMlxF;_AP`g~_9mXr$8~*$2RxrHD5+2j zB^H`B1Jhk;0ETL>sQcl8JaN+*DKGem(3_wt+V{azNfr#|R(Ce+nw)S~=;KhL+Z$J? z9y1F*-D-tCta69*0<({vb9bB&2&$qzGW_b-Y#3jf_fh+>^m(DLMu{P~CcxHe4rHxX zeTYw}kgjK-^$lmL-+J&X`^&)X4NgM6 zqQrqLQ^>)$!BFq!n5v6Qn{mtLJ9gIza}@}xqE7+thUo0VJ&iU?rFXgu&j%&mxBLCZ z`BXxkAAH%{iFXRik&1hJ3ItV&@2II`>hhsu%PG%Kn<#XIj*gMiH-kpgb-pF{DpN{1 z*{QlP)<+33(m!Zz&%Hul$ZM~P1Xa;^9#=r*ICJ|Wk7fJDm4&#S60~Qb(X7$7;L_Q1 za$2K`0zp-@mw{t_hdg-SkvHVi%gYM=4@%Jf4vyj!aXzcoHJNoY5D2OoGPpL>{xBQH zeo$NLm}zEYTRDCo;M%8O{281Jt`1X72l#B)So{eQn#xSS-G{X zxnZ)QvbboMOf8h?^MQ8hQEzYF@{A0!Y zvPJij!a4v-h_m_^)`s%3)i20j;zfe0=qdsnv-Gv(u1zr3jeRE5*%vy;M#mp;57X|p zJnL?4W#ocq!aNQo=zJTta5m2TLx{0r)8V;5P!+BDIEn*J__-HVl~s>#3F9S{p!03G zW7Y>ZzGIEClB&BX5L88LKE_uUoAO5qwUmh+56IL)32`Paq^<{tYBdyx^4kT1s%XvE zXiO)#^NPjwl&FvbnOZ18=c924XPH_kAwE&3cqq4;bXeA&_Y(-J+P1S1eEOaPxE3ciHjJ0swOO|9WGN6-wPLhAI6ce;Y&Z5mADhEF^QEhI$Y)Dk6$q-zDrX55=i<9|gWCTn z->M7W)?Z8M*K;F-}P`+;VS|F(EqoD=7wVVS1&D7Ez za4?8(Z8Jk2I_ZZ@EtD|*j?YKdEI9U1^>J-LC!Ta~j$GcMq(TX*I_hK&cW2Lnwd+(L zBW-X|o%ayAK_5efS}3t*o(-P6l?D|()jp12fj{roDO|pKtfD|r)yIiu@alFNl&G%W z!I=&nc&pdWa>cn-6>6bGr9c~~T0I34V^trf=@ESF`$&1CX&afYVxuc_>8dyUsZ>~o>)|LNuHUV_a5NvUjgm9!MhOH}WqLTl-k{}>IZ7?vbn7vE%$!cLQ~4B` zS}1YkP!qTxzZ}}OR{LsRS>fELcN_U@V5UG&l~lS3%zS~Xo}Q`10h>|$RxK0x>X`zW zS}4)FR5Q5sd!J zTD1iB)>P*vmXsLHn?ESjzB?fjR3-M+N?1j3mr3@Zxtt~RyeQGBX&VS^g>C*8bxrE= zxnsFOl}S)GW`#gd6`ifYojmK0=MyUIfVDO=gjpF%(0MBS+Nr^K-l+kuR?L|x5L6}3 zF10BU#m9BbfYH4YWon^>ID>T*-v()ROXLKP9GSM9kze<^AAsf1tR;Yy%*F*7KfSYMBWsK^>?P@T;)6Z6Z zJKInosEW3B7`Iz>=B*~&)Afm{pim1X>_hBecKH6aP?gw< zc5#p7>>p1#zFmM!zhj_ZE6}zJzs{^0$!}e-lMmePCsPY0=$a5*3HURD4~?;xi_0ep z1XamvzGDfBrN{H(+#^N5(R|~E|Ekz`#ind)i6PF#s&je`L ztG1rP96cq(Z!?b6jOF`hJ%$`xD}kUY@r#ksaqYNqv8&v`zotU#C>=egkpZ^U#clZZ zGO_aMpEZP-ff96lAHM~-?Zb7qbTl^9cxT;AMf+_UjYo|Re3ySIrE~fcVZ4MAbUX;ZwD{VI8@ZKJ zoa>Jh2&$rECpc<=Up2~eD=S$STglWy2|6BxBSn5eJobD=Wy1s`fuJh7QXcml2=2hA z_pPBk4!R+%h^K_O_PohLe_r5fs#Gukk3dkBxU&C*LucN*VH6Y$sib^NcZ7pDx*WTe zF*=9PyP_+c!QZQSsbk@X0=o0utadOVxST>Ql%TT%xHEU>Uc5AZId{6Ffk05z)%L$v zQ-#%6=M65p_2y;po8ZRte#+EB332^Z)!~7BYuj;9VjT7jNIs^e{mzqivzRB1rd6*1 zzI?%0SpT7#F#kb`4;SoUFXp`aarMm^bjpu=<9@U~f7B5Os-p8d8jUp3mzQYZ0S2Wl zgjoPeOj&9TThWK-K()v6WLayDr+Pu#_w@yWs_6HTxYDV4I4|?MKyI01C)1ug{r-oJ z4d9nAiQ&9{_HwytMK1K{DIxZXDt;NkGur3KyA}-+2&$qnD!$b|g>l;w>9WhF$wKr> z3EKC;`9T=Y+cr#lX;%G5#$I-7-U`{zFVLTy9& zX34h#K~*%8#pfJTurGgn zpo{L>xX&`RP=d}C;_Q+^5B~D&INj@@(h4Q0ipIY9e0X=~o4!8QnjbBvPzxpKoG0#? z*)xz=oiRz*DWa-CP!)|=@Ow4;j@*3s2wg2BF_NJKox8=D+S-qIKmJHpb5Ly|_Ms{o z)nNZT(}yP}Ueq%tdekK;;OFUEjxu; zC_(4aaqqU4ZhWoDJKb&PCIUfKbQJ;a=uqIo^Zd8!bf20j)Iteyp7V#~z^l)DrMpzZ zQy{2{t|Gvhxa$phvDHakh0RP@bx#Spk_XqS4YlI=Ybwcy@>>f8RnZmyIJfO@&Y!e- zuB-0mBYX=$3HoI@u7UKi|JifW_g&w>4;S@cc~TICTwjuRxmbd;-)eaM$d=t&U=HU`7s8|*D`psF4rgu_!p&?e zBsP3?KwnOZ0z=Dg+x8-B!i0}byI<$D)EG)pBWvweaFhY-%MBG4pPFmwG~+Btb$#?d}KEX;2R7o zar4q5K~?l_;+$997=CHbA~yJZb@}EJE9j5kRDU>W#jdu;?{=pbK#N0GY~Fioh^|lw zGrp?%Fex>Pul}cijXY&4Qwt?5-K`)rzW|yXQ13_P;t|}h&vuq)VJQ$))pnjWOrB8) z!5>r~dv*=uT61?wzV!PQ^ShjP0=_jkC;p~Sh~HV_lF5;P@MA3JiR`9-Vt?B(Gy0zp+R@ea-n&WGbSR3Fm< zC-9j!>{yo8K&BQ-ynAW|Zk_VM`ld?kHjd_f5(3$W2Nh+i8r{zZZjN3FgD@o`;fnh+ zgc!K6+Rcn)YN15LQXANNtpIohH6PndC-P<+enM8=VjU%@>g5kBC{s5dzw%L2^R>REU1zPjXqnk4F_$Y2QL7N8Vy*Gu{G4Fmg%QM3LphV4cHt@4gKJ2Zpmeu|fas2V_2vROW21KKsD%=ncGy70viL+fs6K`|PUHudn#qq|FBS-@O1));-&5y8LV4B4 zsJ0V%odzcIsEwO-)Iy2ee{3N3TOQ;(sy?bp@clc2JVID!RO|xkAW|u`ECDDc}KNL0zp;XS6jiji#Z_GRDF!7 z6U}e*86#)?oU5Z2N-UdX1Gn4cK^IB&@v>|bFXfaZ2d*C?5L8uVjuot4l>;m5s6OQN z<9X9>Y4S7sDLQJQ#A#*&MK^L`jkoIK)vyR2yla_Ubw*2ppsMqotstmX4mjDWK6dvX z%V#^~$gxX?>ZpYhA?`L{e=Zkx`KUf>KOfE4U0x#(JKaDasA_UcjAYDmU{|AG_akH! zFME26Jn=&Z9ko!R`~z#~7?=y8L8=cpFoG|;e@H&`rdUe}s*1m93H`Tc!#h{ihg5SY zKe+RH2iKch0;hKLgocxuliAM(U z%=8DcMb%kaN>G(cKTG)Rk_|(>R3Ek5cI7iFS5TH#neBPw2=+{Nt$?6FYZhi~32)!5 zfJc6)681=G@g{^1>`+EwE+ckP3nd`o<3vzz?w77np5M#VQi7@mce4i9 zgE_FepIW+p7Jd1kPhVt*qefb4p@f)^3orWd?hW6|%T^o}2&&pT&>B3?=D_H_st>Q2 zL43s6hjQA)k6LP>1T8mQd1fEd9KY~Wa7SUyjyf%Lb+e-3%VRJ0<)@3T30@bsY{l9P z+@u}2JQ_T2sb5Y~VlZ#2b4Jz1_fhPmk(k%|nfBdN_ zx&F;j*BX6%GoGMFSY6wrZHNDLqhJc#H1Ddm9$uf7liAlIf9+ko&bmBSk8rxXK$@K$ z4aYayvyl#)B^j@^){bmY(hlh;UPnw(_b;LOaCO@yoj}Wq<&NxB@dfD%Uat>t%(4`J ziK)aSA3frachz#}_9d+irsT|=#%u%Z)ON+|gmir$bs|gYPGb&Ny>7~0_57-Rh}X?= z2LZ=5N!m?FY%o^8GNq}a7E0u1z19{Z{UKldqUt{pR7F!O64XM8&Z$LOb4=CMBkH~% z)CVP~ik5;%{JGC+9i???z>{U#spuop-CxfKwNS$Bdp%t==6qNkbuA7}6(y+ZiFZ9+ zEE1dUsjHAEK`k{hYU`3wCNOvm!w)l<;m{ zNw-c-p^3f^N>CN8Z=w&{e#BY2=v>wRz1{NPmf`QVgx*0)B<*UflaS7TrS8N=b504W zqV0-E&=!u;m3Fq!)kYtoj&1aOPzxpgbL&G1s#>vt=?u|_&ldgXe3)k|odH^Ix{qOD zTfB6|*upJeI_lpRE@9+gy;S}AU)4eh|J6Ramq=%?9r<4fsyg-FSN9Z&@TFmTgum@9 z&l4-K-Mu@Wd3b&D{EXK{?WeO=(bqj+;`N1Y)AfkDye{PAL_8};1Jc_+AobRS)eo)2m<>*fGOsCu$w!vE-l5_ZM)VL#F%&P~+wK~qIlv_!13kbV7QLKFY1_rAJT;CH(%6UNfhU9`Vg70D{p+-|Jo2p^)F# z6M}6Ae0I&P(X~@2 zgm%!5E_VBYjFx)t`6!-|r7d4muz7aUnt92PLTLKleXQJ~Gs4 z@xSU?PX0GmSKocn5#O};@%MyINqS{PEq|gjmG~1m|J`Gu1XUF`{O!XlSl@^5;DNjQ z;j^}L%5;|3=g#gXcx{Jo{Xfs98X1VsAhl3pO4`%ij!1V4){hzJTVLx^3HS4f2DcT7 z>_0~U)Itd>&oa;*>8Rw%da0rWRqd%$62CEthBp`W3HrWUKb=8MY!glL#xnYT6mw23 zl;}Us6DlCRE?}HqswhEKG%^rT`-_BG;OGHc+wNS#O;qMsbvX6c%N(ri> zk(%g(MgV_k^?miYv>!0cM{2*0dUcmtDDkJ%|9;m}f~vkg_62wJ;iA*;pQo+mPzNnN zxG(Fo`FAW@N!#wH2Sb_4f$NpVmjUP@>a{N-z#-n}-&G?{F;&z;31izk zp0Ck|-)emyl%T4N_}~5LJd9*TA9PI5A%43y1Y^e7NXLKQ=l^|lkP;?U;QttT4Yl}TMP5CI#Yl2gIXxz{(8Q4F8c7xwb%1O397o#d8~Fn5@y5HJ+Nsl zv3wV(JA(0`$%@{r=I!6t;fs5*LFZ3sn<4Rc?~Yn15wkW>cNG6AlJB`M1#3 z!I-LL`|rPza_J>y>?2+@%ruEDSA1lmVnXQrNgM&@_Nd@^B;frSf~$5 zoF9-WEk)XG%~U-fl%Oh4qY6@4B>t|6)Iy1J_vTCKNDREH?}HLl73DEj>Vrf~lzvU5 z{fri!zDl0>wj9ze>ED>)?@`V_Z%)-hi3=xQNH$3C`J~@hqXbpa68X<}kP?r_7D)!^ zBjZr=e<@w6qW53)F}T|A(b~T2TQQIJEub_;VN!)Q|Bj^oJqz%s$D&#&Q8e;*KdNCV zb^l%Z{-6X^(b!HTsD%;+w-}gW3Il)bze{~kf~shYD*E^{_NvZ1ZQSkvSFuEQ7P0>^ z=af*|HH9}wpXjH4T|-kvb52#X)J3AD{qH(@ai|?DdiuMDufliupE~__1VAm6p!1)i z4@ywgpPKl0BttEf_|J2xl%Og)$10|ZMqYNG93*ReQhkFP{rfif?@=EmOvbuP4oFWL z+eq(z{COLw|3y`_M8s543nhj-he;vmV^1gjXo(V3MenTWgN~REX&1Y@C%ys3U`+j| z&Hp>+)Iy162Ay{gM0!mJ{pghvRQ2cG_21)mN@Pmu&F7$xTaNlZ=zmca?K6lur!l8p z+2Pt_7$^Ap*s(vc#NV}@S}3t{p}Y1y(uIHBb4pMZEfFzQ)Iy1Y2kf*z(Z_gy{dz?S zs-olKq7OQ{ys)sn?uHr_-|fWyjLH5zn?Ws#61eo9mjIp)1#Z-b58poR7Fcf zOck|I;-hnb?iBjyP(^>Ph!Rvq=MY36bPV}ZZYAAX?4>wlBnsonB08iEbg% zH_uPf%Q+>eijJy_KB$Ef+bvCXGtkGRk@`L;K~;2iK=eUZ?7SItOKZS~Hd zp0FBoQsVQc_u4m@s=X`q<10!~)qfs6r#+KHMGLgEF;z9rO#Qd@`8yW<)0U_fO6(Yt zuZ>39I#NFtr36*c)QV+AEtGf=y+hj#eb_(LkJ~9hRdmgi=z~VWC!Y_Ky5XDb{`6`8 zMj3zS{LfoWwNRp6-0yeo*0=gGH6^I(&pY_P_wFcBX0@GUi77l)TEACB|BI^VY6vms zU3Z$pdW_X9mw2%9jT^x!yl%Mw{#^m__bMbBCsHEus6AXp+BBZ&J%f~>DjGA2siGr| zbG)lUBL45ilJ5WZKmPleB_)DJn?M@Uk4~t2Q_)!TPya*xFRG%c6$xsgL`Y{dScN|B zHP>H%MG2~+r7rrQbB!g|2Ix*;TkAZ1z`yUozh^W4w7aT>65-~7zupG6VfthGl%Oj5 zmJm}#EtJ?X{`dRp&8@zArArB_qGM;cpZ=CSDX%C+ig}X2YX)cT$m}=?ns1%X5(6@K zR2rE8j{i(&=WhmkN_f30L#^#b^KLP@y%F594pq4QHfalfXFk4;Bhv-$ls4e?hyX{H z-gKwbE<6F&_fS_GPBMw&^-38*>5IuS-H)izi}tX8R05Pb(TUOhi*Q$!!{fQmGgWf< zh8^^uB8N&C+iv)tI=!w2~M%DfZZqztc%51buIL(6+ z`*ya49q1!=jOrt-UIcfHFoMGo%LRg}=qVrgrQWPDyhHso=~3rZ!ucPRIPTO2R-upM z8`X7|erHDUuqY$A-g&b?P!&B3M5CE|Z8-1zCRHk)bzENGgTo^HuOs_?7(JVV(s;tr z)-dih&2TaA^x4lzG&urPN~wEb~gors%WX>z8~+0@Hi~1 z({C;d_k$ARSt(oA4&@GAj9|g}3j#q^^xoi}PE&*U>-UB*Dzu71_m-f$RBR7$gr1o5 zQnLCs=;hOe_r~+na=TPisD%=A=MDU(x?Fd@4e#LiwuS;hRrJo{36ev5^0)X5j>#;k zPzxpK&Kvkd;d!Z!ct3(_mkwh!^-}Chaf~v$lIclzI#48Umf=iRRaI(X@D#q{u+uC~7-55QG z0(V^WwBbLhrb+vP+X&}PP@-|*cl@|10TO4cGjTb`9Qc9OM(}l`czOigjhoVVs_tD! zezKJjyjkz5PzxpKzTUWB_$X(7v{tHgcXSJZpel!cCSZhRwRfZ%Gt9Pd^5%^Nf~sgq6ab-8Eg^yR9Xk9cBdO zrs8Rs+KW}0LqX!2nRMpM;trUwsE=_L2 zL}Fu14c^br2%5g=s89 zlD|SNl%S`s;GX1<>haZ~Mi3d$P9UgCtnEYB++$-0q)PW%4OVFULF1BxmG($ou&kc_ zqsApxmmjmH>x|&eg@FoHJ(3Pd*_hiUjhvWBG&}y5wOwWew$1x1)Iy1sug^;Jk?#6Z zJ@@rw>Q`pxpDOKr*+(F#ir!f~x6iXAKVR1fM&$Gq?l~pmhF_CrppV6C)LQataB2R1 zf)NA<_YerGqV)}TP)@$aLYEss?|MUo7><_PPqz)ycJ$G6mpUhWw)bh)uvVJ%vGj0- zS}1YDVWCtROZWbKb%wXbt9|UuP9vC;9wrb}b)wW#=>YoZy+S1(H($n*v4u;@jZhM% z#!HLQ@@TLfOR||HEye5YBkkDNXOpED7>o9su8wl%nHI3ii;Up=&oK(MP{L!{LP6b`Z~AW^4}bYcY`2qHha17Y zIFX<#G3Nt^EMn&P#xY~#gq+hn4QMh_nuPiIW~$~q>-#)*u~({Oa(A3UEduc^OuB+) z)v=*Ue2Pe6XC@hecSNK>3?Qo4PyMAJ^sy&J9Zy^^G=}XtmMU#(8LdzYCGG?{N;&AG zwTntDJvoG39clz2t}y~ZRWk!xORdqz<{m0>?W_me^eR#o0pa*;eXv<(2!kR zTw5|h)zupf8KrSAB&YUlZHy7@-8Vs@7E0XT?kL$K{jQekBgeTX8(GT;Za$3>2&xiO zWn+{M0p|^2uSbH?&9k>B!&EiI^(CX<_4d?Z56QJ^Lv}Pa$#Xwm?=)3Mod=!P!Kf!G z(&Fp!0zp-$E8g`Sh5uv~rxN2&-G|{lji7qVc!jDSPe1K>5C7M!UqdDmeUnSGrAVAy z9j8zWCF0EPdOkyX_88U2m=RUjfp;m=&^{tTRkYM`kF9a0Ea{aYl+?rt_k$7>)|QaI zppTrns*h1^8nJ(d8$n#>i2^}Y^xkMR%ZDTbuV(}^0uvNkqO_!^^B~XN=%ZU@)kmN2 z&d?<$RT{A~L7^5(EIydtyfT*VwigYM*mZT2^sK%ScpVoBsxsb@-aHF^WWQ30q--s$ z=#nNqz7@~Qh2HQSiU0L+)O6N#YRa#aJeaQE6W)#|a#x;a1SKJX(>^jK`dte4+=@Qd z&7F=u-uc_XrXoXd$Po#uqP=j8eQq>k&AO#Yara|+iL&<63QUz;V>%mgx2kj<|M$Mv zbf!H~LW;-Vrw>$pdYE3vO<454YSIH9a45!d^M=Lz)jE?o7|$L1M4n}gA7L$P$Jik2JJE3--LURavc z;%pQT+dW*mggLayoW`bK?=OAF|NXgk8lEQk|4RgS1s)X24&qzQqFszoR+Pxo*h>$Q zK4YS$sy*{zSJI8(p@CSsR7J~8-5+i}+w(C++PZo)pHzK;R0-dAryfmZRgD)&^{~Zx z{ctMFKA9*z!_=-Csg6KCev;2R-ZO+D<;HSqp+xe7M5zMO_F*bd>3e5YVu!~Mrm2=H^|9|G5L7j(gdzo_kE|kf)LC2h9ovHasOAm(b84Z) zVQWQdi9TX4tHihZ517H{6e;80Ac3GNulhTrw&>$!8FlpBtmj=e`nDmMMh@oGLWx23 zc1RxR<56jqczH_A!*wkvzsf7|-L%vB7NJodO#Fmz(Jg;1;WV5e>Ku{H}Jy=#w zHF?d)hEQWzN1tSHevvl65ueREwRrmA0^ zMttXXBRKYx3j|fsa>FwxyZiF~tJ0+FGcEYZcsmHfRPEdy%RZd5g3b89(>}zp*R9Q< zA^v{5gZiajd}wQ)z5yfsZnm6SDA5eeU^UXK{Z(Sn9*KM77@7Y)2Z5j}S|S>a;oj!l zNn-@>e>e+eMTzG|Ca?s3jQ^p|#8ppq<%?@#gzVQ$AgGF#n?_@K2FHC|Ql+AC2K?!P z7BB^KIAzLscD;R5IEDYa#5$TC3Tg_Y@%Jp7X!H@YwLAZY&&Rxyg96@^F z0`=?6Dh;~w-dNkux>OJdsxtfP06oyhn;q)+ICHuNbN5X~(88@Urxr@w{OADt(MRK7 zM0njmUSydnHP5Uj5L89)tVVO?Z71&d0Y_4eO@w<+iAEWAp!QgzHpOD9W`1waGq4|J z7hYQ+sEXcyji%ef0o?drsx<1wb5`}DC(OVc?pi;NEiLN_*YJPOe;dbWsbfoRJb=IL zYy>q{z7i~y=)b!K6d~=FtbQ?4%cU>BSkefR8+{Q7s-pKsqp1`W#t*N<9^~o+Y(%ja z6k@7c9vj7u4fcX3_`mDwj%FY0{2sp!-KMT$O>iB~Psm0P|MR3^p~Six9PT20>K~Oz z{uIj7aZEp@;JQFi6)h2srsUwky!sDAFkW$2C@V@hJ@ka@=)*imU6a}+V<3NpWp(=U z6M>*AT5fo9Rw(Ybge}96%8V71?gZcQzn-=WWj-f5!Z*BLIwh2uU+xGeu|zDVhN6!o zzX{x~yb)CP>MU3&;lH;%d_ua+#$iYdY8k^X@KmYH%b@~6Rc=Rq&$o>DMKs`1`~lXh zoFz$&S}39Q^@9)S<3jTh=tF)#o;TWCA@i(@iH8-=<{iF2>K;3?)K;^-*!G0Qrf zFWidnkD9v$f~sge#`x+^EHB)J5%Th;LM@>+L+Ts=Khejz7lY8po1PPS5so@9ceiKM zLW#zK0dNlMRnZTX=w}kgWo+A@xz`W~s_J(+05k!UAhW|jB#LIo@uP03(udRK8MRR2 z{j~tNfIjy9BC0ix=eM;+@HXrTP=cz$M+Jfb`Y1m_of&O;C7uu6nkHp9DL^fhIQcjb zE~AevW%?n}%`t(Wz_Mz-X`Vn(mG0JWA4`7`Uw0<(7p+sJPs5cafU5R^bw z@%Ru%X^iwwCh(r8^Q!nnm5l3;IAiYjFU?2%*5J`wZ!$}Ssf*)iq;;C0N%v&^#}1i zIC8B}uP8AS>zi7~{;8sV$70?!fw$X%ZF}j-0zp-@j^TORgC_FOwWXNF&MP{4J_bEE z<49gdFfGUc4-3`Ds#($eV5vbY`pFhuuOWW0=2<3;bm_)sz4U<=@de;izB_9%%okp_ zDS!k=l_+0n0+>}pER1PFJk%a#nl;< zIH#j2Nt)dO-YFT7655rCsgfVZ@*HauR^`Z99ko!RWO4`CTbuz$hN<`C%l24)>YEK) zd}p0NP!&zBM&q+{0_PuG+1Z<9dK zdroT%jz)RJ@rPMQpi{vu9sOVG@7AVHphMq}uc*(5<*GQ|*QyZyvA?FH7D|Xdp7_M^ zyZfd=&xNIAN>CMjRy3M2^J4g{g`L^MZh1nzqIF5UAFfqm__J{XSeczELg`W>YNRiW zZB+n|xmpu1j*H#Z4fn%GtagWDd(^PPiNLi!+Q9kozG^s#qf0v}L$ z8myUFprr&=(KiD|89{M8%J~Vb?D3EAoYQB8`omMeGvoO1sFG~|#uh@oqJ-4G6ZAC6 z_`kBs=@8Fr?tKXLJjAl1Dq3#%Hi(|U8xIR&GxN7=X}J#yZx6gl=CA)1?|Hlw%lG+u zvAN5(YpI12F&o=Mhva4dm#X=PV|mMNOFV#)QVS(Q zt9OE%d4F;q=@rL+CRbybbwq-yXer?NA6@J6QQ?04@k9qWH@y{DpI!}ZQbU+`Tr2Q8 zzZzt`ULD*Tj$K>@HJ7S8(DaRL$zN`7$eY1xY5pZI2-B^CJK-Vh4|5YEnQU(h^&|43@rp=xrDX${ZIBNE z`y-Kf(d`nORIVM*O?$$+xmJUdHS=Jie;m78z7niHl?&50$FsmP#_+XAF8Du;N5aj1 zq1yrCgPqS}nCV6{-Q5m((6PGOKQB7mK{@Vg%Gb3^ z@T}OojcRj{K?2)l5+jc%{$D)<2*?A|tSU9x{6>U=tMXFL>*Iwk?D} ze0w?e^U?L+x)K&!g|OWLzB=0{1#mZ5C3?0Sqde%anmIi-(DAcAy4Rj7;YqC!w&Amn z?p1LCEXP(m;eoGif=?m)Wpo(0oe7*?{6wQk_a57DA#DuK1cRMP?9G!$k~T3Dj&y!z7NZ0RLOF4Z)K()n5Nq3oSJRolp z^BWk)ZY8yXy>D|MdBJejqJtOA!QDGy-%w`ty)_saXzxRQZF9qP*LT%eqjz;oj=~LKB(;#^8!WV)s<-yS%{a6LlwlK>#A6y6bVS6t6 zg6WTZunAY6k7b`Cd4I>L?7PhwiCQQ@TP2OA?2Jg>(`^b{e`==SgVOo3FVs=;pr4D{ z$4RO&j!*26!A5260BWH`Qk)Mg{hkM>R;oR(lwsp};pHUOwOz45P}R~CKH$_g4_vcV z;=roW+~)Np)-Y&9|V#7<#Wz<3m zT`z#DhPmK%L>*@+IeIvrCK$&ozh(;rRV^(5sL?eC79LayqvXE4=y?>YQFujoCcMMl zp!?`-=s8mV`G|biAJ<>ubN%R~@Z?a!D8Uo@8sb|N>qGl51pK|p_W$^rmFvo&V0k= z2$t7h!zn>kU7I*Sdcq2@X`>R$`?cpA?oDO?)TqFp^|OG-U01-Tg|TdU=|*5Ft$;I` z(Tvg>&Gb0|eEWd0tY~ssPA!!1Z`BA)TdjaT$?7=uus4A`^U_%MHL$cmP?eY}r?PI` zzxD{0Vr_?Op8tPaJ7HQ)Xjfx79GDod*Y0}Tc<}hdFm`!TeNJ0sO5~KP2j@mChcbuN zT?7r7#LqlVW~;m`1cIt)iD)!a`g!rKhr?MJpV~rMQKHK=3&>x&9PZ9j$EgD%+VVd4 zMzKDVs|f^E(Q?BRy3L&VHS6IlJJ?xxP+Hv|$rNqP^KcvJr|BtM*j;rGN{{KZqK}Apj zMG+8?29b_CbLdo5!~jH8Y%ov(u`w{-b}QW_V2g5h*Y0lY?k;SY3~V*n$bQ^=hPR z^IT&0Meavjxe0W9J&Gh)j@M_?5m5q9cZm5M$o9Kv!fM{{F^iEZ6;l&)#nWcQ0);QMm9AH^$m5xdsNT0OO7FW_=2DRyL`ABad$0t>yIajlp!q&WSvMRQS#+6z9Izl5b~YXoyidT-v{Vt0BG{k(j=x8Xf(f&oMc&1G zv&fReGBMlxH<`IVl|G-4$`M$F$B@N@dv>OkcCqxAMjAI(m^it*jdH`~ERr-^ZbQA) zg+BI-rPn^Ca0FK2JF8Iiu9-(P&cx7j%lV$;KD}y}?e$+J8<9tH8%E1CiKSaA9XN0r zU<)Rij@R0MdSEumyD1Y#GOl_}+#f?nbePT&Sml{;e_w4?7WsWoCOT{15PBNM(%P(P zu+wT^{qOoLVzq~5Ate;lkEzQd{_Gx1yH;1P9FtA#w#h`b#Wo>IE0#udN(XGgM933| zdjIMyvf-9YjC(s)$YWJseA-Oo2&}?a$WHXsJE>9x$I!K!(*avBp}S6N|6$gTqyPHh zTw|EMgzBh?=gqRo#D-MNalvL~Y`_ zt8&+6lU*S9!zQh#Xmur)nje@7*n)|*j)p4#TUn%fluTq=*@~Y=q)~%iJb_hs44J?E zOj~hsbS%|MNaMx|6B;Eq>opH%k*Er}jg<-S1oPS$mW9oaE>__?%X~5=kxel@DQMcL%(=!GPcZDXdcC=O?DgUXJhxi&D-`R8g?_<(FOiLJ4j@6~CCsC_n_w%*SZScOM{ z&Eeh@iRT^TXpLzSU<)P;lIE%$9J9%?6>=LJj%*ZHA0ABgx=-K;tl~#kvu%TDb~Bz{ z_&byvT|91UT_x3*TiGP8L7ta<8t_PLy>2E=T`(B11rx7b&ZsK(SIR_~q%BQ(nm~)2_k>sEooYf(4l#Z+kB+c-q}n|qhZM}3 zPZvFTt2z{(ODtZ>Gs_4EEy*=AfwsEV3$O(fD_%WRok_?cALht@pWahjNOPOcq01_I za|Bl5D`eimO={AQFT-e9Qh&e}Oe|e>MityDhv*KI`(gC5Q8cm`MsJ@P#1UBaKRxee zDMi(drfpk$f?rHap~bLV;`d`Njl0-F&<)Hb8+v9xvelql}jX@ zfB9Ei93)-a`E*H4cfb}**f{A6HQVyYJ4yD|P8s7WP3oFRjnCL{1XeA4rz@nq$R+Q* zWnbU;2|-d||B19^pgv%)<7@|GA$?&U$v2w$KORVxW`J~P#{_y|k^x}fBqqvtb`e@9 z<&kgs@+$SoZ7Mzcx`4(Rci{-E!dJ*V6K>wpHrph+v#&W|3nnVk^@S0NJaXok-1AR! z-KALPL|VASiX*U!@A<^yp3=WOSmzvb4(ZjI~oCOm<-?<16X#q(ka-~Akt1*&E@e*q1 z|A-^73SS{x(cc*)Ewo9YrVl?-Y{A6(Y6n5BBA*Nmko)nU_5i8XuPM~`?JthND!%6m zn~~D(qUm%v^LSzJIrf-GlqrRomWAZ{BH4d6@AC*LwZ}5ryX$U>Etn`dM}VqXG15E3Bx%_t%{`J?G} zKYwAmC-ZDKj-efY`wO$X7n7qUqZ#ovc#<@fRZD5ym&{o(F=n)%(6(I>8GS^~@fuc; zBpFn!pf1xFas*c4D`dM&S0zbDZqKG`=B}gIf{DYMKzOmLkenDH_rp;)QM$N(7QJeh z%Mn<`_x!I>iZmu;J{=d^oZ4sx3nmUFr1|vWbn}p4;m)*Ta(nV{dd)USi2YeaE;Jj- z+6X_LEcLNmP3Jtb<_N6f$Ex0BilkvWkCqc}uIHG@Rs;!KUlftdVR9Rq{U=Mt#Thgy zswYQa6~0f*r~fxq%Js~odwb<6FNcN*B`GCjpHCdU)+a>x!p@o0Ycb@1;yC*EQ>9Ix z7Sf(dQ-UKrnAr0=Sm=DOm;^@4c}v!lrb_)UtffyruH*=;!ehuzQf`$ht(vlc4!nJo zU<)QfYlDURn~TZmqr+GmOT-kZ`8$@=m;8VuunONBh2r<}H0iYc4C*2+6E1}W3zt$# ziMLiXeLgx^=0c(t?ZOl(DSR2-Gif15U=@yku{skjsgi!o zV%qBVd;wc9F*YMu=;vBWCPv6{oPz(RO3&jr(D7;79D!AM)LB0srAnt*O;4N1R28;h zVogAZ@N{(vQU7=T#}Y-FbYoH`wf=6e!~|C1?*com`LDa=^RfqcW|b<>F7gvrjI1Qn z2S-yn)?ZM(sUSLiqiOk`0O8D=ax!zG9PMKVn@G!bZDI1mbS1W6;=hCb!U-0~-PBX= zxo>|T>Dmh`2saycs2tOxRkY9_2)8tn^LXTS&#A)VG+HSS4aG_ZRS+I0CBZj=tmTs=@3+GS2 zC)k3C^Iv_0>IW4hH&*@)HoECc<5u>9QQfX_1XkfOWT$QF=tzg+Bf&>^FE>`0c-Pcd zSms?x=53H8ibFf;NF(zj!7;jkBd`kJ8|F2L)RL4pdqc+|e)RDWB3zzQPEITuO`|J` zV7;`Q-0v`&4$P&(jb`OUm(6n7S@CzYq(07lz^c}jvtVLL0SFz8D@eZm2u4($*OfxM z_k>9=%{cPl)I)kEbkn_ zjTI*5wI#yq!R2J>5BYw48>}T2=klYF&%K|_}FP-|b)AziPQR3-dL^?qz*b%Qsq6)x>Nao|Oe~If5xgIklC)Sk zK6p60wWMPn3i{hua|BlLqw6_QLyG7W0dM;(q`l1XkfYt57(dXJ=ZbvuNCiz0}XvQs^9XyXk+A7XF*%U=zgaIwa$k#y^H_$EJBtaUd>BlWy*C!hUlx;72I=goj1T=3SI!9n zpS!0x0;~AZy*}rwn9?g8ydDVLSYe{Z%u<*(tAyo@|d@SRmC z`fh$ICR>C-@2IO>z7Osb&D9fzx)u}Tjq-Z%4a*QZ<`4+6VUH-bU?RM0J3%qGh`eeo zukOls-xNE0g+i+nk2wOX{&a0CEc;YM%5TnMMBS;wVzg5Tg#G+U7q@OI9Ca%q)vCGl zhixnye_Y{CF!_mGcE)IEx&OVOxR3nC49>(B1tLo+L>Bk z7jGB`K=BWrz$$!&><%Vf75{b&h1E7MDYjt3>zR&V|GtR0zmofr=zK#oC82QA@EJ#7 z72osq6$?}fmQtIX6mTKj3>d68m9)> zf{D7p3PD$|h=gm)UYugDL!$22U>N!KH+Mg<3g1~4Dmqvyn!OH!mX9^Lp5s3K`g2~D zYF3Q`=K(i(tMiu_edZd27SO;a~<@ytG;h5Ae&SEH-qkS@m%ruqd+)mtOq!^4ii3F zyH%+|0kIe;`{A6o|0j-#_k~ZH9XSH4@D;N4N9amX*)<5dC$$A^!NjuoqpH%M1tdX| z`>{56y?8$&2=1)W<_N6fdw#uagy_B^5GGIV$mI^=J`Gs5O4Yef0XaHM_EUFs8zQcG zPq%3Iog>cu&U$SbX6;(0&?<}OtjBvD)!kJ z0C6QIpts0crOk3xhWwXFXOvRa-pBc5_2^7Gv)o2?B0ito-zIyV>sD)v`)&k)U#&4< z3nqHq7_92rq<}OS%fyE|bJ1X|4-7hN#t~SBuaH$$33L)Y+6O|hQy0J%OdM@HO;u`G zK)TWF6Qf+>Z$WMK?3R7EHW@CaQDnRPFa?<(`LnofI@519Vtx z$q`tE$55fjak(#~mj*!AtghTxVZwB~o+|uAKKZp(Zo@+7li;x}046l!39Q0*R-u@j zyhSyg^<$)?IRqcl++SqMzCXc>Xs0=E_qlJ(Cy&_bGAwX*ecSweQm8HWd`Tw@LH!ay zzMC~iU=38%SR3hDavLCw6*eaXz_(RAfmQfEvAvdb zII)`)0Hc?gfu?PRcRP0141Q(OMeIcNH0DEW#qQ=Z_toC64y;dhavM{<14(T_0O&n6 z18l*>+^~V(yL0kMmku&vNzUXG z^>X&zEqmfkcIA^L59Dvj0=HVSqX8hdy%k4b6&?{*wXVYwvVK+o+;-x}3KPv1*Lgp$ z$|o^j-7;c~@+})HTRXXpzH2+u($@iSP{$as1rv`myDPun%qP1R$b{~89lF-k2dwfTVAiiSXJ8di$^s=ngR92&}?ms8Dq8?LtMPK=}B_kQ*yZeETs@ zIkGK#f2helkNRv!lO6>CobAF9ScUH_TjL}yr5hrH;BWtS(89l7`Ql~)sqM6YPVKc@ z+3IKksqVdi4nHg^v&R>Z94q;Koi9{t(_wqW9lvPNlKRY2yfkO`flh4ec3 zLZ}9-$c8=(tMC}I7|YlRw0L-bV{b z!ULJ;_i7&<(%K(9dTMe6R^c&Zd1Rqg^fUy+p=KJ~SYg8C{X^yH*@fikGWmY&T~J1E zu{rh2GEI)aDtu?z-oEJ<>8Nudu)Ovyx3A>5ktVsgm_VEy0^ zoCOn!k_K5kzlhkjmDg%v{Vq}c_x`Y{>^DbX6&^!{V$$|QbavYiIIH~4jXNfmMEq5T zvGqrokvzKYVFJxL84UXRYTW2z6~41ENwh2`m;TBt z;m+|-X-mUExKj3vVhbi#Ha8?1jF|oJ{94CjkEr|SP-xS>fg`YLlv-!9gvAXuoR@cu z3`=gLooG1NKUZ-(gB)DCkr{)Te?}+me|8CJ!6!O}RfbVKIK){nvFv^qviD3e`F&aT zO!QFuMmvNAL2AGSj=(B>g$l*nPA};3$S`>J>LSG!OeEGD5}!TAB-c;whjokR)X*Rd z+I+vv5m?3dJo3^HT5>2HK6Ko}?T^BHqSh4Ik@}XUWd2S$GO9<^VNQN9(5^cuwqPP* zt0Sp;Q9>pK$lj=%d(>cSW=}A9Si%ulB{bL*f9Ag$ry;jdrfLC~zx0CjEGvHJdpDxi ztBhn!9Z&B#x{&QJ+5XzNiF9js4|3{uDS5I)-f!S^v^nhE)eFXw6`TbV1AaRZK`JFX zoa9s4pA2XPN1lX0@|lesfmQel6^hC;O~L7GPq-`PP;9}(hAG|2lbBM{-$L&B>oHBh zpsFVf{a(lsSjG3eG^aJh4eJd(n?}-Q6O_a(u$-*T8$%!YDv7UWIcafg4Am+jMEhD9 z8Bitf5?WW+3XTQ!h99p7a~4eOiuWXT+snxA40->@W2FwXNDqU;Ia4_TtN78~3Ysv6 z)hN32Yz{Y8m>B8lL0(NSBjKxLzvz%V8ZfS11Z=CH&kcvI8|PEk|Nf{Cg#l#F;< zPRgf^WQ3xnE*$+84gr0fIRdNr(Vb_j1^#+{;6ZmEZmckoHiU(^7chVO(9x`oy?a`N z;nv=8HJ~R)U=_ZzY#pVp0}E$I!jG73q*XItvV2e_+3q}qHh%LVHvW}lavsYu}{WCe-;HJr8Kt*;Fl+I_(+sy#+?yF4>9$t zA`3T0(>?Ef$cmCmqFXD+?zS}7hj&jS;Izwlj=(BBBCHKH9jHGT3C0hyxSnI;R7YR3 zWo{*TGFFaSRmg^{mM83tMGkdUe2aL(BNzeuN)R~`%>{<)Hx>uh<&FD(s`I1 z?Ry;KFWpG&2J1(;D{(v%@9o49Q|4QG7$Vta7{SBhk6dIF6Z{U)#Tr49<`)yt>BZ(% zC@zatxp)1AVQ7eb-9V-+AJ#2AB% ztr^7xR&BrMBkX=%N~4t0TT z4pTV-tNtAG7UsS$Ay=~Gr%$hb{?dV3eb73|c26P;ChF^y!WNd>kX0%Z4(+_8;ckYI zGQ5Bzu&TDoMfmxvm^>dT$3HHQQc5Y-dZ4p(8^sn(Oj_$IxDGBRhf-z2Pu)qnU)Kq` zv^mZZSXHvjR?ur#O!O6UhS0vL&Qinn_AsgV8pRe&d>CyfOiV5!g1$^RX;?`RZU9b= zFF69MTo#!KeVvQQ_-J{~uy3W6G@xfY&^YviVhbh?_3J8}TvJFErpScK$52vz>HroY z%>ffw6@Ib3@Nq;T85<|ZCdNJQEM5Ae!+d0I09!C&uv}NjJW@dB&X$Sl8*L=AS05Vp z>Tv{CIZsj-CYKcuKXrL78o5bJ3O=I^bY2(07EFX1G#5--6cF8xGGTo1ujsK+4}^VY z9D!9jMz2%@e&>^QmGVr#Jng4wQr8A*2igL*U?L>=waSp?!%dK6BBJv>F=dl3WE(hg z1Xe}8x#|AO!9>ocwcfpxb4f|2Oq|F%M((oJ ze6MSLI0CEOTskY&J@d%(Rx;72MvYEh(h8>AL;<#7VsB$-W$Vqk#Lz+}dVF@KF#+vB z)2kOpVAblDiAwjGd1THQ`JQh+(U0mrZUx^D_6BUh#9pT)r3>4)|0Y8w%snz_>-u)! zur8PwqTyP~OX)^ydo%dV|c15}YwqPRo?PKLNpL`;;mpw&_zHjJoR-e)5 zw+%;NmFqV(@^xVWu^A&jMMLKQp*B(FeWH zT{r@(tgCg%O(-NDo^lkq`Rg{&@|!k%>}Cj@1%0me$hIUkuYe4Vm5Jrsbitx$2XJMx zSWIA*aJ35=(YlDZ`pJ8E?O5h@-|lU}Ijc2b3nt#=8j;6|g=A8^Osq@p3SBpJgjwl- zC?>FKjk7gLc~(Ro{E^?zB-a|+&TR(|$2L-I!NiMJHspFx5jmkR=TpB)wu90}1F(2^ zizBc~B{-387mCT-$?}@>bc746e%2ns9WGOB!9>dV1$kW?b=e>0z19a;R!x*CH)S|#EMpaaATnn!2P})fmJzC z{$#AGjCk*qSCAi*Lty1>R<$?Toni|nnnnhY@Xlpq(+-&!-7OHd7@0uV$qJ6ZDm?3F zKIE5S(6eJF$eMJFU<)Spl?IaiUCPP&MREq+;FxfjYTFrXs?0e8tN7K#6Q}M_Hp2^& zr>c=oyZlJsuu4)jGn)ET`;n|(mE;fmd&m-h5*%4U#;%v!n0wL&&djFpYDOD^Etq(4 z-4I}U^QzV%1^iwn>J83oq(0uA&M=Sz@9>d;=wE} zC^m72zt3-S1XejV8j@}KMP#^%{M>D8rw%{Nl`uthmtqShu)mb$QyVvh!&hBlw_77e zVAY!k+9c>oA^Fo*et+nX|3ddZ@q&iq)pFHCWqC>g>GM>c0sLul zgtn~rfSStofGwEd;~!Q%>gfJ#Cs5yH#1U8(_C!)@JrScZXRWx&gLef{)!94Vyx5 zbnO8L7CLYQRt-8bR;k`LpBxL9=ZSw7_NPauxxtx01?BD>fmMUrukki6%_FaS z$#ZJgBSmCky(_qwv8zHBOz=_tZZizXppK5Pf0ZXkVAY6aE%z_pl1E;!Iz#N+?lW4M zo8=0NMz{dBV1mzpc(vfSs*|20{4De22(0?}VOPC=6`O_s+f&_sMU=3x)D^})aRzL` z1fO3L8hTpjK^)=78+VSts=F1os$VuSq`9{g>&qXtkI4N$CbUMfQL#n85i=?0n896U6yiJ)m5tJ4awu z3!z9gU_Q%dv6FuvUb)l7e#hJ(@4Y2p3np-e7|T8P+9;Oq=mC4QtT+OzY91a}UHg+y z_WY992K&!ti8`t7aJ$q5umux1PmWcgt=TO)&T<0tsm2_ERV}W)P<>#P-x}7)&#Tp| z>crMz9&nUZiNO|3;LJnjHSoJ6Zc20p!w5Z&z^X~Rn+adN3yJtnj*OO0y(~uidP2+! zEx;B`;QUKgy|wDKST@52)V6DK1Xfk6wHIQ(7m`?a*?+aA?Q1b>kQelOr3To737p-^ zGM&7dNPQ|?VRF`YiV3W`Q*113IbK9=dB}daZ!Od$hyT1G$^9k87EIuLVYZH{Yb^zT zaDxpQcQ^v8q|G*hcWE)(qb28_M^?6!)?8P@$hdP9TQI@rQ(xYvC#~w^0cC*_M_|>y zN@wB6suHrJuk05+bGDuI%Y(w|!fg~=Fu`Z5AMMaZiePWfPh;{p0;?+bdkF&;u(iPo z*}vO2%0L=k0kCJ*YKkqG;P(Q2J7g*u`FKO)n3)`bReMf>5I?t!q;DC`+Gyf#BptBy zg*^ttDYjsO-)V7Vn}ziHloE0a-8llQo*ecQZp|$xTK^4aZGKbrae@ak znsDnuOyG5iLeVVM16t?WLRPXXM_?6R@3Jht>>d!&u?KW**^67(Vgj#A6beId0c9&2 zIKFBwM_?6Rw=-|lOFMYBq&tX@mvZZKOyG41^K9!mKx~E;^ocLw2&}^X2Ue3K$^t^w z9iW*@4d-XT1YVag|88>&Sl7%F91fr02&}?>6jsZd`INSN5?Ch)q1#SQ9oATi7w{;O=p`IfK>d#PAV z7+C!Lxiws0)|~TSVFIr*SUy~NQ*di%2HOKQ$)sx`b8C>fldr{V;-Y zg?=1?RoD;Dc80P2kN2LK!_M)*`P(sp*Ci~$^uk;6BhLu5b_H<+R^fO8^C3UjP3kwB z!*$V*iyL49uS;0fh>O;w=OiN#&V+CTR^hk^s|mO)mDoyFl7gNTvog5*ABd`j`4Vm}6VX64BvKu@f<;KMaF@e`5tQKp2skp4I39MW1 z$`M$Fz3GwJX6Yw{);|Q$6aa@)sQ*=hW>|qJH z1?F75787_~!lL14pNX3YQ8TBB zbn%%f^l;bZ2&}?!b$0UN*Cx{L{??E-qBR#k#{^zwu>A%V+EP+ybI8+d&JkFJqy6md z?4d2aT4e)q6Mu1;1DL?;5|$?u)>&#ct{bd2f5Q=2h4UO(=JF2%>E%;fsMvIe%V)p@ zUYD>vCSl#AO&2WS`L)v=fmJwPgZaYs&7{+j_Hd|F#pPvS0j~ z1Xkg^6PAZO&PIwo=KviIw{ZC-n8522R=NJNvo!63HJoHw0r<193g^$Ty3TL9OF4ra zA=xR3%ag$bUYD@vF7=Se2wSl5QE~)U;jA8o!hV^vwCfG40r96Rm+ylKyvksiPGw$_ z*&jQwzH^7mDZ(n8oy7KSySPfV3!S0$m1-_;2@`mg!E%HLyGRMqu5fvb14m#Lu2`W^ z9I~~MN(_P39C*dmvfv1A#WHE#NSHS5A>DD=Qk6V1h&rQ!687tY-UupJ1|Se<{&R`xljo z9}jACC3@@EdKI={!Yeo>h{zhl|Lne^t!qPZ|i*em`ZkaW_$H!GzLK zN&M1^$yP~@;~Y8MAM8h5qm2jla0FKM)psQmFBFpRIdW9S)V?!tTDMyhj*iOLJ{U6ZyPj4u;V4~rq z4Y`z6NT`iWY&{GxUU89rSfdV@z^eXFjY(ab0H(Q`cj@KImVhmoxYXO2 zxE?GZg=sP|r=$n`_uo0{T+8;pqR+yrCac@An&mn!eUET_#SwMHu%|a1Xc~KY)Uki=8+4VtWw%RpJS{gYAC71XhKl99EtjkV_71mZLJp&!5r8&}($o!cf2#OgvW| zQs%YDBUhHl#9{Lbbk5yl^ytoh9D!Af|K=zQ@8ysMhh(qwy$vEwKYxWjPmTg?!Nizx zIm#ZZa>=ZJyU)DN6w`HCN9mKuIF7)o)dmxktLNpA4Ha@!=E&r=^m_hfy39Ndumux4 zJjN?uII$eBjWV&TW+K%uIYK`ckKhQb8s*tVSqV8rueTh{NSfG-R!f)YqV)-YEtoh| zY^c2TE{CjF%EYCI?Wony!*p}uSdPG|BPZ8+x9^xkM*gdfd!gwg676t_dh8kv*n){Y z%5~oMCvwQ*9J!6VmXTyn!D0HPR!K{h6(E$X!+^na!_sN|XcNU8H{|j0J4L zM8?9_`?sia$g?_`c#~`;NLvom%Y#@O=(DgYKe(>GSr=AW^`>o>onsm`g6OJ&|n1l6*}Zw)iT&GCKmW z1rz(OpHfAeHrw~;QrJV|?IdUFI;rP;R-2C!&ffs6bU?OWGY(r?i~uSB~5 zwqPQprn&HIa6Wl!DHFLrjHSr8r|Hs1wj6;~9+IB$dvrc&x=oJCWS%jVUR&OxyGNJ< zwqRnolb+C_QvosCA`@S%9HnJ8=cs08Cyv0X#C%g>qH6(B<;qc+wFXYoy4iQ=!?W!G zTQIStg{h#y-p;$1$wc2YDxKYQfp%Tnf+MhM*J*pfseK{&%xZqK2-Y%?K;u4ji~LKm z1rsBz?1lcv3Q0$6nRs#{OsaOiOm(83as*b5ZRsvF|6NFum&;L^c3;D!g8GN_dBQb{ zEtr@+#7$6bDkbIkC(>Id_^rDnNV!O z1l=DfEYB+?Wea3tmd{A3vGy*VuYQnV0;~A5wltp(lX@?BOTQFn5^TW)f1cOg^TVY+ zac}5`G8-i(unM2^rBGa4GDI4n{+n*CbmC3`!vsD*jCl>B5~beOCuy_d6DoX87@*U@ zaNBIQKu?mkN^E!8(C>3?zPUCm) zq$;s$<0r2WnJQH@SD9D!B%*UW09bRQx` z{Vk_$T8iAS78AHyEIXm1I7*s4WDlKaa*HFd3O|+DGqIwdbZJ5<4bgbTJ$*2NYv!_N z$?g!T^`)J3Wb>wgKMSky)0Nd7yc#6+{#`_;-)PA_MKOV^5GxegMPAbGr0w)orw$x} zRroEzd@`@yrTEPEG;l>TJp(Jkj4 zxwjf7aCK{zi?hF@6zNh;^&(jG61`Kg3cs~k&j;#CrF(Ozk&Q3+cE$u>{ae>lU1~_G zqA3QU9D!AM_QCe*cTq^;+S&9`a&K;yfeBneovjCt-xm{~R?yK>e~!Q^Jd0xY!}_Xt zpmYm;wFS!g3nmI+P=@3eN`F`Xi@Il;&=x2S<$LW__5r$enLs z6PYOnmX^^mL&tCgR^eGK+qdmHN!(SqiRRr&;^w=Uz~?Ejy<}SU;-N34w50O{j=(BB zJ69+y^V^8m+iapIuO@S|a7^&$O|09#Q7BwfN_$1|1XkfS1FJ5U(p?yLVk2z{Q@Pay zCh(aZEd1eKqb#1o+GswRBd`jume_pPd@yl1zmc9cU~Qlk7AEj1D6D4Yz_%o|zLd^! znZyxTg;#wF#mgK6y54LP-7_kgTis!TKP5(7HIViSETb>(C2|B-;ngdvxx9KhJ#lyw z?QfUFtx_?;pTXl(vxQc7DyLqZM{)#K;Z-<0pObE-ZMJTv+cHLQt8Gm1CmdxzJ5GCf zR#5G4u^fR_*qgv|yyi7f{o7mU!3i;(*8mgvlqfc*cKJjL^D60^*?l+ytFVuQy`6)b zz>~h&RKFFgw23?^n84?5v1iFkE!ZBil}@_n#}QbCy*n&(AW9$hHOr+}R{-b5!2~{i zj6JC_hMZRo6a0C1*$Q7M-L!*tTG)mounPMCS+vhP1VV=wQ@33joOcit z_{>1IH@s^EjMdpqSMK}7c_6V0dq0`~>TDETyIxA0Zg|RhIWd7xNMx~8{b+El-b-5_ zJkAkVg}u0}?x0aTgiWfTJKXni-darHb0S%`$nIg#chr9Bw0$#2U={X8vkI|IM#Cwi zt+Xr4V8#|q;FC95W!3wmA<0poiIbx^0;{l(ob7iWlLXCg*U)9HoH_3~Ch+;AZ1%b` z5fmB+Xg9Z~oQEE(u&PsnAPUPm2fU)?*7M_|s@ZHl%{Vmqj#pi=}`GtiosKvOQRnqan9b3(z~%$19~W zkj$7+P6qUgrd`Sd$x(JLat8Yw@3djWje$^HqRCE#?&OVCx}yV0@V0VdJLrE22O!wqot2otDt^yTizCC}V(bT2knwOm zjzQr*;dqNev8N^)Qf4)WLkoT@u>}*jZT5?Di-r@E)!|QvdV&e8!toXsH)s0 zCIfyDY{3NH`NS%PusyGOkD9{%o$eG9ScT&)%%{Jz57Z^JgfKCRVhbkl4ld>|+0+-V z$25U0*A{UER^fOH%Mj`u4ksEk0Cd(})&XCT|n zvCtKkw*N&Fz0?2`ScT&)tfJgnduXzv8T?tU4%mVTyu*>zJnLo!J?4FzkO#Ijp=9xCq9`DRJ0;_Pmh1G|fqyxDoO`y{X3&0jk z;617=bHIVU|Nefa(sd_}z$zSXVVN9V{?fgyTGpWzF2GsPPF8N`tb+c0MbivF(a&#z zBd`j`TNH|z6*sBMUIAZ@`vA6J0`CB3XPM4!JDPD+2-F=@b3rMf(g7Mo9+7DJ)EAg zeMjBRV>tq=aJ+@Z)fW2FjkUk%@u+CP7EIus<&1dHl9o(=OKWe%^90)0j^i!tAzF8p zv^DreFS*76w&2gjJLK6|4GJQ&yS$~d!-jJNR^fOH%R`>AMfv3VPa1V?2w)2)@J@eL zQ?}7qNYQ^w>&6Y|2&}^K7KLKqqs4;To1Zk)bqHV!CUC_9_AE(O6FZH3OV4``*`Z(()l4<(B(hQDcy%>cj_ zOyCL%Uy0#_zsv%ZjjzCUAunh2nZ@ z2dV9;ue8m?ZXAJCINriy^ce=yx!p}5>0lSY7EItuG3@-PlNOSn$#*I$^f&^maJ+@> z6Mkzc)xT~EE$p=bTQGqu-Y68?2e?RTRX^#Vc1<|~t8l!9?S0L0k-Vuo)X8S#hSop+BTunNap*j~$ckfxV3hc?ycDYjq&S0G|<&ds4x9s8Dyk@j!| zR^fPyLeZcVB1Ic&K%-+B#THE9N=j^pTl2osq%KWhzS}a6z$zSXVY!1j5z_MlO|X5Q zPO$|OxFQrg>CbzBG^w;HtatX|2&}^K7UpO85-BA+wSpICOewZt0#~+TPanf*X_Kou zyx4MvU;?XfyoE*e)%r`VjgLXjyIjyD&+T&W^WCfGBgRwGQR4c3RSQywe?*i}d`t01e+Sx~L&u0p563R27d z{%hJzFdSP&J|)UT*!=<0$hl3yOxsPg=xZv>vaBEjFImuw{Y`}!vkEec{jGhno1pc% zk~|wH6AMlxN=eUm(xL6_#15m(1n*Ymq}5#uI)MHCvSm5ZW`BRXZ6VzKP(gH)WP;RB zmNI_+N9mPrV&on(A)~O2Xg*@ZDKkMmh1HCEVnL&WECs946=d+ger!$|EhV>_pO*5E0Wvz;_ND=7PvrBrKX_&(@!Wg zuOtUO2GOiQKjF^oN@DImh#ns0EgTuOm7E^glMyGY?Iio|?qK%KQykdAL@3IvBx-DQ z&sdlU{pVDYR_yP~Rc69Fx2@#wB)JW{wWd-pA0L?E<0-a{F&6ahSCU1iEGVYGE;AK& zPuxm=KeA)Q@=Oa!)sBEL(pAJ3Oz>?KW|&Ck^ZlTQu_H%d)#7KSLg13E+=qM}U+^K4!^}v-8iz3aXti8Ul zqw%-UV^$AgvRF-yjPapC+q(;Oy=ut7JMcekjIHY;#pnh@h?jzE0~3b=?1Zh|Ye?H5 zZ`Q{7Nk&q*Ll6jB8XSRDxPR=7^#dkSpUObkw*9!U^S7&zF~6G789_AN+(o$FtcFZJ zA4u`lvOAd8Nitjz2HxuDxPD+l%gRwO3aTM3XZoZs}j1*M)GfmLyl0mAHF6{OBo zZX;DSNNWDEIm~#uUTAFYC)m|8f16n(o%|y}sJ&TEk~$2cm}Y+JgHck;YAxoG8YW;1 zCcKse2tZpAk z#|;P+uFNhcHQIwHzFLK1TiOsQvdK>x_+&BH4@@W>1BJ%oa`L2|d{q+?2TLm~)Id5i zpChme_er5Rpgl!;d0-R$b@I6I_+*fWgzt@{(_fxISE#m z??>_RiPDA+)in54y?`y4_+b|$EGaJ|dA|oTVxjMN>6XPlI{C?Yj=(BBBCHD3tFe;j z_S5wK$#QP2F!A?3q?ZR(|U%k8Wg&^sss%ZD{*ez!ps45m6|P-${|u$P8-G zv4w~UtQxw~UvQpLM)F_CZPYwUk?bZ;r|Vy~5U~Xl-`Fq8cySqNmn{=61E)!+0~{$U zV7z-5spxjWkygTQD*A zr-;djK75E57?I*LU5YMWPs$R)I0CEi6|()#`qQPGy|)qLun-YjFyWN$B}9dmlW7Totc@mL z)1|RP50cCqK^%cqe9v>{OqUvu+*GxW=X;L(w0D<_5YOuGwiruU8`suOmmF1F%Fmq<_4Vvm+caJre!@je|7|N=D`da(C(bnOKYL;3#!?d9%#C82 z`2aSiNPqI<#FCkwBDP@S$Y2Md&!tkb_pf|aMLMa{YOQ{v#VK!&z$*T#>@_D#%ciao z?Q)I9$P8;?&Ycocdcu+3Y;G&`epo^r|2R>6wd|aRlgZNPVQWOk^WC_9VB+){Tj7I2 zDS7eAnO#+z9#f=o%QMC5yLKFbRk%;=#M`1IY5KE0;wF7fF>SGxu*bH9xcur)JLFpl znXV<|L1#ybua-T1OvX!D*LR9*&bH$Efr)``*201K64LL2Ja3=KG69ojSBP7xbU6a6 zaG%%?x5Xo+HWhb7r(q(uj>2oF1(VH%$>~MpMurV*WB2?-X~xkb;?PSu!kF-G!qk*v zvNF+zuA^pxzi$y);$}(RADau`J{FPVsWRc@G+Js?(;)8onkrxmCZcYe3e~3z$pc?Y zMy%IKkT&_f6vf4JIRdLb5OX0np@_tK%WbqZ7$zOh_$bDE_7boK6P>P`3W@9-lbL>U z8;x_~rEIlt;(GT{9D!AjJD3YoBZ|l#h1|yKxkIJsQ=i2{6+r^FV8Y;xsZdv6NHYB8 zHr|Yilb$zMNCOT!a|Bl1A80E0^)DnL5i+r0NU{{MzeG&ZD-?pO&4irOMWnyAB@HVz z6NU>#WTlNI#iPzL8oN)FlBezvqboLX_X88|;f(H6MB2N`ZB(5}k~VuwV*1||9D!B% z-moeKU#3X08tcWEueJ(za=HoLe~U@+P#YSs%S^c0P((UgSyFtp>{x)G>CzH4e{t8# zb3$21bDy$t$g|xZmiMfGwD? z`)VfW4lO224CQ|GQq7X?(m}$;xbMQuKy#rd%Qud1YDtrW%mt&3ER&f1J@scdVUt-Y ziR>x20d=#ak3sQ*c;lOZRf8F^eM1TP^8XQr{bxz-lB$Gt@7@XcvoMivV=kySDMCf&XktZS3-N+ryPM*6RgaIuwWqqy z=E5muDcSwag0^dFAsE(|5)Xg59}j2Dl6GjCk-9KV5nC{EmC=LTN=dix7L4eAd6qPD zrIu3bc{7f{Dm;cP&$7>SX`8bi9U0z9EN){i9Bn8ig>NnBR2_4n58oMfzT0b)u ztxlT>7E{W|G3Fh@S9o%xrSS85IXRjvdq3I^Pmz|NOQ!jw%s2w8u%C(f+XKf+i`pEZ zjXfPW{}uLGt=BXYezN&h*bTWK`BIdmeWN+-d&&FAuwTqmll{(_|4RLWOkBP0B?a%W zg1&CN=MH=8bkCaz=ek#tY0S^0P$c&@l6-X7B=kpDaRT#rdC#sU{qH+b?75-GEQMB) z)nv_E`5jg7U@rBz0$_N^{xQs8ALscrE9j|^*$z^Y5Lt%UGzTZ#U2xs8gZ zBc++mF48!AFR^@Icfm5Jij3~)MK>Bd3JU8ga2Z@-=|SXo z`q;@u#6Cog*QP@ET$VX<{eS(5-;WHI{vQ2ER~Ea9ctkN_8)qSGOsypE{&^sG2M&@x zep0}$gB~1#Rh@>}2s`#y5&H(YAL(ZXOC4W*pbs{Bir9jQv`03=6LyBikE=5Auv4tm zVaPZ7G0&YNuqrN~yU=|bp2Pi^Jw!@wd_{B4x{KI?2|R{uFMx8ebbiqn8f?^q zBd`j4idkIEYpC?G=Tn+{$%*qJV}idQNw!0!rPj}A(VXrafmPT8&7#P^#!1@mchMfZ zJj8?jY=sR+E6I_|&YVw|_tqX~`wfZ;YUq#4jv}_;UljHZGtajFB&jcC(Z!8c9D!BX zQ>;*Y-8V(j?=qh@46_yS?-~EjaocQ`p_n4ABMa#fg)7$vCi2%?3-j_SNJgnVzcRQo zLAoB2NApWOIRdNjh_F1F%M+w{?_7Ew2sc)ksNZHQJY=WRtiB|FuWpY@lFsE;(ZCSk z2&@WzU@v4Jt0bC@|3}tY#%1w*?;k`IMFjyBq(KBE1OWxvvr9>c9atcssHg~n(kLJe ziroPwV0UrPj@@GC$3X1vuHURr{%5}bXZpIXH)m#c=bqV}GqcJJ+5XxnYTx0G_xetz;4m+az%G0rvmLqb#?Xxi z&WWG2yk)Flf^VxA=SS0hAFhdd1w4UW_&!!sivU>Cmg*;qR)iEe&TAYQBRk+Fh_cP`E(EqEh*_@wlY zj$;$(>19jBSC4oCyYTgAZPhe^7A{{dreE@vv4V*K$u1;s$40QyReswWJ)B6FblEEA zSov@ScJcR>R4|cx#%~uJ93&YlnD|M%kX}DGLbnde$m!}EOT#Z577rcr<_PS+OuE__t_ z;P#TK)FCTYd>rh@5!i)$7n_SVo=P92Cy38{17xgVV!%Ncvas7m2yChJ!HoDs8Zx#_ zJecjz5!i)$7dwUa>167qGh191;V)wa6OXms$bzDc@XB22gAK;<^i}3+as4hIj=(P5 zyVTTTR!^dro~;u*m54G{F!5iw2YJ1JBa}NTeXwrd1iJXc9`QDNHoydS;oil*2g$~$ zwWDOQMTagjRxr`|sTX;CY$I&ws`NpZgfX=9ugjvntsO^T7w(U&*PctFlhc;VkG&3Z zZzk~D2>fn<&Ga8mrQME}$W_LVxwi(G*tW-(WH#CW7w0NH%Is1aT~-hx+r86}@!!I( zEA_S{ZuSP)RiY5$%XIo}g|%FNtBs5mOn7{>CkGyGfNckr9+hLCNqc^JMk0ePI0Czl zx9mh5CRM?i-3rmBc_y8iae=(qkyD)a3PCD+CndRxC9{G#0=wp3_aJpQ zYCyJDh+$eOG{~;E7=F)B#tJ6Fw|6H;XVt)t4oZ(Yl0SuRnJ`^^YwOJs*wv1$f1Lcn zzF62vAvCWh($}wNi~IbXWUOG~tDZzU2iAazi889ac1fUG)oaBw(Uu&6U3g4n-(xv8 zg`Q+53HH3GBjXt)o>@LRYEP_2Zh)}E%H2LRX)2v^Ay*EXVkTn+6a3rr(+^YVj$Z@i zR}<_w0=o*>h?8&0zOY)a-0kb9un~vNdv+Xlld*ycygI;6N;glZm7jIw=3BaR1a_TW z?@S_&S3%CVe@{he>C~w0C(=XZCu0Q@crAqOyBm{1bKRGasNaDcfnDYuT*)T3f;Hve z-Tpf#gGOB(N*;a7hn?I~jg z6L?LJz0*IIMh~}bArAT)z!BJW{=e?TjP>(-=E~i^U|TBn>EN4U zOQyfOMTvn;oH+u!hW3=muZC*4)kf(bhF7Dh&6qdxK=--aJAJ%@fma~d`uUx)G_Lxl zTsChPx6*(K{0zrtWcG3NN)(kBv^dTY*o8+p)(5{O&~a)t@`{3o-1~M+;J(Rb8Eo$J zDZ5-gSO11NVH(`oG^&0vneEUA)Su>`Up-w59J8#!Xq3Tai*lvp{mxRze|ve6-?mX%$_F7Q|RvgJ;eSad^iHT z@Cc_o4<^%#8zzXAz1(E1V1n=G>s}|(L*Gk8*EhBtfn9h^RNn7SqHjYtik(y)WjsRS zr%5~pvnTou33O7~aLI0C!yoQPe)+!WfhzbJO} z;paY>@P6Y$EZCQ=L;htataDAH^llqbFDQhYEnyd)+p!#$BWbi`v6lFwBuK^zChjhF zCWUM!v+CdTU{NcUk&;vk^TPr;0=w`Wm0iJE8FYHP)ezI#kDH5P;xU_rC$jycHvitx zUy015@AtNXzo{ZeU>BZivt4v&GO13WN~oFAjhjx7aWH|`SlKW2taO^=E6RrJe-Zq*unRwtu@iy9(`aS;D7oXk zYuwWvCiwMQ?Z3%1u6?0=EoC1^U>9CdW+Uf2AL?`1QX1~(CF7iSoVkuy%-FX~>;0+J zlbuO^qnnHsOz`>bMIC(TO&x2gtCc%PVAp*|dt$L@GxTmyX0LNr1XBM_#*$iwn~W7q z^r^EaEgd&QpSuc?85BrgX_-g^ot-!WyPkA*CM)l5hBcj(=P0isp|mc(jZ~T7C}RZ^ zI}bUN&S{(BrnN#ewe3kAceIl>ezoEV>^kS~Mmorw0s1JvS6Xg;=t1_SSglT$GFC8A zdD4wUjob|V0u{nR)r*dCXd`8O(B}y3>It4C(|`P1f>q) z!7*QDp4h*CU;5b0K>C<{f+MgC=c=;1{pe77eT1fz6n&S=NyP;J26E!{5wztJHK|Ov zz!BKR=cHab97CJFxg*+7`ORgRVgip{?0VRbql1oK5wq94;Rx*Fvp*y6#nF}n_K5M; z+A>x!!H=9B55&{bi<`xzc^VvnT{wf1eb-ViiE4FRC_Wf%AY%m+c%)|eqRXaI!zcM- z`;|Hzfn9uNrloBPZG1ac^geAWV+9lVIf1QBTu7xUOM}EU)RH5x>+mdz1nN~o3vJ~t zvGYo!d$+oa{nMRftY89Xg|ZdiU|05urY=&=9xoa162U9^crBeh*Ism|SB7<#tebU{ zv4RQwJI0>8(z{S<-$nZ2?ZOe*#jnwyyz50B3pz<9Z=7YUU;_V+si~bA-JRAYcalCI z?Z^?>)o;ENxh!mf7G0EIp9`Tr^xJi7DQK;Yj1^4a-!XO)!ZnE&H?@&gG&1H0?3%Qv z3(+vz0ySaEuTR#Z0QzW(xiqGwk&G2g;NLMdwG#(@Xj@GiX{;yP|AGD%b`5aqM(C@} z@ME0v>$Bxy0A22GA$|YYSjGw_@UId(A|;cZHF?QS`c(8E!31{k`-8V%U zrGizDRCrGm-j#q$%XaFeb)xnwMTs2{!<7mXcz*-?nmKWylizle*52RD5!i*>kj;13 zIMC4fg0%JF9CmRu5?6K56LY}hr8P`f%i?ZU0ZSPRP=R~OkK@50=sZ; zW?yA5wx=c6y`>FB#$2z(1iuHXa5MW_nw=10T#Kz{ zJm^E4FV>L~%{*nSU;<|jv9>zji;k|;le(yN;|T1+b1n9zzrF)#{PO0~kCxqJtY89X z4zaVmz53J2`7NZtD_uAOyYO6#z41yMOhZhYNR#ur$XLMy&KzQGwSFKyFu$1;F`^Sk zU>BZiv9}*;Lum2X#?ltqPR0r*_?)7Kwu5OyjF$Au+k_*q3(vLK`(5p!^!ZZ_N%h1~ z#tJ6*72XqtVKgVBsZ{H&#Sz$r=UVK(3LQZWGyjNv54DuBf(d>FYyGtddcx<6SXrjU z5!i+2T54)*W{;*5uih2!_c4^Qf(g80#&RHI#!>A_=fwH|Q;xtc{04!od3~Hf8x`ym z%e6YoSiuBd$7AbJ1@SaKXSEnG$dei$C^U&0 z4=50?NBeUGcHuV&>lH3A{ec&KB93N>`rhDE2$b6WE2{Ah2fxzcl)8kBNADlb?(gOyG5H zHag!*r*roI$=U;?k#v)vpsGHK$PNzitx2S;ER zeuKcWKfh$s;Wq|AWRR1L6-?l~19o;oWfnab+u%)S*l+}P;Wr3uS7Y00boc73D$mXB zWUOEU=TETb!7*91uk$%FV01H%z%Kj-f#qd1&Z4=mHD&i9@3_2hOz`>CV3SGzOztSV zbic_F*oAY_Ssnm;<~;LSPg>cSA93(ogYj?8Ns3D~jG1M{Mzzxp9cXf~C{1oIaeKq@ zuJ5GnW+ZXYMu@ewVZ@DkR~jk1O3v>j`NT9+Vl7a4uB{&$=G8a)+@r!@s+X6-?mwLG1gS=X~k!c@~m1%9|swOV`<)+^(*MsYObR z+gc*s{i?;Wk@$}wuD<6&x6=3JbM5&D`_r$k9U`` zf{Di?EQry)D$tszwAH!igK0}aQ<~9~C$I~j4Z%*0xHpu3t5%a*ZF1pGjljgcl@>%} za~0fLpu}jhVi>(T|BqPl-IXJ-3+IcoRhiD=bP0SBOFKEs*tN95f?Q3lg42twxKk?F z?wTJX>8LTU#I3g+xZHD06gRgd8lhEie3??Js<0^fz%HC~%f{M^F|^O= zYvRysTP__B3GP+CEECQoI57S1F|mEQ+T?mR5Kd6LZw8$mqr!VEGQE=BcxisV)1;(|-rsas+nay(etl zIXs0<42>6OKG5Ozm|((C$BKMs-#1veONrrfBbA!WA0Q5n)#C{4!h2fSR}p7tQuXc4 z#WB_D@`+wnBqw-13^-)P?Z?pzu_E3>*FzJk#F+FVgW7#H5MQV_m$8EPGYW3yh7%nY4(}@v&-?CKSHa_O|lHqJqp2+i@PVK(s30;oA z;cAWvydR7G`dphv$I8CoUi_6KunV_>n%b1o>C~~p&HG8vZH}-`wjzI4tb>#~D-qX^ zeOh+Gbn1KlgX&~?9anQq)Qq(vyVTb~&K>2N$K0Prdv;$E3)v%TClmR#3*u`MyozOB*jK2I0C!ye2&c-f~L`jGv1NzJGK$5 zV8UvI6=_wt7PdZBV)(KA-NN8@@|+iIIRd-lLam5S^jaA7QXx!AlBj>9HS)C705V~d zB~f!-1KQ24xxJ5xA1ukt*=yk2Uxo0UJ%!dqER)BL%pq98yCwNGuUFd1^mNW#Ij<^` zBe2Vl?Ir8McCv2yp~O%hpF$nY3gw>Rvk6u(f!EmBduq1-ym4@}{ODaVM_|`Ye=FkI zcP+Get;86*EuFs18X%uMw~k;16L_a4`)w%>k^}oJ;t1^GTQ`Yi8>+|o$N^0^ z5v*W>pSLgGkx5tnXD#au-OUl$h3^G5HRmI-^y{vxa;M7ss-L|qN$9TCkl4;z)bX|? zRclv64e1{moLeVMlU!5?~vUTW=UKQtp>fe)~u}_51dGK9-NYIZEj4k zf{E|5ElFC7HSn&bLg=~1QFF~>^1ZDR!3rku?p*c-;un+X%f>3XzYPM_?DekJZ%vk2BsO z{gKVDHm9!!M>D17MPp*9rS?;KY`--stY89P8}`J~B!>R%@Jt@&-k4wo6L{A*JNxt3 zSi0xMf3miwAxB^rZfUkElN?4@p4Fzp%h%l(Ia!eW{grUQ-CD$ZwI9V>knH!Bpy#aA zqab?(HLKR3`;RPDVFeSoMc597L*aDmDs?*V(aTy)U{`gO1<|rz4Iy?)46}_*@4f6kP%-#?V!jSH7LiFGRHWkl7pb_WcPZ#_%ra-mU4AQJ&rZDy43`XqIiJ`3zJ`~qF z5YYITK*C-%1}mci=ruc*+@0J8j>t3EiQ{qP!zNu=cq^F^?WV@i#deRy$n=S@d-zn+ z=IS3|rAG$mIyo|dI1Fh4XR^mIVx4gU?PR}Ke7{`-CP!zHDFdDeS#<&Mt;q~hJAewK zp9X?@(_Av-({W*2+HgiBZj7NuYaWYp4Ar6kqg2x3@h4&Mpz(nJ?u?y@WXpOjXc9Y! z5h_&-EjjmCJZv#R*f%GGyeNJp?8_el*k#^t3UR)o3FDXeF~Wb$T6tIVp|tJUJL1_M zn^a@0vLR5`6+LRUs2U$jh1e}E#J6dAs_O7W_!QNW-6ae5*-`u8uC(q?s@S4cGt#u> zZ0K9BCl(Vu(oSbS%%7|$y435F;32c%@x^A0i2ANhU%$I7m+kbGVvaT1PR*>VAGmYu*0Au#P+j33K#%jP3|6r(J6at&Xx$xmh4=^6m8$JzQ0uQ4@VRwZe zEZ(z>5utBKO84h{7f0l62W!LPmpT&v81m4OqWE~O1P=;gtQHt}G$Qy0F@NMXcF zwZ4)VHCv8PX)G0HB*K%yg{sUoWzfhd9j?ysS7n_mg+GH6;oNyX!S~mm|rW06`5V2iNSAGPV5p!ST{D8mOOkXdnQ>( zY7K#Kl(n#W&vMW;8VKdDo~d^2o&`ZeLcy!=X;lZi#f-4{dt1zLYeNI-T_oeTt>Ehj z7cwGX4x~_1@Y&yyoVdiUs9rl*cvqiX&soZdOO?yS(d%2%gSCN@wfl9UNvZ=m@n9J| z)chnAZ|y+lB`Y z-npe1+UW(Xc;yAFo5sT79{a#g#|wTqO@L1i4???dUJ%zj0w(1UMhw*mk({qLr@fji z6@#93fch3?@bTbJcmdWhvCS+M}U%&5ds>SVwDW|pG3ii|*qRX&R@cIjh2hkH&R_Anf$W_zJ08At z)fKA`?C~BH7Z3Wbx}vybpZA=D<3X=WD@L3?yM~0PhtumhYEstj-nFf}OoCJ2b;Qg1 z+iHJJjfbhuy5jEB+iSlZ7!NI-6~c?{eqDY(iq18>EtZcARvBDM28*e!#q+L%Roj23 z!2C_EMZJl+swJb-L2ay3s>|<=$fsIH(msWna2Rb#dCVBZ-7@tDh1RnMqG$Tl|+ zQ#7ur)+Fb_&$l{^SY6nJR&O6n^-Ar;TPMG&?z@&l!|?Xvt#CEc?#XO8*WFlLclD2I zUfXh*QqhhPJ7%?^vU6{G@LD4=)lGxE`!NTeoH7=t?9w3X-R8pZ$Ht=O&gSHL?R;2W zZOn*cfys1PT)zN7{jGqjLa^p&{{R!lK?l3sfZzVSpvD}aS5wuO_U(x>k2i3a=B8mSH z2H>;=hDj1Jem)qE8!m#QeFMm?{=K16N9na19lhxGDi*4PYsC65H%w{|d0!;HmPQ0q3LOzqK~d zk;P;0WIRSot)9FT-^^Rt{b+tB)Z}~=gqCIy-7f{6t&HgUvdNOR<2Ld7`hDIvr{zJ?AeErk+6*%G&48Wsm{6{31}|phL19ys z(8<<~#RwggAT`^+N0jF6^TrA$aB0~SOJ%b3qsts|(dx#+nze&xhFGTZIM|o1O2|FH<^B{lw^y&O+?45`fcvg!=|&a8;v(y_Fg+RI`7# zRxg2%mj??vRvwH<-IXEv|L7ww3GFOk1ruAK7_z6P2%Q+sPMX@4E{#o(7F!JA3G8}4 zs0dDEmkEnm3EAD=I$N3?uo)t3!v$e(8SFTd;BD2`3=CY#;9NTKe%FTGy9-ONV<&|`&^B#hb9otDukYb~U|J_wx}Xe#oT9wV8IAuE>*qz&r6=QWLB~$v z0{*+Bj+R1Pji#{w|BK;gH(ffT`Us7!!UY^16Cbvg0-R|kY-TjeLYg>DIzB{K+^)+L z*o9l2%>dqKOPkItR81?k62`17gAePQ)_Pv;1b4TVL7~CLgQwZwy?3k({`8yF_5HsX z|Fy`LPVL)D)DCzFOCObjb+Z?>hs_<}?3GgJIQT|wE9P>ZUj}WxC)O_hM;zC$I~*0y_hu^?1p+^%eQ;iIy;|Ng5a(_^aAv z<_K?|=YU$5tE!*um#F2W90*Ukto==oSP)Y-&`x_Y|r7Y2PW=r&xa!xTUA^B#Yo&cRk~`u zNdA0_C$I}&8}>v$D@xjG^jU7&xIGNJHwn5PYE8QNIzkai2fOV*REF%A6SoM88FN2|yrgJm8iSos-AFsuS9yW z8OK4BVDN9^N1_%hHNUvSOX^|bLWe&)Az%d)&mH9zNhs_Ht@>-Dt)RxsiBZU{`VaUsqA%`!?lhDc+;jIIk&aRheZYs1b@9APcl z{SBbUZ(kI?i;l3~W&}xkYYN}{bOGNBVPwU7Q?5nWNg*BWr0Xwz=(U!Y1l(4bh&b*I zW3Tllzdk9mr3c45OWW1D)53h7z%JZwEQ@ueh4kQgAl=z(02lqt2754h8%}&qI07y$ zd#*jyR(hS(hc^8(f>SWz-p&ZDSHzNgx0Nfnyh=}s+0&moK7Pp69J{n<8-rHcab)^) zr5+w9noIrFhfw#i4+X4XqP@O8e6yWIQlBV9T5)43zkE2oF+B#bf{E;-O`&bmDP+oP zrBt~VYSO9P2&zhdDPRJ-rrS4%qMTfhW%4X$1*IGGfX z&KHyzJxk_@zmk*by`oyn~&4r_pf^xquZ+G;*)@K2lOjip-T#T?{+SzAZAH9=fc~5!e-af0K7=c`2zr zppt%F7p66BO>Q_$BGPnIIAy9u zy5CGBlX6WV`G_W|YCeVZoTbDVa^tQ1M3PV%&Zl@ys*@9Gji{k#9!lya=YBH=Pqc`n!-%SHej9 zDW*{G)`{458bJb*O`*#MTQcusIC<7vDb>>*?P$4aA9~8*ynq!<;CL)grlTDVVf*6V zX&(`m4DUvg^!ky`j;vG%y-2^?y~)7@Q^2v==@&b^sFS4&y*qfXu-LK}Ngpc^`|+kw zx-yvPso1IJ6WCh{lR#3W?MHewQ%Y6n>rR(%_n`B)>=m$r2^^0-*S7bgC$Ds*v&%Pf zF>0<4Bp=^)Ar6lnpwE-Rq@9Bc*)m3HUCWSQI7%A8vL zdoSwL(}->rRtflTVHfNgMO4-n#3WjY(Nw=bowHt_9{jpezzQZ#8pe<&F=k{%ltK); zJCH7n(4jv{O#myH=zV`8Nk7q=xGhmiwZmX2-S5_n+7`|gFo9h|;wF*h+gg#32qnf{ z`;qjG_aFIt-?;)-F!5k_Dj7c8$E1N_Ok~P|f)l#dyHwM3l~PsZCedz>*UINj!#D!FT5ZWAOPsf=n*EDm z5;2v|X}UySH2)17`zgfiAsKXR-5~kK?OFjVnD84{Oe~XwRBcu% zrTTC_lYSWDDbsNsI0C!I&n+e)0IIToF{XUUqF!%}<)!P^3RuB}>yr{v+JM8?9%S7UKNvYtsmFms9<(mV zU0SCWUyBt?o&V1Kp*7^mzv{fnCvzIK_x2aSBms=0z(vxk%wB zUUF}p@tfw;b^heivmQ{ADKf&mt3%EPJR7{IeOYHI*S#;n3MO*9`xD>SK``cf7$a1bUbN=F&Qkuw9vp#P zv64S=x)TH~J1NAls}db{(oV`)IE|=|_>wc(y}|8QHhgyXBc+!^Vd42?z@=s5pub2h z=690P=cID=z(jptKk|5DDD+yL#9~~o5opF_M=7w~SdPFhTqiX(r@7&D=}vX&?`AcE z-~4YMCXtX;gJI>2h5xe(F#Gc``sk~s)L`D4;PnAad}!)Jj1mXJW5+qHR9g-Wr8BIw zr1ggus4#(DBi96yS#v`m@2f)WZWu_L`|3zu(ar=bnE2Mkhm<`X00;joXGF@h0kk_? z2BVJusW5?EJMRUP3-*D~@m2{V8j5<;ak_?5^Qe9VE11Y{;!7<2`@xauVn*z=>Pho5 zO(eHV;T(ZoTiKVWBAfJs-Ze#xfC;fwSan_Ou~v;+mBBdy(Jnxq9v%TTS64Hlg+?OX zI%Kn`-F$_BS9@+f^d@tqNXYqG1s_Tz()|8l*x;?K5B92zr{;qXh<2&g0#-0VmkVTQ z{|GoWZyh5%^W&)L^P^(YwISY^z%IU2r-cma|2I_B3@V4yLp{lus95;0Y#-#LcoDK= z44mz@3zn_!&d$J#gw+|ll^9*pX(#a3pvmhaN~y+8qvg4^!lMN`B33Xld9w%6IUf(krV24;<}|we zEBz36rPU;;9z_{pv^I^t%GyQ_WsMfs&2%AIWpPkse*t#px{>PjQ=qc? zG}N1PA+1M@hpfW0jQC}eNtbSlAjfq(1rAmBTVd74WJK1QP2rnCsvlxDESu`PbkV@5~GuOJ94R$4nC38BHxz<_WmUkVRJGhd7ZE3JE_!3xZbSBBi5@6!h%Phu+O(|6Wx}luk zd$foZOdNRWN?dePA?j)!Bi^f}&_~-^%1cKla|CwbR%d5_j!vV|huJRHsG;2Tz(mrJ zF2u?%1xi01=aD;PqlTduX9}+`x%^JCFmvEbqbY zqt0aK?P>6)(Ji*(=SVt-ra+SaZ5HF`ngsgDJYAmKeujt@Ol)T-rGGq;1v4^kFv1~g zG9?8G^4mc<9D!Z9)!7-?r^e9%C)UY-PtFppobAb-$5}A-`UB|f=17b-6bqE?k@a zoDq5&k#z9f)AB*zMI3=$t(VxdZ}{cI3-XK+an9j1MeVBmVEz&jE10NiYe#H!3n6R3 zYeuxZHH6kTejuM&xJtwdCMp_rAP?FVKzibPMqEk@qmxcQlc%3u#u3<+_oO2c2N%J) zx9=E{)zF_F$^Rx-WGxr5f{6u7tV#UnGT4&!ixKavdeNiCnsm~+6(UwJ5pc$wOxjQe zt~Zn{i{l@H>Er-yI^yhNj=-+N-K@xDgIVx>gFkM*f_c2N|83 ziDRfaxwm`{SY6Z)1+8Gs@m9&I&LZ96ighhGbcZ$&w-O`H5ow~ z{HX2CHq`1)IY(d@E+PAR_L?5FLyOjQMCN=EE0`FNXGtEsp9TFI)LD#sp+VH@XG^*- zaS=yg7hm(1*1q(Dz3VWnbDi#)6up07qaKzD{fp@BR>a<*zYawRAUx zo0^d^Csu*O40G}FMN`sr*GhPsZNin7eUYtSFtxEWrL(7A16*@V%nmmtn?A3AuvhI_ zsT|h_(ZqeG^oXi~Bd`m%8#_H|WFP9R(T=_pCFqoCPGY?(q17KN@ys$aGluu#Nd8( zCklEIZ+9SGr%b z3;j5ReSOQ!fJ|&y49)u)i?>Y-$mZrtp~Ycyacf;0Qt@;t=w4B-N5t%IG?2JbeUE8? z6-@M*V?dS!E`^VG6{5nzlNvd?(yHWij=(ORy9Oj7eknM-SBSpFZRzE*Ui9ucH7*kj z<~Jti7tMwC?M(hBE3B@o3AL*ZrlntA0?rr1M8iaF5>c@L_N_2wF%GS@rM-trG|2EV zM_?Cj5tf;0YEOrb7wLo*7rC~=#EI1{$Y#5Ru>64%qy4SUw8t_}>Th&_Bd`m%8(SZI zuS0)2^rfraow-aooIy7-w;2&j=0XuD8FV#Q9>}(PBI&Y({^BV2`zph4B_MV-6gv)m ztjhgW3R-&%#f920R34sXkpEX9Ue!L8qc)7BPBTI{1rz(TU#P5Zl)(raBSvT}|0*|{ zHk{Vp4de*y;`90*&-f`HdN+*DTq$t%z(n|h_o^uxv!IG9F~X|VX*cVkRI{%eM_?Du zDP(ie3peGn2P5h1fT`lml~+|m2N%P(5$!~`v$s_mEK9`VLOb!M)pM22v10hSPoKqj zq`pTEtR78=l`r5j8Y`=a>Uxs`IDViFm)*$L=o{C{e$z(N`G00{3MN_?99DHGDS&fd zl<{Nu(IfKMkE7^`TZJ5fT{*8WsdC>HL4v(-+McdpaT+X(|&e^I3Wz(U* zwZ52^Jx|r98_Ns}R_gKDbeX)NbQDeew1-nR`Btl9J!Zg@aR%I9Vy7W~sgQfT9Ysf9 z*vcuGSXxl68ZOR&c5%uW6)%0M_BNbWz-NxYF5K#DZ}`GiWUk%_y0BwoX~O(lo|*?@!9KW^_;kyo16O9o!Ik?u zT>V%E_NT$*;LvdTY_&R94@_Jc6jJ-kX%ci`InXS_G_r(*3<{^)y7B~e;jC%4%XC-; zTuWoEJ6}!0S=ahA!o1tLO@dXwbp9s;yT#BvFc`?bx7A-=!nxU)XmmWt+t6SVO!}&n zYEYO2dyPg=-MbnbfnB&oSiWfDbYWRcIE`{{#I+SBR=>UKsb3riKCIo?6MacsZDwFN z{gc2G*oE7T&EcZ0#lP$d_KW!}9#=CK^wpA}Nu92E)<#e07nTT3x9f_I-tI!TO>uDV zxzazjDAmXHTi~#)w+;B53*G$6Tg;*osi$=7nU~oYh)f?@}Pdk4%K4aY{WN zt4E4~{Uhko7f(3_6PcfVg@-Su!ms{HKeq`RAueI#;4a}KM_?DNwXB++?AG+oi>61U#~?=eWJ z$q)_(W9HW^N&}H%Ug}6AyJ#T zn&aBui`gy|x6FfAHP8g9oy2xxL*y0V_WL4eEwmFS zAG#*&jV^?oE(($0b6mV#JBqg4lFuoaIC=DpFnM($1kP>Ci0ElVtmr?Qb~szc5!iK9 zmkRB*3*g0hWhV2i_^EiVVkEtGzo%I7?xnE!W*M~aZY1`8`a~G_wG@^dHx!rUv-~Ts zGDtNrWJKS(hhlNBNLq2NFQ;I_So^UctSf~%%M_x|%6f6v?MNDAF^D6u>%+QwVHlg$ z_V!nZ`k)Wu!l~i(o1@5;3YVlT_`BflR1T-&mFLojj-y>5!iLv@TU+uy&P0alo+S<^rS{t*|TjA2XVX991P0lf^}Fs z(L-tsue!|z=ikO6rrDa;T5aj=wE?tupgE^t;L_xR|gQ zpND`Hx!-}F*%SrG7qy2Y=_}yU6iab;L0gz;y$pg!ScomAwuQ>)OX1FIs4cE^X73FgfnAoD3}Eb|#ZWRqsd+)2hjdNd zjkcRt1z5qv!HotGueTI>{-?y~*uhN-EA^n|YqtYd8qT){VbWr_(8gTEe~F!?H{MAa zzo$EO-+qjXfeCG)CG76L5bpg|p6-UH+evhpNYBJQ<_PSJ}X zPd3IISwIu-N(eBv79)ECQ~zzQa)zd5X4RRPm)D!cn@ z3`3=sZA8Z=%;E^_+Ih|lHYBWq3_~*( zBS`2eEn)SDiQNiV!Ni6vQ*c|q0xDW5ccQUvi1cKL30-vS6h~m!^8seiFJ>joeyysKFZAKEIT+BzqH>4ugC zJ#Xp2DVS(iYYN)!R=`m|<=HuAQGn#V-kh$v(1s(h3zv}fL8~Citce*d@A@9Ff{E$o zW-KpY1$@*}>hW45SXvZjN{iRu;|T2HYkqjWkJRq6F@1B8t;(dDLulPRND6Ewj!!p( zFGdUD@0%8)>m^f&eKi+)M=9^yO{0CJ{bNk&EzM+3!Nj0%rl8+r5o|lF>}t$w>m%*{ zU`D?Tj^zmK;#)WJvyT+pU`~Ug`*UrDiO33;U17Hb!nBp^(K*vs@*ibEx9RwE1a{#o ztETp|Ay9H3+KR3a7K?bFXhRn(a1Sqsdy5+V&z{jy1A0g|-PtNY(E?7vM1Z;_WD9e^ zE=E~taIf=|u2;07HC^X$1a|SQ>u|wWN?&707aT9<+6oiC8_l77$UNv)qQzpgZR{)k zj%rVvk1pT{?7~-;y*(d0NSglrjoff*g;--~1A6TXz-jY)Sf*nK`+60@qo(g6A;uOu zsuzQ0vyW`$=SOI`lymm7oUvf3c(>9P=AF!i>1UsV9_<8;(()nu$1|wOw}+&o1>j%v ziV@SEkCP4$SSt@*UM?oga)$b;IdE^zU8o-I1ShxV!l9NA;5^Gd8v7y(4D}lrVWd4q z>VIgP+;Px65i6LOuH^`_Ngf<9Q`YXrIV4GHPX@`GPEHqfzq`WJfhlnK!zIYmb%of< zOepws4GxG-aHwwz=;tb{mX-S_OD?M?$aR-;M66(4Er8T14rLmj7Zf=m)@2>ArD6N71cA`;mYvIpp}0HO!M5pt}q2kCe{Hi zEqks#mMX1u(UZ5D4&v&8iHMvoFn4ttc+b4VVtl%gEIAK%l_y0;aRheZI(E z^%R)<{4^_-{`m|^9J`iSj1)KmyKtS<)V3x~lRDTHz?p`>prh{z)6?T%&ng+bzH|eP z197mR5d~aY_TFdeG-~S>^$r9p zm{5P{3vo9Gz)0)ajOaEtQ1a+%DIFg)j5`AYpZidp=MNj=dxOdMY(|XF36wtcx0JU2 z=}54GiDqGaU`HDtXi|{Mi1-vq>h5bV?J}Lh5!iK5KLAd|hQepZDU8tEJSRQHzu+e->!g^VD2E%ad8}h zU3}|)3kGSMo1?TK`Gv~&$^iJWyBpL*3Xrg?2gH5p0s4hL|8r8vaVsy$X^D$8ep_>b z&k(`Hi;NyHt~wCh^MhHbD*Jk|8Gws)YfA@?z%G1c*>i1wFKN>v7b&r)q{8PVw9^WN z`o=wAjh!RlGY;6^a9=O!X{C#FZ(6YmE12kTp4Ded5BM9_os~))3{pmSM`_!HbsT|R zxJB4+39I>ztu9jZ#p_&KVWR)R9&oy$2T1pn{M|fLFKGiK+S@$g2<*b`rlz*mdxmgD z@~49eY@}oThIyG?h$i;GXF}}k2(PrW6G@#{5%fGU%X@I>L^8)i$;`ZU_yyP=@}-Lp zc98l(bK%8Dq!1ziN!QojXY5Hg;Bj(0GgoEw9>5~{o2`iXr zlBOZNiXKc-2Fzo`-r;FrpyNS}`nhuicC`#0>~*K}5VB{ILYQd37Fx;9H1=J02`iW= z%j)m7w@EKDuv|G8$K15BxO2HZ{o5c&S!&aS?QMFH3cbb9#8FL9@7I%rBrb-c41a+d z4qR?&e^UKRxpw7 zcvv`_9!MsRS7O{-I$N|!wxM@6d2j@Fbt$bEntAw;FS-hG&SxYHIc-UAJnJD@KkV(5 zJ;8^J9<_pNt9JLkd)u8B$$$PU7;!iGAxO2>^u$3w2`jjD`L-&3p)IbuZcgts1aJg) z-P@NUd^zt$^dBr|F#_KOiHql1&`=Fu2`iYuEy7ljUqp#volNMhCw?4(U4QlW3k$lr zl3;%&hGnBNvC~>}DsJ|cu!0G`t>V-V3vf=KhP~@2oel`{a<{f4lRVY~ZnrxB*WP^1!31tY_7zt*ck%rm9r~Q_4HKQS{=J+%#e1cWole2>H zO9LXUR8F(He`}`rM7dk6IR{r~^ZA`(JFq!P)@ zD3NqM&V!a&D(y)T*+q$#?8x4GWn^S!)$@5>X2uKIBMOnd_x3y2`;Xt}alU`w@3+pg z>$=Xl&UMb?JRacsCkIA*e=Y8^*%Mwop98fDEsOn6dT>HlJrm#5RCLTRz^$s6vSsau#&%I9l7NfamGZG-?)y&HPu(->x4J25(7ohM7bk29)JBE~-zoO0G`v*WWl(QQo_n#32&%RZhE2z_;?aVq;Ibr(A7q9-fEB9+A64X_+b2z+9d856i zKbaHNYWKmuhLv)nO9i6}C8|aZg|QBgwEw4_@UmMI%iRopej5 zWN_kPa6??;XQN<&0aAq$7j8O1OiDXl*%GylAA9Rz+duY-&F*RfL0zxnTEW$Cplb!0 zoH+T(5T`9|saSljg;b%0?AijPYA(9fztuK^?e%fj`S!||O*I9Ay8f9pf*pH%>#X0Z zZ5V03u}x>&E0#y=B2_36UC$ggMD^6&i=M#=FN+s!@B(M$N|V|GL0!dOhEUu&K&M%v zenGymxX-5i>#X$DYk*XtMDRER(9Y_siz-svSoP=<^Nj7T9I!PO2p zTpbw(^*q5=`MWApZjF9n*#=<;}OFMcM@cM==$z*}+LX(kZVwK8L_bZ+V> zUC?>8jpt8dS;r-wO4x(ONEJ$aX+K*UP#CAPyQQ}ACe4HCFX*G>nluy$>iRq@Kq~Dy zPIvf&+QvxB4$SABx6-|N6JA&E{}f8lZxLQ~p`MA^3R~q;-NjJw> z9jU#mK0+fNVH#7%3aLT~`nAN*bNcLqlkfT~8?IXj1aE?Ey0(jl zg(<^eU>j>_)G?M5%He2yAM~3o;#r`mLWz3w#>0nQhG1$Q#ECYU5qM6ihHsxwbE5=x z-AGJ;5r&%9Yc#LL0vQ-A)hTJ zMPXE;2B%fD6*3i4Ld*%cw^KNFe`Y`Z^`EJIb0K8D%0Ov;Mx^+(sh0d0p zVQ5e~(7S1RE*$or=?H^Ij#jT#`ylM3tBcdCR=H7y67)W4G??j+vu#YVc)X#O64d2+ zI1=)CK91H7(Y%ckB@jmqGDhfpt(Yp5p!bQ#Cz|_XlU=4bByzNt64X^CMZ-PkwqUWu zm$&h9Ss;#CZH$I}9ko=U1iepu{pzzH*1KzpQM9Db%o{8{6O5k z%@|AiG}cmu65>67_SFxK%1tr9xvfA@7tM^xvvS${W3LUSI3Q_?kTa7KVm`}P6Me9C zVIvGT7PD+p7tOfIV{w`eN2$&b);Zz`JI}Ki*GqaN&6Za}!#Sz&U)CNeb=DHtdOsNk zXJ3_Iy1E9iDrFR2-R#3cOtv$sPy$Y60cNh1A`i{w#Qf!B5C;!uRYeO0g1U@mrNfbc zlTvnxda~HhDG9f(8o=sCWHYKzqE*#Ykl*D>t9qz2vSCff}7I>@L(i5~-Iz^E&k(tVc+oEUAGf;}6KWY1Ep1%kR9Jf}hF zyY13%^F&T`8kCB)hx)T>KdLjTP-1HHS@6D3f|NgH5GS@5OvH;FN3ow)H-HkraEskmh$wMJ} znk5)6n8W|`gcXq(TVI2{BMX2klz3nO+*=^1D=kbPE=AYWvE3>W)9WB>d+n{9@NocAg%Uk%YC&oIRjt?k zd`>jIu$@W0pUWLu1quXpxt;wcJ$&|1`#C{fFX<4qm8D2GWxoYsNEJ%dexwH(6E|yn zpWmncs*TH8ozQFY{TGn}L0v;TUzK(&)oDW??&n0b)nnFhQ5|JXP#0mPh^`LN>&AEc zvhJ}%hI-16_lQ)X#Q43|FwE2|-r{h`n&GM<- zx7-J*LW#vG$yUdUX$s*u$#bJ}19=7cLOgMX$6*Gn{Q_l~=TK;@N1V3MFbD{UY6p9jblR z;0SMH6KHm!UhQhb%}Q{Y+?>8K6p}w#j!{gO7wq!Mw;?=uGXl{QQk&gwNb3_ z<7K&El}J$6l1b~NHG8gVFO(cme^ul_*0$S4`F+t4qzWa1jF(CF2iI$B8z19@#?XO% zFuyHd=r0n~we)O&w0h73?d=I_R{0mvW=v~%U6#D#kt&o3UeinZJbRb++cC9`=gGGr zVbOhg)A*qRL0uu^Z@R7R_e@*)P;KMrkuA>|VK1ij2N1>xzaURVd-p)y1`Y!XfPuFSU)B zXNB6WoOpX!B&h3lsa*W%=K<~HCMt1N^NS5!TSHm&(NU;~K&v3o{>Z<)+J9u9i@wT+ z*CnJ1C6*m-3+ugZX`g@F$lI9sxRQ05`9c0??;#M>Mf)TFRlDvndxQJ(;GzAHDwOy) zvpK}|*{$ufNsUfe6LXpMxOYoV?d&HI)J6Lve{y6slTYh6L2?TY`YwH4!Ocd>VfAyZv@~DRU-kp?R z{P9GpP{QxFE3i8m+IKE$>_=qaH&*wsBIm8|D-hJRWJ(8kzj3)%|C36rEO^h}`|gns z?e;^eP~vU-PB3tAJ8e?E0#1xx`Gj=~+a*UO1_}gqb%?Qt?Gr<^r?05QvD`}5+J3#< zVO9uIg%YQAEg{japxAGq+G{WMz035sub2B>4igCKdNI)o+7$gO?%Ytl=W%9tSoN@F za)=y(RG~zsy*b?eo9DJ_v%-n!S7%wzBP-+!&0_?Dx~jL+hXH-3cRz1q9m2Tch#;SKP==9}bm z1@1@{O8DIKfyXX$v;_~=b0YO_WAr?-Ne=qrCJ@x+dpiVfj0w}eHdYCPy-o3m$07NA zoD))o5~s6*;bD{A+Gfe>E^?iHtx-NzDCZlt6$t98+&l;#-N@DYA6Ui-ixVAizsWiI zjF}Bmg%a1oqoJkc1#N=qJWi}EbHSG7XXGg@%mjkE=(-j^=e73<`?O$={LwEQYg{se z#vyB^&IRYd*xLZo11CuXnqGj+*F4{3*gH3`doph$<572<;J#0;VQ(R8=vC+6&hhr>HF}fxfs!(^vl{e-8T65Gf3glAhL z+$!?bS$OyuBkUSFR<2dzvK)EsY|J7t;ts8>CqQWLGtMDIUe%ZT7{;il8&Nt2r(RVWdi zJRI)S*kAmwgBk&`INk*V0%yy94ebSjy6FAqG28DtVe8|g|4QZ(@!^J9)_O{rVzRDA8@YGsF!_kzO{}@-~8+)WiK<{p2<0d<25J=o7=M zC^<#p&RbpBn06o7`mRxM>q3?E=*xDfwjmydcfTh6oUsY$+8KXJLSk^evj^)r;;FEz zMv3t@+U1q*o?PhIlgv*t-z$BADwOE7ZxVF*_*uGTFoF~M`^Mn(;zO*4Z>~U4mjkb~(Vvw{ zm-eV@;oWMFLYs3Zm~H!QKov@)TBg8>g~~3ckm(RRlQ6gsB8SybTAoS zCQYlW?m<4RITFncPOvcfCs2hFaoZCi{bO}-7_06<4)Gm@%SIQnuGg&@C8%rh`H4{Y z>Zx>Vj~b=-CnN!{S67&Se@8|YN^}Vx1&uEoL2rHa?fm?H0z#bwtY4E*fe>6L6X90S zXK8V;8o%4?LOixRRm4i;#xM<0D3R4N9umvzgF{z!KdO4~czoA!5383mPavqvzi0$p zX{iU!^VE5X@5?y6cwjr*@p}`a3MJf3o^UMw~-o6SatoDvA?%3l@9 zGluGcrj|N~+u;$9k2a^VT)ks#dCmTiYiSGLj_!lAFT%n7K|M(S&g<4npMhgGO?wJ8FY+QGEzcp95B0R72g$P_cLW7ZRcLjwKuFZM1!d6aj$VGkH zN4$zbuQe~&tx2tf`$1jwS>R^@Cd6SA$Lq|b!biC0l*ri~2*yX-LccWi+qv_~p=f;K z7>l2uEfCa2pJ^VScxM=X%iP3HHCZG)yOg*-(;pVEYys;7)zuGHXE;7-Hia2=Di8?j zqCJhTA$$1X%+yBc`?Qyi)_|lZ256K&?;n`~IA&o3Jnwu?OBG7cvj;pYmsc<*{;Z7y zocBnSpswn_d?6*A!OFu+`2TUCP87Ni(_p~MFrW%09t%}NjrC)3)tHworNb?OpssFV ze&A^00yb9acs1r8j{ehDvHI11M{oXuj_2ehzZui*VWNs+B-c7oA`8 zGg#dutXDGSwZET>+i3spFco(Uij)J5ml8ck~tdt7p)k!+zLQiT#v zt9)Vl5<6*fn!292zJo2MeQha^>g^#A)J5mlJa=1+E%t5JRK7Ud1F1rZ^hMp_L-Jy2 zwP`VLBRI|yKe%*~%ZK(72oPeUB}8|85GK1dZx_yshFo4*yQwAxwTMw(we zd{-|}&Ku$*5Y#2k^cVf8fo7&-WUVXTc_-hNl%VSmynmEwFnQE?`RlGgfuJt&o3r=v zPi$|uY}tB8h_K>C32`ms@hwi6PL(fC5ee#|t6zM6wL1%+R=L2K2t}wrNNWyyN6m%Y zPu<*n<*xi%eeR!yz9)GM@YZJ%RVYEL4DxqWhb$c0e=?Z84gg9}S8}zvFutX$+ql#2 zyp27}GO_scF1Xb)8>m8wJf2zHCa;DRRm+DH?uRombY~o|9kWv)sLL*U4wRRBxv?xY z_G9an40L+85lZUb1gcOXA!|0=?r1LAT#n_$iPQ`%e>ebMT{B>mpspkOIZ%J)6t~z1 zLpZUnEDb$_`P}SZOGXt+XlBlY#?}tf$$DzUZ>QqPm_4;8{CwYAAgF8fqnXeQ_PbqN zKZz4F2Bu=^<)v_P!e}NaD4|h!HuHyTr8+#bD?cr38;(I8Lt#OH0aAjx-n|(M zZJvymw1MhMs+V67nhaVAV|&y=K_P!PH9sD1ecdl5M5=G+xyuKjncDz(isk}AU4w@X z1%ru;q{Bw)ig5ZBU-a{s3J?C8BULD|Y;Po-dUaMBrBmMqx19Uon(r1cE1`)%P*=t8 zaQOTnUosq|uJuVb`(vkE18@s$j8vh-qJMqBX5SYn?2ft%Q03bjt9t1bZ%k+^5Y)AE zdN24IdtdVLS9f@q?dpU5U)U4SLmJ#nqW44w6z<^n-o zRux?!{%K8Ua`Pl7&i&_&rEbS`FE%tqst80UN3d;V1NSr3w?WkqcRY9Ry)N$tkHjW_ z%Zj*Y4S8Ne;gTn=N-GMfuJt>EbvuMPe6;={yOhR?Sy+y37;mRu;IsC>1~BN7j2g8jxEx6 zYj-8I6bR~~&os{i>D&{ye96;Jf6z*Jb}50Sv2eLVtkie0Izv7^#tVO+8tgXiOLKvs zF4{MFWItcsyx6Lz_UqwhLLa2W`0b4z@W_JJS)+k3^H3&!vLx2BGZp%$-3IuftBcCQCDF$nIF486} z{~?T`lnCc>eJpK*+sO>|q<6vUp*VhQ>!OWgDg}bN=$Oy%;H(k&a^eeZ9oZ7c>J_bk5|9jD7>R6(S_HgAG~p^ z>*r@_yp4CUDVWu!q`2LeIRZgl!aG=FqT%sy-!;0-4I_njEhSQR&W6yFc|{)&$MZJo zwn)Q-xl4-Or+Etmb3(Z%`8kjH&gnz zQC}dai&pODGvqH>=+JtqTg`)Wg*i1P#9G)Z%d;@3h6bW_Vij=eq7}h;MxX*4%$zn^ z{_%hbZ-aL>COliK9=vXN4d^(}cT6@lMca9UWVvwD(M7td2i z-bK_!$9aAdsn8KaFP+wn+0YfKLW!*UfpDN!l$0f@>kMl`TyWFsg}Nt-qd-s>9p`zp z;l!>OXunM7v%(3fLW#^b(eN+4xm3>gclh~_W^NdACs^myzJowe7aiyMtj}M<5vlWa z##s(X6-u1?m;iliUv~>bbq)D)s0TLr7_7VUyoEqe7aiyMzQMuXc(v0eozG@#qzWZE z-W?AQJ`He-tz5<1I9TR~4oxz33p<($1a;AIp1-3ULvUtVu}-_o5UE0m)>-M`7wYIb z@QfP8`rq(qyxwA|?(vnMj1tsE$9W!ge>M)UUn5)Y#hg zM-y-{ZqX$^z9byN~wU%ykg z<>`8Xpe{Pj^EH5oWPJRrLN}=PEJhVdBu?U)5i+k9XM_#sZJ5nV#gbO}x&nuIfuJrr z&hz`RZxTv@WxDnEycks|v3KHZFim(;T=#w?ZzHxU4TIZl($#omClJ&{$9cXwSUVke zb-Btb+caQQp@h3{4orXWzPRMQA8%v(?{qBNaX}aN@~v=snY!q?WIj(!498PuG0^x# zbu37AgC*yzAi4W-STw&M+)J(rU3(V7BA5Qq?v*KQo~y?D{Bn-K{HeDgV}c%1g%WgE zmap|GQ5fTD!E8o;W|W{Vap$M3V+@YbcV~k=pE0UXLfqlK&>{|(eaK>6Q%eMby68R? zUv*v>k5f`|*uM`2!hRGb=y?kMR$DY2-?du78m6oe2*E}6+jvc+UZYU9oX1Y(<_P<0 zl%VG+_$f?&I>fj3E=y zvtj|ujX5vu*HVI>r{L@DZ^oC}o~Ph* z(SY&joxF|(dAJA!bc9)d&PRk2A4-6X0|f}TF)u^%&s;bW&Vw(8GrfuJrL zslZPI9vFhH4^^>dKdwkrp@g^xIePdoEc|+xS@&-Rl%Oseslexn^M{~=Zx!=7;RRHo z1l{xGSRSlvw9I0xqYRLpzgc{3$6I z8;`4+-eHGa?+XNV(MSazEpj3bSEW8;VK(1@DwLq7Zg^dQgrRu+=MC1y*M?Dox@e>V zkD2%#i+3B{XKTlFU{s+5-5KYVnjXfX_ruF5M9r zpga70hj&mMPR%S}`e)V&1a;Ba2Hpn)<1p1~6>E0q0HX>eXruyPFENe9f3MS+$()M< zL0$Cy$Va$!aagS&fPLp#<*7mmafkO!ADWQdgs{w}`@?ONPNSdyOz>pe{Q5&}j7X;xVvk1v^}1tEE}?+S?-R z-5m~BUu^h)^7Tc$PQd#2N?EqeM2Y6>qXf+l$Y*`~M&Pss7uW$QR`^@g_4-OLi1h9S zEArKEgWn0GvFX|()+Ti~P=yjS&moWU{yiF}j@`#jtTJGfpe}6G3s%-~hkXatxV{Ms z$02*PfwjG8%&0;Mnu(FuaetkN5zY(PkeTfTg1Y8zc8Am&y|_oMmh$B!XcR`~_`EVwVk`?Rm+1p_y?hE;zK1ASunyLMD8 z7BpT6UTt18s!+mG0$9?r72G(l#v!km9*H|5Pf7ZZ^^g+OB|eE6iy~0JNwD_tvTDK% znG&aacZEi;J3;if)4YwGOCgxEzN;=3Y6%2&^)YmY+p}81dCw9~d|DcYk2fvR)mm?W zRG~z6VMn-musfuC{KtuzQ-V-aenWTnn2|tG*E+rSJa@Pgj2wHB6LaT8VHa}^c6?W< zrP(QIHcXm#lCKW#8H^ndePI8kvtp`Hg7!3?VIw;ZpWJ)F241uivR+abji2CqMX%zq zutynt;xQMfLJ8V$`07W%aGrViGPCILS|F&4#!v7Vuhdca`eY$H=hKK$g%Y%0=G_vUj$#>N=CP&sLVP1C+Hl_A7fuJth|1}z8*YUWxp952- z&J;!lN;JO8;M8|dfFJ7GQq0wHXp&ZoB~9NT5Y$CS2_C%@J{I3N6++tEy^Jc9sBh;A zd-{360Xubfse9=VvH)l0pU0Vr_{PB4chaJQH2s+ zez?Fpr|vL)xwFTf+fr zcM5?)8HafrarY+Sz^@%y*=IvW6-vZycY|%_;c)M_dI$5PCgR^==B&JLm_Sh1Ry(rn7~ zeZ`}r=Z?pI_m;DlSx1G;!;}znF1MXN9&;M!Fx$&kjQ%a^qJ4$uARI|?$Fd;RLwZ6`)l8|>Q&CE>u3V*J0QqX4RK<3-fkx_*b^gi)6 z<|bp|^3LpG?>K>=F4|Z4iK>RlI4!I`t8bFcs6q*PpZHVKC=n;LIS5T$w+RGwiG9%F z_c%0bHwA*u4BLI(3}G_I)j7`U|<@RjEWk;Y2C1_Rzo_()t2Ij`sVrFM23Iui0 z=oF1+&ZjhdVPwmWo!JRgp#;tDpwYC5OGjOs>TGy;nLtpN5S^kqxOXy6IBCUR*ED2Q zp#;rR!Pl0iO-A(6W33mq6bQjZqEq-OA*WQ_4oz63sTZS>E|j3zHu!0$Rul1P-t&drtLAYhZ zAK2ICtw0Da5}m?hKTIO=NQem=WBZHINEb@b6DoY)U~mY|&3+4=o7O~1P#29(;d6!u z!FZfUkw^K}M5<7NuB!4gSjK^9n0yZUbg3&4)J3CHc+{kEFzWNU`Q{uWqzWbI>M+l1 zFfst=G#>!_yEhOB>Y~vp{L8CpAT|!nlU{e@C*4Rq3?;;Qd;2Q`FnG&R?cZ2)fuJrL zox*ppcKhRrLBYCp9wtZ?O3>LkzaLY5aPZ>oIyYwvfuJrLox*4Os|MiU&v$fY{-#J3 zN{I9JFpqv%(x|pPWxs_$P#2A7(P(-XE|#VlJ1Um9yJ3m%uWn`fUa;jqeYU1vHP@FG zT_LpZU-)DY;x=?jSGXhn<>PLhdV^rZA7^DtwzEJ`S3v1`H>+fCzV@WgYmAJqr-Ojh zPRh>@E=XPFq&Ct5S!c%|vud>f< z!zB04%EWVy0zqAlf4!u8NBe?JnEI1--lzYFi0!6wvP}9>KdP1 zDjCf`EXCfr$%&E`d93C0v-03Okw_Iv?D5+w{hD%F>fY-6AkwaU_Xkk$qiECkSdgTGqI1Pv^gTJT&lKlZ>bwAthgjE+&)ww zs4L-HpcLmkM=I%fhZEh~HDsIq+?4aC4@Ig_;z2@9DbZw~l&GoT#HJ(q?2U3ou1p># z5Y%N;zn;`OdaC5TRc*ufSrM#hdPnxHibtwYBL91io8E(6(t@698+Dg1h4s1DFwG%Zcae66v30ZylEIxg%U;fOM83(AdfN5?-KF2Wjg?Px*`11x z%Aj@*0zqBNUM`Y;Z1)GR5^MUYl~E&gyn|4l37k4aF6-Le^tN~v5bJ6pBnzFdbP8{ zF&p>DHG^ER*Y|2LDA$(PvZ#Q9-R5w{uqkX9bql(mGX`6o19aP=_FB_@ZLxI63OT{F zBT|JDX3zO94Ud*TbyyvJ9CvrZUaMEjH=|k$1a*CPZ3N8@xk8?WI{H{mLJV4&El)JJ zMygQ4cUVh!a7luLXRmQ$w(btk#@<4)jkH7h-)@gDkzxY|z@PM=ApYm|ue@Rp)0!*s zcWsa=l!%JDF9lo;Rdq5st~ zW8{OA|1qjiqO8ykrf7U2cZfPNRL%;(j~@f&0gGxPC8$e$uKry2K`A3yUedodQiT$0 zBwKjo&R+%>{zG=rhgpWi*dM!@D_hxltLLZ`d0AJ|w`@%=-{| zy%~7tMu8Mt0jD;#0neQgkRPSK2h)7hadP-;=rsQixYu)qpY2D$=f_1baeX%!={*u& z7Hh%cyDN+`ih|Ko)b*0!tTg;{O9%ab+cT%_$DW@z9qX*! zAQ04b+OP|(nlccgV%3=K*nQ)%OCt+i^szOJDwJs0&Iv9+=3`yS zhq-LOS0^w$KNgypUI*%Wp3oUC#w0+`5_M(!SxGWhFB+r^Ovz~`pw9yDA73V-)rZ^gerdcwP#0Z0 z;q_Q@lku)^7TkB6$EZRH`YiBhk>2CbC8e9RY4$#Wpe}J_7`0|B*0IdicCjdARG|cY z7WjF!wqtN=@EF~?m}3G#U347dbGV1&u+@{Lx`Y1t!gxgqdjEM=$17v;pn;ye*lxQ( zP!}Ct`I(=DL~Q=jT;BL^r7-SNfqAEz)K9hViry?I8A_EcJzPJBvY;?uGB?(y*N zWm85KN{H3#oDI_O{M1HJBg9J}sEa?j#z^^n4a8>YerC-rN)-g+z4tg=$74bdQ- zd7oFSj`EK4bHnMjQC7{h$)?;C%bg9ocxKmz@W!sfY!Fy97>sC!x8xBf3|FQ5- zYslNMJ3Nss8xf_1I6PvH28T+ee^a3Kp$2Sgry0_i=tMX*s;*F{o?ojj%UJ)8_HI~&@;&96Ku{O0P0#Ds79VFT{DPDvfu)QplvvyH zuJqY@3haGco3|0)=OWv;Iaq1gSQZHCqSfsAchu2Bb~Z0gx&3=7qgCW-oqMr@z4Pvq zY-)`dCAQiIp&mUY#5MxD+-K9$!WH|&%LRhE<`uq_4xO0|_b!_9|Ksz{kL*BFkkab= zLPixzoE!g7+PGyd{E1VEvEjT5co!3;14DiW;9b=6+QI%(o z6x1n zpM3&BU9?^@k5yaQ3n%NUDP!^v3zd{9LC0Wz3c}$EE0{J|xnh*cKPGQUmm_Aw{X`3) zuYAmVD208`0UwV>{QtNbdY`2|ic$(2XEUnMo=W=-&rZ3nie2%IQa(=}E)dkUdipD= z#C0xAG*jE~-|?N5`h+NMbtf>YP(tj3e>&@9=)@qU!L|s2pe|i24R|-25AKI8cpH;{ z7-PoL{z`dK9HR;)KHjMX<;Dx(_II_W_cz%bHLiV>0hjv=1aaY|-$7lB={+QvjL zfBdoMhaCQ9Eu$5zdp&Cb59`c@Pes2#yn|sK_}cNV>dHN%^}-#b#N~6gFn`BfxbR6` z#p&2NoP^p>*3ZTp+0H%yLUOIcY6i9p8)-t9fRPzK56hL+5F?pjow!y5!SiVdRZ#P_3qe zu4BIxNb*qkCK9@jR1A(M$@8XcVpO3-^!1jy%GZ3&$z5GfJenMA z>~yULCqhBqV@{mk9irqu-7gQmaE(!g5-zo^bRKo$AuY0s6Pq*qmGAOJ`FZqpfuOF> z3!CbSc*LA*msgyaWsJ(_NwZ{^Fe}W`v(UBM?+UXYl|fMT=DO1wcc^vwCa`VRy0tso zgHNWq$~okhw^HtsAg8owh*Y73rJcPl?Ysnwa@93UhjG1?>$L;q`ynDhU6-R;>)dC! zz{5~=RV`+hm2z_X9{E94R~&LmU-x0QEnK}{4m%gs)g>HrfXT`C;rS>t-L>jXVSea1#NTY1L{6-$Oxw}A6S2Z24R2%0E+09;a;&H0JQfEq@d^n&#w!c$f_t--ZG>@-B zBkStA#owx=-+|X5CHSZIM^1HkXrivF-S%=&`Z&*&O-&tzt6S}I6J7F+`tZ~3%K!79 zckr@N4zA3VlV(duuL&h++kBU7MMLFD@)miiGZP5vqE~^>cRw2{OScrr%^!LR_k$AR z|Iyb@UolvEQjWMT64Yg!^hWC#We&ZXJmCNNi&_cF16U>d#4l!N%-ZX|ADaTdn^g$? zu6c(xy8Bh>FyYoCP8hY0Q`S7rldt^R!Kgy}BkealU${e*GPi*u-?Z8z5Y#m|tEDdN zOg7wH@PfAyoffS8*Z+zX`67H-P2 z)3udR#a9_sD4{8}7! z>_KD2Z+Qt56!LfXHZ<0yuA2%S8vk#n+N_IG^xIM?zfvR+)RoxXLU;bvOsJi%&J)M& z(O1q)HB@2`IH2ywMQu>LJB)1d30A~B)+XNV19Oc(LdU!}+F2hY2&$=$SN8uI^D}N5 z#cX&RqzWa*PS(?T`FTU&CG`$gx3W-XwS6voerYQZ)U_OI>MHKKLe%d{P8<$vp;UW) zLtai%^s_N-}ogM-&jlO|A@SV2Z=SY|f>aL8(ktWKLq7Ll^WU9Qtm2 z$BEXVPD+C=ALUC8jBtKaGu;nO1g!b?6sW83@OrxOp+lfgkGGs~uiaWP*jGboKimkZ zLJ8U)KLOgItx{HKq%6#@CJ@xsuuE-SsOxBGck&BwqsyKq%ECL1ls)eZkSdg*SA@TD zPB|)lV;Aup*lmPymyW379W;2>Mww!?S$>(_Ubr8Wpl>3+isRi{xzhKLyvL`lKu{Nb z-ZYw`cuU3Z!+E)Hx})%1QG&j^c>VKe6UC@irF`&DCxM_Y+HZIy`EdiK>$Xp_f732P z|Dc5UR-173xBRZDfzoW0lR!`x?alm*qVZXI!+J%wpBaKBMJKdZpH)a#yzhZ+-3Qvq zX&)JL$YC|{Yhny(bvr4yh-Zj}_!EkgkGt%~toGKNsyaRO4e6-h;V%v&c(grtm zk3RUhl`f>`U3uW@VMrB9(A{_bHrTvb`|8kBS(7$IAgF78X+u}brMILd8g-VDwt2p^ zl@r4=hagobL8AzGT*ekN$UgH%E}RuB5Y!cVd8%8??b}kXx9U6*VwS^|XH|0Gw>YE< zC1^AR-zyrRgF$((Xw!W6qOUQk!zQRzNgTg%UK%hS%o6S?p+Gr5qX-ArRCRk+fFI zfBaQ?*jQ~N)@Kb{vFf&b^LjW^g%UJcNTbP2+Qw>Zy)WBmg$M+7Jvn$x`lZze<9_NJ z=f;6zmfz!we633`QiT#U>WQ!Kjy%hbXm7~LqXPtjx|VOgDZP)c4YuKGkD5HZf;HYz zA_q0{L#j}MMsM-mjQuZJ)$9xMJzYP6psojZ-bsFg%;CP5I_tY{tB?nPVr(-T_WX6-tQtuNIH&jQt-@mdi5R2?TY~I1s)rTE%dCk+1w~ zUUQ@hCB*o|6pa_2ZRan~ePSsP)J1pudDP35{&@0w8@a(MQ(;%15;Pu?uduKHJQ3es z-Ze>#9H1^5gTQzD@`ABqdmZ_nz8IZA3Gr-3lf(!-)7eCB8S+PnfS@iKOTlL{OJmUf z>;qkK%}+v<1tsWN5Pkx*F_XO>U6Sw57>X}*=4h7=TP96NxeZ-^4A8E2oFo0Sx&yCP zdupv)9g*%#Rpa3v6*Q8I{@s+<@N>3Qp~RQ@`r3l}`=n)`RpQqD8nTt`6Zz-9Sb?Cf zu;$;2vp3z725wi!#4J3io3{0}9CmmxQiT#WCz6VDZ{3!*KUWDG$91}egMZ7Z6;T2~ zT|u?ui=Px|V8<7AhV0nUR(EHHz9RpNK&nvUUN;lhCDs}^SNkO=0+(&oRx2}7w&{lm z1a;ZO)^%O7!W3Fge9ws`Ws9W;ca0SL8X-s(O1vMK>egqk2LAq3f7SCEjiBtGvGR(? zBU6I9x>}EN8*XU^n}(@v6u(>rFwRKvoE(f)p~RfQpWKEH(T8WJ)Ha^DpMW(Zjg<{y z0|kP*D!re%nQu0SL}#^)kCSS$>oaO8nLT)oDxy%ruEJR=?_mIUhN*3&4Q#?@1lCoa zJoXm|>S}$lo%Fh6BS@=I=hTZ++}XDVhRVKxfk+ifIQAJU+4rjjq0gUlV(!*pHfvvP zCGXGxfuOG6UE`$vB~9Q|yxPXm#7wrnW)0=+Mn9wqB}&|vN`Gb>!)0%^jn6!TM|^TE zWu~^jKv37|Gr7|E;kMv;S)J)8R;*)_BdRIC>-iv6C=pR>pS0>HUxl3hj1w+hcd*%O zYAE&Y^%e-~n$mf@^xC8)=rvT^m^ebmhW`5}U!2ezsX__6y%(hP)mD(Z=_x0UT|dhX zHLRu#eB>bz)a6}pTyi_^0L$1LPUJdQusrQIxm&I~QiT#mPajK{BJ81Xow`yqW5sh8 zx$}>FItK)Ty1x9rBiY3}L*3r$O3`j74Q8BuBM1ELj#Qz{6bnA|gI8mKhc5yer z^bMcnw9GC7L0$hneJ36HEWvk2_1pPkWdnR{Qz-|=J0evmkuu5LKe&{qK8edtbwTHt61m^(hDa4kzzj>U@$!dL&DEKVS*R

      ue3<>&L^WrT=?MbV2xZ)ebr7+#^O6O3>H__2f$kI^EkZcl>)@AgF6=*A_5q zXd*Owpx(iuUHN>y-Ws{vg~N<0l%O#hJaXVoEau$KlY92qDG=0kDZDMjzf6Zlrs{k* z^xO!1@MVGQvU4G$3MHoh=?F(2Wq?CZbuHt>vk~}n)-u_;!5o30uCenvz{3espkkr= z=Iq+jKt6KfiX0F<4C(uoe(BM7BEKJB72RvwJMz#Q@kkX)(62roxg5DhcjI}Ly#Ga< zKu{NbCu%ec=i2Cg@Nc#IQ(}=Sl%QXI8qEUlJZ)XaKk}iZXn~+E`cC9)$hQ|tcRT%& zTckuIRVYEf`uMoJtRbx8@AKU?A_aoF=sS_`n1rr`J%fJB@Hz^qLJ9iS$7{v!RN(zb zJ>`Tuk7gzBZR(=$L>?n-SA*SN^i!^PBoe7Y3HsHi(O6qrvN{zSW%<=GfuJt>PUP9x zH}zmg_I{HmTnR_2P=bE-@w_;;L2SZ=zw+$-5P_gB`cC9IwxZHmwH2S_t1Uy3DwLpK zef%p`JDZum{UOVT0tJG)=sS_ei+)?nG)>>iH&+KDRVYEf`ZSv6x3{yQ)j!L3ulWfC zb---N--pLIuI&P6y@)`tGp#+WJ=BrU# z5t~)+ke|7k3Iui0cOvf}L;E5NULqfeGD50Qf<~3|XZM85$j|Wp7mbqx`pRqnK4ny) zg!s*wZySd@p_QEV^1eV&ml$mbd-;l;&3oO#?v;!xln}pCmrfXlZ|mmkGV*Q-1a;Ba zVP2i;DCDxB1kG5%cN)fw#GTvq zSo2U>AgGJx$l)gx>=SVGq{ggO-7}0Tl%TnnG@5=nBQQ7BjpZ#kED+Qs=H6M8lz@Ye z#;`#T_X|~GC_$?P@tC`^5xBTU4jWgxTp*~6*0kYYci{;*)NM11aGWXBuAv02UBu&F zU4~=V8pUi$>tKPPE?S$1XAoF81pgkr&KBvq3N?5rL2EGaObG9J-SY#l*!RtP0zqB0 z#t>gg<@I+!k^Gm#C{&urKU4?*TPtOyslIsqgzC9I(X5(WA9gp@iwV zaM*jMBMcrnniF^Pdhu+bwm2&NnLtoi_uB)YUn0P>ufsVpaTqTty~PT9#2(dBg%X~J zBO(8c1GILC=0s#SZ?wDI41ewUClJ&X(a;}?Y~5g)dpIY&xAnpL%dGLk_Dfo-P@+nT zhI`I!!D5LoCk`$3!d7dVWBkz%0zqB#%mUzpqboQK?Z=6|aec7oduzP?6OLuQvEES|yqsTJOchG>PmYHA z?^;7xH5*QpzwtzAksX$1_ZJB2TDWK+Sb27Zwg0R+vCOVWu2E>ISY>s=Mzxn~&ra|J z7o*>hmT^cMEW1Jf+MnTR{dL-;S6!gE{4*z>ZYYt{=G0f3XLU!aP~yNiS-YE`gB)z7 zu6{hqmSul^jq)iO{gx2+T_tw=V)lgoq@6Dq?|4*TWQSKb= zvUpnvJfyDT>|DKGzUWh5d0*XAAgJq5*)*-=mrh`}Sl!{hZ8=9a8`n_z$}2Tdg%bXH zf!fqZ4p7wUD<@u$&y)+EH&vF*0D+*cz!815+jAtS@cP4vbpwm#Ar20Tc|i-@^>%@_ z&NhDtJ*LM_Ues#4H{$!;FEor^bv`mgU6Fg1*ek8yv=HtGB@X+Y)}9^za(eo;vxWLtUk1A_`9lCB$d9>yvYG=f>5PH>*4Zg1YE4&GRQ#Xyr_= zEArltK}dI}>8|yA|0CK(Mf%XZt-5~ocEfi0<&OLEA&(HG3MHaUR%=&1_$sygs}fIb z*UQDt-^xmCpg>Sp;+I8Qqglo<&p}=BT3(eSpZM@YK0G}TsX~b@`$uS(_NfI<*HvO= z#1uKERt?2^yq`c&S4K&+*6~ae*b|_x2p@PBD&N~*TX9-20I5O=z35ij|2i~+kW!V{ z*Tzf!c+X5J3GXWq)K%)!R6DM)4QyVg_Cbrq*0QIgr80X)Z=?z(5>H+)t~0h3xPDTJ z@&UEvMxE@Gu9CYzP}is)7m9}-ae*B*{&FIJ=W4mK=Kn|4c?V+oy?^|vh@wP=l86RU z5hb4IoZF~G6d8#SQbYqyLP%+%wD%sG+C1mJ(%yS&XwOf3@87w<|NO4=_xt^FJ??St zGp=);WAel7SV{Z-oOVIce$Api*NJ7sHtq2a>otuw-yrpB*J{^IzM%PHf0q-L`=`lX z?JvklX+tEeVB*)?e67A$wWi}sg&4FhOWy8yPmXIBBM{h?RW(7|#`v|yc$YFqR`N4c zHt=~apKTcOIn=P-W(>p{|eod-pf_^Y%!Az^*2KPTC!kE_pFfnR^|O z*-CC!tAg5ngCwkALRbB&YFR>E;(16R`kZSZADz|!n%RX31a|!%dA}-TO>+|Lpsar! zzjK_qrZxtbJ|PlTFfn&@WR)IYl_`!_2$lXSwyT>N9A6$N5ZHC*bN{ME#_h?Q4$8jm zMLum<@J$QIyX`Mw1rrT}_1zyWZ%16z3bCf`25q}ZZ6Vg8r$AsAuF1mxbEh)Rzlm+( zaqFHERxqJf#i>8@Usdg>#JHPhMy9T_gN#^Dfxs?YpN02#A1opNjN3v^sgF>(1rwJ3 zch$%E(|-TA^0cd;18HY!2gQpdfxs?Y#f8tkcGsiEU2I`psJDa_O!)Bg4GZ?!6N7C^ zj7^_f(7}y6zzQoW5ZHyQN${$Uo4jb}b8TQ>f~Qbt0uy!pA~a7QIg(o*N{nx9LTOo1 zJFxtq76|OZH7EF3ZTMt*;+YlH+e0L*VB*)mLd}=2PUQX;r3aAAcQXb|w}m%5(0=saP3SMWz z?hy6d-4b?JcayM!iR_IBG{+9B$6QY za1v@jV8Wo?MNQLWZ_>^46OZw->^{}ivw-hw9Rvcqa6JfKv;WU$y5V?JI62f_!U`rb z=RDP9-Ss13Zc0w7(YIgp%p^0=8E-2P*oEsss8sitH;{TAGlE8XZ6vHQpJqTWxbHBONdz1lGzc7`sf{9N7dgS%gtng|4T;XRoAjVkXT*_YRcjSm_MyE8HIwx9{|9Xyom&QSWh?5e%gXjems zwAB#^?83Y2_(>bi-KEUy|0*v-(^jHS5G8Kqm&gzlNP3!x4xwU;I#R?|wt?oePoy;RSXO(YMo_(;C{pyVze0+yMV3)YBXyA{5(!Xo9vg`a+ z!Y(0!m}*bbj}{W2Ey}g3+8i#uN`EeIJF-k5wjkG1BRg^+U^;oCr#y)(+|1?6`&?jK zU{`6{$LgxFWBCebd0mQopc?~ zzT8*n^T_Zj?$z?|;O~|4#^`zweKSDly+(<$e?X z%6$q3N?5@J?xXTL+edrK{hR6o>k=Xm*oDUle1Ft3OF1j75$K!>mau{e+(+fL+d4Ls z+Xa|{b9jJ2U>6=)@NBAw$Jy$h7O+CkU&0C|a37Ut=`A?MJa5{gD3qM=7;{f>{yCNSAN|3OE37jX#*SzL<%DTNC%B{}w ziqL3;gQLxIkbR9=-6V-K!0=P#M8H^H2#Zn7~XQ!4hWlbM}z%D#`;kzKdc~iNj8SKgSm#~5foF~UK;wOgFD`n=eE3LOcU>6>} zD0#>^bj2ML_@FqPatY8A? z$?;x>)h7B#ZVIi}Ndkdgc=W=1mL6J~;m`<%?v*60U;^jK@vp)1Q+~>&((+BMx6u#yYT3R=W>QMmQJZvu=2dUgcVHSJUNxh%fmz}I#Cat zw%G~itJv>tQYs*o8+gD%D}dl~ zS8{T^v4j;&;H)=ZsqnkA)VJeDnU*#b2<*b67rtNZ5|xr4-jiSLs3Tzo6F5(f?_R#^ zDOm+Rlb0;}LNS3|c=W<&QX2(I>$_f-Z#Q^Av4RPlC&&9&1N%vXcioozU%4U>*o8+g zD%FSBLDJk-$K+#fl@u$Ozgq;H#|_WPZ+h<#2<*b67nRDQbchsPCd-c`UdtPe zmoSl|??~iU1>{g`CEGC5E>>DZPRZ8xiv$9@Ou&KEoj8@`{#53WFAwMfsZq_La%wHb zJ4?;y>apCVdNJ z&=D=0vf#xFi0f@rs$0>J-Kd&R)@)WPI;_;T1)IkbOuXG%P%sgb*MQL(rDQt!UlotF zEuiNZKUl13DiGK;!KEI1|FeWVJEg=h^)~@BtsgiWw4_+U#O=W%~z_Y+JI*Th3>5e2nr?)8#iEjjfzSC2TJ{tfA^Zh zSB)Q-+4dC(>{@^AuXdj4T#~U$`OouO89~p*0r1-|x!yJVC((z6yMe#oYsRo!Uc}bqNB2T{ACQ zu$oPaNRwa2JjTS(ZqT=GXUP2HO|gOr{KWA3iCYP*?$iM`?XVUI?3#MI6>GU}Ihp^l zC6BT7xI6fNc7)eax)dvzz|S1nYlkKcy~{Zns%S!IvjYXKdueH*A0UEK-)DRAST-!CSiywYQV+ji1W!izf!D`; zfxs@@O7L;i!g`RoIS9_(DWX`x#4Veb+IGi^$gcxR>r?*eyWBE(AmnXL7YOVUTOXG* zkL4X3qrrFN2#OUsr3g51a`%{)@sdp#Vp!Isb5@Ou20LCPSgHrnnZq#P+GW$D`Vx? zykgeH^UvvStwuZQ@K|!q%b3oM>7#9Sc^t7GYfRrwEYNNqoJKwmX~c;kUB}6F1ES%3 z$Rk0)gh@)Cc5%Waq8g^OaQb1T@}9`S5F2_+Ah7FfuX1goO)lvzH{nE5)NJ`j+7Ngj zeuiQN6MGxvX&)qK5znd07pI3=v3z1p9Q3JoR3Na+x}sQHHYCf? z;{|)djRXR_X!&f-(ZXl~^L06KZe0-_Y1{`Qqnk)r!G!DS9-51X<4M!sN{kkPUj73SaNY3xRpxxaK zpVbFkYg-EhcKxC6d#p|zK;F+%V(8}@vV(2`u-vMpgcVFw+3l+edf{K@^hpTBhueMzO3mB!w;BASiyvzb2sfGi05A<<$mmZ<0Nmp z(;GDU76O4?S)V<$>(d63NoGn6_xv&PTPr^pHqAuB3MRz2wnO|Zd5gLyoO#wvAh4_a z_)P7Kf@soby7F9gDcUUevhK|@&l*Zt!31t4`1v2LwQ|5=Pq032AQ0H)m$hGetvZpk zJ*>PR#V#vk&9z_{y!xBa`rsI1TQXv0zFbnk+6aZ{C4pbUZVm+hKIwV*9`>%yXfKr>XOQ2V$xNKF)&+~hKCM-JI0MA ztY8AS61-ONBpX`QKMdrBdIEu6j%rtpTX`zE|5CXhErtxEjiv^{Uw(D5f(hK(@sncP z<akpHR#8|l+_3Zq|#2=xpxfh$$2R2>X$r9Y`2kW!i_5ZHw)psG~XV@)O3qdu@X zaJo=U6%)9ACa=A7xQW#BM=xIWbe=$9msq_u>*+t*u_y?7RxYGi!33_w%ST?%>PRVO z0q}R^CV{{%TsfBKg(rQY&eH?oSJ#6=O<7Ec_dG~PPcm%g1Ahk}76|OZ6>$0Y=G+l-!uD4ool*6&Ne;aR1!?!eiy&zt6tK-^__T?v?c<9UHH@$ zzW;pNQL10-2Agg*6HZsb1nzh7y<`vf(Z#P^!H8$~_yQ`(3>6^V)=DS`c{D&ru+-OI+tH7}JcM(e;93 z&pQYwvS9-EyLg?Vc?;N^`x-Dg*HIv_OI&?DzQsh|a9)CsGujEOub9C7E%IDdQ@eF z{4vuVy0tYIGU72I_Q-BDKPel}cY!a@MFP8Uc0A88T@VU~mN%BJ1~t>xX&b|i+-y%m z&U7N1&Lp#2ADffkzdDm4Uz1q#>1Jd>e@{M7J*her&c!yChE#Z0xfdogn|jU3ju=aU z@O>1+a<{i5neocLiK}+Ou%1`AnfK~U6;^Nz9GmYe$_j+VJItjmd*%uRb{Qnau-lsU zWW)brSQq($)m=+zcZ0cASiwX{i(uCBRyUG3T=`Y%??LeRMpNmkUAPwihs7Du?6RXB zp*oacn)hUe`a$UrOX-5POt@B<@O}}*w(N8xzfY@qjHs!-p!GEy>5!|RKwy{ntJ)4F zpx@b13i~}zixo`Ved@zf7xyBCXWe;>9^vlLr_@O@^$!pT>^j)GCo{UzlMvdD6OZPH z!mnkGrIg`5!hfE+U^qMVs|C606io2{q*DF;5d%WjCTy;F;=G%NU7^6 zeQaBgVFJ5OU+`gaKCIJSU((1SoD*{*<6!>F zk2JVqLuL7_4E8Hfm$ZzsBvQy&_Hb!Eay8PD1iO!A>n(K1V@D@WOkXw>)T5r!#5f-h ztYE@ABAc09f245=b>>81_HgLFq=s&uazu>@>>3j{nPm)krkQ-9Cnp9E91b7p9lGg> zzX$%iiyus8uU|jZoET_HFwOI+U#7t0^Czftc25tiU?SmU9_xShm}Y30@_y7GHVSg) zR8muUy&4nP^}8saUH?&~aZT;Y3H{7Nmc3s#~$mTwouUR(6g%hKf41{CR4Wy|R5u}%A1Y1$oi9CHVmu%k?&JH(o zA$_W{NK4ZpY<5jsGCF7qCsyqq038yHrIkn8YOsQdU;iT5ALv4kUrgo1nB`$`Uayff z_I2$fm;vowXP2?=;IpA*`s zp|H97GToBzL$QJh{A>BH-?fS0VtHGW=a3@K#Q z|CMR346r2Pv-{xc1ZdfB3N`JwTa6V=T<df93x;_B9s*re&)Cz9`ff zj-Sb1l*Fo?x#DtUCTp6Svj0~?wq)AC>8cr9ie?^=4)`JCzmJtk5)dSK7pUk8vRHDxpJ`2NJAc0$)R(U*bOz8mULpBafB{1a|fA zF^zrfl&qO{IF`pKy)+5_*oIP_E^`T1FoCZ+ul>0-3)&~Qrm=rc2?TZ>Tri!@Xxdz( zZy3*G+&?uL5_E11AnozF&vX2bQn%gOtvKLi51CbuYJ&aqR}C9Q_?7&n^b z!00<+#H#lrf)z}N_v4c$8wMSIU-|Q2bBYPME11gt~PU12q#pT2{6(0wCr7xPO*ZC zDc5pX=lvDh@8gtvKD=x=6o)XmLyJKIfn60drm!LL`?c?058y=q11WGUXrpZB9!;@= ziBC`R+2QC}+85(vIHBt}8Xg{7B9j|E1p>QzzbargC+2EvEtD9WOVgp(%{;lp$CqLS z6SG$oviW(vw0{RF?}umjIIxRLmVbFU2?TasEtJrR}EpsPA<-G2)Q?V_@ z3MTqS7coEc4^=Ze1#x13Sr*u&UuFNgT2g%1uuHsyuB#`)^7dBp+b=yRRxp9%@wvX7 zaqzXVTCUqHMj)_DGkYp~I9IJ*(>R&`D%(Bj@a0^pJcL*BzzQbtb>rDPg`?qyRe@Z$ zYN9}3S2JxMTWUH@dp~LfkJ0aS3e;)2OzyN{BE1=K$h2xE23Dz1b&YBsaCHupvYH6vy11@Xl*XbS(Kt#)@lyf zte?*sJesW;`#7KY7#FZB@qU_|{HZ)flSUI@U`q??Uq6as1rv``r?S3#b2L7g8Jwt{ zG7*|bsc55`V1dA{P3sETewCwU6hEPl*L%%OhL7=m$;R|cv~9%%HrCu%^K<7yf`8#0 z$YsxGTWUJ)oy&zO&L#+}JQ4)@7*FegofAtY89P5x#F? zT>|K}I-#BZ{G~u(*G-EYwz>Bz^&XoN9^>dl-dn0KRb8|`MzMkkd_{P^&&iPhVIQ=X z7EB+;s9LpPF~tfd#A`Jnava zf(d-pRjQN^QD7NY&72Rb1OmH$-pXW&w;kNaq?Ga)S4Ip2qv91TcgY=!6-?l(&hPo^ z;ShH0D%+QLRUokIy?GuRq~Es6Z+sDt@$l7XXyUt>g)Q7pv4RQleylq_2BMeTV|AXc z7YOY7-gYWWGg(%(&Lx}2xO_Smo|=E77jF(G7tZ^!z@^@#-^iupX#bw{yZ_nUFRc1d}8D=JZ46Ulf z1a>7X2w;UxJc-purA;*F=eIdMwv_sRa%5P+#12z07F$1v1a48@sK6UOu)k$n$@OfG zKwy{lh!;DP8%SJ!=W^nH!BDuk^9j9aJxRE_4}14!O}u1DO>!h-KV1BAd3Z zBM02$*m*yFlHWuj^1X+`r~7N^?+@$g%f-=bZhbSd?9@`hWx6|@^;u#`QZmt=z#u4vsLrZc}Sv1+)P$FQYYV13Df>d_X0nS;l|MO<@D7ULXV3$w-Zfu-+0{Iknj1z`llVDI&2QqS1BELHRf*M!X#dPp@Zb`+c1w5ZE;{*_nBD9Y~(dJ;RB!S?LgRWi8FQ*n!+?qGoHy z#}V(l<>ccGi8ZVZBOBEl32i~x<<*hoYWQ|eEP0X+ZUxKfsBdcp1ruk&BoxS`QQWZj%M|Y-J!Nk>v8g|gLANlz6 z04GKjOn~RzO=-DqxIkc6?!F$(qbihqx-4^IdDS?u+HjTh9aBiLf{EW_dobs=0c1_= zVNMiv9t%@r?1_25#R7p{_x8H5Ygr-u46c)$$nQ1=)`vJ$bXR5`)0YHf zo#I68@ez>zbS#UydRic`Yv`d)tidc_(#PmLCyoW2k^A_?!)wDSbjq8{+PwGE$!L2s zdTYfsZA4fR*%@U=lMa-HVT5y<8}%J zcGV2Ksm*IOg~VS{&J*6zOb1+V^no+hyC_yLf%gUQ{_eEja>SJ0aP`?~fxs@;fIHe@ z+a{9RNA!3M)tm-k;30uQ)+ve=OyJ!LJjPEQklLuhVc{czz^2*&vcv8^e`^~VhC_>uo8^yX4=7eJflsXD zvz+H+VXn(`*=y+~fxxbpwGQk^BNFX!2~{ellON$M#5SX zCs}JMjHhJyH-1PVJqK6lCwG&I1#Ng7Iqn3Vh=BtQmkO&L94FJI4YS;o_3ZKv0c(3 z+Il6IOjyQrXN_z|lFjkJW5gL`!`Tn_NZH+6LLUda29>$7tR5qX&8kXH zwBH&E4RabxekJBwymE}!x$tT)?}fJyhL&YbrS}VlXt9C`ykf>@)i(G+WwE8C-dHOT z*o9Yn`H3NV{s1j4B}bnVTC89KujBCRH|hk`hwy1meSuF zMOv(20O!3170<#jm+M?#XR zj+D7zjX+=*9+B}}gDuf;>%b3s#PEqQ^1_7w^boe9O;_^y^#Xp+Tk8&iysVEjw);7O zz%D#alr{s4N%4g z*CR$j@T)EK-Vh6l6-<0u+KYwgd6Q?UTRBm8KpIT@UPkAocMu5dGVbEVg6i}ksm{AO zG5>rTtei8MuGEd;b;hd^Lgz)3fDq_+=w z@UWT_HfbrKY3xXz)t;nS!9>qh-I-x$4`LB^loLO#lAzu-RLR6-?wLc4n?SJxCp0q%I_#J1gCnNdLpa!Tg}C;rri!<3DinZ=w20)btP_jY6xx_2edozHQ?JfuI|AMuyn zJ7ywb1rv4i>{xZBJt+@V#s>AOMu3IWIePV5x+czvu;Fs?1bz$no*$EO zaC>(GeQQGm0=w|IjlZ>{$HIk+-RX3aL9v1f{1)(jqGl}YeEpfEZk;U<*oDV!JnP;+ z4SKv>ObRPEQmkMCzXg01`N}A$XgpFgU2{+%unUj$_-NvMGE8dtP5a{eMT!+n;AfiW zY`;r{2YxGA(1LpcfnDMVGTSp6S}b|bDn|XJSiyw&evG&l1!jIG^5LJq1OmI%ZyeaT zKYhu?xJ&#=eBLe$?ngSw!;aLKu!0GEvN=DgY3(2=%IzT^3jISdfn6bPc5G2f5OFcCTgkm3w8q zy+J~?X-t?~>acm=o@#!FDlJ33r2FzZvkLh_MW{ev7p^qNuWpaEGBHVjhX2ZG@qn#b zqpW;VSk#Q3DA=JLre8n~oM|TPSLIdfI_#G%md3!CAv*;H6L=S9ZeTt`?|fN~cL@R0XD5Z7dYHg7VLZ#5o{|6k4g`ZAj|2j{@XkO!n#jE`pB>x> z^c|iE`;Re!XTtbC`g=EJBVBK(e)3l!unT9d^R=Q?|H+YG)ey4!FU1Nb@Jtx5^`hbL z;2Br27;Y$G0=vYF_}cwHWm8RO2rMv=u!0FZ6UI+WU-CgtU(p_tyv+pyyKo!B@8I`( za5={cb}ca#+7e9Q6XE%OgE{(;Qm;8&Xk{r7*oE6lK11KS1+a7jsGDUfw4#{6r@-^- zNn32-L%%cqWXW+ZUGrHNQH@ z+Cz5)0=sYzho2_+I0=Sp4dkaMPYHb=OyHR?-uF3{2s8WqW<{rO2?TcGz8yc6-8=;v zI9Idw7mf*iI85M~Fuo5mITe~uo5oTLss#eO@G6H&m0pz&87*FDe>7YxtY%;WuTAkj zHP4MYduyjA_EM=pU>9DkQO-A*2zQbSNcs0M!m11=@QRsA)$#E}cr~^zJ!s}95ZHxR zom8qiizmVD=M`2f_6=SzRM<2%Tq-IqW{Ur<)!JohBS)m5=H zV*W0=aiJe;_qZboD%e5rYUr<0f7ZUaH5oBx7bn`&;n3bJmAXlXC{{3m*H!s*l`$0D zTDsHfy;lVSyEMoA*|DchNj)Fs|G29Y4-E%;QBT{u6f2m(tIK?5;!iXf{!r1qd%p?< zc12kFvx#H$$hGgvd`TO#PGHgRBYW!LA;qKwviaGzn*W@45}cj#xpxHn_4B0K_O&wa zv-?6fDCvEj9iv?(tY89Xs_;?j>u&H!t&+Wovp`_ilfVR4lhHz*(rGP^u_VPC{7=4P z^{?7WSiuC&RN*To`aMCv)>!^H+gc#7E6IB#J0>l!^gp_k$1v_43}620%O8@BB&=Wp zXR7di`~Cq?d)-#au~# z`|%>7EjYF@mzz%Wl(2#c{PgfOdQ%&i*Soz8%u67!Yxmb+*4)QRU16fkC)WG!05?9i zlHZK=kg$RY{PgfuWK~CKli5{%(al{TuuJ#VV77Pp)yjw|z1Xb}YkKTfKBXkMZ6$4ASQgk{8~pD`5o_`03%Z&cWd@G-0fK z{p&A^3GCW3d;`{_(UxVAuV> z+05C0q}DM++3l3tZ8*F?e49QmA5BiijAk7N8j>@)i6r>R1ZMd3vnDJwne2@m%bH*N zt69-4lM~mDra;?W)wD?@2nr?~nq{$?$QsScK{=erd6o(rzU`$ptqdvtTiEr{Y&OXXTzp%^VJ6F7%~+9jgTbyY@{V z#d?khjY*o)CSK_j4?fe)Y3z{46f2k*?=YHuzPenK7^tjGto4b66BoacC2i|Un82>* ztrOYeSGzTd4V5>l@Ad(3HEkiO=-x!a3MNk8O<=c2lxo@?TF;3AHUTh9b|rO9S_%Yq zt<4_9!mn-7IGB`k;-sn<4Bt_&@_nYQgcVF&SP{G>gd;aTm7}RqrCB7RB zB&=Y`2i8B{yo1TOu@0Y)E~{ZHg64;9eBp=k+-rGUs0*xu2d11a|4! z_^{wHmLxe*x#!RCMnkW6J4pR)zbIBPfv-B>i8MVDj(@Tu)!%g_OkkH?3lFyVXe)Bz zo3ie_peh9PD-Twkdt@YG1rzwH^IG1U`@#8w0%p?HR3NbHUriU5+O##PrOFz;S7mST zx^;uKXk#T|1ry@^C@J>>4_9+}jlQiwU>BTj%k%@8XKi!)Yfn_Q3`o!>30w%>KQYuFo%}SiuDD!>d$M4c{x1Q9=*Yogom|HT=0R z`{V9LT&5^($wQq~XxufIrkz_vv4ROa%HU&z2_wP9H;VcnS}qXSET_XV+?drBa%3$N+%Jy@QJP&L1t$R}!r)jmw% zXPRd;PK}3b&tRfz^+q7D3$Og~YSRw~gU^a18joIeB&=WpzXdAQme!$zwf% zz%IP<$1?$ogW;9UY?krISi%Y>@LRyYAL|0(oBW3PzcLjF>=IWL&#mtXtwOBi6aQLE zSiyw&eiUyW2C22T==;4u!b4Ko$MPm*!R>KE9|iAA=4&j|MnK)l!*qT~BZ?K=N5Q=h zUb*Gy2)OOPhhB^H5eV$UJAipL#Jwpn@X-=F?sg8v3MO#xgV$l%kpx%5XHmbyYXkzj z#GS=2OA_J9<#@Ws{uspyCU9SZ?=dNl1(Q}jw3ppefxs?LlSJmw`HJSJi;^9kcViHI znqx#Q7T1xmf(hLF;9s@Xp>VNV4Y~N%Kp?PdMCT~h_`yld=TTdDjNU8z!Lj=zNlCJ) zgcVHS-UrVFyzB?T(bF^|(<}u7yV{%eX2T=yYN8q{`Mdo_ctP=LJ+>{UgM<}K;NAzX zlgcvzBmQk>yXSNg2<$T4=)~;Je`)3%R&ou3t~L-Pg10|X4RndQ%15*bI zeR!2BJ1v!Gl2_9YJw^)(Cd!)RvTCP`nl9f`c?=hqQE+JHKDwt?D-hU)d*r;*)W|ew z6tbK?Gti@0!9?dyQ6!F!#bob*Yu5?#bZ>h9|bQy_oKd5O9TSDaF3jiScas)`l6O}#H<E0{=YHj(Wp zFVZ;cDtSvAt%gGLzA8GWf2}}Z7w(bsb)53SaInWp;^n21u!4!Gs8Oud*$hqWKV?tD z0o@Q-J|>bp@M|Iv*oAxKy!u6bf5`r2rSa)*DPaW@!~4WBW*V>A;I)y*s7d#R1LbMj z{S(>?1a{#bId2p5J)maY5N3L|vxF5)l$H%(uAc^LT6|D4```X?f!Km=Ec%G6KwuZ{ z!}Cmzcn9zZ{=p{aX(X&*BF4_0*9MrU@x83%4(>JY0QqZ7WfLzd5ZHy^E?y(0Q)_tp z(p_G|&soC?CLa8>W^SKBV|_-+tg%Y5h7BS9a=>p-fxs^Dtv#Nb02>Y-p*{`;LLUy- zwZOeIUTr#XDA-$9(1Fd$gncZSz!fWaHN=Vpxcy`;^{ca4Ag~MXY2h`UZYDsHLkT^- z^Z>;QCh&KKpZU@)9yDhs(6=t<1p>S994YVVr^mv%1O9Yp%oAbcg$ev!;WLm2qhRLz zwsb?`4}rigJPPCcaXyAaeE1i#Wu=~k6-?mo3h!Sfg}_9+GP0qQkw9P<9)UKcXeiOa1?GA13g3g|EtF_XfRxZCFrb8-c(sJZ|HeXFCWiX>yRAi*=B&f(iUx z;WOJ>HKb+KkvG)oC=l3%M;3f8V~z_1ENLriPB=?g!G!qi?(E$i8rbxZM<3}V5ZER5 z$nKa70Lv$h;QZ#s^z7$o_U)f7GyU#P%-aoT2OOKSFOz+V*`j1Nr+rg4b(=eXqrSfw z2muf3!OpN&6f2lme>9DCSXzgL==ySEVEAB|)9JVTT%{ur*j4y9gY_9!hi#8iVubTq zwJk2s<#vslP^@5LX^SkD9dcirR-jZ0F-}W_r}t{)Q<{$i6WEn#md#SO-P4-tC^2UI zO@{nG$K=y9>QSs<;z&^*d;08v_QB^~ocIzj60YbSls9#~OE7_5g~RjNS<3_3#_M}< zLdP}@f`Zn__0PT`Siywtxv4CmeTjBexDsRUjSPUh^JS+-Cjb?&r*6x}N8{RgNpEq495ZHBo<_z{C{Bu>6 zT8VMWBnO^rfL$bO305#s_-O`n>0nWH_O~}Du0GEJ)t_l>>GY`rfn8z+nzCuRu)jx^ z*058WP@4u5MF}&RS#A%t&G&9RM*PiOII*-)v#aEv2LCPW!qsp1SrBt_VPQoI>5w*9 zsEdOMZ?BomHIk_Z{;!hGQV)OFQD_0qZMTvwH$vE_cU@V>ryU7?ABSZOVGXa?u;tK^ z|El>rf?!x9euCtma|A1x!0#sC!%M03oD%Ts&>`(mD4j-k&2(Wic8ow^mr?ryHu=9j+UzDujK#mxVTj`jna-O_u!0HvZt~VAejF?sS}cd27$^|f zb*9}kHqCpsc0`Q>kMTNWB9tv0BgbCICRo7)em7OBgSMG4Yi_9A^a~XT?D8I7#M+GW z)iz(L#3=Ha49gta$vU@V2v#tG-%Z{oPR<687y7b6L3@F~F6U=6*cP8xRi2SbjQiC& z(8Xdmvrh6PSiuB-)A&xLVY%Sulg6GbX)F-fWw&Z3E3?qA+SN#jvFmm&>>!7=%eI`= zU zm6TMf-&VPB@AYc3>)R!v#ug@UE5S#?mbqZ(HFc=QcUe{r5cfeDMi_6-?k(n~x2QvtjnV zGi;~tOM$>HTw8`eB{Q?2Vvd>ouHiF+6-?l-4}YUBPJ%~WUF0*(>QhW$7p|AX_j4vs zfYJ^_7hZQ9{lhHl-US%iZFqDHGIU=n6`C+nJAV=@TD?JgqS*uiofxs?YPl{jN zuS22klBIIv@0*3XQJ4@{^?OyOz)FJxSzW$RAg~M9#Zsx(C#S$ppOJFV__ad)D@@=l z0)8G#WID9^rAj@LH4Iv#AsZe`tnOc5%|VFFj9;iK)TnPB?)m)2lJkU(G;u7Ah#`mRlatlhh+ zW{-#!D&t`S*DT^Kbxjt$l6sQAx19t6yKv<{WxqitG?}!J+_pz|`)7gE zsXA1<%UB?=3s*4YJ3t#|!u+om^yAi+6f2m(HNE(p%!`SzWN$FF+Wt(aZHQgC5~E5* zdrtt{WhvC+)kmS?A|}X?eD>|(CQbjSG5q~#SveL`KNQo7N!tVhyKsF-o&$NhGtA%Y z0lRy8l2w)NET|@sRgShKizD4wx=9f0;^-)}+C2B8tuxrG-5}4oT2L@i80N#K^9+T= z0;Q!Mf4B!!9q$ZP(kp?$F5Cw5ui8it(A(qyUtZc!tYE@CxgWcj;KGK5_2DtRV!gm| zbsI=H>mm@?h1+0$zQF`IJRP>5!>}vX{pm=`orr`9WZ8d1fnBy;Wn7p_gUE= z4A%XTH;1jFSiwZ==gBO)@mKA)86$a&RTg2;>*)*m%)d1PfnB%_=1+T*Fc?Da$#G|Q zQ>>A?A{Z3jG^|CuzB4{x!2kXfxs@@2J>0YdxPLYT9tf_uPR~%6ZcEU zv%rPRwH}R?^^Z66V_?en^>RZQ1OmHo8_auTw%zSR0=sbjC13gJ zVg?a?`^iRzeS|zqOicSFu?Hbh>Q;%$PVe7gE#P2;r`+AwS0Jzp=aKRmuP?^1cz=Lg z^{20pFN%pQUq?2L`Dya`iXbnnn%ETT7W9-o$BP7Z;p|pkX==C)beP-=HZ!xlcz^?_^m&I$@9(h6PKu!JBMaZG8cA+{r= ztX0F3=idYZyKo!KziJ+xAS~AnT7)`MtYBhTmM4pS>cw6kR9fnu+g%~!XJ^noMg;=9 za2w3`R6pqke?1)FiZ+E}1ry(9_GPz=omr+qIFG^S=HZlk8@QX0DG=C&+hCppIg)^P zomQ}u?`gmaCPr@$V_kEtShuzDJjT6KK47=N1TL!=2?TcGHkh|?jeElEe}?e!*%pcw zO#HeM!}4w#Ft^lEJjS9r{xH|M9z0LlE)dv-+hE=c|Lg}h*Z-6~TxE(COgwlzjI}9v zqn!{viO0A#!x54}y<=GD+yB(IlFMUO^f{AW7hOx1lE!sCtX7d={1%dF-Wsls# z{+mEx7jA=jz1J{L7&K?EY<8isgcVHWs$$uM2eY;D@ybf|@%|FHyKa&%v~4C3*oE6* zUh!n0Gh9vBAg36&ldysbU$1c1pm31Z>WH#Zo#EmHCt5F-)v5LZfnB%_<}(w4HgLaL znY?+Kn}iiiBrXnMmwGqV4)#|v&yrl)KzH?YIitQ>Ag~L!!MtCh-yGTvEs#Iv^^&lH zi5b@3%uz0>Dl%6x&q|z{LsW5^ysW9OKwuYcgL%Jwh9UHtohDcG4wSHhiQs!~Y-h$C z_d(Ihu9WcUjbYXC1UdL|fIwguZi9IX*IAFxwU3b7_79e@f{Cq_ZP~<8R+=rRm70LJ zN9u#!wKzGujYwb@Znb%yrTsCjG$I#XB;=92P6h5|KC@Uo*9vzcs0%TA=I z{o<=ru*>ar zsaAjH6qXsJ5IQMIvOYa|s9?prCH>SzfRzo0p{6&GluIiV& zwUxieu~Dyval+Pqw*0H_AQ(0OImHSl{yo{Qy}+xee^HO+#0T{XIqhHw^lA1%Ah1ho zeo4F4B$=H*p23M)%Qf=wq5v4%wVs3(OfQ>^JCkd6!(iwKtfx&=Uyk z+CT3cVH_UO8@S0-=r9yu&R0y4gdgcVGD8}nS7R5XC;JuT!!Qo|#%I@BG4N}CD< zc3s<3k4dxqnei-z*fRT|?04D;I#08fu!0GzuJ^P*+&r1n%Mwmp>{=;*nq?33Dmn-R zcC~B!TWfr`2V0+~5C&Nr1NT?bx`EWZLs0a-vb7wq|M%Qrvbr z>Ek+ETe`F(Cw}@(lnN$~k)My4DkzxPICUC%>{qNk@?BXIUKBY_+CH#YUcEhDAh1if z9sg_h_h<*7Q(_$ckS?vUS|P9gHlJVx6Wihnh(VJB+M6-T`uQ7=(bCK5d*lmKvIGLV z8jYMn2B+6(b-ybyB5A60<-=il`22MQE139TkV}kL-P1-NQeq^Y87?iEe?#`}JX0XB zYf$}(q{X3s+Va+poLEMON{@0M%kj2*2v#sL;L|vAE4B`s&`{}%&M=FW^!>lf&1NkW z2<#ffGakDiHfC;KN{r?8q9hVf7yOHk5UgOL-Ru;SVBM5G3Q=Nsx`as$s3BNatrZCD zI+q?#nw_&@nM0Hq-&X}mAM{M%*{aI~E0{2U6-z9B+OiIdlo&Bx{H2&F7BGM94uQa~ z#2aB`z^ksTVYU+ELWf>b*IH{>=lg(Q1rwPzA>_*~7nX2ciBV`prHWhjplVww5ZG1O zst@t0@6CoRQex=s>LI;2+!-{HZwXc~;nTMliQekXCK{^ig2 zp0s*5n0cO1Vtg^Tl#V3(!ZHgTiWN+lpJ`7>1HKHqx!niuO|_3@%2N33GB)} zsz*%qGFZkNCC1L?f9QtwQBcy-h++j3FWTsmG{1B<<*E{6=F69~>P8&gJ@=Ae0=ouI zf2}#ub~4-dM~U&I>Mp%fZzyP>Da8sVGWI^x1UJcIqkbwehVDE?A1p`)dG~vQ3G8|s zdqPw8g`Z|-p!8(^kE-(y=;?do_(vf{SxG1%J4IIO-g_vKk)l#55z>-uvLYk0NA}m= zTej{w$Ijk+Z&JwK{LcOT^*(>U->;tN^SSrA&-0w;j!($dmbxeN@y9A_s34(NKc)=z zn?PGQ7jwTmhT2N|m7K1 z9PV0oBgWZdMe0nqF}%rUlSH7)tobINW7D!|rjrq)uENxu-J|*Mk~K9{kQnT<&gVbz zTaD~x#CY?GsD)d`@>d;-Nd&quFBMPQJ93p}hsN-3^J{9TAaSqfXs;<3rqQE4j2LBy zF#VVyre(+kx-c&_nQUFWsnfVLp1rP@h6)mcKh4PtN)fmscI2Hy#b=Z;QrB z1iCOU6(`&dJfyi6gZZe||7oZo5%s;C?&l}A@aG!2=+%HKY#bTD6F+Q`2y|gyD!Lg_ z4cOIY3EYC5(ojL750quJZz(frJ! zHySEP99O36TL%oKTUQ&|>yb0*Y}WE{Zd(3XBG83-sra5Bp2XJm3g%~QOAu6$Sd+h5 zud^kdo*iLiuXCO*V5gpT;A6ZkB?4WTmx_v4|HW+Y7(ZTOTLpp&67Ta*>FzxvX;I55 zBF3rEjcoQ+mH#rclL&NSUTQLhR9wl_Th00Di?s+UNZ8$=dY3V6DQRb%eVv@Pnk}E{ z%IE)SAQ9-oyi`oRjGe_E?ykj$_wXdBAaUo;Uj2iYJKbArnTWBZa1JYXvl_pss}g}O z%w)y6yLThWCc7T&Li#=_V@>y)s?HtPS@(?hS21T4bNV-j6J`5I*6QsYNkL-b(aCDO z{T%(Qtuf1a{?rg+ad|!q9dS+~(1kgp$;8SIA}9S;vxvH%R8){~9haeo-8rE5-C@L- z<&{yMtS^DU1H+Mmn(N! zjj(Sj66nI5QS68x5lcSTd&MTrs-U5Q#DN_{)GPCg(exZ6#;4ZNq-w3-ti_O$5`iwv z8ATW1ayZ$0*PO4(t*)VhL{Pazb(5I*omI=Ir2hWhg=~Ik%|HGrClTnvoKaLDO9zs! zo)!6(*$p*Rkl06hsB2F;)AiGg7-!eFCGEHa@6oK9M4$_EMw2PPuQh43tS0yS&_Y86 ziTRzfAy=jM4$_EMsaRpc5`y(i<>y1*-AqNiGTfk)h>@) z)AzpZMT}cDT*;kL9z3g+n?#@sb4Kw-HmiE1mFmMIzjn}2K_X*zGqs);L@gE>F)W;& zNQ&mi6AD{O1iCP16#3P8d(tAQE&rMvs-c3!wwKPTXa6Yr^~L{V3@%49UIg;71)4;l z3v)(MzbdpO4Mqg>&9*%>RFL44Dyn(0{pgg&9mK!mLG5DXYhpOx>)KW#(1kgpxKbDY zqItze^4$;nYN#NwXM&lUTzMe%8)C#5y85YB=X6iLdu=C)Ko{nW;_VT>H?%QzV|i1S ztf7KLgZw8-{i!2q=q@8hmrBR9nt%H7Jm0PofiBD$O(wV8z1o>m@%-3^K^iJZTzW;7 zQoGVAePP6?d2W@q*CK`YFojD5x-e%HwT$`mHCNvh-hJM14HYDAG+3guX<%*#Q%_O0#`fiBD$#S{I_KH8!sgZPlNQ5q^p+};(hB-u=+#akFLt~+^Y0ZWJR zV@G;O1iCP16n&gLCvEM8q5N3)u^K8!3~uhA@SRiWzD`CAi8l(|kEGZ>~=Vg~9s339vbEdv{Qh$1Kmyuas{V<3X3+~L7?^Y6l zF3cHCruI)pu~JXk^08xW2`We|__ki3Vb_x$PB${k1#||BoYk7ou(p>7bYadYDn(}} zv#ZTLd7pi?2`Wg`Y`j9>meY~0SZZXJ*`{f%`}PhS{YReEHPXEP?3=R@WMNCdj%>{a)i$aead=C7u9BB&to_2g;&&|6ztJ+@y&Q2MF*1hvDdnLc41lj)omVso`cZ?Bf6hS8z5j6P?Nbs37iZwLP4u>(N` ziGAba~!Q&pj>T&1`HCVbtY_W4F5sVp8g0vf%6lw)}g04HYE9u1r)b z2T#|#H0>#fjaI3o@4+R^ZbCbWK-cI|6Vz{^`}Jb$LIgqQCXXa;Z8vUOUV?YBB;=9?2YfV>cs30*X zse@W}s2dHtYs5%SXhJgQ)aS=PE|my$JxL|%fP;jNsuV7WS(Xh+lf_~i+tAG#DoEUm zQ`F)e6dIq}R}j=_iHy?K z)s6i^>GyGQg2?Mzk_=91$FryIln8WnI#^DPsMm+uheQa%%m1I&c0vHpXu>p9kl31U zt*%)ULzn$9V%)QTul-F6;xBCXNd&qMocyP(&*)EGcNj4?FMFa@EehiGcOKVJK|;^^ zskC1gPdABAy{PYAzpUjA>BcvGI3yA18d~Rp(qP32P)SF^?)*CvK^EZw*#v_aMn#aBv4HYEL zF5ai~{yB`!XlP_)wM);}x&+4ZlZ%c@1iISo$X3dWH)uDTY{aPFd5RX{*o#lTc}YVB ziNoqVC8FzS>Nwnp@hK@@%kYWgBVtcT1iCf_^j7xo%b>^i8Zp9-ch)A)@55b(UDZ%Q zV&La!rQh&$n!DSG@iU^ncA#kj?>PFDM4+qXIC~|}cM|=6!-z3sO*zfqu^;c#>$-*t z67_D`D*rW~K(F01Vk|Jfs=jNP#G_y3Nd&q^k6!L`waH|<vUUhAfY z3KEl7CVLgcX3+UxjTk@jH|oO#ky=eA&^7z#wA}mRw<`bAAgZR-q!yKX^Fu-JHB^wO zGJi_$f?H$g?C4>FI8t&29T*(LkDmG|5$N)_w9=cqjHbJr8AM1mM*Fo1=XKLd5mb1Hhv=z2H2qu$7GAZ_)?$lH7ND$BCxcjPBaR3@k( z(ITU*-pxOr{wy-G@SnUf8(Y*?)OV{%1iD`CpQKmb--p&?2GJt29?LJQ@)1Mp5mb=) zc~Q~L9Yg4)YDVtk?d{Hvoo&I>_Pa?0x|-*V(am23(RWXbyuJRFO6+a_20Xw^A*dj6 zuTL|*N3KGfS}hku4F@N-V^1yKcxh{iKvziHfqK>@FWT*#k++A{v}IX^cKmv3M}i6x z4h{S2g;i_O35$$r+_G$%dg)kuK4X=Gl)VP4R?3YtiL|B$Ss+zBd3Sa%Hb zy5BgQ?n^QL9s$iVbk~d)e8cGG5`iu`dyN~Hp?ACQCicpD6I76xKBkM;{*s+&$gD*o zMuG1KeSTJbUSoPIi9nazlzzEC&05jL-HgBBhpr>YZR@_Q)cO({R?IP5#wxdX63!n= zidRTyab2ovs33uvvzW5T8AP%>EMmt-R+0#GVU^ota$hxo^axwWD(-gCP(cDSXYo9^ zDTz4x=CY?v>PQ5-u*xlF)jszlMO*UNwp)sZ3KEz(n@o*6^(K?HKVVO{HkSx=VU=5a zYfUkvdvHGcwmMKl1qsZY#hc6yM3CB1f7$!9eiDH$ta6L#w#Oml)wJS#Uttdo6(lfo z7W3^TI+J>{ZFuvPt`dPRta6)7kvRb*AfX~>*(n+-NMPnHWY5`(pvMQuQDV8 zU0CH78&6JGB)<86yo-2CB`Qc@<}B`<2TGGZNga7*_o)(rF068k4I5S^$VJaUzR7oy zh6)mxIg8y19zV3oKA}A9(+r6~7go8&7TRM4+L5F%KGA8ph6)mxIg8Jg>s_ta+bF)h z-du@57go8&WTtp?=JAYZJ|lLOh6)mxIg2N+k%zVQ6MOSpXBJ2Vy0FS^GQD)&u6>-` zn`akar=fxbX3pXn$789suvh{wy0J(i(1lfQ(Yte*sU03EvObHA8Y)O&<}6+(Tz-gF zFR4FY*_VCF1N zlXq;ahKS1czzQoQ0$o_;78QEC&C1-j19_k0+cZ>=z|2`p_7~fw?-j(ZT$w-@R=LHe zy?jGDOXTgbi%x5(Ac2{)=(u0qK$nVVgG-}tNCdjD$}Q^DWzNu#wPShV;CC7-NMPnH za)#noEd6P;s2co`2y|hUThx&6Rc5IN!g!a176cU}Fmo203hR5b&%cBDv#>G}fiA3a zi;0v9{w#V$}D z%vsa`hQ+e&tD13#G*^j07go7N7kRobtF)sYuj1`PP(cDSXK^+ov;*5JHVAxL*h(VM zg;j1bWpTeT%fD5LU%K0Ypn`;)g|`lE!|qlp%YRPkED`9!D!15STGO9BurJQ5Zx17= zAn~~ITD{wMvBxWCtH?#$TO_k1Uy5Eh$up&RScAy(_vReuX} z#fp9U$8)(V=hPRy=h2YAwfXfYz62E{{Fna7J<&UiTC_8s4d&DzLbqnRaK98)BG83T z0OGAyOV-f(Q#^Uuc1@&AABp&2bN$fSL~36-Q^bg!lSy4y5tWnjI(vZeMBj4DbY-?6Y=UG0UD)Lic}e4ns-1lV-~6$Z^aP2-@xKdv zs*5^9^F$*?LCie0vU?~$WMv}}=-RvAS_yeGm}dR|46mZ*sz?07xy77P1QjHLNO`4Q z!_o9}CnH8)fl0Fyb%qK9tR(_npEJ8Ems$^``#%_UhF1gZw7C6Yy!$l^f(jBX_J%95 zJx0=9RgD;IyQjA8S1`98QAQ%rwRr4w<+P|-hMh5DRBRQb{YehtKMt29s375bdzNyo z|4{n#n$a0uGHRd}-nldH?Oa+S(3LlMyYg&fJWX6^#E7w&q+N{(=5^YXAgCa*ZTxN} zBQ%w+9%aO6(O`jg@NoyeCe>0R(6!Lwl2UAIEVb=!#AuwdN^3Ty6aSfPPEbK&|K4j# zLD@vQy_^waMb%xJvZ*asA}k~VU0WQA6w4{y>Cj3>j4J1JZRf3a{I**$f(jA|UB4*% zmc~-&#l~5gz|!ZngvG7-o!iAF0$sWOrPSPJU8!llaq?wEl{?x}e_x(n;g5z264&fY zt1~}D(4!TM7zaMQ(y~|k@W8jl2omV}XKSx++8IC{-x=@bAZ@>BeUAF@kMF)}s35Vs zVm0xu2r(g)F<1~=?-wJ{dz$lRwf;y1x(fQ#Q?GneX+715q5M~hICwYbF@^6nRFKG= z&`>S++mD`nIY~xs7=G_%9NHuE+K*)!foe>4NcN1<_3GjE-CB!e14Ct)U_j z0bXj;-5#`0Ya_-XFGuoogEQ~-u23Q#gX=-%HtM2xwdt7yV+0ZW!I@NkT$8VF{zyXw ziLlP?)Z~^8Y3N*Im&N+Y4GD>>!oA|3Nd&rn_;pcp*4xp=Peu!(hP^wP_|A@x8g)ZM z1&PzcLRC7i8l8G0RS;wQd63qxt$AerZHYivx%3`t6(0+_{MRT!yvtR|CuYU_-af0L zf`r$aUh1YRrRmkuMhtDgADLRG7;iA*f<&O}@RkJi{qVQ?RWl>T);;aX&m})uU>Mg> zL1NneWYyE`tDfd=oD;SP2qG~pUa}Vd{YGRs34NOS(L~2+}$G)=;{+ST8*B+ULT$}LJ(yNV#wSclr?y~ zUPA?mg|)}2_szEJjePnGqUC@-WcvIKtim;!K-avG3F;T;ak}rQ;ev<}Cy|=?E@MuW z7i*{>;kqtEHM5+e|5qtl5LX`eC+j;-WbRh8B?4WULno_FLwxkU=Mx1HKWhWq-TDSQ z8xl!c#F=Q+xHWoqut((<7xu5m$caL>5&B&IjAKuBzuYJJ|`-Kox zkodLIhCX-rt9SjdS`cMpcd+lhKCr(eSR&A6dD=wl_O_ru$F32?#yLk=ho>e!vQ|5S z3KIQ?RHCDvRHSYlmk1*B5N8)VT5x9NClTm!wY8w;w;X7*O9o;4?>hVazAQKY){>xt zgntDG+FP$nPcE4)i275mv(;zqc&YL35`nHRzSeYK&n9$jdE;zf;jls$?d!y6-L6Sc zL1N38T6DIB2MswkNf7DP3)#tTb@{VhRV4yl3%XXMGh$oQKMjmCitmnmW53S2@;yDR z2`Wg;53-|c_XJRqVO)2eujjMudChs3(^e9JuBqco(vBWoX<}33j#Gd2YnHdphr28- zMo>XwatBN5@+E@0>@w~KhmPN23j%!ki{ZaDB+%uw|AYSgzgXI~wQ-MXIqeopC+&IE zo>v+wNCe&cs%MIv;X`?&YZ);NiGPO7V zId!du3KIEc59?!d(&>&h#++r#MN8Ry^924aevw3=>vflGy?0&)jlXXY2@mHp+cqiO z{m3v46(lMhU#vF_n?!G$6hWK|8OQp+9wfd|-6aBDZe8Q_U*gP9ma{>mc1mG)^M~-#)qauN>L3!2mx8gj`8FS+Vk9GM*?Bl)B zys-5+6%{1Bqnz|U+osXHwT^;V_p>~kFrqNyN45C+S&Pw;l zVRm-W9S3q8NW#o-|C)Z@n!N@WZP~Mfv#ucZE1^FTz_n{SrA?K++^k*uQA(V zK?D^f;+z}M_|7+V@7z^_Sdns*WhOjg?;m!Q2y{JkaG;X{3-m@&#&vh^(*o9f>|6F= ze`|sY5=$i9lDGBxl6>BIF=$e?&kk)=%jYd~BuDd5Mm*ssU%kx*I zsuEO?NU|h!7p+b&Kbk0ri8agdfu8n!Vo?Q&Kv%N8JFPU@g+_-O*WG`+?fAyf>Y}n; zf}ny#v5@9;e7UBy(?28YOSde?s}`%v-Tloa0$u(q>dr6CcK!Dffi7?VDzvm+5Vf*3uDe|al;Uk4dh_9q z_cT;Q!L7 zh6)m^ZraewE`8|aLSuTzZ1#IrbFA3qm9$qP(AD4UxBg{vf4cntvp8Mr7P3nzVLWKW zG7S|ZE@YeN#i|484LjqSxO&=M=3W%V8_bv^5$Fmm|4_G^K9ctDWe}sYZZMw)v3&Kc zBn=fLM&v!!Ln@A@*ZzO@^+(7tw&q_yzRazQM4&5Mtcf_#W&+)K%SXhpnwQJ0nkVyz z2kbOdkZ9iHnEv?d1WHaCSJ5^bH?WD-2l6x9KdVTf>!r3__iH$r_IqFu|Lj+=ie^K2 z!26*pDo8Axy;3KRlWAtQaZOCjoWov@7{)zpzbZ(eYdFu=U;Ld++buE($0Li_uj|Lz z#ZtY#1>i_{;q&=8O%si@MuVs&~lUEr_N!7qO|)R~g+CO;AAs^G9)y%9zb& zsSnvr*C>fV7uMuNX8B_|J862$GT(#}RFJ^@(PWx#w~RHO`JFxb*hM1HCD-~k?%B%f z<`?HGX-`l=0`o^vfo!*hg|{uuCpY((2z23;uDEl)pzOdLTYi42mo&eN1m=&T&Tv_0 zF9%fPLtL9n1iEmWgdp6nv8I=5bN;usv^4?=%pXPnL%GVT{dD2}*BvDSUAPrP{LLTS zXXDJ8^N~5_r0o|-U^Xc3A8RhMDskTY{Y`6$Ko@TJ5Va+Co_Q^6&G*hOE^YBZ0`o`F zeH}@e|J`=HQGrP!(1lw{jQxp+SfiB#BBWAW!`!btlgLwU0Y0{P(BrqEk*Ti*REN$5^Ua0ht z2z22VA2FYJxGr1YKaCd#I!W7lkicwEJkhuLK*Jl4;lo2r5`iweQDn-|iZuAq zI-gZ3T%8c`%?>w~33Pcqai%WQ!gb4qI|OlcRUvz0v5}=#2_dK;(Xz8A-BvJG zfBa>GAo|ZPV64+__NHSOi9naf_eQkrmW8@$-$p?+voi6>4~N-kv-SiPBvyvErgPbP zeN6Y2g7}zX;%WWz*gfhm5$HO!um$bx!1YVzj10M zul0?IGX+s*Of~MZ`YXG2u%<+yYicup`t!6I?P_jh$mWR+xRv=|X8EElK?RAqLn3H{ z6UFFjM&{d~tCtB-TIa;}|ks-%CYQhKlS@Fi!Uo}*aSUWa| zx^1ZS3$Q4T(@)!Rq@Zj`M5`nJcU3}@`PqpdfMn;Cb@2WWWnplOO9{f~81&M@o zf4a=4Aw6sU|GKDBn@@jUlkaK&P$JM(b(9A!vEPHQPONId^p zla3x3MfVLdPRrhZTAKe&>Bzq(W=aIQUM?g2d?v zTWY5!&@9!+UK4za@lGk>ybWt35$KxiVonP>4W=!I8N?Ii5Bsn&iqFll)=)uW*s&6H zqty`FVWyG2RkwDk$Nw4$=^~TV?TMT06pQr4FSsbrXJzhlxiE+;g z^btKr)BH^1x|`;DgEd|!Hd8EotssG}k)i-dP4Qa&38T<=B;bcMVflPOL(! zRgI^fqaD?rc9m&^RS7h5KqF~8shDq{Xv@c)@65|wy&)+`{JvJ3o-2r^!_AEUt4c18 z{JuD$a4gzP!@Z^G!d;`H!>c**EMGrQnd`fal-YsUNh6)nRW~nre5;||DagL?l)y6!%z?Ii+KS?6cg}X+@ z|JAZ4yk2&F&c80vP(fngyZ{=U=0+EGFut{`Vmx@o9Zo!{(JF~R7w#Grb)VfHoc^l9 z^Uv?mP(fnvhOX3qaW%SJGrAcSEj6BzTaF*9eo!LNg}X+@HPNK;iYKgi+UYYIDoBhz z7)4*TvY=iuM*pMcZ$EykVKKfm=Db9p3wMo*E&p5n__beOSa6H`8Y)PrJNnRRp3n5t zUH*SJ2yf4;SA5F$R(>E6=)zs2;$88_efbR2eP&bghlUCgv0J0*jcoJ<#j3KA9CcA}$wv-H6WSBMx#y4U7kYwTbFuNzAQx^UO1 z$&_;0jt9-z$hy>02`We^&wS~{2_5vb`bM_2?tLYG^2$;+U{WiIKo{;B6|>Hrt$4pv z3s_>K4g?h>7GLnBjUvD0+Wy%lVtkoz#XGghVga{1N(8!a*QhwVlL>U;u2Hd{VgCk^zonV3r68LscQ5}3zmODFzGS|PIBm!OX4(#sJ zEA!Mctyt3L0D=k<_|8$0g&(WV&*#@-T{pIo2z13H2h#atos~j&qq6-avpyfY-i)Q> zs{|D!@ZG86ZBSDi^E#7m(Ej~BB?4V75_-@`zgo)D4MwJa?577`n=+I7)pRGQAc60I z6@PR8R{V8#N9vnZUn0=8%&tGRbaqpgPBoqlzPIndiMXR4&%*UCuzODt%RDm*jEtG z_V(qjC0}ZD_5Xa3Kvx&9p>$of;_9@V#6iUW9s+hfE z&M2}z+Y)^E>j=L4>q9C3L;~|`(P{9s;i|}9Jv)`s@Mob5b4GE!npKW#`GI_Pu&SYg z1U@H-4daFOyzYRuyxO6z5`iwv8BHe3@m2Z1F|GNP(is{mNZ|91c#D#IEna-A7r*!- zOCr#PIitAOIyv(+QGraDx>`d834Cr7_m9>M`IhA_+2y|i2DCS;!x%1AS?D)@4{!rlmxn3v)*Cx%yp?|L*#XeQD}IP(cFgGa|FBU60={ zyumiX@a zunv4I#BB(Q!d^2D;AS=z^0jP#WWbYadY_CS_; z$(q~FV$N}q1QjH(!YZoHA78Pu|4n5rj>`nPFlQ9!afn)qjx^fiBD$MJ=P{X?C`DGJiI7fQl6e?A>9-LcFv1!fBSi zIFZjD{!XfXAc5UQ(ba!`pXHS7%e^O8(C}xW3o9?8Z}9Lbt8lI-*J3+LRU9O+ODZkZNQ|VAtAY+LmC$9~W!I=eZq_2y|f$Q0$a-Ez2D)dhr~a3sS8Q z3GBX$%66(9uWQ?sS6*~YBG84kOp%ctu;XLby6{NXS5nOq37jGjztuEH-fpWiH(3`- z1iG*$D~MD_-q+rdH_iGZ)n1XnX$WyDrNEhI<=b-CWD~)kg)Xcui!%*%9C@P|W%(y! zLr_5ir#eKZdXob`a=H{>*shX9pbKl{qKo{~hX2*g`Jd@^rCK-=IGrNCAH!{Umrp-f z8HYv^fiA4|i(Puz#rTxhZ&}`7FR7-F1WwtA%@oaw@hbNpvmGmNZ_=PxPO!{U@yMsvG0DJBm!O7dl6L}tJ|!~8=XBdg-SgZByj45c%NedgGutKhF~>9Ue8BpF5`iw9xDnTqn}?b8l-~SBn+4Kj4H7s(DRvvy zy}*(uNAtm#R!RiAaB@iWKLW3?$-}$xgy=)kgb)%q2`aW`J3M7}pMv-;>*ErEE}Vc8 zRfC()SwMVye)ZoSY0?P^oM<(fO7;BAX3X>DUoStA2z22jm*`Cteqr>4n8qbvrHL&h za57h1ubP_ixBHuOtAyVYfi9d#6CINYW?Z@8$`jgH5LA%B31iV|=wiv0#dUf4d6p7^ zE}X0roj6-_e(bapzfqyGG(m?1PD+c~>n}6D_@X^`Z&6($(1jC%qC&s6kd^6Co{#P6 zCQSk&ffL^*Q`GcA_Ij!npYynxM4$^N9mPqDEjQSi^=5p?xK`3cBN8~dE}n6UZm|A+ zzB7mQZ6pF+II$_tdDT3|^2_8i2d%R-nTZ5W;ENqwMaP)A(*xEnxQj%f3nx#-*}fY& ztnZUctW1*#X~Gl&R)%WrS_Ew zbm5&rWZ^RglY~9}*{%V-HQY6bCpd6FpxDOVJ(V=7IFV&1jMh*=0?&eoYvPe)GRJxu zD;^*d=)(PgVu#S3c(S$RM%HP2mWB!vctS;FubF*F+8@f==1!9cbm4wLv7Pcq3~?!W zhCOV)NJ9k)JZWPx{b$jg*u8kje)P(g2z23oK+)%XF7^)IdCfL8S*xLf1fCcY8=4Y= zNZG}I*o1MbBm!NyA5cu5ooY`SH8SUSr|r;CK>|-ciND|tKN9(~4EOlAMIz9J`vFa+ zr)O1?y1yJB?{-K-1qnRCCFVtkdXNWStMIgIdnE#0xF1m5qeRtXnuQ}TSN^z$3KDn{ z&17nl(vXDlI{f%MDiP?y{eWW1;<6NItsefKW1qnP+XEOOeav(b+n(!$Brz8Sh zxF1mLutu>KlPQJYPy6X~wF5C|&dMtULG~e02JS+XFh6)mRQqyE=>;GKy>f4@s zuDvS}=+dRVgU;`6YKxWjykp>N4HYC3q?4?x3r=Yb*9Y;mJC7s+UAP}mTt)93((b+Q z%-03J)lfkKPtJ-{zoFt?dT&Gdz4p%~0$sQtP;CERx?JnJKZH-1^g%-f2|NKTw!O`s zt~qpw|-Qi^;RFC~e5GXx{JT8;L*{?gteA zj?I4Bj}6^JCOy!AAicUbd7Lj?&u zSuQr7%sZvF6`Mjv5LtaeC4{v5`iw<4=7IFPq|9_ z?QO^_eO3r6NZ=+6@x)T=HJwqeHoqC|D-r0z{eWUSAD1CE@Nev`fNmoiF@~q zln8X;W)ksff9=7{ioIpuTgDJnkVu)bR6n}=ivD#=j)-ymNH4Zv{3EtCx~D{-3r}E( zt7!TF_U6k)7M|K$I%$DKh|O{R(5LD8?-B=%40&G`>vP~3`_)S((1rQ6IKwM;#K(W$ z&z8)HlTM5vG1_g1{<`*>+#7X{ix~DdX0V8_+gS^(pG2Sw^J`Ic-Z7f#Bet^34-yC} zNVE-IrZ4^W)aP@n3nIo4Z3;V?x0y9G$ppGEBNsbTHgDAyc~uv08EZ+tjQOV=y6s7e zcFa+qmH4bo-BFv)8@5z!n)O(*Y|)B-EjL%h7|~#bHurcH9(GzGs376o{H9WJgbO|O zWT_x7y_l_yyk3o0E>a}|UH>W`R2F!+(*VC^f_QXqvQ}(MIo_>n06_(bi!aY9)e3AW z`ERWtJ`@|S^=VXwKXVV12y~UU->Ka6s7fCeUndCjeF@r+PsRAQBcTKpBwBlJP+Y$j zqX#Y-+j@?k_tl~+7w5j0!z2P-@B1YwDOGCGdfSW`_de9o94DB#*Vssc3KCj!jB>%x zl6sCYzERdoKB^5nS@1^9!X*M-7yaJ)?AuV69=BaDh*xKIb(^a>FEO_}K?Mn)8c%#` zkFutxUl}o6QZzNRxFxqM2$u+SooUm~tGRQ1n$p6EQF}{{(lD+#|5hrBpn^nxL~Adb zyEb&Tr7@?!G4G__LlCsMOrT4(ypelf{8nZUjo&IeT%l!qe`OD=^dhJrF?9Et+&`UO z>8oxT6I*rf?57Xo3R$JMu@Zr<>CZdqF?}BCoqHRE^_ctg*}VJAtydgD1&MnPTkCVD zZ`G4G9TLR(=XUIX)ipN5rJqEgYlPc8y~2SN`o2%bwZ!beUd_hZjvvYKmcCK*a!RRV zuQ|{||CUJKF41>BwNneIWW{^jY(wx{gv97bGxb7@1=Y5#5ixFfuhlfylKgtZ4ibT` z&!b)|(>K`A;th@ONAU+MwddWwvSE9>5LA%x$@``}e)U-YoVZ00f$rJb3jg=)l-Op4 z1iFsgyRV!b^iF?PXb|m!W@*K|9qdbu%R9c(pFTEX*w1LHM#O$)m1^~p2z23hMf9W2Z&ECFy%X6?Z-NRE zr7aY%N>B6kXJ*EEoaak)JzNlW@iKuf{H}(|1sh_*<;FN4!L!3%^}rpG<5OcF}4tGn><&3@@9gUs|@!r@;K8YP~E&x83|S z*VX)lYT8y+KUFZr=V1iG&Osq3}YHpJ&og-e3yKYNp2H1H71m_2}?f`r>1H?JOt?ez;@MvM=KXDHow z9c0}P$ppG4Oj+Y|cU!E_#P7zxqjN$f^{#e^g{2K3s30-3-#(wrk+yoBYDSELo7rl> zrUNX+TPD!u`qD|M_j!uXnYBiYBdJWhgZcn-I-NpLLBi^2Qzdtjg}&sF@%IQ>V6Jr! z+sCfdk_mJLbsC_=Y})4Y(cXyhs-L|!ch+83YC?a43KE+mCM)HZJFCjr{zd(y7!lpI6aFezjWfqJ_NM$?{hw5mb<{d$&tzQ(;YReSahCd-!CS zmK(W^xmHe;2y`XBI<5?vS4q)_oEOB(Zd0_yLpQTWr4tA$NNk#RPpPC=&h4fd_1%|b zi8im?diLN&oJ63jQ}k=)*L7cIc2A>smp5y@=D%_kt1zQ4K?RB8E@o;_he_UNN*xu% zl@f=wQ8kva%&b_6K$lJ166%=HG$qLCtRRY(=V{+pEMP+p^(3euF|JM}_152YK1-j zUG%|acL?Ik>o3~ii*s42UZE0!u4aMW>Mr+hx$TINEgk9jU3))s1?$?Y3qb{m;9Fj* zc6+S;-ouzf&YxvQt`1zuPP7S>2z1p-X`{AD>7aKWV9e>y>Qj>39l4uDn%WUmkf>4U zt4`ayUcbE3m_xQrwIMcXd)Vdstt0|nf%gK{XC7Jljz`9MgO}$kk}_h$c=|dIf(jDt z!aJ&7L1*;Z^^FsUHx@dO;Jc^Ug@=tL0$nH4yQz<>ZPRNGGbWcE`_&?uWgjrTZf$}J z66LCdsIv-R>wEUj6vV-)F60=$&noS%DiP?q+C4_CTlK7-SkWMkJg>%5pXxKf@~vOLK$hb9tKkdW_cds|$f<-c%t_IbzVH(H9x0Tu{h0|1SAnukm$Coo$`6=R{h%{Bh&w}-by34DD!QZED`9! z>%5p^9au}-o^zZ%Dw9Z1K_bj1TdA{WgQ1 z`g8k4j0f&VwE2@(v63BoN(8#{M>wbr4*$z-W@ixX%jIdchHqkioudgVNYwaUMXh`) zUB58NI5BeRqj>ku+f8g-z3vi$F1Ma_)Quy;^%IwkYkSI~E1Lh*{cQQaZUhx1{!OW+ z_G!OOZ@=2uo@DXvzGmM45L+}cL?X~Nf4rMov}&Pl_Q|-mo2EY1hS;BHE*k?0DoAAS zZ>X;Dzp20eW}FT0kyoUp^t{XpMg&L%x@I=?P@h!bdQlgH*rol@8fLv<$pwUwO2J-tO{T|8c>%w%c#9Bx~aSG1p>l1QjGg zZhEOUg=MMJjahjBmE2RvQPZj-LMo_Lr0>cKQMpQWqK8mH*?JH`tluUib6;W>^S+jvhy1qrh%Y3lV1 zKYh&kEJ66bj3SG)MeM!fO^HBP&n_d?rqh<|6Z#ojfe$2xlANh4S?4NmHB^w8GHQ_e zGHi-Idd+k}>|5A{6w~)JpP-i#fv!UnQq`ynNAxLWG6ZqGe|w@drL1(-KN>1Xw3w2h zwr;XnU)g7d5hJiIIXmhaYuoILM4;>=T|H|+|Kg&o2y6o~= zsml&lr|oJ_5;4Y{u1p&KDa|*9Rwj}HKUex3o8~^ONcwE4#1n3pmk4y7z0p+dIoyTb zoo~eW_|%HLt#8ZIA66r%AW_|}k-Fw}H99(cwjgZtN|Iyq9QkBtJBdIS^Qx^X<{otE zZzINy3ct1Gt*Y^Y8%_ijB!+WGwbjA8^wbq2#_Oa{npncdH5{Z`iHBel8&6(q3YEzYa0;@YtI#@zjzlSH6vVE!AW>*TIkZn49nE+_L@kLx*VEXu%CzW6n%muo5qWfx*6X$#ul%YZ zK?RAlMn{!%X>Dn8qEVqAw|j=xx0MI~5LR0v&}E&vSqZi6N!R^n#F)NqoVMQs(?4dJg4j~7x@JDOC3kUa zOi)20bCjRLtA)_djphj=X!Tz;ILU)2<;n!QN{%#F3S-0Q@U8~&wc!=@%NkeSx4kz( zMIsuRlw!dhX!}9Neb9eVlA7Aoh1;K0C88v_@O@Qc*UQC6N?g4mqZxTQPYyIL%J^Lsf;%3etq<5DHbYZVh?2hKI z=)kIl5!G32)GM~~O)rT+7xoHGrjk?LSb+U4_Q16-K?MnX(i3Og zABM4C-shQlwoIT4dxc_JB)l_g(}1%!SK27sdYF8)Hd>H)gC<%frgKYguaD zuv@t{m8z>to@c4fmTz*8I=QH~e%5L)O=co7NW5Em&A2PMVbJ`LQH=u3fo(>NFvaM zPXMCUH>*E6w67++uH;D121rc$I6)0r=A3)v>QoWqXhA=+x{D|Ce{xzP(1p(l;@wUi zdy~fbRavu)ry43q)K4Fy21mGig`70*YFd{lVhV9%+dKS_2y{K%G(uIs&B-Nij62Te zIbmeScNT+Q6GH@^6C9_i6C}N3M6*!PHc5lMTtOH;=KXtu+hs72iqGR z_ai^sk{?!oY2a%|f(jDHKPIXjN?-GdB*y;TAzd_L*|7|}mt9XH(DmS6Uv>JmDn8f8 z8C}b$x1OZUhKKa!RX2hP664;+sQ2&f(jDp(~w=TIp+m4B4Jp>gbltHfQ(;F|9r?y5{X89UN^6s`5i*4UVBG47wwU&D0 zH&-s1=LuqcJA2a2Jf3x%=uc2V;(hfBDs5LxEwsBTh~mzcLUVQeEgCElCyw#)*y>sk;&1qrv_CDg@#UntR&t_h-7{d{fOzXi-cE?gqeh5ZDR zsnw|aTH%v5teR(p)Hgtac6z6@o^f8OcKo`C!7887&iz@u5Had5S)+MQ+sfKk?jsTC!v2o2$#b!mRbfB7c&@k9 z$3bGn-5pAgM(Y%dyqhA%yyFwK_E|YBc3(e+KdB#u#B{5f zO1tE2rQhsZBF6mIf!e`!2Ux4Vat8}t*l!cP)J@*nwA3Rkc5#B#S3@H4Td2~fd6sgj z@ofL?;ny-EJQkiLXN5p8cd$r!xinI2^QX~Rh*pC+d zk1z)sQtTA7dy*`7s^RBm?#|4enl@VTd};hU9)vBS-y9k1Ao}O{vm}?)aX)r|(cWiH zu)#HxrT#e*O>M38PSF`k?qVaxy8nu^efBy_$&(3mVU{V*@b;?A_Dnd&<{nR!<^Ygr z`6EbQ>Yk{W_0}oYn~d-I)vzTj?AdnK zzm-g&OFmuG*K-}4(Ps~fZyQTcK|(J&uV+u)uPoYQT(2D89%4}q*0b9udrAblcLc*oFZbK?Mo( zi`D3`>*ds+K9>ctz{ZV#-qxM@FKi|e=;CK;(^8#ks$C*33ZhBp=DcNG60TM&&}BBEK0SK4fx0!&n1G0KXv^n3@@J>ws}fX@ zxY(mU^_}dYK90B~h{E%M{KJsyY>;_Hi9nalUKcu|WmEN)yDvEV$3r{2Z(pq@-Xdsr}+|ruJ~8&=pQc+wb^)MGV_M>Kz?w0h8Ffa zRYL`dPfPu2h=s5EvcEA2xbR~NZ|=5G8*C9L5$MY7A4u1qX`&8&yj~D@Z};bU_cmz9 z>bKKSLE^G=2Wsk}sCCz`6~w#GiG0Di-P*OFaEUK(v$XRX9!a#{Y*MZ*=w7pp!RqeZ25RJ?A;ki}s zX*F-UYp5X6Av1*jSF@@5xgc8*P5Q<12bUgcmfw9O0$t1Q#n8_=PU_=<#uMb9jy-w& zvUi&2-O3s&Ncgvkp#Lp!RbRX|x?~p*^yHuKywy%+SC9yFxmD;(XOFEaHscySFK@pd ze9@8L+G}!BMFokfcD?9~yS3HSV56_L!PJwF9QsYGlawP7=;|~(fj$^mNj=7l?$Srg zXkO@PM$VM(sG@?zyt;kp(@Qnf5fOs~vH5BY-?j9ow&`l5M4+o%NPqfqYdJOh&M-mT z*%`&N+L@F0XHP4rAYr*7j(R&gs>`xs1#v?c=VX5W(iZ)GA`$4yi%F#};bqjb>2ZQs zJ}HWC$T9yPS8pDd)ARrTUqqIoq?Agbq*N3lu9-Pm3l*}25RvQ^O4_ttElOq0nkD-d z+2cA-yX;va%D(TiX6-xY_50m!pXa>)>vnrQ?#;Q*IWuSGIm=V}A$?L~1ryVkg=kBD zH>WpU26KY$9}7Jr{;;GoZ3!l@E2$`4yL)qesylfoCk$r?K+O#u>AJ4rF|1%>-1o^^ zlQdJhY@i1xX6_mbcB}s|73tj_6WE2%apNlorUyX(`#REwWgCxS1ru9&cGdFFCiKtm z_Ph+;g0Y}I_J?iDYAg`gC7uuWGb8}oJ=c+jrFb603MRT~rf6I1n9x0Am9vU>`izA- zul};VwgttQz^QeIng-F$oBfI;Bz@LB$b~56$yLWjMo&4B@o#TId@xMd( z-*?J}sqZbBM~_#VFqNt_r@i#AwHmU6ZV`)01Nu{)NA+}V*_HYR)O`PPI{afRW}DxP zK1p0fSN^u)#M@2|to7j;;M;Zw8+pQ;G~b&<^UBTHrPtx>Bbm}(IiJ6w4CDB{b>6KJRPMq3fA#Lc? z8?Ij&B0oG{msS`prX_3Iv8dq1 zagr>%n@(?~S+WVgcakfysnn~X1uvuH?}5^)ZN_l>&2a7GLTlQ&Y#rShWzP{-3}R7a9eFf5Zc2{rMy-R;oMhCFne2@ zdWB`s{tsN)&EvIckz)o;eecS=uly#bzNgb^?_4+$9@|Wk@~_LA@;ib}TrGNja2mZl zydxVhq87dQJC(MW(2@PI|3enPPNf%RS5CZqP>WT!{zQUr#6g_Z6ZKo)1ezOe&t9cp zQ$OW@Tk&5Tb@G}z|6T&E@mH?u^UNeF4Sq{10_Q{6moaKBcXc+hXX%ok`WXM)-_V|^ zC;6#QmM74mdJ3`bsuN9a^o~s3F(0sk34euCJU)8|K+rwcvaYi?+A}<7wNP1)}Ki2Nb&CCD~#S%oBZNsY+S6A(P>u;Hp0f7 zBz=qptYD(`X>$^HKY_;FR)_-Kj%=UlPtx^wj6h&l*-CR_GBAPOyRQ&U!+NpRX4Rz7 zDF(2DiD!qMi6bYzGktN$Ekk$O}!!z13e6{>!yeF&J;Q96Fg^Jn2@4&?T)OfOz(=UVD@vF*joX0ZS z)}!GOa|8mr@NeR?ukR|@-wWT>ot;8JJNPIm79c%b1#zzQZ>j5$YYek4+} zRtlj$@r}jk4kZ3L;{*b`wtl)!mhm!%e^7`&?P{3z&8FjzACCd7V8Us4C9%~>qDPN) z;KaLqI?~ruxuji8fIwhZ+|&w^#miW^Qz6R3Or)(b#pLSQfsm8>mqc-;M@C2HZ}XYN z@V{>-xw5McpNVhdBsw%vY1=#gY9e_j7n5*zKfnqm&dhyB;yCT3Qi!b;jU{%2Cm*F{AHD8Kw+nVIzUS`Yc|Vo$&d zCQK)&=vB8Ansq=agSBcd1=*R)ujls@2<*z`SJ-7}GTq6qkY@lJY$loZ-6bEd=njeX zYtbb=_*XctBkTA}MV(rv(j`e98R_+hoM@Ix5B^lH>e^c~Y3`bQSsh3LE0}1uK}9QF7pk1M71dn;EJnPMs(++hr|nE|BiuS2_rXHw7puB_`>9lB!X0y-nlm36pSo1UJ; zS1U|X%DAaxDiuy_0y&?I04tbim8V0Ok_B|+7KJ!vZYIU7w1N>sbl~i@y7b`YEb8&W zh0Uz2L-W^W()!euom^j=CeF*GHm8**n3QTNjs0!`6PniptY89PEnodP+DtOq-v-W< zf057j)uk173u*Cr7nb$0F6~&7MSnbXVO=9?(}ST|)XGFDqrZij^x={%G=B44#tJ6z z)$-P-g_U$=M|)s>OXO*z>eIDvv+1nnF3h4zm!3SGP37|)SWa#OdhAOME!nTMJ_)*( zQX9E5G}wAX#tJ5eXX(-{opb5-|Gpn?K~|DuxEl=1+$|8;^^A{L4*$)i!9GeEjm@p4 zrL+s|j@&9^1rtek8`9_oi|BVxg*ac^M#>%11)z7H{H3)XolO_fPaQf4BOybgPbbz{ zO#j|gzBu8VY^CRiyTDW3Y#A$f?9_KdBifSFJ@s%2 z^{jSg+b%SwDVa-Y_u9^ERviPn;Lj5J^Nlj{a_HwMsU$Zrni?Ww1rspKke;nsN*!h^ z#LJwHl3|)F+$ndLlU^9nddHX3o12~3)s05fDr-5dKIX*qGK^@(vE}q(Kc$yZ_{v54 z)~_SDne>&hf(fyV0n@unuAxpaBeRw~ea_W{}c?4p@{=Ya83~GDi9MN{cc~Vd9X{1S^=R zY2K3Rs@K!r7E09MWz{h0^g?}b9@O=?>UnEAdDup3I=wBs>C&2hDA_=Dx3*>XOIp$u z#p|ixV1=l+bFftL&0|R=Fn015T2Eh}rfgeEHyv)l z^hhImp!+iVpr(ZopW#pNiM@0&Qi4~vms1?M!Nij*O(>a>N3WS!^D?Fq7wM*FH`q|n zQy{PlU#&`&W$Y$Rjpz)Tdj7)iz(ny5V>;7lCGB6Kl<}~rtMulfD@0WG76|OZ_mJ;` zus4#rHXj837v54gsSbVDbrEg<*Mj}-RF@{MUPKLCELp%6UHYN*5*qYXDTC)^ltLVQ z;fdcPzC+;u6imd=s!xO7FQ!G6mYi4?R7{1f`W;^dbQ}LH#zjVpAz@Ea<{&;B!3wE zY1Tj>unYe_zT)@m6PBeJ2Z2SDy=?KCbUlzoSN67KJ}+O8kRJ=^inC^H-KV!CuRN2Q zcW=(in3jBoUAGGc7iltk5_pr`t4gCyh$%B@cAH!cNT-$IrfgmRGIH>825rlK6JNKq z;3C@{G7$z?2MP)%K5u$NMpkD~pI%DjZo}E@EH`KZ=-wJC5ZGm*_neST3ux{tg@8N! zM2Cly;G}yhJAe8j3EPlL`z~rG#LG?_0x{Rq&^K3<2xOPB`OG4GD#W-ZGpyhUn;2EQ z(r_)aF`fb|8f6Ovc0HQ8mpp5nOqbj>=4AxAu3)X2O@VqYOBhx#@nGU!lHMqpzAIM< zr_xv!kPrede2ZACf+VthdJKgeBX*(IQle=;pC$}$%2FpSBM!Y&sOb^qc|1Ll&YT8L zhMD?X1O*expSP2qy_0DD1f`707t&a^?sRAsohuO7g|Cp;+HXr)Wt}Oo_|bA9(uj%t z2Rn&pLK4kbrIcY^x}42xG6hTyFBJ&v5`VeDLy4^^mVtf23hmym-a^ds#M!O+1}Puz;&#dX#oW-@D0E4%KZH&mE;o-F2UPDg&il0Z_e8+>gNfm3FG+b@kX$H;zW5Bi@ zJ*XZ!eI{+{YWP19`g&_tQ2mJUFevGxpkU&sv8;~HnMuEQQOdYHttVBr91oi^KMQ5x z$bap#o@z7W8Fa=E15N}L@;#2e6QQfcONJFp;5h`o=O;XY45%3g;myAa1a@usc+0(M z`gH2?P$^@Plc6-i&lhNEcX|Ck6}|o{m$r>^U^rTDVW&$+doQ9dXDB_HNh{5y?@RhX z`k^2hE11CjQofec!CYE7&I3OE%Mb|c!o6kQFF9i+jb7djPV>{Vv4RQQbLM+~hFVM3 zW4gc}y)6QPU1BfXXj%(t*F#Ob=&KAGK1(hVd$?E%Sm!URwD^?_VS? zcp=}f>&&pLYWydX-ZqQ6wNb`Vzb`ys-xiF3(N$~Z1s|T1a6TqqZtldIY6@(r`)T@w35BH7z4i}Q)R4RqGj{vPUGYBZ~0$EF6ua*q#MtYD(B%LfvEB%8kUR%U)W?YO}T^`^kU znl9SU3*M87mDw~Zp$)^X=8<>FVBS-!=iP=AFK1t76FyCW)R}o&tY89{$5(%b%k1>i z=`hrKxj5q)#J2=jS<3W5r>X(6Z z)7AmjrvDQnMVJ_({!Q*R$)qQ?Dy`_#Xg$eoB+ml&qDmmJEB@^-VpEk#*>|PZN^R>% z&n|a?6IP#PtY9MX`zKOs&jK2nrx05n{$rOC7<@2#CJ@+_y!#UwJvWo4JW=X-fc+;n zG?r(bc77^j1rt9aUXY_c3ux40h1inxg3VgkAI?6zDG=Bd*XaeZsGUjG_mr05sD3%K z{N@YQW;bN4U}DSh3Uc~W2DMqK5P>tUvZMWnLH6a70)buP6P)%)SE}x33O+%WfM=xl zuc#t9cInijlMC~XsUj+EI{o%sc^=J*R8pk7B?QWxKnf<-)qhE@{79nWj^!xRwS`5@-TA{uyklL%;6Jp!=`=ZzQ##pqVr@ zT^~OGFcl)Hn7}jfeBJ9-BWZAvG3?MY76|NWmiC*hH(5Z34OG6)UoRO*3!56lm6@i1 z6-?lJsO&PWCuQfhf(~FP5ZJXuT}6hT&!CaLlzX*WT~~@JXbI1H7z0)?f$usWrKbL5 zU-=&1Ii7kVfu7Bd124#)m<)QQr*d}#GQKjuwa!rWyD?w||6lQW^#1*XjdNFnW=|b~ zz%I9M6(p)-23_x?yzQ$4nn`0mHiz&%4TV@Zj&kEV&v%(_ZX$K5wuE)w`a+x<6Zo$4 z_R6=BWdE%V4D6*V5ZHz5JfBhY)|I;dY6mrT^#CiFz;|7xI=iiw6uGezT=i551a{#% zuTq&0{>Hv^aECbuRe%*t;JeP(C+5FpO-Fk`uH|PL6WE38JYOgC{ysbH-y3fB{48Sy z6XNse-ryE%^Kt-8%6%*l*o9jOKAL!bhdq1O2@Y*Hg6sB`q{ug&j``)xMtW2d?~7^F z(WgDj?|Gd(U7JSTrzy|;SXpCfwrnI9^%x8*HdT_XddalI?he9y9i9bLGCMSreirHS z{59hIAfCq)XX2LnHkY35yR0pkIzX6F#4bF$$lt_yADQ2Xb@JEqL!f3bpI`ozOj}er zvu6Fyk;7#vbo@zY_BQ)ES^PJd4mqaOj}bbbS$OVV`Qoa9fE7#}OukN*>A%_rY$Fh z@oBVXd`p&bVK=$Mcg)5lDbd02n2TBD?d$)?ku1IQA!yxlUA}v>TuY0#Z2hQ;6BPTle47Plm)b6uF_i?yml3H z*9nDEuRbzXFfpv(S(0JN`$RpJzRwcxboTi3Ea+P4BoNs3F=r3)bLG2oS1Y}~%MY8g zst>Vn_c>pohwfF~CV3=sd^$B7(S}X&h$l{bZ)%CDEhiccQnO*<(ICw}uQl(RM>cm( zr%~VSn1NFsX*?{QTH4#O|0&~}H>-DY9<)7uM2i(nluq75vPWmoI#-ohfHgzrGL26p zm_^r;F@at9j_}hKTFqq_BIkltK%o{Zm>AQ157``_L0>v5eQKL)sVuQ>B-}l)OCYcd z_c(c!^NWUgy^n;)r}ed1!GyZ^88YVG0($$uGD_FvvAcI>!<~VP1OmHozm%V1{^tkj zST6$R%v-{;%&w~s>`tNff2>*MjG^iweN*Vtb=K_p`=RPXe5Ir0uSA`FlbVu8-)F%p z^#*oi>2CJ}*OTb587%~tN7h#Nd%T`MOi?1+XBs4v&tY@G?pYqg3jV*iJU*ImzpFlB z9SJFyvjhUWC@-Uem+|PoGCC|tV&)B|!j>KzeFDUPJs=R+ zC9dTh9Ji8bnoflMJNL*~!9@7Zv*fUpL8C7!SGCV&E9>!jEG#fOE)dv-*OBt`8H{(Z z*y8cwCo3FBiqttLeS6}$z;IGUR=j-HR^K^RJMET9{7ish>QHTvc z3R&ado?t(tE?@-{5BC+53ePk;pRa-Cv*D+b!`k8SdFDHTz^v9J{{k^YctY8AK zd*X%Me@U_D#m0$fSj5P>@?`f$5fnB&I;xU;`nk|ITJC-EH8f+*u3f?5ZHzLk9_X#dMLZUcn&NJb{Bek^R{B;d9{Q-e4Ikn82+aUzzFOn>8q$4f*Hi2n2Suo|8v>Hl@*1SxS2~ zULC+fPfmyY-|J*IOrS@s?CavC+#$8^vkg}Y}AT)k~Jlb-p{gQ ze<%8oG0#(JUY61e?>fJ}G}6NWI?QY>#Np_HDl#N7jcQ|E7>=;LqCtkVak7lo8}J&wtFq%nUC7ZY2=dgRgbdp1x~%Ss@y3%6Z7X1VJj^NhCxr)JiG6-?|OcAZRV!uwZRrPudq z>}^)WXW|C8Yc3Gjg?oTJH~H|(%=^6y)a_voSiwYI>vLq~`&3%~TIuy|xqFITH17ts z%bE%VcHtf%pOr~G%6epVhoNVU0V|j&fMODSF_k`VrIbj_ULH4+Hy!aYD< zKZ3Wil>>W$<+;Xy6-?~tP)J~FD!m@8^b_-ctz|#1^@k5XSPslF)?#)Cb62FMs@$& ziKN@ZmHllJ30ofr2n2TFHirN5m6psoejeQ1+*W8yFoEklpY4mVVqMCkp}@VCKwuYc zD|x&mK%c!o9t$xGHw$qFOyD*~rCQmyIdjR0g=Du>fxs>tbKu!%*I2RXYeM1C{S9)Z z98X4zPV}qm?p#?`|r+kE;)(r&$5s&xco)<7hpPa_(;;d5x+I_bbJ=9TRwkIY0L! zOJB--steal?S!uZcHwrOk8xJ$NvAx1%TYg_0V|l0uT+s~y!BakQi%@wO{*(y*~AX&*oE799>3c2gz29* zg9C#c0V|mJGwC|12}`BcdP*6?>)&J-%iF*+6`$)w-y-b7?L1#ezP^-Y<+g^?we0~b znDBJvafYF()T+DkRil+BSi$fPP`<-jAg~L!^So#IL1s;kIf9jiEno!`C6|iH;jXE4 z?;PcevqCClIu`Em;9!ZRVvGw*O|kQx&VO^xZW-%cQZA#=?N#+hMgk=H)^PH zvNJn!ub3=y)X;B_l`Zw*C&o_@B9K{ zzh6UX7v(!>FYjQ^&uyTGgDYSK6MjhrWMZI(>Wonc({&r!=dU(EYIPC_?E1AjkBsT3 zp}n=rcQD6hBa@m~!uWdK0V|lWT${(|Yg1^4Ckip>z-{*K#6J1c@!^1fZTRzIvj1r^ zZQaqC8G9F!)3=jpM!fRNtu3#x8*T2&9p4TFd`~cK)W4A2@l2uhLlmO!fKnFec2X{{ z9tv2&gjj}&(;0SG=Yafp`zV3HuJ-wPLm^r@#b9>+FE4TQN?dVm#7bS;S|=k{pmMsKCvUAv|aE7BPW z>wf={F@ars_&2IcomATJzgULWwhLQhHxS$c3_yRZ4{?vv(ARjGH#iMe!6DQ z!bbU!T~tHI@h_Z8DqSp7py2%=3Op^j`A$8bcR`=WcXkE6Lq!8Y(#|t>{uK z9cj-zkUM*U7~4NV=av~cDJzOz^6*W^Wi z`vO)lf#;@Fs#+gjv3Gyo$-_?d6bS6XbzY^KrT>!Eo%lc=k?RRq!33UT<7=H)RI-fJ zm-3KzB7t4_J?1-KzCB?bBDC_X+Jl7}g$Xo?9~2 zbXVG|rJb{xCVGK<^4B!b>*Pan_a)KOlN}g#?JJ5Wdru|NMFSL~SH=c5?8ZWQ;E2h9 z6-?mrRI1<>yO_Ouv>aY864-TXO&+;(D~YZdtNiju?SR=9#L52mCjwS5f$tlS;-p<* zS2mB4?;aKj?AqX4NV>dCqWjh>Pw*el=x`~2mR#H>5U_#?{QUX6!IS5#Th>syBzCMo zVAt^x=g8cjNi^S3se@<#d}cnwr^&NZMgmqaf#;+7>6E#D`RSD1W$!SNz%D!!&*Ol!a7^!E|=*J1*< zT`E?t=7iqD4p2q0 z7vAB@V{9mfhL@N6&NS?sH3E4RnM@J&4h0=w`$H=lRj(vA7f zjDbz9eY9A?ggAnXNi$=MZR4P(eg9*az%FtA{B~Ib=DjrzDyMfpjulMc5i74zfA3TK z$arv0jV74Du0f-HNbJj0T6S2OqhC9?gkC!y4~^=k9mfhL#5mjvx{l^{n-5k?6N@o{ zU9I@e1$j;?^*^nYF=_H*s?%{ke7L8l#R?`;m<2f#l1fLcR$_g(JSR|t$oX)3P6L6! zuDHTd_0U$S^u4}9tZ*t<*NmSJH8BgdQxliF-#N*9sS#~hc5$A2iw7EdUbhYFyMBoJ z+gA;pc1XFZD#v1aw|6Y`S2vY)ruq=C(|pJJI6J20f9n#e%BQ3MT$0m8y4N($Fn_N*Rm(b*5ov(J=V^FoD3X>`_D1`MWh#U89uI zy`%*#+ZqYmHl@i}!GyQR5Vd)@hUQLD$_QRnKwMwXfo=zv3IulLS}k?IGEqZMdMm`u zMV(2LS>e#%WQU9uOpLv~#C_;+4IMm5A%2c7r~8-1!0D+L!t*%fIEl3RkxC!%wY>OF z^OgOdo>G&7dEnQfw~Q4`G~!S5d<1_UosTE%re`{#NO67M%UR^;O-k1wZ>>>mLyYQXnvDd>n)OFY#xUX3%V+9jG z!%EeM7iehZF{O-vO@nFDu-P!<@fv}^E_|o?+7GogV=x{Hs-DVt4B$N8hr}Gz&=?nc zc4vYQY0UfDni}O^-6_yxc2|R7;+H2fRxmNQr3Lw?(a_Bi3emM$BbIk^7`z)_A5twW zNPRyI9lE70!y^lIGYhh|8Sl@RDa6j7E!pu21L5LwL%<3q@F;`NZOf*tNqj#r?cZD= zuxq)Y1#!5ULVMLxMiV16PHa@Gp3tdFE5HgS#PP?q#jRP@#_ljbyq!Q`*RqBdBqA+^ z&S|HV(W<2vOWPj^55GK>@#qeZ!f@=2k8wJ6Vb@Ou!Jdc;A*zN6{G3#(^;Om^wg=w} zpgt`S*d@jj54$vD)n=0+d*MYHE11AfmPgfMYv=}#X^@o(0)btIZ7hfdj~Yzxr98nG zd%w`)AtA7A*9{pfm=NC*+u0}SuI$NhGNDu;uxnsQsk-)f4XyQ2dE1A5lj-&20pMd_ z3*5$(szQ)s|{G2{!5I_&!MZlHPR1X#g@_$I#l{DG=#yTFy`t^$Ew^IS^Rr(2}ZHT=vw zUTZIvu+YZ3kg%qQ5Wm8asolK`$x~AeUGJ#$^i?a)vo~{p%fF|30#-1ABQHFD2w1@cj@9rz4SR~&q3!qOM7<#b zfnDxACR6H=!p}ld%J_cg2pf3*yxgj61YiXdc+|(wNb%dkEPPAkK{H1S1a=u8k0(9_ z$@Gh@GP>JwJDUARmg20IXmF-vyQGz{3fwPe=#(LXk*d*O}Hn zfTJ{K>B@o!vV@o{ge>;&r8mGL8 zar+9`Q(H+6yfy={f(aZO;JZv6_OPX68_CUD@|70oe_lCU9(kpGkiEB{RCo z^Zi~95(w*&9eB4#sJ_77P&x?80ZE@$Y$XGpW97fcC;cU%(0`#M8yz z&Nq|l|F~LQlJ6rB*p-7$XyfZkEG(o$-EWh_Sp$T#+c0t1Mn&iHQ_>EUD5pU6f27Aw zZ=VYTyN(j(Iq}>k?!)u7=k|K6h3R82o^oC^nEOb`g{!hLvt zatl+jyN74PxbN9ARxp8kQ9M6q`eW*>ngc!i=L!UN;XXX?_3gMz4T8d;G-|7i6-?k> z6klu5w~!ij4TDGVI|Tx}aIc^5;5ojLZf!puzV$mPV+9jp|7z#zU`j^KgsA051OmIn z(Zrb>!>E-e5RN!h%Zau_)E~?>H1wJs!@aX+&4#FVJxig>Ym`1*V(kSq_VXyvOVTqfyW8FyQ{0ij8_K2zU)sjCa?>SUiiv^R@bRMKVfr9*H1E5FoEBEzJktf zFO91g42e;X1OmHoedK$Wj>gf1lM^9f(^DBMn80(KTA$|`eQFL- z5d~zWCY7G%`#kWh_4e2Ta<)c8of;|q_K!yk*qLe zQCoq)uBcUcWX>uLoxe=!EtOlWX1d0X5YJaxUx!yiq}Wli0!A)%I9Ah4_M*?5w3F@+v2QF@k( zZ|1PJqfH>hxEEjr6Z=lZ6W!1hdiJeCSj~=Qha#H6n%;c`0=u?)`;d@Qhp)Ppfo2MGjrCH^%hcICBlQrfnVSlw;6Ea#Luxq7hsX8DynFi@AJ^h24hOFSh zefeGUiGUSMq&6&7w^AijFI$Ch8B;>%t8d8_`5^*c8KUXxMF~-Ob%sK>a!& zk)QvX0a(F=cn&}2r)5K?><26h?AN|j!(vX{v^ej3T^%dEP%IV5y-6$tFYtDgAE zn%GN>=@>)*XnpLP+({>y>5)c| zpkja(OyHOk@3+@K${I{<1fkv@0)br%Qwm7GIvV;XLHT|}SsY{M31_4$ufn!d5h0w|kY?

      in>*2%L>GDZrx=02t_hIiUjINMo%%v4WA)e~^1-sUY)`lFckKj`X_H($m5@vQ|aCP4h;9TE-uLJS51`n>Lbl&t0#NH zoOcF*6-?lM7tduHv5@7s^nxenO#}kFR<6h+-Jfabwy70h1rxa6 z#m_==$YKi@y2JH9tpx(RCi4DOizE$ws#3~0^EQ(efGcQbwgaqS0{6Rk2FXb&>}OL~ zu+Dc92<$p|E}o3D(ol*+c5x&VUt6;C>fB;qOZ*E8k!bR`t6I1a`q- zA99nAYv(>v-d#=mV7A7oCH(Y}04tcl{Vu-ptZ6S+RBa6dZuAfc?CMs>f~@G2Lf`%u zN$pnIh1De{u=h=WzzQaCzl-PKscgy)l^VgHnZ5#nUDUQz{rOBXo%>(rlYaqq+1(d) zVf=c3zzQaCzl*P@9(t1cxz&QoT>%1tT~!zS)VoI|)Aq9Rwp&}Rqn`?%%Y~mN09G)8 z`(3;b*T9BeY;{+TTN@$}*cIZK>we{P65Ud)l#w!{Ev@;oQy%m(3~*l!=Mus+Uty}h zlkD+3Bp2C-3cWr|^lX;vp2&CP?>eQF5mL5;T(vkW&v2VA5ZEPN)ugdU*qYC6)WdGh z1e{j_XZ8@IwcQH#u!rlyj*rR@6JoEJ5c7X5y1t1$+?1jHc`95WunR|u`5eoOTz1ON zQu}Logb+i<1kP{5Xg>Ly+~jep0nV4 z$zpHPZRHcS#ognDxd}{&d47WLZKwOwuV_2*3`h8XVHf@~@T+R=Og|ciX?G5tFU+xE zLd-sNV`&jNP_bRRw6REFm-xjQv|%$zH-0CNGM@nW9qk>F>)tvfnXbui%W&P~ebMul z^lFc~P-hI^BZcZSCdByFl7lO#r)xv-*)m)punV^_e8$B22)(Uq2Ksxvg|-9}I9|r{ z_Fel+y}nt%?_@85z%JZY@~qSE_1LSlw$M0;32h=K@JuW}p{a#43+AW28Fp6-1a{#z zpU;0ZbZ4W7c7$G~u0q?63A|E)XPhb>!ECm=!d532fxs^O?c!&PoC{**neK4k%3khA;=J8u-Y zdRNI(Rj* zUExG)cY(kz9Eaz7m);wY4 z@O*+wb#rL~*>|Ncgb;Dw024tE7P)6EPN8Y$N*V6aAIV8F2)-RQ7G@f-3(t%2z7LyD zTnvW6`iG5#`43F!%vA%4nDDPkL7c!TFo-1OmHote2k_YPpZRnCUGWT!%;wCvPY`A9;T zFuKD8j>+-0AMG2nb20nmo-s270=w|&mG7h1TC;X}m*llkA;KsX6F9cW<37*(u8jL9P8!lsmqqJU!!Wn#*PC80=sZjgpZvct!5wk>cL8TFCqGY2^_QL zyHYN1W2GK?a5tZR7R4@d1`-;{dPDItWoU zOyIc?o?ZUTZZ=!p86Fi`3j}tFyBgVue73Zu2UI1S09G)8;{iM$%c)%EA^Si?LtTNu zF1&l4=UtkV#5O+|4rR~2$ymXJ_#JepJ%d>$jf1RJcLV~v@a}c~H5f32)pZO3z0W6P ztYAX?avoVun3-!Rymwn85ZHxxud7r~R@<<&k~y&6Ek?!)Ch&f4-pjBwWEaoQgNxQq z0)bt4_d1`0tWYrz*BDUkH<7V|3A{3buL`q$OhdZH!IdT@T1;RUUV+aesdul?*xqqq zU{tQf3MTMMc|P)bvXidr9}mV2HwpxH;WhhwFM#2C+Nv-PN<$xNv4RP_ww|vqshLG9 zj>N-<;hO{kyTrW!HFZYQBNp)xd;5VFE11A*>v^7^-{#b@Ydm~j`%ECPtLN+?YU45u zUAS0TL$5u}^SS(rffpIBGFC8w*VglUH71L!ofZQ>>v{+TcJ+*0=6+_JuPfXK^IZ_zR@nZ}E{M3vx72>W z=R?ytTY~pTV505XRqlD5uF+BUO?-FiL%uJX564X=Q%qo2&buM%jA9M-`q!EhUq>HM zC&b4?w&p&?3MLjmTI;?!S3^%cQivxliqsn(#=`X3)(jKab?N1L_d#A78h=AMWwYhN zrR=0f716g%W zIH=821p>SJevc)iefi3oawX5t+n=3SY0@0%U}1rr?-;>a&mDg_(mR7a>bX2p&X z;O`MH5ZE=Q+MBH0nL@`|D8Ibtp}K7Kp(vOc+@E0u6U|idA z)_jYD@UL$L0=snYm8w7d($LTT3SsH#LeKx@ZON5P137mVK_xkoY(bv(lVbbn3!il8#w9sY4udCnf zPNK2QH9 z>h(m(kAn#@cMa9bG~n8JI5hj6KwuZnuER44^xCVoDUOD*dwm&hm+(oaxE{U%g@GL>_r<4o(Erl2MGjrx%gO+YkX%9UD}eDF>FN;4W1bZJx`=DtY88^S-zgy zA%~tdjeuVfIRYWL(EG+ujVM}0eX>HKRq$TnO~i!w%zJFOK<%DQhY?}N1OmIn8ntBJ zCmK{040Rrr3-tpNViu+9AqFh`MG&m{_gEmX3ukTOE4C(2VCxg6!b07hLOw72%@8wA zb@Uy;A|{2x<4((k{85;|ZN4(w=fsZbgh9mq)dGQCVy*4@qX}~@p9OQaAPh z_$iw_ub|C0c{9Ef>MLHM8gHy;kp|^wy@%u3={TykSF(10#8ZQvo zg?nmzj^4PRv5qq?Oe8w?u=5(u@o24}2o6-ZgrEepR>D31|>7ON7!GuL6KSf=gNA+}- z9ze(P-je>%)^K$ER_$#MOFFyHTKYH7ft_?Qr-8Rt(;2)%^J`JT4{{ArOW*NZ>CLDrlND0rW*ZY=I zKN_z7$;M0!gyywA2?TcGC(F;k9@a~`No>IQX1Nx>;Rky+r@^0^i(n80;~ubQkdmh$<2pUpQf z2?Tb9u24~9&qdT?oiaD^a@QF)X4G_u7+HA?=L|dXs+@G)m_-8?*f5-ZjQ1=X-C#fF zOo8W*U#qc#3GoR|*#DmOJQM^wyv7~J1a{fAQ_&5R7SY1vO7!EQ^>4PyG!RC_*6D^7 zOyD<0rOMc#C;d$s4v}pa9mfQAm0hb(5BV;oufHl~)OpfG3LoPKjrNW{h80ZU_n5Ej zpK2|U9$w&DvgkM_uuFfPA>EpqN7uDbW=w1!*h(w!^n%g*+8@ITCd9A7$Us*qG{+s@ zP6;}W3GBk(U7ktcy_>Y$qBAtJyxJWrm=H55>lyZt`dQdR;-$)Cn7}Ul-Q}mfdGwO@ zXxhMmZE-@rZA^$cq!(LwN*yk@1nuDy0)bsP*Eipb{Hva1d9Wu`wFMbx5X6}UaVA4P zE3-gX8phAWxm~$c$Z?1X=T$$6bwW1P-c?p+PDpJab!yNLtd^`52<*Zc8F?AeI?{l{ zesIAyO31v3i5Bmx$=-fBwCR7lephVJmEOD@42P0K1OmHoW=Y-yXkAPCQ#t~y%$blwI1a-RjIml(~&km842xOUTLv{39)5Z z)tH}|={XdR-O?3uXJQx5gvwjdu13;|^nsB4P)EiJCU8r{vo5%sOa31`p%>T-1a?IY zZ%CW;TS7nlmp$Ux=~hxntsd~BuDgsCOyC}eO4X#Hjg+BBp>=tXKwuZnw#v^bYS31C z@w+QrY!WGB1rz5h8q-q`c~7QVIis;lj-AwVOBZbs#4?NDn8wF^{EvvQd4 zC5_!`1<6jnLN7eIumwHZC!h9c=^*sTc?@7uFKK#(E#zkm)#6%<3EUgx(T@Y}Quz-T z$Qj*AAg~L!G5qYdyPc#7tK4AUix4eVFoC~zd~bM@wvs>l{e?#~W{x*4m4{G6D;wTst5-&btFpa~F{EE3p-b9M5w zMRKcHA@42i?^sL53MOzX!M|#^-Y~yoyYv3W*47IEa>`4_3MO!C z$731yKd@Dg1E7ib2!X&ZoJWvFP zE}Rcmr8++H2Mg)p3vO|RLf%(Qh}mernZIHIy@!BN_%4CKE}W%SrJD1`h`f0b2J;+u z3t5yJ*Wc$JP?1Py5=$YY5A;G@_FaYQHMx1u{ zE{~#zhtdZq$_UHJ4gz6LU54V|$v9uAc)qFBKMo~Piu zImVr*KS(_IkJ1PPcHvXt_`1F(&uC1CIJn;PJjDto@O%qzsWTd}S;evNbIwMAz%G2o z9^V1#Ys%cKqG9f4U4|7*;CUlH&*|>S>hGNg>k^s@1a{&4dVCG!Tz3|m842A!dJDPw zFoEa4crT;RPzJ9fp)9GbKwuZn$j6^Yy(#QpSOlyMYR|BO2|SO-+jhGoHd;RtR-LJ& zn7}T4N+Lg(^TC{H?T^JSx~>;7Lh>noGS*ElfmP%XwqpV z`jOpeGyC=}6byaqF|6SK>s4`*EW4XdZ>1@%&)8#oSxNp3=+L#XKw#Ids@p^-Fq0a# zSLO#z>~^rTt*65eO+SVeOw{C@AcqXoXnCXNoEUZV06X%23e>sdBM{iNu74RhcsYZ% zU183NH+K%OKHEY-Ycrc+1rz5_UnF50Qfc2s%{VdQJFujc{1lxYVFH0&PXcd}dsS() z2~pa_f(|B*p8S7#ko#q<5~3wEKPVk4j;DvhGRomr8TMiDGT1q53W zxikg>c4H8t0(K{IXUE3wR&30Vg@NtwtUkZzIrIJRKKHy|duC>LXU^o}FErzCp{rEm zyy1(UW9|8br%#3N(PILCVHw5~57v`boOj}NTig-|tipXCIBU{cSK2wQH-B31rqCOyDmp!}~GxF>M^#kDGiy zAP`t3ww!AwT%|s5LwLJ`dxbB*V*-Db2-em%xJ*0!9?bigt``Wb62Ai8%>EReTN2I> zc`TE$1rzvd-7sEKbetMlMDgU5Xo0{g`~`COTC=p5Zpa?XJ2$lvzDd>3e6j3XAGViZm!mtGs_{>yTNj_sU&9eMFCKd}L!kECd5}e}k{0co}8pGRvJ0K8P zg-3^BMEGhstvNM@Pd?X17-_}?u9YAbZFZHO+Y!Zm8k!0OR^icM7#Hn-l@`8=;2l-& z6k9OSra`4zT{MR*THO-rtM85v=v~_pym~<&fxs%i=g-v9)pN+o6AJM-XuWptW)FE< z^JH##DY(q(S2Ee$(wsiszOYve{J!z4GtE~o?6tTsfjqEO#u;Yqbmj(Evt(;OW9dx~ zQ#Pg`fjrbnqxJobm$b6sP12# zMyuEBv90jiV(E0cs7_<{8;B)^(}CF1%z*bv|HkO^0I4eHm-frt6k z*w8WQq39ZGPYo%?-hS`MY+<-{y?m| ztl{>%J>(9%Oa%g~KI;Xswcw*${SY8}yqwDCW@+Se*$ri^`eGBvF2HsD^h2mfL~f7g z2U0Zhf|joswqPRlc_2Fr^x?sw;G^HiL~g&!LwD65|VlLZ2+#QSmN@F+fJhlhN($4PmApc^|6W%4njFTEHh zu?qNYo##ORdxDRV3!`|4X&QOy4JKntOw&H>H{@1ltrx{tf>F*Zqj*G; zM$RuhAo#$9)l66R4e0wT`+^UT<70WqUJuz@wM`(f3cm#^Rp;Gf_?7t@dB%x#GFIu0 z@nrwOb@iQmsYtkcjpLdGja)QnmGDMk;@AyO_6lgW!WUB2bS3m@Ayr8~777Gb;r9{F zZyyO?+FY!WOEzW5*n)|KaX#!m_?WX@d28n%gPt~|>ifnxfxs&K-oU7VML!;vtdTv& z))d}a{HD%4WX;rY2aDfH;G-nH0}rprl7~F+#oNT!WEa7*>AgL5@1w`I!S9~U9jNar zJ@yA`hAF>#01@@LGj9!b$&L5jIksTJ@=0U15$LE%4nVjV_2N~Rv*dx19fjHl*Eoht zTeA$sUq?qE{u~?#C%0;3gR@mKu5k{wab#^l_5Fn_^}XQ8-osO=bJ-P$FVYYm2ldt9 zMK5J+!GvC^BWn%xC`&gW62FA=Ch!ivQa=$0tin$|lDIksRTIWk8Z1N4}w$}GU5{rddUl`PrY z$&kM~nM%Y{7)d zxS!fX&>EaeR?fLgHf_jli!^fgR(=A3Rl##^YuiIU?wnG-V{*{29)EYiL#~eL$FT(y zufy+XKY@?$c?z+#n~I-|)yN~y1`7mMoqTvh+Yx+RTC5NQo_&<-uGPr(Vg_<-!Nd+y zsto}meW5b4z3A>3c`>vf`4(~f%G)v8HBgGRn{}mqV!LUt!|!D+y1@BAJ++^J*chwK z>K|BTA~)UcA-h#*xZ(VYvU(6%?2LtzJT=v2oguOqcGz5?RjQwdddd@KYGhMmI8P5< z7ZVZ3yK4V{kEwsZcH>wpKz=h(BTs}cnqva1#8e$CnkJ9QhBoTmM2;<8>x|K!f$MsD zbfq|da8gLadGc@Yp&vRy$T=pi1;=WS0c|u|S!JRBbhZ5BpohHYsYqaz_$0d7l*pPT z8acA%7>+HN==pxRb_w|KUavg6>w52%ufaXnrbG(_R^hh*YPfZA+!bo-1q~vECaY@+k1U~bfC#x=q5eTdjBeGUo2l9(h z`#5~~CDd@Z?!vV;oZ{g+j32vL&cd62ld%O8JI*??RgkK=SCl&OQqE9r^W2ja`|EH_ zVAb3~_G||bQ|y%(E;rYU@4J~LC!TN2ZL7@KV5kAkUsKc6K^Dvte&1k}W?ZshtDrS# zzKJULL*>ikAwqszRi9%ECd3x!U9vylX&x>IY-uPEShdQ)lC^>NJTG7IQB3;r*sUHi z8Cs8H3np;>U_WO}fBtyzH#YD~LxI4ma3@PP5Mu4UIf{?5twMR_o#iZYPCbq-m=MeA z?fYP^{!y-N^`((OVAT^HOLiPe*LaQMumViY7aRw-A*8|>e@v;HUmm`(_5uIuOav3*MqHO_gfYmTQH$s zZp8e6P=8liXFX=e*`jak#mepifmIvc>oE?cd#qCN;hW>gS065Cngv!ITQIS`)QHUn z!mUd2@#cv&FL+e0{qLD0AHP|TbsL*b3cvTDm`?xMj2XiJ9sBnL;*g62uXyIk4u;rs zY{7)+Bl4h{kNgTg?pX)~R_*U=#J<2Cw5_l7igIVVbIZo3wED6s#}-U1oz<0{17ctv z0pfGhAb#v+xpvNqrW`*FScRWASYg`7hj0Gm$!43h5uPhdV1Mw9+$}!b;8Z!AY0yd_ zunNC7aN>JkcfM>DydTEK!ux>fLI$dlZR zg!dd1_!)ySfB|m&{UMFqrfW-qz$#oTLEqVr@VJLra?S`Np}xWd?&Cr~>SG-5|JIYa zZdoGZ8hOV_FE$G9TKA0q?Hkncp282`@?;x_B-hi zt`uTwOx(Qd%$9(U&`nAd?qW9*#=$+=;<&d0fmOJ@f}IvlExEy^a&4nSe%!3&r?wjE zjJC0MwDp9a+6br(suJz!-bK~gvG6 z;zae4+w#oG8d>rR7ou<+8{+sH_F6W5B~Ll&A(z_>h?1E<-rQJb1c%?0h*}JTYE~ z`exi1qxBk>PENNIV_z6Uel}X(e$|utzD^KgQB1Tn?WRowdRbQ`LOxpUAm1x5XB*ci z2?SQ*$Qkw(&9BeLzAM*$un6V&u5J2!TbmE}dChKXic19MqpW|+x1N-1pP3F5a*l}x zO}O?f(ASHUNdMfeck-A=%h|}N5dwi#_|C!?b-Fy3FUX$kc5sw%2QhKM?x6N2_~_xS z_~_B+vfSWqIm_~k5eTfpaWJ%;A;)DWc%!0QjT7QsOf)df(Kdn7jmuUd>zbU>-mB3^XwUImi(6{g=T+O7uYvk1eY~d-Ghjk|c5ierl<^n@em>zOyG9~;@y;v{G-2>+|X4L2&@ugxZDoyc>50?^5I9WLPUlM z+>eH@K^YkF+uJpAmpn-zunLdW!1>g1hTIrNo!4)16-IF|fqVL}+sRvB*4^pJdbduM z2K9JcRtI{iwv)2ych|>dJK#QR#%I%IPPMcJ@H=OCHr(@3{0X~#!jsi&lO|ymrnheh zD|@IsiAxls#*Dq}<&koxE>D%P1ryI~hL!aK->C%(5$D{48E{W_Vsg4bVAb@%{DXSq z(~0Fig?Ll|-y}Z+b;+8^Qcs)l+5+g4AI;06ncrq;Z6PJMqO+)5>I&^B_xt>f~DJLT->pD_Y~Ro>2}S_|;e_RlOJH0#I8 zouL+e|3D*smo2qd!4lOrn^upv)TY37pBrRToLU(7X+Bf7y6(yTm}!K3U?QQ#c&!J} zk5*)XkCfZXWP?MV?EacKfxs%9Cpc{(HHg25ShR<3Q>n@QuIwzd!XEj_G&R(c9fRME zRwvOWi!50vw5Su-C4rBcAp>{}^l@qoYb0R{CQfd!XWM{YRWkvIzBhvTR_I5ytSJ&$ z)icJDwT9lrf?UPNJbS`dKoo8mVj)$HYR;NLZE5~_8jap+#6H7yb8XY<`nK&^Hl%7w zUuBM^b=F932r>>4EySk>0(-&~Phs|nBUbA9D$4`~p}BQBJ)Eockf0c(x*n$bmFL$(g;N!vUKwy=3 z##ilVAiPUv0+IT-EQ6>|KKQS4ccu}>h^?CTUKj}2c#@X!WK*z zM23}(fKk;BnF^6qwMQEOb9dGQ69fXQ$k@Dt3xR00Tp`9Ec93DLUQYcGFPXNs)c%5z z#xpgtDQ=^14Gt#)_3R?wfw7EsG+C(IF(I~`WBmHab(tsoUQZ;j3fJ?nYipO091Am} ztmjlARkP;4Dzk*NhxQj!238H!@)=CEX7BMUo%i!0>qaT?htbeQm-W1=$Qpf(ifZqJmO z!DQe?`TbE3SuTqd2&}>}5yV$xPslx1Xylq7BZSxo69=PK`vFNZm= z{(DDB*mClAj&>2K3@>H=PegXD%Qkrc%yaI(9wYd`M4RTbwHtx9>ZHUzmOs|Y_AsXJ za$vkbV3inOxj8JAyQXPm>M~x4mN3y|`Z(<=@G)SP;$!CaX>v!H&FFVHRv@rStQn5m zM9Xf=H1hDA$wJM5iH+8_+V9}w>o3K}@&W#G>I98^?@z2iU=^;F;0y@(Cdb!1S@Prd z*24M{yr$%UNlP{lM(d}Ip9Vf|YvJ2CdZ)A<%seIh#Fe&e%(}wU_kHbjDn9KmeLM4R zZ#>!lFc;z3#e`LOW5ysN8@W|k!}7e2G4BaIuSb%HKwuSK&jRtTs~I1j{f*V>)LX(9 zOt{j~jK^Uv!sEtGCslNsP6@6lrv6)=xuyhtIIEb-y>V2(a#Spx}MFtNPcf_Z?CYv~GcW4Sjs1R_Sa zkw9S8q$%B)HxSpqD@1m+J0Ag~=hZf*5{~Y1Uqp=bPwn*KM_?>GbWv*wTQGt9CCcge z9y}e!mUdUS7YWp_Y4g>H`M`5E!$s*$^jPY{rPbe9pGGYuY{A#Xr4GBv2f1+<7z@7` zZX^&`C9VqV-n}pP`t2bv?PDlm3np->!+M5OeRx|AGrS#I3j|i-6=^UAu)>2MeU>F( zU1%VzRl|gMKcZu7_zjq2aUSg`;ddMN!tnbDb>a~R{uQFv)N6JUwqOF^CpZW4D160( zm$M)9x(ftW;r9`~Ai3I+CoKNP7GzsW*n$aspWytfKXA@H%wXjlu@eZa!tWz|CvI|2 z{u^e=jMBPE*n$aspCIQ??D&Pf8rcSVshGejvEE&Fx+k}Txzra&I!f4r3A~O_r8?VU zJgji}h~f6IDlE}wn_$7jxIM1yE6{6ll|H9i zzZkw7;@$OHSs<_q_je%zV3GV7)ILYFM}&SYCPq8EFdcZ$@AsSxJ}jFh@!wFxt*U#F zY&ZG0wr-Vq1YH>VZzW*plW;nrebC?aaAxC10P+2OJa>TB+5N&zf-SmR1KBx9yG`~; zimwE<&$@WN5TXpZ+Z(|LCTa%;vhzTHH;Dir;jmwg_xab^?YT399aARX#WZmH1=T+AXSz1$3UtsRZZp;*030?&J+l&!aaSM z=X^1qN5DO=|8jxwBx2$M)XU0xxCyz+7=Uxfal93*Jge=nS|G3rKb7!Cof^rLVAbU3 z!)GXdesUlFTS4WN5i2}zD%F2hBe)r?9o%^QvS7i)YBR$0;7NR|nF6UQP9MS7Kp*E= zvkHO0D%`t=F`1h~`LyX8xnJ@VVWbEX-oB2k4fyEoGZlPDdXbg$m~Ef83RqXCu5^G{2@`B9eK zWV?$Hmn2O2seKC9O%Iq!aZCj7U_dk8<6@RP!_QramN4K3w7{#BiASR{cr)0aAEmgW{vtIX&J7=G8Km`3nSA;a(qn zzjkwN-VS;!C1rs^?+z0mBJXP3LKL2SKpD#z6RX3g!I~obTEPN=Rk$w-(UN|#_9*n| z_ZOw}RVNnqY69cY`{9c-cqMsPpWw2`Fj~uO%)y7#?JjH%jDEaXkjAkE6L?KJe8=SS z4i#{}5>1 z+LhR>{M(gSTHetVj%N{anWtJBOz5|4<+;OFlMRe z+)f~{N^CjXMy2vy4?S6jhjoQ^5EHSV1DQAYNP|`zR<}(|<;Sm=vxapq3vDe{;kF%G zgBxkw@`ES4JYfUD7EHYV8pJ%oNAE}B;KN}F?34u`MG+kZ0;}+@0@!_4oX#hL56!YQ zYHY#8)}Q^DEBNRM`w-wf{R3(I7x<`{u~&-;tio&SVN7OfI*$Y&LyuVtYv?htVk7;H%g}nfnD1H3ze)#|0pGSpYo^i5(al(q^-|LG??_R{GpUmGQC*tZ`IEXtFNh@knEf~H zYM%fyr1`%*WsdPDzipQi{Xt4TVpyCM_9K%l4p~CKXuU`keCK@5)p1no=}kVv?`yrr z(zfA!Ny`(n$tAO~K*Yj3*m%Q9lBp?Ik1`Bm{i^@@Q0l1K?BDObe*)QXNa608!+~h6 zGg`_G?N3u4AE2GPsmb&T^76KMT(XA)j-9cdLjk#;H}WE+%j)f}ad^L_Lodi0qM z-2|n((>h<>Lz74LJ()%4?pvxh9-c=ow#%e9YvrihLq3dBmD2ScyHIW~Thn7_CQJ4< zG1{@s^GMkh7^j>YqrCvX`Q=PH;q_Rp+GZ)aVWEuNX$RKfVV15`#rsQh7M;_2HpnN< zMr61=C zvHC1sTR?b|X;jzTfK377wwW?=ck)gUf2iX}XAP?-ZHzEufjWic$ofRu>RVT~JFJj& zIi;anqF`k%5I1#{`Kb2=Nqk>HApLf&v3gFa58F9CkJN!D@kXE*`y5bAn%5ad7i)aj zCae6v|HJ7?7ZdsL#Bgem;HSnGOkC~j#fqmElhWSGJ9zngBClH+PMv4PJ7WT?mbiJb zXN!wTE$|I(6wLP3%^F147MRmKIA3Jz%k?C4L=?Tz&4Ug3v7TJ28AUq<_GN~Uk8HCj zAbR;}_^R21>1^-jf&~++hIz7zgd%b;b|er(VFh*gsgz~h{>YT_MSPiAivWo=*tM>or$=W<9BJP6} z9|!Bk@>=&o=oFa4UToyf+JX08A4k)e=srx}U_FUGKAP_8WclwoqEMAxJ1IOdR%dV||j>ll;PH@UiFSRBnA@Al>)IQ6R7i z-zS*co;{i$wdhZu_1H(7G;(Im->xNlc1@)I8`LbN^Ez@fYXW`rnlf|9-x7HO`1sa; zEO+Y~Om!l*2o_9?vXI!}>FdbUJxUMKJ!t~>_~=brH_HqSi_@}SCKx@FZe zp{y`*Y^B6rE?P%UMJhf{WKQDeE)Sp&-_8*Ttitz3rK(yI&9`{=qs4Aq$T`mKtJ^(U z>f*I<5}z{qF)1;M7e)7_HzLncY{5k7RtM$)W%VOY>7`EIGlGxq6hxCQ-xdh0+V0td z8G5cIjhZS%it_+|T+g4*`cgx}wL#7dEB3RfkaQaq|35XudTj_Vp6^dJQ*})9-gRe>=~@y` zlzbFK59d!71kyFq1A)LQG3U?r`t$zAzO-vcJ)us-d8#q21B*DnhE#1+MxD>r_T{tU zJ*dGH0|{F&5pQA4hQj?=6qo`;)@g#3Kc{*5y8^L0^k-u6l#n*Ob?KwuS4p-T0E zwdR|ixzUv`+$C(mM9!k0+P8P}$qPTl$I{yEx!W{%`gw96fxs#;=k%NoubkG0esBsE z;u4&vLRh!)@oOI0wNM%T@a*|pcGkMkhzA2DY{3K{&$XxFe&{?@h*7=Y$@YeQ=tBK4 zfxxPzJ-GJs-8>R@TOrhIZ_4+7_ok}$5mMx%V(k&Q){%9yXyKv_+OWlWq~?lQ6w@kI zX1%*|z4k6t?K@J!7EJi|->$vCK94+$R_3-J@TYR!#V+*R-Ee`xDlt{jnLFj0<8A1Y zUgM-zO{GE7^K(}?!JD#Z9k#wK6@1Jz%2vv%UN( z{x7lo)JAqZ-HLV#PnPhtFp(Xxwk+mgE^*~bKD?e@V(Mj9w74=!Ag~Ij7S?`DZ?4UV zw4yhq6lqq$lhS-h?|Pa|9U~r=?tm2jf)wJ^!Z}{rcVz!rolTr&Gu z7M(gH%b5Ya!91IuUaY6ixtdGHr75YJ+gqQWDKVxadn8HNf{D^)P1F@YcfG9;i3@D# z!e>@=9jqzB1Xitk*;w5J&Z>Tzq7XA*A0RQ=R@AS1vXH7z^Ork!-k(d1%f%F`RHZpv z$S}AcQ$v#_oDxi2SvAW!X>TsEIIH+@_!CGvO*E#xrlkl3R^c*)Ss9Hk`7+yz()MEM zV&b(yp3~gT;NywnW9oSWXL*DbUD!t?unONBm5RJ_psjyf(f=AHNVrUJSvCLKPVIa@ zm)wa^e5~3MLc>ap>7gbX30pAX8!=4%8}7$WABC_loJjW!h4ucbsRDsjPBVSg6aM6q zk4+S!*mMU?O0%K=C61GDAMn$*>FOTc^T^**rw9aAi8*h;&eKs9Ce-`+C}~w^ty+Q}Z;NrWsBL+Xx?+AFIk9=x|MY~- zOpnqK7h77sCq~EzCh{*9s2iu`k<6P)y<7fCrp7I7>AA4c0)bVy7Y^rN>DQL}+qu$} z3xcJG^()jn`{xs#(wWq@`m*|X$9yv0I)h%HRiW+-J^B;JmA>=28amR`l0MXGSEz(7 zn7AVjjLQOZh(7HW`3j|j6Xm~&!aU5DZ6NUKfWF)oN2JLw>S4n5N z4l#j<#p3gHn)3U%disZalH6qm4LJEn?FOl8;;2Lb?n7EhlYh9;wckA?Y{A4>_t)yr z3-ifSW2LMt;tiyyNBYn$#8)7&3YQ`D)n+!5vK-v#>%0J=tT6H6<#V-mdOkVrruZ10 zTVHy7(Un%@1PKII;X4a4TuU3NC-bB&zS~L3rHx5A`A+~AVSVDvB0AyvFlVoz85QT zqL-tw^s>GO-9FAmAg~JGCzzYK<|-X~tRat=CDU~^+mS0{*O1!f zDRiuk5lMjjE&r~>)Q!JMQsk$;bn-?M30p9c1mB+MYq*9SPf;R$=dn)G-2iu*Fx*@q zunLzUoI=~!K|0j9Fa7VLg-}+QV9rg+ntKIg^?GI1%ZRyllCPH+{hVea5Lkup4UD~h z@RE*2`O;;b4TYTJJZ0DFLQK?! z9VET&QMVQOp->bLg?1o^J!pLH*yfly;k`c`e3FDIa0NbWaNyYA%}VstF!A! zMWiw!JlA7_v^Ud-_H3Uo5LhLS@9wWLPTJmf0G;8sLC85Ka$!W+Fk~HBabi69824qg z^zu=Ey8Fy-fxs#}whTMN22Pbqw+*C{6V!{_yvSk5$Duz_^!QwNVs&>tS$-#q&W8Ne zNmx&cA4G$X%06+@qe5S53#)J$!fx3Y@ltit zVA>|Gy--$|I1uYWblVn@jOR)iJKU=fttZT#7rpITKLyNO$k*b^e8T@~#xkB83H-vUxRYKaCCra3YiQH}mY8B8& zj1@xDLQNmM&m?-yk_7^*#y&Ps-vb{{T@~Wy&Te$o<4p4EVzPuSm?){#RbK~U(ny7H z3~?nvI$5ODEM3C69e$&~^IlMGgWZy1&aZ{8CUf6pk{hsB23s&;pE=vP4Cu;i#YY{p zXT*4M2^p4|DiBzOQwVRAVNE&~O82O5s)Q|=NDZrSJ_kNNPWYP-_)6y#NL5};ia=nM zm~*R&6Lf6tEOL4JSSh~ON_Bgf6WnkslSZ~XsCI(i&ueAU(OXuiUEzLI9#;A|(IMAq zN&$S){8Y4rEtu%mOIAk$@nEYGQ%@h#S~B^TNm^z5NP7qUR8N8HCQO(~-Mng$wV*OO zJcB;mT&cDjL`@i==CZOW1;mD-Uj~Lx6sAS@ChN3KsWoC?R&;h6)5$ ziK#k1yROvxXD0dYNvMP^m^kJCR2>dJ&W%-kER55WPJhWH!|MhM1Xke^fgNsl=1?oR z=XI`472d&5yT+(>;JWQ$uPuJNVE$v>Vj5nRNkVSLN!WskjLPZihCp{4r}WS7A6P@% zFM_vrK&(Ju6@C_Aed5FIbmy;3qF-Z@@RVS}pmC169r$?vOnI)F)j3FSK&rGp69fXQ z@DmE-B>_~*X`4k%BD+dGh!NQg*V^oxPWA0g$qjfieqK+d|J83!R>S{Oe=9wf;<`>! zt<5E5(;6!YTQJdSPE*2w4t%E&3%ib#dcpj8RmvNhTgRE)g=<~?8Amr%I+EX@I(svY zjwo{^x8Z+>zp-d>S(sF{y@X^X{S+*icw5h!yaxKXCJ}tZd>t%V8)uQOb81NVT3B_@ z$DUjOAFDekG4=B&AyQbaEMnWHzJx89n8vKhDIiwlC_Y}ic9n+J$Re{}bP&qw^A%IF z8&p}JQ-yMa?-d>Ol1zSQ5}m4c5-uN1bXnS!aG*82lEH`W9Y1MLVF^h(Vki(;g;NOo zKdOSHD}OS{$Qk+)wqWA^7YlL>d{`e;=87cyV96TZsGRP40)bUx&Rrf)kv78}oL;p; zSOI}oJuJ)lw=yE(hcX9w<>q9m;kpu{*|3gc3nq4M??W2Fnu*p8CIPWx#zZMZKZ{&g zy-Ogl>dHG;@(S`X<+QQ_;_TE^$*fTpIo$3y8GbX6r~;>ve7^|VaC;!>2-me4HG-;x z;p@IYTzR9!SFsr>(iAA&J8lMo1ry;q{=^t)eQ6XBEv@6Fjdij}uwS;Y-oy8Z52=Rh z*4{b#f7X61=$s%Wnq`rypjg3z36FFBWvcXI(lavqW*os5Oo(fWn$1X&Lbg?s(MP`s1XkfY z3$^H{Bx%bcU1~GEwQvV9;eNu0e23A`w2sO>_ee^R2JNgQ2XzMv1Xkhq5u&~h@zT&G zy0mFXqVObQ;(@g%sRAEsek-f)r`C>@PVcTHAsh1q0;}+Sf>VL-Pms!%>QXnGt-}4l zM9n3=$#d{A;JWgj`{|9AX6&sbz22M^2&}>_1FXf-kCF~8)1{FHcZKH)6T=?$B)7oF z-et;oN&eh0DSBTeSz7nIKwuTFUEw5XHc)b3u1j-VYYMd}CQf&-Bqzbgjm}E@v1ML> z6a_v;8#WaPtir7Xtf&6kSLz2oZai!yv<8@1ILVmo1Rrk`Q^7~C9+ET`%4+TQ?z_WXARG<*`VPey} zhw5F8!1=T8QB=foE$}D${WrY4dfJ7hNva!&eNL>xJ$;B1 zTklZkP1mJKcT$Bh08EH;kc;=VleEzPXkFzc^wo}>sXXnKo_0(O%-16efxf>@8Ph-Wy{pu8QwbR#K?DM;@Y@Whg%;UL77!=aUf5H3YcVk+ zr5RZTK8hMCKJuG&m&%|&nAEL@KwuT_0l+uCdxZ0^sk*d%(<+*r;>e<4B<1XdDZ-lF zR}HP12L4|$UWvkQ4;sREW>ym4>naIb@G9RM)ix{#R>~%oDa5ASAU-o)mp=AuED%_g zx!#n`10O!;mAMJSzN!3YkpV3jd{T|adhqCwIPTN5AeFzc*QLKcc@S*D1RiIC6M?c) zc+GfSdgA$2fxxQp(Z0+bQuWC*3R1PBVG4h#sU%Z2)T7vfi5(^WEE00wcDO>^c%HyJ zC+JecQZIqPD%Z|l%oltt?5woTa|$*5Vsa(93ST%Z~3aQDSE83!W7MQL$9gm>W<3o1$f^F+cHO#G->n>_&E>O_So zTiAvVnW0N>Z}Soetg<-$OnVP}1m07|WTuoB%1a<0216%Hc;&m-vf0@E{fv& z4?VBKWS)IClN9~37A%<9^4XtJpzFhK9ynbLR!6VVl#u6d0t5o9@coCK-m4P$?AMv( z@ryAOTQJf5KOg1_KBmuA&O*BMJD#g9XOjB?GXw&wo_FwJ?m(CgRi544$~3M!9{SEd z9scg%`Tv#nc-$DjU2tCCwKP8dB8+%x<`Zne#Ckc1Ie`yVmNFt-d^DBYPAMUye_j&^ ztP)Fi@8VQ${uJ`jv6^5DCSJY@WX|BD%ioQVB({-8w-L|?J7~;+7P?Z-1T!NS(SN7 zAg~JW*?@DMpAX=-u4Iy!bqyq3JNxF_vPp2=88;HBMSvyK!0)vym63@FANukAw=&6@ zCQT%48O*w}6i|5=CsTYS_%hIv0Pa7vgm{i|IILQL|x?k0vYscOT12j|krATqfz( z>!nb-m`KobVk3dBh*0Kh8_{rHom4{VwyhQjtP;!0{=*PX;2j+LQb))+CN{6NXXC-g zni@)5+idPYUU4mxY@Jp|Ag~JGO<3KQH
      K9-D}NAcUK`_hZ`h3i`H7$>~VaH4et ztn5FZN#1W+CRi}BqvRhQ_(>UCGCLB>i{U-b>6kANScRWs`1U}+B>oXo<=t` zYs|L5?{RPf4Q@*yZtrc$EoPRG(m-bkTQGs!5*X{dX~tb2W)hPLE)uq2V*Iq)tQ7pY z%v0K^UhR$f<=dHLbsbNEz^d;3e`(8sxB=f_f>nB_+i;WnnIw0Tw}dTu-e0w6K~)Aj zma%Vm5?{CA6Ov0v??1kR4@}@z8@{e`xfx%vu#&6{^cM)M5?jve2DQ1;4!$o8m9Pa9 zxP62kWRRC^4fXD}lqBhVw52u}W_Z5nXH%2g#@a#fyL;Dcdd<#Qn+EM}lZML7kNLfx za%-6F8|slPVGAboTh`J>0evQ1A<_r5l#`~Fkm1n(z!vk&;<7bx-HK8F>*Mm98ggC8 zc|VdO_`n2Sc?vDgFH_kXA{nDKNdkdYcm*wtC*IPNW0H-juV0d|wiXk3)hwJ&xyVx9 z{Sa2l!iW*R7FOYPy|8}w43lHvNqpC3yoC4jJ?y?h+YZX7+r$6e+gEGoZaEx!6F-Jc z6k;Dtbh|Y}YXx)$oM#HB@1+&XRZzO@f1)Llzua3rL2rJ1i zO_LwO9n8<2DwHlJaB5YmT9G5=@9>ly(iQIqR^ca9rTX-In*1JSm*zZ-7oHMKi20Zi z6fN(7k?rLd69fXQ@OuO6OWri$KcGGDIJlpL-|g}tue3LzW+<@9p!j`+uREGH;8$T5 zxu#Qy5VvDu<=Z>jr$Af%J#kUJss@+ll#l}}2MYvN;n-KD+A#X7{ODCC+3yf8VGAaD zE;^z80zTTWR{92?P2b30pl+YvXQV)2Ri`&x`vZvSf6tmMG=CvqhPdSY+z1I<@UB+u z8&)pAy(8;ql#uYGQGyRl;2r>+VS4SN%%N{^&^AUOuu6>d&)V&jM?jsJ++l)*EttU1 z7@X;(Et2;TSih?~Q6R7i?-78t=d+i|F`uoeiSA@!_W&mF{!!Q^w8)#!h4y?zVH*iY zVXsX(u~|@}zx$?A967;h(~sTx8+ZqIWSal()xU3V z{x;c`elqAF^d>NY_pw1f3Vry?J0`TnspbNKRe0})&XCT~< zuY-8U+a{FP5Xa%LN*t59w?2&TOR%N2hrSp3oS4A-BcU$27scz}G@;tTR|Ep9@CXvj zhHsAHnen#tvfEK%qzDsu$0@YujuZLrYbJDa$a;amDm)SfBVOi{dE+=+YTah3Fye&? zaYwG6emw7T#e`0u9W4-8g-7&Ms#~2kJYupfP3r3@jND;D-0xg9HHpu;XhOY?)fEV= z!XuN=)*epcITLKD*RU(X2qY%(4sck{a5b5C7-ma{u5}j(tit>2VV(ZCB(8JUpN9Q# zCD?)qac}rc7%7?^8%B*XY6%2Z;a&L9D}s~vgJE69&x@CYS^WtUgNP2y@HZGcLYU!) zSafBYbQU5R>)|EBTq-8mgMV~xZDkb4?^2rd4(6R*&IbtuR^gdnIN@(Zy7Z=57Ae28 zOPCYJMEHw-qz0t0Odbk8GT?N7i?5mF)~yeY_*z)y`t~28tZszf1WA?JT{fU$tv;#o zX%zUh4LsWmr>c0TNW(XpQvDuN2)1AXuhN8BfR{;<{wotYU-~Q%ScPYM;S>*>M5)1S zTe@RXD~c_c5ZAqqgLSVi|C!L#jROS&tMF_uydTkV(x|z%v~0D8Vhbk3RmC^bCP~fT zno!5>xdMSzc(xbjQmw~J!{^)54?j0kY{5h);e?GJ%c7;kcTks}+2YW2Mxhf1OEO=y(nt3Y5Cp6!Lz>ODfGn+t7eZb%IYTQGrF+er%vTQDK+{|GGZCI!R&_^`-PAg~J0_QH(GmX6XrxF4CXsDv$;5O>!s zPi!HvHzu_HFmHjtDm>c@@oudqk{vu(-QW95*n$ahC(_nyI@03TCiL->fdYY5c(zxi z>Z13FzMNxA@2?pu>~O;b-pvJjesbn?2>=tAdukCd#+3(01(V{7MpPmnINcCC(zxUpP56C3+Piq-qllxH?FC? zepFLB@2OUcXLa%XaQp^;Hf;S;vZIkg7;jAB%X)X97VorLY{3MMiQokO6UjV>*waW0 zHNyl};rzkZ%tKCPsk|UNiwqc3 zNB;Br-@H@XumSW%o1njQP#x-p&?ChGY}L=%IY{A6$H32Ne zd=81&rx2efCi6mSO2;(6$g(p1*xD0I$u*Y{ic31Kl@D8bBbQV>P`-KJta~!g`eRE+ z+izyrf(cyeDpj>v5+D7}g^rCoArM$4KJ67biJT7VPZzA*#IOYu;*&UG1Dw#bawMHL zceg-b6@E8iC#zo?chNi}HS5V*e7YEZj&Zp`KPoSks|M7dmr@AB7EIt$fHV8OQn}uz z7lfOX3ItY(_hWMZ6#ndVO)(b|80{))3nBOU#*KM?cgj!UU;%i|Q-qQrn)#P;k`$#7F)~%`( zTQGrlKEY|a;m*8^ZVUcr?RMG!XLGjV`x0VZZATm2ZNbtyFDI>t9qsVafORNXMy9>6 zhMXVBoy5!hmJ-W%o8^-q|IKYZI@y=L_J*$*LfRXq`Ov&i?rezuT=JyE2Z+&)G(6Y5 zCLOeBw4C|PgIQV>5LI{(-Cg0rR=p@7H)r_J*Y(}lZn~V3Nq++#9 zvd9=OI~uxN#TNF?By*$fXm)80*32!Fd~9wH#51pCzIR_aAx`Epu6=MV5%tiAUCo(8 zvUs49swYYOnt={&qG>1NClNn=_jzBoa^^Bp{aYcTpzJz@s9a%xddNRbh zD}CCcBa8E2Pxh<2(xyHp%%!xDXg_oXB5VI3uIpBt-!AIRutIB{k=C2BK|;7@o|}$}i{X$t?=aS!R!7@~Djs)nuEq{oP=9-cM^Wh{)$*eCv*Ha^FAK1OltXvf9^b7(e&n zyKFybE5jB{WW;u4v5D)+t?5eX&NUp$`$XyRR#`a$fmQfELCp|0fiKyxMqY8yMNa8y z!PdZz)itXf=-G4K*oRgnf&Vd+}o(*}X}5u54RP;8CASPkMZ)6$`uqGbw)@ zC@v9LDZ3?>pI9+N?&0Gqlocj4b1hlQiV`xYrURrZ%WX36dTW84v_<ScS_CPObY- z!{Zy*ly8n0EH`klV`mMD$hs^w?YY#Rsk9r2aSKAPezRd&-Wy1|o)h?peV52LLcKkN7m;Q&B_NJ1PUJI2^k&VfhRN81 z3C|%tSk|`1~?q}O|I@G;_A zB9EUkhnOb?%XW!QEV%DRk`Uoex0*P!`KCo=&J1^2x3)98=)RG}w)6nvO0zw)Jqds_+wRt;b1%IuRjkiwUW zk9TJ@T-7dyo++#l`Z#4PT-p8vIEVRbkkH?O@7JE!z=_<$>5Nf781C0#LiCZAp1{Kn z45T~EUJ3+O;r=^t_&oEttT0f_-;>iG0sIN)1-l5(uoq@uNx=6q(4+ zG*{E~k+o%P!32(KVYT7d6kfC~n>-%gR*3X*D|*Q=;P1M=JLmgB>DpXL;=|oGlE4Zl z8Cx(Rwzc!ipm*mvhXnTv5eTem)54$ihKQpyM!AFP#|ivx!8~%bSCot`n3&YjkM#k< zJWXkx!+W&j2cFzk?|ajiZ;tw-Jpq=-yX@$sUp1Kwzu%SF(}`35Xl(Oqi!#|5U3p=`ea80&! zQx<9XKp`4?w&F97UzJUBtU0z|0>^f67E(b=?xgccz7*YwdvvJ9E~{WC^lCfm+*Owi z`;tutJ+`ITH;k&4w&9;1*W&GOw&c&uYOrxmbBH^P7EWEM%RKXElSZ;FJ)BdIEef4O zKK4@D^Cc77@T!qD`0c)JIJRKIFj<$KpER44mfHgHA+jAeIq*Z?dcU1OU=>a+%mR#U z$sgT$isjXAbpLK9qr z?HV_S_)k+(bv@UJI}d5W4J~W()1eL6;=A)m)k-^hC$tvxE}lmk+_a(CH_Xc1Y0ujq zZOfBAzRH>Y4ViD_1>{9Y~i@7tO9E!1__)0K_{K1&p^)%+1f&U3UFp;vLHmf>5pS+)> z_}CX~% ztimM%<8aKB&y48A%>r);Wrc~WSL(2RcNY+!+KP{emZm)TbO)YS`+-1U6)razVJYdt z$M3e{Y47sotsNV&@;^&RvWFE7INE@H(OE)jlv&Y5E1IyCvzL&8hZG;S9nATnYD@lb z;0766FtKBEeYVYUF{w6G`kcAJow-|-B{#3wDiBzeF|t1US!*%bW2F$au3K@h!Pfl4 z`|0w@ca7QiKg&qa5KCG(OONIJTuMe?vHYKYt!A?&Ke5G{&m5I0;~p<2qQ>hn=hsWg zh&xIjXOq4oH(Sw_*ZJrqKIyyJTO{{R0{BBYd-hIW#MR79PNtd^B6 zLMj<4qO6Mc)IuQ{*`w@L*L9xu3Yi(%%3j%t{Lc0M{PBC9?|*Kdk9+5JopYUYo%1}; z^E^dl-b}myvr3&A-wT>byFnruNb&j=6LuZ6q@;vGGH$25D%vxwCj?BggY#SbI0CCO zeKe&lKUb5IH!?vjyn%E#hPr`|r9&x((kQJGvMRf)aBW{F$@WSy`Dbk_+{iSN9&K1p z>T+cwxM>iS#GAk~?avanV8VpzOEWEt$*dT89W|$MAPh@oJ*rhBM_|>CKz(Wcvvs6% zp-hNX!(qImHay#~QJV6@ShD-JftZ1fkbl@vTGF$G*v57JKP%yNW+S1Kr6#yFuHXo~ z(py*FS@KTY$Y!!Otc-@q6Ch$lD|i7*xV1B0FJqcze0LcGhHunhOk)JM9>l~2V-uwmBQJBCh3+BI?%RKbhH?Z};WZo^6JIWdw%4PG@98nz z>JAfl?ZYyjq=bT1zg48}*b`cPM35%3ncg61@J)7eW{qMwpN9vIOB`?GBi0Xf({pR$b<`X zIRdNrRnf+SVW767fCOx+;rd5)!vF3~c~ivq6*ha-nE{hM3&_MDw<+!un8;lBKYH?Z zxy@(ooee9s*N|hrXE_3^a2>K(gUC5>(QYjnkyFXl6(+td{olEw+sl1e85_bQA@A;L zvT@V_j=(DHzh+SuhwNah=m_ncUW__68%UJfYJ6w9B1uNb^@;A7EmVkBF!Q;{5m<%i+RX3MwhP=fw1*SM`?y&+Cir=x zNrgFh7_^7j$!)n+5nk`$m5f4R`KcT1OKYTSYSpEHd@6yxQLTt~+GS z|40YNx913~a(bpIjcL7t^jaemnk^>7l5Gk)>F^KQ-P2aGS)W4^HHhF*<|6Hm$sx`s zJ%tCEwo-S`d{R{D!H5RqX|UViqV)IDTZ%21xL)8QNhbN^d8Q{L6wy;*Z%;Ftzx6do zVAbl+wvzkBmBek5T*lhi5XhoU(tX><6k9N{G1En=-nWuG9U_-;rbRILC-*wrQJt_BQ7Pv9BEVIK$c;@mQTU(=t_Q*~WApA7c4@SX`19TTWfdQ2C!@51>RFtPQzs&uAR2AQ@@ z9(_(-FoT5!Z>UQ!@0q|V{>j^2w1EX4H|Za?BES|*Xev5Lk2NyL$?j@1XGw5*DPTYHii5%0;(*4I-B>a~fE2DqO09eyw6Rnxqfg`XA_X3vfZMPRB zJ};)Tf4AfM2PS-Obe5`fa>$>2xs2M`gW>OKk-iR8<_N5sq%e>yzUGng2XgJc8|Mob zM<1n|o&Qm6!9qb(Km8;39_3|j{lRX^1 zPrXlD1zw}rf{Ep)%%mgFSCexpav9e3BcadWC$ur*1V>=iwXT-Z*b(c<*r)PyL@ls^ z6Ne_!E$7`}nuUh6c>s&7I_N6QTH9Lc#rB%leRTdmzSo4oW-xD1BCV})=RB#Ha7

      fmPV=%d#Olc|b|%1F3y*H#j%MSgItcG~w^e>}pY}Z=ePTztrdxNw7EIvhV`UWfU|yW|blg{Gj=(Ct zdUfeO^ExM9lk2MCOE;J~w;NSC=?2(>3G9t#KK%$A=(R#Y_4EXez$)w)XZgq;n?dq1 zb$U~80ALFyct7D*h#nlxi-Z<+@TUi88? z+8h(N1{q7gMkTRb^4_crb{PR&G+QLa``U5@R^d04d5T^bg3@o1hDgp_BnOV(z+WF$ zSEo&2%gZBlr%exT-vATsEmWmNd(w!NB!8pk&NYK)doI(hb+#OVRru?}zRs;|Kxg+6 zS{`K!*n$bOBn|0GSsMA4DYxL@Fgv(1`~dCl)P*Ck3V(fACg>N=Fm`kn-S1}u*n$b; z5?$#wE5kohZo%1)dcndIsdVN`OOC)Q{Pkhc>Tv=z9~(zM4>1R9!9-rMv2;v_WexF> zTX0X$0pK(|m_E-jN;=jls~rB$qd+*;pTNZ#35Dq#P9 z@?9=t(%M1rDEhaDQ-L{0VAUocTdB@3i5To7jQCbM0h+r;OEK?N;PwL-sr*iVH2_;M(Y?t+s?*FMw| z;6uP#NmWaiBd}`TGYjctFLtwNx=bAWHXK|7EG5$~+JG%LI@wCo9NGE$t^fB|b*vl< z7jC(Tk0-R_%D@En8nHEw&LmiN-(B2Vp~Mkbg=>WEDArDcF`bl2X!(1JEttUTc6M{` z=jkv{r#<=H=OIU674OA)9UKlVlTwMa=@i8lOzV&j!% zG{h~uK~B8Q;CxG%z#bii!g#_$xHU^v(D)O?5m<%yx!EbY8H-`UM+3pqsT&uoh6x<+ z#bS!SEQax;?1Ufh+j0a}@%!iPPuN22qct824+((30MSp>r83qhit1ejJZiIC77y$p zqh+bb&AaY^Etoj|=6`g}D|z(soa6+POny}^UE{_PScOMzwoA6!3F2yAdIa=y18l*B z=7|o{ZuSe^hsrB2`|rKr`sh|3mMT3s0;_QUXS;nxy`d({h}5fh=lVG&4jeR;idY#5 zy7I`NSz^WG&){@u84dkgL |RU0|Y@Jq$fOmg0RUyvK&0 ziJb`)?W1x9#8(8@5D@R}zj;3U1s`Exe_o;2*{p(H?TQGs&H-%!AY9M@%`A(PL zGvx@Z;-d|>t51UcL%!0dWBYNjgP6eYn?hlACm2>3-lqBX12_V!aBL*=uxJFszIWC1 zw{H*^1BnU#O?>@yCj8#Ak2(}i;Rvka;}ZjwePOQqV0z142k`90R6XVxEE{unMoEnJ@guD7bfLEw!5Ug<=aP zRz9+lS{z$R&V7-`-EW>FA>Oo{4p{z{Bd`juquE)qg0XN=*iCN*JfhfwiOen5(rUdz zqOw>nBk1R7=#(nbs=V7AfmL|r&E_Q+1K?ZcVcKMUhGGjQ6u~x9mrZOhHBR8y@X+8WJurC#&)8g$Q=5?IhD%>&R3yd7fx6B^;&|dea|9yC}9`qIZmwv?_KZ>1!d+ zUfX>OhozQN=(PnKI0CEmpW92RBQ_FmfB7x3{5lW3-}j^=w6ZC-U;;RF1%HfS*sHFteNinVr|reVx~G&w&Zt{wz=G@i53a zkxeJI-p&zNh1*G?a99`w2J!1?@3$3PdticlD;4@Y^qpxdu00RJtl!uuj@ zgzGmNY)89N=~QdL7EIt#n|XvCqhb7Me_Fg}7{zZKj&;ZHG|TpOKMGphkD^y*jOE@$ zOz>Zvi_ao}%*vpZzZP%=R&j5oVzJ{)n15pzO`o%rVhbkl7mh`Lc9;g4H%?Ngak(6U zRopnHC|(}`NmY;O72N`Egu?_s_xYAJ62=sMq*qmUa0FIi4=amr2Oo&cYzaT(cXOUp zOyIc|>w|iOLDfSEetVqa2&}@MVwQh5!xOgC)^LCMS53Qz^JZ?IxHynkPz^C@R3g8e(s!c)M04R+e8aUu+`P9p2xwg7Cw#L*wF(kw=+s>-oA zzo!MlIsYV*@TZw#0;~Awox(}pa6~tl#2xJn*k^U--v4q_d1-qHy#H#N@=(~?7*4F$ z>I1f5LMg#kieta3xlEn`IR6+9jh;~?Ek&Cnu*%ooURulu>$UP36N}y65Vv8kcXsw)>2Mw^@UUmuh>i%`w5()rOs8LFvYF z@;aw2M_?6x-`H%)z!1VMw$Q^ReE^>_#Je)s1I>Ev-Og}++#2e6vNvE0Ch#s0yXAPG zIjH{FK<7o1Xkf04qJJxmr6d;=d7EEBjFI&-9OovuU>&5Bo z9&rR#;m8pdA*44O0y@sFuxC3n*n$ZhN67Ai7&r^M>A6Xw^;M3*DjaLVTJXwjP>X|o{w9$p$tD6}|E^{Ke#-vct%Yx;?cikM zRbs-3m2M|##|i!6g0U(b^tmpsTc1XZCfExG&ez2>{dBTN*S&QI>hosYsXMSL0EK@T*mE#dE(pA^s4@ElIB z1v`%wkxkAu%f9e;-+Dl6O()oNy*I@tA2zksl0H`yk~iJ$1bn`M?HeTaWbq}A(56(2 zJ86ME^y4BmC0*Yl;%O__RpxbfxS(POb2X|ZybIuzsxL*fE+(q8ZH4;t9i)`(BI0i# zNA`!a6MFA+I>XO(ZGl+QQnDonnBHNc6(Bh2d*>n|nBe!7e}_HCI|IwAs8iqx(mz z<49DEuJGw+ zL0HH49D!AQ?QT3^MK2`>!>^)R;ehBNMx0#0GSFxWXNNn8-sSU2CoN6x*RruB(11ES z27^k=C!7Tn+Ld~ub&Du6?SlNPTx>f~TF>@{pFHCTtisR4&dP-P(MdY&?8MG1!uISr zVy4?-@>E+(xau@U-2XR*tlXn1j7abiPmNtpG79xr8N(X;(bn5SAV~iPXTe0yWN%UX zMl>;9pvef8Z@p>cCC01U$U0)C~UE~vPUAhmafmrcwji4jt`s;mSMnIFmZkULUE$k60+V`ixES!r&4M- z9sUkD%@J6IYlNMHyqrkCT?_+_^<{!u(@L>)Kr+$a(@9vgtU%Q1wTw*g?#TUGwz{)P zr|GKUP}eb!>(98Kzw8ZM8JO7Pxl^3snn+%TX|v}jGRvUpBWA$& z!`nCltMD&mK4k43^pAZQ^jFRm49r1v>X1gd{M8pW?U2NpRw?A%2_4~lQn@%?HHjR% zESC{@;v(I#F9bGd1qseo4@6~>K}@UlgnK2o#qnd($-aqt!hn~z#2!~N$dMFzyfVIX zmJaR`3K`}s>nXBeV)=&~V#4P%64_OLuSOj_PWMj=1LZHXIRdNjuVv4nbA)cqnGUt1 z6S(KVgl5Vq(J~{2Tw$Xf8+S*S(dVtgAaq7LM_?7M1?GEQf13uK3Wjcx{kbt5kL~#R z*yy8si>CDnhVz3*a?gQ@X)aGh{a+bGaFpNO_T^V;R_hQDj!obQtirXLtI$oNKvcSEDg2!}AV{6P-F94!UV^ z7EIi~@Kb!^ltZ2e$Sv4D`#Wv&4}_u5JMjck@n5yS)?euNrGcP##Fnco{C6jD9qPQe9&v{A{f&-APzSu0OL7aE-7L?y3{~Ebaw=-i2{> zg^347+S1;(Yl+$^xvsR-2SWEkOK{Qk^1ySP?(YqxyQU>%NGV?)i;nge;LtByh-lG~ z;J=HBH(zz60{wMFwXZ2F<5om(IB3-!uKG9;Y|(h6Ek#DGCEXfKxMyOKvi@$c+uI3# z>~iDEz{IdTZE4NmwdCu6Z7!bb1^e$i!GgIS9D!B*lRy752JWP*LA%005zq8+hNeP$ zQz`lQCUU~Xf;~rBnLoU_&raTF>T?8E;W}jVcC`_Z+C>LyE^BeMi;3c{rjo^xO=POG zT!z=%;gB{~2X4gaa0FIuQ8tynt=UADcae!J(}shnsSC9crXJX0yVOLQ(R&k7Z#EbB zU&YRhfsZfCmVRkER|Y0dG#N_C=SxWEk7lfliZX8){-iV9JXp*TScTi4ot0VCA9|g( zgxLZ}_%ty-i;QRIYz7cM5E4$C!zHqpo3~>EM_ecrIm(0KvWgjKZQIBZScM}z*m|(U z5*GC93&lxx6t7a6$G4Hn>sOK!Rb7Rcnl_S`H@lJTP&fAEBU;$PrxmU+D>RBbONLLA zyAD;CPGznlFaA5Xt)$isQb)PMnLaZqwqOFs%&=c&W)C~_Twr0^1dhNe9HYZxKW11$ z>B*ju^D&3w)AsnhTIJBT(wRvGWI(2T#@%s@H4GJd!uFdf6k9NX&&sh_XI~4*I_D1F zi{^3!R`GSU)5RK2h4+CgXQonY!33@mmXY+d4YYgL8|=1uaRgT3c4D!$r4Dd(unW9j z<-@fgCiuEi-QWbF4NhQmzaK|n6~9WIaj`Qvne>DW4!gM1XZXa~7p+#(YUez%S4+-X zH`mkzq)|QL)ZgtCTQGrh9I&s!a{~wpC(t>)kR!0_>JAkt!Y`lv9xMA9b|e@@b2<_4V6!8^8XS3Uy?Od7pxzugV;`&^Os;B3C-yu8VBv7p>E zSQYZ-x7h!CIyqM(M;o>{qYcB~zNT=}4sgC5oIPi6w^kbc7z7AwxBW5 zm?N+X*9bcXc|ivneeTlUsZOxUr%C+#DwXK$auRT+AzUM@1*`O6itk>!+RGg}gf@xR zI_&nT7wo17bZQ6h2(fkTn+_~~x14$n><8v88bqVNDWu|UcR|o=5OWMth`NcBfd3N9 zO%_$s}*E+~!jU>x1!QPn!473$O(fI3pDEz2;~`+?qMG(|w-6D*Q}r=V!DY+kIV5 z4F?PaY{3N1Q^h>n7J9JGG?miG0UUuz@D zM;hqeARbdoB(uZiCs+EY2PZz%RFt(H2H1iL-jmw(q&{dX4UsOk8Ojk@h4Xu{EX_6@ zz`tvSN8iPxxL<|K8#uIHe8hfjpD?-CRw$`Kmt~gX*P&wpTQJe}RIPZRMItHLDUWcs zqFMuO%JUfLIDsRuDq?%BSkKD%T`m)E=QL5laGN;x%Vd}tc1}F>BY`~8a1fg4WmfKT z;uY>7V4CIGzT1N3dCBv5y=oF*3nr8oGA}oy1J=l8JRhV2&3Snqw^IW+0;~96_0sA# zZQl0FeSFgl817RpwqtqPy|&v4bq@Q)w(Q^L2knG4Bg)0ncL`+Q7Wq5a(B~fYtN7u5 zxa|zU7EHMGKQ1aW`q%(@?qiemjJ_)UB{m)m|h-oX$L`i7OOM*zY|vyPMz@ z8!Jw!W6=T=ZH0tO1)@3o|0{juxoB+GW_t8_YZ7uk3a|weO@6VW3nO+-mA&U})+Nw8 z4_c57X$wK)t*2eatGW2Y(@D;t8>V8sJ;i~;?(VhJ}t(8pZUd^J#lfpe#2r(Ri zRk%F1Q$3)7IzDJkd|4b8wqT;|y#JL^*jg?l;Ph%bvbHs`+_``wu!?_1n>dD*VXG#Wp>5bKncn#9(f&;woV2Z~oX;$7<86dP@TfA9{W~Sh zM(`Y6Rq6F$Ihi|3F5_z(75az~zmLTMwqRn)m)HN@jv&pIiAQa8sf(R~$JyRIfmQey zDik-uZJEQM(ZgwYEMN;J>LT^UK=upGYveLE?C3`=*puHKwv;2VihuImW;dm6E)5>J z8S&hc<7XP_6!hP%3)|YuW!OC3DZP2w?0&2BGQbv0bY19ES$L1#A>BqMF6AajozA@T zNDJZ#tTJsqrZSB^hq{_fq%L19^<#wL>}7y0m{1DvsZ3`?T3eZ@i7=C%e17hpShWnW z1rr+%<+?T9Wj7Fil(RJVj4Ku|^ndFSe4i(o!Yu)4tt09grU9Ga0FK2wJ1AN&Azpsi>x3c^E<`6hYH&}OFys+OV3q3jMzQutHmSCfN9xCuRl&ig zA5>Xgq}YOqoS}`Pf5-~rJWc+7M0)+B^$UE#^7s*sz$!JpPvSzzCV77HH)_!DCOUf3 z2)M4lfnp0LPOtqXc3j3X`ka-=_OMG0)cMy~Fc&g70;{Ia`zSs=u!1C)$)o5|j~~=a zYXS@&9zwAN6HU*5il@ADiKs3UA5Oog@vj5H?2Et=SY>|cgZOi74q5nH?jIWZU+7Z* z$?%5iQ*6P+CF`H!&r7+av$sqPp7n+XJqZG}qE8Yguu9YDgIIhlhs<-6`^VoWhpEns znUK?A7=88gzF3-`MN~a)h1=ox#XQGs(z(<|IHprA-uuq>(ud09?!<__wBw37V7khJ zVhbk1i>`?a7H5$j<^T2C?2XiRZzMbzW6cp*wOesk95^GB+?p;w$0pM~bau~qaJt(e zanA62Vm#Z)_3LdVwBK=B^sdPy5n&d>izoL)y}WEP?5i~+idSr)M+4`>{%Iv5wqU~1 z=!}^3E|WYnkav;mZ^EtZI>aMr?IClcb!N%jm3EORZ;yg4WZ|60XHn z^InJ_B36)|4P69W>+EYV{|=3x7z)o?7;`O%iSO;|#E0**iK0}l-Gn)h>5`BjxUix> zM_?6x-`H9G{rBnd`%_qMgGlbZ!i3(|I@ktzIolSB($h|hM=Px?>j~{&BdYmJ$3ip3G*L@54XEFe0 z=vH(69249AG>UgVWs&3THe}`Q*m4Q)H1@=l_fMX}UwN-0_E3ELRaGunNciu#67n)pXy2k#HpU3dI&2ErkCPo4xwf z(z-t0F#pIat_)1Lo~jooEXg469OO6Ar}jPFGTQ?R)&6n>R^b|9WBZxgRPneM+rBZaB&>VABFxFR$X0OD?ZFlC5vv$PyVQ~4fHfLqly1U!M44% zqCp#$ZzaxA2s~aZ_G+6%bk;cv>h2BVWTPbVbBgTC*mFe0u2uENQ_8_t6_}Csk4sfOR z_9Hmo5+?ZPuqe}k4i&BFl21c80;{lJi|yA+`tW(xWr<}~(Z# zIW%*uKSyAdjFWRs8GE;>(Mv z1d>NKjt~0r%A8dDq4A z$W-#@m;C*Re)NhOY3qP+#}2Rs6S&W_sL6!K^u;}vh2N+PM_^U%^r@727E)a<7#tXr$Y5m@D{eNOB-FO8f}lD}$Rjv_U@?+NXD zw*_p$1RwY65WSZwpZ9~1lM0T&s_P{u#NvZ#4p#k1{Vx3l7M z!%PzG)b;<&^dAIlp`+K$g7P^Fxp_M#_}JRe`u+5Lco--?EawQU!mAAC14yc%kEI}Z zJaH|z{=fwOYO^@YZx^XQTSu8km2d=Befd}?4rZD8ueFkE_i4jTn*VkzjG1_ZVhbkl z{6V2uI^YHU&a%+Nl%3)TtnxknNz{+YA~jd#w`U^G;{CjLC$QFq}@wSOT5O+i?U|6@T6< zUW>~hH;m+Ul(6pr4K)o7=*p{861HH1UwKVvwT3Q; zi2~g&jU0hh_?>3sZcr-iK0O*nOnEM03nqen%ETQLGssISukLhirqLza=7ZR>GuJ<` z3cvX*O0QrM?Y}-6CVbbT*n$b2=rS?5dj|2%mRG|47cZe5J1&6G3oaaiRoNTM#KoV} z$(6D4N;v&m5^Y^H5B`>orr7e>_=GrQR0jFZ?f}ANv-ozuJZfSU0mqBxa%Et`BJ!*l za3X_L{gl_7p(Y#XWYt*^J|&eSunPA_cISP&o%HhWUBSILh*`oIvM`PT5wP;6x~Os zlb;6iTk_$Hsi@~R7h>M*7qnClxCPWEkU1Vkf;#*6ME36p_V4&NEaKZDk$f2~N4IHR zG8L;|&V^>1GR}gD;%`MDn&=evTcxt)yPlq9J&0o`5Zw(EnIf z8CI4|ihjz`ZC$4>lMX~I0RM}tI0CC8H|UFQnMvgR0Qt%H{z;XpKgNLh`9uL*Fp+&y zUkn|WzQIsS@Pw4rr7;^1nCr-v5V5kAvH?@zddYqcjAdOwP!qpg!d%a zf{BnCU-7`sRI)=w9(UKqU691h@o=`E8b@H&3x%Ip_mbVuTyDt-^Jg2RgJ0qxW6%|X zEtp8XsV_>uQpk{A@_C#ahcl&RQSqP|b$}zV>ezFAu|rTQDXWuzRnz;?QoT|f{NAo5 zU<)Sle^gbDk4hmAS*)T$u`H>FWOFbM_7u0^2&}sKr>e5#H=EmylFQJq{4T~=#lf?2 zIs&#}fy2(I}Hi}>u%dP0;}+d%A$APl+kv!lVI)l(-d1U5!&Lq*pEGj)kt}Mb@Uyj zJvNO5oh`K-fmL`6W^YO6b845+KtntSK&JmWao+7@Vz=L3z_WheLFYuZ%_-#BJb7$a zTzE>0OjSWUtT$i_Ch!VCp(r1Bm%fVV2)Z%O9D!AjdY%*CjZ7sUZR9e1kKCbC^-SPO zMOVNUOyCuOLh-EK73zH326}h1;0UamXMIkb{63ZJz9-jJnE5%H%<{x{TB#4%f(g6= zV3FjZN9co`zOZkV21j6(#=aBck-=%iuR{LTMt#~zZz%aeX9H!x7EJJKgSi!JX`{(# zIP$iEVgjoctCx$D64Hp{Ci%V6`P-3J4q5^siAG!>j2jgzUYn6dP9<0it>(vyarSA% z&0n7TR2Q1i9qkrDMA<-!EqwzsMW3)V^5|I?0rzG$`mE|suV}`=@W@GA8JKt!SSW^V zNh1ZzuyNvFC(t8n`(6z4++(zR#iK*{t{iY=HJx1dn`$nHz786>x0pS#29_TdpQI<}Z2 zunM<78?PP)(W#$iz>KGdD7IiiYfPzV?Vm=@zL(2*^DBay_MZtm9+hzfR^j%Sv%@6N zcinLN~Z1XkhpXLo?o0y-&h5^NvMq5;txhY38cu(RP4 zimBGmiO~G)CP!cueq-3Yy?PrRJ7+X3KJ=Pm3ns89gk?%!xR3rx8wEe_*Kq_^@o!?R zUIo1{%nvRHG*WEA1opkN{0!n*`sS_=ymEW1JW+G;RvkacQdTw zI?}{3k?b~_?X=zRV9~xLm8>r5BDmW7i8onZ-!1uFgyz+;;->gi68qmRV|s!L7`i*c z^fD#x6gKvL@ViUFdP-2W!Vy$LRM@H9|9@5+6a260QKt<5Zd<{J-5MN$Rd{EM-DYmn zL`PV3g@MtU+@2REa4oQ%xTnqZqLwM-)^_3utin5VEcZ@MBduOx3U5*kxt%yn;GGnO zBK~I!h##a4`Cj~PA6DUgLv}ZZ?>`FXJA!_e6}O{^3A``D+WcJ$FgI<(vfSEn1Xi^i z`cll@ol2}LWzY5&gWoheyDfydIRds|0{dZE|7d8WeJ3g)?MY9Lz$&{HwPMt@6k?|@ zmyxuqfvPDr)9!hF09!DDXMhSta`6`$WBZJj4?}}uA>F++v)k` zV*pz)G2-nBG46R1sWX!abMX(SlM@YEB`ao8=imWkV5lThbqr%(MYpFmZl% zskkaRm1OLY39T*pG>P_uxh%E_6IfM~T__HGkwUspmI=*H>GV{V52S^w1GZp7C$&)g zJ1vzQXekqehb7XpF||BalpkCvg?xk9gON6MO9w1yiR$lfGwEVv@}!H z>7Pn^Maaa{&@j3@c_>Wk*PbJ=YF25i_^T|1EccX&bLC^`h81H#r(6lJ1rrNOV#O}z zsl>BRo@KZm@}rh-N5bpc)*OLVr(1@I+g7EJ$LD0?LQx_0wf;q2nAc0(!Xil{lF8<$ zT?GyHOXAuklZ<~|g|UT&VvS8QdE8N+UroNhhJGy9gmIPwpSZy0wd@MykNzAwGaDn4k%z;?qsZWcW(C48L1@X`E*p zDDE(rBe04rD-{Lh6e2~*#J=_?D6n3;v6C-g3nuiv%EeX(lZnDZes{mxiPSh(3HIrE zaRgQ+3@8`R>ZXvXMlx~r`#gH%uL^Wop*E(BGObMecG!0;r{y>hvs!3LUqV4u%vgoc{#uep2x^O80qG|z) zZ2iQRgn2oVZG?5KZSss$$gje#!V}iA`7={U_#FAYIyE7VD%-F-8nU_pwqU{`DO0TI zkwQX@en z=+bV#T*gSXJlbo&BbXoV#t~SxF}F~RUz#so6stFtBvw2&}rWs8lpLm_q(_k%@5qy|l#J1a|&&0c^p<^uFa{ zt-jdDA(hOSZ7uA6r!R*1rxG89>=9n2eMnjqumo0;{uEmjNB1!dfJme%Um#_sBsjLs~I-N?cjgy~a*Q6biYIQuQ zTl#YZR%vwf6HnEplHw%!SH*~*C8e*6;JE%UI`K`gIR8f~xqj7J!1aS?oa`Gl?33g& zU?J3>2BX`6U|^HW5m<$1vTVH4y)Rj@9K2cKi4(Z{?fYDa12RZVx|ELmIGh2|QXoj3cnh zSj)F^KKpWh{v#823(`bIax6Sg?n1Ez6EhPE-R_=BArBHCvkb6t;dxhJd#aW&|B8~kL3-CZeu>}+OJ!YA7Otwnd z+Hv5Tuf!2ph5J9tnR#fQWN{)Ml8$VZumuyiKe8Q@kO1k2VLa${d%_V|h1-U$guiu^ z;=3<{7_EE>TQGq~3>Gt?(I^VB@!*(Y$JhuTEbqVc)2Y9`e}UZ1qc8^EU*-#y+Ij zf(cu;D!y|#g~WA{=L`u_YkHx7DC}8$pChoUoDnl$rjWEBav8ttjHwX>!4CU6iY=H3 zQ4SH~lv7FLfAQ3x=r%$)vN7T)U-O-c;qR7K9!018l(ro(-~7rgaYV$4hfqwW=RS zU{&~Seep+XGTC7vmofJXp*7joushWQumuzRJkjU0CH3=gg-EsT9D!9k?&*uWZzhwN z-*TJBCmfQF_nZa?7QCakYO5;Crlyd&Z>0e$Hh$uU@5v;5pIleLpN7!_GY>dlVZ{+xh3CG^ziT>+{+r?eZ`=0(Y{3Lx`>+-? zNur;Q*g#Gj7K4Rm-dKg_zATSdU@pz;WdfI6-2q!Lfmcfkg}Z7IUAW#9TEx3?1Xkg> zFT2Zh<`&xKiY{DeF95b+0n-AVjcYW*x>+1S&1Xkg>FFR9ReUMIV(16=@eF0lA z!LOrE-9AF+)@Z@|pB@~6Rd}|{A|P&Ulcu$r1!pH#abqHWEBRjAcid&^;^JWFJF%W( z3nuUz%2vYjRp`m}liP~qn{D=_a6m4P1*srV1j>l+r_!iNbBM7IaY%s zunLc3Y{%rdFCF&H3j){caU&ci@EVTo4~`j6O-sGudx{Q6U={Wzu-(4QNV@uAKiDzG znDZK70_6R^Bd`j4ci7I)($(~xxeK`5vEsZqn80f|wl^_s4ej&Y6+#>=I0CD%&xy@Tx^ANm zZ|xxD6x**wo-Iu9tGmNJcT&9!2S^>=g(I*E`_5R-v%Aewm#^9|_S8`LQeIVAd^U-^ zdfP?7U!P&et19OhClj?x@+j)LTZ3*lFo46v2e1Vb_)ElQWSttMk^^1gt1saQta@;g z<$+}Wpv$Fl8A01xQ!_mW$Y19M*n$cCC1U%|Po7ClEj-}P+-@9!RhuqWRgOEBOinG5 z%h3AzS85a67yRE@1GZp-|3)=*x+xuv_Jd;cP8@+%<<(V{r&$Dcsh?a%Yo|Qv!}w01 z=rIJE?)y|OJDx;xHgpkiO>cVPQ@LFune>a537b_1q<E@r2u<)S_i3OvMGm|U~cZS>d_;y+y`j@&*bK44KV z>w`{l1Xl57Z25SL_KGW@NBaZ<_J404QZ8=3lSI5C?F8Nze#QG79a6NO4t+Kmumuy< z%#&JMnMCf}$$p=uNGib+SK;zk-Ew*5yNZ(If z!y@Pcd&$1O(z4}L!{Qh<6{d3pR^8X~6KhS9Nd153IqlNN(GDfo=&>)sfGwDaI;$^c zMJJKvsq!2yef%Jrm2;LBu$-2dz^c!ZzWB0z61iR?6V0kdbb0Lq+Seomumuw*wpLZD zgeH-jtz}~D#x}H7-)cHMJB%Z+s$^|dW!1k#a@<5FY#L8Vd!!e1PjfI}3nuzi`&1?d zB#{@DazBrouwFWuUPF&<2;&H>3O(afdGkjivAQi24;p;ws2%at_-GW2Qu7n*_a~CG zQ@RS*kLrsbHz$(G`)vgEefr{KmM1lU%D<{)hB@`~O`*rG&j)P5#JUw#m3D=RysB~ryT8N5QznXHFH2wZvS@%J8n6WuGmrXI9?VH3X|Lqx zsPik8RD9#C6R2ekjvN;y;^KGJV%v!hjRp0_1DdFOJLEsdr!;6 z+c6zMv8j%F1v_#%o$y&p{;bRz9d+nt^otv zKZkJyR^bz4Y>!^}N;|My#s(CR;!cKP0`JPQIQ^;y>N$Qk4ZJ^rBd`jeV`DeV>D1A= z@iS@nE$r4Cbixf2_)En04N7Y1r{#Whd0`MoVAZ|h<)YThL=urN?|BV8a)J7sT0oa< z4F+t%1pX4Sz3pt4a{0y#sy<~pM_`o$`>H*-l}Lj8<*%BZ`)=yLA%hNOr+Bah6ZlJ{ zP}F|kL=R6(q%VzTaRgTFEQ%E$o?_3@PyVW1_0Ognw~FW+=UIR)n84o^cE0v?BK*$~B5gdV4c+_U|t0yKj z`)fIk={pCo1rzv7#763EYV`QZEi_JLE=OP$9<^CSitYtz_S&P=;_)277EIugk3Glt zjndOIyJ+D4xg3F2c+_S-nF1r}$eAOw!6Xu}1rz+3sD5mX_%L<{C6DKE1Xkg3o~=2z z6pN9@O7zjwIB2)lr_%Ch0$HH25rQGtP4#dBnf0=ZuxwwhTgbQsa_ECR?)v#&rt>m> zy1(c;o6AjwvrZjb{=dvkZ&>Cgc53U@N%~=cmGtR#IA9AVCa~S`rB4$`-%y!&rgn@* z)!4ds*N)@}tisu$SYDjSGJ4_u5UGFaTrO`ECYrKh#ppW;L>wc(?GEu<=%JSz#7|jK z9D!9ha}$eo&d#NUBiBn)zwsHGF!A`0uh^j~fsBcfXML}hrchr)2g&ty442aht8nfm z_N^Til%BusErl;w!Vy@7Gaj*(aE&E> zGXA7=C5g{$go)~?s>;I^3B=h?E@PH|2m04}vJ~1Oj?0CFRXAr6+eJQiRT}PjMfx(E z&(MSk{Jya#pSV>rC=8csX*`z&3afAiA{HmJ$4ojnYnNp4J|3_I6a2fY`MX#Q)-;vW zPA}sKtim~qn4jUP4!n-tAiXUb2KekWK2weJ(XlfP+3GO%%W)|sXcU(jk0a3Ob++=d zZwpan`I415mLu?)YMg0~%|*3az_@d-r4C&tav9|?fxmVvI-zGHjd405wVyMYBe06k z_V%#POM0Wf8rA>C=WfFU{@SrvPKQVIX!29(qirac?G3ANpJ!`>HJ2!@w4i4y!?+xD zn805B!TO z9D!B1&$BZoQ91P9hT&8vU@l+_Ciw5*)1S$-O}8#|DLegw39Q0>p55)VZz`SI%9{>2 zya2ET6L=-V_6>RurS}&b($ez_IRdM2pJy2zK3Pzz=|OdT76G>z6PbTMEHCh$sz?e=ZiB28?trwvg{IRdM2pJykk?wU&E zf*;*dwuJktVS-=d%sX8yURLTsP1R#L0;}*hk==4^+h5$9J_8=Muc6pSvgcocTW*IG zQghH+;Qb{TZ~BSD8m7VWd+#Z>VB*b*0=K%xWOA@d_Q@oztQI?xDUdMmH%DL<_8_sF z%zQ_RDeOk`qO-iG2op++3*5%mvKX%yav3w9J`=~S9Rrac)i~c0R$)&V+gBSCBA(eY z0`?8zJzkiY_Bh`yqac~28OU=6-x1$L#mvF*w9t(6kzp0~=&>03r_th&>7LMbUl-1E zhl!TS`EIV`m{-kRE@Q(`Wyxl6Pe{vm<_N69o=JsbU15?~s@(&YJnF@HATjaPDc^0B zSu$xiK`x`Rx}8*GVhI(4266;eVSg#xCF`3diY!~N%QGL&lZuHoC-U6l4<(U)DRLQK ziZaDx#aiHcgWbP`e6LtFYge9I#nvR!BTFWP^S7k@jd3s;4of&n2ggj{^FJ&%)th?h zi+?Pnd$*w2f(abe!)|vBRM04=rQmF!%Mnav5R2Xm=WBG5lrwALgkY* zX%CfXXd0ft5m<#!k0=y|TaBsb`bb!0SW2-46MTHT@kx97-Ea^Y8%qn#{5z@zdi z#THCFVcAfhR;7|{+vPIyvP0?0l3;k}dxayg3ZEWfSv<}}Q`h*(;2QCWVhbirgGxo+ zZ>cO_pFBfu&QGKzd!!5`+PKH&o1js zL@6Wnx%VTXB#|wl$WnGuly*x}vM*&9LnBLL8B@CVeHeoo41=+M&B(qD#=bVcbNT1> z{{7dZ^LpO%Uhe1K_kAzt+-~}hKnoJ}8|~IAG~)9(9}ORi4y+PgTlJ?+ZQe)(s_^6+ z--)fah`nBZw7t4nIz@-XK~bc6{Wec2sBV0pms_=0yxynKwVO300#$hC&twXza8R^q z+<~<9jis}FNNhhFvE3yCRk%Bzzj5wf5~H@>6q{H2OJ_!r$h}#lxgVLU1V1x; zoILtJk$?J-cyK33B2b0v3A~H7`Jck?wl1#zGC*Ewfa|vK->n_sjD^R84IkT1ofRjl z=8Kg{ArgTqTy@}#o;wc7G%SxtvY1gdb=f#-dS59$d`%%pM@8nhsR?_iUu zs9CoDIIb++nL1P=P=#~k{I&h4hQ2S^LOmMl21drd2x%rM(}x@`t-Rc=c6y=@~o6(_b_n;<%b=_u5upqylY!R3lg|PjAI+d4iztZ zw53kGmkbG1;T|TQVL32Eye;KiCd;}=Cq|IK^9}qZ{AP*BimgUHZN3tLDm*>H`xAfN zAVQyi5_59<5L%GHClT)!*|1AAzW1-#>fKi&P=%*Qj5uCJqV4wU;*Z|_2`xzA6P2F~ zmkx_Vr6uBfpS}`-Dm-t(b26_^irp>vJ>}My(1HZMOE`Mc#9u|tRnNrwOn-?$74EF! zHQ~J{#el|dM3U}HXh8zsa2y#g_GeMHurhTF^_B=!$vd`s>^dsyhg6|Cc`Bg=34BwV zOo~|({`>1vz4T5JfhycH!)LHObTQyoBdY$`mC%9&jyO0+Zi9V7cl?HKR&tUERLOgB zuFlvic6D>5;2#~O6K+W0$cax6to>e8+UZHxmei97RN-ki9*dsaBw}0jAXm+f(1HYx z0Qq!(#7YtC){CBOs4Nkv!qaZ-qg$4k+p`}{v@;P}kid~Fuef(e6D_^_(Xn@BBmz}< z+KunT-{VBhyMyV-rGEulkiZc+pU!+UL3qp>Ow%X5mIzegX*b?A`OQ$#e@_@~n0HH{ z1quAJ;0OXU`Uua`P^$CnzC@r3_b2n$UA9e}`DqmG8FxY2xr_vUA@RWSp}R=<_}JWQs-Pqjpe!&u5bc0wXhg*&r(FK5n6eeCwh zly_mbv}YR$Jmta9-QlC|gsKOoQ{KoOk)3ZIIsYBZ}(oS+D@RSGdXneX# z-xfWU*5BJI5vam_@4PB=!B>B6nL$PE7DyuiB=D36Kik)|(i>KYp^}lSB?47A8ZepS ze^{s0KNL%c7o|!&gpiQWe}r{xsZEaMtm!^WB?48rBZ=3xvrg;1J|$Aos7DG$Wx~i$ z7)goOYnSKi?;{eZ{ZMBWEl6MtDU<2H>dWu5vaZV3 z+n|3P#rYADRC&coDSI~N_r`YPQ;i*Kh=Cg>QnK|&DeE*6-@fRneOEAB$vb0YyzQYj z6VH;TP`Pcn5`ijgH=dc;)kt_QjHZh@^HsDU(erM+HpVnh+3#S~h)MAa{yy+qFT1oF5t(24}ACy2AT1fs`{z$M>u5n@&F;p!-|US_=I2NunGO5UpxSjP-L2DZOl#7(SpSA*NybHFE=QTWVBV!-hJq|nA+rAGDRX#g)Pl% zsd4Xw-f%d5P{Nf-Hy&uKYb;XE-)W*YcQ4gC1uRtti{|QtMxV5IAD1W#&lxcROFml2 zo3pDV-gLC01qnx6WxaFY3MJ{fakp2Kb|U0 zX=Jo7RkMAiqXmgO$L#gAtZXHyzESfF3tN$0=dN_`ab<}>)w8Ph`rvul%I)&T3f8Ob z?vxejPGc{u)X{>3>pTa2a;3FO*lnZmez_8XDlDPN^zxJ&y}Rf} zSArkuXhEXJ(b{_JTC0^gQN})*uP=0__6MA4>ZdyrfvUVv2R*uEjna6PQL66?>(c4% zuJl9TSt(yCWwcPjsWbMT-SmkiZ;Fyw2%cm5%!LqLv>LBmz~ZubcGK z-IgdnI2&!1v(}z|OAnw~L;4G}Ac480c&}O|JG!$Zh|UJNNd&5n#+vlfdrK7ik;bZw zo?3&nh(OAkQcs`-3Cwn7GCi?Xr8imqXhxlPIufYrZD-Pl^jNCY$S_v>{>XHopPsa# zfT<+{bG>5rTg=+T*-t}i(ab(>bgAD3ffgjNXL)z@wJMaFq0;_>UnBxmn6-(2QJpMQ z-`1U0rtT7GK>~Z0XKNiQ&{58x&?S#=}=RhZ|A<7Koi zN40N+&{e-jI$DsB`#jn1jo5rUi~_@sNCc`d^ASfRZTVDGIS@|69?q9?A|YXpc&u%? zwn(Wu(Rj9>etb@BZ8eU(PCU}^TBs^lcuAX)o2BH(8qf9~4JL|xd^8OO-o@IA z1<6WK^P19#-0s72ZL`l@#bHN1Cg@YJnEP}JEo!kyMGJlp;OLyslJ%M*@|H!>>P0CM zfvP?^`I=YaJZ0zyWAwVsdAhh4HjPR~3{%m91dh%*8oMP+wD~@Y{+!)cB2YDF)*-F* z@_eOAtnoEbb>~viYwuL5F~mtl3lj3UJ=JcTsPVta)G)e*q@wh;_8F3 zRD5T)G-g0T-TX*<_v<2MW{%P4+gCmob$Ax%_G4FxKo!1G`4`pvgBVd~I4xSd^B`J~ z@N)f6`!r^$vVWU#C)#=2(e}3k`9!Y0^maxSzIXY}*{>^gXx@Tu-My>h`>u&_(8sk{ ztBjxFq{<_J+#GMB9WALO{iu!>Bye=b-;jEC_osOdRTZ=#fum(!G0Cb%C$jrf zW>`;&KoyP#`5fd=94YHgFfILOpMn-7s;+;pEjqne+5XOm7ascQwYdEujDESIO9ZOq zJF(vA2cq@(aQe-zf{GR-emQba(>UW?qKokxZ0d4OOg$PwH#XQw1gh|N!}o6Xaj|P@ zB&CpxiWVe%?w;2=oZ|dgX~wgpmDnrp_M1SiV>~4SRrvcinH~?>A!=M5PmT+QNxyR> z>Ng|JmGhXi{^YN$D z`RPP0_A%T(TNKtBN0Y)=NCc`D_siF+CCpaR<{O0XAIr4AY@?}V{yp{HuG>ZDvnDF% z|E{JUn|{Q@?{b_HSyEdy=W{&$->4Ws!ySOQ?(0b1l*$r;Dmiz}$KzEf z=Y%sA4*np}f&^w^4V41@$`#pLnsywjrI;xOvodYMF^O3sNC zvGb&eIy{nkT#J!193g?(J^2?k{%2vwv$eZw`AY<c(1HYJ zDdqdhi9}rb1S*;GLdx@lD$L-+^CjV@MEmMWE9n(5xq|m_m;R;%iz!-b{b+_WV7FCc;3q6iW1gbDQhRL+xPdEL) z!6~$2aD;*uBrqx;uOct)t50o`LQY9(5`ikr^1-t>i?a0pg{IKnQ8TS*K>~LIb99*9 z>-B*gkL;_WEfRq$%vQp!d-kOM2WK*0`eP#q!KvFzX6u zWZP0z9BYzDTl$}u^86ry`2u)%!i0t*esKcL>~TpVP=#57jF=oYQ6)Hz{v6R*palsz zE6MIPRuT5sOlsBe9~}u)$f+p)9b?7K$T<3E#Q+TnRAGiQo)`Ufp1ARB2Aw?@t)T@8%=OH3udNfr?K`nld%Pm$ zK0_6*n3+tw(&md=$ulVFCub=m8xr!fmTEGiGOQGQJY5VBm!0V<<0rF`yUlMTTG-C6^>fbf&|Xbm`sBgofE_T z$5HUo?Gk}1{PO0=s_UMJl_4X^;X*kbElA+3k;(Lf_E9*-h0(pr7KuO=eyekCC(cJd z=-UAl&~3Ml79?=SlXqrj)}pQ9eW)N}r$nGio&)g6ZB92ocvIoRiUKW2Y_inQpB-GK zJa92)ojbZaQKxZM8un9Ji9i+3z4QLvpbpfarW<{g)?AzD^tfAKBC^b z(V*R~^!!v~i9pqd+O_n5?q@5`rN%t9!D|$lj^S^-MZQ=f}GdT9BBOUsZ3z^rrV6nb_p%M3q`ul>KFF5`n7e ze^=Fav5)LK2H}}{ZDvuakI&T7iXT6!J!(V~AR zCUOsVq`bXm;e%Slh-ze{&1>a8-)`Y+s1O*g9S!@)6- zMpd^ccbC*9v><`?;|SwUffSXHVQsNbCQ!9J%}GDSJ_fH-*vFkPKWe-n!}?c`CWICw z{z5G}D3*H@$$b747D&Ha_g8Pv&|oY3}|1>hWgXK=RpYR^FVmlj?zl zR=>SIgXzMqHZE1Gl75uD&a8-=_7Z_AY(tYNwUqZ{WSf=8zg`krGn<~yrP`6(Lp?Lg zribu#A7u02KdSmr{(EcF9_-`xx(FIHA;bEh>0dGds!P|r^ksad;O*U*aPb{Y_cxf8 zCJy%mTJXAFH#_U2*oWt7A0}2#9!UenWmvBscp?#~Dmd9$U(G%ioHK}ii$>71HD)E< z_DY}yiLb|X(j(c&j`dxcSn3f*CD9qyTXv-qfhz1L-a{WhjE4QstPD6)M(RN%4!rKD zk7pm1D;qvCEJLaMHM8=-qr60*3VW0DW`vKWmA{*nZjCPr>;vqZ%r#&7CTyG0AI+AJ zC!ZS`*5d!25@%CLTP;hev4EhNe<^V1{Q_Yb`T*hf;eX;fokhBa>@XTksiRaja+S7eK$ z8h6dgyM3`DszqX3ndrT5IvpOLVSPAzu|%LsE>(D~7@ELs^;^tpsdbSE-sh+HWFOXf zM$KKzM3b+{qSSHRBoU~>zTw{o$2(robpx%Xj6pamHA7dWOqzz;F zz8VlJ(1OJ6>w$U@x7E|L{g~)-JD#4d;P?3kKZ!uqA9ecZD*L$lyFt9Wn?O&8XINu) zb`)qq;$?7OJ%D|9gbZNf)vQGNC&#R$m2W8#sQT|wU)_s+Gz=ZcgxB~aIuVv(O>Jf` z(1JwK&Az%n`v|lQVxr0JB&xW~tc0|!AQ7m#-yrC-kLG5BxH=-4qWJf*ZSgf7El9k1 z5~O$LQoSl2%)}N`3Z<)=)|}inh%cTkp3SlBYAcdZOFe`r_ohK2f+Ebz5 zXCDju8id2a6f*Ih7}3c^M+*`=Klamo*hi<;!F zv5(3-jZ&GerSN_Rvr;8K`XCahl1sJ2HIbVBXI2KKwpDk$3jBP>S;8aK);Id-3SW22 z#4+luDPQiZT~|i4k8(MQ^!rEt4gTFsvLG=!w6AVuy1_$(IPH@}Z~5Lm*Q=I9plaHy zFZWgQ*Q1zNn3+V!`FGwY*sP)ji3bnA+`Hd=CN8Z{rZL=u?ibD~NT3Q^o!4>hCsQHc ziJ@A7)E`J}5ka~q*Ta-Pf=gA) zr-28zG`70Q6tsY|Q}CEUUmhe`ka+r{mp+v5#ILf(aj6mlXHutJvvR7sd@WSfe%$Nx zQ+w6|g9tyv>k?5J*1NrbR%60#`aHgt-->DKi}qjMWP7$vQI~Y=rcdYpch8%`#EU;C zQ!?Kr4d?$PS&%Rv|MFHF-^(ECZH%JR-kH`vm+qDbRLwv1<^8zw?nEYP)}2PzjM3}z zttwiODA@Mp+1~f1K@8j!P4~HVt5#Sq5vW@I(oY}5^{D)VK~QcqOBeZfp74Dwi9i*$ z2+w$p4x(G@%u0O4no?UK(YBAX9?L#*bK==Y&9MXMhQ*?s-CR{7P=)PgGPQoznbJZt zt*`I5w>^)jt=Hn&fv;bss%>xA(bw~JyA-FY*diQr;DkcKbu7xMm2IT9LSoal#`+Sb z16@+MR5x;c$d|us<8QZ+2vlLa@vrt{bF$6IwARb$W;+=6Nekyv{W@xnIw`fHUc}e+ z&YG$2Hef8(NUat5r?k!Suw>ME5B!G?wQwZbfyL2vlK< z@Od?@19i?bD-Wx8lG;ildeqi8v5(VlQn^&cCpyxtDi&q3*Zm&Hs{w@wRK#>55LY;j}LvQUE=F*aG9(6&wZc|!aPR*~JI+2Xjx>B+ zYtV>H^)1T5r#&SCRoFK?vRwaK+=$P#KIlEd*0Y3YtmF~ z5uPJEZK8}8JYQlTDzz07IZv)?x0!CoZOHo>{3?@wLyIykW3WV^3fqlOJ8{O|Pnnt4 zUnWnmMS5my)h4DWbxP)`$!9lcbpunC<-6vo^}UO<3tZYgrD^P=&7_N>yR${v7dY02 z79_H~iZm0`|9vuuf*rR+-JA^TGw(4Hfhuef-kIrkS3D^&D}SVpmf8x5mj96UfondC z+mL7OTpx+Y{QDT?IZ7f>h3&@C5D)bhFI!ub@Z5Nt~9r!x`bGeg~Sc_Y^@RdXmev8mug9wVv*CtqO|yWvP7T??=jAK@27}i?JY_{RD#rl z*f-T3DrjTa$BE%a58nQ&gV6O1tB-x64J}Bl@T{P1;I>*d!XQ44t|z)2HY*k1$ONiX z>&@ax>|@15gSa=Lx_DodVVw|`WJ3!Q?|p6-7qE}mNd_@z(tF+4#iFcxA`_@`_1sn* zZ`32jAf~-KsbAd4zuF&?ZD>JacV1}m4fYYU%pelJU9X!vSQNKBWN@Sd<=DWdc=o`>!ut&ptf%8^pGnYqe*u&5He*6slIZ*kc1*a-X(VS07#M zVb9k+z%fP34(VAu->8S>YbLhmwAA<4;dd>65u*hOr(Oe!Z*p7dE(Y-|DoJn0vr+E6 zB8~*AnpPTEoX$R~+8IQ8`W*eu5wnujKZVeOL_gQ?&#k-lD}(4&kgwO}ny-DGOlU#k zkQ3)6G-^KBAf~>)sDB)lY0b_`CbS^ozV3SQ9e#x2&kbW4LKQCrJdV_R;m? zDeNOH(jZ*+Ru(G`nHBSrBti=k!=K;(e7EaS1`%_`UN{`gux=lfL})?c+`Y2eCN5Q( zr3Nv2i=&9(=kBKO5+wpvx2HI0pIBV;EvqUyslPja`8&O$ zlREq2c+HP}{PsCN=kPl7#b92+da-2&p#_O;2mLiazS5OBhK~bzGla;>v>u!oClRQ^ z67s3vtzlv#x7DknnS>T3ItRFD{n^LZdWMgYr9tABW>);i#Y+UL0`p}EB)UuE5BaAaY_Zno2mxFjry(oszf<)VEvotquD@rto$u~BOo3$-U+pK94 zfvQ=*Ez_E@k5it;s^zW|JB7A0!`k)VC_)PoRhq5R?Ab@me1mYa`%yHxV^+KZr$_{< z%rk^n@$qgqF zT9Ckq#3qyT(gR|{ZL<wcW#O zB%vy4z)|fjUpJz5J5?t9R^AiQ{M_x=y=P!x({JbjtAQPypLcradEF*hl)0cC<4$!@BzHK#4#V-ftXb^KC_HP{X3o&=Bdq kLSpi^YuX+5@qV|F$Nm1v@)TLkqKw-!L?Tdy_p!R diff --git a/data/kuka_iiwa/meshes/link_6.stl b/data/kuka_iiwa/meshes/link_6.stl index 10b558dc5e639f87c94c6a7627ac3b11ca3d3194..7fb9fcad205c9e71ab48a3016e4fc6cec7891f38 100644 GIT binary patch literal 57934 zcmb5XcT^Qg^FLfh444%YD2igh03wp6r>_YG6i_guVpded3@SKA%sEHQam`AanZD+% zm~~whbB^m`Tz%{E>~FW)?_ck8&Yp*3)n}?hRdscDRo~`uu|tN9=+oP|@30|*otq5m z6VtoTu(}QEd3!t896qwAvwJQ0|MkBqc>yw(98uQ&?!=c43lzx@D;U-nfy`3ag_S!! z)qnzy833o#wU40&G&7;vm3<}d*CtR#l-b3d zc>8KWVod8KL%UW(*Jgappoj?TBm)+#(Jg<)>Hzf*cT`R|IdM0KAVImp?#CNihM|LH zo-QNec6U;C`Z)4ICxZmc9ce(rS2{e~uTw;FyC?%DIv5t`$0*}P;s#~GK1W_QDo9WY zMSxv71M-C$TB4%?5V2^vVn5uGyDpRwl*_W9l>uw&7@AuiL^QcrUGWI5z@PC}LZZ;` zK5#ZHBGmX?!wC^ZJ96dufU>+--w*+mLJ-#VxAkS-y^M1EYa^n6(-TUKV-v6B+*dM7_B5=IYav2ZJ*Io~apXG|;d~GZMI^7R!1_Cc8>g05 zMntK^q54m^ihSL|V4>CQz~FHeBWp;ut_|^EaIL9f=~dd05$*U6{k4}9pYS7Oi4+~qAI2!$eEL{DMK?WgJ5ln_L;u8^i* z?&8GX+z1quLJ^r$Coxb`{b9{2e}FlM41G*zC;s#o1m*g$C5dSzzGOh96tpnsweA_e z*RRZXjcX~i>!TPvn61Epz6wQHocl5GxUIm=Jqke5o;~{hqLujF)`5ajC_-!8jKN7) zrUm3@0BN~)>jz3!;$?#a1?75IrwohQ9>OxSkW)e&%HFJ}HLk>O)IcpE6pFA6cV?C^ zAq=j%q71(;JCvl5O8lUs>=|G@>d+HErpvsAsgbRYmtNCY)yZFls#9@D%yh@%1iuv z+QJOo`k;n>>wkaaSe37SItO8Mjg&$WP~7VG2ocsRXK~KE$81fp$vAhl^C3!^zNN_j zYvC_4ye|DbXhU4sH_402kP!TH#y@>R8R{;(oSwUG+bAKh=l^nL&0eV6dhT3sE+Q%| z$?I*CVe5zOUu+cQP^i3l*n8WEz{47dm^ybtjtm=uQYb=}(fpQUj*PsPE7E*Ob3jHN zpwYHVUba?kTo>y_=Yt}g_gNKNtCGKz!B#!4wKiw0Hkjk38Khj;znnR@wGP1Pgx#T^ zKgaWu!;%it?@}$Xjl@4=r2w>@sprgKV%(BL6hXO`EzD3JW2jrp<3;C#j`XlE=W^x=bvGU0Y~ueA2g@%!NGUbo^Ng^Ng9`qw)WyG1XBC^4y5ipe-o+apO4>cf z))xsuxoj3zZbZOF+m`@>RuyVAU}v-cBSR~B-`{8RaiyM(>(5xldE92Db`Iig9k+wb zX{T-81^rgb38xgecqGHdMO$mrKY&M@fAjpcRTN?SKFZPmCnMm}h(;4ux%{72rP?gC zoHgCnD%+^WqIdWoBIaIdO3_D0b9zoG6oIYPuVyT-{=c5vT2()+c}_oUBa3ZTYTDX9 z;gpX3@V9-}ecWcmhRe5yq*ZH7xK)(dgdBjq$;1Xy4Pd_9sNrr87i|#&{BZH1R9bGzZ0CPiMAJn|- zG_tjdQYa#d%oBi}!!o_xIR_DWDTG7q(*A*4rn2u7A{jX5(m(!~!fGz-%z6yFmTp&f z60u?w%UjFt-@71-ExSu=(W8i$*>Mpb?1}Cbj$jQhGuTl zwE+{*!;NWlTi^Z0Nz90pWk}z3h|u-CLku5`y8sfO` zyZZITP9kKT+;iGnDZYkIO|$eT>zqX3(m+lr6p>|MJpbvX4o(MftUSH*7^Av6in~cc z9DE-Z z(U$f9_zQx32_yZ@@AMK!9K|II%AndnzAMRtF|F?EBa)rOU(4iv(6(ErKx#QsN!AQXy_V>n;4iqSQ`qNr0PSVBl# z(&)ByEN$fPP*GfIjtD}b2s%#ym+zj_(^q4w)&_EG;BW&XlNC5LLGB0XAHbL4pY`b- zoy3^avL;frW`}#upiF-V+l_Jix2ADo`JKx8pq26F<3bCr82!}f0gP1o6rBX=e#*YC9xltK|SasrqJ1g#$5n>O%HWLtD#E$ zUGWlva-nPz>A&oesGhLI>ftyqk_^ISiSyJiW2=heyr37IS&Tam4pGkFyif}Lt{jm) zDel0BC57m}aQicyKYCnQsWZEn zgrHouDD$07#zR~5>N+i+7yrAwaeH(RlTs)GcS-t78vRM6hAwSc84FS+}6^oKh%)?nME{ zt?FSmh#ji5+!Ze&D3>PfSf2JsG=2PY>_b9OF4Sq|AN#;owM0KvVQh%<>U}t;6pBDS zCVMrs5AlzENC?V>Bdz>nA1EVO4HxgL#VYsb7Uz^g5p-_|5cX%dh`e4|`8cbXj3E0= z4gFM(w&(1GTjn1lmd~$bxOVQSQVRVp_4xpKh9!udb1Jbe)4GLduPKkI**~%DvR+|_tr7O^0k|)cr7uL7fvvscLfF3 zU(l1A;|h08S71(-4*T%$d36-{Q5q2koAeWE`K{)nmb1-mjanIw0U`R$C2_`wIA(lv zOVtl=h%+)h8XKS<)U^h91`D+ojSw5X3YirrO*OY3Yhxr=Z<(Qwh%+c!v%~Y6VM({OZglIu@w!ibv=Xo<4M=}+=g=p2V?$j^d(L3d=wnRT8Y1Z z9AbNBloOQ8`r6lcZ}T|yFX=MkkxP_lQKle!aV*=UToQUvbE9RxDGU;CnYT{4C>r%@(Ks>v z*c4XyW;yfwx-Nz_J)S|_qqN-LBaBbBemFU2&@Ta;i5Mq5&(C0w>sOLwPz03+5Z5PB zEdIKmjp;R;Q5lvIZ4B`n#tAK56p982^&Kh_&OTx_SFTgFB#UA5GO*{6LJ`j1!A9~y zoTmY{^Y(msI*X|n@3Gx157!3OH5P0`M7?Z;y22XW*q3!BIkNbXN~<2vcKAjW&Q? zQy})3KaKRHFTv~S<3x1CD>gm+jeO@pVnaP(l414lsz7E#T-B<1j1}AZl{PAZ9~M>(&Npr>;zMybV@X!&@dgAJ<;ht0btgKP~oxUmHBaX ziV4JLP+ubL6X2asP4P$1(qc|}wmDC)ZCFZ!VeyJFI`$}QXmilpbRA?!yFR#`;4eO` zs3ayYpJ!68sTJ!OE^j{Q&(_8nwT)s%_>T(48T2c-;v8xt!hhKD#+|#G)4Y6)&3Df# z#izv?)<4~iEY~lJ);rRO+3aeR`vUA}vJG+jMR)Px^$GP|_eCZ=h%l_z=P58Z(4c6$ zCoPPK8dH={i)@G!ZbOBSZ%1{@peZJ$m|B>T)#QQypb5w|zO`YkKTOg52O#2#ORyN0 zR+QVFi#N5gEevb+Nd>}!rB+dS0JFb$6JZxGs&lu_mJkvbX)W&0U51Glx2mg+^3O9R z>4b~67Pb8t7r$+B;kRCUm~?!iu2e9hW|n4_<-L9xtDDzHh}c?9%;1r|BrTzO1w>;o zPF$WK^2G-mtgEbvQGZM^pusvnXuL|7(2(cL7?E_Rt}&-!bCXgi!dh^m0fW0_z}5Tc zMT?&uDL!nwX3RY^Swcu$QmcNt4iyuv#nhBit4wM2YBJV<;)DEQUm=68b^t%jQKJ8+ zNi1Kt$V^P;x2DRGno=HY*vwZ#q z);sDlLTwr=Qv38(o$RNYpFK3gI(~%$xs#>US?-5t{js9zhzjbZBiY8f2NR7`PbVvI zH9)6mSq8ivCvGjVQ^&SiFCi!wZ6Tf-JRL8FMtAUczIa#K{ZcO4KY$fy#)xV6%Bx>} z3&{N-5eJnAkUX-zaB?`MIt3k-tX7IkF19zo?ur6~T+jv$jD0#g-B!yqerE(CmT@ zSnk50rJc+r^{@MzP9p2%Z|agi&Y6~a9SzvpfWeDncz*of_(njZt>lBDZ;@eQV`dSSBsNJ1iK}Nj10GHB)2R9q_jN|{$}hY5s25i~}{`|~DoV$PRdYM#^Q7+ufbt&cULjFJpyl}?ve=Yj3x z#H50rYL~fnqzHg=(P#i*WM)4RQ(}iY^6?aD2I;J29gH+A`vMtsY==Jamd{{uzTsMR zPrHsLrBDR5d4SLF;>6=z(Q0K)Wz;j!R?$8I9Q`p$yy!Dk4Olx!rwGb*EOmh4d;qO$ z`(unt>Q+}pM8asb_hF!bL4*zgu1z2YzEMY8qhFAVHrl!$3 zK+kU@g>k}HUD2hzq*pYWlw;A6YnqB#VIgX>dyZU+amlGFJ^jSp#K0iY-`Q2|Ua72% zAZMgfd=2h#Erk7Fd)bWVm1G2o!s!kG_qD6Lisbyh>T$cbQlu|M_tHt~A3w&30lNd# zcenFNV@1b@+9vKfyNnTK9|x;#?`e|NQUujwfRfweM8eEqb=RPLCZ$k>yz`o{DNY=G zFhp%$!Ofru%0;yjGgAH@DynVtRc}9-VNwc3$hsT5x|?`=y|K#1KR31c!G^Y|2ZLM( zbh=BWdW`GfN=1yYYpE_ysV>=|gdp|^@YW?(Y{~k_I#1fH(m9}-DC?C!PY|`jO;#)9 zDW3TLxBH<8s?z`$r^JeL-TYOp!6M0D(VojY;kSijgnR$WYT)+m5`uEk5y7**d68n! z#ENS6-=Czhk`Uws0i*D$0m3_=l$vtaNjf#4XAabN0hF~LDJq9lP@8=jr_wzj9XC26 zcy|{)O7yGBRBNSRl~U;V$hv#z#voz8b+MZ7!)U4Jw71ea4+p+Sh{&p|RoM7S@^BO( zYss>SzM}45l|)Os<$@xUg&n)@;irfj({U^Zp%{@f9>Ick`!RzE*D!Gr+!Uh}G-UoG< zR2(CK8qia8TCv~k`hG1g`u|brURK@-cP|_*jtp@zEAKL;^DF7hY8*xvv3oM$lf>^Y^qDCFMTUulGRd6rK5nc=*&QIbiqB-^Zs3vQYeC+AOVc_8Z7D#nru!xKGT$Jjr3L; z1#r*Cle-<8&9H74Bs-^ER5n26%y!~M9S~#Q^q2ZUx#*cS-jeO?Ag<;5X>JK>D=XT+28um?8%_JFgQc@@DuZedK!GKpf-OFx4!QYI_S7`WB>OhZ@%lba_#COA-tTin zp|LuRkm=4FZ;?AEh=pUHG5Zet8AVVodY6tT+vlgNrKXJ%S=-wx$#^GpDfNOr7f;Wm zd>@hr1mM*xQGNC2Xt8EpTb&}LTpYZ|an4HBC+D2QmHknM2L^}?*;lUNUP>%F0jA}AN;d)e~g(wFAQ*uQu@-*vjXF}3C- zol+=*=Eea`iW|=htQp5Fr57m_LAjn_UaE#Usta>utT;4^mu!}(mKb@;pcIPuCC4ke z9iJ3o&s#s7&L~3S!h1C<&dHn{8G2vF8{?b|#`yq3kq}ar-t&>g_${21R`z9cZleGF z7U9CVP%vXw`Ja~DkG`kgtKOGS%~#ftCjDxV)^M1z1(-Xc$qef&$I2($tnby}H{gLsFxV}<%Lezk9oef&$I z2swA~d}g@F#yN>7o?{>XA}AN;f!H#OmH*jb-YWe>M8(@`%b3~*rBDRTjRQz+9xuAH z9_sYlLm5R-F5BHbW>ESq&gsXY#p6ZkligW@+a#S*D1v5CVpeh7coDI3oDo-UkwOua z%XW8<_K`6^N5iDuamrwmG=2%1d^@KYa2GofBFZltK}<>{9eC|Kvcv9Z^ioyc8~qK-ruO>wmvRxNt6X+c>Vt zk#RKoo_W7|Uoo&?j(z+`AqXkw5}G#dXm))OF9re2KnkAdK^>^T+uZjN zf1KZCu0QF>&ekbnwAzR(&T9vj)fR7jR}3+Vuf3(zs_JFT$hrB+SG^+d+`O^))L1hq zg(9-QAVQYW7WB9FVXAGRm0MCi88N73qwngzbhkleaKMnq(zEhDf?s@ z1brf6kTN4Q$gssh7=noU{W=?yN{ttL z)Fgu}w}iB9RDlVyq0RrF#C$p zaev4N!bL3&Z}lg{nZZT+31_E6@_Y~kog07)9>QF`PM-dm6`z_(X||j5JoZwtj2AUEnTq z%`YOPaVK1oSAq(Mw=0z#s|&mNO{IDRsghtvcctc$No-HY_6*=oKSy?Jwv!k=J&;>s zCNXVLvaThL&@b*uVp(cc9ol@%p!IkF`!CmJP0{m2eQGDk0Q%is4VC1Fli9rP9Z|-n z*dkxC*k0yFzbEh3e1CNPP?jHC?M%JHsfSH|zknM0LCS<#ZynW8f&`^3M!im?Ul zUBuHD%{cXHl#A*ZfLZ*ta@)mOI4y0#DTN}aJgjibeyvPg?j&9=59GAIl8zhgAKo;S z?#3>huPXj7*__kw!Zj~uiL)4%DkTm2CERVhy;gSYa1WYSbGpt4-usv7iA?YRT4w1{?d<) zBN+60r)vo*I_(pH&*EGxqOB^e0X!joI79vCLc`^N~lIy3V7*!NykZ(ycK7}!Db!i6A-(WV?>gvxG z-q}f{oU_#e{70b(c|PX!Ez35fJBkAyD1#sn=M}ac7CT1%wQXR#{fFMps zk;;%p9l~DcVymY)ipYNQd{6`(Lx3$A=}Obzur>p0OlV8s&!G$sY*AoJk|MXNeVZbp zXY+5YkV`n1ve;VZHs*bt%V06qOI%CS?J&E|>SDq9nB$&DxSd|XDt_(EB?>`kJ%7`q zX3u9Z81oRIhuu1JaQiQ877UdT5?AM%dQp^-S*Z;orbmo1i|sAXJ{FGSTDM&pR_7%w zYiI`sgiAuh%G7m6_Rw;w*?ydi7<0<+0p<~EKO!VFz@B-(sXdl_WCtF_a42$8X}2A7 z2bsdOJ|0T))=g|{%PxVQN`M zzl0S$akcq}+L$Bgp-Kq&qY~2`XE5kmMn=QQ@6~t{*C4faMJC%Iu@#C2sN(jG4Y1E= z41SZqf%KM+o75-xUU8=~y1AeFaK~6qDHI{qn8CjLfkuM+Q})_EQS#Ihg4UHm`IsAK z*`2x6!0bL;nkiCOB-IiH@Q7X<1wJi)^kA{LP00rI0&e z`QCZ#nA}|RZKRG(=zvv1|M@=2?#RsIE%Jlu|- z7!tLRRqNSU_C9n5>C8gNr_!SASQqtHwN~<+)64;?V_=@$kZP-`F6GuB#dgZ^Z|%ZV zi+&J2L#z>MfOcH>vw4XWJUM{#JxiuyWdm1sKlIXQ?Lw1F>5q|X^H)4uplAr${@mLp z!_~gUK}7sl4MhAEwM~GbF%^7mGQ_xzsWfAp)@jJCdV0KKPOAz|ERjkn6e0BwJcp07 zRk8BG;n68lKSTwgJzgqBq7VeMKCEQe(D|@p4-&rC&1qGws0k_3 z3P460zeK8?c0D<7s}bghc27J6G&h^9WHO@olubEW@~M2)G+I|ga}8*YI97SrT$|IX zjd7_ybPnij(u{wAXNL~hDt>v3RRs=F1m&W&K$uf>C|8b*(lz~kX>EpOTL^oEIrNa+ zN(uScj``YF=bewS^8WUYSvhk)YWo!1=>9h*q~~-Dv3{`0@|>|MaHqX(2LG$)BI71~ z2^~piA6q~6HooLd=iGX`GMk9A29_cQ(Ak7hxmV>NGOfkalE-?at>#Wl%JZI;kJrIlpzl8nVpj^`0 z4#(ap={7_S?~3VEujshRSxEVY<@L)(#QTGj{iyy>E~;+;RqL)w`+fjPSS`^lc( zv}%K*<@%4BldI(DRp6_N4Jm~pWNm-9Iy?vQ`%I@4N}={azl5hBcU^N3-@48BMjidP zo{Rb}*3q;}!wjKIZhqfU#;_DeU#g>2cco|m7F=%W zYqO|2^=J4}3PsTVVJ$#(nvbpLTBR&s+7H@u88N?Fft-G1hIC1hs?SyhvmZ7cD>qKJ zUhrX$Y=5U*#SGJW(;wxmAE&qVl@OGR`WS#R70%|!s6KX1Dy2|_#1cI+*8ZA^c322Cx2))9ILjFa&Wj3b*B%5Vx0|` zmPbj>jAF^zJrJ>=$xgNMh(3JVlZECI*9rd7F%%J%!t(IKjau`{>T1(!{WaY|QpOix&|7)8Eo!8hbXVy&>6Mqw$LK=p<%YiqRPqnY>RO=JOl-{bP&( zLZJvr9&EJVt3DXAg;fk5A}EC-sLf+O!^6_7=dGl@Ab!#sX48`l#(RxVUe_NyakR-yF>zG2aF7_%le_$50!&w>VGV1>Fo>*O$# z=FR6#C}4c3;LI`>#{E*kpCgqZBVw|GH ztqNzFv#p}4NMelopix_1pl3cIeT#BcS**;ngfeS-FGO^hzg}end-Ct4cVnj0f8U~L zDjRE;R{E;T-;CnBn>I6PODLCQ&G2~c81-tU8hmJyx1cg4Zy>cw^sT1eyYyD|itZ+W zQmFr+eg!TxD56$wR)%-YZY8Ael0H$tg4MF?f2s=(w&C9EUJe;OiWS=`a;7f8{jTsfnvB)zeSWT?+19;W&uIh8W0Uy1- zgrMJ|GH7eDjy_*;KKei)KhaQ=`$5`Hy(?yzZf(Rp=Tzp^vNlMqqP?Xp#F`(mSDiSk zH*b-9p``6puV`!W^`t6R^(!7*URYX8?gzCAstfRGsa4(Z^qac#M@wmRVTq|&Mt5M= z%@O!wsj~%yK&f5fyJ|vOQ}Z)ruR&%4;p@hlGaT+D5A96Z)$IY77?=g(ApGgt_NC zcBy?2wO6Yzik1v6`hkA8LH?_xWi~#7j2p3(05mESy6#EPxfG={z*5og4UXx-5nisyOAQ;xK^_eywUxR|jyX%WCdp!7> zrQJ*#SMtm>tEN&&$;^jlHn3O_gXqO)ASvwo!8>1aj#<5q=%l3`wTdF(=Y8GMuNSinX^#Dfxn5HgA6rTlcN8gxqZK1Go&#|4uoo*XXetlF z^_+Z*R)fiiE2GMYV~-s8rB_7-9Z{)I(&+x2aozN=l;Gv#yri+B{g6f-Ue8`+PO*>X zD^AQaX>3SiMmg#`mMP3_n^=rvfN=>4xdFpb2kc`P-xvijZSb_vrlM zO5Z>}vmxfUlX<3G@|>5SpHIX-ZoyB#+AZ~i>M=!QM*K885nHGwpHpd@NhuT|%Sahh zR;=)OtGd;#Dd>nw^FeES!4cmgd)V%{8g$b`LeM#Ekwu;Ua<(gop z!-OHsIn-8jJ)vrdnHL7A{hnZaMJW_PN)I2e`+olxSLOM4v#__D#QEjJIzKdf;+fID2voE$UIIDw8EI1MgroLF2^-PH)A3`!vg zc{lMWBFc#Fa9%A^7Gr9HkhrAzc-13_mG7`p{bL2{6`@E7x+{h{uU;uv96WjA$wm@F z+7(MS_#D}Yp?@G7&P-#WjazIbaQAt)D(CGZv6KRnYeR9t7fPZcy9msU~HOnH2zU}9)` z=^E#Kzy2bFp2J8jgj@|{d>ZDfX1hBO(kPM&6*}sepLl+=&k6UAwv%URbm@r7h{YF& zr$#tW%aI}Vkc^M*=Erto|G(Od*g4(OGp|-i{eu0V2+Bnx4t(2iat*(s?o<3eB7$H_DSb*^onXC)jlc19A5iONt^kwt?kxCNEA|!MRV(MJ1k)K z<;k%@TAM*%l(XH+)M@TpeO^wUe%w&Vs1w}Ue-6r^6pD~4PGO&3I(=37X?}kpg36%P zfD{dI^O#3!g;#yjY@UJ60rd>nzke$*Favw4)o1wmk!dzfq!fyf^V<)V%1(8DH|zh* z2d$xy<_02Lzwy>G+U96Gtyinm)0r(J$d{V&B2^3oDnWKl()m zMbH*vJ?9)dZ?_B6{^zNQm!ZCkS{i_TySu)gPs`ad6eKO7nj!1e=8Ly{-HI3VwfRI! zp$Mv>n5}-Plz*p$J{d8;$e`;v)k=VN+s)MJ@p*DQ1GRH%+wwZ-x9hEM#mkdy`38bg zD1xr2_?AWeRNtG$_vEYw)QV`^scquxlqoxWo!<`6={coP1hrtydKtSl<$g#+&V0~T z(e<4AO3ZI}Jml-0nw)0SD@vgV>QOQO>U(=WFd&cEzpRmI9caP#)6;ZF8f=s^>#(Sf zUv$Wb`Nfx9THJ?6^{A^(ZhA@849sgynS~jp+Z3ApE9chMn;pleb@EYz_f=7$

      7L z{#3wqzdy~)t?4$IflC7g9Vlk2Tjq}E&D=Y)w7sWvn#WG_+XHJ&VGE5~3S5uE`}4i6 z8uPykxrluODx0+Jv~EWBq9tEe;}ffw6=U9gHfbigR4YTW$^jym_29yHuNixBqe(Nc zA$Jtk;N8+8*4d!h*Z@mc#q!G|HM5WBV3X#5Q!eeT#2P?CR6RhygeTi4M)7x7ywsUjf~3)rW*dEt|j`f{goiOjC+AF3pSa7p?GX98mR-58Uds=8gJ`A`%sBXavD@Wm19 z*{0Ti<2~(vxnt8j+cK>y>T%7kzvPjfcsPc?%>2yyRIj4aoC%6J;@W|gb6kiS`BDA= zI}+mfpABlTT5E@yRIcxFF*Q6AR zptAATfGTbc zYvY;fiu$hd-kHh^s*mp@d1Fq!?f1N##x>;q4o_2m*29xKdapvbq@6d6TkFF=1*NMV z&m9C%E^=cgBepu!=il$YP-}aakZ;Kd8ouLQTa7~an;^D#2MdM!@@13r@V(|slTs|? zeu&;1;j0nejdeT_*e6rqK-!*?zgDDVYeOMp?UI`WAZ z|5QCHj5H~QBIG^i>#I%pw(*X9L#=Mo3{oz-V+CluWibCkZ>)B|u|aATolQDV_~PP~ zQG7$I66%|UeWae#k*0AFo<^PP!hgO!uf9FJUg`&JmDWFq!T6I3+_PmN?a64t2VQdE z^ILQPJ+ik@+gotLq`B(;-D|9$j z%#gLDNclLvfAk?^W1oSh^&sB7HVMjrNl$dT!pZC4z-OcRgk06k#7j+0N}&jO9h`7* z4EObMG17|!o2QndZ~gGZ4^FR>WKh`v>D7nwIxZjmn_a@!dWgPKF3Gy!a_bm=+5N3? zLfLCliiD8X^E&57@}lpf^$*YINC?^|X$)c4`WU{kcv&;D8NLEVMpr_Rkp}3!eI(!G zIFFScJX0E7+9$2X1gycTqQJY$7-e)lH;QjeoWWksnIs`77ac=fapouT#3_6A$LFr# zuQ&cTx-=rAbAvYMJBCNpa8~a{mN4meoukHMhTcjAI&RbHm+)QA$>VwU!eBOYOeskQ zjr6EIj2Rjv@FK~XEMn{Lj7E?&-l6d$Mr5NC`L<&h*_y_#5`uD3c^Fx)8N*klv{qlI z6=Uup2@FaeS72JN3@T4Xgxna-H%%I@mVcFOSO>>5tr^BQa|3nCMMnWWb)G)F&(S0` zvmU-pMZGBToR%9HIqyH9K)<^bh~SZRj;j+(T#))f5s=cJLBtaU((xr!_^k`$@lEci z1&imEqYUSk3^>+r4$foHwH;u|%4U38uCwaL!&u!<)@_Xbw4rpPM}@m+NF!Iwf32l05HBsRza zS7#DsNS=X29QX!sg?OHv5TXt}gTFsO_GDD^=^hTx+s6*&FZE^WpXJM#RNJNbUlYmZ z-N$t*IRbUJc*7CA{w^Q&-h5o0357<>G!6!6^>{pQTjs7(yJ<~y*q*E^1TKt8h7K8Yafg9CX zzMUj(ry5SbgmtNF`*WjbBX%a~Dr&nQvn1i}XVdReE;yA3P-#_v-YG4gTHE2Qj37G; zYk7wIPrS80{S-&{ylXGs-OW$!^7E!iDfGK?tNQu%<`2IwR5KT0^h&-(xvaBWvE)?& z3|`sRkG#=Qyx93^>f*=eBn0J>Yy~de9>yCa6i|QMT3}KNMNoNo?h`YLU)%4iy8LXd zI#h{bmRXqhHnAc8V&u?&Yj|Z%EHIbz_)%W!Lwto_+Gmnos$3_$zg#$nzrL|&U5dyE zT4hT1pLkxddEDF>p1X3OYF~SmgrM^wX+D&(kLSTf zqtuuCR!FUqT0&0SY#H%!T$#~Ft#|FXgrHU=`FYT8$MJy$zfG?u{IjI?e%)_s?HefJ^B?@})+M*t5>wB-i^Of@j{u7sdm)W=}d z_d0@)N)l>#Ud*N=hocoy!+i)=k>Y8yVViTa8IZ%RYQ`l{IGBdw7;X_LlUVnvNTu2v_dG{U1*< zU;I2LAt;x829Q*G0N<27z$`amk10{ed`R;I72;KVIY;zz0_J zG8gO-rbHnKd2~h4NUk+$Y0Qb5XVUSZ=P=Tj;O~+{_`|+)ji1x@OEM^ep6H<8of^Z7 zKAdXUT{|QpD3>%M@cPmq?y_W(*|FwaQSpf@ZP9sP|#q!9IjV zb}l6&2p8Qm;HvgCl;7CcpJi_?EhvSavCH}GlcshTzI&FKt{+dRu&tG0?dorU?#?V# zFe`dTKSQfrlv%?X8E^<|amM0#HFO=@Oq40{!;Cm}QKgjRt6oM}$*BfxaAHxdU9eJU zI-aiiAVR2tB7fX!_UWf1hkAhqB(Kt81lCv%_B3Eqny%HrbLB?(ce7$T1a?Nm)oc%u z?b1{4_qR8X%5X8Pd(P|DYOyk6rl zF~HE;Rl|ylskocCmM=jB_qI11r%g4+v`#X#Yc+Ij#@CDp>m&mftkErh#p<$*v0rD6EK zZ11H$+kHfJuG7VUs2K{p&BL^hp$0U@%CML375XK7Po_W{(dd2)^-Y<=9LA&mJi&Xq zc~~by5Rfkjf0KEUKX`hemh>vvP%Mw?qPCk}m%kfW1v7mIDKH^|!MqBFr9J+?j~mk- zxZ|(VeDR0y)`%$izLxNw?xSAL^ySvRh=3qpEnhE2(J~@ndqZ)&p1m6T(Sygnsfw*? zp*xQr$S7JyE^h>tt<@%!j(G)hntgnQSxFm~euhtWDqWwk3 z;t!RYzd0LMUMx4XGHaD`!|=CvnlCqC;~S;h15e{}>O2GdZNH?vwp1O_>8Pie7a40> zzSJ|EcT6!L>}`hg=}Lz6-fRQ<-^!R**29Q;HphSw-|$B9Q?Y6y`@FvxGq#^eDHH)K zD;w^cm*VW=FN(tGr&Yz-6}830mnTeTH%GjULH+$aPlszh*b1}@Fm>lwcs3R@(14cN zXdmI314PN7bkk)1l0}_rHq>wq#oMF;kr|RT!{VyLMTv&X&Ap9umYi#>;oPm10agF< zpLeI9@%=O2^z7)MXzNEB*1hEnSUVkCb?;=n`2AK#^XSJu2DLl-U1~P~0j&mzat^iC zA@{7Z?h?%p-7(mBmDx@S;`sZiP}XOFIQ+#<9slU0grHp37_=L|ff-=`6cKN44Hpl3 zEHnlTS*ltZpj#zr~FfyT4|#fn8%&YMs<-Wjik#6)&>V=K2rn*H1!FE-DYe{oOcG{%SF!w6(lS zDHI`(?h^NLBLBX#MuR!UBn0K6ejb07grig}dt<~Ur)j0Jy)OS(Y z=-~=_iHD_22%nL7T1#xgvY?d#Yw8%98=eS1z-$f?YJ9HYg!Zy!wzp_H#zPD_waB1$ zPHmgoCjO?yi+Up3-&Yhoa!Nu-T$0sZ$Wuei*i%Kc9d#XlH{(C)lBJT?;%V(?MYvBW zE*e%hR2m!5m|^R6^p#Ev4DGaSbbGaHD*Bvq5FNs%sg!HaLN6n^^(;d>lbgwiI!_x3 zzS&JwKhR306pEnU4&cQXCW80W6z5ldW0XP>blmU-%$0S;(Uv##)VvChYEsRx4y^A>Y+7 zBGWvZ8QSZ%h)7tjikod`n_X5_ln|6li^do(1wHER=7_Mq@DZOEY&PfkILZjZWl3^D zA3w%`$+%C4N++6#j5kNk?QZ!wrO@xvXb`j28!AG5_uOpn0TP08QC-07&*7cLt?L)f zg;TdkktK~qsV?AH?T!@jZ(o^xwuVbuLJ@Q}0XmsoMKSMJrjguCr4)*=&I&g6bRLgU zXDWKp!x?SF{+-3ePU8fl2+AdENnG8w;%@1Z!fn+eol+bCuyQEl!>ZA{tkIZ%)$L4I5t{nS%x>FQLQpOm2LUXy))RSut0|sku9JFB zV=XB}ZuTRB6V zQQLd}-d&u?d~41am&>FG$|d*XbYQf2eCM3mZDwSHMKn^wYL2{v#L1_F z&G;Q_WCV@p$j%#oC(bfZ6j~c?)@ipor04{|_ia4HIY^sdE zBSQQu<)Rvczj^=GPh6hjB$nr2CTSwoK58pygSei@R&*3?6X%$eLJ?Ho@C0)FaB+6n zDs#_LPwCWvYK*KUU8;}9m|?PceEV~q?guEB9E%p)6({_%JDLv%-e#0S5popX?_j*B zbE}M*wX>#55tNHY&X|pxdz8p`roaEKb+e@?oO0290>FS%LxpeNX6(&~%@Trg$@`Dc zk+GuM)Gv(tZj3IVF0GO8p1rqFRYwwB1lK zFmtszV@qxcLAj`x02u5NAlf%}6cZQKF{uZjmMX_SKUOl~e4?uG4C^MHGf)Jzd5m7a z9#z8oR^d-q2MFm!{8r0#%RY_41AIHW$@q-QW2dsL8j%?L^z89U8MxVrx15Jnzm!4| z0eyAoF^O4D;!QFviQA!!Fe>rT<5;(y|CtWAV;IzJ%;?LyGa?HclN;b`>^JKoqD85t zO4}-xdC(XcA#q81bzR4Z^o|oRG8|h)D9P1I7|uP~vi=`yvE+vp4C{+PW-07~GW12e zl&`lOIpaZsewQNXm#{Wt^;ZALzbo>l--1Ng{dhymFm$lsnG89zq^BYPxvQothyQTm zFNXcnD%uiqK8LUTyG_WL)T}apIk2UmK7*b>(lZDA-9Fd${Le{>TB}lCt~GAP;G`?l z0`fDhHQv5WTka3{>$0pdcy`=z9Ku|ISv*t$YS-w(_+8u*0;x%MY_^7U}j6%JtINX`H-Iz;ty4s9OTm-G%tctnk z4gIaIHpKMqb@;n^t<+-vjkwkb$I4Pb0XM9;7=v7?XB6;h!DNKn_tAW2sW@{`Xg5hq ztoKJT=jRTFR$5b?!ezCjQj)7UhO81;?D<9Hy`J_t5XV{XIV?4+~W9!xFP1C zMav9Ip$MvP7`)t71~0~NXZz$-)<_R<{xuRrM4#7 zU}f}^{jr+rvh9>JKi10Z`2?ziwo#?FM$yzZ@pnemSRV5SsBLy5f>Cb8Gjow<7d=wc4*_W(28^@bp z-jY$mZKz5qblhlbF+x@nxgFk{&8l%y@^F-kY7d@rM%3gD3pudOn=F!jIFGKzd^&=W zb#KTo7WJpA7eBDIiW(l~&Z!+xd!%*)@UeIRKjILk=384{S`942otfneo>yJP)q$)G z01sW7@vl2W)E(}QoKh%)+9N>Qnk~59^Ui9L1y5MWwYnDq^n~8@6EV zMvc*L_?4OOFY`RNytgy6J7xEvO49g)7MtEq|Mg{>*xB>|Xi55g%^0;WRkpfR$FRnB z)GhBj3+t;O-Mtz3tCqtB^8(*BsiSV454pY$UBUbG_V+d%8|{`^y=xj+f*JF60Q(W- z`p%WqymmMI!8j6`D;J+FMHm=mZQ2pO7z4M4-U8pqdbib#CEfp&S~Pe`R*aCBm>GRAsY+ZY`Y*-mWAgd^4IGm;EZJE!U56EWwO}iS_l? z6P5^D9(Y#f9NgJRA6i58u$xa97=_5e7zKTY+<4QJzNO zv)|2zGuj$Nf}Ts)sKMKUjhDYf$ZmiB!>xM*bW2^R>Yr&%{wu5tP<^!wGTiE}lxwc% z5(Y+DYyJp&HBzwPitsxg1q?Ehuda{-ZU6&G2!m)z)QAB_>o)l^BY!htV2!~u3lY5; zX1sm+m;64?{~)__lZ^&8GnzOE3e^ESyWN7HDj|UqwxQ za|m?jzh_|-wL#Z_p2pHOm-IW|S0|o<_^WrY_xYS*vZg=4ySkR=XY@S0R8Nfs?}H?S zL3SC5fxV4dEv;V8XPhVlqxL|jaRYm(VjD2Vxz4=|=T~LTS9%SDAqmk8q%n;38x(BZ zobg#y5srj`H4$qMV<(dO8&8Hl6DP+*ei!K#VIZ#r>)^63#@t~}eE4)XviBjs9C=sB z0rU+rP7M4kFRy_P>?XlFE2<~%M!z@l{`2>cU_GoskoeZ>X2Q+f?tP7i+BONJzvad37Q-8L~!z^(PLPb~PeyYWx-x5{%jWndKEqrz#~ z+1^H2V|P_1e-T*?Faxg)jIEnj$N2lDm)e>Oola=Yz&lpDesrij+NkqouWaWMMt1sm z4~O3yV{dXt7^haAlOACn5=$_{Y4k8XLimARb%8#ajYq?b#h0GT9zi_`1EcVJgFM58 zK8D@+vTE9gRuW4vsRy352m_<=dxJ4DyBet%UDW6N z?XowF z#1iaL@!Y`8cteAX#;2>Odka!bEWr%wcTcWtWB7IPRO-NbfhC&@-SrLsWQbFt`!yWt z!EGde4m9d`m_8ePzH*j7NM|=Un9LiZN92RCuY?mk&ZCT)-Ij>B=a&hCpxlPQNml4e zSy&GIZnyCxjLbX7#DPUOIKvX`gR!q<*Bv8`(Ocr=zSiprgLqU8#;D^fSm%=XV|sX` z@z?h8a)uKykOVXE8Vq+ptQcwBU6wCv&8t8eXr;#U#8~{$NaOUQ!*ctm>Kse(bMf3T zwm+kt;qK8vi9=fje(%_d@H{c*-Oty^E7d@??zVxLJcs$te&K+zNs{Q)nC(j9kppb?_1#4!cQMb63z9=u3Ft8ruXcBfZBgYy; zl4gj#1tupF^jsQqUO6zT49Y;7PovaNMwCy_<_&?bb9w4GVukO951(%a{_1Wx zbn8a`D>m|o#-7IOwjF*tX2ZMs^1yt->KJ>f^&kw4!ecYm-y_@fn&xKA{M23H(eZaJ zDZ?eSoH1)b0KeoDXyAC6U5Cu4G)iZ<24oE*hlOZxAiQz1qUAtisqy@?K7Fb=tACf+N5ti<>7{TCr){aLfGJ zbEv4b2XbRS1)8o9ehBfo^HCF5#u=M<@t*V_ zAE!ge~7aUdg{a}?g@0P$4 z+#!a?h8q3EvMS_quzGUjBY7?!5BE&Lmty}Yt3u!QP@yhMIhIr&TUxwizX3YpQV0X1a3>dhpVRfJ{Ia&4deXas!D7k__H=<@&%2O* zbIgXgwr(lqU%R84;PRSd3GO_iV??a@AhYxus@+}4C8IHL*Ar&LmjtHYk@t^OQvH5t zPdc42n;8{_^=pz~|3XB=ED!I?<>6Olz2Y8}fl#FPi+$^VK_00VD)Z|OHJEcnky#Ag zf9+y*+=WINt%J|XirF;E9S z9uKNZ3p>cwZvMOm-0j4|oJ`jGyv72i(pnm+l9ikLSUdB5H@=2VGhU{+?*G%(LH~3! z4)X5EClW9EIP59USY3@@z8PU)pFwi(B;S6c=@D)e-V(o0i-a%5exqjwIS6Z=M4hbX zC>sf9c(d~O%VDc!r~3m9ywYO^>tUxuB3M{Ij)ECHwBr(YjC>{YM|LxCmJ743gUjpI z5b!Gv0)bIn_a(o1$VtTnG&QgU=dbXSpqi2PhJV@Wr8?(*;Wz_@8JVTZ>6WSBl~y%@ zF`6BF#|O6eS04?dzi(G`sB3jV6$thr`Q9c8HsMe z>hC;%zO$8`e$ZzFoRN5~VH9RVHO{M)k-joSg;d)_GMku9*V-!ql4=({wDs zjH~m@=wo`U7nTp(z$d=4FyqgLVXE=5ToF?rx>91-L*2=T!~>MkrLv<@w`zzgh}tBu z1n*?=*wCw1DUlx?AEzwU?+e?52<`Zo?SidbrCH9b(w@NnlznNcC5N2W+)8a0nW4YI zfAv#FEDs(SuO`*3Oc)sDetEUFt@~DCsdx<-b+gmBWonH2=bLWa<}gG%czmm{{#{DP zD9du2_T~pYkttIuQmy5ZOHSo%&2&tbRbOS?0dkm z1T(DdH)`&db;7#b8yG7R!+G*=?&{qL!(gX}X>8IWVf_@LTeZ2G?G~IK$nOE!F1Xw0 z`FvrG8vu-sW%}_=_utEmGa-b5QP)#EH8yd!V6~%x5t{WAkC^{K?j99l5D9*+w@tG} z#t3UZ+~C8$ukX%xT|6#rPe)M(Lb*RKt69fJ3fs&?V2pluN2_4<*3FI64K}Q-W}B8{ zj+!@5XLolUVwnST3fj(vZ*o|2M%EPO!n` zFzlMO)yr!wMMg3(umm%n#2&V!*B9=KU_AC|_884I^N###9YKBv`QJ}DnU)T71v@ep z7%BT=wV(SukoQ7{69yxwrk$)E)8H)AFktMmrXLC&(M-8D<_0^y&xciCBdi5bDPah8 z_E3(^3I2YzheT^YS7 zC`pw${fFM^_hUWFC3z{3y~+&w{u6$E4qM=Z@vo@@svG z)e?Ke8pBTJZ_-_&>Z&8Hx)BD^E37fh^^GHMJjPEg3wJh%|G+4$Z_MNU1HEIlN$T-} z#l*v5--YKN#@=^DPl!xVO)8fn42&Z4&(5_vrQgX&Pze_tB=+qXg|!Dd$wMmg4OJra z74C@!TenWT+hng9(Pa*N4G+x?nU5EBYVgD|?jpP_We`uaX1A7E+ga@FTrwXwJ)HTn zGF3$8pD=@1f}e|h413(E6yN68PjZ)d=nFrkF$t#xQo#3N6q)lqzK;COm0|Mp_me3D zp@=790m~e@cCm>XJWZ!Fh*k#TC78o*cix~~PjxY%s)1J)GXG@G9qd|g-!pyH2s=l@ zz`lgcKMU*a#>+gMrUuU2PgYC3isIRXZ<+3E!#CDQQ2Vw-X?T6bD69*N^&IdWAO0m? zIoEA0@v4teR7?7&dhvzzCaRPBXA%ZRSwdH7tN=WNbt~NY?fjzyAFE=Nf9drSOE81@ z7&fJO8=mYnN|hgboG>uTdL=_+U0|Q+KGB4(;#fN#6EaN2d)|>mf_)e9K5^0R{Ls*W z>H>dD85q?Gen&X0QMO_jBM|K4n_~miC0C{xmLP_OMD&gxjrgq9jiq#%LbV;~F41ZB zetk6vn4D_4u&I!I* z+-M2+acHK}p?<*nKGh;dtPs{-I@yI0>tcU*Sjdz2c_~{=J;J~!Y@4v+jM~hj{tQ&7 z>%QQ442;5iM#e_vZs1{K$Eg-(2ND}#6t*-tQFU$?pB@seYK~i`brLc4G&3eNs>L6m2L2 z#~;|zm_yrMDXPV+YLm*r%v$?eIr$jeK{S+wHSqM1x}yY=ktaOMyp$E){saTqp+pHU3$>-arpT+ zJZ;cul9Rz673XK*w&~Pe+^dYIo_Z~sbcJCC^`f`)5A$Zb9rWfM#!&{!=#Xw0c5}%_ zZWmNTKF^M(oi&I-G=`n+n#CJVoG$ZIM-v7?A$^0oT0t)N{;62zzVs)VBCJ<9y94J3 zf4a=4UGY%Yer{mk%nd;yje)M0tOtBUhfZqd!ZL(`wS?#!yLY&lcbPOmrS6QAIDdg> z4cENEUsWmMOHYR?xb>4%!!ZN;D77VoqC_}@RMG@HF562u^$k9F}cYb>iZj6WRJ+rV`dT>l_-5mw9H!x&^Y zp5LhBO&A!3YcGr)d-jl@s1nDIF9{=ElbC_?rO?^`p_U426wSAU`x@kg0y;^6@3nwz zROg;N%17rfj5x#U3tg&b+iTWp@w95S2D+KAx76;Y&4h@>zP&HMyPESsyCEZtC8%OX za=q-sjwQP8$@%E}Qz-*wgh{5DJ?r_!Ec~GX-;3_%KFx9U`5>9~r8A%NW|Dy=gn`Fn1?7XKTW&KRwv6V&38OH~ zWbUPXEU_igUE#dx@&iOI=?7s9Bq5Alw@kKIlJyj*<;+PxYj9*u5eK!>IM! zOjb0>wB0Nj)DbSoIWx@hOfRZ z9u0EP*_$!KQa=G0;e$&X4d)H#eHRB3`@nThY+aB~{B)Z4_3O!N&mKXCR# z;<}?{`%#mfhMMQ~L=#v3V6FB1U0SyeRBih!QiH?{OD#B^FfbEplfOX6R&-07th#WR znqG4{Wgrx;0>YW<%xhAl_^6qW$|!uJ1FogwiYeU7(jr%mi1k&EC)+D5!3_NS7>g*( zmj}M~QBz*hyIwGg{&J78Su*cZXZ^`(&=Rb#Slh9Vv3i!JvR|owdif7vQCNZ*s20Z9 zoO>(et2%qc<5jR1#SDzXTFF*Dn?Y%N? zPBqnGi$)n3g{qlwYsAPca`x7`YWaoslz~vT4`)ov&E8F6DR+!Y3=Z&>(nC0oAhtCl@I$FT%6GTR?D z-5+lh*72^uSZjA)US2go)v#rAEWr$1gNFR>Lj~u;hpMHgW)lWRRrWn$Ho2cI*oA*J zI1LEZ*W=wss?MGc97`|*SH|JnP9eu+;f6@%yLFq685p%G`MN0zvxV(RHjL3TeUCiz z%P3Xr&Pa*v*?s*EbKH5TF4+yzsMY?GrsT4OF)BCSNn#0R&@ry=cq{|w3{|JkEGK;c z7=`~s_yML~n2PkQd>%5AGB65T7rXpuv-~-6ukI8RLvEDAm2q-=7SntV%FxJF zdPvoAfAzz-oS&>f|4Zj23E=Hca<8PB? zI%}4XC6%AD;eW|e(+2Qu_d+QHq39lNmB$O2l^Dzq+zh36o*@R=4YH8mddQyV2dZCo zK9hKr!Cf}Y+hSUmWI)bx8sr(e`}C2!%ZyMz^*Tuz2!(Z;v4q=!(!0|Lm3{sM(RTb? zs|+{q4$2ZGcdjv(^mnv8(mqB7wS!D5TFEd9Yd%!_UVJalgilib>5&pkFoV@@XFl2w zb=)eGzy^=sm@Jz$iC4dkZYHozV0PsR5$29#z&Lvb7-M#(%5Sn`RcebVI%Z%LwtvVD z=8u)@mdB|NQRS#F!O!&_YVN$YMOgckoV2iyUm)u|ic+OsCKCojDD3&5?p$uXysM8= zQ|9d^9*!_v$C(8SeiQ767BI%~fE3wiMVOkk;x=JqA{6$=kn76`kvUFX)xnds3@pJ6 z>zo+V=C~5>RtthL^7fCA?IDipvdD!nFp8`zZ03X+@_Y*qwRUkQvVLF&Ssz(TPaoN~ zK_&Isp%+=z2!m8f`z`7vXZ!vm_xuI^3a_;og?ty>i{sHrwwziZqjlI>VhLuD-RsaE z-DURr{qmn%kT1aujKaQ)wTa-efBAW`ZPN(`!xGHEyAP&^trd%2JMm_-U@wXz6C5Xy zz3A#>AzYT;(f^8odK8vmMs{Vm3A2wm?_f!#dcf6-!n=24Ei^O9Aa!z#!Z8DD-XTtS zl^QHU8bLK2SHLj}*CW~Pf)m1d#BI@{7yMUPf*Cl82hQoZlU*cQ&WneGKy-Z z1Vt+D<%+Azj}Cq+u#~gGaAh5#uyw)L>zt~|Msr81Gkf6%8eB8SY~&^29Ltag;^>$J zB@TSiNu3F z>~U@Qy1aX+N^EUU85REPHl-b=724$S?B_r7_KDybP@IXQR1!_HDiinfxhDeoE6Ai0 z3F_bdzaHUceMF^4I#2HSe;stVYYy8#YgN=(*6FZApR*it0N7Hoo#Xh5c`7$qIsB^j zsQ`QlW?&SyNA}9aSyt@YT}{sc-9`F}wVmqj;GVhSVosC_7;18??F2=1H*~I}JZ+h# zraZ4mwH={|Rx&!s)J)C91ktvRAsh0d0 zG*k8&7OcuTLuC|o5@QtEMX~qVTKOim1^L&GF-(T`6RJT5L-dDTlhA|$$YcS*P$wW z+7rUS{oB|!8EbAo!@N8id`Z|nG9TFHarGT~Aj{q~Ul%8-n*H_=21a481R4517tPEs z3F>MmXQCwpg}Q~{j^Ba>p5fKuhOw^ai6#<{O1cx$gAxuctmm&DpLHSHj`f&!K)m>A znb|eqsH~a~Gl*9fw0_V^b;Cu=%$5^2%XxDl`+*n)h1V`t`R!}-tb2(5xuo+9TPdY#h`CBs^a@>h5_fHPrGH@Kb3@BQ*oPpv?|s(OGMo2u|u Oeo=%$DnH~b!2bYfAz`=x literal 392884 zcmb@PbzBwC_y4Z~Dy?*Pr-BIFyN99gr9nv(TkJ+rQNb3wyBlmpxI2vfw!7c9*xjw) z+4n!cv!B0z{7-DcNZdnxwgi#W z7b4ldJ4Up@=^U82I{-S~HKHx&#mP42x#F!=;thbi>?a2$|&0 ziN#A6P_Kdj;@(kUGkV%mo6Sk!cgqb<L(U$g_du z?G`1&3MS%P*wM+a)sWK3l@qUa$5OXzKE%-|nl+#1Ky`aIK{d>S3Yf)2P)Wq1rEJ-3I2&s=GXKLnP%umj!mZgj{`0tIjEIMH(Z zYOy@mgS3f^XYRkf=;5PEDBfxXPkwpPnL`CIY-$6gxt_FJu>clEHk{a$(@j|2!HL+} zC$TRNis;lS%LTigrNTSDU1_*NI6Z2t@ceiYEiqUj)Rm4E6bh5>+m+_8?a8SoDeTtG zV!D5Dt*AF+hIqEBgq|2wE2i=7uazaVw5UovJfmDxD59J0Qtez~PZq0Fn8~AFba31! zu~BV}cryCiRM(Hn4$<0jThLFwFaq7TN@7X(Jg7jx+b)iZ$B(-Ne#s& zG-F{nxOQ$ycW9e%qNZ_I;ik1a*_E8YMu!K3@39uJr@blI&kP0+zP+1oH{;vWI<|m~ z`lkF?DO$`E?2J7~yOHtiR<0-1w-=zpS8LeZ(i@Jn72w`?Yv{+ft9vP-y3mRfF-}vX z2DgbNA0At?emC@C;;ej_@+k=V{LqK^x%m+LB?v}+(FfN-`LOTbAWlr|{yoZge+p?D zccAWTFMUud3Se<&FgOm;hm(KvAt*Z-Y6j{<=WqECoE*%F1^(7#$2T>J*pyM1sn7?b z-UZNPQ!w-h)`xrX1@Lc0Fx&{#hlWA{^cyb`;jV_{Y)UF=lsd5vE0}n|Dz3Kg@&EgQPw0mSO=NEq%$$--LZ1Y6O9& zbD`1nKzQ8L2*k6waDH+iyyM&3?ebvwnLtjgUXUiLtDMPnGY#8&%oH~JWW&`?{;(p% z6mEED!`DK8sN&n>S7d|EL4Qs(n_elNtac<1=O(evo`pm39zWQ=Rv(r<4TrBIydj`*A zE$#hE>~(k#|9yPid{TRPofAoXp<$NkWz^F(OF1Wes&dnq@pRKO50$}4N7c;I@ieGG z@7mLY7t|;eYr}1|(^M{`*(NnRXw!!F%+&?IimQUEWfuM2tuYh~xg{JfPN%2s8-wQ8 zP5wKd^35Msrr481suZ^Nu?J1Ai3amA_R#i~JH2r<2D;`tz{zuN^aYIp$4(CXSiP=l z1Tk-wymI2c}d909kHKC-H43zO7J< z?cGVW^{)##*+k9O@m@x5hg_%#351P&`%`!>^fM2H&c?>{0^eTCw-t*0zxvYhx&9=s z53tZnhIDdp9@N|mgviZ?bYf;6Jo^y{BT^0N!<;-&e3A(BKhvnfE|4rZt72He#7Iu8 zS)2!1t)x4{oT3|bC=zk`pKh<8K0 zm}U1^lDY7dfE7%vchIMIG78|pe2H-A;>)%yB4kXB3NV3P{cQDVNG5O9e}qcck15Tf zNVk$bfE7&KGu5Zp3ksmoaw*2NTkGnq0@BEw+y-pPPkq{bO+E~3%AWxI+%&qJ4+W9I zfX@^EeKf4D8*@36Jh|~qb_Ov)wEFZbr}dRmjL{ov>+~RtbRAePBd`mfO@$)QdQ06j zT{THG&}TUMjf46$c2hpA(+>vRT7_cj+J$v*=OqyD%%-yaz=X|TeLARDK6qY}uEdLD zOX@c6Pb5PQTF40Oa{r@Gd#uWb3ntQjT>l6`A%8pasV>%H@#>`@S4mtL#^ zJ;YT|(%NgxP(d)tm&$m|gaukws&|KqvfHdP`X z^ZxmZZ@%RF-6)0?OuXPk-j-aL-d`e)eV8TQXux}~5dB%xsKB|#DIq}o-e18+F@0J6{gQTZg zaz}nId}>27f2FcG{>FPXBO4Zu_lMpMOzDN~*>L^5Kg{}MLKjwLL*YfKpE&qf7;J54 zOQvm2Wmv()R8G7-kPSgMB%=H67Lc^XmedZB6WCR`%Y=@8oed>AQmd9Pn*(e2nUkWF zOqRmmmv@}b0E3g>pzyS$YyZuFpljanEzpAQzK{V8>iPdGVt&p9Z#@eVVVB8d3L;z< zTF_T1nXo%V>Sa*NzOZDF6&bNKT}EKna~|Vcd?u8tBqB3)1DrQ9Bb!xO3@ezp!igs< zGC>$F5&fd}z>oW8*oeEYBq;ZC4!X7YX z=4AiB84UOCaIa6^Pc(`ug1Ks2(rscY!wM#z@jhes4M}kRj?@>8C?5z%p4gBc$K(Wd z;XbND(Yb4Zc%-QZnKL?`JzecYuSO@p)L3V5U*kld^Y?zU6aU*oKBA3+QDf}L>wi)h z?nigXbEVIU;-T#rr~m0wA944FwUg}0db1RUd)t`M@?LnmZt>7{f)n458R9yjz}A_# zm1<-JcH!146dJ=lqW%sKV*WCY;qe4K&fxvTgT8nnfLU*8oT1{0f6d61uB6wLM1~bi zY~!O8H&s!vq{NmJtsmzJ%_lpPsOB0Ofn94k(R5T4?AR(1fqK>u^wOTVTuNqG!9>$m z-n1`7!Kx7wG3(($p_i2tv58M&SiuBtp+eES6BF*(IgwA%assRX!MUW`T0jJBd}||pFdstCla3MN#hKihbYAQX>O$N z(FAt-oj={(D-1ehn!yR~ihCOYRl%0)Qa>C-xRc&dZ8!>p6ARAl4E_ti!$6r*{EpZ`N3)BoNn85M)NKx^Ap?8`S zN#LVVn82>}9sxA*Lj-*Bms*vt_g2-u$c03Y<1vte34BBpiiSPssNxp5knE0X_GoW7 zoqoX&&eZ6GYGDYif7k*n2bqFPK`{M(zXj+HG37CmiY$at-<-+Pn`(v?OdOcof@+*X z!Fym+PF#NPDRjK#Od`L^3GCXEA53@l4uh`gW}K*rtP+A^oXC5xB!(4CwCf*CZ*rpf zf5aBuJ;DZWCvqrKPGHw29>b$73>-R3F&3+XQnw5MX*M8bg>H` zH~v->IrBj2bQjXNrno zkvVFH6->xutoKo?1~zsf+b_ro>{?=%KnKjTgtM)rR!uc&q)G>^ga~D{aqXICYU?Ot{oeINaBX{9~HL@Eio5 zn~)QGr-qB!W1Y#w2o0-PUP4#9y9vG@8wtKEO6UboQ^Bh0txD%Z30>FTNoey)hsWr9 zFjPD?%$XEKYZz8AQDi=v4sb9PO#gYSQYg$KFKF$ZoJr@Y8us0593Adbsrpp5K!siV zc)X|Af2w|uy~2sz;TLKj{cs}n8~NxUQZRwzDHM<5-m5NFIFW-tyYf~c1rq@=#q^w$MmXI}A{t$urxMONkufLb1a_?_gXs-*XQ9vU2u>Wnx?Stv z!b#tAvm5;376(~c~4 zCikJV zq{}oOW7qaUs>fEm?=xFYV3+(?8#4H)w(OWQNzv6XtYG5(*B-Q3JRpP|U%+D&X|3$rz7(-7@sa6FJT&cppW_||4n9`aP@L2vk z$Hb*sW2l=?rK)(?0{%OnV^*)NZ|F=`uapxqSN=G9{nQ%OgPa+hNNjUK8~fOa4A`$> z3Z!5H&*>->VaF~ghmCb2gPJ5UtYG5!+i~>%oA%0c(`G0YidELzly*h@9mh^iV3&NZ zD1UgZHglL0X~FNicyavdPQ)Q8iD3m3s}GN-PD38l z-pLroi9KU?YUjl}k$quu0=ulHmeYt|iQ3l<8)*4hpZ5&q5^E>Ys%;X(3MLG~%IK-v zDcWBR^f=LV>tU^3LnpGONKRl^VY3O;^!06R+pViOq5bz*YUtYD(+!ZJE} zjgP25=LaYHemSP?XzWO~`6SB-?9y15)0|m_;`)6)B7Zs?xz&#Q<3RR@B{QsG;u;-K zYfcu5ci%|F@XPzP>QxRzD3ue~)jEi`>ijryNNOx60xqnHXtK|N?CPJ)u!4!br^nIL zXUB;LTT6u7-qqR>g$~4Mhn&E!o2$mtwJ)cM$3J9o;_8{N)%(Uekk^Zn8CEc{z416o zt!9e1@8@#j;+xId3?m0}WQJYQZAa0g zNn6EXKI26>k-4Ng@|eB@IsYMU;adV8NGuO^!EYfvVr!*tyc=e3MS<9 z=QsOBXy-q%BNi9s1a>_*-G|=hU#d(zP{U&=IyX|LdfJo9H7N`$n85S(3dMll)`Np(ENoTaUmXC3WHhfOIAE11CF&nOhJmDbuJ)pq3DCpm## z{l@p8mX90Kbkl!$jKo3asz3JjWcKD1h80X~AJds$c%nz!uRhI*;?5S@fHFJM&M{R+ zU{~nqF7)<_CUl?nJSX0khNwRLwj((#g<%B~Nu{0W8%|6UC8DXx-P*?;?8u{tR2hL? zyVkU)<3BW|Uf_mntK$ zYau5l@$c1oRXpUxne<+&fi-r-|6>Zn3MK-+VFeQdMr6~koKXBn9H?1VbLy`xQH)EK5!m&w zNozXvg(EF_^_IuD-fFrku+)y+a86}d!Nl)LsdQvt7uvAuBPYIS%#}Zn+maeS|A7hY zir$+{?Y4Q+Llr+cQGRfoYKkWxr|y!N>A!GRoag>duFPxn%WU}KJ$YK z9psX?%4NzyRe87_nV+4?u!4!PE23#-p8&e)LPNeE@6*jyUVJ{P@TZ)>E)W4DI$=-~ zifP`FmYpUI6W5ElCE7Z?T7i^=c-P3ZAr65sWJk)4<=E`j&sm#m7bGmZ&r@ZOEAPG#P%{cLC@ha7;8XIzRaGH$3uEsrl=<@nlT2m~21KD@g z8P(;VHpD+BjbQ~7ZF!6XoH+L%(KA0lWo>6ezCD){*fo+9FKgncj)et}G549Huqw=! zTs2Q)$-O=3hi9?$;$U-X+{Bt5e3wFvP3`Dc9Xq;!rqZk1?Ktr$?Sv|b$JqKTjbQ~7 zTjtx+BHc8a|4<@&Z_p7^9$S+ICg}_-m=Kv2ZB?31E8p95;^Lb$Ve<_eGA=ibVFeR6 zMq1I+fvL2yQi`$QkiYPBw>7!hB3(vcmsg1uJ+d^NZq{?)g!Qdw~nl2--YovuK-MKD{F81VK{wmIFA0YT%w;^qE(im1S zLH0MHZ+B(UEDMQvIUq$Cw9}g0=KFyO?5g75WhAd`LldVsbHXNIq!51IhD>dn#;}5k zzen}x=PRx0=DSji*ZQr6uqtbEiSGv{uq*SJ9<2|}p+>7*IH6lwD(q%9q_TS&!wM#{ zcl;HbJLk~o;SzBtsk6{{fi+nipDrV?>(a1SqVcY_^aj6k^XqEXWa0f}8**eu8p8@E zx|d!PUmt2mqrOPQ-S%UJ^x@XzTYkEXz^)1VPl&VccA_0_cyr=*yLrOYG8;l?@ozcN z-+Hz0gg9en2Rhc>i^_?A4=ogCkF+5t7Njw(U}EX!9pXQi3#qZ%hsQ|rohHQguqGy5 z(`5v9?Yenb{8(K`xvzTpO?kx^$^OC+3;16S5L)h-YmY z!wM#JA50Y8ns=vDe*1A^$hnomkSuGmtbe+Uz^;{?n4i*#JDaLl4V?um0Ytmssx{ScCMh9DH+b!=$Td$B}R9Vau43}Dy(W-QY z6-;bgD4ZpgnbVgYd_fF{y zE0`$#_$FZ7^M3TnD2XsrH&71b_mb}^=?p8Fs4<E>rbo76%>fMgdh8tLuitTa& zyG*}4Q=Vo##$qYP?Y%QZvw7BJMoc=x3MQ;O-BCVW+K2XR7{rO#d;f^Pbgjvj6>`C2?d!z9PS)fhzY;Nl zT@a@yO#jx0b~ck@D6t z<9(daP2HOgPmuO}Xl1py-@}HyJe$U_f(gsl8bR+(PkMZw^gCCM*eqrRS`+Wd=`sSl z+Krqj^y=J`vc(c%*Sb>FB-)Va)oBbXn5gH(Q2*}K@0)b@G5N4cY@TdQ_6X*9w1UcB00`(sQtT;8Zc7k2P7ze}kC7 zu7_DCgeSK<(Fs>2!n^%Kv9Q91Jf57!u!4!A)+dD3D>~4XfnJ^wg z(im1SQL&^6WS+>P7d)hXqF9(Awp(va#wycg1a@6mX#!ovEb0;_5l;pT6@NCdCAaum z8LVKUW2zOL5>jbUywq=B|D(A$pFeSi#ih##>@wvbX&&a7ZOf19}S-`hkhnkjz!VMC4zX$&iv&~IW5m-+jSDSzML^9JvmiaGpgke{3` zBe1Kz${HG})9Hj$(z`+9`!BTt*Q`mDT{^=GCg$td!6p74)ntbhBht)Y?AOhf1injU zSiwYidt1nFn@lqw+i+s=`0d&|?QF>418Fh>yOyqXgmF2^H0G5=6dl;4&F6Q9oomw= zRxnZi!WEv3R?~LZtvE62v!htN&Xz1bl*+Jz3HeIBkOgbBhv(Xm=e$pi3G8y<>->7( zh@+`~(mSW+*YjG(Mz&;dWE#T?Ch*EYzUQ=|c40%l=Rf5Hc99l7FpRGy+`!io@~;gY zPit@fwILz=YR3vD@Jd95;&Y^#xPFZ-8PDJ7F@aqt7WzVU5}`$>n(`PYmj;S#E+2t3 zN@aL0B3`4|M;Q)=dt1`p-;?=1PE11A*%yVnF(J(oIUHFJ76gyu#X?I!K zk}*MP46l8|`(b$-V5(aPO|@#wW1QY|Q5%2Fmdsg^%CLe7yv|dh=rg5}_F1MaG1Ezt z5!m%(kOqF3_|S8%fBDGW_9=DRUmko6nU7gw*DMkbBR=`i9!dq36X$=A*Jc>lk%7gj z3@ez38LWZQ)1FkHNuz_~%63E!>d8m$KFA5|GMbzW73N+vJ>VB7Mg&+ZYdGP{39QJ7 z6Uoq@$N2nT4D;{0;y-*AK=mPo;g&okYVbVE$6ITEikMa?I@B~0e;&6ZtDmGWtYD%y z-w)&I9(3UK@4QvsZlko1Z0(5HCsjsZmyxVhdzY@%y5`!E=fL*^DVR9gB?Bf$JJOfW z-tZVfUXvp9PS}!9TjT_G*%ar1{d-$#{{A^9Ld*1&Exy^3YW~eORxt6oA`iaBTGNzz zX}sObVS-j?sU5k_*9l`+L|ispi?gPm?mrgg#B-w(ZQdR`vhQmO!wM#5_!Yq3sAe?g zj5O2WxHMR)?_)q7P^G&}SrlzYA~RAMRxmN|TqhX2(TFbm z_bMk|>4j+Tp0y+Q9;Gm>V4}vk9rV3!LOla+azZ`unX-Q;JF-7KRYqW!Ww$Oc?Qj#? z;iEJw)8|}Et?O$$;&>*7VFeSRZ973aCw_d8h`ajFm2Z~VkwJ$1SBw4@b{%|J1nWQk z5aTXNb6!J_nQE`w+LKmW`CJkDTRmTQgH)=Zw@)4s<%D;^ftnY(_9Uk^g<%B~K97oE zU&SYJ;1_A`u6RPZDr==3S){G@i-_auq$rn5Gdr=l%ClJPMlraUezbYp8PXCg<%B~BbS%JgmqeR)bN>{ z=vN<78?)7(*a#^ME12l>YZ!E_JtDTNn$L-qTZ>d>&2sTrc2C~U6~?nl{^&3r$wf(gGv zCGbjLD?V39`|;6AAv^|q(z`-VU>Dv$zWOX7r?%I5d$Qa)h2geG-YAA3-gX6VJC4nJ zGDF(eCf4)Z38wNGnCQBq1pe(>C1y>LvMqR>8?FjFXixU~$qDSjM}*I2JeU~q)6#+T zeV!~kR+w0vI2vwr+91{)F5xjw&snAl&W{5pm+@lq6^Xd^a=q&OS_e`$N={(cqcPC)kB9Q51)@!RcTR*1-=oT~btGGzunNiktj*5L8*_(@CE30*%GUs-HmrZnQ; z!__rSV%T+S|2WXi*sFXs|EN+tCSPiwe8v%aH#m8GHZU86PxeOjflA7M3(XIcd>$rrIjU6pz}lZ$@nrS?%iIZ z@^^G5_0!}8c4@0hpu&#-*+dTq!$~>9{cXXVcu6O!8g%C0q~>TCRxnY1t}lG6TP~#NkL5(lV4K?U zzRsj!nTBDPb825W8Z<{JUei~Q6J36qR8Nj^CLj817*;T0@Vf}6A6hO<)0JWboSLpG z;cI2wTgnOS%AC~~MjEdaTJdj@6^c&X#;e{;cP3V$8io~2JmoQ7{oNw;Hl4;E`&Fh_G3-N z?i#a1XVQkR1;7M$$y*h8!8r0_TW4~;t%hL*6P>?yfl9MF;ZuX9JjU+qBGsTR&ZNp- zPGHv;m%PJcr#O?X ztuzcPn8@kY0d8!+D(GF7h{YW*D$gBsCPVb)1a|G)TL6FNy%V}<4s&Ao{v|c_8=VO_ z@$Zn4f(g&7JU7GPdg1uB1DxnP?0KuTd@WfP&-;N1?D9;@f_rg|;VsPuUT;W2N zT$2;n)%AG>oTd8U*zztX)ML)n-s6Ol6Ij8-y`>r$`P%{p#=qmlozh7)E%{2MMLX0C zyJER3Go~rr+4@Y76Yme*i5$_@g+xqNGpu03YES}Ls4bzcMv8G}sJphxm1jKB$_eaR zotOaSj&@Ku_8TV*56sp^>ba0ce9aG5FrhY&g0ri5Ua}WDz*h;)bg6!}#)bUI=9ybi zbj>Fv?B}lHmpULPj2ANHz%MRjV^cN53ML#YBVkpcC)niZ@fg3!UhPLe7m~L}PGDES zod{Sw-Vat5>vLlH++gL>Pc9_POwF)@37q9fq43YXq`m3nLKcd00=wStjDT@_{ovo# zQVjF&^R){LT}agwHNy%fa8@NgUwc#|IuCFr-QzVf0=qnT9;T(s{K2%nwBnE)@YNnV z?Lyv#s2Nr;A|l5pyzr1#XPy$CD(4luk{6p28CEcX^OW)Lca0NO zjkodKRAUll8O&Dq;rVx-gu+$JW`O^aLUDY>WL3XMu4H6}JO(CWI{QP0ek)jYNov)Z zhF;?HhtA~hbG58h*k#cx0A62@fRh%|id^6CqBx27`ph*+3@a=6->tk70iL#&z`_FH zcC$#Rj+2PiCz)8^*ohp@NMcyQ#34@q^C}X~ewK*7M^3BGj&>toFC?%%joqQ>A%Vp= z?4XyEC%DxUXnf5MaE3O8Vo~%@?Xff$(qf@n)+)RoI36Ew&$ATP>~JGV8xj~+FtKu< z52Rj=0IiMGs$Wa5X#K{zkiY?I8G&8${aCDfPj#fN8=3zqfnfy`@{Dp#_lAl(*PY3c z4{8~KU2hut!hlW!%>8K1Tjf>WNV_rIl^ppukzoZBID;J@-(9*xT-d{j{NQU$Fo9i< zd7ituLKN&Tme$e#v%aRbQ?@IaaWs)(1rze~u}qyTj$Y57QMMWxfnD~CJ>ljP0;4Y3 z@fhtoc!`dGoJq?oJYyD8FoDlM&#DsEkPe{^Bq1tUMqpPlzha8JMZ?wzdmdxd#nIw` z*3M*Fo`zus6Zm>lD4Y+j6U*l~ku}fd1a=uTafkL5v9R*HlqK!@oNEG2^(3Ah;$&F_ z7xC-Z?L-t@d}9lkRw%k8JrgEx^(3>K#L2F9Ojvw#g;IXyH{e%3e^)zJqWa?QMlRVU z$_VU|x2kz?l+ae?P7VhrFsxw0@4XA${2C4S_esa<*6SiMy^}Mc>Acs6_7J<01Kl9D ze;jn#C1rc_`+Y)KIna}Ij*Vk=x17MTZyfB~>j?GF9pF`P0{n4zhVT6U-})thv!633 zl7BoDhCcQrx;J7ORxpuz)B#fS5}-l6MC3>4QJu4V)S!7XtKmw;ehqZjaf6YEonYJN zL`a_P0;T-_*S}7LS4&+u@h-3l9lX(j_@yQ@tYD(~zfRzBI}s+0l8BgukK#iIM>64i z5+mE~Ah$RfwhVWNO?mcUF(w&W3~&cs{{Me>YT%)Plquv^N>lnF%z+fINM=~U#1Y;q zecdD|5hTK7*$=TZU-Of#BPXy6?;rn~%BYZPjcv)7+Em$|W1^|CBNWzXfc}+om`>8m zqdesoaU3HjunQjrzOvZohS*@VBeAPaVpA9KT%yC0p>U)-xZBu){y!}R}ugJGp$nL{7Vl`xSsqY7L0cw zi}?B|tY8Ai<6m+(_EL5~du_N3xrvMkFc&a5dX4qmTUoo?<%?wKSqtYBh3kL}wa9bUJV@^Uun zSgzgF!-f1QSIY?O!mU*(YO9>7VFjNBxSqmr+p+60k1?Y-6W-+b@EA82wGltMIrH2i z{27H5ObqR04h9D^pyY(K=X>O_FrX|8#z*=>55Aq}(i-OMk%+P%hT6u>TuGCki3}^4_@QYAttMuHeJhEue-R_* z^CxF@JB^IMt_eSz!H*uTVc%WYfoh*@aA_~? zhmCEOV0zwzjJg;nBd|-Jv3K#TVAy%bo1FR@&9H)rd=C@I49^CmUQ&!Fr!s{mv)oDZ z=kYQEyUuJifl~b(cx)5EiQ=YOA!@iMF^h>~h2AD`k1J!jvU`m&I2h+ZUyA@3!2kd8 zpd7f|Um|{O87ru#dXV!L@eC`NxWH-a+c_W{mx#nJ;jm|sFB#NVp51u%LL(TpGZ&19 z1wxUr5kzL^!UI<+Gu~XM0ia0qC;wD|EFUs<;oQi47J2tRcrreS#J-ATSiywfLPI!v zCKozRkYaS{HU;uV29V>u1Q~%{@|?@hgSNx0jzPrTPsy-?iS3gOVaUI^kULw7VM>O= z5RU-T|BfIdu&egBA$;`BgC;j6VsL}$@abS6aS2s1tY9K@x*_~1&4aPdL7eE7auz2IKv7iJ~ZH2sJrlN(|@EG<~?^o%G2iL^gcO(T{v$w&re-@8SZonA;b5D$ue4F z0%y188GBDQh>E!!N^Da?8CEcnT5SNn+w)+EAnnI)pBM1pS11Xok`ve^&ze2>o^I5L z_F?4Q;uZ`mmhC`=@QMdbslZW$zWdwFvj5C0F3He}oR3f%jxJO-3 zMUv`g{tPRa$cr?9NrCw=di{U<@zpnK7!%0v_1-c9yW+tBl*Rd=dMyz^uwY-!4(f%MwY1%34NXmpt!zdB5_gZy||ft(^tK3MOzScz(6#EsRQhrX~wKjb#LO z;hgIV#SOE)QF)Uy$h;Yvm@-}4{Bg(!`4IywC7b{$qQAScer%;4Jq1zWeG~l#Wgo zv2VIxMqrmb552JLOO(#1G*bRl=Y# z1ru%##&DniCDRKM5qfL}{664Ma+-jQz^(^2#&9el2foBhME=wBwXP>!$@K1tvL_CH zlHq5ULa}7YO`+8hPjcyNtn8_V3H(gt6+^^KcoFMMN>>mWfnE3s$B9p~;rBoOr15)! zVFeS<+8Bd{K@NoRrzr1{y@>?Xd>^tYJz7R!m;A{&`$s#tKhu}&N+S#_n2;Zfl9|ZjF@@*!5_ZG330+fzKDERvF!Nfv=CeiO=6?h80ZUbHm4X=X4Pk9QGj3p2W!r z>}t->c~W97tap^2IDVVF;CrbLc|Vv}3_%Je@D;;z4lFT(vUlFZST{ySU>EK`@Sc9) zI4~{sC$qZ&!wM$wHO<#SmQ}!R2q59}1Q~%{xc|U=$g9&;?3*j;5S1uoNmj!cG#A?{#4&I-04Nr9Si9$?BVd)!i{!qF$vn2csi2beP6 zm(0r}3@eye-NXup3#riMkwk2MaZ_*~;7P1WoQ%LOTs?%(zJAb!Z^Vm?Dvf1W!Nl^R zmf&_N71no<#+I^=%@rP-dyu0;;$;MO;gJwN2YFop%VZx?TM^B$f(efz3s`tR4Q48( z@scAG!(pbK4{4{B6WE2vPIxZX(?elaxF6}WB#L1L6AzOuAoy<@RJ4&|jM#4gBL;Yp zb6K%60=w|o34hkcHiH{GIAIwp8(YFeRR=!8@-`htSWBZHePs|>-mzs*X0Cu;d>V!fjnU;_*=V^ z+ZhS6@m+@rwxCz70aHE#jYmKE$o7#Mq4tvpxv@P?HZF>Z27Cna*v2Gyd|Vn49_2bv zczDm9>|7TwBd|+8I_UX47Ch(pkYY`=Y^)Cx_;N0=w{7CeIqt zqba<=hIE zm&Tu*!xQOJOItGXe5#DVF7q;LINC5BI%i7P?)dYB_DrxP#=BD)Rxp7p2Ju`kJDbp| zatBh=BbniOjv;)OWNfcE_;J7yR`BiUz40)&)``d19`Z-~W~K|N?ab!~k%9?4FTz)C z|or#YB-o7 z#c=a+hvB8(Bqv8sU>Cki@H4omPCMnO3t1hmmR*T>CJtX?3dM?EyM=*|Jcu)kV_3n2 zme0h^^^SvgqoujKz4NyTi*I<46DQ>acHwJ`zt`Szg#-P($;)mrve`aNBrkCS2R;k9 zh0g-=nd-h?kha2`TnLvF*o9~Qcvj#pJ5|1;c^;P4^4uagX9>A*Rngsx?wA|HSN%$vTk_1^gxP%UQp07b3@ezx zIazo|KWT9!pP3|nUDXWdi;im>VYmAo&U4&^f$9}*k$^YLg#pz7ER7xJ_lzpjvi33!m(XKsx$n3t+3@ezx6*Bp|n)yEQa6?bxxIRusV3)jlo!P#r zqIHr7d83JESiuB7BK+Pyce1d&gER3?<9TaQB|PlHmGk&`V!#q%^H(SGcBw{IQx6mP z81i|X-ac?I*Pghxl2_rwuCO^g7g>X782?l{ANTz2A^y5ONx7TMu!0Hs`8cd;1^zr6 zqQ|%thO7HsuW+aB{bOO{mjA8vr>GZTEniVJc4vxg&oO~30P<{zzXuA}mhkVwo#n?0 zyYQLi6eoW@+z+SwgYK(v>$1;D2m})ueb&*t{|&W?7MPC zymHW!r2meU)t1FX7Oxy&1dtZ9 z1lD4R9o248gPV^lFe7_<$xsbjHvMn?TIHPibmbX;vh;z#aAjLe?BtafH!e(sY>m{a z34>bp zT?`B>m>A1z3;)ri!t6%U+jgeOEE@CKpR7GA$O!E6;4y@(R5qRxnjrFJW+cN3Cc0Uf z)1Rsgu*s5$h7%6bKH4C%XqueBt{pr^UT_ASPn3x5v$xQpp99FDX)5-@uo-Q|zbS}s z;0q^xno;whEa>vw=YMKWb_?4|jT{2W*={O^t5ISib8#~|g=T`=3~3zBp?Ws$QS47% zDnUkImnT0WW!0H*d%i^MYkHIp(FrDp!y_41Fma=?8U3A_2@je}gw=vWw8MiS(zT16 zz^;}&MinPie9b=3HTgG^o*e5eRtlM~oAe1Hk1uiHSdpF~uR`bz8Xv>;C7!q}WjW7=zXHgrGj4=s7C&g{yDQ+(U9 zn=zg7GaK4Amd4w^Y}-#?zX&9IhAH_v;s2*#0@rinb;D18qCxH<&|PQ4=c;z zm3jjpNza(JYL^2?a{^!xuWOoJkOL?3q!^EHeWcSWTM(n8VGJvnFal%xp4W+6?=2Ax zA3UT+Bbt-PiQzH=yGHOBK^{4<(o-TXK737w&uu~6euuH$`9`#pKCg;b9{|5P7||xW zx!`r5*JtImQ>h{sUO$qEX37_Ig4lvIeHzBFf{B9*jOgLhIiSbuyYp2LZx2(S%fY0m zI6_8X7p@4;R~B#mLyHE762}vvvRd(&n0VHRj^cIW>&vAW54L}zEgyuC>$6(Q2<*a@ z=J^=1iD8}Zs+Q!EaR|c-Ch&RUeYiJQX!(rh#A8^vjKD5={aTm5d+5W!AhIAv$*_V6 zd}bAj*)|QS74;-P-^R)a?83Ekc@4LKKU6O^gzWp)lIdJFqzSWg!LCgp6u&W~bB6Nz zjDo!0AzzEU{14sxss(Z7S0b)!hzX^a5lt0xA;CnN`PrZRh(7dbPCm{Kml4>7>mBmU zMpj03*9t?)j+jt}6-?mkjc0B-tEB_%gGhsxN*RG&@;ZuXgXdA@Z-4Ud0fAu!6Zi_{ z`_XxtXx7z(n1sg52<(zq2R^>)qrCQfs8EzHwxVsOdlAbPv9e=@ z30$#~=X7dZMVlrBl1VL9G6K8sndQ&(2A64Rv*yI`bGYoBV*=OFj zNF5*N!p6l?41a?rb;}#IB#~!B7*;TmnPy0Xt@B{lA&HpU*qR2d@+MbeV`MczaWzs* z^9*LegifsRCHwmmS!Gg8;JT*#JAJdG)ckxfDIFdmBd|-}s-RupXvvHaa`;S3h80ZU zYO8!!W{rQHaJm(Ft`j69u&c<_kZ$Bvryu`Ub=v)=O`Ww~7@6^|Il~Gja5ZX$f-Q5c zb1V-d!5@NU1a`@5%XVM*mbSGDAudD07*;SLuWWs8^gTNCXA3g-o}9ogTnU#~?Kw7& zcHsRI+b@x_ino|(XKP5$9?XN@dD2%e|Cnr}qpr3fgPyjM5!i+6^YSbn{e$bOmqd~6 zfu6FO#kd-=L7V}ND$0iz52YB@kr9w|n@^GS7&eSu8-;K8th33&zL;sH)|Z3>lS$~Qk5fnD-Fzo(3?>zyl* zu0y?KHH$If(#wDj{gVd?WB+T_@1}L$_aexEoIn|YUATTR&$eKotn&|2kx4l|3@ezZ zUu8gpj^}|#mK5Xe5XZU}`yz<$l>ixmUAW>g|9-cU)R_<^N&fD`u!4zo{}@p7m3a`~ zT#7NILs;GXc@bpcSbrITUHF>jBP^4$=u4$9*|Ux?{Kkvlgz+0IUk6$GMeIDmi)1Co zGOS=iUT5^aZ)WZ1K5nGf{RA0-UHBbWq3D19u&`;p6IpOs!?1#hQ@rx(OpipU{wmFw z+^LR(V>9iD_5KtYfnAlHC^J@r|3>M(_W8%|!h|+1<_7Y* zuZ5$h2;KNt-w0lj4J(-F%-@~$k7=O9Lz?aDymBDyJ#Irn@9>(%T-muT3F@!90d{Sj z>OkA1Btie-647?daQHafhAeHC#;}43EhpNZ(fl7{XC0PB_P6oJP6Saf5EW2D5nB}I z%&3G)rwJ-{cK`;0h~3@Y-NBqW25YXa-Q69#wyVD9JnH`L^X#kF{;}6J>wSNo@0=cH zP7u{W5Oof(CB>bKYHc@!O9Z;^n;fav>4xNF5kXkxTSQGfb_X={-~V_rdV`3{&gE^Q!7o{>~x6NlFu+PaS?rSKgG@(*LN>@ZOOa%5$Xk z-3BDCtB6s}Z=)ybX^Nt87~`<(s6=V{A>~V_@SsauU0ri1&Nis?(VDDfV|2SbvK_!ZxYnBxVD?`#D*sV zFXJZyS1A}k`e!Rc@Z4YCY7Y(|TFK&?HQ!qu6(jC!0i-}p(V|SN9m%0T9W>uV zK@x#3Y>&L|)(9kbs+ZJ8@Lm2N2B z4`-+#A(uyu+(XHcPsOy~+J;I5y09PP^JLB>lb4>wwGdvfP(cFApRZTz_)(cQz)|b9 zxsgPmOMW|;v*=?b=LtvcEnioJ3KCe4`TBFaA^P26_OCNQppv~*0N^d!lzZElEc{Ye0fqi8i>pe=0rjwSrdu3}L7sfjuAJQ#N)CEjFv7*1C#J zpldBZ&HT(C4M|;l(eGZUT!c2B<)-ZkuE$V80!Jc#mXN;-&2VNV!WD?SK06Hq_sW~$WTE7&qC*`2R6+2wcX{UP3t2Q=<3B|JR1>2p3V?!`#KeA zPYy5&(Dy5QboLb-PEEfxxS!;)}ygZpbJl(=ku@r+D<-JEuw|g zlFy?@Vt$8`)OBDmx$7fh)V{cbl>Kb04Q(nD=)$w|TBKv@fm-B1 zv65QlQXvc#B=8RT_rY`Z$kc~?@6VbtfiAhsOW(PjsXukry7miTs33tk&1WZs24@EI z6Vpo_k_mKS4dw5aUd7Puy*;$SJvFKBB2kr>|ARjok$n$Di`u8wqvu|_YbD>x1iG-L ziC%OGZS>4j+rxVwRFDWwE>2%_$us1ek>3F&atgRDDg1L6a40p!0Yb2ilJn?E^5ill56$2x8<}GoBS9mNXWIM zUaRt?7~cod?MSdhpiAd9ain)B$-Y6vDAC4^6zWk@b9xxeP(cD~44>KWx|+;Lu+<8_ zj*tj+*=#9JJ@~5Mk>*vuD;+kH*VSw_n{1H`6(q1u^V}`9otC*#Njt{d`Ryu2X>y4$ zLfg5Lmi&yc-}t>dtS?U{)Ul({R$*j%KQWK2!@70!W6Mg~B}ZR|3KHu$5m7UgG~Ogq z9%br89Zz{^8**wAfi5g3{x{B@rPMcjCCzoJuT+9aY~(R2<_jfNMv53udd#M^lRdTJ z)fI_A7nUZU%X#Gwy6<#lt%+8fp@PKa2X@q^aR^C#BicFJ{5w6pqcT5*PbScXU+DN) zd*(cOvE54RH7uI#=CvVLY$)luuRIyix)|+SGK`eqIqlDDVsh~?GOdHi-9mLQkjjRY zRy8S_p@M|U3Dqr(EbSo(+HeKwG{aW&z8E19=z8RDPfr#MBVGCnqQvwG~C7#p_<`M6`hv4mDRIfS8t1m-%Qf8|kAuQ1A4 zv(E~U2y|f{@>6xa6LjZieARD{04cAKkV|lW>zDeUd?xuRZ$F7Z7nUra1DX3A@wsWG zwdxuz^;eCC7N?i%gpxvQ%Md$+EWPlGe^D${TO!aU&o!vwJA;nCT2Z^q z=S-l2gj{#~zDlE$r|{?9s;Wew3ui{~-S^H~Q=8VVT7wq#r8yHwOyDyh^4E_b_L`Un zuz7Sk{a{qkUgcCJ0$n&?ga0MmWC3Zv%T_CJDS}~du&=&7Ey#1UyrUbz7R>izeKD83 zzi6wqJrW`H)JWXiYDb%N4JWIUM0w=Rl}e^IvC}d_!X*M-*w6ECUe`8}iMwsI%GshA zDo6zLkzwPpaFU6G9~dUD&Vi?}M%Lk=A-it-=A`qF`h};(eu} zbPFF>vfULi`aRp08MW9+JDwgW5$M9Q;m-^omnbQrj@q>cjifOOiAOxfd;bVB)K`>X ziNT9}S6(ZlrMzk&5$M9wWtv+l zEs_OE1iFUtU%Iv>g5;Phh{LAgWPGTd_FGsuLj{Std5ThRzFyLMq97I=9ZbgWv(r*? z%LKYwCl;Y;o{=Q;i6H8ET%~dIt7yCZycy1P!TKuCdf8ztp>t1qYL~No87fF%j_}#) z`9@Le4;8c{2Z=!L%bm3eh zJ`*sgwsLuEY3=c)hSKaEBzp7mSne80%Kjzts$vXNh7K*I1*Qc_1iH4*v!ydY6nxElzWdbShR#a<|owsv{j>ND>w)FVC zNTM|qF$(VLPpqEVX(L{QNd&s&yNcgEl5|;ER9no#87fFD=IQXh6iIR?ix^KHS0V}g z44&ApArgTuoWsO>pEwWV?Nma0dNYKfg2a1!Te_0ZLTX~3h14R@Nxy#HNo(Giw{t$v zDsp-xSrO?$(1mlD_>K-MYUuOJIBQo*1Ts{R2%cP+uFf4rPOTH^nE970t(MD8d$6aT zM4$_2J@IFT&tw3sCwx(NBqKL~E4^qQqLkIKgD*T$S zP~f9l_kLA0pUK_~6(mM+B3H90((}3?hE`ZZ$(2gl!mU0Mfv#I4Z0OdcD6%V;Sfki( z;ugAH_0n2<`!H0HkY{YY=ow9q)$`Cs%+(|UT@(4Nu!94mNW;7$#^#ZsH2rsXtzo{p z3>75gytEp#coJeKlwyf>#Ke%czJ^~q(mp?sGcRFJ^3;eQF| zEJdQSwD)*KPhsz?o>xUyQ+ki)<1-yf&|tW{)WYU5INGvPK&P> zE)nQj+}xJhTSbur%S4O|R;lEOlbz<;H=Lm&5mJkq_^>Z|m&aanyB;RRIB={mZ9OE4 z1ZJy1Fh}@2vd2Bio_Kq0#Ii6cDIbYTtUceVe*p6Y+_ z-Njl5N;MIQGrYFXei%hcw-Yg@mI`?>pQk8G8-uYPqHDo9{FKKrvyKWf#of@TadPmVZA-0$o|W%-=VUCRT=saf^(|R8?oKcCJ8% z3KCeFe637BzQfZ12W@H9V2MCiA6`QIWvuzGkeu)iW~d;6wUW;kiS9yz zT#ISli-$=By6!54>6&LzHzQMG7ylKrN=wy$9rLj?(JU3?wO`}X8qyJA|G7ok#& zoEvQD>-cCAwx-Ni$qNyoF|uDWl|K^h)+&?dbN zk_dERIq|yt#YDXMyQM`rgQXHgA}_Bc+m1yOQ%Nx!x7_a1`h~U5+Mg@sGDjEIQ2x&H zXnoz~tg}Yb1EiXWL~~x-haQb4$qph$)wq$g(WMGn^gSXG=yH8ih@S5dP3C5blwUhN zfzGa7Q5%}XcRT?FiS@4wQKu8pWQVbHw%M;Mjs;6;%TEVM1iJqIYEAX~(d4UnuJgfB zca$@^N@=gp1u;~Rz>`g}bODo9|i^Bv5xF=gH5Qrh1>K@x#3KVBZ^!ehvcR1ss|oxMs$e!5Bo zUm=YO5?D@rCP!R-;#9l1RwFS~BGA=fk~JNv#*o;)B8Khbh9u)dG0lgs07V4}EGPcg z-E&v6tVv02;D=x~rcWVSvP>*#;ps`X@_F;0O2?AM{2KGnWE!i?Q3C3g)-ozKl5!Ub zoQ=0LARC|G4m|+6u*cx<;jTN8`h3Qg*IBs)|KKH< zkI&{m=p~mXpXt=Rv$E&_Uq^qmA;VHbLSApc)Q_33(wwzo$M_E8P&3elWyAl*S;)__ zkM+>*kJO~K8A#yz2ENjw?kakHMkUSZBmcU@WBgdnfi7I9!T<7l{DOKNxggGy2tFxQ+o=UC3)1sx3S~SuZc`)PXt-6(lfCyk32pM-SET)LL~^ zBm!MH1E23w(Ab&!e&p}^4%d@bS|CxHuO9gj8%w<6#0rHAY?}T@2N$hhjsS^3mprq- zaN1HO+0#)Qkd41J;J@WEHkQPX@FYk$R4hcbCb49Ga}lHVnBKlFRmy5N`FRuT?^w~c z6JyEsQJzGbXGJp(#gfuHJqfNu;LkoeO!|BN-5}RNK63JvA&WTC--2kv|Gg5YM{%0Z z-Wj6N^H1EhdVgyYfi8J9$C?}m^d{5FYjeu`NozBZi03hUU&oTyS452JnPsU*Hh1m9 zy}A;CE}XN^cU9Stx@Xe|C+!0Xl-8IaaWck=uKgNITHg~fCNAxtIiat!Hs?}+M4(Gv z3($YYCpX@9wM&~6_vT%#U2o2t%y**vU0G9ig0Hv^+H^z_|A}kyZ~PQKAo#yz{&00J zR?zHv(`T>FuXXY7{Fc<`a#~4V!-CD%JyFwTI`_Bpe`0pX+ z)UJ!${2%WMiRsIRo9Uys=lwi}f-d0{xhwun&MR;!5JM4VA_$QlnLq^zNV)QJ0$n2Y zB8K=CnLq`JpQi(BBGx`A8;iR_1qo4?#a(rGk8zdn3JG)pohcKjh?@N)NAZ_r0u>~9 zj+p6x=M@s@;(28z{$1vr_@|}v+%>yIEVx^XR*MP}{BF#&h%2W933TzhF%#nMWC9hq z_y2fTNI))F#K5~k7v!`B0l%xm9qO3tayn2!0&+qBIe{+7X$yk?t}g15xI2FD=4;VT z`2U-)MO--sDoF4gF%#mhe@>u_*L*Wk{zPMo_JIlzz8L#I#qfnY{BP+{cxjsNO5`8k z>!t2HYcW3Yaf*p@7XRvTY!VgaEOJ#`3xfZ~}b^2`P?DB$^ z2~l@`B6S?y57)YQ?q*}D`e-oH;Ow)H-|2KgO62{Bg zu_)1vPFKj}aP3E>vnzf+E_^Lwi`_s-w*P5C#03KG~J<#Zr{uJ1Yh z|HMEAiSOm{ohZ=zyk22~BWu07k(SUWHnUUJ;bhmP#^l`51uIv$4<`vhO-S|#lWU)e z8KnAzIR3X967}3N(VhJY=#IZ-P@396pPz28x1EtjM=o~P^G*K9$8#jC)7NJv z-|9lEy{JSVDFK=J_Vl5D?5$4MzC5#Y>E5n%?k>c1e+ zwcC2yn(h0#(!u|VQPa7S-sgNLTE9>w+V9WGdi2+xR9#n%X4&V~Z|?6*U-q@UD^!pe z>z7lH4DC%D##r7J66nGlkyDNe64@Vb%6wwght3*r83PG)VZO;Ru%xgA&(l=8`$%j3 z`g3>w)Q9DPwV`r{o|$XMWss@);|SIsnLq`JY0oxgzHFF5?zC-TQLm6d*Wsd%GAA!i zBeVL%S`gPR6{guMgwYEN9cYdUrD)UVk@W9}rKz?fFMY8&l13ISZBa{5L1HQ2bEL|} zCN!y_%P$CYea*^6-<*x2tFBwdKm~~l%kt5NLz+>q>g6nAAc3x!jbHUDW%xV60c9-+ zRFD|9=e_>YswMT0cKZc^uJ%LE>(BPJpz7Oy-Bo59&HQ{N^F*$NnK{~xqyf7=XD+&w znTfSWE^}0n=vr|kwJYPIpJ?~mqGvz?UD(ISF*;AJu7~imwO86k6R+Q@>gS)PliV3i zNvVy!^?Knc^WK#y2u(>(;dHX;G2|X~Mo_*~I z5|XRAMGPd+g}E-L0~I8$l&GSwf1OUwOmAut0||6t*~l?2O>anlZ&!}yT<}5voDo8k zx|OBb*Z-wE&X1%{PHyzCAzv)|E9}(*N@UR5g}do39#qqR-ov4S#QHBI=)T>(^=u*D z7BP@O*S2HB=&|F&^u1B_EeKSQIGASywQe&?-y0PE3j$pm@(iQYeu94WW@8Hi6(r86 z>2zz3>3W&dZGJ(ZtIfsX^lhy@h>FI#)j*=6SG+b4CQD<)Q^ zId6^7ovXB`qdr%lGJy&bV`-Xx}i!>5a?<(B~?GSs6F-bt7t)>g2eXg?e&s@ zJ!tiVRewRC3!hiybfAL7+Ix-ljB`C`XZvavF_1tPKGn!E+-slFduR0{_j3l4*GEq2 zA2Yj?&~bH1h5g&~3ETUTv&n%(Ca_nV?=(xFp${Wto<)$K_i(5nQ9os!zH9gpQaUBn zA_fxZ`uSaEc;y~(1kf7ryT3m_yOzmDQW_}H_n}64V4L0keIV- zqkia2YiiZN-J%4MK$pHgOP_SPJv}kr(}F++iKp8S>*FWH(-ariUl8aznsG*-x2G-r z=weyhQ9y{>&cj>x{GUT8n@pv<)|QmPc?Gx;&bA~BztF}n9Q}o4P4x7pFOKK8xGPkUC~sGXRvb%c>?`YE5a^P3&BniR zP(h+nyeDn+C6IbNu(ybT1iEm?Zn*?eLE^l1Mf&TpzG(g1QjG&KQ2c< z+lJ5_i!AFd66nGjDyIXV$nYsFM??eqdL7?Oc=RWWX9iS|sO1wx$RaK0WCd z1iGdK^`qf8kLtdzb1Vo{khpMTFpZi1hrYZ00t@2Z{s7u!ayb$fl9S*r_U$j!p`in+ zlie{kM9y7Qkih-ve@>t)fA%``-mn^^glA!k7^onD`_s!YkU-ZG-nTC=Qj2`(V`~v( z-itysu6jH<9$$@=vd>Fr#55;YJ5(Vy537R139!|2WDaXu%;jQ2TpJDoneUDo%uqn+=Bp{dj>TbDh@`b^&~ zryLa|HYyo3%O`$M>2s@pL7;2V{#07J@2x%8!u#)$W1xb>fKC~7e$>G|V>h?_1%WR7 z`$~?13KEl_WzaE0J7s3JFKh946cXsdzry4gkx-)ceNzP`AR@Xt%Ig4UDX3^38N#sU3&h3+(Bc@Dbd z=3#xqkOX@2el8lf=$J(eRFG&nr7OMSo15-G`TH*jbTt~D7G?enFtCXJQO}SC&6jZn$Sbpn}BYF>!R>wvx2yi6_4x(1q{h z$H013=uRiv$M3bCd(UniYp6`1g2c>Eo$2I* zFZCitc3RvO66mVivLBuJ{Dq#~!ID5lB7WKik-(OE(LIq~{q2@MGkBfFU7>;mws|?_ z7fV*8LkvH%WQ-$m`Rq#fXZetUYwXF;#^q_dfeI;Fu((AJhr7<;{xvvC$T3hs0(UR? zIe{)5ePjarrIMrb(X<;)3G=Q@@OechP(dOlG9NustQoo0UYtOTPsm81YizB2^klVW zB=2BLqS(R&+R5*^(v&e}b=Af+PuoA0;d>4!W%IV6g(v19Q|6peuMkBp@y9IeQMN4G5qRFG)YFpRpi&qE6Ix%>+PU0?j7Xbx{%(%$}w1%V0@ zIeRpupL*JmJ#QcWfFXly6|rXxy(^P0?*+3Ie{+x%R(mb=^js+`uUSS zDo8xv>OuWKdK0(yMJ@6Q33Oo}Bi|J&NVLmxr?XzxCX*}KS;RmBUD$WYF>o(E-1825 zC7D142|PXK=LEXsy{WJ-K?QfS!q`8LfduZJ^>YGU*n`UiKGEYTG5_tZkib)EePz^w!#@q`Q^nXn+K|aP*O5;K!-E!70!Y|iab7Cc5>$}DbMSsnpbO7)lL;(yJk3Ks zJp%6v6+Gnuf9dBjkihdBeomkZPfCypRPd~W|8`eM$UDAc%JH|*h5NLyx~C z6R048JLUhJK-bUvlKpSH&_Tx!Di4AeDQW2mbbOC2rI+nOWz6mNv~j(wN}l#&g#xA= z6(mS#Jk9gwoYJWdao> z^nII{ua9ML_V3oU4TZxZbtY^GJy&bxG&Pr z33Oq9EEA|8A@AIRWsU^8@NKjl1K(`o8CCd8GJy&bc#77~33TDpfK1?X6h2?okMBv@ z#9>No-6)G*6cr?%Tuh>UW0I7|SwX)b(6vnKLoYT+P`ZAuZ9$-d#BULU=-&OEmA^Zw zzaY@HJ)tOnD}KNFPLnwEEk1iDuF4y1?cR#1+{T3N(E1qs%1 z7**2TmF!#d|AIi*_W8;5!G%x0pHt5I$|Z;j5_3MbVtRTy4LaJwH({ioMGPd+h2Qby82Ake_kFXT!jg2bbPooRCZ`HC?# z#iB(afv!V`yVJ~s-O7T6(=7;8kT`OwEsaatt(0yv;}-Km`dr5BBE-x^SGA39JpcCkNIynLq^z+z;gE1iJ9- zRGB~p&*#M0GJy&bc!KE933TE2Pk!Lk;n+u|8j1 zi+|_4-14=^f@roWuRACB8ovK2NQl*+g66-(d$^YVLs`Wuw(jljK9dM^iR-w07VR$OfAE@}%ZNQgQsVu-qCGKm_P zZ(fYMsF6sZOI(W>-w095N97K37quQ0Bu_pO^KK~#|7C2NlHPc2bfh2C@%wFC)tiE9z#pPHz} z6xr-1Y9cB~@EU54@lS2nPV}1PCTcqp=n~f=#y>4eJF+*}O|&Rfkl;>p4E}Gt1i4fD zdbgOHXp2aoOI(W>-w1v;n&&FTRkTG^kl-mc$KZF(WAGGf*O%^CCfXtr=n~f=#y5iJ zs^+}&+6vJYQ9**YBy$X&`#c6OIqj0O%SzD}kwBNY7BRjNyzOZ{_oc5CZ4nhDcuO+J z;I-)6XrP@wK7XZXi%6hLT#Fdr2;TOz0R>O26m1a|BzQ|Q$N09x25);>rh0FsXp2ao zOI(W>&Dwn*2esB?@~#piCn`ulyiD^rsHsl026%yzY*Z)h0 z=ymuwXihmQNbnp{zK?@EhUnS&IB3pYB+woIR?LL9)qWt@o})6 zXp2aoOI(W>-w2+ojE{q^qAj9=1aC>^7(DlR3|?}KkArTaEh2#~aV=teBg8W(9|zq; zTSNs3-jd8QcrE%i8ZbT%x{0=k1iHkvi1CdO&!AJApKuc+4k}3Sk;ok5+fHoLuQp)0 zSHCsL!DGgiih*>c13#njx*H8ug6P)5UbKC3E?Q%C40XI>N4M7#tDQR5@5U0#ejrxX znQBI#aC&j+Nb<1G80BF7hP2`6405i;W@S>HKw8d!Cb@oig<>)dU(|sOe|(GdetBL+ z1qnKn(44=`AiJ9!JVTl~!n80Ihh>mo)Twr!1adht@q;i|kIfChzCh zqHRwl5VtzH_+P4hCiP{he<E?<;QR<)J9jl0mAQIC}MpC>ADgWFO% z#F@ORlg49obRNXCtbA${FKeUuXMR@Bjo*CVWX;fnuBX%ClT3=w%yIhoGimhp(mF~; zqm{hOPt@wkTxhf!K5&{bvDz@&)VZ!QukBfV+xjH>x#}RLT+~y&pnoED+!?Ffw9Urz zYE+|87VTR|d-A@uku$LpT~q6$ayzpl^$xE{LpOd>rk(6gHJ3W{_<*xY?)+UjQ7~^U zHeq{dw)Wy`BhLy4I_|tR%{#IW_2JiUCv514J-ukbAUB%-es;R?axYGlWEI(v)5X~0 zmv;=ml@4^skRr5eyKZ#lY6p7uL@|1{LkD{Jup9lHkdH39)`1i2S~;=!(~c}~{43+i zR|kGdCC}lo%F>!ad3}@}ZOdXh>@cP`o?_tKW1QdXUntS*5-BW@L-aZyEXf8dU)g&UrHAF;(J(=>FAw4EdHUl`q5^DiZugk48ET;nVJ?%V3AKW)o625 z#hHNm`WV{rdJ*!x(@h0uA@Ue`2C#sn)?~+qF~;(Zp;WZasQWGSDicG@*OR++(T_I| zr-Kv65&w)1Jg=TVPG-L^{>#TdSFmwzP!x3>66Z5%Q6in$K8im56uV1YZ<`iP&$$=e zGsL$qFTq#&yRa))HX3@FIHStG1~kvrbX~Y^@Aad%3d}KIm!0cRQ#UTq>pbqwiQsWD zto@uktoY2TMs!p)I@|k}zN+&8`l)y|dN1zNEag`OB~wpTS!L1Ig8h3>Rrx<~r~ z{H~_#Xv3^#Up2POk_mKK*Q`sQZeRO7#$SipvhsE(j24aK3{;SiQ|?>314|fuz&P$8 z6X@D;v>tulW7+o@#in;;fA!IgEW0=Z6(lgHO(q|g-t6Fo5k}VGCI;ykLTkk}GXK^m zn;?33M`!c($UMQ6P3WV01oYu4uj<#6C2pKzxF2m|pn?RJEI(Cu=|EP!oxL$+YP7L< za3sC*d_krtk3U#AjenEJ9An_7a5~#4uV0)iV$^FgfYt0?)2NgfZJ>fg)T%HV72^0k z<$n45vj&U9jrC(?0$rFses1`@B(^nQCOum{T)L~9W25NxN*gmzKkGy19gU=Y%Z@eQ zE#Lk7d=fj^e+6w?Biuj*iL!Q4)bDKL??k`A{_OU}hN|7}SR-n8Fg@uQqllF2N5iPy zLkIJ<^~Ffq{a9YbwL?#ya%1EGR%eQr+Hp&)feI3b8imu;leT8sWXfDPfNgwIK%EiL zO(M`$>2MTn;W^H?dWL9&G%kr9a(PDj7Q}>DPx9JvdbTxGvnt8WT+Wo@i{oU(AKk?L+C222GS!su&Hbjq1ZX zg^f|`pRR0dZ5%|eP3ffc7@J5F{DWxjrJc<5x{X0}*ub{mQ(mEOSJvm)HnsG^%Eq>G z{D}=K%S1nD?{1d*@d-3Sv8D? zTfOL`2anCJ1-U%v`b(dck!SkS?Y%tdu_3R%$Jm?|#Bxrx)0_*`G*CezwWAw#+V$l- zk&>yfd!JmjnK3nt`^z2Z()>20QT1L_T<6rSh$ywpM$WWu(cI>1lj*^48XG-s5?Qst zo!#cH3&m!Um~}q2KuwfMmmWc?qVi>C`jzR zQrwk!nsABm!NxcnmSFO!62%(>I_o%j?vc)Qc{_P(fny-O6U#=jjVh6g&{c zo?XcxlVfZo0$rFUlWCS7%7WJ=ll-HLF;tLPGS%H2W9%96v@~cHn#MSeifeI3X<25?(-gt7e zNERnTtF&cPm&K8?agQYeUALYRbBxk^7$=Ta>AU={<+>#AS;3TkYi7ZcG`}jIf*gBm!N3mk2b+sO~hE6Mt)c z*}~u2l8f2q8~FTz&m~BkOwCwtc5H4lqNpnjRFJ5!vY|Ofo>mih49{FWS?z(%$nUY+ zB?4XYU5$)SVv`CalY6;Z8FABNX!*NiN$7;a`rLAn=HDIAqm;$d(wbq3?C{*yq{{G~ zQaX^xJQ!xCZ`}&wch&U%0QM-kHCf&wT_VthPip)vPRA7Hb$Bd!mu&6Z_Igu#Z1fm1 z=)qZ^{+D9Rzq=*czs~Xp->w^0tZMEjag)9ST%*8MK^6AvuT@7cHSSPwki1S>3-XpUdr)&-)i5^ ziH#MR7}Gn6m28nthK-L?Q9)w%^$2tB9y{R7V_Z3r%x*`dlMtW!5`iwfTmBa3Mlbdv zYa|(yXN_9FZ-Du?+&V2#hPpK}UndVAtK2LRO3Ut@Np3A3#$!x=8plTF97Aq;nY5nP z)y*#NoA(r#L3Pa6>#R;G^55s>ueN5%uSS#p!GEf#AW_8rTc5b^@BKW+?>6mOv69>APe`{~M9Hhb8D(36ni=Qdu!>iLA{xgV?SFGA< z9j~%7H7<}z`S_XiW87%}%<1G_gFNJqdk%C%>FH#DWjm5|#euHvG=tuuv5+o+to%%WqC&}ln zNPLS@l-$f9wcnTEgjXGvZ68re{dCk-Lj?(kMWyJV3#sI2+ftlZsH*Jd6iw|ku$=J=4T=Qo#HR;ui-ER=6ZfyHWMMWZ{HHw#qC9q}BR5j_qbrs)u;G2+IJHlzQO+C^! z?Kp2A6UX#oZG)<)i+jyf@l6WOFTyu3yk0fw$ugf*RmXN-Aia}80#_CAS~9&C%N#H@a2P=52rn(|#iHZsmxT?TpQs?wweotztIlC;D2z1rl(uBSW4&xcd4Nsu-~epf&{J+Fqzsoc42vgYpEYhdn5u~xQf^ z#hI%(Q#Rj&0koaASQ(erkl$68Kl(DKQWe$w)6!H_kia=?Ce!je1DRgSRrQUjuev&= z(gN=rDl4jO^2OPo&&my@LzYff7KLx;W35|`fvl2NUcFW=Mnwe)oS$kkJ@rUpOUhcQ zmp=Kb__hw;;$du)>Gr`y*5wat)np~#6%sgil>dEho5;?0wpSOBU@0Bw!aFpXLT(IZ z*>WBxRd>86xXTI7#w-*%g07Fb;~Qj(<@(yN>c6Uf^hXN`pNZ`Cq{?4*9pYyT$ zy)xZ5QF_aXZ#HpHNM0VTQ`iu%Si0*np#%6{watrN%`Cm&U9XvYB;A>nPk%AHkuL8k z+wRj4wyg3I>eOT*ZQC(}4ro?ZKbE_Pj(dONE}|yWh>#)dMXq~v`AVIl3u)Zd(`4Fl zYB1Y4_5v+qdO=Y^;>*|(bZEn>dc|>Lbbbct=Rqtt%WW+3cqtL+!d*R0rjbT6%PLgD zxHmk%feI41tEb7d%P*PjyI;WQ{@%qv1&Llm)9LY9ieC4z*bC{jdlFmr#lyJK*I6Ra zh5KUhv$k#|vcEc1GCrIrZ=iw%?uEruK0cAH=vl(>^wtbika*l^IDKK%*Z1!h``OIpFAJN&Nz`ubS^c8NRvmZ6;BV-oyRb_7EJGPK#y|xLmm7U)$)w+On+6a0 zT@^HSVog^pG3FefAQ9-2zp)hE*nw>sw!%1nZi;~l68N>oWXhoJS+z||je;xZO5bsi zSZLdsR?57mv#vQPKiRrzTXyQ*W@BgmITC>`{D#C^)V`*yOoQ{rh?=Vm+(`v@ZkblP z4ON?2(a*-4({eeJA;QhOnBCT=$E5TkQJ~U8iQNokDxAdc&|ms-(u+dc>C*{~x0`*Rq5 z`qYEIF}YE%oAr2JrP#W#6HD#b%M~Vu3KG4JIMA)5yl7g%U``Y|CKUSX*F9nI%}JW z((VJyUj)vyFGR}@6kjddQD{mzmnj075R&a`-Ao@Ecy?1%*)CKDoEfL8h*lR zMmzS#_LTa2jGsiH%lVc{+s@gk+$tcxD7rmq!nQQZuEkZYVl)q}Mr(QBFn>$IZ#v1h zs?ly)*Of6{#dn;R4_dHCm*1*0;;I;^Ac1$wpO(HfV^{fKsJ4nC5$HO1rUosw;fiAY zR@{~Uhi#@h@l){zDmaq^ zWAnEkNujK$qm8!xRwF3}68LS(Wa@n*l35MNuaRkWB?4WThbGfo62S^zv(hR(uOa0X z68QDZWJ*qmVF%yj(GGN#%L83lvi!a1<`6cfh?O?5S3kqLe`UI0^9N;QS^~xSEV%** zjh}Kt$y=r^FOPatBiVz_xwP6g0}WJ=z&zw%Wx6$EAx|EuMLLg^2z33v!=IACwfrRS zPCUl#0`V+v)eZH5Q>uXq5?Gr2JzQX0HfBSX+US@}psP~R26U0r6y@)-V$MXBTpd~S z=Z4znW1N8s64+KurWZN7vr_iU)kYT^Nd&s^t1RzD%lBYU{$8$jzAJyPMMD1i8acZc zt5I{Nn&YfYpbNkDnoOF~hqYSKQVsO)FMU79FXQr8WVJ?5X1zH?z5j8BfeI2`mc`J6 z_dS)4)@^uRjqK8u{aIm%Q`Wy-6?9hs%s5Yka#sK zhR@z=r_9dNj1!rM+p(ID=BwE*uaF3Ik&Z#s;n*Ujv`0%$>~GtKMdVnmcFnz-&&&9q zf`sGoaC&6>EM=mt7^5;K#IZTPCseOm3nT(vEuHGoChdus^I+{3D7Jol?VD^Xu8PsMFIW0$uqZR-+$s|E=`cDekJvW`(sM;;4P} zo@k(QkB=Gm9PP;rwIvnTFPGbq2~}EgV)|BvWgd0ZTAm+opdzk!&a@+HXe)}pWHMzf zug8uRD4|WiIPzaHeh}FH`BO${Fk2H>Kx-2|Mk3IKIbt$(coV_2TRF5v*G5PwM*@2c zKAw9tV{7-{QHR-0l?ZfU$(l^DS#j)qz&Z6|%v7lak-#3qWV+kG4ZAgQo4Uq(oi-YP~^yYdu-2iAZ3N!ToJC?XeazFBMHm@s&a0KB`6Womvqh$?ChT2uS#80? z0p@!3qh^SD)pD0D`4rlbVrlaCqLi@d{hhT#Ra;Br2NL4??dHOyh({M*cQ5}{pS4y? zX-{KY{fqeF!m-3;VpUYuw2_Op{Z6s+K{cSy7L%cruebbw@Ybx&V)$> zx^ScxGfY($bH+t0qWT%AAR(@Q%px(F%0KaAi6b1fW_|1Zi}>Nfk=kThv9TWe^0chh zwN-5c75rU!M#}b`fvoDCk{az+QzFnM&w8oWY5@ClYZGJI`pVLqB7C2O?|}Fl$QlEg zlT95Xq`GFHf&{*q;&W@a_h(V1>Kav!#!3Xb@Es6;BRrr#tAEhl=u5j9s339pZ7S{1 z+FyUO^Duu0aAR;^Hse#E;hNQ7BG83zbWEnt34Pg;ag~fhuhI=vkVqdpj9x5JUq51q z-E=FC=*@E2H!{i`93>Ix!goOYi~GdhtkU&L#`%$x4OEcGDlwEQ-4%V}?mu~q`)NH{ zr5JxB`ov6$K-XLAfwao2aeAv@F;C{&uEFd=)4_D@8hZoZx0Z?;L2vFTn7QTk3LW2g znoM#0+jj38<>*rvZvz!10+Q3|>V~12T`!6KUVV=zGxtR+XzFrbi9i>=zciV~98O|M zT{=_$DNPMjkg(}BoW9?doVmHXSTRy0Gm-t-Hj5reiI)g;Vfpi!vL^1`Fy24{LSUP|m7k@h?CCJ- zUw3lmi^OL@qaW)Qzl1j))@ZmGpsk;-FYX8AG_3OdTJ2;J!hEj!fpJ7li;DWPw!T~ zJMv|t-TEZazt%tX%{f4vN|OD0KX!9>d*U*2ih(X)mo&P%_7iXCi0gWk-!STxYpCzI zYohKB*)@Pg)~iNhe#5Ey%+8-~pn`;)j+bK-S;g~-Bs#FWM4&71-EdlK{8gU?i3X3cDQgIe?|qPL zIKP9AZkRzg51QaR+Gr!KHwbB;K_jY{@pbB*$cf0@LzvaslO*q>`xF&ip@1tF_^g*z zLs)R1S)@c4nLyV;9($H^6`!YPM)4Sdo`cz$S$)aN@#T%F&qmN|*6sFWxz5z{+)bzZ zJ5KbSGjfSuX?!{zw_5exer_Wt_KZqqP1k1;cY7ZL6(sWBOrwRpaw;G9ig)^%{2R;d zvKPtY^AQq(u8tGaXp6&_eI0E@-`;rf02bBJRxMMblYt5nxB|muIYpRKfy;0J~`Py1qpdI$FSNx*f#rmYR>J8Bm!NzgZk5Q z-4!KglohYLF)W2;O|L+XT^p=tbQwumInT^SwI5_+`M()Hl6KPOWiGT9>xwG*rLcF^ zT9a0#nov}bz`9^Ewa83i*&Fp!(yCUK2z23hLzC%s;S`qM`%k6v$feR3MI_`}vbcT< z^Ql%}FS~BGM4$`5N19A)wVv$#vQ*XmRf>`C_COlnVT1DS_3!%n0ZBCK)HEgE;>-H# z`9o=Z)-d z>j`h?H`V@1`@FL_F@b-nZrLM1eKNb2feI4xnxDy2lGx41wbk;Sb4dicGOW_+m&SFK zm)VkdjBKxyS!(SvYS9fJC@M%`3+D6TG6pkt%1#}yX_iEwYg6(Fn%lF0GUsYt9;02x z5cag&TQWX=JVgZwtTB8SkF24rV2^`j_3^$s66nHj(0tb9s1%maU?3^v_sItpB(P5N z^|i}VSg(yHvc8xXK>}U!x9w;5QrMvm5sJU}2?Z4-uodtfPadVPzg_2Kc58V~BG4tD zqgdiy3JchoqW2iSUOMX)3Aue-xRAn{HnF0uGWSXZy6{9-ld1o-6n6Vv3~f6tOGgC> z`5XQIqDgFQ_HJsnxt;YjCx%he*rm$iEs?sDmPVUS8L#~HxwyW9*Y?-1HY?XW3-K~P zbYTFqpOB_*s5gz4n>mEm;=2nKSeq`YYM-OG(LbO+ z9rWd}vbOtv9oysh+kK-F>0UWy75*f#k)fSQ9?lkKXS`d0&qK$lyQbUJrTl;T*` zgU6`WYB00z=%y|SC`nO40$UpY;=X(cYm+m-I;XFuAc3wLD>A6V!<@d;66f*xC3*G_ zWsfHBB?*4d6jYGFmd584Z6C_QW{x5clV%en(1oY#@VCzAhqAiaL&(z7D+nq`;2J!W zY4+HjtmWa(s^i+x2KLUl4ibA*J}-PxZ`Qbdl)Aisx`7H3IPUUqMFab@&mlw|u`o^| z(1krJpJAGPAZv2MMP1%F)<6Xbe1716rQS~BGiwT{*QZvJ2z23-lgZTmelnX~?j~uz z!$Vp#iUd9f@ijk32D62)mJw5t0uq5P97XvYuZlz1Ul(J^YMVj^DoEgy8sDX<+fY{L z>TKVnUAHL`=#oe0n|0z?i<4W_vQ-Sj?Q%RFJ${n%@_7yFwK0KiyF68K>s^6Dd&byR~XWTgv9oK?gxV=%`e>}@T1&M|p9cfJ06-v(+cAN<8+>~{@xl8q)d_*G9 z<+U@8pQyE8ao$^o6AiaCXC<6Bs&zUXHc&xAso05*AGbppa;_jJ>Sr`zE)907hxeb5 z2y|T?9#3~IJf*}85oa7e`m-7P?6*;kNDe_w(@z(jsBf{o1v(jwO>^BoX6eMPEtwl?}%t?G3h%eP&j`^?+yREgNR}V=9 zy2KkcuMLhQ@KA(^F(80#eRxUj>i4J7s9z+FuKG!-+`xg}L8A6rZ`#JT5ZP*5lN0M-1+qSQZmSnp+>;1&mG_9G zr@LHNygWQOadCQmwk!XiYG?nu1}aEw>+DUn9QjCxzkN92HLf9BY5Q26IsJk}pliXJ zaH{q@t0Xt5%86P5{_N$-PwMhPXAD%3zxHk>@Y#nY0$saCgwjK6jw|h# z*WocdUk9*WrL$`-9QGTiAc3XHbN6U4J7@J?{kUznM4;>M$3b+*gd<8WoBBM)!HdmV z(YbrowSVm})N#$I+I^C;siQ`*myn6;O7pZMFWFm^g*pITjeAQ9+V(J6w)7s*ZLToZ;5q5`iwP3nr5l4QFjC z?N<*ixg(W15?CwwH^>9A>}A4E)&A-^i9i?DQ2w_;#b#{Vp-t+x47u(if#WXkeX`eP z727;jTNTdrt<1mYs2Kb1^>QbZ_W4O89DmBFTboU>eyjdn-^4I~kPz41AGwiyb^Ljm zzqa#XYqdA(l((M@OX7zM$1A=<`f_b{()+XOzV@Ag3jVIR_ONj!2SWmRi~!Y_z25az zJ+t%Kzla|$9IyB{$gDc-Vq`9@nD2c975rUs-D+Q1($g=5$GA90VSOC)Xd^pa{1@@V zh2s_9L14HKd$KaWwtLfg1C{?{?5xA8YNED(1QfBc1G_~;#RAUkBO)TGpdyNrilBg$ ziij zDSY%k=|x5F>I~j_mZ)e!0@nnH-8J{RP|w*nm3#MBO9ZL{Z+7B-jc4iao%Rqu7BmbX zs|v@J<+IkPXh8y3D(H0P!+OxvRm&8Yq*RGO)udwnd`W}0`h`ce_c7#3Pnx-FhBD1( zn~D}BaK(jKFWSF1z04D&>>ssTB2YE<)g<2}Rdj4f-L85>1NZ#|(M17f?cZ82B zBa)~`RCR?Ns37eULKW^%(&>!BgDAL4Ev4*ib7}7q5;l`Z@tN~n^^y7#Vif0oJuH#NP9LSj?75v0mpYIy+VVml*K0vWHP1NiyrMWuK6)~JhOrOd zH>)C>Xq8KhMh$(PNK-BiQJVJ5%W*sr#}MVw!N8V@bR^GcrB~O3MzkRDWYYk?``~wd z9Vc_)qsOTPTD*6%qD=ATNT6!`;eI?e!h)47>?nwN6(h-_-Fl_)bl_fx!bGS728T9Cju zD~P#?RH|mO^59Z=XCzRCPg?9y*fxMRbsVp}xxUAU79`|cGOlL=?R+*>q0SK;2~^2% z@Ko=9^!eIsMSXXJqXh|P`*8j)ybfFA9xk5MV&8t`TyvTdusolN*9Q*dJD#7> z&$*N$h#pg%9gr zQPk_&auFjZOhpS4n8(Db$+TW%S8JUzy46I9K-JXU;e5lCyzE>7E#_IVHQ}^(^d`mS z<0KU=NMI=tQ3TI+r_lSUO2Y4z5`n5RN*8|lT}?J|{SD!xT51QXW0tNg^LnV>N%7>stZ4kfhXw8lc)lO2LRw|G_ z-rAw;vDqsTsKWabbz*E&TJE<}DRZhqW)C^By9fI?)GqU@$m)d~`&QbX|DM%=PiF@9 zs(KmG4i1{sl=Ai1qzrSlA+%`UI3_|%ub9qQ+#Lr&gf8(WW6&<8(u&v8Rn1Fx;{zQV zvG{N19G{4YzBk#8f_%3r{?qajT982BBIdwV1GPQ3Q+ZdUutcEh)o%yhZk9cp-(4F| z46W@*cJ67)(xRmaEl9}s;jz96DSI=NO;=?CRa!dPsAucDXge(~w{RxqbdYi(x;kmQ z1iat&Vs++L=34sPu^uehrYeuRTbFls?7`|b*7p2duy&@GfiX&Tk7|S#Bs3r4GyGVK z*V=dOxZ;kKmUn{ku3**7H~48^7gpA}X674g+r@|dyjP3Au4vEimu}CFp3)*4g;+S! z>bx@)eQ0Gui}t@JLQC_Lo~-tjx`MdqkwBXkPgEWRtI`Y>wk25R#k#&1{VCRNnqtvn zHAf2)SSyLuhGIqI9jH`|jmm(qHxhv=ERSN8Q}G}^XNgj*nU&bd z^S@;q3CwR|_dqFE>briK^7D5Qi9i*WN1g8LWM@j=vOt;8L#}<0kn`@un5MMzYl`xB zUB&-XUzu{aMwn_oQ9fb}^gC^^BDUg|Z4##B1O-k$%zgh{0l6Pzb7uZ`N=L<}2Bt)I?j33bh+C^r~~ z2P58yUPhN;bnMJd)^_*|h883+!j5b4WTa3?VnXF22m zd+L%)MGF#gETko^2UCGjH`p$(DiVRJ*F(E-uckxTWk+rGPUxwD6tHR|J0`xo(1HZU z-V&?AmJOg%WskGx1BOcksvh0!z&E81V~bvg3Lh`d^d+)h%#xFqsAxd~qjia%Ozk*& z2X4 zQ|eMY-KZwJ#BO}9L})=mE`#ao6#6jh2Rr(%rbM7hYpHt`9L*YqYrUmBPK@*(4V3-M zYGn2RI)(LT`yQ9){#Lg9)!GEs(>H%+Zy=*g0-J3tFNjv17@hc3SJ`_qi!fPo5_6v> zu?H({1W~$(SZ8^ou~K;DBqc!mM*#uh9#YJg-xT8d%3S;r=bO)y<(xYE(l*Ex$q`1yVl=&9NqxV}e zkKx+MaxVrX(u&ny%KC`P5`iilu@K*b!v>N~=Md%lloJdsNZ^;ZIHw_TAO&s+S6X-3 zA`z&EL5AJ1qu9a6Ep691L^jSSjFe>NQpodj%$dX%>IG2U|FQ{ zs%{iR3ljMKDMmkn#JNkmyC}Q*uagK=;kbrQ7x6iXnm6jK*naS5Xh8zMki|O7*@Nh8 zO*iFWzo`;|DjW$BIdSt~IybMLvZUE~h883++KTuP9x|8$1{YEuZvHC~sFFumN)8)L zLjpgrepba5v>+izZrL3^fR4o1R#uk_P%xSep6-a_TB41zA3#&P)KQ+d3YNyNkiaND zBChk#0n})AGv#5umJ)#~%%NhPOu+$^RJ^fLs$f@X91aPL`=isHZ#RHedp1|92Y5;Z zs^l^_-PoTz)J967_pwrmLPCxq)U;nedN|fWxe}Kw5vaoGP@SEG9+F z%4g=tACG9n%G9-H7z;~`)~0&U%(M=Q+qU8cv>+iz<+48JNyUD*R@QwgCK0HTqsr$y z;ZCjzmo}gU35)_J*1a}sMTKV6S1j(9lL%B{#5D2ExuiM8_N%Wv+*ieb79`{- zX;(KZbm4CerS6LA5`ii?65DC_5L%SKxw0?fp%lgZ8$|n(<9PMk8%PQLU6iZuUMXln z0^^2>=zGlqXpo4+9<}YGM4&47M;HD$Dvaf-^H{V7TTXVO{(l^m*(389(1HX$b+Jls zY)4A9t*vwl$uAM8syet4KiqmWtK;=U`1snq4IPcGtmN)c(ts8u@Tu!`O>274(iwS_ zq8Vi+0#!NU^?i1s(ibh2v-7G-(f5$R7<*#IWT!&B{3qt0x0Xbp3L^^YbZ4zvQ>WIG zS@7`+28`r~Q48g(`rfcD4Nu?5bWci4K9G=O8$Mm)MN103U=KWsO9ZO$8H$xomYwNI zfSKaAG_Ulmkf5dp?ie|S?L2u!ypN4%x=`%ma?0P*77~Ff%nKss@~I$lFI-jeSn@_e z3liUlw&7o_B3P|YT=>}fEQHEEXrQz``%ofKg?U=U92nh;@`gAlll4cXyo&_JbQ3W- z;=}3XRVU@^&=V4YDvX$?(~aofizZcYQeJmDBE`}}LXP$}-#3&Fv|)JHpqvrv)*ua+SB?47= zE{INNF{wXI&-<3;wVfoL7=py=^_}>`?c>=PPgn5?DS5mwh*hmDbMr4F= zagG%$ov*O);Usz)UTQ7H>unlC3lfJ{bmu3p`m&P`S_>a;_Xm+3XUd!9vn2vmXO{Qo zR?{0WXMZhj?d0&m)Ulq6($Z>{Gg^?~l|%UF9o^WDt+pAW9UMD|7S`#g+_3I#L;_XE zLwoUvl8)?eT}wf%*_lMGR<%{UK5&i}BrdiK;8(f?v$si>Mp2?fJTiBuP{lmoJ&8co z#JQn-R&sN;CPl?98j34P`;&dkCU&i+=QVMnC0hJ}-$t z)k3#G{_&7It5j6`61GuespNs~%HL&^RJ0(`zJ(V*+Nd{cvOq)_(;b@Khn)WoRr(*E zEfJ^+AKQr+KkvnCzH4(61?u;v=24+aXtUiaT963t+>&2f-G|L+t?gaHD)7 zrLgyVi9l6I13iCGCV-8&_(c$T*LI}Z9-hkdu)Ks8B=Fl%d^?YCOI7>%DKjb;kqA`b z*s@rWGNlFeEZbaZ?Nw14bw)z_t~GtVij{zKoT;dzw_@u)0d%tIa%Qt-jDi*mKjO!~AsKR? zh&J@O%ieWrsGtQ296J-M)tv`Zc(R%DsA@5ZKo!<2;%mZkDAhlnN2wCAh@k}u90?Ow zl{SQCd)O%PpIjvZRamcxR;|WRQm&O$2GrhSL<ZYOv z2^>2UqnxD^XiZujC8>YBM4$@m6)^^o7Eez?3o8+6^HsDUfn#SPuJef)>bu-lsnlbo zM4$@m74dXCN7C@$1(hqK_N!{ooZhsO^`zO~{9yU595vam?Ma1MN)}3;-D4^V4 z^;|^@5;%4yR@OWXpo}|Jm0{7JB?47guZUGhWqheoY(C}3Oe;bQ5;%4yMh7p7$aq(6 z6k9_Pi9i+BD>_}i3oYq#vqH*|6BP+9NXVmV$I=+3zN?_*V>KlLRa*Lg$HPg? zjz)?Vzw;C6k5wI|*r%2XT9ClLov5jwCXykpsWSXj1BpNtjz)?($dMwt@s1YC!9(vE zT9Ck=nusm(b|9TQ++L~a@k}C6g`<&TJ=~fk3jH3SRJZkHXh8z|c4D7bu_TI1jZiAC zDJl`D!qG@Ei`;4;%^HxPx1zLs{q*r=kT3?AwVM6SF94 z)NGOR_i?gBpbFM-9PFGr|+)>ej1orL37;?NXUFRh{lbNiVu#H(D{z$V+HJLhkhy zNOz}QZsQfNS4AWORXDFIcFVq1=t$Gyify$D(#ioOw7Jy(U7gUqvLkIMG*(GmQdJ^Q zrKL@)7DV}QZB7nB0a8@Q_jPOX*UNJ8W;5gnkD}jx*o{KQ6{n9yN2?gg5s73w zJAVJrXXAS_Ek0a}n;tYewkW+0>m?DWs{NoYpE>Kj@nn=1Ir3$AE1GiOf?}ucQU4Bc z;GN39Hx9ngi=W)okQdNDHX7{XInrW1+>mw@(%X{Wm71cW1qnRQPsFka@S^W#1;`ND zOCnGuU)33(j$~t=pSta7prQo{`E0=N&)U)Qf!1U^EEA~0XDGf{_OzkvV~f+_)CSVC zLgLi78oW{sQ_M`OJ?><4uMD-CDHEu|_?bFgY%V(*QN0AE)O{+&d&LN`7|B)a;eAk- zp2ifVErD-Tv><^IS4Fh9$2Dkkz0zc9@m?ZOB}a&D{i7PiM3y4YO5aqpAb}BAb-HJb zs?w|Ia&+P12Z=zHd_L#6l2s`GoU&B@?N=2oNXXG!_qD4`KRVmch-sfC0#$f6sOV+X z_Ms(39;+X}q^d5%8Sl5{v@z&@Z$2(j&wC#}U>rUKxl@IG@)o9t7 z;xuN`9~Gm*Vw_w#LhOm@HK^R`qGYZ7RndY3J~uHxINgpe%qT$X8vl?8RPhf@xb^8` zd_fgAaaF}w1KPhKKeasZUPTKM`2Iyy`FD;~W2*%PRDUWFsKT>z#meQ$jN-#{({=yr z(y6*gU^Hbh1~9t?Evs!t6B?YA2vlJdYH`L$C0FXy)`H&8Ju1bgMq=s+558Nhy&LGD z?WpRtq$RoBGo$K54od{8FjloVqw0BWiU}%7Eo@$^c%CfA`^C7tI$f!;wiLarD2+S$ zUW&hq1io3FuH2^vRB=!~svrG9B2e|9absSpcpg5fM`v*#vz|Ak`nfEreCSsdElA*- z6_Ip)JJH?;ztsL?-b)0k7Cvy{{ZIWh4pv(WAN7J2s#)rXy4UzzMGF%0JO4GY6?IDqb(fi^u!Z=`PjnN-2xZsGEmwmF^q~j2$ncY`O%} zZ9A?y?%yI2sKO}rBIcQU5LGU_Uyc8>N<|A2a#Z;lDIxS}bcT9k@luIEl^h*^?cX?R z+$%<1^ejn4r~KcuW%1NlJl$2Nd*~fapB9IxPKOpr=e{CgQ=tQ2zOaeW>!Wt+wDE8Z z`7NlW)@i*;B2bmTNGJZb(3uREyL|*vGC7K-+%B)4p0r0r3lej-cHp7fsc1psgncOgQn9GL* zF0@h~ihe(rx2ttPB2cyYcMq<2?~qaRvbH~}R;xbb)@mNl+h@Ou79?KTMe;d+4`&RR z-9!-YEu+a{+jFCOYoA1*YQd{sd{nz9%{u>Lf`|x@rs6$z7$aMfiWVdqeU9O$27XBQ zTB5C#b!Zb!7SHpuHyvdHRbS6U@O?`bId2)EU6p%sG)0W_XX4ON6)i}NX%WYNc*i?` z46G@LB?qJE;ZvP5_MA~7P*pouFaEKRz1}NDTY+6;UnJG7S5@(G&QQ^U#F?Nz-05!} zee)aIs^ZY_Ui52Y59N2LOrWYpY8amz7OsEs*G>>^^7kg+Ho?m5MtfDXAW^eXJm2-Q zp5CoMSwUDV2&Y+d6O=9?GJ&d@g(7+3lTmty9#sVK@=b5*F)dgbxG+sc3lef1FL$LE z?c6dzxpiQtM4;-@-e^94SCYQ+6|LTFbvc6CZwymno^Mvsf&|756H&8o^`fwbLzNM2 zQY8XaZGz+Ygj^H!wrTl=kFlbB{5TV@xa?c4q6Gw8nI$7m(PVuM7WYRKGp zerm`5G zn49gCVsdDEMol|TG4g`=Dk^HAC*0c5YH+HG79?=@sVGsi+^Nv)+=f4$w@C!5FbacM z7w*@NCUyL+%(2@jMO#1ucc1EXb#8X19doWKrEF3q0#z6rLd*}Q_|u+ahZM_sTcoHF zNZ{^Mu_|nC52_QoP{|mvQzB4x&#^m?@^aD_@zhSJcvw4(DrSsV3h&;fq6G=ueJW~( zcfILC<(A6$?na3~)l;)j?zZBz^MnxX+u+8Z2r9Fwp0X^`sG!iX3R5HkRd@=#m~k(eM0dPP@{Rrx zDq4`37uJ!#`suqT>!giM-h-&9KA2zg^p*%z$*0SATQz_-|H`F~of9veV2^z&^ev)t zt?NsZwpyyif@VuTkib5XC?AFU(S-U-`P{>cBm!0V48=aL^ReXAcM>m~zEyfwNMN5x zv<5w5>C^ISM(_7&5`ikr3!*h>7fp_SAB`;%NqXlR6La*PnvY{AHtdrKRAJc^Csc@?-tYb{V=TJqNZTW6WzXWut%-7}MHSXDqQ846g5F=NuXq>WQeA=s_K8Fs$njyc{qIQS`~JNW zfhxHcJs8-N4&9ufthu~bsuPjGK9T5CzYd{Nol}&9u`+=wjKd>VQyuIf%!4wd z$X`fcpGdsHeIeBA&SE7g*eDUG!YE*(E_v94bmeC#Q4=y$v><_fBJr&zzKZmh7AYex zbBRC|MgbEm2Xvv7a(;#~I4)g93li8T67ejPLg<>;VnwZ?N(8Df3Yb`tVi8Ky6K5-J z-1ewwK?3_kV#KRa2)VUis+>8*B?46#1x)m0PV}JfFpc+L zu25et5vY>mmrU>2gD#X6^Y7sV$&I%%L zi>d0o_UBc!AmKSAkViaTV=VNPN=jlWBDwI)kKiVY`sOm3H1ai%t&$xA!_61p9 zd~Ii#6;WfqrK)H_V*Ig0KD%u#WAl221ab3u4E?;mo2M4vE)l32usMP6edd?pb4&ZK z_3IEvFK18Z!_zjYXhGs;o*{hO?g<%lZfZM`P7IBsqw`ZUekN^|2vjZc9>8C1Z|i*5 zTDx>soz?rKQuivx&zxNd&4+*(7rBvk#nmBxy0Wyv^e% za_C*Qpxk;DEl5a_;B{Xe9cj_SN>tHqriv%BS&Eb1CSNJc^N#DwaaKcXFgUpBrhrR|Du9^gw2?;cXC zH94uG1qpdXc%Ar49U{J)uXrDj2vpUK3gvAk95dP~+V1}Pg@UR6z0K<4;GHU3kiccJi7!>TEO#0 z#Oi3CMD<;^>g(hVQPF|~p4p(&Rc)0-QJ1!5?5GeS5vaoRMno?|?CraE^NsVg>w{Ia zAb}@hh@CHEMI8EOQ;jz|i}wL%qM!=T8xi+$JArmT8>iphbE=9KB=F1*u`{ei0{tp@ zB*T2yOo>1ho;M=K!e{iOO@lt^f8ATGN)|Y218Z%auI!3_bof#=iekeQq6z__G-jPQL8XoqMx9CKe|&QP=)oFSlxE92bo=*q!v6&QhkL4 z_RhqYur7!myh~AsPdg$JsKWYKoIMccPksT*)$i%&q}85*q2qkXJT*;yU+B6- zpbFa+5mBzS4=t#;M;-R?j?{i2fwPNZbWm+eohwnvfhuet#R|H9ZK+4XB{kgk zuG9`9fpeZZUFFBE=t;R3>a{tyB?47)4`5t;8=C#{tr|G_u+*L-fnP6TAIo)53Yh#` zt+3yIOFYd$n}$4@ol@3la;DHRF_e+?X|TSE;ZcwSSX~ey^4ZRQ)X7kUz4zmrX2d8A{cL zja2LJcjuP3MrT^2uQ1CtoTm0Q)^_VF+S)z$!f1ZyMe2bjD^;8gMFPLC#E!$xz3J@4 z;p&b@n7h>ga!4Xjg>#-_H(*K_ z)!pc+ZVW%6q6G>3zS8NE#A%yNl*;O^yN4wLRXFD<)@6){pvzX3)jXH?t7t(2zpum^ z$O%#8_wFU{kVX=LDxC8aYgiKdP^oJVdCJZV6)i~M_mv1nGGEN4E*;4W-H-`X;hd*< zR%2pl#A0vWz5E^(ElA+^mFVxL#89Q`HS`vK;#78+mqiuMd5Zd~bSyoZU7XD|-=(4j z3H-hiCmfZCrVr1bGPmY?Bmz}9=P5>`Iz>~{b-5Mg-3}EkNZ|LC7+Vr&vPOD0P>xMa zlL%DdoTuo8PmHGEape@|yG2C{67sj&o{@d1@(>55M`M{l70!9;bUWsXFX5*Z6&ku$ zMGF$rIbS-v$+2|lNKIwS%M^(~6`tTEBI$JLM?=fxQI^~+G_BcUW89%)(g|Qlg!UTC z2Xw7uJefy}pP1n?j5d8J%QtMe&+)%dC7(C3ZTv8*aBu-Xv~Lkd3lilIkL7%%yK%|r zlETNLJj3a2;W_+UXiJGem3*R3gW;9^qjHY6}&w-}QVJMX)#JgltglwTrHg^}jO_xT`K3YvRNaSu0_BFZ6w(Z{)-gq`ALfKhboNSC!!%Hd6BD1%DcudRJ0(0G0=6oN`pJm;PL6oCg*Dsfhvsl zCw4DW7uwfhxAN!sX%#I<$fLE30s?7Cu^r0VIeR1mRdN);TpL5^MXAloWwR|(G(;qD zbXfGS9)^*t$6DpjgSircDvb6hdiquo^x@)C#iHY6DXJq9IKwX@TDOQMgY5#vYjAIg zKov%<6!TFTu~c8oe^lD&BSoh~0#8@c={8*LOD`@=QZ7+di9i*`(iFMmR(~pYJ6U;M zs)!V26A3&kNt^-tWB~Pb9imLWa8QcAhboL5E9Pql4Wx=?BNTs1kz&dsfu}3!bh~FH z(fo?tl^20UB?46##YLx^xo;4SYu-*-R(6$i_7xI%R+3mO@^&!Y{Mt}iaQc@NixpKE z#YOD9iylhNZ{<-orFLX!K?2W867Bi1q2yJPm{N{Q1gf^`$MQo?f$0@4uiq=yGgKW$ z`=?D|8u{IAef0j3lid=oV9<_XmL*5qt`5`^m(uN@4b~MqiltiG)l+N-Iw!z*|p_voibg^287E@aDA^u-4erNj-YJ;F?=%8E@ zfhtov%ZIokgSay49ddsyT1;uphj>nUabMX!#9bT2-P4?IXC(qvrgWAM@nj9+39D8; z*RMs3DXsYs?^`e4Pqq*7_6&s%o>1HOnM*k4;V$sls0TFShhM4-x)&VE)chZ#hU=SBRsu0e|_t^KbkS^5zpJXU4-5T(hW zmBS)__7Z_AEnO+3&gv{5*#r|r4YVMU?aw*OhbVvARS9CNM4-x)&hn9c=Zd)VnrJbl zwg1h2Zu%@A*-uvyPgf#PWlCrH(B7a{4!!%$sfiX-TKnJZ_n++}JC`UTmq-MvOzA8i z**VcLuiM$0XfdTVAKCdh+edb8H;CLW5vVeyvwUQiD8rCJxoV-sl-7J?m&a@$*`?MX zO07ho%9PIXkzF$wM9okOEvB^QBfDP7_K{ut7)0$O5vVeyvwURNa0XGs)k2FYt@+5V zAG3Xk@~73JhAFOg5`ijHI?G3PO>Gc0buF}*(wdL#dOq7nc57e|t${?K%9PIXk=^1L zZbdlPLW?P_`B2|AtFDz7EuGm8YOR{VJ6JCfs4}Iqd}OzrnFLx)>FoQ^TGVVGTCJd! zL+z?eD(%0-RsE03l+N;@)jV1`)b1QDrnKfmJU63OUb5~(tKGD6s6AbiO8YNVnbKK4 zMEO&-Hz?Xc?dfLzS588_f1_4jvV3T@v{nwaT!I9uOzA8iT1%jnLoFww#gx|mSL9=( zR$j7vXswM_4z=8FQfdE%DpNYkht{HL7OzA8iS`R}jhguDX7E@aDA>Ox9 zJo#)N;_Z=E4n;dC5vVeyvwUbhC9NE4H8omHY0Zbow?>hJvfB@>H>Ql_{O&BfDnE>>;DY zl-7J?*BIG8vTL8rUbso6{THfC=`0`FHC$#-A1$V|<|Di2%l4u5L$$Xk+QD@umG)n# zGNrS8WY^T0Uo2=br8OVfHF&m2GD zad|U(U%U=&b}vBYcgyjo3!8GaKyw~>>b)E69N+G%`0#9 z@zomoP+zZ1f}OP2ryS2B-rlm;fA}AwYK4-9o*`8!EaI)Veo(-L3X-N1|gLd7^ zN5l4%W8L3Wn7fRl6e1O?(V3WVbS>7RKQ0jP=)s=`d6>28g9R>PQ(9RP{*t($JUi8$`gEIc-yt* z*vp|}yI9XY{AF}Omb+4AUcb1ux9^W*6@z0)b=v;ux{4Mg_6pk7r8pnrtL-1`)Vh|z zZE`d6zYwB+iz&!TWapn7!3Ej8i{&!kW@LI{R^wEe%(PB7YHDM{?_2e#$j*kUh_S;g zjRi9;&qO*lx)AReFo4TM-|r3v-FG`0y`-~>79`#Znzt^@^H1w1uIjXFUBi)Q4Jdg3 zNQpodUag3;?NQHgw397844W_A2NDIuGu$Osq3OjcG_lIUr>>!$p$@V6t0e+eu7Y59 zi|`$b;smk7rK(};XFWL$>aODR!7G_zZqEMfua^C+w$3YS_H!gSKM*FS)67jtipSUxr8os%k}E)PGvuly~#io>lt#mkJ*j zK*~OU6;)lgp3#5l-Zb-nWn%yMZ_2$de)Qpjzls(l%sXGyZ~V|W`>L+IF*C4g9qD?- zWQjl(J_Ql+q^ypYd+5bGJd|B01}E=Hx6Sr(qCowWD1Zdh)NrSbtyL zo;#3Q7aA%NsKTeN)A_W&q~>1SgW7!VBE1hJMm*eTY@^F+uS66<+heL@NEnq$kqK1c zyAf+90`gHxClPb0OtOmoTI}!Q{fSnsMqXk&I*|Eq`Oc9rpY+H${%HN|JI}S>j3RA( zY0?{+Kovf9(Z32SN540^Qbl8s)Cmg1p#+tp1$n@7g$0NDW(BbgzN>M9i{Z3@gMdB@W0uiNw^O zGk;K;uisfD`>Ha=H6@D{b;R0?&JuwtT=6ere_Ge2twkD>(jr7f?|4;6>vY%K*wfax zc2w>2SQRZu;P;MBH`t*u`EIU7RYH>`0#))=Z8~T}_2a71=MWqDLMjdgNm5$MdSR@lADd%zsfLP&Hh9!_6;O zl=tzD5k#j$`RQGS8q{%vrSv_B-+*cR%kjFcZTYX?+Fs;6m)@zH+#Kk0q7|9fvEhDi zI`Ci5DsYVav~p=dUS50^y~zA3DxCY1+T(V8T4$S|(1HZUkP`8h&VE&&Jg!GKf5-%? z@OxLRHmrX^Jw8=Wrx#n%i1cs9cLjrZOP`wj>MASVdT3W(&!HMe-(n4YOlh^H?>EZ$j;x<&%6M@o>gBq!dAspO?cMk{>rKYEUA_6ckb1&L$?A*L`-R%j zPDe{Zi*fTI1T^Lbl?Mt6JswL7pI5vA60FIkGbX2 z)y7|3sp@N)Ko#DTSR3V*t`7EfrG-&n4QD0~|qcQ%f_93!HoHxxc> z+#FQfiCyT|8Z(JNReVOWar3(n?$tw!K;zq(sgG-RrkMN|gsPo)!i;5G#c+os4Y*7! zE8w9P^6{lNZ7c{aNK6u^K_0)}ho5{^U-YE;Zxt z$KHHb8&_`jA~oY>!M=R{6bFt^UBuEWd4+Es-Hqntc)CbTaU8_d9yLy>5J;zP=;-s3LJmK^MDSL%TzRQJuU5Y<){omRb>Mil zV(-$AlKi@N03}(ON%w)obG=)JReE23cAs`tt%~&HZ$J6d%~CRfD!eDLZYj-~eZC$* zwr_NF{#~lG_N;b`XSKn8z4JChU+%ief#cQcbZ6S7>PHL=pe}!MN%w)o*1m-tUS;2t zSh?)6z0t0e0NQ$8CQyaPGP?xhV3ZypbGCvr|Umkuf)IX zOc^)KXjVqDev>F`9YtBQ2p_Cxy`%Y>Rt-2_t%$=CSV^h!xeFZ`W-i?a67O~O^%YCR z@t#~O=P{P~l~c95(t|uQfhxQwF{-w2gi^J82YNc#g6`(qq}S?NM^V?dJiSK0B|3s{ zyIzmu)ryr)A)(4fS0CbUEu{NEqT-Qc{g4-Z_^pSNU;muRET69q=SBf=k zLDQOA5n7N~#=q%}MS}Q9Uu{Qjk3L70uLlj}WN$@iK_dNIUbc*P;cI~XhA|A zt@Z2tMrpaV5misiD-o#5TgOI>;&$NX&nsxp>O^hB4zt>1J1|YfF+Chr#W6V%)v<3C zLz=%GmDsCFqk~A`2&+!_nUyiDJnl%|OE*gds&JG_>_mE8*f6LGqeGUeG=7Cd*syQ< zcH8Rl%9pg!+MOG68wMwPP;<*=V zKH`hqR|4vFq2}dQNCc{IEKBS}ay_FQ`sqh8S5l?%L?oX6+NclEx8&pdXg+G^OH)oy z>OrqME|v&X;V6}ORw8afuf$M#uxo=feuc!P&B^+X-`eo_R+^9YX`_|so>BD8d!9s~ z3dfm5pJ7c;#XK~MT5en|jjAExB4#u4P3yqN*3o=;w5q9`m=sSdC(n`yRN;7#sC|Z* zEB)uj(f8^rq>&;dI*SpnF>gEZVP!NQ+fI&QjUM%<$)PhO0#!JoBfe_`z9@0C?J476 zerd)8OBBvoh&7N!?<%&rn^C})e9~+N5?JQNNdh-+D66kIQtww*5+SK(e$#6`3-B(xw=(*3M{N_)x7dZ1gfx=5c|)Y&Q$KyX-6l<=8@VD zBo^3g(ziU)n-7lG`t3u^#w($Y-t?e=OrQ$e60u{Xq#4`&wJ#M+Sf=88z9q&lZLB+U zwOACF-}#E-W_*VrY6=1^NE{PmedGQoUwu6>hBp-XYMsbeNT3SG=fqiCgU!`Qk$2nF zSRswWA@S>`y|J(;ALBC1$8)!u>QPZXZiw=M|Ai`fjBNGlp6Z7lQFKa_L9`&TeRHzW zPn7e%ndRIjZM51;lyi^v^CSXQIHD(71OMe}M^Tq7-n~H@xkKW}uZ_kqQD05Wtgqf# zrKyKSedXt~SRzm*k9ZAmJ)^D{b)x^(RB6NuiKXEejp3r+&68R0HY##o^%3>%AyMz* zf1yeqze*kVO>H9T_Nzm8OXF}zv>x`&*iEz_RWsXm1KOFpgq zrhJ>@N-alRmk3m0yDMtyE{~LAty|H~wU1S_AkjGNqJCDK3;+BuNcecu{k(E^p*T&s z(*=n@6}G!#*H#CvxYzDTg^%4)(SpQe(E}K8(UY48X+F9SU#nQg`O~3wCnW+^*zSr* zA#Z0X{jU2{$EDX)v>>rn%&R%Fj=b^5K;fgor2)#=JE7!jc|;;mh3&2whwIuwSy3~T z-mSQ(q6LXUckT7R=6B)Vt2H0XL(3^$(<8|5;eLrg71rS5+ra4^b9&c{+?t(}>UJdD zZ-_6;%iZ|v1kJ~!kVLloNgsMUgCqh~SkLQpRx@7cm)MAyuglM#2yKE*dKBoU~>dS1kI>YB)}tcak{-)B^`AhGv)YDTUr-T14_`?zxZ7cZ16 zivE1xClRQ^dS1jmuUA@47!yu5Zs%3BAaVSTz44EDA6}X7!z!hl`tn;C<(qp*B2b0( zyeLtl;?&s}Lx{DxtfB>psba23FY;BR%zQQZ%>vchH;7uEIxZ2Y!g^lp)VsezoxjeH zlIezu79^rXi!)f153|hjaYw|ZO44_tLG{l`1gfx}7jY(HPOA6pyeO*4eHAT8lnT3O zTp-H%$INnmZ0RfY??ZR$sa%x^RAD_YMn96@t9j?SP(}M^Dq4_eIrN*+R@7G>nf2AS z*Lf-LM9~@q-H`}XVLdPAihAZFLsbW|v3VlZ6I z%9o^NVinR^u?h(-NZ?v5@$J0F+HkaFHM(@(oN%oYt`@>tTbv)2ZfW>XzYY!9orlnZ zgxm|C*ivU0Sl)pWL(L=tRak3_8m{U~<#fGff}x1gfys7VEDrHdc;y@TUv!zN%xkR7}Yi)66nA1_c!;=t-ZuLn;3lj1ur$yWgg0i9i+B+G3C5ML&LENC>T2_(??z67u+N#G89O&x!6daP7VrAxW3$@t$ zKpNQni;5N`e03{BybK% z)FsYe)T%X`(jYaLM4$?5ZLx}V=ofYL2nV{jJP)A-37p3hEzX+Uw4|^t?N7Co2vo_l zuU_IznWk-OQ47lggcc-l^{$U>wU>-#2JZkS6KFx=VZH?C4T5fw(fJ<)s(SuNb>7{6Ec+GfpMz)`P=@(+ z^W^Oxm*!S^ORZY*1E)6Ur7PFWE<0eyr&9?jJHlZ=a2`55259K+t-jW^!x+0=-%OrQmc ziXFzX#%Dr}M@H7o;R6X&{r6R2{=s}TdGsOYNSCp!oomi~g%%`^J^kd|aB?zR*3vh} zvqAz@GxS#a9~;K7&bhngAn>{4`#@TLR%k(@eX@;ye#jVBv3J)TK9E4we_z#j>tr_5 zzgEUGb|HP&_GC6_%;}61+h=7YxQt_U-|Wx0P-KcY(;MG8=02QD`|q5H79?<1PWFKW zs`M>$>%%Wb@G`@5=619oAr)e-o&Blr%=) z-!_cb`Bo=~4=lBqWAeU9*53?GX60`C_@|#KG1^1<>K@7L30MNZ`0c3@PP!XZgpFw->nR1H-CENAh0}Fa~Q{Rh1E8;YVs!o zYbE*Vq6G=xcH`JVPYdH%&qF!#E)uB1oG<%83lft8$FZo@H!`ZlF3aHq2~_=eiRv?; zE-Ut`6+e8vB!80LgxPr*_%TOo9_7@OyJJ6e#yIcWLLkw8^S#x(s~ z@1DH%z?>xtEl4bj-=c5(D1@Kz(q^jh>EfI6`#6?82pyEsq*uKRtSe;#El9+i8_UYP z*Jo@W{ww{z2~_nwF_K+e@+5uFsG&KCZ@F5r5)&KpE=Mf+G($@^@KY@w?xf@RZe$;5 zK_Vl)DQnrh5pT9K=Nm)yZFwLKozb*kO{OP@j-pA&z` zP=zZaWCATnyo!9F@BXbTA9_$*oq#@&Ko!m|$^=@Fi0F7szide$UuvhFwS_*AKo!m| z$^=@Fu#8OC|D77l3npr7KhOsfsKWV3nLrB?|6R_JK$SetiC2XdB(PqQuPUkF1^xF8 z(d_Zi=4{-av-&aX64>{{tyt2N9s0+Q`!mC;RxAer79^VOC4Ikhl7}YL^4rbA zWk8CPd>=@l>c*}S%)&d(>DBB*If(hKhOleFtBvY`LB{qIMzPiHmKdkai8bcwGlGrk zIo|lOxL1zv540e${^2OL%58!1Pe{Z+2vilWKAJ7|4pFk%J$K0ecDuG*AiWGToqc7`0x9`uk9U<6)#)etA^5bKQ00HksLnIf&})|WFLOj3bFQ0JFx=2 zZP~Ggh1l*|omiy+TV|+i%~~(@XX^?zU^3ykpaQe$<0^7Qd8UdhnHT29N9f)iNisu*48n^2`O}x?9VPo9%|O_{C?8eb+59M*T`) zLFosL{+nm#$cYnOe(1Z!M6h9_^lbj!S2DU5gjsEDeFxG}U=C~@fAhE6K zD}AB6(X4IL=Kmm2g*CYRtk8l)?LL?EON09}vu$oUd?0};tmkDPc;|Rey>6JZR(4^m z*Vkq_e4qu1S^ILc{rLmL8r+=k90^ppzb(Y>HVkC3femx`KnoIOO6Fw?I(1`r!t4Ko zKvjF46)Oj)ve8C zndLZlRy2R*90dMv@o$ycutx@#>q=QRpuR18v&xlyNGP9!KnoJ{EUU6A#}sz{O__fX zsJhX)I(rnLXMtZ!SDX-KZ-u{vQOYu+^5!2U?Ku_%V`AEw|Npc-WX6K9E2a zw(YVH%%j)rteBa;D~ld!&#)B81X_^z+S`gb>AJG{?Q`aKBv7?C&Wd&a=Ev+ka}ron zXWXd3X4Z6N?}o^=wtQ8Xcaf;`z7o6swK==Dvs{jRg#@ZFAImc49rtO24M)nvPSJF(p%CI3HbA0(FUti{@1ZpJc7m&ozXvA#mpNHJ<~?0IAM zu6@xQ1X_@A>2Axst(vfu3pt66Z$ep%n%4YO&~4+n&rxjCnA|)y{iLzi>z=GF*YR7& z59TPfXhC9gyJ(g;%bXWJdh8zrs=6QR&0b9XWNh+rZw>-2NDSW?%Wk^=HGV&K;2#94 z!X8GjxEt?`e=6p`N{ zKu`9ydOeO3I*XO62v3libSIxxSFHF#^sKmQ<571_5nD>$hd zkGuLk2Z0tO9?k2*Dt4;G^{$`(L7?hT4{tWEd3pZw*_#{$T9EKe4`8-~%JMe}FaJTH zs+nsicEz<6|8(zh4gxJm6nz`OlqO}lSK*vKkU-UxI$c?sV$EGn-OAwuEl5Ny3T1aw zta*BgJO3b1wYQ=_>vOdbuU_|h4gxJmU}=`~6%wd&=oZYp4&>!OKAg?r11(5k`Oo14 zTFAvatQe*Fv3EuPe_LlHqOV!8G1L6m_)qn6)Nt53qw2rEqtJrH;4fCJa=ahgc{8UE zBv94GF&`Ui=f{Su%1M04m7i_y(S@D-W5>3P%g_4V?94h(xBJJ}9r{3`&fNU$^r_A) zXtZ6wL~$IJOhZqU@OC z69;y=gf+ul_4Hkg%R=&n5;n zU~8;$`al9z=4MXprQ*Qy)hd$12U?I=^t37aI}A8@>F_(Sk(DcsEwuy#!PDzWWD(sv}7q+50=ztjUBIIS8~M(PCk1*50KEyS?Gr zKL}LKUGB@AQwp&A6(8gv(1OI27GCU+t0h~m-1rB9swX|WvAjDh*ox@OIS8~Mao4sz zOLVeew!!}*P_?yQ54LviOMUHhp2G)Pkf?sSE30tek^ab)J^vt3^=@e>TcG?u#?Cvw zhUNX^izq=vMD#=uB9UIC?aUBTq#z+$^b#c<5d_hR-bIP%QKEOw+10r^QLd}E=)H5f zzuDvF-p|C(eSQDi*Lgng^UTc7&O9?aGn+4uY`>=vffgj9dUhheZ@eTI&&w@DU`!Qs zHicZc_C$A8-lqF?e1#Sy+O$d~-en)?Voq(;i8T=kRN*LGB+!Dy)5J95)$Ee)`hn$z zd?0};oI4YJU_aqGtTcJ_xGiZM@ANaK|6{6X|kPjqK z6$JgG=mYyZ&&UcS{aXvtgGZ|kU$l-W8(e5$g8hOS>n^W4Y^b6e~sagD4kN4BtDHI%}zNKDqVa&P*rbs zS@Qi<6p7tdn7}(_KC%+ocqo+Y8ENxB)?FkzAFWLELqdr6fI5Xzh4l(mIP)Tw70&gP z-8P0O6SMr<#!m42^}G*Ska+THG`YU=H^1k>>k7>jA%UuexkE|&Vqg5;ndB8B(1JvR zQKQJk1?A+Ut)Kk|fvSw5gGgj!clkqV#X|K8ElBL2I+ARSt}7pQEA<})s-7bbDMX+Ji5Ab(h+~Hya$KZOAp+~qohl~eNI(?%(A437Y}=7|)XIcZEFDEWD;BPa zSa(r{Z??o*g6VyjnMRVY#mMWb$uj0oB+!Dyg!V&8XRCqoxMhKba*hP5YKFy;!%j2h z)Masn2(%z^p-BokX)#ysoRRz=grNG?m&^=VEN=`QQHYShf&{j%V$KBu+TdaL`;w9S z7t3BH(+l}P3;r**$9$c>PqT~8Fga#HVogAtvQz`XV)1|R#t7yiN4H*h3ab2h=!gl zGqVP{^kfu?v#CM$cC11Ex;>r@ld6$Ek4;DlU#-4xtJZVA(}yV@`AbNNGDBJCCAD?= z8&{EX-&&H%0nUc&?W84XF~wOIe`PL-Ypbn+th~@%-TZ7W*&NxDMJ;=4Q2AszkyMLM zhU*f~9mwTgpL7wn^T_VH+B>i7kzVR3mx-j~Emy`*9@c9DZKvi}LezF{`B>2I zkTN%E5qW+omSNg4PpkXPGWgi>EQtF!;lEXxyX!Q0xFCU{1&N7+N9!W)&m~8SY_L!EV6Rw zAchtsj&AB{@bTC}OV!B*a}}TXEYj3?pg^EXOcmWzMmf4Uk8JQB#wv~4yl?5*xn#`# zHe`kG=6zbtSh}%Qp_XBkX&oibIGcpOO%w8g#N$LWL#n)wMetOmD2j-?o#yhTw?s7E%)Km zYu>)mmP^UbhUp9~NE~nIw^yUj-fhi^_!KLB*E<)Fyiva;rH!B_1L-r8zSn=Q{Ho0HNQT9AmG;w=B$e@O3}&<)R)kYQ;<1p-wY{hSRx zqMTZCAA^RTq-VPq;C{O|6o&4@_E6rG_Z6w8CN2ep#_QNvCR!WGN(1?KK8Wl z%+GFHLLOEfA`qw&OV{e|75ZVoB66)|Z-ym`C0%*;5rdC`3$*@Y-{E|E*6BAASGxy8 z3ldK}^5lPeoRs_TXu_>bVpOE7K%mMj;ELkkjh_!lZ#PhC#@j%x1>nwd3Zw_kTB zy58;rfhz4g6xyBDqCrWDoA1W&_llzfR&Ncrg4gB%&@>CuMuhaN|v&xcE~8B_eJ z{zfFjRdboJuCHIiFLK+i@nnzc$BDCEW!U~bO=xeI2!<9UaGe}KWz(Y~i&))+K6w@* z5U9$SR*qD6P9S~SYO|dBop!8WhbS6f$(!NKg!c|h5)spZoVKf1Xk6PawgDTxJ&bm+ z@?tnjMdFa9B{^V}NT%J?)~aQ=)?=S1gi_acegc6ieA6gNciPlruX_a23Jqk279_-c zv~#GzD%5I5)5kOw2vp&EKZ#e~N-XhY0FCf(#?XQUmYXC!dRByar#jMzz;+DBWH?qE zVEtKc-*G(I*20tLeB=>6zrWd;UUf@iPS-}uea?&{=DQ*Z?p?zjW0K_SyN)tjN7`_F zyg;C8hJUVX{%#yef2H*}hcb53x;U3P;HN z>nf!i(w@y6Y1amW8SeDN9iVT_UF3g9+r^Cn=&4Lcx+*D^p#=%tamvRZ)e~s{vW~R6 zTZ%xS3h%5Wt?(R9$K7+Je|ZiR?jRDl+mU|_>fJQ@;eivamY*yTsKOc}N&9aOk{8(2 zq)yj|3DGO=UdMgu{9J?lo@DaXi=<}55kgFj(K5z!+7}U;k!#P)Xf5;MLS%`A=%ZEW zS~9glP1>=@Fo8f7?osCV+;p#Qn@3Ih;ruXR=RNvxj!E3Ne#&?wHyY&Njs?sl|2?VO#BNi(a)>7KP5Lt2m5_HCD)JX&$s;z)aK8^F+lgu}Jb zx`I}TpH0o znYwwpkz~^ImIP@&Vo|b{7ZEOWvTGtk3leu9j@FItJepj)sEwm;$#WDl=1iMbN)`xI ziK&Wqc&kjx_N1n3JF+>c7j>`W`KokX0IBbtr%OIOkmMT$lGW$(bpOt(-FAAUn7((X z4L5aRXhCA?gB`lho6^XZ$J(x6KiwZn^$bT^zhe)9Koyn<@14h=P%h7PqnEG52xWzY ze|oNt?|~#%>Dq|?w}GnCJ;asPY1~&JP=)2jPp;qdS()>+Azgl;gOGE~lh>#Rx>M&8 z$==_!S)6ZAjMN*mooLUVZ5UdRNVfj0`?pscx2u%OPI%GPBU=dsss=c|&=s#6PZnn} z?qkdFvTFZWZ+i1fONJIC`ZoNc`#1LaU|&W}+uMXb@{SM)RNZOxMfW1EFX=g28?j7} zwpN#I2&Kc`G-3zz<@K&lqDerwD_Q)qoW7%bCvuvv=ASsNoL-B4`Wj*%tBmUEvy;KJ zVd(&d79`3)ETaD-Er#?m(MBxa+t{g{CpgjIkG`z;V-vkL$ExFVtksv+(5GD)MNagn zQOL*I<&J8t0X}qLi-v*^B$6B~^)|H<$->sPxQ{vc_0%vmkSUYO>ATOHN<38@pv{NewMA2tH-U5NDsh=$M|Lz_r66vnG#oZ(| zXL~T5Jw5xNx_+b8TyoIaLW|pBCN(G7O|=dAMz)?Y#MJ*-knn9)Lw{!Q1af<$HX}Uf za|1PGXgONO-&c#<{~=I?r7lU0cDkr@uh*b8N_q|;dQrnaaKK}A)T8W#W2#t7+#F}tZd4%y0SN&u=iAt3^RDjZozQt6g8*r`fhG-qT0LkkiZ$?|!hUG-T+hzBk0;wKQO5=Sg2iaN3} zo{V;$*pQ(G35>`ksc4=HGfS#YH+=VC_&x$hdYD@NJr)ZG*2ctydi(easX_wBaFUdp zS(ClmU`Bl}G!+O`VW~^fldP)j*7RcZo3&WFNZ>e{&$n+c&3<2ELF?UbCEO2GiScgd z8b&O9TS?k*g*Y}q0%sE>X~VupbmI3a^sf_Lg?JZL7@hNTAd~-~@lDIn#}C9P90{DC z;im#G-9!BjRi`Do#|m*fs>JB^L8oz-GsKOBduO;Ix>DV1+^jXWH z!q@-_G2U(2=}%HCwI)5DFA}K2({K3uj|G>>^}01_zd>mXEl7y*Zi|&fIW*LfRydQ& z@SPw=dKjJYv(>LqHE8cX2?BvCG4|<}xL4^r#)Q`VEmnwRkihpXJf^O2Rf+Sd zMlF{16bMvdjKaT_a`Lg_)U!0bU%i_Uks*O^o%kILFQ%S0sZ58AXeSV;!We~*IXje5 zotBiKfmK>Fv><_R<@nh7Q#JM70zLWEErj8FK+k&gLAf5 zQBOBDr-N)l1OioES+uW#KTQ1b{(Qs^2YvkZq6WHL`TBa1(7uJO5!!dq za|TQ>Txb5?Okd)~YQuHy8%+ukQny<5et18n^U3OL$WzdO*8h>t_X0k?)J{D0ZRe}Xd z0q%LB`+)?i8f4Zs_~`hpWg#CnO9Kou*bT>I$s=u>8LpGYOqTimF%bNI6{=U~ZR!-< z4;kO~;k!bytnjTaz72&^FXRI)NZ@-_(FYQ!!qkccT96RmTH+Ih1gfwUL?8GZeCzgO z^~R-gHTC%1hy+@Y*gnV9@I-}rSQfg2NT5o4CbfE{*+m~{LE_HeYg=YCH7n!;2~_RB zR@acK8^eniBCs{U6t=N`Vo24BORj|ov>>6iI$A!oR!GbT5~yml_{Z9h!P(x0d|)ec zc6hGge={fh>#!&s^lqz@zb*RD;5p#|fB%-GM=vP|z3n}CS2~=TU zBKp7I#>srxm7 zs$a*VXh9+*%FW>8>%vEcd?0};jDy8gX;HRTR=iI6>9ZqlElA)B!Cw=o`t|dH>t1nvD)jAz>J?g$z?G+B zs*pexmZ3!<8Hed?6qN#kFrtS1s^ zL1NXzA9S#*|DInHs7kr|gV@@tsgFp&bFQ<`2{xpvWS40=ZItwPo!%!BXhFhd`j0kd zX1{)go~XUo>KdMd`#c_mwJ}=DV0dn{`z8873le^Z%nko^C#Y(n{sReA@&7jX(ApZ& z2U?JLcDRheM`(<7As??mH|gw zuf4+zs_7FF{$u2Yy(JQ7jGG(i71P_uq7Nich3%L~paqFH#ecMR&)?Q8d?YV>UdRVpkbt`I9|Wp)WY`*fyb9HJFXR0{3lgXH)H4vZ z`)Iqckw6O)P>%}{Xh8z%TcLa)fht_XCZ-D8T}~LDZOs?|C%slHf2>u*e4qshP8n#; zujm5_RPhoq`1rZ3>ZJJ?EV(A<yY0{Re?6 zEDX229SsU2zXQT)$R zI?)GOkbu+{>d%ot)gqf8`52T?qmU2m=~rzEH>4yoKl*=+8Iag_^v6BFb0?&b4@?QF zew`|uo4)hxM}4*0tNzD4HPl@l67^$#JdgWVZYY#0Bv1vlvJin5B>t=#Xec-LT8sXJ zKo!PX;yqV;%`!w8^m&lJXt8v|_4JP++WeK_T1$gSpalut+MWg?s#18N*arzzX=5I( zP1Np}=mRZCTy?NF_}Dk8@T@ZusQUFhHO?oPC!96>Z`+qX|KnT+673RyL~0q68W+mB z)(2@h)b2g1utdb1qXmgi%hwqG>1F%EZ!?fU72a9V2aoQFmZ}s#|2=$cV7R{cV>Ds# z@&Aq{{;?p@=*o{#>ZxtZ3$+Zq{rHDK6~EVp-}(J2M4$zU#*M#UAtf6{Xh#6 zycae2_GA~CXZS%$`5;Lkw6O) zd~QjvJ^zn?np;8wRT!g)K5(AukM}=XgG$e`wb;i{L$!R01X_@I(CkM`WW@9IYXVi+ z#)t%3kcj5H8MT~0UEsg_*95AttrQ7-qVQS4olhcx79^mTC{(YIKo#zl5`Ey4gL~KT zNfQaQAc6bXeodeXQz#N>K|p8A_q-qDNZXUeE{shYuts-*-09p+CJh z!2d!OAGaHP@F%&D540fhdE}3oqWb~G3dM;?pbBR{#hhb|v*+lK*}779L$q;JLA(1O z@f8xwH-#H=K7^0LL?8HHsKUA+5@`FX`F-~l)b6vSIVh(xHEk=DhCr>xG#Uf%- z-B*8QM6Rx_)nej&x{1DGT&}Lky_qCtL;xoOs=2W<9j=l(w>(vC9Yg$r^TA|tXm?#s>^|?r&ORGLr!{pk5SOR)Aib{DHW2B%+L0?kd|qiK zKh@Kx2Pw(iIME>9f~LMIN|)A7Qzu5)%e#h5=4TwV)(`JwFE?2^noMSG^wn&0{BE8f zLwt9%*$JVtJH~zMfH)kq4e?{~VosWM?yycd)a5 z+o?6OS$K1D+@z~M_`n)D)H#xve$t4$evB@$%%^_KyQtO~_VRM~F2pFQoBrNtdwF!7 z9^_7P7k!7`>2mVnPNctoCr%7bxGyi8oWOo-x<^S%8owuTT`MxO;Q)PZ!uUPgd$%Tc zyp#1+`{elT>e7mwv`gm1@vNr^Vfl(Wy|rzTEh#?rxh_fhBMUAGzgC*t$jr!v1xx?(Q{axc0o6t4lBIPs|;XIC0qDS(P2e&^=q6 z)cbsn_1*rqq?(_tUb~K&*^c->ucx2rYob5gs5@EWsjYgconBcr``C}fUk+Dsg%GZp zi5&1rcdqS15;jVEtKYYEF}3uN-lS|mw2G@iCX}%8mU1w!&mpF1Ic8H2AD{v*p zoS|+ypWr!UM}4i9IOGM=JX3yd_tv2*j>B<$ejwOh-WolJESjzn7q`}B-S5VcYIFQm zd^3V?O#V7qhB&raK(?pW=ET7^UhKF1@#J$^Hx=K+Xit|G>G8Q~!?WU7C6kQWXU>Uj zkFD5Qvv|_Gez4#J{}Rg2kxH%H z^sCRFl`FQIK^iqA+{gTk3T)T1exz7Tgo^)#G_Hn_q}WcS*{PND$kyp?RJ0%=`slsh zh#eX@g*eF_1OipKenOJ^{PBg(Xg!5=8`@b#3lcahB1!XFo}#DB$B{iY{nYf#HF90! zS;QzPP>=HrI7=Z(H#`18OSN82x@N@)1gg*_OKNvd0_ ziYlCq5{d8OvuNMHhLHPt168yjf%9d21$OV%)V9QY(!W!(K%fdsU6QJg*+g5^8%M@H zP83QP331-%&qpeCt~!ov+8-wnsKUD`Ne^?&64R*OBsVEt#kERxjdT3^yqZI*EsN5x zt}}j*QO&u;c77XPR(sYzlt0B!AkErv0xU@U<}!ZI@Rd`@Wqn&ttUp;*zy9O|lG0ct zP!+Rd*S-b$b4ZK$C{8q4HIam@>q;t>5mSY0vCtpi;r7=7(rH*%(s|Gb6)i{zD`=$% zzhcyLPzuS58!iy2!rH@k{kFBFy?kRy@Wf$4y+Q(4(DIW)Zp$>ed@Nbwm?jXY!nTq> zQ4iwuOH1@2_v)vsSSGj<3`<>-63(2`y(-y>{54rDT_kW#8Q)(m;hEt=K9Inb(tN+c3Z1@UlWyen zxDf(@D$Em)WTuQ%JZHv{gVCu%ABFuAuJO}OTgX+O?MWjqXC`l6^?yO>OiK`~Xo^yE2dqv-;H<{G1s}Lt5fvYt6iE_^$Dk<3m z$mrcY1OinUWlB=-p;qd8+gOq}I#`GRu-C`czx))aOP=cTy1mG`W$r4jz{T~uceUu_ z%R=(BnAUR!A8=MfAEyyD)kj4O5?NhL^bLI$kYkp$IPph)54G~<3{t_=Qy@^K{nM4o znWS~D=A+^ZH+8P{DbgbB2l4UCG;&9^&}*t{UuKZlPz!y<<|g_kBN}b#Ifg#3QC^As-E?o4Wh-ClXT4Q$_DcXerF_%OK6ySLQyFbKF$r>J74yiUg{( z>w^4Al6AbZdO#UUUFSO+qP~JiPxEo^cy}_oMx8=YU&l;-KU`vIk3%jh#)C*`*DYT5 zCie5R`_c4;v+6oMni_3#{fQ`0X+-N@1Ihje+Pd&=e$J}7?RZ+Xz8H(5KP@f|<0m10 zy{+xd*z9Acs#()$yH0L~d=yxan9ZYC+v!ncseMCEBp5rZ&!5es5AWFv1gbP2`ja8V z?y>_XzI=63-*(QTmc#4}M1iF+k=m^pc{|*Z6Ya{_sb5E|p;>1f3`Bti343C~!}(^U zay4xQc1RIt)w;`inq8`%K%h!XmGP4R@~Mh5CoHVp)dR5?Y5x6+2BHf8hT7r7eulXH zLmOYxY^SIGLVFAS#U~Ak8mo;Um)>$yk5xHA`{}EwXwm++fY7c->twRFtp_LeUU5^$ zbU#K-*H!(AC{Ss{@)?9A-E`-~?R*b4uSE$~yTV)L0k?EHU`-O6gz2?wyYltO(Xc>$ zTxSdYz6uV+^iVJ-dX4r_Gct;>xoy8IXhA}|j(==RjD4DNqH-?}b(SQtcDE%JE!y>i zr21sWfhL7~)b;dGqq~2gWpu^W!afQJLn-ugA+vUC_v1uMSGA-5Ic*VUA`qy;GL)n$ z(eCQ9fVw>?fi?r4a>pR+3g`daCnx zTd*dvzZpt*L2&C(5JqrO=_#HxR1jlJXOax71-J1=M}VQ zWmQ0E*GAda#JHc<2Ag+$v%$v$%SvP(?QHN75?PIOKNMBSN6-mR^-xSz zwklBnlaB&I^U-}*HPX>hi?0^%@l>bmtIWdk4*oaq=urWx|FYrX}c;av=> zSF0?@G?y;={_(the_NeY_36rqB^C|UQgv-v^H$>o0##b7I`6JPzJ~Ya#M0mG)C%c7 zY~d#=q-xnP6a9T%b;D@8;z?6|ZMCZ5n(qJ|;I7`xc4l2?1}T{K!g*Rzx;$y-u8q&F zoSoG{O+8rjlg0+3z=DM6V{&&-)%>Ls^XTp&5UA388|h5`PF1(%)znjE1DW-gCQ8Fo zpL9k`>pS zBEY47#7kFY^slwNt~kSjrI0rxQ#ZRr)4z$@_jQU_ZVb!o-&a8k5-nC{>ZaUiO5WAfW^r2V z-K=ce63bjNeFXwl8-`BOnVbsz+ei5_Ym~Xi;@Fg=rV3h+nEq^xuGP$75^SgWXymn2 z$)BCTeCGQJ1gcCPjM1$;74)|c+sU()y^E6ANj^V{79SbWLW5 z;{p}5AaP_%C!OcsP{LfbRMqPmx7SbiYM4Cl|dmADg{L>aB{Vu?$6=Rl}LIU3>(2Ye3}R zKAt_-G;5rquN{@+_pJSodARS*GW_bC{c+8s44=+)T&EOv zcoI>vliSJX5`UCQ;u3o~f`92xoA*oIWiLNJ+?+i3)>3uvd=vWq@F4ba1X0j}#9uQj z$>z~RhjTQ-1Z8Rwi6xTj>L8Z{C^Z73nMxs7kN4R$ef)F-fSbrK-Y%E3|8357zRa zkAfB?&ikyF^(}woPm=+S@lQzC`m5uYOtJEO_=UZI|VIBSUxU8JYUx&F+N%=dhA9W zc6J|SDa9KJ1ge7Xl_68BS^iyCrG9r~b=+N;r&F+kDjr9ZJ(3ymNQgJgKz1lqo|qrd z`Var>_1VPMzHHA&rr>`eP5YN8b!r#%QPnRvv2Alb*o#De1uaNu{{HpRXsIW&+2zEf z`|bjPD($-DKRwR&H-D0hVm;XyquWY{b@uXuq7kI{`vhUeJf>HUU(fK?#MxJC+wHRk zl8N7Yv#7Ak3R-ZE9p~Qptignvvc+P49*2}K5U9EtH-1mks3>x&h2~???AIh@YD;#a zqnT>F?Ym!2>DFWfiP!78=lJ>ci6ZVj;`JUIzx(+%k0Nsh$8sX{%UP0V8OHL%tEgx} zqH5P1KbPD#WKE7nm_2+#YOHR;`lZ$u2viMO``z!+jy9zGxxSomv^qi7U#D#5-ufz9 zkVx;8;}=k|9kDmoVxJf9j*y!9u54Prh5~`A?(K5?Uin3nUUjrcX6vA7G$%Zsy~rD> z7#~fSzfBJzhu0+OkN=S_r!{Ow9^0qr*UgTS=Qa%^S#H`h*s|gb>M%En`L7C8(1Jw3 zzI1tAOz_`z_v_M$)ZD&5v)L{S1gfyD*N%`YqX%0X6 zdzWpz-~);DDN%Cfl`yjE&;C3gw&COGbX^>qZ#7LIP=zJJ=M#@UmIE6PVp9FdN@)M_ zd&XJul_*V8^!OI&QokI(kIN#7>NtS=c)xupDQ1<-hSgiEpalu6$CA`=ND&&=BA&&Z z-YyWRTDZ|(-d(XJnfqCL&S$Q(ra=c{SfdqZ6tp0LPZ~e#{(DOrI<`A|oOD?rQ1!=% zD7ndm=H%Rdt-boKOJ{oPax`na6UJr)%MV56X?ii9oUlB_Y@?2 zb?I{7^iX0xDnXB_xL(pqH?evTI`?Z&W^v-E zK%fdsozJAUi=t~z_hXTFHVCDQ#OJN{vPV=4a@b6(C7BL3w0)UGcK7@Wfj|}39)2RJ zlM!7vY9Je)F;S=`NMO9eXQRrFB>JbRY;5^dfj|}3X?{P}$CBv8p=@WdFrl_1A;v!X z&KKpuebd-YJ0=jQx=`$+_q@>s@s<1B<1VHBVQT^_5lBy=x5HJYufUULheyGG%PD>GH$<*g##nK%ffSE*>FguA(E{;@S5t zO%=2tfsqp*K`L1^;cEh;`}_m~RoL1|Qjp&qI^=Z-D;{aAVy*5zV~+e`V<`DpypJC1 zG(YupXcir8)||!OFCsi2NMIRC(&_2*=_}{9>_xyM;rT!n)_h4?)n@@+a>=6-mC59c9xN(NvU`}#whN~ z?d627tw@cAT9k3LZDrc>U>NK3tfGn*Brsm#-%uE0Lu(#r%9c&E5(rd<^3luuW37qL zNG&e0jxne2t2Scy>eW@zf&|7Z{QXCKd1}1So!Opu69`m=F8%J;?nZku@Nx|IaXIWZ z*>lm3l^#J+iyGA(ZF$kVJUEXpBFAW+q#RgPcfeVxgUwLQ5Hv*ZEv;(dR1H@=!$ zy?>N!a=#^sx!q518W$xm3W+3FtMt`>U&_~hG;Tq%7xv-An)pOo`j8hhxofMU1&M`S zqvTo1QDo1JUYv-yJd7@>~p)Od)S~@3_(XRgGDTv8`0JAc3oTcwbvH zf(|-WoSk_f5~vb$-ty1R^v^aQX=b(dDq4^bR|uIUoh4@$U8b3zV^pPCj^CE{F(h5> zDy%6Q-8{!HXi#_JKUKRQ z+e%4VH?=j*e;mNZCsq~OL?p1qkffK>f@p3`IQuQOyg;A|TX0E=$va5-CJnaef~lHt zb&cFfA42wz>Y;CNTqke&>`zP=#powITq7IL3nHP>+E~r<^=X=u6UZF*e^StbgwHjd zJiT=z(zJ%w8~B_Wr6$n%nE45Zu@A;EBZ!M&p`KXEa& z6kFS{B}?Cspr8c_Ora$0^eN723=3y_8_X35R3)0;ll_)?l3Q=J{`^*nFLZNQbJi?* zy@D1bu%!7rucserhln7yuInj*Kvi75bMoFBgybF3dbPl<`Lsoe09G{np@J49urBcR zSGBIwGvEE#`IHhW5~zByldtit6-dm7YprNAvlF!CoQCXrSVa{rNZ^yk=a!sQx_hTR zn^?K7K%ffOj`EoaBR4i;zBQ{dW}BkTY@KLQmGoTQ)-dta4tCaWJu7*IqwFIwzYhZ%U@O($=K@ZvTpgIa;w>lWM7GK_dF}U75cSB=7cX zsj@NuLhZ`eXU*))1p-wcZr_!kC;5^4R@z&#=Q+jMV1Ea8xPA#0El8ZG{9fMM!;^eC zs^x>VD$T4vxU<&Bo+(J6D$eP>T-3{roV}?<0CnG6uwg}A*{QVO6|^9MWhhBU=3275 z$*%l0_kMvumE*-SWYa+#QgeMb?!#h61GZtC9n(Kur=SH1@qTQxc4O~9+w!(#u0Wtl zyWaGN1t}4%MN5grKGEabs(%Uyv$6_y)6#XQB8HMm!S9gVo9ph_#BwXf)1s09CJlK+yZxEr!f8s5}CRcXmP-Ql%#`&Lo6c8G{ z?N$x)t&+ClcbQ8Ac4DO!%jj_7C!#@<-HU7nkq)i6~HML_v$e-y4Lvu|6h_>}$p#rOM4R#G-m_GW>GyAM^M}%}M>2 zJq*|Wt16I;(^>>j;`C8Ecw1ez_nEDV?Gmna$Cgi$>^}TX%SJjdi~7}t77mG?70$_T zOEf0eqqXOw!@zqq{A5G6bzEtIKoz#fl2pF*dwTY@FMGB4v(UC9@&3bI*)GtVcwW~= zUi8g(s`mG1dmCRC2vlKD#N#WqB#Rx_gar=L2|W%H>x16QGiN%J`=MH|HaDUy^X(eM ztZf$y1gfw{l_aCymD!Bljajv&(}bQA3A|5yt-(>==H8?1L*F3+fhv4^!lMim2Ug*M zJL_03QFxDogjP%bz31hYyRq1b&TO$qYk@$Oc3tomNRk>iJ52v{vS5CRUMlW(z`g|U zKd&X7FVplMHCUFBgRpM`3G7$+N{(f>Y57E3mUF;TAW(((pSL9mZ)ly{4s79}@+w-8 zz+QrXO|a*mwBs93#ycp1Ko#D9NeW+Ig1tNI%{Da1SI~k4_A8PU*|ZD`xI@{hQbz;= zRe1mTij?J**uq)9%shCTf)*sOU*R)Fm95ylK0fTaNtQsM3hzJ9`ThoM>~<%1e&QUV zWk5o^=l}LNGs4|ibXWuSe8X6QK$Ujg;qP{Z&*DryKt12}X7MZig?GX@%ZZUJ|E`R( zi?&f>SjW)8!rNCQa2}R_kENAD8_w#^8m3Mc2vms?a<>ZG=!$V2S90Niw$DISw<@U7pibX zCP_mEuBDHC{Mg={Dk@r#=s0eU{P5_I3Ox=I z0sZI5(LQa+t!ORkdl<2f)*55RcC2V55U9ddiSP4zy@s}0Qi5IH5-hY=NYvi7My?Rq zhP?FBVxOli_tI*8joHy#{sMt2Y`gd>i%|!u-`e8r-q0pOOpU~_sXDpW)d=#ryS87g zUe}AX)c3N?IL=2PP=&D_|7y?p>$I`8F|&T{BSd{jY`l9`zWE@Gq;}BatKI%DXzU_W zRyWXDAW(%7pd@X)I*mTIxlR|Ki&ot?u8~LNbRfqMwH5ZLS#(U7H@xmfOntRTKXP0r zTHoh)x~yF{6)iYth4W1Oi5gGoy4lC6lp7-us46wwUbgV)P2TU+#vg6@mpr169i@Y^ z`l@I_0%yYbcrg7e={jl)J+>=BAW${FQI20mTmmV2UGwqfQ&aN!&I)So-Csou5k&ij^8qwin7tyzs6II-ch-X#|LlPHwkoGOKDEx9;7xsFn#ELvFuA)Wj zGYSapdZI^t^2%IWjXQUw3rn3;l=a(O>?fi?r4g}p>XE^n136Lb&uVOUtPu;jR!tz5 z-F+uN&T34mY>&`mY9;BCWX>$MN~~FIT_GPxjJ@6eH61zI zMj%i%e?u9vu@ob#pEcpcoa72@v+onyHrPo;3lfu0ypvzYg_0|WwR4@T{ZW-o?Qof< zg^C2Kj^~si_tHbi`WM=Y-<0oWEPwkMI<=0MiWVf69e5{yTGNueJ{-h}whztN$AANr zT=5kMRORk{Cx0&2h6I%f;KYE8IrN=tPZete))M!HYvdCH`w-thA~<2^v7A0^ zJDu+M-djZr5~XLYk%P?plQq9UYrL&tzjL&8Gcs+JqmU}C?(V%5 zLO#B6;KaoJwrt6`9QvN$bF^TpFn@fuww)7ex^NEdP|ZOgP^JCTrY&uWy49BZSk}Oq z*$?@HF6mL(KzvK_BqKg~8=l(n^IXX)Ygvyql&|p$cV_W-Z_;r~EQGqN{ci!GUC(do zN)mc#HL>;H`mA5tBl>Vi)t`t0mG}(SJnYQewm+k8t4)O`3jbHT-ZHQO@v&~qeH1Zw zVGCBgr}tCJ{6rL}G@_tg;X8PES@|wnN7p>9C)^KBH8nJd{MpkZ;RLcboT%JrX#0+m?0rg|q}APVO{B*yE0S=dowtvpDBX=fxL5y$#~j*e za}u4N5iby^!d8NR-}&KN`m*sJnqm{K;?s#w?W;p)rq%J{~oAZ&T$E?Yk>L zMGF$xKJstvvaP>BpepC`S@}pp1nJmG+nZrAswk^8K>r0Z`LBv7SY-?OYmM!pQ?J~GZ# zXB!@d(gjPJs#)vHkPMIEWZ@}$;lzuM$~(Eg$7u4kr?!`@{VQ{(jP6N~e+X95f@fsR z+RV#JA4lxEY3***-Qq0oU}NfaptV4tYVz*0vVE&@#Ildp54Iluh5FxbL%-~3r=kUk z?VHca?%xNJl$u%uU|04AU1#M=M=k9x5U46UZH?^oVgh-j*LvqJJ5JEcJ^bl?DMm#L z64R%yk$2upBRhL(J?EMAxpc;x>hxP)yg;DpS*>)r+qVqTwnYn0oF8A6rSBa{u6lSA)a4iU$zRn_VoxEGbl_TP=)6x@MvkI8&hu| zASL-pAzE!HI3ooK?e~l4W)tVp6?s19jdNgL#kP}^C;SXVfdvUnA^&z}ggeVPF_+X- ze)uRLP^J0!_tc0DnU1Vpz-Tfr`G=1J3lexr1z#al!<7Z!izlAU+mNaP0#$fo1wS>S zs|%}jwk|ckX4scX4h~4X<5(q{E^Xtcq6Pm~yIyvpH@UOB z7WXmqgA=Php&!jocKwMcP-#TLSvGtPs6$wE`BOnkPyqt?~o-+TUL^K=mP};RboxtYFddsIa!rnIvc8@1qp0p_zX*jQmo>7 ziH0_5BM_*?Op%;65gSr$lO8zV`z-rc2TW<2F*r1TI7REeiX+;%@t zFCQpEJM`==oB@FZwlVy>;ib3H(7NY{d0c`(pbF2p;OhX6FQqN=?~u;D#j`As5L=(v zTchY%+im3h;z7dc7pM|XTbPocr5KM)BeRMPP;q}g?&ufy>bGw)N!j#pB6)T{MMVn| zcs2k(9cD+I@;G=cNwyy>5U6@R+D-Q=dNNtDPKz04ezjFvzTQBpW~QlVLE_!vUHfdB zPa&_?YqJJ_I22Vz^}R-I9J1W%UT*y|JN%ishlJbsKR+INg7d_(RV{O(J9+wh50Ka zaCV2MYDOm-w@Xjm<=z5;Dx9C=r^DQuM%!*XNN?^FXYP=|k-j8#?wd_>6VB5;bEAcs zJ5=GUA&>M+R8Tj5>PP5-2o=w9!qb}YbO%ZLvrlRDoWn3O?N}QXEl7wbQT+wT9DW}d5kXfdIZzO!aNT3Rz zV7~LE(_?v(vWxt6eS|QRiUgjQ!%t{B7)ur|zeWyL5eZb`7?;0M^!Sr39=w&jFdMF- z1qrcjzn@Wqu3vwOY~PY55U9fQ=y=>7+J*kMbU(4%FjzR}4hif_Bx%NjR60AmIDKS2 zNFY#!qhfyUVDW`C>nOdor7t}^ zuBVC?Brxjd>&OBw)5Mjd=-uEh0)Z-Vt}iC&BQ1JnBu(GhMnww}IC|mV!v5^3>T1+w z!KK;cL5Vt99PiVskR? z3IwY1Um5A2hq)5l-?g);Dml8VW^0|;;OKUSoEMy5faeV0PJg~iZ>fuVG}nna4NMiz z96$m~g!|ZGugaBOnNR*yfk4&u7!$o^k2+*jvi5%Pw7b1J>ZU#O-mzXm3ldl&ycM;n zqrThHfX#1xP#{p{@Wn`9YJnqZT}FG4b6Bpa{=T&y3te_oK?@RMSrwU7S@m$N%OXNQ z3IwXA#(vV-{NY88Z`a9z)S-^1x;SfvQ1~Pj%0y{W$HB&&m8*LN)3h z!dmsu7E<+QZobZHv}vc{fj||W!XQbbZ{;gz)<&?54LgL>7Ldr!+^<{RlaV$>wKc+D+-3YZ3CA^;W8>TAh_Y`AtCrRaj&A+t<8G>I%22?8%>{RkR@Svi&FB z`S*V0VW9S$->^4V=icBWyp6^Jfhw^k+TJOxrZ`k%WnWmRXhC9g<9yxJBL1XvSFL5Z zXI4@zdccak%&sU9sIqO9uRH#p5cedly;}IkpUUh9RoT@`)+$<%_%<_7XS5)Qv}mb4 zAI8S-l||jHSpW2z0)Z;`<$1c(i<*!mW9_M3+vuLMu~!xLWl#gYzWrYd68Bs0*ZJ)Z zBQq_uR1J){rqFXW_}W){fk2gIkNrBQeC+u&O!)s|R^|sz06c^w6?CKb8pVz zs=l;i>l?gP@V`)ny@Yn!TNQN!pONxzd`ajHkXUI{TtBR@J*kqZ-H+>AYpOfjxUj$q zdVxR{_I7-pA=O%4sPkfjn=TT1H6+AyaT*2LsNVKIY{%@;0)Z;AKOcC-TK%JbBX+5G zgwQ)9f#>k>i0qn;dif<`78RI4pbAeQlB9EWoYk;i+iB0VI)<~t3QiF#e7e}b=Xj+g z*{QQG9;c%x{vZl0NG$N@Uj#o)h?kG{{(NFZN43e=i}dC1)eSxh2vmtDW>wx~tJb^p zik9c^InjbdgHRKF>i~CB^q^seetrWrJNp|wlVTzesKWETBZOVwyNGS z(#vMP#A{A-{l&{hdMnbDkH`Y`YeGKh7WZ#Nx_N73wMct2Rl4?u-ss_=q6LY)Zl82t zTZE9aw%R%Xi($rU@rx2G(b7>MP&LFYU$=;_PVm^E^-*0*6<5b)zM|dN@$(tLf<$t) zeBJxcEy$h#?S$BgrM@U727ITdmU#&Ts!ol`)3wSEC0$-?ebiv-wNlCX87+~~NJR@0 z_2Tn%UA>~njk?-9uaRlDl^GR2)9-^C3k0e<2JhEhd)1Q6ET+vAtxUe696IxWjycy% zMGF#E9{Y8}j5?5cN3|8$Tb3SGKA(O~%VmcM1gaioYsY#ogw zVZur2cshD^r#xLZ*DhpXtX4}hw>41bRIEh*Hv*}8LORg7`5?ZUW}@6@YMNu714EDQInqM`)}Y{&S@nywYp zM*e23!RE>WfhvqkxsURt)dof;?1*U{6)i|$JH|(MZY9*&vKe!jTU#Jdg>k7QeYO6o z)OuNl@gq}Iv><`)7=LeI`&Kdf)0ABa5D8RaT*}|$47sCR+Gxy18hfi~K?2(`-X^xa zsvJRT#-iQvX^z zl`FrsWgT+QC__%=>MB=lO6HG^)hAEL)C~#=CfT22^}%y9bq84>nblX@Yx#0pwzA2r z8}muntqi*}M(6Xa8R?vzB&Zr+AER4yEretZ&_=?S`mI*3&535~pPf|Dg8z&D_<1s+ zi%Hxa(zIF>tK0UVg5yjq1#!%|>7lAjBGGKasU5;eg-BqYBx(QUy-Gsw9&FmtX##;N zJXcSWawe`*EVuV!e(mQdXh8x?oo^Vqu|gSNrXS0XA0ZH^!c+42n!A))O8A$4?8)UR z3R;jTvaXZvLwFc5`=p(0N(FWQ=`p(A zS`zEhLNX3WRPNdRpmnp;dg)rv_#Z|N*fp?RC1*6#(#s6p!iwP46 zR0ZpDbw`yz(%4(`vDjswqOTjyHurg>paluMo4keVazdG0Gl(^I{2~yjdNOvu?vSxR z`8Ys3XQE2Ui^}ATP&Vn_T?H*jV147O)jjViH5Lc3&1R1U0#$z<&(qz%B$Ja1wY{&4 z)1E2C&6}~ZuP-QQK>}x6`1oV$S0%}|3H!R`ia?;sb$Gtc)z*u2*r4qmnB`JbeY7or z(N_l*v><`AM*RHUY-81R2V;qeM+E{^_2+%klVg71~yZ0F6{p(JI}BvmMvTl<{S|fF@Q)g1A@wQbs-2C5fBjxDxjdE zfPx|*AcB}ND`v&8%?T6G-6Q6lGls2V&T*T))uW#C)fVr$_g_D=zIRr2b#-;ss)T!u zVziB|?W47I`|7*X1G56Ss2UR3Lt?!mYa`uA`;IhUlfei^SLrT-#4%D-MEgf2rz=#ezH)G>2WzAPDeRjSkN1zI8KGuUgw^8Xj z+@3C((}1fJk-$@;*gXA!C5qiCM|vsHgdcVrX+R&3 zt1ZK|UXj4Qx<+$4)>JoVYDF3lR+%GEg)LduW4YZ(_bf|8<0{nQdh|$O1VN)YqBGHb zeEeFx^1zfMP=&pFwz_|RLtWmcOQPj5D;-*pz}^chyDjVJj*Yz}j@{XcBT$9CdsY&i z40W{*9ueDqa?qg#3G837sM_*!y39-GMZ+@!N1zIO_pDu#QA!tVa!@?Cz(t1^B=Gbx z79HIAK{=OvTAbwK#u2E(-aYGcj(VxwuCQ0Ew4j>~ElBV^NY6#Ll<|Q_MeBw=I097| z4`4ITmY-4@n;sBv?DWy01&O7jH%ilj`Vy^$8vQWbAuF?v-Vl9!y*UC^*uK_itS)X; zVkgYOm~UyRY5Jgq>>d?pS!HvbJG=I{+nAkltk| zZTv&&ScMWdZ^rW1uaPQy=^OH&haE~pQxo|Sw$nI!IVIH=g|j_KvlEVWu-~G zd$JXQ!x)j%#$M?*-H(<#s?nhZiA&dQrTd$`NS`liX|G{yrlg+pq<=+L;RsYEXP1@A zfA%4v!_;x-^>S;a?ze9A*|Eh52~pO|+IO@%~kPWph$TTGy>1N1*D~va-_3 z5MOe4pIVo=^>40N zY;Q8wOYL(W^K(_c_G(GZ*bHp6AhA3lNP6+Whs5aATC}sTr}C|FBU=8f6GxzmKbbUa zrKoh-Qkx!L*-3{MJj)b)v$)SzQ|0&x6Kdbdjq`!T>4jybvXlD|>jUb2%$s4PY(CwL z9xma?5vamEWb=>%-^x?3+S29=+HiS=MB^HJ@-wgZCXF>}y=(X6liWFs(pg599Dyn< z3mQ#D?M=CPlnY&|Y0N!yB#dh9$)6bOOIj>fOG&5q8pSH08*O~Vh$B#iWm=>8zNkpP zHrSKWyVbd}i-cjFJ^9(K*@><}>ie-M^r755*N@(5RGK4Dh3_Uii|&qjeuvaVs+6M& z?wX4y6!1ItTG=&}l?@5h-hkh+7YVE@HJYIf8_J~VXu4KAn%l7#Rk&9*n^{vZTVA|- zB%OF}GI#nZ5?EKVlgvt+$j zM?P9*5LNsya|EjR9pCTSOp|+r44|DC6)9*zf`1+>|LQ4UJsn5~T+`@~K-J#;PWf%> z`jSqg)Mq~T`daz$5`={w;*`JnpdY!{M12SI$uhZuuSgBb zH`Sp934FWQ4g#qQ7Y3rC>ppSfkFoC-mtu(cW^%X?5wX>4Oi-R5-Hp#=%7?O2pEsfv>S zy)+H6>&+3U@|{^$QjYc~cRs1}GWK>dQ8pjd(0vE`=+J@$o-NJxbgEQI>G$%!Sadj; zBT)5dYFTMQ&H&QIP;IxzAHN{fe$<1$a;T-#*f-SHwf7~Re_!4arh z(7K^E`?en$+Egti$`&hO;Y>nP%QV-a1&NgKjNA_TV_xGq_n=oW}!-aTpccdTcBY(z6Wvy zs$w=fVN@0ix(2vp&>i_Lm5$d-2f-Gff|uEl+$kidF{ zt#Q|7OW||;=%WGUI09ApMP((ix1BIVc$@i8>=? zfLoaIa>-utPTepaT9EkcA0(OD_9qLd8pUz0GD1C z;L09#2E2$jJe+KB^I$%|ytMkC!{qjdi;Lu~Xg zj3ZE0VdzH5I6s_Z_fcoJnckhFyrJ3RUXySgT9Cjp%~lV1E>@Zi+Aco08Nv~$3h9_7 zJrqMoYZrCqvSa%xO6>Au;*8AxIaS_Xf$G z*4s+*yCJ0V*8sWj!S4LdlSYwY)702&_j^^8pnwc9Ju+5@79^BqwvumB3~?T%zO~fC zP$`P`5luJ6aRjQ~X4*<8#*8CXpQ$nAQ91ES%%t*cKQa$pH91Wh(XAI5UOGg^_in?0 zAZf2dAZap0{c`5Sge&2?529}qKOI_-z&DtU(GPZ4;$t6(O)mH42vkMyvXzQLJ&8KU{|vB(UVO)@z=R()XsTXplIP zBT&UZ!7>e!l;Ks4#g>&u>d=A&uG(YcQ8ZGilv0nj7~!nLs0u!RjH9qImit4LGcBvo z@5{Pz5f&t{EU?kOe>yA6zm}qtF8Oc-s<741d~9r|%DIT>Nz>P&c~me*pbC2#tllj@MY{a?n|S?A5Z9YPVo?8#+{XL+k%%{H|6^*w z6sd?*p`}mya0IHbx5RpP-8(CNQ%2GCgNcIYW#S2&80BVT+YQ2$u;5r4!_FT>3rBD# zdR`72pj_=Vf<`us;s~61gi&r5Pt?RJdvl{`L}8kO79{v_gTTc8it(DE)c(XWjzASg zx!K+c$D)***@NlHNgEWjAc5l)Y~-g|pwhq2K)R;w5sp9=M!8wsr+tKCu{W3=yn0SS z3lcbb!ibFCO2N4Rdfw>;N1zI$+^mJ%Gfdei_)+t19~878fulfd&*e4V%K9c=^!B6j zIwVkqQEt}W?Gdb8n$n$KKUZ0Y79?;qi^btCc31vc;Y#cFHRcFZVU(Nogu?=r3^Qli zJH5URElA*~9ELqrW}DPtijp7QS(MBH9obb%f__i>UJb>bWx*u(|fG4 zFS{{q(a@12P=)opMw5MHy3(>+L%Oo6mTNO0fup3X$5J9w**CogEjiwmBT$9y2exPb zy17c6VHG;FpSun%NZ@EM8~5GR`z+`5-SmZjzAT*2HBXf^(rM`+6A%STh`Kt79;kw}I1)IYp4D(Ck0~z~C5irhLO23d*vnvZYt61J{pXDoGtc+sdJ{5 zc~TcK`A~n3Ko$0uSnWeJy60_(I5XCd>lGn^s}DNwSDi`#oSaRjRP zb@V&u)Sy)+&J@eu=%_;r61bNpYnPapr1$qs758=ZiG*Ct9xCDo(u9o7-O$3EcUQouquAK%7^& zNAzy(&k?A?-A^GIWk|6PbY2EUuR8mmM z%~e)T$|BKshw0FQ1nzjmR!EQeOSv%aAbGwfnj=uf_q;lMNmmTC$4UN!kvg;>fjb_t z)o1a+%DE$7$)as>9DyqA^|9|qU;}01@>1e4DS_(`B7r*|v2nGEZ{*XlEyZgQJb@~V zKd@1Now4%4HO}IN8wp&T0SVmkh_y><50b4bjuxdid}IPu*n43s?+xEddBz#y<5#1& zcnK1?yEW_G6}*xB=Vy!cSB&5YRAKLh)w|zz2-TY9h_1RQ9a@mUJ-68oe^+-12j86% zuhtsE5vao63wzJ+b|f=47m8&bh3U|O1fGM(zUMP{3H|oJ76*F=a|Eiezr$uB)#^k> z9$?2QJ_yvI1qnO{kCl>%c|zqwRp^mHJ{*B6z8|G@^dMn@wdu|({OA%Ac>W|?ALU^} zE?l;x(UtiTEL7p>8H<<9o1 zk(Wta4m;DA)=jw4J|yteaTZ%@F_4U3)|I9w8*>Dwg0V>!r!GI6e6;kW_ixwaMlF%R z)6?1RNwek=`-OhAnnhWTKouX;-}3DuslU^Y&dV;XLkkjk5-Qtsd1obY^xQx?(DV~` zRy?Zklxw!T@r`Dp!(2Z)Y>I&nElBVu{iXEmCLUsQqh{NE<<7iE6`pd<_Ir)$Bi8fq zqCHBM*P#UoJXw&f6HXp2Zn)W%GRY0 znk7~==t%z=#}lZ+^DS6Es?Q8DYh$n?Hyv7# zz_USFDY-sFEO4w$PZW0I2vp(u7Hnsu&6p@WI0998)*9R8CfSfa z8dH~AH?6Eg3lg}8F^jN7nNZQ$gjO$Oz!9k8PfK&(+?387VMvGOz2MG1Lqgrp^uPNd zAC9!4raf!W=C}Xm2vn)pzs_@G@1WB^Rj+OptXR)bcX-&t{D5RndB*b5@}u*uq`IfO z>#x^4W#)I;dQ?(>=Lw7ajeSS;*Bb-3 z2`5iNWVXih;TqD{+T0zs&AbqX&av|?wNm|X(Sjo=%G(9dmdW$ZVPJu;A!@}540eGzW+?1 z%B`15^KS-DO+yxvKFALnOeNwdqaz6rYzEHQkl(1OIKgvnCn6U9A2 zBvAF|l2~{}D_8W9^*LHSuB{v~@|6CXl`EA z{XVOMOZ|KXEJbR)TTH6Zf`sAms@ zY!IfFb}EKI3lcxSU3!}Lfds1hE8B&fxneOs(1JvtEvJO{!EK8nW|k~Tz7?43Eo*!} z2&WHP>#x-kqCVZ<%Pv}wh^zfX*tE1|F+Pw$6{e8CbF?5)()YZu;kA7+K9E4wpYQxs zD=$*(FG*h`CyezXV_K}zU#s8T;%jPbO++_ZCmhZH@rC>8TlhV%(1OI-_8SD*^9Nn* zo$LP#RUPb(3Ym}Fk>7ow#i-30LHWl)uR`B{_JM?5>KS48tsnHC2~_>Lh5Yk-m#?Px zw62F7^scPFEU}iW)ZDdwli%+HEl8{w<0Th9U#kD7f2Zod|Anf>$Gqg2MpKF*Si4YC z+YPGsJ9}N^+Z7k;uUi+m%Vn>p>#unqs6u+zu@3U{$W_G<&D_sRpYHxBqwE=|-w(a2 z`<=bgMPqF-Wfv_-{A}SA;{yp)jlH`;>Z&QO_CX60LCdoxS8L~DQic7@=y&!~#KiyA z=VWiqe|n=x1W$04cCF}Ej1MGGg(>8p2U?IwA!$<2lAVh2fds1lFL!S5yjm@dYAM<4 z?4DoC+*|*@m|8wnXhFh#*Vg=Qt$uuo{!E|>d-^*8kVfwut^qcFfh2)P3`|n6DaIkWiyU&0Vcm|DIP!pvqvJ7kTBE zRg4d`AYoq7n{4gZzZfF(LKjjgJXlb@Z(i*|HqUFMzy6s*?eD2V3lhE7dXT>c|DgH2 zLIPFTw&MwmQ+nBHNxABK^{M*#ob=Z`ffghVbfToui7o$wK-JF@S`2}4pQxox1+VYj ziJCt@Yw%(Sv>>r;xSwz)s<>Dm5~yNt(|_V+{GFo(3D^7-VSQL9eG30fpbA^gJb{sv zPB|^*M-LwB@0R8I|3gd$iJj5S<>N`OipeYdFI2I5?Ej%Bj6`a?c98=!7ZgKa%t|`uA=i3XPp@Kc+8^Rq zXhFg|x2t@nzE3eekU-Ue$zA1`Q@+IzXxX@>i##?i^#3DONCbE6B9~b?s2CrZDpX;< z@lOyfNDN4Hm5ndXEXD^CsQUBsP}`xu`b!rRz2*8zfsSg;fT`tEg%%|2=6cDA%A(@y z-TypWRADTW_klgEMzy?UmkYl7F94>NC(we#{DI!`)6c#3{QfmS0#$fVybtWfeXiC; zF4{F%Qvdg7uIsOP0xd|8@NTk0VCVlqpz3F?7xNuN3liRIJ!J20^^5U=1gfxC%-_e) z+Ccwb3y-vubw6AE7Q3~we6_fC3C6GL&l@M$ymr^OSbx^}#iR-?NW^Xm7ryrIQcQan z2~=Ufguf58AVH3|5|$nP(f|B2fvP`8?l9J~Wq}ttH({~YJ+#Y?{3VYMWa4 z-3MBbIJMK2)S5rze-Nm`9QkuzA@TNFXVP@)uws1Rf1wInoV*W=>36t(N;2=$R^NL0 z8Eq-X2U?JbdwW=V?$o}Rwht1hVmbSVu~f7m(e%|u=}sXn#s?Cp!tpl#&hM4d$X<0U z^>63)dzIvk15EVSYQI@+v;6+d(SpQ=h{|%!JAdfc{^!3?^|MV>j1RORQSwe5dEL%x z`V{i_fdr~p@BTld%RGT`xT+;@N+qw_>i-ubY&?M$BuY*xk|rK*T}-NwKo#a8?*lDJ z$bCOZy5m1$?|&vxg-@0zum@SSb$50ms-S-cKi`|;zfo%4r?((6*QFadv#4t^PZ0kL zRX=NtVhFS#k>l8fEEpO7KL}J|Y=FOW{0`!`kNN&j+?OZNf<#q&C;92l4aKMGKmUcQ zKSzXd*29Sp7IGttA2AXv(|oGXg2Zcw)^fdG_lrpt5~#u);eDV5iO+Rx<)ZRG;!J-g zP=zfHw)595FKYZsqkEDtMS1+JElD_gURvxjoUK*0C9_`_Nu>;j%Swzbxqjnsse#uh zHg75BNI3N)cH*M)hr~zQx{}RigGu9WlJMzu57ObA6N#C1LWqCbo7i=7BSPVFfvq?k z-k+Ad*-m^)i$qi*ops)oOg^Gz->LVEXnn$yzS=^>>)w@Uo|!W-O&Lg1;){gi`y5D{ zTfxNKpfovmq&?ZV*@0+!S0(IJlDl1K;r>0Mu>G_0FtR6+oQ=t~bd7xUWhb(=x*4&$ zQc*tb*pa+A*M=-AD$VX=_?A)h#KF}>6FE*%BD~0x!er86$zZAF3lFkx_Ea*l;!x>< zrw@7iZ3=m@%}8SFCZ3L_2U6OJz3bHxNklTa+;yhVrT=>EGWS&Su1zPwHEWf&-n>-u z{qmZTgBRrN-08}@V@V{sV*??_?v->lE0sJOs?*AO*VuIm**tct)?M>~5&nB( z>4q9kN?WIJr9|R5;BG)cQfDQR0s~Gl!YP^Uu(|56 z_(ii#Y1uT8oP9J$nDf#>mhSZ?L!QhLYINx!8<%w>wyjSHD=fOP`f+422WMoPmd($3Li^Xg&ZkmLlh}=|1NzzvQL`b zG?Em~`zU$6JI|hA$`x;FYI#=)FWRAW$qOXS5{%{NBcDh`^LvwqK8<9-<*no%>Of_Sh+CL4u!) zGqH{*wHQ~KZhfIu(1OIkL3X5c>@8tLX*E^TU3}=Xn6k9yo^~98Dx3$T(S)#5Pj;~x zzqMw!Q_zA0#!K0`mP-TZ`(hd|^bex_j$Z&wg~_tOw#D3y~vG zg;71uaNm-$$bf zd=^X%+T9S})#eFQ@u_m08ADee7$J77(^#HY*JfA$A2JM_E zp1sgXK?@StdtqyM-6Lsp^ZDZJ!a$Bd73PRW<1uI$ZL@xrXtd9T%PSTy!#B~PG=Pt{)YI2t#>UAYu(qhOm_EA$`-8r7HjyN!~u zwXD&UbRR{@ncm9mH8u)bkeJ`JJ8?ehBCT>)>#JjJN7BpjLzML+cmh?}T4rmi&0=Z) zYl+IRBpU@SNMLK3t-JG$p}zOil%pGL6tp0*Zgm&3rsNRmWhXUNwjGAkYNKW;o6~p# zReURa@S#Zh`N9e%^MH+l79^^4>PUp43#Fx9RUb#~hSG(-wK?29|*sj2b2UF8?l9Iwwg#@bjR2fA0 z(Eg{&>I$-K6dVo3(O15`>wLchZIs?XmtEIK8RKM0=Fc&ZZAZq)57{>=YFHK7J8+cT zzlkN$uGGj&da8L9a$lrNH=64P9J5i-g2d0S-OpZXpuG#VpVmVI*4C{dkL(#KyRd6=tD2m%C|Z6KWJ%87C?P+R^ygr`vZvD*G|(+r zwq8LC5|tRe>rz!&n4s2)2iptu#y(@+^(Tut0#%qJY{&OD?P=cmM!Kb$v$(uM;swh$ zxl>iS;&k5w#Fp3C4JqkuCDFi%gXY_mSpz3(sJR#2s!t! zdc>uJp**Hngxrl?KS`=7D+APhwznOyptllg>B7o=P+F|7M?S8pBX@NiD3@JtMUF%n zGPR$)dUHK8vAKzCTt?j&=VMG0+I*#;}3^ z(GrVR_{xmwcr9Fts(MY4LS*S$)4N{VvrbzK`wX&KVu$hW*XR&TY-*fi+y^ zn{Vrp%mOF5)cZD!=-Jqe2G=px#g_c2pals`E!#E1-IO+{X`*xQ_MRh9{f#Hj?k>Igl2eseGip+NPf4(wbTfsi`Z!^R|K(ByJtol90Y_<v@?I=6^Q<)I~VeWK( z`gi4F>^>#zh!^pDV*G zw8IKokT`$EjV#|~BfDCuy}Lt?oM{8WK=;b|3`d}9Zjmc-tyfEKp4W^KnkgOV?uR9G z+SX?kv>@@pz>U4JPL+RFvx; z{zt0uB9Mp<#IktSeI>nTfNd zO)Zkh@WrR35o?!7m|E6@ToOeC&BiM`UX9@H1Br#T#t@@Z=cKjQmop#j+A`uwhEgVe zBuAhM?}@GSemaV7@9U$~wX{^cHl`7SK?|i=`xwb{QW{y^eTg)EZj{vdQ!2@C_H?ptN2b)LRv#(5YdR@x+g5tLa1|q5 z=f~5&-_4YTUmGZBL85Atbh6Zco>cGd07fXcMpKK2O_lzkRvdvUOfB09Vbo~q($GaI zaoLEw4uT3@d+2HgeA( zi`SS)o^|7;mrur%m$!yXg#+43m?NwO@H&Mio^_B;#7q*V1Wh0jtFPsoM=j6q)qMil z-=&n4(d9tCW$Fa7NV6c{a%(M?sux8mbf3u+$=|Uc4=qTT+f5(_1Fa=Dhi@zhY=mNLfSZm)=Ftjgb%X_T9EL2 zlR@r;CgeMWw`4vh#-z|5Ht&SQK9L-ODn3$leqAE{xaqMqvc1QcfCCCN9zT zj+mfjG0PsK=n{{nqF;?5aYCO2(zijZFn)!b@E|LZ3@;25)*A}~MnBo^#&M(Q>owM5 z{7HW%bcu_jSs6{m`c2(A0#z7QWu?S9jygNn7wfL>C87n1 zz0<~$?Ey`M1GeRu5BnOUsY&D7;$WoZ^F+lVco9G*-&WC)QQfC9-h%hrsyMO5{4q0tR(Sk(ghx%lL){FE=w_?P$BZTgB zw-qg)HKAEqCgkGdR5H}ug!sNOAz{a3$-|I_1ZfswsV>qLciV|AEt*hN?XO>-6qJf0 znKv8#i|F7g(p}@JxGmb8;(sC0ZfAYs73NP)T3fJG6$Oj5qpO?fdb%-3po+hb1u~(} ztCbh?!mX(5^?Ias*SRF~r6H;A!g?tNlgO%Cb&2gjE0W-lMzV7%GapOKh_q3GkvOoA zB}EGod4VS6``;O4jK-J|TLy~s=9~*8p|UmYb)g=qG;kidlx0Z#FV-Um8_Xk?>kNt7 zd;RcuE@@^~mJy!*lpa4DLYBl?Q?=i(j%H+btWFxUzO2u*Y@$6>ot((E(En~Ws1zdx zH0elJo(v&f?lq=pL1O2mALA`AyOw0c*+fdy;^vYyx2-6uFoirZVWJD|S#~SQ*x#6< z1quE>TDR{;4}6?LKJ~535vX$C&{}^V!&f|Gb&2ig9@OB=dU7YXCPfPpOQY<_%n|d* zs|=Mm*Q*ybsx+B&i>bsBsM^)aPVZxK+&xBU-ucnvwI`D$N6S#OAkjFny`I=u`79%D znzOz1bJvmwuQe1cNF?qhB=7Y+QflEbMkofsG-~lAlDqGfhy?%Upc^SQd_FNbzM2syjtr)s z%1t5>$4+tts@&f>>wWZSuz?YuCyu0*dQBjncc+S{%6sT7E2sMkuiE_>iJLwlQh4Ru zoftixPg3?JGosY|7<$WZ0%>}3fru6)##(mP|5J3@6h@ru5=}i)SChC68#n@0m_k;= zHIJlMDo!HZXYCQuf`s{USG^C1v?a_(;fe@as>~$Pqvb)4Kox)IL)^#EJEhZ!)9Xee zjt}CP;KqkN^*#zVtYU2j8-pY&WX~tBr>AaSqrk5ST6 zD^r<|fDy@b_t!C`&A>d4Koy^=CUcVMwe5Y$j%xYq`RSv3kqQ9|h->*- z`A(OA+{cNW?0k)8d1MlOS2K>3I$uIT3ljW@d;Qg8=MnYaFVwD?j^ zVq@ETN7AZs{YblwQxzOJ&fd~puZq7P@UKzigoC4KN_;=E(|5drWB*9x9{TYXl)KY~ z`ADxinhsnRN4EQqo_AR|tu^rC}pJxKh9O1cu^ zb|mZ2LekCpku;^Km7eJO^o8Ww%T|9~Y0*PQyj?4@{mzDwcdeT0cMJXbRg-Z}fcmx5 z*2yBN`D(<=ViP;Z^x7oy-P&AF{IVdy&m1^rKxtW*B_yPWHAkRI^>N|MY|?6+A@gCg z!G#{!UtP@BnCi+X*5vlvk>vaPO8Rl<{qd<}daSW*lW9fTx{W7KB{kwDuol46(gtF3 zqLmIU>i_;C)ayr1lgRVuwHXoT(veOe7fCf6v)_ncDoi1J9$_La-)Eq}w2M_tq2pM7n9xdh#vgcjA{yCH{No?gfstV0w@^$Jj!jSC^)Sl7WS0`a557 zES%ilV=A8*+Khah6+-5}uEu;kGt|;tGY@guM++TV)c^fOsMmGvN0K+DYJB(A5Wb45Z0A2ZS6$nV52 zl}h}2Htc!Ka-=KX4i%k0{U}$z?)=~P^lLv`mb>2x9aWShZW-86pI5&uNVH3AK^{%> zBx_cy&m(6;JKFE;cv08#hmT(bs?=2d+Vz%|tEKH|E00WZ{|Ga^k6)I56L}X|EcSJC z=A&J%BR$`Ifw(8RzMlAHK_Yf{E3)(kCD-cIV?^EZZRy|-%S5C4jW_~TYN`Snbtajs zTQFj4bUSuZ$`0|>+d8_$M>fPXvNc&5VX7}BUAGfrZ`4Lcn)Pw4+R{61H;7T?>+8^> z{_ihBy`I+9oqQS4lKH60Qf23tE#6OS_#5#{#i#03jsvaYc};xQv5Nja=6AFqk)eV< zRT=Ya$m&LdY;o3(v~V;d@2^@hA9J%D=<8<}MenNBbZAlk_ZOjFe;sL0l0UR#M9%cK zbhXh5u|r6W--ur-%n^1b>o^D6a=?CZ_CllI^6D3%`Y4zukN`y;%}Dchpf~GEV!CPF z--ur-mH3r!8cmCj4zx-A+hP!@$ldwB?`d0XGt$0M2j*i(?{+lH_*P;98{lbsI*+9%)OnUcM4<-YCHls8UlEBv_O97tW0EThpEnd|95FB^K&u?{v~O zBHJH#(?5@2JEL8B)rOedtU!V_gb{BSx2J3Sm#0=GZYXF`|MwT6UjKI|wz_{i(gUHT zsKN1~--ur-8+&_FYj0Ju-nuRG@y~;H)LK`P7EXDppauU|y^d&XK}Ppg$JG{PwWr_i zeH4$M{qP&{ONF_>o_Y0lbX(C!(cSy2f)@N=^?G6(EAp~tN9Lpdqqel$k#}P9ZH?~V z#4nXf{5N;6UT9C3h?Qv4(+gbg{yX0;jjm6sHS=OVMp_B9?TZTZf$14N@ymk5%Z_bG zr{`rzi zvLBWtCC7GVL>D71E!V=3)*`tafhyIi=%JR*RJB)bC%!-Od8_ z@ohl=UNB9;|3X5&E-*48OA7ijAN9sk+9{$AeP4UtZ^SRvZWCLwZleLoD^y2#dz{iz z#jPGacyF2}eOetfw8H{zEH^Np1&do6V=s7+I)jS5=u zf7R<_E_KO(HR?!pzouH+afuP#d1LEu#4nXf{P%ereoAP7zd7Af$L&Y%{+yYos&X~e zNt?)F@`?Or#Ixcz;n=Z3%*WDgan$HkAM)|}7;Y9)zhEDt4G{D0_vL3Kv6(d`6KHbP z8^VcDe{O~l68zl3C+`yJ*cDaDST>Ub=MM0+s=SSY{-ml$lug*@0J~)g%at|cyqn2Zlt#AaYFb~;Dm=&VvCV7c=yW?&ycQHrNw??zrFq)RWGKb7OzKQdJ#2!}0vU|SM zzHl7O?xUAe6kRi6FB!CH3rC;|^N^kGloUz(#a9vIUu@v=3W@BpzNE^EO2YFA>Ip|3 z4-chBXT$bRrq8znwBO*=))kb*m?gRW#Nq|vh;(4KmtwV+Bwmrjq3~T-gBn% z!;%riX}X=zyRtR&Ay0{*g9g~NNETG9J>C%y4Qe^tlzvd=w=Nr6yie#KqqyDQH20pUc^O(O^2Q{A}@R{ka^0 zs(E9(kw)Lg3#rT1v*Od&52U@%<%$E|j8)Kr1kQ(Ld+(QQlKh#tl<9D%9>bK8B3y?%N_b0#%qJ8qKL3KN`K^i5UNRB9~W4Z2h|vaT&B)xUoh( z`81&MGA(JKl4$0`~W(l z!(Zau63aLORaipVnJ@l>Xt`!dV$kMITuDTNui;u4524|+!o_!IH*f^1@J(aSqbP#S zNO2IC7Hs9-C?v2(Wh0{@ku;;RyV&LC5{^I>))=gBa3zZV71COqvUd?zGa!NWyhc;v z=5RW*gq?V%h_6df#n*|_k>T`G#eaxH%3`jDLju278jaI zj*iob6Z4UmIh3Aq%pqyx6$LFwV2NR+`#+b_9uOuXl39Gk34DXu{KRS@bpG)5VtLOZRm8J+i4Sh7oPU%hPUO#PqNr^_DtDri9h`yv|6rcgplr8K6>em{;t zm3sZFXQ|NyeQ=`I9Zl%a#_?RA6Z?kfo5jc;cBWUmR;GE&CUZWJ7N>9B|mE%Ac;z_>DahK&wtT zE#5o1oFh<$Wr3aB*CK>gXuDE0$lby{b0qw4^dr&JT!f=kjr+V|vkjxFuyZY1;rk$J+|EsWF)^PjyGWGSJcx8?xmo+qIyDY=!D$H1Z`4FA-C5=cRN=eHW>YO0 zN++yZMsE4&xOWhV$K@i)_Ah_st^TY=AO}AmN(0{YB5Nz{LPz`%4;h;%gsNVO_~)8{Qg9SDbq!?`WRO)uKq$ zuOChF8V!{yd#mx?H}4~;i?)pN;Z`0;pbGn{N#*{zPUVwD@`0||b9Vqm#A8a&lO zS!wLb5vam7vFuxGK8k+X(_8thYs2Lg68y}}Nt0t~nR5LUUxV%(fht^U%X%#JV`=FV z;fjAyR|PFdyx*KkzQ%2rG_@wOyb7!wLtR%6R~#Gpa0IGwb}O4X@H&wu8h@60K?1$o&`qwI?!ytNy4*006#0eZpSr59EcQPhPc2V>6Kb9hQf915Bi6@DXnmyp z5~lFnv2kRmW}4%Y5OpQ%_xUlkv=YbafG&RM*8cdc@`LLB*8I#4(^zN9=iI)S8iEiHt8 zD=qtcjUlJ=T!hR#b*06=qr+%=eJinLsr3q4ka+Jgnk26KtnL4(5+llQi=d%>1<~1c zD@ULT<3a4q;!{Iu;t+Gut;<#}QiMdQHzUcODX+B-f2-r?&slqSSQ&G1PWhc2fhvp| zv2(+B52MyEUXaOMcPMB%*Jsg25j5D!z`-~`B z{<%51+9O9n3lesYiDZ-*lkYf8EhUR~MbUc?Piq@*;t5pkKNCwnm2${W@1?Fp8umGw z_H8v)?q{=3K?@RIsY&F_x;9cjLEQ=AezRzL%=Ca=1eNxhVCO_>Y|B#2 zM}r56be+WudE15Z3f8qaryXll)>oU5KuKOH<>Ro%3R;lBZz78UT#Kir+HH_)f9=i@ zsN!q5a?MB6^H&n&Q@$|@T9Dx1+HO_jXwg6qY4wNk9DypVU0Eyq;7Gcq$r0hUl*!e* zNbqlMw8bb|HJ}qYGiWkLpbEbdthH2i6x|THkfaw);JyY(;NBVRr15ugY$o}5vh(1` ze-Z!PVFSNiY(_jgU;X^D@!~(VS13`Hqsd|K?Lwt_|42^5M-vmH`N9qDEve7+(Zt?q ztl-}86)Pnh6C>%@?1AE>)L9BzkO&@|Lj23P3d!zjxiWHMWw)7|SZz2@pbGZ`VJ*v> zY-O=kL($^qcy6ZVfFd|pLX7){qEA0s=( zK?+)s*zb}~>}PpuUw+@ge6+jF)}LD}CWbMg9Dyo6cT1ZjQv1$bNcu)6uFZf%n?2*% ziYoKGvmuL_k7Y55G_=nRA-Ac>5vaoUgGRGEHiumF5Uk;oGdy_zoLI|H^JH4u8-~86J~D_6nnfqR$7V%9FUa@2mlw%nAz7*S@%7@Aimm$>$sU<>wx2JGG4G2vnV8 zGf*>hm-EeE*)kvH&ZSVpBabD&kq0HTAi=NTN$8tGdw!0SNyq9k5~zByHiN7-=`Pva zG-f_Z>`0(-O)814*3?n(88qLNPNWqjh1PVYg!#teKDlG4YnLLDKJAf=79{xneJ-aa z(bM7i0s`RUW3$8CRF*Ew;JA5vanoS!{*EtTFU<)CE$yNF(CzIcL(x zldsB5$Bu!^9B~~JD~VH+=)y54$lcKW1T9G1*pWdZ50%yKIJ}X~Nlh!0O!vFJCSkd? zIRaHSgU6GejVlY$VV&7CPfkjpF9viMeWtjPriQ7+d;3!1qu-wVSIg7L_eU{A zfvWgzV~Kt8Dq+#6K8z^$EuJ>@=q4 zY@{H8szn8Hb-8M(a>#&g#RTo9lJt=d= zob>@5fvSadhLelQ_k`763L}=?97@~InkP!#M=EGRqR)U>GEX@sWNtjfi0E(O^q$*t z(Rb`jjzCqf4nxWD$+v}%)@m%{WI;6TG&@LK)iy)HZ#dTT_}yje=;y@JfING#{_f!l zT9CjxU!%!*Hj*|tVkBxUcmh@U-DTzK(rCKk<5SYBkC%cLB(TnBBXOtVsjbysvY>4j zjzATDcUk1F{202=Gn2HD%@wpDfptE62d9srVO}m|r9mT(Kox#>+5Fux$&|W`61w|b zm(hX**5DdV{@G;ucia-`)R?^-fhzn`v;E=fr_h>1hs%A>M#*SFg8v%$^h&0s*DaBg zzii+LRPil<2Je$-r{;&{s}ELkD_N0f=#@e2PlZZ{Qk%1KRl08yoxS#!JfW@35vam- zuo}&FwyTO?@G$XUO1^^Q{f5m3kmr@7gmmN9|C(!XH+&%7-*K$ic@{r&0Ewd$2a(M0 zF~aDD=B&rE+b^7cOdTY4yPnI6usxu^jW#@c8y)@zB-vbx&4yO!3MK3bP8Uin&} z82g2hcB@VZ6UUU5QT5kMHs+O)D>yY&;|yWTgQ;P9mKd}zUqK5J=#SMU&-+rN#mmLY zM+!IsRTYv35}&Kga{AHG+-!02K%PJq?s>@O2>&0h-aD?x?~ng~*_0K9 z678WODx_ZLoG2P12^p1?v}j1XC=zAwolUlEb)9p_7TL0AM)uz0dtUF~_jmg~&*#5x zx5wk&xn9?GuIsGld7d#5q*sGExP4l=lnoIQ@J$ozY8OV6>%Uisw)U_@Ko`uVC}s!W zHgN$b_QUC0JNR*+sYa%HdJ{aH2AHtvl3D~xa zm4^9=5+X=l|}^InQF;!lnxjh8II-_@HLR3HK8IK;~6#W3RXb{$^L4oL)b z$yraedyFL8oetyjLsWV{O7T$S7ji)Tx2H3OZ?ou^cn>4)HAit|R)zGQLt^fWVaTPq zqCWZ6Mtm7+^G1;3X$SCx%;ORPUGS?UYRRx5(odoIQ}J2p>jR0smq(x;si)MpznX|L z5>F2&{e$=6zgx~o1a!f#t2iw@Qe=p2SB{@Gyd-@^A#rWTNVMbdHMQ>{O*MyR=W%%6&FkKvDKF( z0=i(^C3dnF4kmc@VXRkjOKR01@wWE}B;HYVoXBi0qN#@alII&w;q#>**{H96NV`r; z6dBr@Lf6^!0VvYH5im&wAm8|6-dDQrc!;3@*{UVt8lxPPbC7nLQ4J7kIJ`d z{|9EGjP^YSlJNoOaI3Yq8B`zvpTC$jINzUCp1F$WU6Kjta%tv|RyTO8Zsunz%BY_o zKyYmper$P}K?M@99;;Ld9{!}b;1*ss{GvoaSIM0IXkYA2b=qJjQO2elgGkHLt9W$f zDFzit!1qx^_LmPN?w{`CL&J|t1a##l_d^pNURHlv&EuCd#( z`&rK5mkj20hTlpt-|i4bVq#11&M*6=Zz3e*5#+V*W69m}m3YtVwGshc@SCqv_1+py z>djt`=cX=_zU`2JBUVupAC4zQ<}-1mI#(i~3$|S%R_#;*xput}moAT#+9*iCakN;+ z`I}7Ehfc)xmtl#JT%ZkBsf>M7Nb>4r+~BLJ)Yd`*&Ibr$YC3swWDwT#`a@xR4qdP> zAu=edGl+9_Anw!Tl+L~Sn zAOYuR#MrrM4hbG-fVbxjRm1-UU2tAYrFz{ro2bv3;X`j?rTHsJzYD1}5)%R+K zzZ!gz2;@vH`jEaR~H@Vk?3}Vvt7rIj0Ln5H- z<@+hyZrI6%qkmFe*^wnWz~`Vz)lP`GuPpR3IUbIo&))l9C_Fo%`Rt9fdq^w z5IL}W#*ro4THp<04geC+1)~B*W^U0A)_xg{uzop%3M61efl4*Ic|5t*v`YQ>o=iX& zj0zN^qIwBreAPheUvPjy1rji#K&9Fq8&8_tTtD7gmA0O^Dk~kP6z^nE zfrK1uF#6><^5~a2J3Mcr>@NS<*K7Dh+WNw ziP3h5rO03MWiGyBl}p_gj6>1P2)SD}Qc~xqqQq`L)xlLwlrJ-q(d0w*QD`j@#FY`L zMCW!P-oLOtg$g8mM4n6iS$oxaLp8Y#UnHfHqTm_$WI`W_fUbTfIjGr~Q);Ij{RMGw zRWjK#ZXwQiafd<${-$+v6U3PoP0`l2DS~*_J&`Q!T#UOt?8u-33Hg^duZkxhQ`g}S zDUK2WT@TJgqJukZkg7&=@<~IV6yo=)6@I!ihyA=Y1pWISfzson6?mG<-)=#ucvLnz zlB*+#1|rv_U&clB!gVZz3M62D7SSV1%Oa~X%Ta2ul|(?7%jO_-GHfQQ@XHk|ii5l7 z5RyC}^-|SmP=N%@cq7J~cP5e6C+DN1x|1j*pbO^xQK?#s6<+(2H1u$B6om>TU``&D zYDM~FlKDLzEsedaKmxkp87d-|p6NIe@8yo(dY@o0hs=!m|6h)!!phbElTW64Lp<5! z>yEmfIK*J48A!mBUBoQsx_I*7UvCs%ArsJ*ztIbg?KvA6rD<~3+)*cyg8t#iS+$ix z1rjiekI0_%H-VInU4}O3?UD%S>Og%^#Qt1#ew(I@CPov8(VL^_pUCkG6-dAuqf%)- z7STIvTHt`3tr7uUF6;ZFFHzBmA6_fUSW}Ql-rC#a!uVwjDv*G6T4ZQiG>-gP5{Y|7 z6iWnjEqNG--st!vEf39Fs^5|b()i;p+@r-RR@8Sq^0HN-Pdg7O+xADI?_N#Nn5LJN z-48>Ma?=EDTcKI!9M&_I9C6=*mmQeE;5Q1=PDjR|9*+&s_Rl*7F*_-e7=77^4}P7` zpaKcGj1Sw#ki$MZv1#s7iGVJH=OfXIp50K3Nt%chG2uxPo_L_7{cjk|O$4(X$$5%K zza2~N{k2DaPwz0OKmyiKu`1IciX5nPM)8eg0=nj|z^G-TIcT!hX>nB@(_@Kgtq&UT zy^=u%60nAfsN!)^Wc`*UXvx}YiGZ%c0C#lDUAqZ?K*s6YbNP_f$QJ%()i z8HSfFI42R%HFvHzDtR#kHT!x|lyT2_ED86WjLozTGpIm9uDhwX!bsbxi}BQ|V-f*f zuNwHH&t?Q^+20Ulbh$Z{e03Ord{=65n1c#twt_jUMAS?2NV2kt8ol?cCuOsO1gt$` zKj*2Dq@vwGWV61mL_pWcuTIFS&Rq1k^J{TcN1KI_r_V#tVS}#>Dv*G+N6g%92`0Z^ ztwlH7R2&k})s1vRCm2`1ml8et=gUlIXb zmx_9zl@pTC4&%?F47P0)xhwKyZ;pD!paKb4dsM2ZH^Yhk&j4)X`%NOCt4kv{bS6F+ zB@Fl}$_Ne#CY!rWz}{ug7*rquYmbPnjUPh1B4=Tb$S)EBT}NXHQrx{!u1*~>*XPn{ z7}>~|W8Ucrg9;?%dey9B06E-lGj?_UED_KppDb7XVK6zIw+j#Pd&r;yiN7X8(VskP zRGX&B_t`IZZkbo|Ds-1|FX+D&MbvTR{G`%LBcL#};Eke-nzd9%^uU3?? zV@f)Su}Z@AYKauLG_N!rwg2=|%|C7`*ZrJ<_R%})#g%u@fUZE}Bs6|!6LjeIBGJ>2)6O8ePa?3!qWYmqbHxh(8KZSJY?2a$H4wne%l23he6QhaF-_&?v{c#v7kboJY#VpQ< zMAFxw2i94&L?WOIo;W9B=!wYU5!@ZCH*Jv4qJxB-b9w281maTK6(?+6h2e>HHeJS{ ze(uNAM;@;HpVR9;-bf@pn{~nOmM@mB3KB3kwpej*o=l26xZts;rb+~K!MiSYXQGMZ zy;}T^%2es@LIRGd#92c3Q%S{yzSw4^i$p*dtUcoHMx_z6r`~w2IA#ngkbq-DF^l7! zPM%#1!FI_tQoVvM_!fv(Eg_vC$5EKqT$O4&B;XiVM5Ks(`df1&arc(9Bm%l%Orcm4 z9-BeVy%~n>eiln_EhOM5T*RKEOwu#h3xAH;ED_KJXKuwlmPVPxtCtgYp8pp?1rjjl zx=PhaE0Z+Y)E<{NY>y!UU2v{f^uq6noS7?iuw4ztP=SP;jeWjN1~H%206&fBB@xgi z&mr$6m@F7+h#Q=;BrqE@%vBAuH;Z$A!rjS-(oPsUYEkEVLv7x}3ua z`d2UwEogm1lu`6yD7kmp3fnKJPoM$`c#f({HAodk4mQxo2FG7vNI+LrqBpv|xd5#e z@dje0L9EvvoF0I$UuZ35N{6}JVGeXLnlSb!ehK|?hnQvrDv*F#+C{t%8cbXrd*i&V z4J87);1!A)NOcH#pxq6xwEKXe0ttA|tjKIs9ZqV>OmKw31Brkx`IpZf8bg+uo8bhz z3JeuU$S2-jA32^3n$s3LIqs1N=&D-nj~Z4?M_+%<5O?>{u_W@_+#EO8UWlOr3G<~P z$Z|KT~$wL1{cyz%rX-)>tw!rxyv9~Wdi9BDq68G8Bgh2%o@(jz%R>>s1 zW--og{#=?Vf-X2qC9Y~?GAUd?2bXA*Ve;DAHNox>PAd$FjBnmv7j8=ty5oPqs${-!) zTH&|93^632ORgmY)6z+~l`$@z;)bCDiRO!jq4+_GDAIk9xT@>-ClZJC?Q!p#NfH5F zu!f4cj3`VJ>s6z_f2|43Zx3_p!(8qnD;MoW`jmV|B;TAs1rqX?+H$Qg={?{LT3M_w z5zqxQv#V77pYySo}@9v6{LZL^7g^-c6Fvl)g8B*JQfkXdCRx)FX;)b{x!CK31C{iyx?`BF}D z=z?>Z;%tsxlSpsdW9Ug>J1J8-BsSj~hVE=GLQ_lki4&n4eVIh8ckV=onv0$B;H+rq zf^)JWuR*g(2PY^@#a@x!LWB?7wOOreaDGPQtsNdqjD{}8)ph1D zs6axV>*F&c$n^WgxN!9jiGVIRjuz`5ufs^ki`($`ce@x=AOYtV#Z?UoCU<)5#s^y+ zlL+X7<7kyCAUu>*UD}Jc+}+2Z0tq;)s#1-6Fp``v*pC-GGl_sMd3=6(d>o0d-HiYA z3zOzv;jAiL3sI?t?~NwrJGbKN>3Iw)kbrkVwIF`v zknw@vkzsm$3KdAeuY}0TRgps$mDRy-&$mU8fG*fli%cN}IV5WCC-kA-0t6LEz^|Ri zz4JGd9ABx8`wY^-kbo}Owu`yGdtz_+!ut5Lt`mj|B;Z$DJo9fUMC-H`-nS-ABA`od zKTdo|CENH*q}482>hD4VwkzW6<0VcdiM@dyq|cBD=#pEttJ&$qE@Lf9z8EdFYLNKY zAmG2#3f_Fu%=~_Vwg3d|=bir|gh1e{?LbI2)~ z!jfMKB%lk9uS8xoaYEjfsrh(vn41C>NWhs}aVmR$DoG6}#9#9sO9XVmC;}0~@=j!E znl}me4UJVp1rqZ7)jyYX;uf8Wz0Op+K?1s9+<}P3jm{u$gT~_L&(qaVfdt$Wt5Q`b zrIW*dQt)rxoeCtN3q~!7yBm;Bw#`ey@t)?=*clRV7p+Q_-aM5oP*2A_KWvZ)=z_5g zVvSzRA>*9sxb{vJg$g9#o>-OYXZQrNH)J73eOgP=BG3g_WyS1AP!bv0a1kzdw~_h` zkbt{r#p%GlKdmjF+5D4q3OFR- zDc7PskFg~B2MoC9gI5v(UGU6u(Hac3Ci$!N`At$Qon{URcn-ISfOseNO(f~?cU!wM zlZIBPT1!Retxcx|&mB;-*Kl@@~pgq6bL?bmg1aBOkL*%FV)LLHv9&fV4Z`h%c@`l|cm(0T&(7 z!jCmdeO*ls?1|1kIe#JjEJoH<4A_KYs9U;e`QdCgw5{ms8K{q+Pa62D5C<|lb8A}_`iTJ5&>PX#)wFc z+^*!ERWm-h;0=QcBwCudBFoP<)cU3-tK+5 zDGR%@I#!k_t#_UOY9g$aVHQ@%ZG(!g4%E~u8&6;IVsaavDrzEBAOUNrN@a1_o9wUD zP=?pA2&qB_(uMN<=}Mf#97M|F5~=tKq;NWdB@B2o@`kcD4b@dC>w5&>QC z`HM^lvpfmz+Jf7t)-tF-Law{7+jx*YREyt_Iv^3yCD*I@N4&`9^Yyv0Y9E6NB;dOu zR{IP^_HPlB(Y>ZjBA{!41wyY9Pb-^LWugH-GooXb?c-`2QaEGRRamY1^ zfUfo~YSjIaEA9TRnILRp{K++sSF9kgjMXd+LPmp)soLYSGWJXW8urPOdiVURcts3G zn_XMeF>iDP@kF~H`EK!<_56N}K?M>W>-(a~akjM8=q7?_eo^Eqo?OdDZ>*FE=+ar> zk5VK4C<9Bn3ZgK`i&V{d&n`Z@#-IWTco)Qc`xjqgviJ_OJa|tcpzBVqFR~hbNzs0x zIalVRD8pg>BWARvhCu}q@M(%j@+v>_C*uO^7$g(W)%K+qD$qKjjNYg@|KrOqA2KcL z1|x>g7*rquYo*v%6c|N3Q8GI*=^)Fz(+|}}8A^O|yf{s606HE$NEuNXPtPt5M5pHr zR9+N?i!w~N1(B(%NLY$+oGyRk!3@VU-Pgd;J?>LlHt~$l)d7P36==$9&2w7~nsJu(moFDZgZV)+L zr;52nR57SP0zO%ls`AVb(rVBl*6P}IiGZ%E`2napX0wuE9Vp6JczzIhe3P;-&+ag& zKmtBlG3$IVh#36X!g_AFEfLU_x^n<3ZZlsg+!!Xx7(03hxwf>FjqiMyK?M@<$%;|Y zvr%N&ja}?v_dTriP&6vjd!!WZZbBN(Nq*D3Y>szn(t6(dQ$!&YW?_Y8vy zB;a!rqtr8@WZ0H@?BJ>@iGZ#%bSPRjK26c>HB^+bcWN++9J`dgOu5RS0txt>#Jtam zFw*|sWVWlxWr=_;xwe1(7fRmLD`Ka*Twzdw1bj{+Zpko$G~YLs{johE5zqzSG!X}2 z8$!bO6|?r;Dy4T267n<0P9Y?tWGhqEuaF4n`X1H?t=qX?(W07maQDeU`?*GnyZh;&oyeWgma}~iB?7vRi2l4sFI}2FMAL6yF)o!D zrWvs}S`n;U*Fh+5Z9U~masqWz`=b-a9h9)XsnqG#Kom+|mz(#|^elBnl-`d7TlRiU zR|XYG5C1{Fw{hyZTG zET)7F&=7^Eg2|5fT6Vx=v_wGHkPT|o16L^DlQliEr`q9UBe}-hCX8lKfkbm}Poy5V zLMiU2DdSynIC*pF1RK$&Kq8>);5kp!a#c*?~!9wpBj6zhD@H3M7`=^hdqV zdMF#cG-X7aCX(Y{(%IM-*%AR=yLf-3Ro7Rk4%L)V={b?qsU5+FjUURO0tr}S#6Fg) zB%+1;Gas925&>N&3kRZ!_O?p3ae^qL!;lGNExL2W7@Pum_$I=In^MfcX)OA2M^8jIH8|Oa!&lE16OusP>~4f zjk>oYlZ={kkDd*Y3HaXCnG%3L3|sbp-@$(7v7}k+6>LQBA~rNI4Y@RZs*F9qOYypx zg09?osoYZUQ+ReVnh|hJX_oO;tnfZFi6&bguVKzj=QF54Vxdhuy0hem67WTnjop7% z6iHmQnEC3gkqGEon>!xa?b@z9vDWm$TlEm~i zD3u84TCa{mR+jUXETYNvGVWjm@gA{&Ezdv5paKclUlHS4aa92*l?6QE5&>PF2gA_B z&tnwg-CLAlZx=yYCQV_N4xeC9fduTYh%8VQk;F}VAe$a@Mk1iAm1+cfWMZPswI43Z zaK~ea&*~5sva6Co1ro5oA~GRVM3EQew(MrrX^DU?_!g*CIjhE!n%VB`ZRi>4{eT4Q zuZVBETPzvg!jaj)RPavO|ZmO*8jNZ!IL?I6AY zq^~F>V4p~2u5UettV`I!h74OL5zqx&36WK0_ec^ur-DUS?2%dnNXWe1O#Et%8 z^|B+R))^9T##79Gqy~{wFY5BGV#W*pFX)1O2{D%uHiWqQHRL`^aRtatGE#~3C*V0^j5ZW^;?7uH3{2q(CTaiU>4Gf~jTjcL9B;X06V(t}X z5YPJgbVTnk>Dvxnuw4-=Sf*(t@~J+ZXPYmzACQnw=Q`?}L~OsVqqYv4B?7wS_dK(2 zBI)05JT0}`CB3zffTw|peO}GRk%L)Rso!TN5zqy{N@AX&XdG$QYAgLJ^7TOl67m_K zUe{yDCsh+x_v#6WfG+rT6@Ag=u|&JcH>wwNT>6Sa0-iZ4dI0mI#rlU6%j;Aj5zqx& z3GqCtV~BBxg_z-#TLVbQC+ak$(ZuIz5WDc=kko!a7i{fBWWPr&G5_Snwr|=mwQ7)% zcixv=jUnWEGCR|Jt3*H-Y_&xsU{M^|+9{m%*|JG$ogo2t`iq@m=i-PqnaW;?Q;y;P zg05ow4D>+%va)mh5zzxsDdWkxaTC~Amjw(ekbq|$h*M%3Cy?f0X>7H}bcuj2cnXS$ z3$IKhS0X%_{)D*Ze;J z0=nQSC}NFeR07#G^Ej%i+{K^*33#%HN)LL#6`J`v%Nb^@7k!x4wQStFfq00}wYYt^0c#AQ(c-cqt! zBA^SN-ypKF=f;qSm039Z{TAtD2S~t7t|IergD8^!rwHHew_PHj3+7T3*?RhqCM9;O z@T37{(s>h*kn{C@_!L6StTtoYRmWrkWTb_e%~Y!7^dPb%VIS@mcty&22LCV2#3$C( zt_G3`l}GTgxH}R7U2vUSA3y%1w0V=BC?n6J9~n4e7H+1iEfLTK_uZ;g#L}DG&&a|h2U>BcK;ry3Tl8Z= zI9mEqb3RVPHUmkWaU*feRxOEuF1UYK?Csm+N3Q7*ywkB2hYBPbvQFsH=M?nst0r^g z^s#}YS*ZbjZlEm@&;|EFi=7rCtD}xqL%jb{D-IP%be&_3di0%!UMrfFpM@O;6U+H$ z(YAKYBm%nN?rfFna(#c2ZNDEieXc9*+lIv8YAZBTcOL5Gs9E!}=o?5*n&hLx;uaDC zUGk3g&u9QaT_>XPPufWP&mr+6*XqBB#+p8wbFfT<0!Zet0cgb8RuTbSGix0FBl^A8 z>?S{dCX_#FzJj5>r}3r|FM8QIkotVELm!I0sQdCzYP;GTO+T%s_LJl2d4ESFPBU-g z!KY5G!`r>A!dRyZ?YStAZhhp8)?9L+y;m2|IKNIPyV#oUWrfsgUuQwo-P?oXvwGZr z;xSgQu?MXf5lHu~FH_bZbf@}rvqSptuCDxbVE5IiTgMKhVFOQk z*k-z7mF9y~#FhStT%z=F3ql8ids5%K9?J0tgT+<-Xzawx7fvZJ{n?$A_3A`dRXtWh zXT_ln+Z|}q;XBHcv5{zHvo18Ci55LNbBrKHzfR}feBzjvn+=^dGM64S{jM~fyP|yG zv^=^a?zK`fTXpF3mV7!IZCCCYT@`x)#{7=q=)o?w%`uEkPRpdLJbxzne@pZ2`|E6SYeb)cI*Wz%bwhm|K@9q6FCQ)yef zCCcf4R&@M4T1ZGp6h7UsX5ceUZ6w zCwi&REp^)jBz{MwOE*4mV;J85z?MJ-5(nNI(GQ+2QNxjLg2=ey!<#%Bgd0ZdlE~Rz zspEAuI^U=r+OSMb>oo3y>TYd@-gm{+bD|+ayIKjN_U3Tz{k|8rx$+aQw(Li@|1(4} ztA493cJ!mFu7+sez+YBXtG(*sMNI{9f#mSL=@d} zLYuCsdtKbCwp+}3R*R1O-J|EsyoWU%_tS@d|J#mEw6>si>-y0zVjc4I4GU^$IE=1% zr-|5V``MI_>}k>jM>hDT3BMF?%A0L_A`#HlGS-lqeH=}<`f0A}+&??sen(s0yWk;nckfKEF6l!T zp3tLH-*%?&BmL;O>)N#7XLs5P6S_oSQ^w@FU3fy29v{&29)k)bEOTAxzVC<*wAOsv zFTNPS^|pOte`lAn+u~XmKWtAQguYR(dj`<>A}i`#`&Suza3CEv*oCg`b4A?U_zAxJ z%gjIQwC!OA6-XGI>rW59wxLzOH2E1EoqTwKp^9I6eMBOlDtUHE5zqzS8*%PyU?k`218mCbLg|fyL~B(NP51t# z%%9Cg8EY&ec+6CVUGFwWBA^StkKzkAGLcv5&S8gh2ePtbxzv1Fx$^YM9Hp{)5;gsP zN(o=SRDs`0F`CGZ=f8^=vwGnn(pMA`p2?Z?_s(0&^4FWhRehK^j<45S!*X^8$Fe}1|3wox^-53&*srZ$IFy!pHq~ob2+sBfZs~`uMVP&7j2UHBUZrP z%<0Ua0tu(;TsrtbnKG-}96_9ZnZZ3KxU%OP-c#M|X*4TwiV||9k5bx8v`g0)DpMAP zDX?sDj$(Q`ALH)FZfI*sR|Sa|nN#V9YsJdexk;i7?GLG3)i#VdENvqZ&;_qh#Nu2{ z;bUh;F!Pso3@VV=(sl~1&EBbe*3K7YH0Uysj~<)MI^K1Y24 zo$q++ZSJ6cg+WM0#Bon-i?(bvp2f+bec|MMyxMC)h?=B zCcd_v%qL73Q~spM4g?iQ%*wMu)vB8h-5c(o!PE+&hc zEuM?sSUKURQ>W71q4ke6)A{IjbI&yDw*P%k-5uDqV@^J;dNi}##p#Op9oomUc@fD& zJ>KhLs6gWVkOFEmYXO${BA^T25kZ{D;ce1P(2`3k3>8S= zH3ii6M#u7m%V$LykHRPMy_Zg?EqXtc?k;q}`zFSNe=@mN#!WP`u?>FLFrTVM7P=jn zk?7VgKcBui6y&z`Z7;XHqW|Cl{s#*T6-X>Tm`|_0B5oF@ z4uZJ$HI*Br>*6y8qw$)Z+4R<`5$Xe#j%uTfT)HU8QoV9?6LrfDdGzqThU)m!P1GXG z|MoO)^rtyK*J2ok3M2vsdNnlYTiQVC@n0YIY{CIeQjO3viJL z=z@1$L_m~f@Z^b?kjFkR>3Kjx{v9VmGq~f|kEmt)J`w?4=d7mC(mp@k^3pDgd$lJy zo!jcx!_&LtKKeJ@Mah(xXuPeY%fyB|>nRM;$1oiM~9)h@GKan4QqKz+qnIRF- z6|gCrZf`uqZPqqT8NV)#=LVB)@M4dx_~ps5v?TYY+H~bE^|p>NH1TGYdf4;L>gthk zw4!{zde^GMg0N3Y;6)kMctGe{3>8S69g#$Tj4n|-_-S%kBse8-*D8JdFlLiPK-cM? z2{h2AvHIyFE{K`tV|d4rF4(B+bv)|95V}07DQfidk$Tj+;k48C1}NI8T5Y;0gl->p zO8sF?jUXK7jOE5Ny5TOJD=}0cp?`c7EgA7e-MsjuAiS;n^ORo!xU{+jfuodPnV3Gi zX^+~}X#dZMWmeumUV7IbZ!*^=a4Z9fSI@lY>Hrh;^=us^c9V}A$Y*Ky!($H01a!qa zdQ!cI#p)x9g&-2YsJV9BVBBZ8IqCDG107)&fPNQQBi)O3bn($%=tCnzG-r_!ZT`j( z-P+tk5bmcCuN*QGPrGhPpaKc4(GIlSu?^B~ZY_vYA6z+IJPOY^Y#|ZQ^>w!q9X&xG zEh%vk#GUA_yd*RfFZ=BvjUeIJaM>&qnv}jpZD7$~5GTT%_?5U3_^NMb0u@Mfd1^!V z9?Vy_(iNj{RdihkKHYC9P7@LSkbtg=`zBOrR-mq479fbjLpt$&%nh5^x{`ZGOlbq> zsctdeq3CjwDea!!S{=N6I5M4UN24~ccUw19Gor5>X2X4FxZ~R|TnJPkaX8+To~+YW zeJ*miAbN2JUUA(MTTFA32W4-3e46q4&vzMlQ@!SL_`m%CNj? z&sApv@wEZY5&>QEFE7Y5=e3pExM$s7B(`2>+SBi4dGp^P=%l9^)tS&pu^AhUF58_@};s3iir;1!BE%N?dX234Vk zzdQ(3AhC438MRrIq&!n=%BX+Wlz%*b6@4m~3Fwl4`LMIcnyr5UfRWoEQ( z(86@UJTBc!8;-{o{X~Mw_kNf`$Kz4 zzZ?>B8RuS_@ORhKkk0Nt5&>QCIf>_S!;l+o`B>h0kS{S^Vn#a_H=$t%5|D}b9VH$w z6~jh}2$m;i2ag-_I{r=7j$!gIhXfY1^Y`b<9_>W&%XgI-a;HFNwO^!6Ko`7kB5OoU z2fliyH+?n9hip#hL`%fJ1-B!ysC2#=eRaJh4L3|c@M^^x%Tsf{ZrTz0GqE=rHoX&d zt+k;YyrTZAiS@r5(KUC*Blw?0dtTjvv!wa-!Vzz&3{6e^|B3l?&8WYxF70$x^90+i z>cD40;%UsaA6l?Co*v{%iWv=acA~4U#3Fcw38T%ZOK5MpYi){ExEX}%>^yNr0yn^x>gsi#!N&NMT+=xSHG)Fe(S zPwcMAH{wN;n=y;leWZH@35zT@ZP6lM7RFyl=R&tQgu zF53AF7uIXf^+sauYpi912KVO*gCf6sjN8F7-1rja+ zX7oj1KkBqy^SvtVYsx3x9?g26LJ|R8@HvT0A#cq28ndOWV2!i%%i(XzwlJe>Z;qm- z79pYxy&OBfywNJ=GuVzm1roKRJJC@WBIqjDA%ZAuZOMb{ZDIH7b&&|@YHwslbLWQB zD_X&V=on+ov2`Vz{LqXns4=BBD1~;p5P%;1GNrnkwG`)ixu4kYtF1`EMsd9vQ)v9` zzNk;BDGm6WOOQjY#!?@Vu8ONoFkSQo@7^`;$PILMM;xwRKRJ8weksTR;7SB=oo*Cuq=^m+7zodqHR z*7UdW9NKrCi74aRMLWLtjTtXmRgR$oi4%WK=(W9bX@HYvG!gULkteol&n=QGBm%nR z)jrQo_PpmOLvHi)5{3#StPD(P{@2+w#MEAt5!%R}=lSXL``_+J1az(HVM=$ln?(;N zYSth>owVcYu3B@~ysgqNhrg-)ArqQiXCaNTF%*PT7f10%S@PS5R${0?!sn+Iwb?$O zRwlI;M0OK9KEJFpzuR`9L_k;UG81~xY!Ur=xs4!9k9Fahg%14m?>Jnr(ux)iUPQk} z)JHc`O=#EAi)r&8EfJ)}&f@*HyeVc%%tA|iLaeZsP2NLG~rxbaa9i;Y`ANAPhRNJ9YbZAtqC1ew3K?Zt%u|?><8I! zL!F*H?g5s{fW%`D6MCw835{FONR&aT4R?Rholi^|CK1pD@0(b=JMGNt?Q-TGb)!*( zDtqd>cOgx^e^k9>kujZgWI5gVyhJQTAACl}lC#vk1HkVTsiR3P!; zhB0k!xSaNE_goNe=gfJ?bq{|3(N3jpXJh(TcLg1Ftwepw&6p;&SV5Yr-a~X|A8|C5c#w|myH{LkXWB*Ow*n%r-%QZ7G*qqWW)c2VZN@sopi6D3*H5haj~^2-?q+! z-%0sRjb<59pR#3i#iSwX;d6}Wo@2|Xr(2NPbhZTzHCsZ>`VA0eT<>GbFMajk*K!|I zs6gU)l@YzRbUEF_@&&P^pB3M5+?~g16-xwk!FwoTQb(HeCvQA>%AlSUDv&U;F{Ufp zte|U#Z4qTe?KkJu4?H*ut5P5VUGT|@ujnWT+CvW?ut3*JT zvyUBpwtWF@kmfFa$3$BTUOSWUdg_i0Dv;n~jA&SoWwhVP?t*CY!HO?!(1Rb{nF;OKk5hG&dTt%5+swJt$8ml+j0q8YUjt0} z`n;ZezDtqxJ0Q_Fs3U!{VjjIeR$VUUGWwhH>qf5p;M)R;fG+r(#4ZSbQ@*{jD-Sl> z#oQu0&^90QY0l{BN{6HlG;G;48d#R6?9=Te-h_PGCrYh|exkl9A2`N|59m|EpaO|4 zXFJf&2}RV+%|Q^WMdU!t9cRA%a91VyPl1s>4)AbXJ1;< zW`VJE^(4(|c>R{9e8vJRer(}Y1{Fv&*lkFI;uB~@%`-t9@DAlsZWmeU)ddW$dc)Ol zdEHs-bTB`XeVd`!nbImUBx20NY5Dpt)Z3s)l#yyTnh$SuiG|1INCb4jRdTUo1nM@R11UlGnENW{u}{thTY*4|dW@H6-B5uNZmJM82xmBGzY5cZq;5xUMc{ zCdN(R!}`o%i$}RgEAEhx*HVuUNaWd*_OJAXsHxF}w{8!_p5V{9J?Zmj zmg;=H3|jAzJ|+IS;(KMMm&`ADtYug3t& zP=Q4J!g$)Ms2h#FH&`v++A|Y*-Q5dVizaCj0bQ|GnN%lKhptey5`^>XWd5MlV%BN> zZUhxb7~%w)*}n^I);(7cj~l1*MK`Ci`#KjS0=n*nWYH(_+H{#=4?!%^O5p|*rm@;r zDhw4!#FZt`UpG3@A&H9wvF3a#|CAoh@&-4P2^5N7UN(IefcB z*3!gHxzOYDZdLRVdnzHc8`ol6fh+^RlHxKo@+w#2mniB;L1b z4eK2JfIYoMhr8eygTvBlA0*&vrs(N=MswSKov`oMlM(@4ua1c5xupr}e-l24 z+OGZ`%cq|(!&hD%!BBw&T>lii=&GZ6{bM@#&)d@y0bNsgBt56I(5+eDU!sf?)8qKv z$4#(Bq=KOW33+97=YUwwHr_=IkDihU=(3y~L!YOfF5fr(pD4pYYdpU<;S@4{R)(Ph ziQs+{>D=K`2VD~*dPqQ*cegnDb%PD~qk`yFF`gH`GDfykkqGE|C)$+nNLf8URSD0!B|>$vBX-G=zvgyjk@O^^lQkujkWSP>CnKA)gH7*Hsy4w?_jn`8_jJzvaoOn;lZZ5}A zfyCkJOltjYw{rQU=1cu?Z!#~dIz(+>EtUxAihG|x2d-#Ht5sJ7QMoIHC)KN@H5&>r zR3K4zQx+W)c|-A^t!Z&4i^#LnuG);Xn<^2|<8So?T5+E6z>1qiQO*=lL+XVXO&1(kLlB;?uSGf{m-ZHk*|H&pUb`&Dv*Hfm016< zO5vpwTVVG~xfn)0z?d010>WLD%GaN1gnRRJ3>8Sg_!*Jq=2!~1$iIhLyXQ*;bnSmK zi5{P|r%c}{Py7x;k2KyV`yt97l8B)K2^cvdqFAq{@|DS3&``HLiGZ%-DY^7R>*M8H z`lgFA7DcA>?F~ziPoo$N6-dAc7!lEEpUxwr`lD@6QX~Sp-VDj38I$ak_N}5t85w6X z_?CDdRCnPB3>8SgNG_3${ZIyPJ$j(pPj|FLK$l*_DRkuR6y?twe^Ev^-z;zkIedWIUpi!WA%Y4dU_VI2!}(_OV#Sz!KRZ<- zpzCX&DKu!^O-0LUrYK|I)hw>=>cl+fcS2Bs1nkd=YzuTS|MsviHb`thV5AF-@|UAt zDh!8mdpCEythye73MAyc0Fh>ayv}cD{AEfLiGZ%`K3??oxfbeqbsWU(V8h!%yx$vZ zJo{f=0u@L^?;1iIcwzPUU|m7zFC4-fzSP5iTQ`;n=t^_+rS*_?`Sa55f-oLFf*1a5 zh`0II5$E3hKLrw-Y=+bE>0z$%>kI@j#&#J0QS}TJ>NJ!H=z1`}ADvTQTX~(`QxLOt zL-_r66=-kK9}E>p92gT!8+@}-oZog3#Mdh$c!qZ|vKU>DKmxj!-}R%fN5m^<+%>y7 zv>GB_Hr5Qkq*ertb)h>~mzPh950D~6etLDMmOIY6{TS&jh&jt$c+3ifgI?MYsK6*2 z7!4zK@VKcteccDI^s|%*=yLnzL^uDQr4HPKL>a3F^yEt{hvMV_YXTKW!1yBZJW_gb zy^tXM@U$h$d=J~{DU2le<8kBbrkUGg5R2N9k5 zok9Bi&+KXj6-dC{BceSY+lkLJ?Z`vs-jWFDf;(bF7V~^-{=TCjzx(--wDScLaDR(v zqb^zUjVlcKkBv_y0=nSN9#MCHb>oVbGkR!zzeJ_I&?DSN^u;5s82fM`ZFGYRi3cO!>`YC#6~f31;O;e^!jA&DLyG#7f)|C%#(O zkoS&KBm%nNzCtlR4|3s89oq9<4|hmA4k2OrOHH{}JUwF+C(7uOfw{S38~$SZ28nu=C?xpBm%nR^}*w})!h1~HJ`JrwY1s?3AjQhqIVYc;CE9TczQ-1iGVJ+ z{;5(Ox!#o*jp)vk9WNlLKtf*ad!Av<8|}e7;m$*efG)U7D#p&%X1uNI73G_CA1PK1 z#;3_KUi#ZQ^UJZV8DaH#D^1jr{c3t?R6AMHS*hM0s3&vuJ)upiRyqYQ0pq--> z8wH7y!Ck1=EK7Q#y(Z3bn!ghtly1OQE|v-Cg3(E0r^Sz+{L%nNmfP7zib8_KpUf_l zed{XYXusA(lu;Fq_^pOdnbUTaL_imepAnrGToI{Lhb7IBy(%J{3T=4J2fxYng96e^H_ZM)bLr{&3qEimU!)pHd{K-bVl zuGDSrEc(}Frzj(-gFBDu+KK-gxW)}Ckbu1pk)3j`7k6l3%uSQ^5hS21d9^ETBO;)j zu2zaN)=u%@y;IEjss2+CR3HJrU1HAipD*_mdFX?-o{|XYs<3jSx?c(@-CiroXnndb zFIIKr|A(>jjH;sN-u}TZ77)7v(tA-*K{%Nxh#-g}ilB&KM@0cq6c7YO?7jEidoN5T z_TGE%z1PRC|D5;JmGiFqUiUZFx~?C4X3oqclkDsyJC#sSK?2{wVr1L8HGeCrIdr&S zFA?afv^nQfdz2LS)vL8F`P9wTdDEdS6jYGFwnXgjyk4xd*jtWwI?z)h&{eLY zp0#l-WKXu5ix^{{Meqi*D)8;cM=7WvfvugGsm_Sz0n>hJi^Hc&1iHE;>DhrY`OM4B z@a0veT_ksV{#U!xYqf$364+AfbY@BIc>SD5+MAzSB?4Wy7wMU8*G#svw;})P@2yDw zGyAEg9XYC?f&^A!5aT78?fAHcC$*A~&qxHiJlx9$U144F?odum%Li7Fm;? ziG1<@wulN3TcsFCR2>$|j+ymg^M4w?gdIwD=0SJF97~0@5`iwfhGKX5S6%p$C&#o2 zy1CM|LLyQLWtZXyGRvxl-+Wc`c%EPGp0;)GM2SEb-V0)V?UMxVXm?l3KbRx^=1BNF zX~9Oc$Yuk78}8lj+dJ~|Cq8Sno+n8Jy6~PB*|^m@^DSpSYVCRlN%t-iSJGRsdhPRB z@R>K_8N44K%h$M+;>U+LNCdj@+0^NNkLk#j#U*&{6J@1m5Q$??L)eo&BiO^rhB4%M ziS2oni50m+#(9GO3tjk*5m_%O9e8q%DSudHf%Gmx!Xzw&S#~I7Lwt6M7(w5nc-NGw z{7<7M5`iv!^NBsGzDDz#Pt5s*-n;dvAdxe-IlJ#aiZx#_Tf{iiC6ZsgSc~5q@wXTW zbm1FZ!<&7q&P#WBEWO*2h`bxjf-*+2T8%SAjP@78xL>gqPqLXRwIArhmPo9e z+}V=<7+RO_bU!b(QAk_}4`Lsi6tWU?KZ|j=M-7AcNLxGpXQ`#s4x$TNRMEex(Ub4! z(NDW}=a6#Sw=J_|0qjYCM=~s;Ez@^x!N!iZCRou$tT)&c&X<>IOXggyOR+8r)=T+Z zK9K#-;k0_&Ax_-w!4_@Anm9|+reO_=3KH+jhp?z##p*-ba6weciR5ip-wRx_v6e)j zYv$fSHZ)z-e{hNw#NZ0iynnqf#r$E2tomkR8fAas$}-`-btvH7Dcvp2Aqox9Sgx zK-YxZdN!qcJ7!%YNDxl5JM&RZI%}KTy;4v?V$J+eW>YtmwJ>QYhy57&7Qnw<8j&%i){)jNHlBN zmc_=jWuN*QvT;M~d+>8~p{9IYClTnvwnU5$I`-muEyNuCg@p<#65-aCY28KT7PCqs z#vrpEeEFYk+VW8|B%&&~uq_e0ZC>lif93Dc^tDGTs35WYRTTRa-GlAPG33@pMRez7 zvyN-M`VEl?bYWX!sAt)On}wdxDh=#7rb;^bNS$`pn}8%vnaNu%0PCUUKTN|$0zcD+3&Op9V$o!y09$~ybbgwk0ALC$AG9-L*7l;q~;WAQAaD zl3f^{!;1eJvXC797sJ!CEAmxMXRAn{3)>P=@x(Ni-#iM2uX_YC?0^mwbk(cqo~|`)h>ln-`?WcL);C|RlWk8?K?2)gku~|T zDeoDV$$pG;mI!p=h>mz_gTwd--9nbs%$lNt1h&EAy<6CvU-B=jS&X-l2z23yj;KQW zGlEYEuC494Q=OuM1h&CqrQXa?{_T4!?d9{DG68Kkj_8OLxrwd$y*5$WMWr%D1^+L$ z!D2Q%t0lh`HB6gv(p)0Yg(EtmTBt)5|JEZ<>vFOTMFk0LgGFtsMiD$-KU-^7r<_Ef z3rBRsevq5ma?jk^n$Mb_3Mxp*t#jvPt@zUTty;xInLrng0g1|Z&)e`>1IzJUW*J)6 z!Z_wxr30JoeX+P|tqyE{{npIkb30WY3-4OFB@fN4%&pFi(@;SIN7Y52dUFI1JyMQS z_i562I}+71+p*G~%^6>`NENvTwL|#d3zhgCk7W{pE_vQyY@IM(e}7pXQg4kk3xEVx zHWQ;bhnw-xpB4BaWw%723uowbI@h1gd9+%ZmvK;~nK&fmnrFjaHRa3imgQrn9+e1m z;k=<({l?ZfUF1P5nS8UIn z@_uUWKgUX0-bmmbBP#IE?8uWH-)j!X21^9GFppHHTU08JzpnX1yIa&<$}mL&p8|33 z9!TIr_q^6>zG)^A=)!DMkvn+8mT%lH){?c@qhakwTzi07{$kw6#F5`U;l-c2Y|&6b z0@opkU9AemS~7pJ4y*iHi9lD^9lngO&tZ{OqQw(6ds%&cq@pW-b7;1P3KBIMH)8en zj%3|hY!#WZ4XgO`2EO+E^X`cffv!1Xp4+Ks7OUv?N)Y}!g*!I2;W0LYHB^wG^O`c| zRls!bZu^U)su05M3u<%U*d&QSSDDn7tn$$eHl}?k5#xbR1a}mBsN{I^BLl94}EFMJI=9_2y}J&+ljsE63-mV`!x~yyVE*xx3?yIW%wJ03KBzo z5?I5u1a{f`u85Ias~hi<^HTE-Jtq<9dXd|g1yP0Fd$wAvuJQcVn|qJAs&zj)fT4l} z=I@JouhISax{jKb-ZfMr&=vl52=h<1WOIF1iWoa8r1Q7+HfSYYELTxMLS73HnId}O zHM^4H{w5SNPcS2;a^=?S{q41?=UPKXiqp6xZl3K==3n}(pn^n$+X*bN#3(iGij^SF z{_4WBUrpAZj`=AO=o)U*hLvr3NA1?q@XeV~zB@Nx^(b)bnAZv_NE~dC$Vla#YEliu zTx!YlUHP=8chvZ^??dWJ$Y)#bTS{4%x|+|Hs`~61r;Q$!n(4n+ZtTP(cXsf#PQ=(sL|%Aqnil+J zwM3u`ztzRHdY!@t%t_T&70pplL860MH+JZEBi3z{AxF6W^1l4q_3>J@$ulJaUHGjo z@=NUcbNdtHv=cu@DX1VZ@MBl@G>Ed*Z|;j2yGHfpbxtnUw%*H^2z24Mx|oB!l)@{O zSfsry>ZYKA#Pv;G*^=R*%)j0l5#!9sKK%RK?V5#idx=07eyfYO&x?M1#@j8LOKc+r z6(lT!yR!15S~Hh0L;h}hk7V9;-cjvEAA5;F7k;bjbcvn&@`#5Awdkd#6;zO@xFv}- zXwaUW+PPT75cTHyVu$ORM~R0733TDNx?#tuWPYdhCGEq^wFDI;&V5T{CPU)blaoav z#&oSaAHDaPcG)IdBG853>SF)eIX(H8JrA@?mKFpRB&ypdvNH+stj^_*hVwX-#H;JR zXceDz(j$Q`{8kqmZLIIcE4+B44ccL;qJqTHhF#dnpPgCEMF$aM@{|O=>C0cOS6~T- z1iJ9+UfjE)7Sgh*F8tN{^BS(>@C1iCOU$FTdUCtvO1#Cw(5qM?EW_CCbudFzJUBh!|ro?0al=)$}lvF2xT6Rz7( zkMBD&Q$qy_?0twfszFn}`gLt?S8akspbNibL_hIp2!B~zgS)oLkiKz{z}|=0Uu|0? z|FW(Ux8Iy35$M7`qqy5|wdejl%kTpp0n(Qj64?9D={D}|%q<>#*52H6lL&OlebL}m z-T34+kF`ymN@=JdfxQoLtum8&$605z+m@dh66nH}PolpY)1Pl@TdZw2UCmHI0(&1~ z&TCIP&;GVt(>+=s5$M8|Phw=^SOyP$HBXBybd>71BO&)>wC0)oxb1k&eZgH7{};Nj z`n&j!@)zp|%_eA}PwMGWK>}Ah>U13whVmIsL$r!Z_ecb~PX;fN70_o%jU_87HS-8-C9NJn0@uxmoQWY> zymz|Dt((?KBG84aBgD7bp&@+X`Fyral=wph30(gpYQ#Sr!douit{yv6jGB0F?M4$^--H05PeFHg}*N0rGwnSQ8g9NTC6YFu}Gk9>`I^tGq zu0)^a~eH?6pE#C4>a7kJIUrS`Xwyk3J*IcF&UtbYUG>Q7=3ojkoal zAIW~aQmXfg1g`TFF(T9X!`s!B|81Qs5$M9|w4$voo6av2E5&x&T&Zp?5?IMq{O0F9 zxaWr&{GRC}1*`I4wI;0lBfizX`|yA>m3U0fGb!&C2|16<#X{lnrA+vXPY)ylU6{`z zYU7>`;wH79X%;KqO1qLEA&*&}oF2(%{XM0vdHhf!(1qDBV$ZN^(fr|>En54bPo+E= zByfyW{DPh1dBdf1G>^Dz5`ivxj^62h0^hKDr1tj4O=)Hn37l6IBNIEi@wFd%YGDn| zO9Z;)ue+3oU3t@y;o7jpH>GbiByhG@wG%eCB?4XeEo#X9NaWj=*V2}L zcqM&vB7w8kV*kO_NxbTbM{L>2w-SLa{HE6F4kRS-w_6UdZIgdV-_A(j?7P_eEG2mAD*&U7YTAIeJvx^U!0)K#n1o_|bJM> z$}l8w6_if*wRbpQW9O@sZd5}e&?T?=xihsncgb$5Bp%D^e2Vw1ST<0f7CRh@$ zV(O=iAM{8;1qrMpF4oE%=)&7K_D~Al-$(?yaGjqRxf|4t|NLyHG#GSWK?Mn{EFf|X zVw1RjzqxYe@GFTx7q0Wu>F$2*&JR>5t(0$iPeBCt1l9=QstQ8vb~D*Omb}_Qs)`x+oW8vI-C6qVre_pXkig0UVrKMVAO13>t@_&H zyhNZ2M^$yYWjj;&{ariNkE;$Us33ur1;kwvo5FJv2eD5{GJ!4}RTZlm%ck=7^Cz=O zN46`dAc2(y#QO6c1GqlvCA*QmSt8JdqpG5UvU57mKd#fNhA&o7K>{la=yb*UG=Al& zix!nKUn0e9~1bo-|281qrMyV920LQs)`)1?E|^` zDO|I^kf)%61XdOh^(=kTd9&^PwM7L(Bm!MHsw(oY#Lf;co%(C9=5|(4K|-!lu+Kc5 zm)|u;`*FIhM4$^tRmD>~c_6>>YP2>ex3Pi>5?Jd;tbFO6#^a0TX(tk0Bm!MHsw%3z zv2-3_I#=6NzLJ89L`b!elHF5z+imN$>)pN)B(Sm(j;e}Gz=SkjCuXgdwdWu~1qrOZ zB)(XZ`txcli?vNQ3nci^Iu{;XHhaAQunI%!rDhg0$n%`E1vV6y?BMvceJe* z)(jOSa2`*rGM$;o^WJ>b79EX|2z1HgyRq>d`Tl;Tc|P6BP(cFcBgJ=ZL0jHux;f9< zc|#)5C1-^toDb)-Eo<@tU9B}#kidCW@m16@nD4O>^}K@`Nd&s&T<1wk^nCkbd!D|b ztF*2N37j7mEly-Zo_gDjyKfvK5$KYu2ySoa#rH*e@(VL3OEm$Jzwc$ zoVeK%fiA3IDCV}W+49S68*zs#OQhO{NXQlbDx_c4yG^p9Nn*{+*6`Z9z7-UaW79g5 zlS6AbeGq@26MtVhxoGt&myx7vxFMe!iG`m`SgXj+Y?`SPOWIJ0mADeiLf+f4s3WD> zW8WB7aj^}PiLL`1er51hP>Zvs_s}hima$=SgD6GP(k8o zwfgGm%Z21{t|5~g2~?2iGu>BhHL!rJwlL&u{}X|(hn5lQ5>iMi#~GhFDo9vvPFI_? z8BT5=Fs#(W7)YRN+V2tSw)hd`+zaEQ!ZZI}Zfo&arHBNGy6|`nelCmqNmt6gO_Yk2}mx@@Sh zf%k6dpOx7ws|3=mmk-GhdpVc66h}HX@g{SBmS;Ve#*xA1hMWl`uv(z)>yd2f1!wg_ z!|%mdT~H=aK_aZ?NES0WNnNqiMU@Gxk%2WiCO!0H$6fr`iu0yM*9sLRKGki)0va`D zM=XsAdpDy6NmtvS5;7-z7YARFH5xxI>+^a}c?l-Qr&ebY%^=tj_cuL|Uvd ztd+qSs37tA#0B+7aeopyq3OR6=<2Zgo_eKYI_aeZ8xi;m;=Yae+sH?S3KH@jhj<=H zpew0LAv1e(ySUT3#UhUk34D{`9iDpfoBE_y7uGe%naKnyNL(EJTCKFT6T9BS;a>=J zm4AC(U1Q&!MXh%;B2Yo1aMy8l%H2ekaNYQ*kU&?>C70Bki``iVD|e$9=-PVYp!#Wd z5)1C*!v2{+1&KbP2UYtsNvzut7o!+RpzC9uO=`u}$?SHpml1&q5<$hY)oXitvU&52 z&jSf`HTT+}uDPDfQo9+)Kn01|EhAK)GX2?5{+AxR43V`FrBw?3?$I?d&K7AU;2T}ZMLt`QK5oFnf(ol;}`U2(F=`Z zAc3wV^V++@tTWis3C1x{LBhlO>h7b@`-{EljAI~yu09rzRwjuUOa8wYs34K|>8(fp zi~j6sj&TfpTjE=^Q`aBr$?knf$_zb`e?e4`&?SCQ@9gYBEWi8z3xO{6(JwW9MKWpj z*^tYL??g#~|7%&J9Glg?6S>{1{=X3D`sW@1DoETjE6=WV>`2NiFzx{$fiCQQ$mfB5 z5#QwU>}s`+WK^Gj>z7~*B-U*&&mP@~BZqDoD`c^6abV2bB*nj)4Ta zu;(Plz1BOZAf{pLuZ%QV=ODShHdgNMdM ztiJb_>W5(}?je0+aRFQQYMgrXV_Tyh87fHNF4yvTAc3xEuMuqYxqLOFRgh5( zRFIG>DC6^i1iJpYXNd|Da?NFofdsm+S1X_SzzS7ZQMGpDY_1!5tgph>y@@6#6WoZd zYIQc9#*x!KjDL?^YuuUL+NMl*r3%AJY}l)nW1xaW(T~Q=LZNI{?JDe_33Op!TPEtd zS7tOehAiylLCy`R%*xxvkfUB6|8gF9hDeMXSeezS7enGb1TDSckU-alt(DoZH|L9g&J)CxYlIxekYg@pOGTFkXdBpE%{I0haSy6X3?&1&^+MQWHB z6Ifpq_u(DZ+n@bB??z(wmNz<&K`xH0M2S}HOLiTW<>ky??G0unt5y4t-{(ktEm?=n zWUbhhO?8<3d*Jsux^QejCh++v+slP5cpSv`4yh_VD>8x41QK|J|4g7uu7-$j22_y1 zYbeLSyFH=1*x&MV4EcP^gU|()SkbW$>}Yd79k zEsEciFfsbBMFk0EaS?OBYF(Uq;lw`q_do(&WvoWB1JfVu+j(!05rGO4?_-LXTio1z ze>PV67Xn??TaRFlwrvBZ`i&K9m+;I{K?3)t|7QYSt8)w3>gNuDrdd{E)fUFU9!u6Z zQ&y)z9C^Rp>p%9EkkF2rGSwuGyqsX%)?#l7UGcRmurvE(N#9swV)>nltV2QvGQr1_ zbgfj0o%icNmQ@uy@BL$YjtUaz+gD=i|HhD{C&te?66nIWgnX^=ow4yzCDwg%47oc- z{NMj{R7li#QHj})k0A-8{_UvHg*^lLsP1pC&SLwuA#1aorME#ulj>~qsW!y)gtO6e zjtV~WI>+j4*{wFj>#8w~V@9<+T>)grrWK*MSg#^0(xjjea zOLc|Cys#&S?Mo5t8OTS43KGE$6=uTi$u^TxMn{DNy0AXE90L_3*2jgh!Wq?xRU^Y5 zBlu=O0$rHTBopY0?;pk%52;S(l=-0lX95)@7C#MR%Gqk<)t7fhM}-8sFi%Q8DpZgN zY}l6l?opO>%(!V30||5`F73!%*Ow;AzSoQh9P`GpaJSGvHm_+zR(nl3CLa|lNXV<= z@%KOiU6sOGu#N5ASjP|(qZp_lfvfQ4qe22*t!IU?{!g9RxF>&9nLq`JIwvF9uGent z>`&vPLIPb)cZ9P#>mAvF2|tZupn}Ae=55)4an7va3*)0g0$sN%N3%gF^Yi-5?Jp*j)4TaBJ(=4MJMX8Mf+YE#lRk9=oB+H zT4_&WGX87t6^UPe&6xVM9r^2K+!w|64qcA*%*9jNj$EwqZ^ZK&7OZVhG+B7wl`QRK z!D>{BCWltI8olB6Js!jkE_kDc+U`{Q<_u+V?7rHm&3bj;$5b|89AtnM(IX+)rc#Hnj}%*z1qpdiJ&b__x^P@ezIRbUVs*_C?8UH+ z>gNiDMrV!$x^VPMj)8Xx{{9~)rL&IHzpHbaX+|+nLE^!wequ)EvpQ^kUVYlwhsR zj{OUPF5K@@zPhL&;XAAwyS=a++gW_hCbt5JTaZFMK<7Q2VytY^FMxhAyJrDk=0t$fjFcY$H1eKT>t5d1&NPG zDzY!B9mu0*#xbxpKo@?)$!Cu3#O_h%Y-w&g();qijn-leBuZ^EXP*<=k=FYJEnQtC z(1jz#GJ)g9UQ?^Ee(R%2Bj^8mR7e~;RfQ$xMw1pM|8`X9!ZuMpDr_N_F0f#JH`UvWvS&5+bYT?HXSzt=pYnO& z*Bufzv#PPz5m98DkD+!nJ|9R(u7CVW#c`?)1M9G-eIv-L`u}x|42fOM>$1F=;lyX8 z{l6R)y4>^XGRydIvZ0+Z(do54yMDMC>E6MTEPLX>!uK{MRdeeS-2X>Db5xLMG}V#W znKUH@&*~T*6%y!L_REQx=O|?Jy4pqre%I`;)sFS

      Q%sxT62(ZyZ#R7-rs)`E>iJ z&s7iUr0$sTCrW^yu#b)j*WS3vjKu0_8z<(Yi zLj{Rig@x?R?%2S!Z<`s7sv#k{;_}(GlS>01#7s0Ibf6&du1q1*#g7f#IVSC22y}gS z%4eB28v;L%m}x}dcw1Jh3T)||Skkufe;(@tqRE;HY*bV%dH%z=HNX}JUDzhdzX!f$ zl7?1gBRtxY;#cBr@SomrNHi^5jrplj#BZ|ky9ECiy6{aTAJqy657y$NKlz_~b+S6n zn>mbVL@c{n5Zrf5CQv~let&4_i<&+l4ZU-Dx%Ti)4P-|llsecRRrY}$t^`u1rbjqWQ{kmyr& z7)!M@)0-W8XGGw8$-J>MOCbtbJhb+Id?zCD>ZS|ZnWZOcc|&a~Jac>}q6@FOOrV0q z3O9E)?@tr*w6vj0GsZvyU3mA%M4dS)%&YuD{o|3t^(pr0%xrCuzV*j=J?;%E6WFqx zwXbUoo)Z+sL-`~i8VXm9!fqG+ZYimcH6M}6+_5ilX@f})|Nf* z)0}k5wf>Ly6%vCR*|DZ$g2~z=hT3iTn`0}};bUiZ`N1Q-;@lHg-bACPM=h=d& zuj?88=J26)IEBi zqce@}L?qB9*ZsirKn01a5BjjI-s|+`x{Wi6fdsnbY9tr~6(sPTFJCJp&~<5A2CJU6 zP(QNiaHFF_1&M!dKd_aV<~NXCnUt@e+C2JSS{(deNGw+dvOB%<^`51pjgATlbm5-W z@|mN8gh#U>?5uT|{!|r5qZmk_3;Qc_3{;SquppZ)vA5H^ekx-W0||6tuSV1s8SO$x zyE*cXqmODQe>ju2#o27s==o}ur%q&BTwk_0=bE~ILVXhaHGw5RxU1@PU6!O$|2jJ~ zFHcK#8tYHC7BpdNUpVOxA4(zSP4sNwkhg)$zYZbR11#Cu+J+jY7jxX`F_(8*-DlOP zYq1>}T{)kb_X{T$+w90&T>*P{DU5J4SF&wmE^BqAxp-<#ZoAVa!^`mJmrK(t6YPlg zppXrS3L+ClYae{0h@FU3NZ1V*GJc`>YRNIw7hN;gjcP@Hd?jzISoN?a3v{#C{ftWF zS+FfRe03HxnO>HV8O~%+>|;fI0!Fb$)kmrS3$-GD zN{(cv^=GMgMMNF1jka{|3v1r$`WvmimnFF#)Q&BvYsGBbEXmLxZP|hA)~rKyN3!x` z1e-CykhfIVuL-5amHDkc=e3vKdNRC5ATupnnRU9ZkTb>p>`;q}Z0?SxWZ%B#>|N~- z;_5~oYDQcBuE68zZms*yD6*u3KN}x>QGHxGm`v=_jrc=?ir{r97+6F>-JuL`5`bXw~%}}FuvHa(nZlm(ev5#?2$Vpu+T%9RX{jc|4HmOQJT`U$}!5&$F}t24G*&IPBYTL#*zenw<3M* z+maIFUC65hZ!)t%4bs5E@Wpa@q@GrN5vN?wb)cvqL9^-+USuOyr5LKW-XMYWvty$2 zx1Xa#psT_3dSuN@OLAb5pCHCQ3#A)Zc2M@MtU=>v>d8z~k5`z2DKIAmff3)^-Og|jI#Mnsk2|K^59cFi9i=#5mC`0xjjw( z*h-n#qclA~H-ZeVZb_)~PyLwkVdQ38TT=Oi3HjlzkbxOuXP>Qx@2IA=+R>AhS}Q^E zWhp919F7kqZf)&I=q$soB5M}o0M<>BTX==B;+ zl{0foN=Jpn@5*8(%Y2)D@PvvY#;MEkbnSbptZwjG!T*J>KBm#ccd-R=`tVA;ecJIv z+Uj(mGO6oR1r;Ppujoi>?k-JQw=m2*KN*xvTW0wx`%fQK?oUr3(Q!xhjg~&vcX`*7 z92s?6U;E5f{q8!QN$D{rq~Y}Qf(UJ%Oxv_^RmOcjqO986mF%CDs*f4;LGN{{msk&V zT_3o2lOF$*s7-aWFTKd?E6x7wmSP}L(54qLxpGrqIB1KAv35aU`t?hFrR?!N5`iu} zLY;2@@KhSzxV92{ak*0UXDT`4QBHsT9@j5jm_gnhU!d>inWwkv+>e}7r|Ngk+aqE$ zdYVS-1v@FD{?1lVLBdU}zdGJ)jlOl%7(rakOrvJ5&dSoSdrn>=P`AH^TxTLdboAc5~LQCYQA79C*z zg*?xWkO*`oSQU`Gmu2)tJIad~haU{39kh~4M&~dE6(pj^6p#lCE9p;W1iJQiEFfQBRMCIzXc%V*89a=-FKJ8?^6V8mI*O$El~d~_uL!L8WE3ek zLDyv8sSi!$H}(4bVKn^8IC7BHR!~8rk2Z>&ZT_jr(}7g9wb!rY(D&OGkfKy4i9i=# zH=SzB= zi|fn}nDXH#8Mk{B8J`iV{_u?mY*lJB>0D`8v6-V+Fdop-Bk0nzVGsv1QjIG z7Z#C)udR#y-WhTr=S|F|aSa-h@H?fYtBWqYZaUqi{=@0Pqr=&w<_GkDs*fi5w;QT- zX<5~(^=MLQr>Q!$;7oDe#ZjbqTE1#ux2m|hn+k{1y~F(3@)S3M3KE06k0#YReJQ>= zd`GdURs123KHjBgMsqrwR@LDpbM{?PS?yYkIv42&JL|KVHQ=2Na3de>PM}iTIFRCsk}l_S2rkac1F}yG5(Fl`+Y-OERl7a+YLs5-=?l3yLXLU{MIgLfFDI{sW>(#3CQgP|` zqew^p4E09^e-&ekO3*d3X#R%gTC`b7Ew0;05)ipdEokYbUWhFu7VD?0&0>?(9?69y zZBHA(yG%tYhAlJX^T!2kd=G)sV7V_)u!$v$kg^5)!eruC0gv^wyZxr z{%ejFbEKP=mN1ljczj>2oU&eRm7hyiC7e-57A#QhhGvs($`AD(PZcqmlT^BU>NM^6 z$T$rZByyhSk({STRgVdVoQb;PO>L!4)V#*GkqC4}T+JtD)%U4ucN_8=Z=NpuSW;YpM3rFHa)Sg;zvWx#<&6XLP!(g$-Gt9Xp&vZuGCt zelLHd`mX9t;>5ggT8%5}^NNYYbi6YwGiINNadJcg^-DghnN6Idp@PJQp2_65$gdq- zV8{dDgS*hn`_5{*q0=M+U9V5{Ba>%Yu#iV<1@UW5SLz&iK(mUPs-c3!x03ycX}z*y z5A-vFcvak;n$O>-mHj$FBGBb|Dvit&*;>anLk7fX>kztYZfWlGu~@_2cK)$Q@=9ca z{S}#D*gMzh-hYmumf=4%+fO^CemfG)ug8$JGwhh%kgp;}VBaX(WZ--4&izdifiBO> z@g$yGvg~p%1<~qqJNjYoW35&FO&Tglyv~m&GY;2fwS3+P!s$#5t$p{Nrd?hq5$LMZ zMAR^OT8CYIWXQh?xlHKnZKm9O@ktH8QdU1`N!ot#V(BKOjlNjow~NyH-etJ0*J0^e zAu%v1l8lRWXZIsYF!60*-kf%PREke%eo!LNh1X4|J8$ntmklxJzMn2i-%bXi1u zk(Jv*Sir67g7CO!OOJoB;UkYd(`H9mlG0P++5PY;48ILKUUVdbZR1$lTSL}l!Y4br zp?y96s?iG#6(r;@$o>gV^!j2eUhMQ(BG83LsMA$%?LzY^)#dI5Pc&4J2yfv<))j}a z2M-MA(JaM{o*q@37sNl32z1G39$3MSZa(D9dzZPS&D>*2=9EomF`FK!yOvp!>337u zsZDRC5d={c_@FI~%Xi>Mp4`#U^)=0sge7-pV{OVXydt8Xc+Qq~Z)?x5_&<=&9Epbg zEy>HgZftW(S#cgEui4V|!|nLm+(#0DF8rNzx~%WElr{6>eJe5zzx$6_Sdrv9!2xcu*wO_-jd*FB zrCN=LR^;o)@oZQ|74_aBD{?%299!$}t!9cb8TZMBtYa6wh|&6?Egi9|Az#vExrPc7 zpEN5{(RUnsSEZpK!fT1UB-)oRnZ8CM(3P8JMP@G;#i9=s2%?4PxgC2J!2ezup&cG& zP1f9)#-6U-)TC#kH3{l9mAwspyic)rBX5_FV~Z*q`aUm0?C5Hz0B-T7NJ9mQapBe^ zWx*7-yPRGSj_vIzY2AbmRmMvMy2e{slPAw7v4+}4LG0~fPyMYXOlBQKB4 zVT+o?>YEigk}XcN*won8dQq3Nk{unhDwz8W{>4y1;`8`=WH+0`LUUsTk-XG_R(%{S zDnb8G%}a11y$8%@`wy(qM|j$hm8IvggO|nM7B(cb>^!#V(jq|&eB?$aBq}`QNG%dP z!-m-GnagH9Kda9!upxu)&1Ktu9n*h0=1KbOoX#FR-7kpjZEm#WN`*HFd?6`FG)T80 z<4xwVEx!&3Vs2kAIyNzoyB5@w2z24m>U2Zw9jX6io(D~{^!8ZWw}p&#FAUt1#3b^?yPUHh-t5I^&|EcEA7LFn(g z)84uUJZHri<$oWYN$94jtV?E9;xNaSymp$w)?BGU{Bmqbq}NOqxX7?4k`MEs=BAGP zQ>K)1Mr?w<~{}i@kw*z_7(uI_An8Ykr8Rk-}o${cEMmlki*lh|b zNPIqNOMFeHiFI*?`Kat5ANqNeBWHz+B?4V|v|^vQMjo_+lPB-GV6Jo?NDNwSON!=C zXW4TMSx93(xzocPz4`AEQzQaicohtzY97?LwH@D3=YVwPcuuWq+L0=yC$al}hK!W> zw?1@m&)Pig@i7GzB1 zr@sg7waSzSS1_SC#(p5)j(li5mR-$mVl>{qzLy6bX;z7!jQXYENIVkzJK7O_kFhM* z+OQY)^TR&$+`J0>Z?`uRfi65koo?0^5BlU(H9o533k4M(eu9sCsjE}w8qmPCdqY_+1!sQ8V%~%KNs9wLaBMcXHL@q0Mdo#---%>%nk!L%#jqs<4OIls6*$l>Y11_IYa@yZ5-S?olhA`5 zS@E$%LA0>)p#6$xYl&jdVkFRozl}~8yxozO-n>K$yV8K7g2Wt0douW9BI{o}LB!bD z+KG;CzfQaQ*GnSMCI9A&7T2SLepS{Qylzf=<+~D}H*V}^tKOs_+n!vm>%}Im=|`pw zvL{jAzO3Jlz9L5MWM^7(tE)EZs$L?{wK><7Ogj_GT+@>T(J0oIo*SpvuGDBoQ9)v2 zKYMcgSpciutdAgOmbIg6&&6qdRwxpIt`gDqq=9t=>-N5fAY8Mp=)|TetZYO}`YhR% zH2PVI{nq-DWmE0RgzM%kxIrozIK`g01y*A&Wm5%lXp88#d#zyfWspRm3$KWH25(x^ z-Og9pr!Os}Ge_b{zCFoV?!uODP7yH{1=pj^UzF5-Yz>hJbm5iO>3Sr4&>!m*;&?|- zO;>r7pV}>Tb4pM0+ryi*8^1!W5Y>ZJ9BWV3&)ckyJ2XJV_;l2g9)B`kzqfrj^`2=@ zE?S&dM_x%KYiHS$8b6+?L%yUE-#}OL{qjS#?zDb_usm!@UpQ9O|4a<0s337h&{i#8 zs$;(yuGNP_mUQi$0RdLsWddElXWNs^k-ybu7HNVgzHUdO&R!zxwP0GNmpzHU9ItjA z+>dNYu_s-ZrK_WBrx2&bUPPOapgQmFDv0t?qQ5&;BbK9^Q&f=nA+Bz8sd;LTN`^E4 zyvUvQIl6*$xT2Q`bm4UqJ!Bs{+G+VXVjmeoQ9)wMXmOW(U9VnUVTke2#Eu?bn@jf3 zkO_3jzsD>)ds>m+ArZ0ind3RJM0?UAI8>c@)9^%9-RDkg^nF8W76npNkVyFBNoFLz zES_%CMG)5W>}j<-F*XDL3tjJ;*^@C7%c`>jk_9m?!Id6T0~H5{0NNwPj+}_8 zs@DzdNTxA6azA}!;NpH=$e?i^Bw*IEz}NBZ1@S*G(X;H{SW(6WQdE$raKer(J{T7` zyPn|<*Z+VsZF<~S>0M1P5$KwE$BtBdb2h+frs2(Sy}c8?T&J#5al1lMnQCuOriV=| z{xY#A!E+M#m4zeCn^;9T*{mr=1&J-*_M}(M1H~STdx;o%ISzE#nF>lo*=7=fF8Nx0 zvu;Q$7RD0*Y>+U!7BzW5R@Rx_yG-1*we-=+i=By6S+Ag9MQVnO%Yi|>#0 zed)C0+11+Al)ri;(1n>QqCWM;!Ib>+)k4=MDNUWzNbQ5QnN84cz0JKG(xLBnH7sn1 z{*hH0`IK$We3u>(F+Ly6q}P3`Yh#^zD5xOOWn~WO*8Qp)I(~*AN?p#O-Q0b(>>O8u zb1Cgwj3Alwud9U?;{$hmE+8j|JyN}=n29r=e>;nYxJPR>ht43VAkm~t4ms1m0()1> zPsDhgHI(-0+gCeWW{yOl>&V$`@~v|fR`qukLF9MIq>>ot8WsK80e|jbn=sHVMiFfPzY@}blAOg&CX=T3}+UjT3q}e6B3OFOA(_O1E zjP7XZqj?0^2}A`6ydt7C=qKic=eO5VSF9>V0$q5&iTdqVhSKUs`)dK#76cU}@QR53 zRm&mbdvK(-=1*0LKo{PXVjq*1gXxs96Sa194nYM8`C2Ji8PxgkTrGLe42eJ&-pAry zaweVn*IJ{sns>Sw?`q7s!lyu|t8zSpo_#S-dpORKp&}9S`DC5tH+9aEdBq|RAS9EX ztv6n~x#g~k#9eUVH5B*mts!*Kfg#$P+z|{FBydho>{s+Oi_W!<)wZAPA`$4qUsjA7 z{LG@R-I{B4W}lE|6p@hU2lGbd(4u5#?e4l=5`iw9j}&A2ERPPIf0#{Oa#ETT#@SxH zE5+}TnoF7IA9i`kSm`-OA}@OcnfKw8TD1PSc+NYA52NpP*=R?#kum`;eCBmJhm36M zk={t_GW`}o1^;i3I?OuDyug63>r zM?nRNHf7Vunh-m7{<kl6FSQa}28dNrlS0aYT^H z)s8BtAaOIV54n(atk`R;VXW`Om;Q7@yE&x$%RLf-u881FQuF(j;vd$AkbYh3iHS? zlS|CXB&XB;In|ZsHglznEhOaUn?@(LxlOXVtdcU% zkie%vj3Iv*NUt1K$)BWo5`nJ7$9ZH`_?CSwY8QxWweUnbty^Isc{hEzf(jD&6o?(! zYzNURtdR7}nI#eEs+*Zl97-H2{u(e;#5n4jK_4YFB}+pWDX1WUPk|s745o=rB?(QP zED`7m>rg=64)Rb3mq`{e&YT@Yb(aG5>le*bP(cEp0NZj0-pk%Zi|vlO(tDpv;6fEfv&J=Bgp>!Or2LsCt~bL%AyZ~ z%4v(r1}dl^fjx4uyW_?ow4be+((G)kg4uYO(TMqeV!UKTCY^3qN@+G>pp@5#gnYL@ zc#%oXR(>GAo~BC#x-f51>}y#*lltno#I^DZN*>qL8lln?ST1f=DFyBwCH}K1*KHY!r-H;k5<@F(f_p}(l3K&Lnu1--` z_vEvX+ z@hYpJf&|{vA`@`+FnY`H2aB}2Cgl#I3wwZK7rv$0GtUH8G+Dfz^tMv*hNZ>cMcxulMroV04YyIC)i9i?j8O7H`Cp$Xh zr3JCx6GCzH4972V^i$+B>~^Np9xvA`vCX7$Q6z9IQ>SapJ!zdccZ=8QeqwYG6(r&JuyH{a<}a|L+s@uXhkZyzdc0mqq$1rBf{_DoBI|hmuc+&Gdey z4Yk$lnuOEkI->miU0ov3h3gwcpL%aQy7ah*GO&4hii$*Rj3K>(75(Zi)kF+x6-(Fq z`Y6HaB_*N_xNv=gPUlq^KqGWX$~`wHitANyOb%DX=yWk91E~5jNm;eZNm^rqggkQh zGFwk~TPGqC|sW=601Hle%w#w*b!Tqr6?;K-!NTRPK*-U*FT zPCHekxcUTF+Tdyxo$h9fFzPoiRw-4bhO{aL3Hi*e_Jq+zW22Sg*VQEgUHCicbQ7GK zQ?c)l@^nUB>Gwba&ri&sS87i8&upWtZDJ`A=)(I=d^>Lsq)SS~C?2Y#bYCGMU#s4( z{xmi%RH?tkO(M`GKT-Lk>r=ilRM|h#M|wVxkjHo31KsJkp25n7H+~X1v*J zr{k+S@UX+0hHLnK*!vJ)F{Auy-U_4aw!4ExCSa5+zj0`bl&gjW=6;DM>Zb!;e&359 zeY9C3(1ok(3~Nm6=&c70c;lNJrFC~m$XQ`2Gn&vhd+PGY+?CoNC4__rC9&gAN2v9` z=}D^D0JgG5KNXKqr#lwWkfvqXa(a4|h6)lHTYQPz)*LpuY_zJ=Sw(o!%&E@YF=UNI zpbL*sd^;af=$-lYJfLK-QpL)fH0e5tP06b)<@g*D)rYVBn8H4GHhj_7n(a?b{XO}P z-L(`{F!u*DZgjewKY?^l1$UnNhD*3_%46 zIeTaDH4kbL9?0{P4@d;M@{ZY%d#&cO2ge_X7$px7THb1`c5#{&4bQ4i`aF+fTYAMv zGvIXx)+c6pUD)KXHsbB$_SK*Mw4JS;GPR+o;5;|ZV2knHWt6f;E3|b}s!0U8>UOD5 zUXAa^Qtun)CXU_=p!$j1wV4fTP*jk>90c)hZzkrO2kh6%&n_d!_V>cxNUENN46Q?CbY;#*f{j1yG35}axnr95Srl5iZ zX55JRs5L<}I?$BQII%|}(6ubvn_PW4jd95^|1L>+*rLp|>M%Xds@6ElQ_37bg0-$sT2FCeOKc7E=cAk(&}EAcvTqIiBm!O7 zs}&g#IgRLo`eWGx)mQ58B5}QJee$uQDVsahkY(Xs;7c1_Jgz?K(^w+VCHLD8jB7)$ zMEBSFEGR%( zzB{+2$Hz_5#x*yQ2y{Kaswci15?SH{!)o$nYa^(&!(wf(}X; zM4(HVrzfGkGTGM@!zyftb&+&*@MX>C=1m0^B=8+0Mke~SqaVlL)Q)aaB?4Xh``He;vzoI}O>mwoAk4jV-l!#)t+ADo9{E zuhZQU>x!J#)Z|M_d?84n>*bsP@@eIGW^wzJh*5o72=&gi;Yn+55mb=Co`Fu6R;@F2 zPl?pX==aLU%ur%c5Wt2%X+rRM^q&(->emZpK4lDT)cqD6>D8Y-v<;oUD5xNT&!$*C zFgStkJv>CS|8rj=(A8jND5=n-9drGkhlugNC7o#0i7}ez4R0fwH5LE6jYGFXH$%9nqO|Dj!cO6qjK?MnX z(!?s$VX^dwt{g8=4-+KNHLrOHSrGSsjGbjvRZrOV4-FzJf(=r3p<)4h_Nah?qM($5 zN+^h6AlL;WU^ilSC;GQJv&Zi4?ryOV>z(s_c%N%nOV{&_wXW;O#NKD`nc4T;Gl6A# z?Gk0=kgn9jv^0N_y@{ZL1pYR~zSP&9XywmuNz@TLY27C@rUi-2%gKlQajO%+)(0Ex`ITYYp=NudNM zYPF;Ty?e9@d3UEWMFoj`GjF2SJ);k-V>r!xN$DV(anVsx_uEMXx-8%Mkp>e!=sy=4 zR-^7s=|tB&Eu+_YRiLOK;j_z|yiYY^*>w%=SnLx_Z#SsR>h3Bf5$IZ<*M?|1JJvqN zPY{nD2GPQPnQZ!UTZ#%2XMGg%v%DkgyTx!8_OZQT^uyarYi9lDrSn=AIU7wZN zq8iFb4WT3bEwt$7RumN^_O4gR)oCr*>5m-+;pP%cZR^+7I@Y|SS|11`L6u#Z(`$Ev z&-o6Gg2>DRUab6J!wF#OgJ{}nvcGnJ?JX4*B=DIpVv6*=>HMf3TEEPb5`nH4?Sjaq z-fdXkl&YePf)cUR^V?u;_?J^EDoEfnUyLkQ_Mt-x#%ncl_DTf0Hnj;NrMd;Nk^>F7 z4O4E$(#2D!YdKf;s;D4=&wR1Fzfv5%buU*d+iZ@cdbbro$jzjI}0B)8`wWyN&M0&>@S!!-HeY5?A zHnE(UM4+pDN@vn~`%w01*gjFlq4hoKu%=(MQ*%BMRFJ?YxY!MNp(oA!R;V4lwp1d} zHT+;Fvghmwb|!a;DC6O}2--N_m?sU$BB&sN&wTM+?Sda&80oCl9^puFeulqPoKxv^ zfhYXwmf-KKnPVl23KIC67iH9HP2*zMus1WRO9Z-b7AAIDC~fJAecf4yy3Q08B=FfK zc41pk8f!93-z&0?M4(Ha-R-I6OZ{ubdUq39pin^qpTRoa&glxhvcsA@d{<8*(1nrN zqE_o$(eG;lh|&8RQp`3I_%6}u_Gn(TMaRXYw@CwuKo`bV>vX^OP@2_y7rEtBONt~% z0^f-`-S{+5derJMv2|`B5$M9NCt~lCk4gtu`AQax{dcG!f$w%P=X|G7mk)MoO(qlQ z!mlTycMr6szh9M6_kXTJQ9%N~I*F*so*ijyF9-FKOF4-^7k)j_>81@2rTI6k)E7f7 zC@M(ccPgFEJg6IOywY9`bug9)bm8|FaXpSj(&wXZX{6s2DWgNJYB6NQs)j7K(&S>9 zDXfCS=($!Ov};=?NqHua_)$KTSbKD0bKiB8-$u-p2z24PxEQ^j@uFqCo%xi) zsTwLs7&mT8UgT%6>+ah{8S8SJ(Ip>Uc@MvN5`ivUNf&Q}ghupq{W?7F+H?&SByc~s zh#YuYkGivZJSuX&M4(Gvp&w{ngI)@1!oRPXBkey&Lf+{;=|2}bX-hM1SACI0pbK}) zi};e?iL}n=<=UZAeWiRdm?;MHv*>gsJQHcJ(Ob0l)jLahSdd_S29v%e9GT4;Cvle; zjp$2fTkO+%uL+k3bYa#Qu|i)Wjuttd(Smn+OZjAwFnSSB-i%gQnQBYK6}-1ThIYJu zU9-+4HYCB{_ajvq9a)U6D>T&+u19E zZae!`D>IKs1iHc(hm*~Ap{%6aB~hy-M?z_*hGzW1L^ll;Bz8u2AfJ|xV2=+O_R)_E z3!)ySOY%yUn@a?`HYc?wO;4q;adk~a8LR6D(BQ{*d{$Uh4HYD2wrx#@C==Mi|2~T{ zejI5>^{p!M4KJEV1iH%Qwj|9Or8DaXk6MVer51j);fShyL`Me=6(l~CZb9x$p2EDM zoD{M1rBX}!xsn?%@M|Iw=n7chjGT#?$n0;F5ViW#(~F*KP?rZ?sjQ)bM1)U0;;?Nt zE0x(&lyOgKLZ>-3m@zRDfiCPrLEQJE&F;E!wbu}-uaLm!qfQr_LFt%aXZ~_wltiEl?**N1 zM`s^e_H`xR$u~v1=1AakUd+4(wxupZ%Zu!-y(9u%cu$Kx?zKA7K2=KbLfv5L-bDi6 zS0W$4q##=Rmj!QW9wiaz!r!LY`+6djR$E=9Rc@Uk{RWZ1_pVOIEFx%4_xD=0p1mak zUHFU<-<^$n(d7}hw3nVEq-O~dm>o*Y2cu%>hSc-g^!5EE0$uV`boTY$blps*rADSp z&qO5TyivbQM|=R^djq4@(5P@Jqb-j+5Pj`ur%*dk)wyeQ`$uv)+nW=ks3FKdK`C?zdSY&?S$S zI{)^eeZy_|LhB9E*arzYk5`=7AH0%S@@%oM8vhr%aBQd3b-Uh~4n9+;wcEBv8p9!h z*}BBnjAp@fOxinbPufz6Ko@3D6RS9TLa8r(sO|2wS{jQYA?NYRbq}YHYlvJ+)mBOb zx-h4kh$@~nj7A4`(<;0utzpJJ++Bk?_QYC7q{zOvWQ69`<*PWs@qe@LA%XjU#G1Z+ zDz%$FMXTvzD&^}#*ND?&h;h50`b3keVw6#(LJBS4f1!3FZ5u-c3EamdcBRA*qPeTq zYpcqfln8VUjT}NM3=!FyuS^mnfM&XZw0fgmTA_O!Lj?)UZY?5AuO-qQdk<^9m(Gz0 zbS)p#kC?R-`N)2(6PY7NJ?u-%#9Y=U?`h6ZL1LyyPZIJwlJ&k-O}sh#J?u?~|9PZ+ zdpuqu(B;>t2RSgf2P5>J7ynK*qv7I2kd4$tJMV8$E`(`~VNI1^(CB3~fS<$LoL0ml^Oly@Z z#lNn$WJsXv+bth*d`Kp{;F}_d8rgw#{0MuVRa9S(3KBPry@=!NscdK~L$;pZRXS3w zPi20i)**>N*Qi)e(&qeBcD(s?K~yN|M;rBb$V;IBsl zU0d4MC#i*VSmD*>qKq~ln^L!OP594(C;6x#f!T;etlCL;`g^=5Uy|FOA%QN;+$2^% zrq`sm?ziOXr!*<26B2TUrt*5R^FF|r?^Sa%|)A8ybGZ1EPvXXhB& z>issQ>*4n*66l)LuooF+yG#GFq9MLy`;A`oj@=^f3kiiPDo9vX?M%9Nx~rcZVEC#Z zcCxqF)390ZFzl&BpzB<>C~~~%Q~iTxhBJ8D>0@Y{ul3lP{cluMkSJ#rNDil4vKNaC zSk@&kJ8h!L_UgdY@L<(N9GM z30&(JBjg|bsM!j=*y&wfBG7eqYZTew5zIR8Una`vcp;u{@I9lIcxtDjf&{Mh>vZL< z66n3nXSLjYX9yDLn*FU889ySNwLYIE%CMayejk2!H9F}KK?Mn1>le@6nQ?U1{X5!^ zqoERkt~)NhNN`jHOS{uelyUxQ49%$ZMhn=Z5LA%BwSI9YzHyYINaSLd*@;c+%7r4fu}dTzY>X zf$ITc9yO;W?RdK;Z#raxM4$`bcH+KDXhUs}JMmAxrx+?o;JSubr+(3amd~rihrXRH z5$MAAycqS>?o5NM?fK_=R~RZt;QEY+3qK&vP#98*FYmuxBG84S4{`5?hEe})3%>v7 zLup)s1gaZz-(@=m*P@rN|NLIT&z#G1^+-n4F) z2b%ef>k@%396yThQReaV54)h{rg~ORFdm=)&>5h>f~BNUWsJ(N=G3s-c2}oHe_Q za|#XFkfqf%YakKm!g-14t178mZ=vx=x(Lb68Dlc zrDZdTKo@2k7vDcFcBc#5EhS@OO(>3*Fh&E%LE@QsJ(&KiyqFw#UXr4M1V&$o$jq!z zdis7OS!rx75$M8kkXS?h9ZW4x*C5MR*-%uFz~~DxBJ=M?yI)LD8U$EK1iEk>q|>c< z6-IMry5t|8Xhl(x2q`Wjyn7@qwbO!STN+CQ#%SO;NT+jhilA9#dax;LOeiWyVDyFf zjx)O#U3zghtLFYiMFL$o4ibB12KA(!0$#HxXtS+KVP^sHnC4{#qi? zh4B;Oo7b4`w8N)kI+WkDJK!=!Z=&8mrU&QDs=6oC5n8hs33tk-9$e9Z_Q{_ z>~JmQLrsZ57w!uX`=iR&q1#Ig)1H@;bLk-=XM0Oo>qZ^xWoVO^cuKkS(1m&Y#LD*e zK2#akOr3Y_oQfyT;CVIjxiTXUMbo5bP1Ws-?@On|AR+GzEB!W_4s2dmjj(d>sZjg|_jDD>XOQ$ukRa2KfkO*{P&IvJNxgJG5?9A19gI=qs zAc0?E#W$AVKD3<2HPWZXU5P*!=A01E#O<-vvgLoI=Juy5DoEh7Qm3nVHlDs-lukVE zUXuuPVa^GiZcUjudN8XK$t`nVMFk0*S&CJhy$NFfppH}uxF8Ye!kiN#ik0-G3$+o- zZNKX(DoEg5RE%DqCQ?%RX@1I`V-kTb%sC-)C#)22=c70E^@Gl+s33uJQJt=+`2bqa zB$REOwNE0@g*hk0sXbNt(?yw!n6DjEQ9%Odq9Vh_@IiEM@9V5l?R64?F3eIP)-s|7 z($@VgHNE?K6%{0KE-G>kd`zaTBC2XTHxncRUAQkijUrCec1;9OLUsc#Ra%icz5X=Vu$fi8K! zbD!qPboGtl+T5Z<6%{0KE~?W_$RA8?52b6v{Cp(>U2^W7N^b|z)xp!X-e!I(DoEg5 zRP5lXG??x+oueIkRYfAug?XyPH^_2>Xjzlxn%9ELDk@0eTvY67cs+=^ZC<5KJn@hq zfi5}!RhLZz=%$-_n(yY@1QjH3W-0d3HyKC=RR2%=@^zv_pbIl;iBb6OB%0UxfaX;t zO=Lj)-!l#+LYk#cvF=Ze#hC!#tPUzj;EWa5dPOFkkbczm^;s?M;XLW=L?m!7Dza>5 z_NAVV*R=V@jrI7y(1mNgV)VK%macvv&YFn1=#2^z^1QagkzTa%?n2FG`JnwspbOV} zMF#$*5!5HrgbzG>TR{a0IUdd^Ae=UNXvqum21o?DaIIIg!y%ZiDk#NQtF;I!NXYTj zYglJ`GpQVRANEW^0$sS)D{?2yZATCFsLH2~8c0w~Q+nI63IAa`lc0ixyw|c+ySmhFAK~^Xy(I!&m}mcgP7T%9neIrVHniuDOAPVe zSSy3H&JQJ5Pc2=yR{S09A4X0MFJI$hdKNi9J5sFNiF057KT*14c`|ZyC-&Obfpy~L zN&47M?8?U~(ixXBF}HL>W%d0D)J0+HZ zrGK0@+}iKgjdm266nGnk!yvy=7Oq?Co|5E*Plr6)0b;8o-%14E#{oq4*Xx4{XCVR?GwoG z#&S=~1YQFq{D%)wW`7z_NReSL0G5FSx~~5mtOPb6M`AV`_V6Ns3KD-_j8|p{jVHmk z4Ds!MBhYo#K3D0PBQjKq{1!6N_tiAzM_wE|-?$!oL}w`%@)FtcS`Asmh)kt#bUfqp z>oJ)?1&K3!ymIwv5}S0V;Xep;ZTsk>^lsaa4fShKjIb*y&PdI$)6bcDGr!4;403Y# zn*8)}ee?0GHMv#^WgoAJs+z)*{ii&Ano8*EHpK{hs`0Dy z6^CVMr17;t^7khkDoA*xZ&r@Pk0D>i8%`_0S|Ne1zt;*CB&w$ERx(mYk?2dspSwt) z3wuPa6^zc*NKmuJB4IU~BQX<*+xz&pis35Vo}sf=(#U?(||4t`@HqDoBJ+zO0-*8q3Ps)h$*A66i{qbx^T86~!tIE?z5C zkO*@;s>EFH!-l04A2T3ep3{$Q8(I9#i3GZE93+>4qx(qj3dFo^CpO{Kzef7_OGRR?No8`0b!3*? z3}@cs^9l)c;aP+-feI1}S2~ik5P#O{O~qnm&_=b$5Sa(HA%l4KCELM z`(gwtNMPA=t&l)h#w!={Y;;=|alL%8GEhO{@9n@7FYzSIqU3g@s8lU>&gDIqDFu5J5Ac3)we<#qDTRn|@30|tN`q*%u zF#bNUzSxdtX$?t(GK3v&P`X$vwSiT@O>N$hlJ8$jLZ&66bD3?)!Elx2GENCt^D=DjlQMTc1lLeP(>tFZg6Q%M^)v zcUzG8>2=7`VO9h){I#`H$=PM%oS|1H#mYbh3Cu1imw^PjmbdXE8IF}n)VM-LCfq7k zCRWEgkVT`ak#2JhCf06i5rX<-~IgAWFQ@mD4plkmxYx1df7_q!roWR*uy(Lzp$-8iJ zrSrdLURVYa7E`Rq#Gm2hb+_X8E)wX%J6~=&&SlPwx}r4dl1d7>Jkyg2oC6}Uw&qt^` zq){;f6(qhlu^^MgiFO_BoBxAASEcfnWI=Fuaxbo7F#;7N@H)wTg#@|+bylQgziz~G zUGZy<3KD;R!r|DbWVSzYs31}Dgg+T@x;p#9e-wKrN(8v@gm$?M zRPg^+92P>Ve5}OmKE5ng#)!ou$%Iw;`cXrt>+2jGN#0oH>tE`o>oJB&E&~-L&We+P zS|8r8Uwmp>u`-ZA7e+nFWuSt@-^V^kpi7RX!e10BNZ?pYt`)vBCR(*4w}MsNhfkYPtkdf_c{2$-7 zNZ5_9K#mx9BGG|0iaks4?ToJI^z!7`xlW{GVR2$jFFR7uA&79(+N6JZJ8{N#5Lwft zHc7HBPsVNwBi~*Ze@6|hS&BSO4k4EZ)FT&G*pLc$LWpv#-akfU_!dUu@eCUh@+yRU zxmd4QJCHyZzUSrZf$!A7Db}QDY#15m)Ib_P$OJwIk*M9-nrzt=MyB}wYn+I#?Pk`b z?V~VqI=MK3ihWuMGRH5Rlsoc&trZf!qy+IA7EZk17B2(afv&%gcgyvTA(IbTvL2t# z>km9iAgezW>3uG0dK}5heT51V0jv6vtJ@0o-T{!{B8dIdK8)@k`hi9Z2z~jdb}58 z0u>}S_vuT19V@|xq+c#}&5=OYoO8X%xV0tOyxUic5vU;Hu{NHBU$SO{%KwW%SE)MP zh)u(C%;wOeVr8I$guI^<-<(LG>&w(IQrNlz>+s}hu`*CW0{4%~y^938{yvgH1&KFl z5oGR>Dy(ATx5a9O1iEk(CD*Ejx%giDeX94Y`a`{EJ53;|U9!D+f#^oEwaKHkOQfc1&MyYOWsVC2|?4Aki^x3|ZUbtUe=sak1Yy z66o@oo{oeia$$`K-b@&J~(b$7gmMXkMSps2D<$ppFT*0ZLLh+)a^j} z|8gtVa;z1)a4l1AIlk5Kebr@RI(fLnMmaO-b+LC8DoAX)HikG%E$}Ye@a#Vbbm1v# za;={KN+56kY*6}@o~+dAmP}5>tyek)PE-PCB#9V`rAo8uX~pg=+mola{Ce4mDBA2?CCVziNp@PJW>F(q}^QPogwX(&oAQI?G4XRJf zVq1|Ey&)4c{ytDa!oF`k^7eWQa?-xsKL~X3ruE1jTTimbr#OMi!RWf=_#01h_KSE2 z{-0`v#5?2KWMD6a%>Gp2AGJak{{H2bqk_cKCN;@yMJ2n3RVr2n66mTjzdE`3jFM58 zDiVZB?DjV-GDAK%VMl(2LokyBffrQiScK1Uah z3`9Pe2UE1uO+3`IH3rknsag8d6E-X3#|IjQhTorrc0JoCe~-TvLc}qS>aTcl>Dq$4#x+RV-4&`y_%+zNeZrFOp_E>&O$nN2!_6iyXW5OBozg ziEL~fNVaI#mDIx($dapuDDT5fj*uGBJ@~%fKehF-+r68YnaHwB8Z)EBhRUFwS#17Y zV|KugdOAmS?CnAp>*lcsDK-SpeCgR)jN!{JU_OzC zr|9}}4%GF(!K!XWD~cz*;hAyP|CJ$K9IB9UUws5o@v|#+iU?L;)KMvp+i|s}gkx!9 zb2*G$J?J5b;N=!P^<-PMeaEgeblrXZRqy8|*MwiH>aPFMXb|hZw=w%Qep~)eWiYFg>%s0$+MaJBdSspG5wYi| z$_RCCs~}!?iy6nrBaB;$7_nJ-*Dak*wKf;ThyE|s=pCNCp}8p!Zs0&}wC>6lS8-&y zfeyrMW(0fSZ_83&*%1GQam=o{A@;-S_iJ_5s%AXU(Sl=45z-jrC-!;md#HX~=f$TO znR8T-kjofT;kx?OgYZjdWddCo^H+b~4CefUDQ{jjLunxLG*oJ8$}sj=j`1pr+Djhl zyYscbj5*%B7+a0^u{d$6)*JF@SvNj=iU~&r35=T7>6#~4t42%1xz%%-Ko>?$i!z!l zRStfP;0vD{^QbbFcDEA|@he0`JVwW3ZADJ2VccOv+N7sec27#%MYvz~?#qsb9` z*$=tpNMIDZ$ZKGpOX^vQTGcU;`U+jx3t~^4UAksGAdr`MYQ_sHZ`GGv*O%S#X~29N zY}T*8(U%R3X}}!EZ`M~Ace`mx!`*(_CrRrW*@btHGvlZr5tcVz-`KoAoB74CLm?x* zv-Yc82tQiNR3gw7S|vlDlRAM75%+?~)>FB@W^yHzcMdV-s37sOVnh9@T7ww<&k*0< zOR?2?MT_?sg)LV(C-F5M_6IoR*Xxg$EAKuT&f-j}t^{oaZvp@FMY{@4h z)-fQG%@(n)c`pm~pV#$b{yv5X(>Gm@Xe*AlZj^5Q8q4eKqXS=PgZe5wd4-Onf<&2q4$Q3}nr-O#KT&#FFErno-duOYNFvaMy&y84 zw0o)5vTDt(jowQw$2Oh0BoXNHFmYsSK8mi=K0E6A|bC!TX;FSbu+r?%G-Wz;zNRy$?gng3yXB?4X8BO-^;p>Nu` zI~{oa)BB{BBeCwJBWo~lGV}I!7iIKa{Y5MI=+7sn9gqlgVNZ+m?yQY@yRabMZ_Z?` z-_oiqugx6xZtX;`6Ny#XpI)-XoX%=mZ?8&PYw zAoRm6xYxB%-n_j|>o(nqQe7(aIr>Rb?{r>rE;n)yGU0;UHI<|y$+t*JKxv4r> z@P(^FdB66S8Y)Qe-cBs4`Fz&lXfr{WbT;DGT)Xi$UEL%CU06e%u9g^4Mt%t9ZWmi> zs36hH$cfExoyWQbofhqA_|uf<)DGr9DuhS`y5yFp6k2i%&v3r$^n87MV_UZF@KTmz zvQw$hz?uEFU&wl0S+6+Nab^q4FJ#NY*NJw_9B;xW`bO~6ZXFpC=)xWm=aTtY^5dt% zcy{0A3>72}pL1eYau={XZGtGnBj18It{ukfy?!DQ=)&tH&Mf|I$i~7q!ZKX2N~!!g&11`VxUI>=B)=shJhe-WbB~*D_O4LE_^zXI9E# z0rRZ*T$J&yi4`9=CY09HHyw*rM??Z zud8ot#&@;%;q7gXs?W~2FcaNu7IN8%RN3RgMjOpx33VLEiuq;Psm(d;-B?3xZLPUx z{8X|ZZ@Ox~iV70_=DV=nZgW}D#qxq^QN@VIE^5!cy6=(*bYTs}siAsvUj4K`f6{2F ziV6}ZM!K-q-Z|{#dP649MSsls;=3KV*@j$+K$qO|*gmGb&ZCxm*@N>^%dt%d-ng)> z*)!RZdWM$oc>hyd?4$Bb}s^XZ_IPOz4*7lR}z7)BfnkP zl^ru!kcZ)`rHl11ZC~Zu{MeQ(H## zuFQ4Bcs5{K8!~XdD@$9G!HS}NiA8`N8+?DYf!4I_L zu!maXwe4ur-{N}Q?9W8vMsoj$E3;oafNgsmLdLDJV@canSiJ;84hZu)kF<}SUT9{n zZ73>8%zom^>X0F<;n^TT)I4%q>)+~&7HH-x5$M7iigqk|uJx|}M=J~_6cr?FuedVL z7bDoS=Z1FdF@LFT4mRdjOuQumU2@A$+_@YS+6R)n?8Ok_dEFadKm6Gh*1K5|M(q z`1OL;wf`b*d*4VJ*~X1c4Gv;oF2)ew)^02>w<}xV6hlrvv18jmhO#1S!`kb~-j_6; z%}TB4UU!NL5-&a6nDx$X%xZNnL4160T6@)Oi&m?ROrQ&ED2R2}H1qa*wB! zS9fE}Z}eiW)q99CYInGyEy&We!Z}?f0$p;;-<&(9Z7JPMD;gP3w+wS*b1yeyxh{$1 z(hxTm)x?7>zSNKGC}q!jFKNNDS`HFrm?oXjlGk<69_ZpIDo6~Bc4IAiwr2DD#|z@w zw!_-9$l;ooUvG&(7xtkT`oK3a7OqoCz_MsSyt~{!> z?ovhj_OY+jS4dPJ<;EseZNSFuNEBrh4n3xYKX%uu--?$Abm5g1IWrSaXcMOCl^Np_ z>8SZ`tU}4h`tjukk*NCiEVf*!E|DDC3N+I1`}IR%F;uqNpIT z*v+0DOx>l=+%-fHn+BfImaiX03hVci2z2>Qc4Id4w&`!ZF_bZN>ltmoT{@{#sUJlJ z2}3W8|GY_miW`UpZI5Z@zS-WHW=T>zRMDm;h0pbQ)^eM~DKTY_X=cHDysFwJQLH-> zE`na~^GfevVYu7xn`q)Ba~=COx4%T73-1N77QW<&cB#EPYfv>wx=WC7o#)1?F12D& zy9SCf$ZpZQ@(&$zKMFokE7WVAk#{T-+l~V-4)2?cPnfHj9NxVd$E4RNJt1~xQ|4cEIQTOgc ztyxYbwQEKUy;$Fk@p=dI-{-`UqrPs;cCdxMPF!Eovl zO)DKsQ9+`jcplHmv(gu(8J@elPhZu_Z!=RJJ>nz+U06eLJ&xVf=3V(oZe{kNs2~yC z$Bmu29-)7hYWPK2`(4vUZ+jx%q;V2~F1h8MpFPu_uc@w%-x(#f9NSd)n^?UK9KUa) zui+i_-DTK8@r`!(Cm-^4n-hy3T#3wE-$Ilz`ho-h;5JybDc6dk zg2eQ>POQ{h2Xb?*Vc*?Pi%NW-O(%8xx;9k*_@_R3bzjozvp3n@wG^ATst1X>(wJ;< zF3tSK7v8gC7ADSiO0LS=xdy3~YPY7SAYt~S6npL1gT%xcW?mmwJM;0Zi+b3*r9?@AOx5UHeQ2ExTlDQJhmcM$Ldck@oAn-eX}293BB7%5JU2|X(kVR)yy7=6cr>A-eu^I zjteG}h8xCkmQ`12i`ILq_T>gh1iHFjouJPmQ zE*(s2eTpHE96IQilL@3$co;!ir!#9kSqmTFsfJe=Oi@8%_OJ2!9TDTn`Im+=hE|=Y zMR)H;I2z1G{x)^s37rSUkUxrHJN0!ogtp#{LTtm!XK&z<_wnzbYYK( z^UuqAYqe@MS8t9PCiN8($Lt&G&s>>6j*Ky!%3k6{SIy&4b2X>wP>Dbn_M2GCxN<80 z-kPRr#QRayFQ@YE8N0fY2GQ|kyMLwKg(5rQagm+yVP5+FN7J*&^a+OfNAj3h(%FNm zBPx!fJ(G5LHy3^KpXd|J35fqmoXuf+Pe}{U8(Q z!W!yyN#+6Si;U*#s+^$|GwxyTKHHIvlpErHbNFm{s~zs%RGn9*x%%hOFp3Him{Cxt z8&P1Zx<94r-m}9c0$tc6;_GYuXT-_5nOfOzq|{ePV4g#r&O2l`xpSwfn)g&D(1rb` z)8*|ruKrrBs*P{QQOp&EnWjRPZ&BRD6Qj1+7pK!*Tdh~cCL?u}l0Z>G0&`)BzWTjU zwdv}s?rN1J5$N)KnxU*0Plit;3{QsSyd`R+mA5*^d>};y3Cz|daxTxwP!IHLtsa^? zSR&Ac*GY_)rjJ)g%=c8|Yotim0}0HGD1IMD<5ioHEz|;=ArgTuynDoH1!Ya>>X{wY z)%QYZMX~QRPekd|c;AxX-tbpxSCt-jL&(C&j-uuNjVw|}F7;EZv2GL!(LoK}93Wi}Bydl?P8V~$1g-1PUX86CBoXMsYa>Q7k&g89^knt@)|M0_ z!RQDl!n2%7z|>|$jtYya>O$B1C8!o2Dn$hej4;>f9-Fw*DQ>;gg^gtbT^L`c(D0`HJgsv`Inug4!RS4)_G(|2-k+SJy0>UA#q}Xk zyNnB&dGWkr+@r0ycl$Q5q5FCdRIB~&C=uww7(a2hJC>p2ZYHZ04*645kccsLAw4Tz zRt7(4Bg&|^Ku42IyQ)D&p>#HLB@dD_yq6{RB)yYd$;l8qMK`z`nRB=bsocay*-*kT z(m(y533X14P#ew&rl=sXppGk9GBQLtnP7OrwSH$tMOd1iG*fbvl3J0=0BX zYt^D-ByBm}ju;KE>y@%1f#lqEB_-dU^Qw^(RjgL2JAbI-I{2#x9lJ?oAYpydl`K0H z?w#voSXHYT_)E>M7NC|H6)q9z!X6Q;IIW(jP2M}H7OSG^j4O6zqsOECFFyv5Ja;z| zSK(lOy=8G^mYW-y({5V+muY=O8JSD2tM4nnCwE%MQCCxY@_TE4{p%_z#5~T8L|lo` zM-NFPtd|>UV7L$sudFNTe*>m z(=7D4UWS?Qom&sp)e9@Bo5gG!{};NjO*&oZ<}<2y#dNY*tgw`vq7?(C1>Zk5yv*K^pgq)k`3bT@pK;Yt#-!S( zRrhy6q+p5MSLnj)B+i_y!PGCw(d_i_{&cRZJ*kmhi7mO1N>bt6MFe(774HLQ5mntN1r*1yVsQClX^h5aTX8fP3+YcFb~ z{pRs>cB&f*boXG1JNuFJk#6Kll?H73`b6@mggu$Qv;{lT%23AaS4Y(z->YdIhWDkY zAn{b(SEEFJ##P%4*Zl2CrY^i2%KvE{gH=GHpSR2ztJ$8`;*r8?*V6Y=cnXv5l4WV_4i?jaYn#QA{| zfiA3}PS@w=EwzcuNo{9xAVmdh_-*wJ{h~Fr@TI6Aadx;JIU~Mvnm0GB0rYtJ zT#c@yUimtLRLw$cpezsFTbH7OMA;p#yNCdjDhGP9{@*DNmRZG6UUQ>z+61DSPNp`6;RwmKkP^&Gk)cUbzyr@eHi9na! z^6un|>UFge|8v1jYB{!P+E7>Gb2E#b3^05@-_72tmjj%*Nr($Y1&Lo}?MUXZsqDj5 z1MxGYNFD52jWO4{2_Wy50)M9rUH z)a{?#d8~+lKmuJ@LvfbSpkHdnrP{pThSC%jBo1_QB}(r}Y)n-{J8p0Np$^_&gWFiz zO9Z;)mhb3qOl`AU@cBzVNG-=2Zhq-Pc+N~#MKMIAjCuW2%@z?Uy)B-rs3387ZdtN; zOAc$6W+1v)o6?JuDX+Hfszjh`&odX|e_$rtxu=>SuIHQ6FcFKxn=DmvM@_Z)F62#( zxorK_@JK_vVBDThO5Q6G=)xL` zsIYoww9X43zR>BAiV6~+Pq`2equH$PHN$@AJN-@R1B+JtgnC{g&?UEg=2Q#1$Gj8o z95zYXSA=bP?&Cs^T${&?<`^Qjo<1<9w@(G}ce5v`s30-jqAWSMVi7Ap$x;xZ-j>uQ zCy2-Xh?EF)O|I=iN@nG zUc#n~Go0L8(bS6SH-+$u4rVGUNW6UGO#a(4pBX0^BIvB1n9u?CVLT|kzC@r4YpBz8 z$g`wxle_Yg4Lns;kT_b&g*<+j%W59|Bg(KGU`bOGyYN=W0we-ma?7W;u%cC#hVqi_ zPfIPwHp%C){O~cQWzD+t$(cI|DoC^(YD=_)rL1m@Akpy=)((Pe8um^1QjG2B|DQTMhjWq&x3+^Qp1!cIYsaiXFe*ZAd%O= zmh3ySl+`xhDTsA;R@9LW z)1Anxqx0EP&oE``>N4cN<4ag;%@9>QeuV|?XC20)N4{sMAR(VkKJkh%y|lSI&$T@w z5$M|Zq6}FvaVfjIa;_-DJ;9PTycfnVxXfaxAc1G0i!&!To6ub$5xi;FiV}e?>;C{^o4JKzHf|ltXWkhk5$M7i zirL*&Q##o+m{)%guAzd&q7PNc=F>TBXKh17eDr%$y1*@%v#%i%fiAh_Jx~2q^P6?z zJr1wavb;-^dL3r5G5k+{`A3fATfr1II>lB$#jz@R`eHh3qHW0+E87P@tA~4c;WIZa zl?ZfUkBB$U5gkqJ5Xh}bj?{7_Ci_<0GFZPL z!@i=JjCbm%KW+Gshl0q-e4!ex^5&H`7;)U`+oZn(c{MhMZA-E!w(B=E;D!2f zp2E-c)N$NXi^R7<4y0Y*ST@PooQaX;?tAKx-Yxmn_rEkG(1kVB>B=ZC)cc1h@9yz3dr9o{)_0;EXY_&yXvHf&`6v%q z!stkKVwqrW5i9TdMMBLF|w8Q`-hd@kaKKBm!NxZe%Da>5JGe7b1wS-y+ne zU!r(BuUi@_NURvOMR_@XK3h`0tsoK;JE$Aa^x@6=osDiO|t1I1;c>QxrG*pmKjC+J$ql%kT2tC?|AiU&7r*8O(%&!*WsR-%6GDb z6}-(A#P{my>eq8a_@5hJ7%E8cG24`?LpHKHqh|?X-?RbhudLyG&4C1oKv&QCnacWk zTUaHBy@Dt(ouEFgIgIZtU74YRg#D>)%D4v`S%tCN1u?;XuzGvXaGv52s~~}{+{>aJ z!CP3LjyD9MXPN4;f}uSAZfSxF5=$%QDSo>)vZU;bf+)W$RlPoF7(W!JNd&r_%Va4N z<2SRfZ3_kQ?p2oBu=Wt1n(>yPg2dOpdCH528(8Ju9|h5)@=&#Zqg3wJu!V{Qy3zx( z6sm1xQyyE3xmxvJ+3M1^$$VdMkctWtqxR=12SV1fRq=-Tpy&G`>aLUl{8_;ii9na- zlq{uh$Mvjx3qxk3>2I^tFQ@wP{L%|lRFG&{a=T(`vXK-0>So%VH!1x= zBG5I=I9vJrb2$sXYKXtO`f|Mb=Rh!@{P3rW3KFiHwkw_=momTDCW6>fuAjQRO9$S} zsSHH|T~9r;72A4?S<-%AL6}?{tH$>6G$D;q!JS&3hsH9nwk=6;8&eL;byY zL-!gIfv%fL*~*tq^Vq&ofr9usV5oZNr3c>?U00lf`o9Vims{*m7GIjntZEomAX_i% zuHHLVlkXeuDG}%zwlG_%F4lbpn;BMw7j)>a4)k#0LoO1E3KHvv>`?BUo6ZjE!vyi1 zc2TSBw&$Z)wU-EVg&)dRt{P2d9$gL5>Xlu3tC@96@x2ZK6cr>MZQP;U^q z$k$)(_soco-y13s=oTvdi-GJ%*RqxkeGkPY4_NZ^;ywa z1L3;Emh{PMtVO;UB@yV#j@s*8&OLx-x@QPt`|eqani8nFFBnNtk%$9MyOUQ2uvdc( z#N)4a@g6@v6adGDTlPcg-H^Du3_)?crPpx-xK@|UlhZ}FIC3*-OvvGjHjp|VcOGacU{j+ z_V%QK*xB5L6wUgsed^dtBG6@Y@c(gjmH|~XZyP^gw_q!X-HjNqJF9| zgdiy(sHoW8g#{Q063Whu-JK|QcRzN#vwrzs^M1ar9|N2{=iD=MN3O%Rzsa}%P z_aQ}TQE1LgKzg2cWKHaSJQ%%$b_8ANfVv1-=20)O&mutcEiLUOLdt}P-*;k}WU zv9MQ~QgK-o-f>TV4HYEzmbA&~{%kRA9c{mTp`{ah1%-lvO5QvIKT#J4N8bM94LMJIeUh}BwqwPKVVkFjen5$MV*o$KHe zu%6C1;w*>_gL4(HqYgaeWlIeeB+OUU&Z(8Xo_2FKZhp>nw^vutp1f<8jYOa;;b4wK zvS$kI`^G^K8DDh8eVz;N7gb$D1&Px`YvJRzKWDFD4tr$7@ci^^geu?eb)aKv(DJ zYzObbduUQ8lOQe!9#s~5NAaH3T?r~kbkMAGHtyX+hcScLvf5GgGn>jU_pdAw=sM6e z+u^2H26Y>7U&M(o<{wt)NNo9Lm2>}K25sj4KoH%OuIlmbaeULlAc;WN zqnrC2f(~TR#UHpJ@-w-z^-LW9FRQ4E3KB6{Rylb#duhPOgMv6zny5o|#qqP<*6B!~ z%WCdE2hZ>fS}=cuAm%sMmE_Dges6MXiV707f~;~p?`6S_+$pm(KH8VRsP%}Uf{#UjP-s7#>i{J4&aORF3D z&BMkTeb%l~e~gRlJg-}vh6)lGsfl~%T2y`0w-haLBvvBObvmM>vhQgb`mVaMM$VFD z>d2v9wA%Yv4HYCXQZt#Hr{=1)8yuxyPfe8wbPW&fs1%lOLCcSsA=aq>ZIODm%vU-m za;k<35*Vq8I^l?H^^tiS_PSZLM4)SqXGbOddLJ4;HbJa$I%<(xZf`$U(lSaz1qqDQ zL~hilTy^Y;BzE9%m_(p!W9yD0pL#r9o)<0FXm@F;y2g1mD?etkh6)lGsfiuSCaxZQ zc!(wCO^^t5nZ4|wT-T=4N|%jHz=W}D)rdzo*cTUn4HYCXQZt##Z#$`WZSbAVQM@Dq zUDNdrN|KgL7as5vYusD5SgYxLk zBKkSR$SK-1qqDQL>6m{=c?_np8VEVYl%QtZ{1GW9=@6Sc-xCLB6IWA#SSjKWru1SDo9|Y zChl<-y;V=Fap!*z6_*Hf9iC{X@HN}065m3sVLtkxxV`n{*4cjuDo9}5CEkOrKdJ9J z`tk~Tp+ul7!OBh<{VA1NoUs;bbeeudEes#Wr#YP^s33unn#c=h|EaGJ1ajMxJ0t>K zbxyZe7Dn%+6DOA!Yh-*msva|&%m=!zBB&sNk(%f&;`l`!S2LVg=S zZn|vfZ$(6wmyW9G;`==NZhwLb5*Vq8{#U<0tLHXH^B&*IO9Z;I8nsuxcHTpa^|&L} za36F;4YZxgACGvdqJjiQY9cSZ*GIMR(p2tT(pw_X)$xX{axr-ief3QjYZM+osJ1^C z%b$3CR8TU+bV0i?4ga*)`~UW#!%IEODtdG+KHlq z1V(D&F4gh5`tU>yk6Q3RBG9FMX{Vg1vWsr-*jcQRaz01(sUE}Q-&JR*Ac2vZ$Y*$Q zM}1Kvf^W+nB@yWQ9nemB+cuRBI6FziSF?NVRviyc;RhV1F;tMiNKL$gGq0$Xs)TTd zr|TpFT{GXdRXYBcLLcsk67f||?QLqxv><+PVj4pQ35?XlE!mLMs@e4k+;hu8i9nZA zbX#Ro`Z_xHnw>5_+k0lkYl)6_0}ts zEj)SuOu64Hy0F)*xXnmtNIF~2R=vu_XujsNlt0xP>Ng9fs~7=xZ8=NnTew(P9~hC$ z`S|jrqB2l@(tN6h3KAF%is-eHHK}s$gp&3+Mk3H<-gB1nyVn(ceLLec>c+wnWc(NA zP@GNGP(cEtL6a%ky(+o5?XEtwu1uh7#v=vp@IZP zgQ5rBEeql?B9DG|i;)O)4Re{Lbbi^CHY_t;tWl-uA9ZuW8@jJ&jD`vl7!8U}2+kGB z=u*vDql=Lefv(T?vy{(kd(pZLrinFv4EU`+Kh>KhzmCvQK?0*e(X(c_CGmSSgSGJr zl?Zgnr?q^o85whTC9`W5qM?EWMuXxMXLEHzQw}m8Q89u9y6|jSeD3xyNuHYBU@b5E zN@vJOU^FQHS5|e1t?M_@$-`43(1mB@;tctDIkLk~bWaW#CY^;NfzhDJl-HpVd6ik7 zR|^^-5$M9Re$gGqzY_V}LPULs`buZ|NMJN5&ScKCAXca9^6DvFB?4V|XCZDz?P`$z zu1)yMlB#q!fdoc_Moeu>p5(OWo*Atr0$q6bBI;6~*Cws2IPmD^&7?aPBrqBjClj+f zlUd7q@DseIM4$_AghXUnssZVg(3f|dSXsI&LIR^fak8CC$kZ4&-fmZ`@y~~$W$$u-z>LOx`RXlqd{>NUZOiGcOsO(DLYCc z(1kaqCexfgEy#xn;e6$c9@1SZ5*Q7dOha2bkw;}B`GfMsBm!M{S1kUH2F=N+Z&AF> zqU+L~FcKIIit7Fj-H3x_G(VY4Bm!M{gDo;rsx&3t$H(x?u3Wm?Mgn6yQCBoUBQ1TR zdCcNhI{qwl;oZGBTk>f{a(l$^R=@g4cl1bLG$>9|&)JhJes1qqA>O{U>Ltx3YK(fpBRp+ukyb96)$zOE#x_Hz^u&X#j= zkickA)XMa(MS>rA@dIn*d>?dSu8}y)m|v1uS0BMwKm8`<6d{2#2~4J|+1BLw%wfE5 zRWpu13te(H)rQ0xq#hZ{Q)d^Ea-)!trxgtFu_HEv+<4*?IsXb>IDx@r@=Ej}r2abf z_4^2Ieu*q)X-+NO8D8?g!mI^de?Tm|ALDl!git7;%cTjMqa5 z8(l_iWGfTsdhMO1I6OP22U!{s*}IZm$Zs}5@thQ`p@IZPoF;K8+?V`_U7}Aq9VHRy zN(jhOsuU?fo9r?Ej+LUP!H@5aY3hn-4HYCX;uJB%`W|Gk>vmeqDM}*HRogF13I5cG zw(ew{^|_R4Pxd^yOH;z5G*pnlh*MO0?{FgV1@&3ny>N*@*NMJaip%UCbW&lgSYzW_ z5i^{3VhdY^Yp5WB5vRDpy3&(8Xq?F2dxl5^x=z*3Qj$ja(mv)>#2Te)b|ND)m$T!& zgEUl-!1z&AC_Hf?Nslwx*B;{~0$tz!WGZoeLTT*=#(k~X#X-b*@+tPk+gC#c3CvUw zw*W8Zkt3G5YJ+E?+RK)=l|5G~=uY!uReX-;2j5nT`zGlp^Ww!C9SWzBPOBHI13pdB zP(cEpX>s1Za3-;vL)5q&nLt5{)L3sn*~0F|Q&tRFJ@DTGT=Q7fBMdMbvXe zxJ009$okt#UD4Ch@qL_FeSoH zt1aDV(JfJ8jSPQ(a`A@39PWl{s33vQw8(S{jv=kpIF@=aP$JOf?s!|tboHT)z6Xmn zW*whMW}aKZmYtlap@IZH)8Z`LCxI*+n!#oc_Lm5Bb*^<=S>7^;4ryfM;&i+aN~V<6 z*|u7K8Y)QOGcCIHM9m~$4qswVQ@kYtU3XpCyUXWA7na91iH>nDpY1KoJ$vF7*(dvV`h=bB`fo;zTGuckia}Cld0C@<%GG{;k6HS zk_dFIs8^_zjaf{COB%Tb&A-nh7e6-QXE(IhP(cFoy+qF4-nHa+emlN#PeX}7*Xnb( zl;I~i>^Yr6&G*pnlyfu+i^koy-ztfR#xL!db(B%|-OPT1gmhQ4? zBi2~>VFf9-yccilQd&a=3CzC}y(V3@k?#El@n0X_5hTzxzrro0YlDr{rhYxK#^AIy zWW{24zOmY4f(jCtM<`Avf>TMEvR>SxFOvv#ZA!bT#9F7&W1}jGHQIGtPvVx2;(yv_ z5>$}Dd`MCA5l2t>33KE!~DsFgZr<33( zf&6vuNfilnc|{c{t9`c9nl`7z8avBwAZ?ODcypiiDk?}|o~@`J=$%G-cm;FYAv+W# z&^5Apf#MLfogVIQBrsoCIt1{TQsX27T}?+^SHebaq73WpI&sw|GJo*Ejfxi*)fSg*Qd_cl*V~W>8GiKb>*av{|h2wPXT$w!)LIcy*tlf&|t#h@Ko}l1bM* zcV4ahTZur|de^Ipc6bK;IP8{KM*wBx!E>lb*&?QgEtJr%s zx%H|aZ`igtM+FI-MJVp0a+i>_#(jB2$MjlMQuAci8sIkRnYW>A# z`e?^+6{F?P2h7x76XWzlc}7H5_2D|QvO|V?cxH%(3KAGOi&LC|o5;A0G3xXXnLteaMk+}d`H8JPG(aNI zbgBBZUNFk^ofswPxG|cJ($q(}3r#8h%1iIR+ z{i}@Fu!&AF`y-;IgdIo7Qy*VmbgDl=1qqCt#i82!3&d@LA5Yv?S0d2mU-z%#dUG=! zcJi)R!>rU%Vs~X6Kbl^Spn?R(!Qy;(+Xd32)i@rqe65NEx&n6mQIydsG)*z`cgOi0 zA+AjVIGa96MFk0rgGGK~*m=^&aXjBYd7uLl=xW>Uk217>3azrn$lr~8c8Dy07Qjn4 zAEl#$1jfOlcf!K6q+EmX+@*CaMFL#|`EOk@KAFpB});ybTl;BrpyZ z5rESv((v+FzVuLOh6K8PKK`XVDI<1w1B!?>(mnFY1Ml(Ntx|J_3KAGOi)g9n5wfR; zFIW0akO*{rt@%qi^Jop-bj(6T$ipA(BY^|`c&1AtLj?(poJCG*DV?a#M)C~bwGx4@ zZ$3YjAv481uZFipg#65WH<`G`hu^8UgQ0>1M$V#|qf$26*WQ!I*VQEgUF#40P&Tz# zNL$n!rHiM1)^@Ts%~RZq9%rZ^fswPA=22k}Y473A--KS52z2dl_(K_FHk+=Smnzn1 z<-eJ{-r>&6n%`rnAc2vy=z(1;o%9?%h+olOO9Z-xZTYTLZ#0bt&$}4=~p zfswPA$hK}bIoi{iU!PD+BGC2b!8gS*&6}R?)=;dGdu$syYSxRpT`kU0K>{OZad&6h zOMa(x=LNG$N(8#{%Dz#CT92gfMDIb7g+#ZLP~MYQ98;2`f&@;v78O;wqPO9$A8KB? z@lsz-jIXh4rN}+E+E3fM#Wu2d zWMj5BZj#gu5ebZ(MJ-u_OcJvofTgaM`&pt3`y7gFs%PoM;d3%`IpQaEbwmPVZIP2& zdq1h1kjldAcuNGju)Cm$sn6{tZsl^AV*@X#iy#shYl|JrLQX=PoMkoK-6R5C*dI`Q z8+6Pgxt(sZ*ZHneH$)^b))sd~l~0hf8{f0xx8;tD=)$gi;`Dq8CoRhTVeb|=OWpU7 zz*t)l-7gTIAEkNK5sE~h3;XJc>a)lbL^)_7`hIklx(FhHv9{=KD7pfF@U!NJGMh;R zy0Dv_$YJrlKz>*>;7P9=NnPuZz*t*UtWUp3R?=3ys;H^PpM@^$M`tow9==Y(s@w6Z zDHc-qJtQ#J7T+JfPf6pdgzLrs5d2x_!Y**)rn=-EqQ7(Goko3@y1gNRk+Ybwe)AQX zmD8ICx}1{;bYUMi@t5CwKz@Jd&#i}vo~->XRd>r()X}q=iUh{m;!`y99l6xQm49+y zD-r0z?rEaxx6u=F`@v9tZqZ_?OBxawYnx1C%svt^@r`fI^^gd3VgEC6;`Qk%NqytR zn>KTny1gNRv9@@wzJ4Szue`V^w}?cb3%i+#jK=6^q(ky3e*gSq6%`~fauyl!S3Z*F zzee&gb6h0?UD)4CywATrC6ArQ@B?)#tEeD>k+awjp8Y_q*ZJ_@vu8@3ztDw!%EbJ^ zbx+8sonv^4(_bAGBrtLoHzpSENri4cJbS=8se>81unU;z!?NxXxnFk-pLk}!)K?7& zjGV=J;)mB{>oadY`cWl@KMP&hdrN$_+utMpl}7R7liNx?wvfPBTjVFQrz9xblW(jv zQ6kVKcg&i*pn%+s^5SPa6Q%xFNMNijc3$!K$f>g5$KY;S@mvtiL4#%!56gH zCiSL50%L6vg}=N(rr&qvovZGb2z1GPqk7*zMS@DW@tST&q%KfMV61I2E&Xwkbe%qc z@2`ACBG85XokR{x-VsvAZy?ue-j=#qA%U^B$#nno8Pb*a;hTeANCdjDtCAqh4wB`8 zeR*1GxqA{47;B5H7mw4VW<(GE)bW?pZwX!4>q*=dbvj6j*6hifS2UCQMj?T*w)n1% zI!=COcjJ`@7n2Bd{Y^GgGY5Log{2#bc(>+qMz#by^3JtOa8!`MSX-P-L>?l2zt?-2})8Dj%GVNu4QCE)Y&|Wq;x4l2F8SIs36fLCsQ#E zdU&Ar0wech(EO=nXo-p>#xG1F&^6RKQ~9DEb9gY_I73!%EFvS{lqa)KglMQB(fo9w z(xF%Kfv;i4iEz_x8%XUyD-viKBoXMk*{x9d?`DC6$0*}`*KX`yV%EW$G`t>4B+m6&m7dKP8dB1m<`!+!R;aFPTJ>$2-MQyBFxpygb zlhXku`QH?!Vr%{*Gg=QL>X%^}DoEfQ3K3=OD6Z|^>`yj67$_0w!kHc7Ouu#o?dq0E zM9bMKvvK{A9BDj*~>7tK3@~wNHVMuwKY&ZICA6~@$B3L=HS4WRA;7X$l4s_@6d9AzUN37PcYw31cJzUGi(L2V5YT&234{eqRk0B=A`f z``S28e)ecia%PT`2z24|ChAi6UuVe$Ze(b!QQD#gCTcpAt32}aR^86r)a!{1!1<QBVPpy=0K1aY9DiT@bsPRfeOCrF^{ z=-uD?)qyosyEX#^aqVC!?r7mde)k`sp@IZXvJ*SVnW#oNt6DNz*&3ZgnmXPp4TCSxH&mX1iEl8q3C&bsu7QB#TMEZcRPv z4^)56X`)J#_oR7ut$tZ^wWmKh`(GE$1PT)P8;ba9sTJQD=t(jjb(08m;dDOHq3L2J zzGvHTvO2w&G=&cd{7;K-&M-@!aJwI|iR&W~=)#$S;&XRbS>E5QH~Dz2zcft{2@jti z`svZ*)PSW%-;XnUuak|}+{gs$QCd#ljIhY#OW+LA0K z-h7-O8gx5K{7$+O&ryCFDoC^o+M`qruc|KL#wSCJoPxJSj+Y2@4YSy*+>hR) zBvm#t&wR_SB~54aC6<1ZG*pl%-eZOm8B|5J6?2$Hw&BRxWX4WMGBhVxBGA<^ai(H7 zeW#KiA1;VXU&fGK54)4C3qv(jkf`i#tE|ebtonR5reJvO?n?4rDx|`*DH4IMbw%uy z!QN>~t(M03pq5pEJZsXG{JtEap@PIAmwgV`waV)GijxIVZr>esrC%pfzE_k)psU=U zY=^u`sfue6Birz)^BA>d5+QGFqBT^IDC}UBGqy%$)zT_d5RD$+P}(|oAT2M;1iCKn zvd-DJWrs54tFcDmlmb0W5M=~`3KCr#=H$N=ztszKgK+NImkupkmt371BN6BtJT5nX z-i;K8dy}UNqH~qCY{$&LBzepvtzP6F-9tP-g>C0_GK z7me3^@VMD*#%@PaG&@*B1&JARXXW2Z;p!w&Ii8DwM3S}#nRyoiMScYM5H&1MeoMGiiYr#qqxCrgUS4rj_y%OiHg z|3tKgGZ}GWr9632+Zs-%Xd1a(RGy=VguKS!8PRn6`<^6zX_Pb%5?w1p_vJqq?~mdC z-XDji{73zJI}`U7ks2yU;NK*k-D4G4YSXTyr+5z{fv(3@?etvnuI<^vc-Pt;?8=(I zR*3b}DHr%m79f21iC^alk|iW*$yNAMd6h@hp~|N^+;ZuFbx$X zCJoHgUvxd@keF!vR_5wh)+3}W=~OU9BG46nE=k`NSt&oglaZ(YW=u#A@x_#A#x{s)$6?qvgC$RV}=hf(o z;TkGPq*ct)yX>o_j~QWP_K!&J$FgrOQ@53hk_dFs4zu*3w-)Q??i-b?j}$NVzHEXT z>J_P>f<$BIEPd;ld3yDKl@@jGII_-je<(*AMN0&_;s(spe>h*!JN~Q4O=>@wt@2o+ zln9N|P(h;1xGeqIlXLnj3*#>@*TaFeIj~F5-ViMj=(^)EOD`oVa?gsntm2a)uQ$s) zU4tIuQ5q^pYzoWLN0^tOyLKC|;KV6*tXuhAbhUU#A%U*zZnN|qFPhS`rH$XJ-p1}M z(xZUZKM<**f`l5FrDuL@L}^Fk_2}NqmhBe(;V-U=kO*`II?d9@ii+Ix^^G0m)|XCf z@z<`*J8p`G3KCC-Wa-Oi^`NV78I=|*ciOT2Zxfj!W@jRSE}wd{^h5K;(#yS!{)y)0 zi)p&EA8Gq%khI4+e*L!+A|lqbb_4$3UTvu7f22dHk>vhLd9Q{9MmQqgefF3rX9tq% z&%C6)8oDs*H<^;^Tp?w;^dXV!M@u_MBrqm2ndbfBWa(Rb(thVyi9naUo2XGMgA8{d z(!Lf6jEO|<$F+6j{E3#N>&8HdKo{=9#jQ+1GHKh+mRL5C_vc7pOe8wjHw`1U zZ|jkxZNsGfIlAyPLA=k4xsdyD&4_t(`J4d>jETgVOkNApXLn8Vby%cy&VVjF;}8+@ zQWLT9Z9s-@jFL`2kieKoWFaj-rrvU>Lb_LokqC6%?3(K^=X#1mxlrRBwV_B~wXjTG zQXw`*Lj?(pi9}V(HLg6*wIthnO_d0A9X?(==fjds4yFgj8spp#>Na_nWS$^UK|+p} z7B97_wsqo8M@sU*)8F(b)xD^XICU!Z zwm{!ee>5GC-i&6v_@;l}?oE3;8n?(p>+WKI#W`I1qLLgHB&uz^qDNmIP2H@U3*yb_ zOcpqy2jBLgxJ009z4l%2Iw_d`{dXI_XZTk3(!Dp|-L)7;1&QlLuIja~i^*BTj11G? z1JfB7Cy)c0n@I$^>g@ck*J?P8Zk})4>W{J9$SMW)=Mzr;W~d)N=VdXE{)>GBpvwn*N+R5r-oi+`?287fFDI(tnID7%Jw zJTx+}k38DXrg!t^;=z#!bltA^OF!~(4J|sy$a-;1%wVNzjOLyV)-hC&SnPXUU+TS) z2DLCU$-g{0$od@{%_sa!ln8V^fBj3pUwR|0($~n|Is5oBOCLb^yeGx^$erb=`89Xi z{e3;U?vokq>*7fli!-q?<4|U zcJbwD3q6ru8Dz|~_-=cM?W^67|LpRTp@IZHp<=h)^8%amt{)G(eoG?IHR)D)YW;c+ zoq0V(tdV~I80-3M5Kr!Xm7#(JKA|R4TIMyD;yswx8hltH(A8Y4K)>}`MCYFPYdne3 zXW0T@ckVFu07C@{d_qNkhT3=7qIh>c@6=X_K-afj6=+E2a@r=-m_!qI@e13%V>thE zaScNS34B6D=2`S(7BFf!pZh0KBG47ys3QISX*J#GXiU^O^y(JdzQvp0eKV1vf`t6+ zHZgz2_T2H}ZIbLH0$pTBMY`ztIy!8>F-56fm9uQ9oeLRg<*VVTBc4VMUVlqJkTXuP ziZ}MPJ&s&qgKzdFxjv&cRFJs0*+j?Lgeo!NMn}0-qT5N;ISLsRHdZ3g72l^&zj(L6 zA!DR*LLYtV1gn*9Pn6RB8Y)PHmo}r{#=Lh}|2jYrO=e`X!e0$ZM?OI!&~^24q29H9 z@`16T#=U{wNoNbj)+42skJnH^!gaVAz27`}|D9#VEr8F@H1@VnDKhQmB#A)RvJSWP zD;F#1XOoTSb@PzD?8C7l#O>ik4HYD=EH|Ua=bPynU5#^wB`%v-a{L*!aAUAUpi7Cm ztw)be(rf;!uYDb{oqhGlSF4>2(ojL7G&iHEW*Y7d*oI@HfW^M_74s>XkM4+op z#%+Dr_#!lI_}VS~l6uDirsX2y{KD ze_LPGB8ZM{XuPAGOKf01b@EuVE!PG7i%t^Ih5RqZ`gLj{Sb31-wiHj?%glg&jH-GlWkqS$BFdC?$= zKv&xXh59&AU%Sb2gdnySNoO%T{<3mA`f8{kaoO37UQ0@(yC)d+27ZIKvbuU%Ua@m` zi9pxH@Iu`r>TB2UG3skW%Vx52+bwylInhu-BDRhhtt09U4t_K04RR~*WHF0v_(a}b zBGA>od7(ZvdNGYEVbs?S?X;h%-5T;fZCYrkAQAJ?ME&*D&+H&8bF2fmA6ZR91qnNDqMxoWrGctZZ_qv^kA*1Rxc9x% z5`nH;k+<{} z2|)r~b*kUeSJ&T2Yt}RBYjdWbW_L>t=7)w{AgCa*tgneWh zcP-442z0f|x~ZSHN}=4xsIQ&7`yA`8d-BIv&NQR}}(cgn=~M_B*# zv3y-YQ;9%V%V!1pf!*6^#j8er?VI}-M5AVZZvUebZ0jR-$7T!RFJ?|Q|#ztKC&I2KAeoYqacB< zACVSx|Je0(v9~cV)uO>OmhoD2Hd-2@qJjiImE!&J<|8|M+nWa-JTDRGntRxSjvc*@ zzKk*E*M<#v#?);-{K)6B1QjIk-DNVZ5vK)R7I|{BV-6C5E|)Tv^xDQX^jK0!@yRfM z#8Vd0Zv@w-`w~=;z)uO2$vWmeoA%U=Uw)S?5$LiRY)K<5R?+`Fs);o=RCvs$4t3+M zLpKvtkibtnQ5jbE4I40`A1|{~mk4xiT4_m7?_5UT#x@jd%2nsG-;KY!@{Aa)>wP(7So1myh}TC4HYEt+ehp_c0OR; zY}@lY%gajyx{g<^L{CncOLMLgvBr!VSDF8|*4(UG4Gk3}@LNG~=vg+cTy1Wa&{9JM35*8BO~d|6Y=0{Y-tJ8Yi9pw?m`c=I z%%d-`Ga{M!Q;st4$TGb3eWIa)1V%ODj%C~_w)4|3rcLc35$KBBT8ReiolIMd8!p!9 zou#uy2_IN-3l|L)BrrM?U2e7*CHO{fC zjzcw6kiaO@WJ)eLz%Fgt$38Cdln8X4dR&R_{oqD_lrbjJY){?8+HFc>!!C`~P(cEt zWwFKa+Q)wXn$6;ad?f;1ndK|fG3z?fnO%$yP35YkvQPa3S%KAf4HYCX>KAo)Ub|Vf zzNlU6xQw+@mBbgivlnH~zw z)@NiJ`=|x3>CB03R6^PWYp5WByGgOfIiANpY>8Jh+E0=QbbTmMnchvCs5h-?WLdOt zoW<^0EmsRG2WqGwfxBW+cNc$H>>%%{H5yNl2y~4os6@?MJj^fuW0F{-Uj@p(H-D>c zDixrif&}jF#qH9kbIf;374qK8Un0;|esLvQGo!hEzy>21=h?WE?66Z!@@>pm4HYEt zltS!r=G|;W#9dL$e{BA^;iPBb zFo{5yoO!n5>|1v1xCi;lhD&*5NZ{$0$@JO!CtEpb6!~-7T_Vthd2*tj^WjU@v5yz2 zztmI8heJZn1iWSYnw{V7K{|%Y1iCPLPh`q&b!QLzdGIAUpIP?lox1Ou*|fRMHGRe4 zM4fM&O9#BWs9V?FrQaL5h$fpG6ILhfbY%BUBlw`^?-(jblwF>vUmd-an*5C^u2ZIa zuy<{|xqaRPi9lD-^j&&WF=4ev4P(OU&*Yx$h~+5WXyz@33KAtACh8C4*U)G6jVZ3? z-af3v;xYV8vr`g*uJ@mI=`Sv?rxo0c39C!f`>|hJ{rRs)oS}lm&kob|{pU8(il%vj z=$|{DE$Td;Csaz42z1p5+^s*d+CuwMW5Vk0{qF2l@I>xcc|Ah~iRnwH>(*k5>yv)Q z6xZr)!r0=Ifud?MK_bu<``>QerPdBwyrD5+H9Ovik?$dV>nuNp3KD~UOxIhBDXyP; z8B<)_&xvC%lS6s;cuGE=(^uW+Gx;$!;AZFhl&)oWl^OMn^C@M&l9y>!16;oXI zzc!}0whc{Wqux#t(+VOa0$pZT_UM=IrO~jMy@FWqJCM!J786#RR-mXLk-BMy-cU?& zy|?XiV6}>Z_m)9 z#S~ZTKE@PRx@ji!_#VdF)X9wJ3*FG*u%=%skXQ^!o66gv$lA$*h6IM_A8Iits%PH*bx)46&wi`hOiJNXS z^|LgMK6+?OagDc0ViN{Wz2ATeg? zO#Nq{9dxgl(InRRFoPvN8pGY|9FPcfnfr-bB{5;O*1rj>9TG#>jIN{jrX}YIDoE71 zG*kaudMhpRZ;C73o5-w(4&&PfzLp4dHQl#Y&wIa~299bkeyih$CbBu9L-@IlCJhxN zZkI{Y7mF#byRUW>ME&4+cC?^3zu-|`BGC2o_g=lYn6TR7--Oj0-Tm2}``vl&iE0`u zNc3||()TrAOHb}M&f)r>i(ve7XWn#K1BpP_gRYr+6ER`czM(N;^~PLp@#)i^KQn8o zp@KyBDM|V|F~zm|zbUTgPX)4`GaB={6+1};y7tFr>H%WH>VNs}VvVJp-C2dPb$Lf; zO+y8VXDLbg#ia}Bm7+%6t}XCmHzF(ZLlc}O0$pFTGWCgK!fL*yk0924=*I>PDbH>F z`e~>japp{to+zfcE*msP5Q~nDUI+u-qUEYe-l;@bnD3)M}B2D z<2^J~kof#2N#9*Mkq-Me#kJ=9Axvv~k6G0mDG}(hESaV6?Hx+p>l;yc{6LMZeSC_& zclXm!K|;<#dh*_d*@<4PBSkM(B+&JwvDgTC`qBh5BSNmSvKMQ*Xc?=xB2Ys`BBb1? zZaK&3ait0=C@-c*Ko0G8_YQiARcQ{-#57XO>JaBwSudz1`KvA%7^9(r#Gz9i^ryXA zpP(fnw)Q;=BNPM}_ zK_4I{vNiZOk?myWR{Er71%9K;V2MDNTUKuVLNW37)jKb-M%U|?XvGm#_-?JAh6)mg zR(H@-#YDEGe-qg%H`z%e?CbFhx1A&cT|=kj=8q8*Zzuknc>A=>Et99KJDYLKl&psRkn-2AR$;%(o56K}ok9@0aT9QgMNEi_b+ zU^P1Ee;2Q#+wFUbHFAIDQR}3he0xr9i9pxgXF2)f#l&07e-m#{ZGS<_lyl)HL#t}2 zAhGd+o$f0pvc2=N7i)y{W%S;CcWyDWghZgrYE@4DEHUvmrcB z1&NB&?DR-6k?mAm3$aEOhr={)xi4R8e@7zFwW4QE{%JAscE`Vox0gPCqTW{HxNXX5 zf(jBRTHEP0#6-6Br;R%=%Na-M)3!mpOtUnJK-bgH+4=rr;%(!96K{W4`9fpnh45}i zRuEK>@VwJrcN7!ZeuNlzUQHVwqo22g^EoAhBm!OiH)rQ}5EF0v{hN5Jb^1adyo%sW zintI|kf@T}UY{Z+vSqp(cV3fv9i^x2WB3;{3yDA%8<3s9M@+nZ-2c8H=56{+PppdJ zUwt2_s338-b9;TWn8?wv+b{(BM&1d0p@O5`iwC+WYcriix*BQ;8r340=l4 zf}(kymNgkFNc1XYt4|OU*=lz%CbIdh$)qc`NARJGM@a;_J}$}1w-6I=x34uO-txPJ zbV`FM{9e*Dh6)njPg|zZOG`ue`v2BR1iBhm&dR^hbt_#p&zN|- zeDfu0`6ZAynwG{;K_b+wonG)cg$~$lOk^v&ax>l2Cx9QN2PFbs0UI*&zkXj&ul<{N zd!*nbEq#6*@8x@%p@Kx?`EB*GVj^4abvs>jRVi3Y7fkZwe-;%=1iE^4$jt8|Cf<7e zn|M3r$YFZE%^1G!#Y2V)5-S?D)q5;jPFt5)Ce}Eoik`P(zM89;uZ9G=?#$ksU!>wJ zy1lG96>)pNqx8tg5&Y_yUknu_PEKv3m)bXz-ne5B&r4jUXH*Yfqhk?{1iCKQZms`p z8$>s zJ?`q)S1r}j))mxpSKQTWhip~3Lb~v5CCyb-PHx-XOR5DxqI%<>N`|O?ZS>Blech** z(l%A}Ax8%dkO*{PU4WR)QP-p;h-%rrzuYubka!t?O-za%qOSJrE7oYx{57d5PVQDt z@stR3VNImi*RHrumRSrYE}o*3C)8IWF=XQ|rGCvJYSWiP#2Ves944DryOQXAeiDH$ ztcesS6OYqKoTyhTmNh{`1&Pj25|tfsuIi^qBeSN%rWNFbYkxB5zey5-F06?Z``VJx zWY3vC#Qa%^h6)lEQEioi3a+ZvXX73xrkESKB&wHR)en;hbYV@T*g@u7lWwA3ZOOxM z4HYE30x}&so*k@aIT`th_51&)HV~CzUqxjY66nI3NO1yb8?DX})n`{l^%*Ki$Q5qS zhQC)%KJGyp6p5AybYV@T$oT#BUcV)X-{#R8Do9{en)t1jj-fL|J?9ot&xr)OaGxkn zCJOG*aQ{xCCs~xVgG2)B*u-@CttRH-*MJ<}AQR}q-K6;RInjbW*;A8r6tx+sAc1vk z;vBAY1Ga+~A^T@XNd&rZH!1GboIA4A(mzz^SCJYjNMIeC$<%sTP1c^DQA?i`uLtaS z(S^H7k=J*!1zWiJfSRgBYp5WBb!=h|))xy_^-Q8V|7MItpbK}CqRY*Y`pm)1Q>{HL zMneS&tYZ`TqLWLr5?)z~$MUHXfiB!lihMYyTC7st(#pdUVn+}AS0u2GO`OpC6lFiR ze$cy9nLrorCQYUt#j3D(>j_Qz6QiMm1XiVq->QR&m71Z`bB|;KUAUVRC&Dc(*y7{Q zsfmgzQ`o;Efpu)6+d`?|G%}+FyX77w5$M9*q{#i4P?60!;LN-OA~aNxz^XKH+jsvj zO$?pM65oYN1iElHX)?Wxsl-Z^UCENS2WzMxfoDMCd+={jmiFl&^Ef$PBG84qNilus za!nRF{yNLvU5_q;KZsKyPvK=q$^1xl)Bm!Ny zn-rO{k*!#RCQbOxl8S~35_m=`<_RZSF^8A!`GJBq5`iwBwpY`STu6 zj}TOlz&iwyFZ!rC+qz&9ci6E-BG84qNwI@G?!?j~g18p8h@gT5-i3&h)Zi9uTUHn! zRnbo((1p86lPTbx6YD;03a@syD?tSbywefq3QB;t?yFyW&d8$4OFB#3Z)p{-w=)&Ek$RoSg zi5=S$!3+0WGgOekJ5P~qc+rZLo-&2cBV!~2UAUVRJII@DnAh6LJf(30Lj?)EyA?S_ zJF2iTtAltwi}ezLF5FFu_xY11?B4E){Lk1lh6)mR2QBIcn^a)s6UKAPh=US=F5FFu zle=$qS^We4{NRsM3>75sE?w-ST9#(d502qmI~7U`7P(cE78^o!>VQW@HOpx3wCP*TI zF1K2V`m)gJG|a9j6>)pC6C1a6C~q+34?_hB%)StH^kY2OdMh`+s=FCS0$tV#JN1Uc zrqQBhi;Fc<2QFh@clPCr1B!F3cl}s%w_bMpSbE#B6~!7=lc}X$67y;?fFD0zl%s-# zyoQbWTvlezK>prMbeo1cT6AHJs`wNwh-Z&Cx^j2VKMWNl@NW`3$cuB>JsUUf^Wc+2 zpbKkM#W#)~&(3SZcxdmp3>73WQ$^Gpe4EQkRv6B&x!#uubYYFE_&XvJ+45dq{JHZ@ zh6)mxsUl{EjbFqfI*#N^kDQPQbYYFE$uzRoEH-e}Xl{0eF;tMiOcgPKxZMgCHpQ2h z8=NW;=)!z)@tU8S$2@ z{c)%oyC)Io!U`pk8|Av14d^+T=S6>(YL}3}Ocl|q z*g1uzymaOpikFn?qtJ!5S)w~k`{nGIrxVvLEu|VPBrsD&)X|gm?8l}~{9aaVi9i?D zn29HmEMnnpZMns%#!@XA5}2tXGO&|ZvhK?pahEggBm!MnD<^8Ot|YU=+v@N}+wG;A zI3zGrMNEX=w3rRbsl>A{I7$S%u;x$vR^Bt2DYYDT@a`?u_920pDxwzP^;|Z#P+U>$ z9w-s$!rDbK?WW5#mh$~SR;-x2RHKLlW~zuj^v9D}T>m@FX^W>spbKj-#ktS4NM;&# znN4{ zW#xPpv(1kJBm!Mn6D#&nlgG0TtK!+`!*aDO64>jFTT(y0904=;$zD8B6TeGmCw0-<{a694`^*!cGrj=XErLB?a{*euu|PJs^<4 z9)w~C+50GKb=sALjP#QTbYUL4=oE7GFzdg@l_X~RX{aF4EOnReEN-y+JvVN!if+2j zs#^{wRXj#X1iIw>_Igtb*!sgg$-B9uq`tLCZ0vhj-+ewpT|3{XsG`GPFt0w{$e4{@ z5`ix4vMauEb~K}TyNB~jrXu`z!k+wJN(gPX!j_J#SR==|_GG$gt}Vs;PjMf$aJ}ws z;mN%+&83@BBMi`GAGCU$rGN?Xxs3%&SRMZSGS7vAHF^OCex`tMdge7lEy z!;3^C=bAa42Ct-xdMp-q!nelOqHh&nUa86>=}s73c!MqGb9%4So3--i+CKTF8i|mU znmG>RH_#dPTZ=Vn$JU{jo{ZK`Ib2ORv%rMQD8EWYw7yV@X7qtT{&|AiP-R3IngiDsJ+Du2l0B; zY(w`(g>&0_a&`i`Ff+nra!T5#A4`ek_i}us37O}UR@T)AG|eF@n@k6Gj2o` zMA0L9o2WSMe>g;fc2Qz3h_XlE)K?ROpqTb-~QGLAa zRDSzUWhp}li4K}|&c?la=rCpypA7Mpx{HZ&Q9Qo>V2MB%WiDM!(H@Zaz(L5$UP_OwRJL&X}d-u(1n>?qPy7Cqx!g4LEJxcr5nHi#@|uQk^c8{9JlCwULw$i8EN7+{Ny1$y^$YZdhec;d4@zr<=Q#B?rx{) zt6GUQ>|-^W-)IES8DrA$XQ2x->%@0$Fx87Y59R%@m6S5*kT^ZGc8+ao3cWU25o`R3 zv!`uiUHHS!)g=O5m?0?M=jU_vz_UI1)sHq(CLj{#t7_-e%3e>qIUC;weIwe_Gy5I* z(2SN6fiBE+6z`AGdv%9IJ3cF@y_C_2#J4N8bM94LMJIf96>Hpi-;xeI)`XvL)kPxE zg&CV7>z=3SHNEQbQ8&9wnVCrJEoqa}{n=vLI@nvR5ggo@KAc;Hmrm?25$M9qQxk?$PNbKuilT)P2Tv~3Qk;OV=LS4G}k~uH9G+ZLkh54}J8z*DEZn^$D z+Y#n1Wy&H^)XOHPdFL7Q%_$@6-fCG*x~5S9`*p`(BG84Iz~b2rU9LZ0bC`{$a>g$b zWmendOga!i-{(#hYg`bOu+8{tR`iyfRg5moXcpD|O&06n&u1~dSs?kd& z{OFbmaT0+p%#;_IP7_w^Bb{o{$;ai4cqAU3vdK9+@RnY!^lY(4oMmm=ddrIgl`hBx zx-jEkbOidaNuTq=OR4)t&g@6xeX32)oX}PJ#Sg~cF=SXHy03m)b>Uo@Ko?dnh)z@A z)AS!UzG~IvIH^Jbi6>z;Ile>M>X#cBYgiUf*VmQGRefK{H4W&(ex0H#*WxtAUJ#Lj zKn02TGIj>sHx7l$|d(Rc{-VBc3C$5CUB=fZw)URoC_0c;A>T0rJo7BK({7*jecR=%rS`}&$U2a3XlG!! zkvPq6_UwPQAq$I8bRerjzGDX1hErW`m$%}N?ZoH#_Q*2GI*@Oy1dhEXZm|>F&u91I zWe$oCWL3zwl`t^W{y%IdSI2LceK-^4RuW_#{a1u-R~bLr{q;9!PeWG!MY}b{3U&vj z(ol3Dt3thxWu5l}yS_XXJJZ}Gl-pI1bxc%Nww>(JyZdWzD$tHcc5m(U7)|Zw_{5>; TKvp&Nu97X!+jCZG;FG@qoNlCD diff --git a/data/kuka_iiwa/meshes/link_7.stl b/data/kuka_iiwa/meshes/link_7.stl index 5909e7e01392c09859e0b2fcc01a6d3824ae7879..e4e301b53c33f6792d98ebcd8fcea1eeba36d461 100644 GIT binary patch literal 75684 zcmb5X2Urx#v;W_7IVg&CGE~kV@{Z} z#~e{HD`x%otVjKh-h1EYJxK{LKWIp|uI}9j_3!KM-=|x@ zuH6Pzu3p8*$GzO(p`G15%ai|K|D1d#O@XB@DwU0XSU|o1( z|CyhC2#GQfsC8slUDbEeY~`h}N63JZdAxgXEnib7P%?B{b#5^88rXb(#wB<<3)_~SRX#_2Zd&tIqv{aS~X_(c8(4LVfoZcYu`m_VydRw8t=oQk0c)p$zSLx^vuh0g1I6KKlYE-Y*fAt7- z*qCr4>v_9ZD2dnRNRQ&`s;;8{u_QuX%&4DOv(gqjfm$6Zq)6{wed&8KN{mFkJZ?VI zb~dn&#Ku9dq(|c_sbxhEB7r3la`rIuy_O}Py+2UP&!Ys*a4xf2QqZfJ2Q3$LRjDBC z5fc5iuJ?fkwe5Y55~s+lw7uj;twIY+BBaZXY&Fh5oML}!QGy<#JwkG~_>?ex;f#2F zB%+Pc&nwf`K`*4GqOH&#AuC?aN_-kt$4;OY(&EXY`iR$`E<$pC>TOa$xx?n-tNQ9SJniTiAbdo+wkobPQ4$ZZ1zI0o(71D(C@=de3?X8{E_?wY< zxuG64opoEQdxG?jrC`Fl6?Pkoss&T=U+h{s@$+xAO~~$^s#IXY6kF=ENQMMzz1$r{ zldF`oWwhxvuT*S>_u1w)`?$hc4WC-$%+PCDJ7vY(s+RK~BiYT{jp&RyO_h1VcPtm} z5mM!AceAaWyXk{yt4s-jboRrCmYDa(+M>5VYQ8q_340Hs1ltE&fsk9DR+=jWB_+N2 zqd&0MjN_`fr$a)eHp}caM+p+1^*pH3^Xh-2Q!$vA6knmRb2AP7?*_77V7O9 zz0AZn%7pQQm>JrS;ScAXQETL>Pf>!z^SOa)yK`j~lGsGlx5e0D+$Uv-_N*9@kw7hs z9|)Q1Ig}5YIztP2yqeBFU03bYVTD5Sj5DDY(u90l(wR55KGyEOPoVD3UTWh)_Y@Mc z&V*|_mPE+Gkgh!Iy_?z*^GAaXB+woqmY7C-3@yS7bvsB=3+-iFR!lYRa8{$5#_2Ub z*MPUYSd>%p#z3GJMjV8UC|Qe|7}8=@^C-)|7WLzo zgU(TuAYrtzHCMWJ!mlHL@KK?th4zMRU8+1eUQdl$yiU|(f6;VpiQJJFon<6Y3uhui zE^J$@HH{v~t9N&nQGx`n+Jx+Q-Ail!Eu0^yUy#lYQEaD|H&dhLhL}(bX+kQV+pg{` z6~WIIagk9AX?zL@$>DOxbmUqj-=8TPJxmqLxW&T80zVUKAx+5j&K>3BlZNvb-80Lm zg>>hO-n2)WYYVkU`Qbd28oR{B-H#^gxSu()c=6 zR8lq3gljF*gfyYgolN}dHYYhMp*BrEvq_06&P}+=AWg`%f7>vZ z4H@{wqgN?PkTBX9kZU;G-fDuDyTwxpwa^}}c7#~Z4`B;G&C$X$M^ls_(IhgEc0OKC ziJIC#)O^9rQLJbGoLaS*uLc6Oa1|va&}B5+H$F|h>~fH<{nnh`p4G`pa*j2j7Se=N zUpj_Ou_n?dY72VkY9Q@5r<_E5rkZfw#gYhFx_C5;{eDbJTbNZw2@+_JkezLZvV4=H z%+9XkbV|}m>GfDMB}zXN#=b`4 zbtjf2tGD>jo zge4K;*gGFB=@iMz>|3M9w_b(zHK%6|Ih&DK*1D1Ak0 zC_w^k6SD0?b2apzNVe6jt-(gjs3SHqtr?B_u+SNH7*{f$CY3mKC%HiJCX_QxQ6YlPf z1nKrr`}af__BdsUfj}*^M@UH9QhZyZI?Qr>CdG2mUjJOK>fvZ->eqgP=)s<2%kvp4 zCDy_*hl~Vj8FLxtd98UB{!KR5sv}<>DyiPD4@*&An@pHzG7^kV?r+s-yD@Bg`@N+dv5tVXY1+Q6YD2x;;YNeI0A&9h*hZ0dTaAGR`HMt?(Ub5ry~I>YaY@hQ2G}C_$oi{7NNzfoSQNXhTA-mTHg`<9RPh>~ReJfu3OB zh#h2ln)%e@l9pY6^oPwoTq$33ol>u%v2O^u*~}#=a^I4qKfOXvqLx=ziuO*D0;ulQ ztz7v`+a5~#K8imtxkyEmd5(5#})?_--C{f?583-&lxp#3} z^Oh-gnvffroBMD9+@yJBwsLK@EtX(8W$=j+mrOYRq zP~tZ`-nbg9so#ZeZnacCHGVKht;pP*Kn7ER8o3n;RC@S{BRC&X#Y&pPOnb z6LsI+dnEXm8K89kBGz!frSZnOy+`5)b;OiJ`QiRP9JMyzpRbfEQCAQv{vdWf%Bc;w z7%wjv(T8JMNUYAbOL;GgzDYETv5{1HoVKj#JNagwRvaaV3#KS(ZAEYTO^?U5M8vy} z4YXPp*UQ5`_u;5@r~E_Z&{$7OqB{OTcwA|rl?YiamnVHWmW9L}*Y8RQFH1>?NqDvA zTpq27({0KxjpD3PcJ+cwapB2=_~eu#YSiJ}qIEy{8rKiE;?8_v*g9Ey=g-e5Rn+8h z&m`hrEve6As**X05+S9Ma4jKZ?AqGA?w93qj<3!fB}m{ZA=cXZ+coor>!R2C^Y{Vv zRB~X3M3Ps;r)F)WE{F&fHe%w9L}|-TZT;AdbYH*z9JLbW1*q);(IdR4UOqVy-H}my#$fbV}?G~ukA$v>kKEvv9EDH(Dgoya+ zqd#31xk0PGbRfUvA8$$1J&9TzAKSi=l)aIt2U#3%BBB(iP=`ATep zHllQIj#@?5Ym$GOMR?UO-bgI#yGy=yxHQkXqY6g}5|i3qm0V_esbs(I)$yg9<-Tdz zcx-50j*?Z{S1Ia5InfG*lQ7#tNc+RNS;)W=Jk>QTM+p*`6(OWt$~ZY=QcKNu`9R)c zQBm5tcrKMF4-;sgGBopKN6`uw;*CV{V$0;s&RsQIj=mhVnub-Om!rfJ6}9yb;#Oof zwz}&cZC6rlj%6X?H%9D^CyOW8FGbY6UeBB?$IbCtgA)xoN<0^f^N&2U72@oZgxMBC zw!GdUSKK*69lx(X&;6<~U74Ydh`M6p2fk`bC$`aNqGj>Md`Ta#vvTEaW7HYNdUBK? z;dM8N@@1RrXAX zm+yV-z{j^NNIS&l6YJ}t_;!u6(-B3*nn;$#V>W@1V@LbT%EGyF*p+ z*W_`35VLMfmZxk!E|bTdIF^M3MrwqtTGw12nk|^6hh*WHDZuE=5Ji#b5iu&uU0?3h zbtH3KxzKmYjpo$_T3CNkighZoMz0sp?sJ&M)tTloMWUX?Raf# zsYjN{F@HpTM`kouPdd(%$-N;QeMbVLK|*rPucrB?R%7P%)eQt{VQfc;ca^nT?Up6j zNV%pV>ce;r<1RwBE`O_KZjzThPpM#x$RG+c##cPc3+-`4F6N(Bm1C@i(V3Bmui>P% zjB%4MuNlcPZo}xzNchhU;ROruOF64)b6Pht#8((oVH721xM%yc zStp&fr=@#w)Eb#AZd-g`s*vPW@kV0c!eng@FQC0J^)f_cNMPJWNb3()ZBazL*0X#& zju8^ZLB?pQ$Da< z@l_a^qLsV8SKBcpJRNdaI@4u~mf$gvW4Rce8Eq`;^MH=;y9|PDR(^t*Xc&&z77^4{DlCRg=v(D`&Yxgr> z(NKbs3`QS>xLzp5I=k#vd4Q7>R5LH_Pkqj8(^+7{IYyjDw6sn{{X8ybJsk zZGTULjldnjG=F!o9~ApGv?tDlJD-(9tydJc@jW?8kia;IkWL=wft36%b8q$lSq{R|<+P7C05s}r8H^y**bz|i4HB;rep}jb2VLWFfp7cK_tC_CI zmv0AflpukT8X;>YYH}0T%q-`y+8pCHwZcQG_IN!fGwY8$oX6uK@~&3<mIS4{dg-KZ~8aOT%~&<2F3s5qq3vk!)Ne2em+9 z6UB^hRM-iL&L%7DM(R*#Hq2} zEK`=JC{a)LiQNAN$CdKUmV6jr?aNzI|mS?szbtiUexm z3601v&Tqyarsw8v?=DIxL1L$ps6-X4@t+O&L8z)kfuK$*_`Ps)+wWXtZ?i-mkR@G5O0=4k8hL8r0$MARUZ_!p_T%iOB z??MNZiG{LA4?2^rY?Mbr8IfL_eTm!kihd6Lh?Dc z<@@VoWYYad5=xM`y=jT!C(aIjJhe|7dhoZa{aLkzgDgm(mS3L`CHdmE|A;~X#dwB^ z4O!u*1yv+a3(s2!X(XT0Vk-7x>nk}@lo*KbS8Y3=iPgtGmpth-QEPN<7^`Zg`i781R(2GOk%`mR`C2Up~qR^0KBR!p~n z1ZttTg8KE3ID-VQ77eIJFD8rA6H#v8tc~cE(fa9$ZsYeqMgq0aLvdT=%Wa=aU&@Lc zUKGcEzFW~uTle_!+@bB?7XEB2Bp#jeqti2qDD(gH3bn9KVy%7WoS0{C6T4T>MHF@| zT0~)@thFK!S2bDW;l$rK@(EFHl}&0`?T)YR6-to6`iV2)aTyX%&kgy@2GUN2Q>5qm zIi9^9rYorl-=e$O36vm__;#oCMnAi?6H7})`6l`~>TeHlTmf>3Q=nn`DUi@|ydI>E z{U|c2cH+XrDBrE?JL3x3Y#6X`?uS(f%U=8OuRiJHOeX#dI zm)X_nmVLMW>yPp?M);J@@B9~mTG*R}%&cMdxe?aIPGF0EYM7m_DyC;ri3i#yB!7!W zK8YJz{$&G+B$1QNrsrhs^;i-W;`3&CeINaa!m?27++ugy&Aw02Yrd#^4_0^o|1w(hm<`2>;i{6*-LeJ+8OOq8qqEVoLvno87hapwJh5~%e*+t9tj z^;NWj@^ieRhq^yM{}J;Qc!h*$5#@JV{nXcOAc0y~C-I!Oh)Rg-6K-!^Y(;EcQ77ql z&HHEeHYGJ(l&H5AN|3--|KU^Yl6l4cBv4DVmF0JTB(%9Pd~f&{fm%3A{BB#lb#Kjvwngl%0=5o0wqW+ittvqCY<~K z@CvoCPDUH(l{B}g`oc||$_cMd_Aa9aPZFncf7Kib)Itx9HgI3lcT6UAdDc?)aM zff6LLK6X}b=vlS@(<{`%IuX*rHhIh{fPk!w- z0vb%HncATHUj%AB=>Nt%)}HayN8-&jRZLAYtnk%s;O;kO_C)Eve%dR_McafV_8aHj zWI)@$Y#?#+c(4?eNt`0vy-Mp^&pWMIXoCI>Vp*t#brRICf5dzR`&XszRmDj^2NvZv zKJZ#OAd8%}-NsKqw}Av|Vc-1FFSvCzETh^^V*p}0N3yFB(Eb)WrJaCbnKnW7! zzQ@|F3HCSBMCuMkT$gZ_ z5N~rF7#COeMd)8E4iaL8v;AHN_gUN$5BXQMk1H$-wXlBwdp(d4Yn1YH-TmJQ)WUWX zH?Y55N~jeQ_Sae~`a}BJYoe{BpZzZ~cl&lH?A+MrZvwP%-4$;Zm(H0OG^+Jqgjffq zpR1+lbLr?ZK|<{A>F*ps zo5)$d((~i?8}Ue>7S>NZAC33=@_Igh)dLB!o1i~)4uss#w#WBH$=QDqsDe(i}52NGjf+tJpGXUHLj2l5gGj%UyCoZq!&#rSh2}p1Zv?p zHnuK~3=!SapF0-x)<~cP39(P0|MPAF3DgpCJN>yA`E5fVB}kwawgMpq622z6IghZv zf8O!tGNn|G2q}@f(a#}cm06irOKp?g=!R+Qm4e9&q+yyH73a?D@>@eUXEc8j@1LUt ziI_z(N}W#Yq#<_VQb@EZy527R4F!f;Xm3&PNadkRwB#sk6VkuKPU}oo#QIziQGF+v z=Rdh64Hsqk2l|^^olB7N+1zNc^%X70yPTEQ+KGl+2PXws%Uks?>7W+Uejg57H@M!C zj;Okg4ZAOztGf;|J^q70Etf}bwgOiVNaaN<5Hhj8ljTItN7nsCw_C$we=B#v&)D1QGPc&Rccgu_ST-YF}ES^>hZa-nv*WYB?`D zDkc3>#`0s7Tnfu!I`piG^|K(z%3D_F45~6zSbw*uvUwrBtAtwJ=(H&l%)>_|DwFJ9 zsVC=JYdrL}z7hmVkO*5^!O}keDdmR^$JJHMWz>vTeI%k5+B?;=qU}S{S!JKS&!4x7 zO)65y>?7t9)-URwQmtE}HGOSSTK(`Ih1`3d^k98aO2TZ)vaK$b8T#Mk&e)7rkLly> zZH1EOBX20%OL}2pQs6P%x9!z+`n=1cdq+yoT%whu!p6~WD<$!-qCZ`3o7PLWzRtA&ExwUb zB0eG3?V-NbGSotPq8Nqq#j`%b-h&Hv%khgQm$KVH0<}tAnT6kLI$fje3y4TvR9ws*3_&;ua}Hf((7EYs}FOAZb3n<}jc5#4mzC$%xE>)bDO4B|PYg1xpfpgSdpmw&CaO zkv>Z5#+Riz%6wOfHN0Z!8d`z2S^7@uRZq7ut-fnwY7VnK>O)VEHWL31o$Hex7iG5* zvN;z`j&`9{gukdYGS62@D_l-3U0=5mmZygAoaw~Aa-t`wg|v8oaAXOecf)(wZ7dl6 zMA|M_p;JZspgp7sX_vWY!U4;azX;T-nro*tKTX_Ev$yVy=jVKO6uPQ^n~I|ZiE&qV zN+DcUE8B^y$r}=UM~D4Ipw`8-I#T7J#_Caf>z<81;=OozIlEUVsXmrU0e2eH4WdqH zTijbpEEAu)X}Oo~Ra|Nz<<;!~^|H{q9?;F)v0X5|BmPEOe0%5orkd{Uzlrn9C_X&b zaq~=bu=-YLA#Eh2GCTIJeYDhGkCvU>l*&^B=%YVuAT8oVk6k`Wj?#bC1ML}Yy!m%Z zTy(wpf7!rtFZEik?7Qi&J{Pvdo8I@M_d4vpy;FZa&@0s1)pWIzwX{F|L6l60Ps};- zy4|aS!|p4}SWh)$qbrsXK39}C*}bT{=ryFp8B4c;@jc(q->us~2@*ydUptw-OT~7w zKOb$a`PEiy@~gu{xew=fs;39tSD5%4X+qxj*zKEgY=eEYqt@XUdDORO3(=kIPh!!) z1-}2DFKQ>S9%#>KWB7^XiSx&t(7(jS>jYO*$FRH7M$w9B18s}bzSo6JwqDKb^_ZTo zp_(CfpwyLKu^??E2CnUvc)R6i`<}C3hC1r$uo$JVs4db);_#*0i5|l;+jlIeg>>UP z0qUtOd6aARKDUnAk`$=!Nzfx?lms~jtLyKTvD_D0SdzGTR@=||C&Id56j zx{p1Yh`N6_sd>(E($+*bD*n4o{C8!reQtmCafbP_L$1VhL7>(;%}sHb6(m&`)V?` zx7B%ti0vv8sFf#29;LykmeS1zdOecPpOWvD>czv#&r(o=1o7!$#d5dOel}=jN?eG~*}p_M|95!uWhN z(W-Ix0X}@S`xF%k)EXpOws?*_(k*-I7U|rIYiqJ_-)-9|N|33w*F<+G1o4_YUZ*UB?jEimwuf)XT>4n|4aGGDS@wR`n0U<_aNq6AIf zc%7mI3FGr|^X5Q4Wyxx}^TRzV5~wvJqMei>Z#E_Di9U8$ZVTe`*XL$iF1@8FK?0vg zF?JJc@+n`dvmCv*t4N@h7@?9FyULHTyZ`(t?M|s)Y)VD@*!?9zLX0&N{(E94eM2eTT9_Obhmz}arhZYL$Ibq8fZ0lm*}1?Oh7S2Sbo6T&D;kTA}P z_19Kou9JOO=WA0`Bv4C?H${wH<;U1d?0^CGun7bt02)=STVe5rrmSf%W;g%WG3-}#xd zfUyDF%5(N1MM46#F!Lhrs=eN=W%cdP=WU**Vuq#ehLK9+mrJF70lpON5i2_qDOFV~Q*RX88oYyI=4RoZ3Ci7Rqoha8e5o;uQz>yMPwqHb?$dp* ziV`HyLqaa!8p9_CbyB~sU1}%`wa{DfPF&9ctnTF<^5ZGhBy1CGEA*BSzr+1mvDSO! z*YECHP=dta3@emNu2Iqx(KjOF)$t&8T0VwtYEfE60=2MCVjavliVbX4QJxZdPR(gP zYke1;B;6HdVLs`__q?{aIaj1CqTLAD{CFta;5k{l>AIex1PRPc5wd;uE&0)wZv4{9 z$tn^Ctt=xGN7uU}J+;?^rWTdj9*pE#Km|%bg2bu39ZPMme@9BQ6Km$X(rlX|`Fh_R z6eUPthE1%TMYtMyV+{ALSW7|zwUR5&HjnCm`#-NPeWLvBYF(NK`A0ziJHiWYy#SFR0)ROb0Cm(;zKA6iS ziOeHk2TtKO09ftoX0yuAiIp$|G{{x&9j|<}AMit(68mT=Ju~hP>$g zVb1(`foA-ITUiw|rbwVY@rLxK`g~T98*?~4iDLfq$^Erbhbj}Ly}`Z)+ajkQ9?8cp zysNY<(^o~WkU)E4hD#pJ`Zmv~m3a2R{`CK>VY+#wRPWnFdp)p4#9O~JN3(=kcWLUh zjT9wFVCI&P;Cc>hLufnJBx96{5+r)Gnl07nH~hcWojJ3B9Pn=hyW-KskZDFOY!UG_ z#D=f5YCS^P)||~$lpukvAkNjaNFLO!i7ijOH^nUQo9?%zsF#z>`Wl6~UNOU+%D~Gx zwB^e?bXHM<#GFINB+D~T%Lvgo;(Y_hEn1}8K;9}(K0{fkWy~RGnC-#By7}|c&u&>z zf&^xxMV50!RrV#s%oA#iQ&570<8AR>nT7StKW4b#=VO?2_jvVn$8`n*we% zMF|pp4&RhWyPej@_8HEjn7HBOzM1B^c-DdhYGMBqlG!za-%ZV{1$rD+F?Sz7E4Sr- z$1BRL7QVD`lgs9bQ9H^9Zpr{3^Fq#wxajSC1$b`x@nB8Njlh-KyQ2v4|ppTE^3id;L4J zG}{yT`of(mN{|riqgAZ6|J8$)%ET7-ZOyLa{z#EPEyGC)8R^1llUrhqdR{<52@($T zx~~;6!+)(C?pjQ#@FJ3p8n)3u7__pC^c8W*e_p+FPSw3pp80D81ju=8F z4{E@@or|+#;Y$oBN~ndSN34T^GSBZ@k&P%{#f&F0S-%`mI-IO!%Os+(tM~RQB(R_L z$0#Ygygr}g;m$hjI4vQ8T848Y(&yb69^NaS9{JQkK?xGAO?#E$(%8~JY&8EI$#bU^ zRfv{mLjtu9nT1zb7W)1eiKiV0^Y*7!X*)8Gmyj@M8BVZ99_h?)$EIm3|1GWJ2^JE0 zcXFjw2QN#6eZD&Jt)lv*S0q1}sWn9cweb8)>{xQum#ROC!`QCQ zljYfCDyk?!qI;)XN?hygwn+OkSpDHG`StE@Y+pjS;ZzT`a4ZnwzkiqI0fsq%gC)93@y&`Tb4B}v4w@!inY`J0-|p3=b#A<3y@qm& z)wK)+YGKAg+*Pwy;3s@5u;SIW%9u}ZA92#sZuNL&V3@BVV?l`8^@Fx|XLjb2R>fcg z3G`5Wxy4pT?l;+mgTo#ufvrAq8`SqL6!|wXhjpQzDK%K!wweY4wYJwUv8IgESf#Z|&l;pnEu)36tY|;$I{TT80eEv4Dx{Z4Z%!Eb7HD_kskrn}|!Ai@aKchw}4N z9Sj6&VLuV_s{b{)8@nNUb!)^h&v1Qeu+n--btOu)F1EVJA;%Gxn(D#YG|pq_4}MueD|ZiH~ap0D9uy2hM}#H zz&eQ?WX;U1{KhOiBv*NcS!cfyxs(AP`baS%ZbNSg8PYHV%iYI`C)}uPs5uhY3L^HY zR#K~*`>S^4YzQ-CYddYXTyH-?+ScCw3|f9?oj=d%t*)tR=AH$r>QB@!NfZ#`DJUsw zFa3C;wrm)u#>9H@v9b2&pG4e}_C(6D<68CpwqN#YI_efHC9cotX>p zz-Dy~Hc$)uNqiS)_8rZ7`hm77bA5g6{>pj#UF|0I+3zY{YvgOls*4+qx%2SWC1pNs zYrKs8fdsZ2A-2nf`IKU1R7=q&4Cip1+cD!!$T{&Xz%MPwX(4qd$tXbr?Gch8ya2EF ze4^HNejSDcYGM6EzI|MICbgCMi%FV_cS@RFpQm)}K3wq=al-YivC5iz)0ENnHL69{ zF)Zu1+fswe=@bdnGTunB_3y|gUVAH7Ideos2@+e^E>f0Nj8!_>b7ZM`Gi$p8BG~2< zR}HsYP|J8vW_jWU?ZB;pEdRoMHk2SCav6%A$@{U#N%=UMH_Mz(UtG+uqGaIqk;>VE zla!gF=2(*WGR1;Xyv&T!TBp`Fg9Hh@)g#^??DbIVaHGTD7l?{pzH{q)Nu{P+cXRIOprvjR+%PR)OfR|*s`GYhq_XT@_~|DgIMVhn#UDo{lU64;xBn39~#3wpk@ z-|<2T5;(6A(lqgfsnWl*>^IM(=sQYkl~5^rYhNmeUm0`Eq>HbleLHTtpS!dD_9w1h zIPV&>=cRAtHMeQE-uzNOKZn&4PXUa?j$N-!&VAJ+{eB{9C7(#JbvU0cJ#XSm0|!r3 zT3@{=#oEVi>(vv?)!WTV((f}Mfm(PLBHo)?mcbI4w#9l{5Lk1pEz;t4^x=or@>z2fsXI zeIkfq9o|VBM>$DL{d_5A1hFKss%_6`Ieam}bVCrBF+~DPBBYsHBWsRH^R0RhZa=e0 zT6NAURd3}>F{g_qiHK~8`0BprUddZz4lui%{Go$%YR^OI)(9VJthxEqJoCiwg_GV2 z8%UrQwt~0^aC3mtW7!(XF)fl|xk#h8gmn9K$b8AWuPySAdLV&y5@+;YHB41Y4mayJ ze&2rjq)gsi+T2;J8Mq(B{inzjc~mmhxtZC1e-{bV!dNe0{tOwc?U+}F~&wRB(V3N4YX&_JwZHq4(?X8rwe19eT4I#9SH8<|h z>wjwEo8jzh{r(k0$%Szbl?@e|D!KI72X zza5QUAz`$^o5|MO`^(vDj%8v0qiyk~_lND)Is-h-`W<>akHY7pi{X^)Qr)c926VUi znIKRLX`Cy?J+cKSlhV)4v9-}{geUl3x&Bf5(ow_)aJq;mbmDBH&=kpa-W5x?cgANB zJu%oOAIdIHtSy(e>V1x$;Q5!)E1%dJw)C7cZKZVrJV6g}We|JLfp-!UFa5Z6j|6Jr z8LRk;cGrp0Vuwj)kN3u!V{LJc5pVGH94EDQ&nM;lqvl9pD~R=@>6WB2-dpW=&#{JB zbM#Q;WGdvc4M?hFy(DUm5+scEh;QG=l$v*k{nkCs$T*)H=S2N|gSGum>-R-jseeC8 z;{Ua0GcogzCjw%Rlf2Lr-Opkl?MR?jpCjo~r=?cgL9tScyK4VBSevz}X4xm|fu3M2 zf+sX$cb9(3^u9{0y{%A!1fHG{(rS^HdF6E{%auQDU_H=V@ml1z+ukf!U;A2%{$f4w z^hA6CGv8}d`?wYMxCABW33@1^CGXtou||bx}2lp_>zA6lc85= z&uC-r&P`@_|5s-H4FzmnEEijWkoddVmBFSPO5B4;R`2^2X~)~i%8R$&6zv&pJbf^b z`a2#_97jd6kWS)cpPp56h*3m0Gn-X8_9a`H|C{sWCyJRA!`n3-?Xu*k@_|om*u1V8w zezosd&;}A%5+Tj!6!4i5NA-96^f>XC4Lpg%`VmsQ%?96!nTlF5q z90{)aXj|N^l`C5+cz3gO{KG3G(4P1O`;v2g25l*-zX8fn3-b)dxMbq=h9;-=o$Wn{ z1bT?Hcsnznqb)r;%5+oMz~>qF9L60>-%I1owcmX*UlRoG2Qk-&>!X+x`!`e;uiULt z2jlJz31gHotcj1ccuEC(>*6jI_nF4XlCLgd&DXn-{p~X(Pz$re;`ta~O3EH_!5sS~ zl3~=RpGAoMrMMYn+(#3VtxHAuLjRjmjz$rNC>#l+jq@(;69P>B_M7C`Q`iTXXA-wq zS3dP^8^r%!Z9s=3A3e_DbO_{NnfK-3vC#Q-3ux! zuNzFG^ST;spcbB0tg^y6BqKDQ%*&pguN z_UEd;)>@zZ6ZQ22%R((2)8cnC2ClFb$rfR)DF~E^QSvL-gR31O4xt{2Wu||y&sQkH zbqUui5i^u5Wf~ltLAm$UIJaY+u-(LMk%5WkWnaJf>OF`N06v50t;qXaZpHdHpSv)hz7*>;Z{2Fz7LD>Ri6s7{7;gVHf6UeFPRsu z^Jaz;{^GK7)7Og{XP5^NQ>WTn6_EFlR|lVi2}?o&jXuZ z!Eef%vR)KtXRMRRp4VHT?Ov9dXMfm;p#%xECw@^Up^E&%(v07`nU$sWEiYv+{Z{EC z+6N;Ja@@~yxEWFVNqWs4#CylH?p5XCs)-pSup)~yoKj_+9Mm7@IA6Z`(XnT}_|UUn z`U%!=2@v@%`<4w z?`At%*T<7(x${->i%qpWE9ph?c@(`z#lNL~^q}V{FE;ynJ=$CRFG`TmcPyD=`VVDZhUjn!H8d9r#d-J78V39J(#RnMQ5>phN^uR3&MExj*F z{c6pX#)z2#ca7+w$aq}}VuLsDle^ctE+c_j*dpS$IYyUYw^uo{z2&m7l9M({0_ zzj)f2b!7*YPR%z;?ZlfpnD;|k{IWy)EPP{DH`cmDJ_CVT=&i`AWi;{ItB1?cybN16 z?W+>;_=v@~tIIIT#Y8L8fnR>#EG0uyD@Fqthryb+dc)g z)jhpwofV-rkGnUe^rfCOb!Upry7W>-PJy?NrR_$cpZnF0QPZ||E+ZMI-yMe%x z2@4L(u_W<}Y{z@DXA#Tg8^`kP_FFSPW&jz&Zq*a+T(@+nr zIkvj^KD9Q6rN>uNr?@7lSaZ}udm?l9?+{iz&aCZd)KfzV5;(>P>3p>xdvQ2Y?y`2g zp{>v!wuqS9y~eN?lQz@42ezmvK>}@yo8&v!$r-y1VlEk$S|5M8C=D5$izY68A-U9k zDtTYbMmcQ;`g-h1(I1=UDsqAG9ay=?8?^zoK1jV@W)#2ty-yk&@=Rh* z8EE5coBt$sm1Q-0xv{k_{~CzHo*8KDKhLE)3%46+k*$5*j=da_D7*N^X)b-U(JvXF zNns1lNQc97(WI7_q@AXd64Hc}tu&C;*|SA%o4(3|#GMB@>E?o0rSL`13^XAXUI(*D zhc)@zq-%0SnD9G6{O(}!bZOO-FH)Tg=~CsDnJLoZ#3VXD+p@Jfi~f4aKqL-(EKM$# ziI%&Oks?jV$g?SOK(}_RXWA+mTNGOwX%Q{W>c}?Mc`bLaKBMRrdV=*M>7COGN^;jP+=Kow3XDZfxDn&W3S? zgwd;ADSj+(u7a$_s~7`;TE=meVjafijpJoX$Es`Q=Tyn7tCF+)MrzVKtJ=8R3#pS& ziZrj8_88{Ht~Es+h3QTeC@z8w?3euR@=wll-PgXNnPW%{6Sdm$7qgy2eYWm z8)!_XPs+;-nJKCGKnlDm?tw4LN+)ZC`lnn~w7xlM_)`6Q?i;eEXlbi@v9(Wgs7RpJ zl|!$TCzdSq<+Q_sc>dapkFT7CRac+Oo8+*2qZ>_jn}vF3CWhAHGwL zPX8u-87%CR9TT(jIwSm9>veH5O3*7TNz9_Fvh)3y>az3hu?8DRpts_Lcj^vpe=*A1 z%*@ZxU#thVo0u7%H0Q6Hzm)HuTO_0J=n3|d$OS!W&3Et3%$#B}8+s54qgRt31@TX- zbFp>{oMbEuwXkQ!FS0fD=KcIVS@{+@41JCS)=%V5wd$PZEW>U$S!p0p%UE+s8^F8X z8=|$FGhDmwt#^oWy9)z9NkGbe^QXE_7Z-t(FCfOeAuBk9+Vhr3%q5-!2;nz1*K#MjL(db?2V0x3zlNE=nEq3hR!WZQ%#s zOB3UK)RL>5Y`aU}_@f6sw)WuVgU8DSb8eHdw&)?&j}WJX0lehYURs0HC>ec60&R=$ zy*3!cJ%dKeV`nzkuywITjs3A=_87h(Lp;5=wwIwlPz&osNX^~@xT*V4t$}ldh7u%< zW4DX&YRU9*a`86}4K+s(u}*{xyFZ4f_KT-aS6q=$f&|(oj<91BSed2j%u4X+0=e#o+{_W^D(AUPIcLZYl{2zHxia4Zp3dcz~@-p`QuU< zS>kvHwPatS`W5{sO>Xi;QBpFh_iJUM_a8W_?z5jMF+23C)4pmK-CJl_bF8hgt-9Z-%@f*`=BIYoH?$RMVVwwB-sFq6W?Ks$ zaBh@_5+sa$p6_03ULoK+bYD?oUN2UXouEL)7DKR^jtv)^^6$17q(@jQ4^jhXVSMz&no4lpHE#= zq*MCXy|kbh%kr@xZ~EPdBe8S+Q>jzIjH>(QZ3dc<6XEY|5Yv^@phZw(0 z$M2Vrz>>txnhqgyr%xmJt__ZA|1(deo?`so6k|8bjcd|4F@76}xgAR)T4+Gigjj@_`|BNL0 z<)9bD_#GejUb>l@nXcIKUWwg*{g0YI4M-Dv&t^REXsnE$pgp6F>m$UkL4W?NeH%1a zMo*AH+v1|fs;~0r2d((6S}ioJIo8(LR$80VY{Tu^oP{+ov=wS$oy5GG+=8XP`m8ms z8=;{D31gp|K75uNU2e^@Z*5|zIeLh7BINDd(k%UPZGOrr6GaIUXq%Aqf-TsgOoV@2 zI7CJQwTx|5t?mduwN{umA=g$VcJv$NwrWz+x)-CE1B!5SR99szYwML;yq!Gt{P}T2@(fKj!>=#Jy6!a z)W77}F;jw8Aaj4duJ}gj;HLu0i3T5(=_g$&o>Lf!XL-(QJKV!~=YE$dN{~R?Vm)_q z(^dsX@TE^DsmVoaSnn@(Q1|cn!v@$Uqt`kZ1y_n%2Aa%?3y{10Gm_`)+0Up2G@gZscgZ#$k*iPY&GQd-RnbO> z!*q#UzNSRnbEQVYfBG}|#-~ueyi$xof&`wV5E3L+WUWR}zI@*dwQswl(&)PDluHL) zDQY1tzFA}QXS0Gzb4&BX1}&tGXDk~NTe6x#*?D@M`BLlEPo=15ZIvw!u7+DkNQ=A9 zpKo}myEgE!1?+dFsD-rH53V1@94=Sa zcGEC}7See3A~HoWk!;?;e`t?fx23?t-z8_y1k2nF#VDSVAT37Xyhv8Hu_uiSDMnF( zgwX~)F_fLjK2v@-EQfln*E8v9WQer8mC**;7T;nG>dqFgydb+=%qnBKNE=UO%2-;n zM&Glr+SYbbqsK?2`NK9!gR>Q*sD-r1>EEx+UikX5n$h_TXGKWIzh5JH?m8}wTQ8mh zvZbNSGFmFK*yDL5EElzmCqEb3II;IZZP?d=Q4}Re7*9+JR&-=)wRUVq-7*vD2dG<8Ikdg2WZy?+V$s!LlOGP1Jm4p20lAf0gX-lAs`gTE^3*`fDQj zp4(NZ!-)(OB}ibzAx;4@MuW z!lLvX``8}4yE}-z_h7epunQ5}W4Bm$UcUR?`^@=|A8S3cCiXkA*0W~#_2|-Mqk9__ zC5VvsC3n1rgt$LzYuYUMC7*o5^j;_Dsh{G~)hY$v`lFOYwOOBZ)i=&vPxSsv9nnhM z$D&wnUKjeg&88v_Jt9ymbef;OYvLC5qbNyH2DtRfx_zij)>vT!%SH5xfkC>Z|9BC7 zH6!{ugdTP(995K|@N@h!?c10T(nv@w7yqR-f8kEdT2F%}X?g2B$v;Ji!9$m2-ih`t zVn-tawU*Wzp}p@HK-P6I+puZsm~pxB(IO5#B2X*aa;i3TQ3!cbWW%*YiplnN@vt<} z4n#C`O}bl4~gLN%c=Nb?xL3mLw3ZE6!8B9K%Rm(Tj&f&xRLxlPUw#)lXX& zs!ns<$sa|1MXaL2&h6h_#Ct`_yJB0_?Wg=m$Cl|TmZT_;Lq2D&Z86i-;$Jot(VGhg z1{KvE?THNO(Fa2PimfcVxqjj@cVe-2f%;0caFl527R#wcWAM7Y59!-&i)z{2+*emR zPR(q2@@|MZR|X{#Vp0gHG+9~nT3FC3wk>1(c4rDoGY1E&-eWm=qT=1u-yn5eZDw|tdc<4zJ! z%@*94bk%EOee&DaG;K$W88Pu|(~xQnI~OtNP=bgxv%JZb{TsDnq9pOYnsf22K~W#V z%=~slpjO6^`ef{dRoazqX2i&9cIuY&{rVC`a0ek8iqXCkZUJQdw!C%!@%1(BW5ee6 zE>AAZY9qx`F@h;0@*9M+E#2;h*0!q2Q1WktlHd_iSj+5Bob5a#wBIuKtn;EBHBGD3 z`)fV*0|V04bTQuI3)jtk^>F+$wZzyE{b*5NmFO95dN4jHYskM4sHKY65pEm{C_;;! zKJA#br+;q7x_=?WZ%{2*=c&IGHqf59D{S8*(~;`k!n%qvM=g(p5o)#e0eZE5|3;LV zJ0{bEBX!AS?rW`uS)aK%l|^4R@kL2S|fiy{bCcdjcN6c)*toh zLs2Hu2+^D7dBfbJpC*Oq`^PNP+Ka#QYgO0Nd{T@4FJ7p~c$_)uhNCG{*g&m;fxh}< zvPD}K|8In)r-x}puNh&-1p>=LgntKjeelY8|7&CZYAwwA+taMZqIVIod`^JAH)DkM zSlGbYDvDc#3t!<8l{w&4b1uFsT@g3H(|`H#&Hpc1{6LX^U!2eP|6y$DFif9(K9OUr z06p|FV!{I#b=cAaWap2RA{+lL3lZq87x^D$BGnT~8RXH+6o&q2^naUeOkX(Rf4%4K z-|~#p3z>exy)Q#8^jXV@k-ydB{eOgH9)A^R{zd&?S%^4k?h#v$^iM^R-ZShM{pMI|_euK5Lmg-v%|1f4x>B{h2`({#`tTq=c^nGtD6Zt$C z;-YY$vw{4|iee1U%Q4$dXkmZs)3&%fOXppYy}aT!Dc!y+4{ZI7Vz~?Rs;gSuH*Nbw zXM*QMu^RMlK|_|mH5{LGW+*{~e7f74(Uw{CvgTFuHtL`9_Np#FPiU5b&IHd+@>%U; zd{_3sau^vG_lx2g=T*lN#I54=tWs^AiF{&dT-KGH{qD+Ygnp)Yf^f56u4W9nrYbd@ z3GU&Ackuf{>bugCm2TRCp#%}q?p%qVIG8KJW%QWfW0DsKcSwna!i$sEGJQbNt0bMT z_25;@yf&UpzpUdJppQiM$@KpFoblXct#N8`7lvAh#*r0VoSu7)>ph0@-rJt)=*z&- z#IHwDPRz+9#pXtFn==j!zaK>4$O?|v$3j~ARaahRQ3k*V3K2?bXt%{X`3fTIea15k^chU)A_`k~7nSq6880m$>-+ zc-}tv9T|Sp%NY1HL~k8CS+#h$TE#u}gC6zus2;1-eY;nSHR}4SF8rm#Cu4G0Rf<}O zmUrPD4(1yjVtVtHPsf z1SN>@SKM{C4)fLXN6j``?ikAYen_W{hv59Bj=hu`Fs3nj2 zDkp!wp?e_P{iYQ~8>offg7`|Nr|`&>TlxSe3)6viIhuEkie!|j3~A$&D# zC^m(CiJnTz2Xh@IhzQy+Mmw-9kR<-+yK;_TPo{XW%M-T~M4*;@5{_e~*@nN{vuBeo z7VUNadqzeCj=#7`XJivCbZiQ<4$dQ37HZ+QAZ~&#zQc$NNno26Y|`<>yToacTJR*4 zd}+N}?XfFaJ$f{lj4f(Mh1TDVKSR4QzdoZ0A|x$16^s0jn324(;M>|wE~Ddl84+#g zB&ckM53wnleKJla@q;(kku2-76cMN;pSGW-x92}~D_*|QCJiNssIq;c>KErpwiMa8 zus6@>@7jY8$Y@Uyfm-Mr5Lqc_Y8#ItlenW@bqytm$bGRyT^Q?5O71g%SMM_;SY8=- zK6Y>giU`y~pMzlUg!W)lhrBaxM;bax5OH?tW_4|WKY4xJY~#BY&T@x&vjD3wDzmj*WisnZ-R)D zEf~j27LPGvS7hplK&{{Q)FU(3r>f72#$(bC57xG11mBSfK`SC=B!8z+9Nsq+{W5vY|A z>`6M6n56bBYR9*}iTu>AKaBlO8wg4epX6EK@{M(l!wD>=3DI!qo?g1~7|9zdBUNrBnAGb~~ zYd?YQ((4&0K}6*`fyC2)quMdY+`B*DKc}yEc4GsEg;JCt0>2n>k5^78OD-S4A}j`L zD8VlVOHz~;jtT74h^@5anX5W_ibh=xC4ZJ#q~&y9T{KsTxkdZWd=0qy1NFex;gZ*5eV{fNXO+cuN!gku{$6N!}$PPzya_VlR58IiE^g*wXulvrvMF z*g$u3C3dD(s^}{@9NLB7|NM()mAXI>fm-M<6TiXY$-E%V+1T1HRz(RS2Bdh9sWnz; z^NMEb9TU5A2mdEVLV`*Wfm-Nc6LGbSZ${^iUHGc1r45uIA|S|*tcc&DEh(CPhS~R` z?qx@DPo*_Q1Zv5iyNc9>mA>DYkDcpkpac;(nj%LraRMvsx+Lq~V@45yS~#*IYFQ$g zjY@N-d!7;%`{%`ecM|htndV*9nqZrRZ>dxgyZt!8c%1rELqvFz7wNHVtQJzwh9FvG z9PVk(y4P~yGaZT()Iv0lzwizgq_VK8uhs9N_e|(R#LR~)y#vVP><^|pd#%N;FE%Tc zb?as#J@PMvp#%}{CkBxGgg2%VB4baS?$)QW@_jp!-977=Pz!S7ODeS(}!_eV9 z9}%n-+N)wA@=Yd0hHi2zFKX59a|#>ybf3Q1*s3A|wS;$v{J&pxWPU2!u<(m!MXs2B zwhAC!2ENNWeZ!hyc8#3*^5<8PQLLngM!oN&Vp(Vd{l0=7Z8x5MyyZrBpRZ`31QD_g z%j4qR+Nh1Dkk7THycdt^yMn%EOJ--~LJWmzdpM9%-1Wdt#c7Qw9l zWLuL{<%{Z>SbMVOu{FW`540_^IqFwn``X8{z#%79lpq4LJj6|fBBQu^P%vAUJXLB3 z)_t9wJ;|t)TX|4c^-BIGOxtFEE!&YS=iYIDSd2-L#d9C2$z z=lbl%#=5M`+V(O6GI+2L#hh3?mfg#$z$zqf&`^TqVit^|s0)MG^%{Y!#mvV9dpGU* zM>TxdH?;BG9&?(8hJxrQIQ{dGW|Bw1K%YI5y%=@>78< zqf|X+?PDj|Km?W~c9tEc8J6jZ%x2^?4fpCx8qQFA^r}WyeG_lmo>{BLO!Oo@CYobK zp}aQT>Yl`E^es#91c3-FNib`S_AL5{6|*yqR`Fbu@0g&@4XZ_BI+u}3Qj~*D16im2 z^;oSILo~F32(%~e3qRn@V;ozs7Kg5@wrrf{(#eYid@M)sT#M&u;kof?9aGSCrI~(~PBC5?MsU85(LK8f^=Y*SIF?;VCJ+i^VOn^2;1` z<+V_~&g<1uEKQDi?GudRjA~u^+fYMC1ZtTh;b#BYfBZhHyEo)dvpx9v6pZ{3cf1Q8g`6g-*ng!S!Ji-k-&t|J1q2KsJRH}~?<>mM}RuqZc- z<(^na3q8CkN)RE(Ik))?Wv%+`F$Sh61|m>vQ2a`@-RKZK?&~UHWA&G&Y{wH9zBuDB zK?x!-t|~HF&$Xh{mXGJ!FgY%ZUksKcnB=cw*@W#jd~Ji021Z6JU7e~uX&kCMDn?qS-DxQDI!n{&63Z{raEsQ~nNZhoYbbil)e74rrKnWr;Vmx&FE6cUW46}_*c`BRI z-IMq2*_I*#wdC0LwzetE$?2Zn?rUisC5RZ<-d(R`J45?+*lfcty9N8ZdPP>;wH`$T zY9%;&>oLirwCExqa+}CO%rx^9U2Ym7*+4Cft1HS_zj@TbVgx(8!;_)}5g2_Jy9`bY z3-_^X(;hDaC5Uj`Q%|3~K2>{ObUyEr>&b6+ZNN-z3kf1nOOEPiri|l-XJcul(HS~Q z5P{>bC5;t2Rd?oG!Yh=-+UuJWE~=OMSrg1~bSQ1F zm-Nk1YZjdcE0zi7=idjhv(JCmP=W|K_tiTyj8ENFo7qp>Ptwzi>EV@LsWF$u?jABr zF>6!o^h?y`$D7t?2hOKR2-L#bD$0!9KtBC`F#Bt_A3+Hsu!iEU;#clGb9f|svD;e3 zC<$hn$`O;uFC2acWJ69Wy@kO$Tqfp3gFo#LzrLQ zBB_5+OSW;lY<=$bp)MP=yo59!I0kagXo)33eC5_4wqVW_9Y+wgutyZd??fPfsaxHzjY9AG>ld;Qn|;kmY&}{ zK~0-dhG0oz9UKzE*QM5BV-KfkC_x0;6MO3WDcrU{*PTXe4QtvvKwtRseOCGoYl4}K z;S&RN_pxuXPX1{=d9~}7%KP5>LwlMxQ)GGv=m9%En2tM^BbeKX{29Sw4H&`?onKBS zZPg59@0b}d|KppcZm}#Oo3Flli);b;BkOD?t%~S~yN3mYS2w$8@@`ot^ejMF}G0 z4A7%fQu(z9iF&`Z;t~S2aQwwgJw25V_pGRg9&4myFJgWz_PTggSJdj0{~PT@$OR3{ z!tuwE6}Rc0Pvve~suHWl#WXAzzbo0s<)5Oj*e`OSQ%Myih`^Cm6k}vf-tce6|Cq2< z!?n+QUp2j6>FHX`8ym7_yN{m6hHCjYti+g?vu?#x#oMo@741~iLNu=J;x>}R6n@tK z9&sz_Bq2}>_YaCP$7(EJ>yk`MeQl_rBw(|r{w8mYmQdA_plz`ZW(M?G{LR1G9fwq|fAQrt|NfPQnWdQ3dc@OSx3Z7ymHMMk2cJdE<^bXFLzTjHh(^ER=D+ZtTdhGyF9@mtOQ-2tzv zb7zML{_;`vER-NZZbyS};{LhMK|IOsu!a(BIc6D)8w7p}=2I>N@t9)y5(2fbed492 zy1{&B+aT_Hr31khV$0>M--C|9+%qGPuPnAj$~ndi;Iy63wP}+|=!H9NM9ZI!4dI7l z0=T=jo}dH~*dyY^Vp)${-wfn|4zE;{AOd?`?02sR@nD>H!KUVQ zu*7R0qiek+elN2u!P6EZup}|Vxpm_wn*B8H&fY1VEz`~p(`cjzb$Z6E^eiPzKalGwN7%oa))hOP~9poaA#rZ-S!C>}gM1bxY>= zAI&y}Z&;)@Jy=aQ`+ZOgeFNe*SZzA3wjz-`=1tR33(;s>aEgWpu@7B?d6RHE9dleU z-?>C_dy>^MM|1yXX1!R}^kpYT68?H=84a^=F$4IEYmU0l%3hD_Z=M;pO?768ZCY?O z@gEaP5MlT9f@=NIPTV44{+)-cW=uC~@(TaFH(`z|)^Jt}d(xr(Ma|`|`FB2lLnC(Z znFqIOYJ{N#5pp|xUInoUAA|VMw*P1-!Ioo2w#b}35yY(Qg1O%@OC1rYh3ykNGVefk zH>@82$7&?O7Glfg4C#vnfvmi3Ft5CIm6V^2+0s~&xL0jkAe%8enEP5!muw&cdqnK7 zmISjE)r0uU0uO=`L}0I*{fR-WhaloO23YCXLTovH3u2$>-$u7sRGikGo6Il|3NxzK zA)#JmSt|s_6igtvJT|y$s1JdSz zj6f}9|B9^m4!6np@#MyRa;iiULy3e?D(T_J`lx%lna88a$UVBt&ph?jd*Rc7oH!@YLawU$^}79f z|2fv=N?wY@VnqZpPsQz&`PcOC`Z@LC#1w`SL?GK##GRkG8W(NL=|_zuhLVJ>o_g91 zo6I-Q9Y{2-E(*L{v9Gn60#nbIOV z^T$PfQQii9#jRw9T8in8_NCEV%{Rf3$cU5ex9a70?b9!LrZCjPFJDHqw_mCcOs!=6 zJ}rr5hcT`H6<2-DLp-{@Sg(70Nbn{*V#V&z>RaE3WI#t&t1xbOA3HJ#tXN_QKT z%up-5n>)$xQ(ns-=s<8D6MNCJ&a_d}a@s4aWHvXuD%msSn<>4Yqojps@y^e)0@CT9 z6m@ERiZmx88s`;pi$}@~I%STPmNp_$LZFtMp%8GbkOWo;CDn7pmk62Oh`^ao+$UqX zk{q~~OZMGQW;jRT?1QtCcmeF6gQf$kD%1JplNmDK5h3&2hYyWW?^%|km1ZO})Kc!0 z2wQW?i(HxSK#(b~D1SYjt5zTNj$HIkkr1dQ+t6;NYk6KCf;X7Nuw3tF?X&>BGFe#B z@n1Gdcdf6lJyx35njpp;vXl{l^P{+Vc($)zP@xvhsFx%mPz%>YaTn6?0zJXv5D6O~ zT0ZoXcB7ccIZkpQIKv@YWCQ+D!N~g9L-mSIW;mwOMQ(pwf18uShu@dawRn~d zUl68yU-@QA8~ksdLFlisnp6#J~Y>jHo?YZZM<=%o_5;dP1| z4W1>ln_ryNX=}rEzdL=@dM#F~h?Ws|9;RvYmYq_EK1^lE9!Ku^_v8S*mBH0Q2Xn1v z_ViJ=G<&3Kf?I?VM4*38ycm-CI_u7a>)QM$sSIm{HNo5iaj)93ru^GQSMIU0m5M$+ z&CyrfJ9t3N_xVSaZ4|7H;;Sb(@ez5}l6MdhSX;sIvJ^KIbf@f5iyYBcuDWgJ12t_< zo;tTuWj#FkmYV(chl<`$;mf#FnYFmqf?a%COhq3uY9U&jid<{6`GZvEB5vtLE%Kn6 ze!TSywd}1ml5O#7=&W4r;Xl)|PCrX!NuytA8?IF&mSfhamqKmywQe@#lkIBB8!d7g zTE5a!I=)qNPNg#Ru_6L(i~B{p4p)D(yr|X?V~!F;U=78q3+{{$464O_T{Ou$W)g%{ zy05JnP=(}Y{Ug4TE=x_qE8)khCw`X@sDW!T-s@2O>Haag}+ch8H&c(G6X-kTi0k)GafSt>&b@)@us@jlMW zaolG?SDN(jR~E7mmU#`(vUBSZ<>W^d(IWSCa}w{g%9F13W0C|BvWvYdFYy6bB(f>XpwGjM!48Zl*$gg`B1btua3RX3@v zHoB8sBb6Z+{L%@o#wP`k%BIySGQI^5;L;v#^8RNgJMrcu)(Uz0SVQ6KTWF_FGcKw# zo{B7Ns5>HL8>JR#YSyB$nvAy%tEo9TUP1~<-DG)ri z-Y-O7&AREp>t2m!@pDZkM4*;zV^Ml2`&2xDZwvdSPMY#UjoMj_WVaT-^Zxnj8@nnb zO|UkR$tChwPBmg)ng?%GrI;i^gv=1y`)yCw*15OUG|}>pN2-wnBSl@utx->f+K>>z zo~tf649Lq;l+%$mB&X7MH9jMip#%|ft)5*gLGJO@riORLyE4FsLj<-@%y2zDc)1FZ zEb2lz$vQHqo=$NgOP1VI^RwTI-kmeUj|Y30Sd*3yB?M|=`-D$FpbM)xw>Up_!A{HX zU6ZWI-Ki?q3MEz`^8FO$O?p-RwvXG&UwH0it6K_qsbN<%S#qR^Tm1qNPD@vzTF0{h;B(~9dlL--TnwrR# z8GY5XMt4<23ufjhd%CexG8{fBp?fJ9BJ}ZR}JL@P(5P^JQ!LzJbiv01pxar89RE9RN+=^oOjYr_Fnxioe$<`?qd1b=FfEN)Um3 zSaFx$kvAkdG=r~tEGIo$tlrw1%C2TMBxoJAu(o2wnc0+{C^dmksZ~#VS~`R*Io4lOVqUArDwmn$ zDb*^|pB0k%m4sZ=fUernS{?sY}ERhqc0*VAh4$i%!T@HzyWkT@b$y zM4*;jtMNyo*@zDgOzGF!gx0ulr-jj=Q*k9fkdxr|1wobk6!s&c4zbI+%LK|zuQ3N^S!^Q(Ye*g!htWe_z!DT z)IzkFubytwh9A^4<-T|kI>?3;_qWlHmR&8OWkko2*J^6#*6Px{REA#89%9Yg{&zL~ zz{fQzmZT`B;w{O@pHH+dM`Q$Q$u`^DQ)gvHON)O8(+UwF$y5Z4Wi~%;L*OZ zd_uIldbA%`XQl<{Ydlt~h?WseAJ`Hl>WO+&OJ&F%MD)K9EvIQeY)sk~F}EZ851F9t ztmDdoCvJIPwZtQIPCj5AvqbedW z!iQ*a%jUH(9{b3TeVlk&#ds~<_(D^zSJTf=TBFW&EzrV~tLWjAo`{xj+s*jhO*PpV zn^*~fS{VNnx#1t4YQLs$Gc6Y<$i;ej-A=qHaQ4P36>Xqx;S2w^NbCM6L;E4tT8xag z++0m>n)*U((`t=mTf_%fIqJ99PtXI~r!p)H5olXP`wHDyiggpdbnta4eva|ex%-`T zx63!Qe6M0+C-CgPKU21aa`IO_g0;F-*Hu3~>%OMkexjm1kzJEjg0xdTRv{t5swL zin*lPpIM)ly;7Hn5kxKqBCsT}3r}=0c7I6X7iaycN*s@YCOv3SUoAZIj*2CTo!OtY zjQ#_Y_}bp3WC{3>B+G4R0C_XJ96>*< zqSS9Z!}$I2KI*i)50gBmX}dJVvjTCmu0YVkD&E@qy%q6D`9a;W)2mMlY5%D%v zkXUH4C$-XmI!1cm6-MsfVa&~SgO*m;L3jIZPcYts(Hcd$JA%^rzpXQzU582$lO9XN zne9vkT{&k@r32fah-1Tccwe-`bbe3L|`mLys&Dwg$};oo&LcFG1S6Xh>SS$ zs(_q%@Pg+1^pw7Kj5^4@d#le{#ep7jwz4(^vJ%OHx>Fu}>ys z0wP*QtlxN3yZr8vDO{XbFm8aJ|31-8bj8CzV-zx@P;URgxThtM<0Mt6%wh2k2T@HT=GLPWR)4r_z{bY5)EtR1J5l?Fi8vzwfT7ua|kEQPH z_505%Sr{oHPz!w=in3sk4Sn;+L1Vzd!P030_v-Ra-{S5>EpyRm{rW_Chm1Q`+{ub~ z)VYJkTZ>M-NuLuG_tdy!MYPBnot~;&bo#9I?Ul-KH-UQ*+@px7Oa*&Bdgy4q^^RC6 zc8APdoGZnRCj(0Ji-j!=8~@e}Ih#0(%80ciZX4Hs?KLVTwUxLAxKEVVD8u2N(etxz zd=R-;$F@&UFp3qrFf_KI0=DkEuzKUhSm4c-f1iL=Y=SGcv>vO>~37IaD5cFo{o4*Cso-+8(xW%RyFif z;|eFd=ewWN(`OFRQe9%CJp&>zXIN2|ec4U#9DPaKeUK5TCHwThUp+`ozg|(#_N^ov zsD*nJv4<-aXf&B*!v;KQ#W1=g?L}bEDB|Zi-3_nE(rlzfoP@w#jf7S<{T8I{z7QuEr z?ph0SVnm!Ym*8$dnpc$I_p6OD$Nbni=b8*-o7g7o1w~oEB*h3^QJ$6aY%cBku%|K0 zSlr85ryX73RE6z$8o@9VT8gE?2|)Zles`mzD}1AC$8=^mwur_vgLvP-X9cY@-I@Jn zm>5Q_5P>C$Y(Q6ARz5n0mb8zO_KA4I0{(6U581sroAue3I+k)|sD)m6^wulN^b-E; z!U0!WVtzfz1|qN|5pnu&`Lt!EP-e-UpZA} z@uODgF3X!RoIlV*FC(`OPRC(t@E63AJ!d6l3mLp8LICW_(%_ zDXq@9w#)t!m(P`W4~sTN!s4dVISPFah!#<@=gs)a+BJ=#3mqA1;T~Szw+|T_z~|b! z87cvMi-Jn+=86hJe!wJ!1E}8w)n4RZ9BOi8>W;o0r!?{b$3~>&8 zVrxRn>dhExAwx(;y#MOVJzA}#V?;a^nKg*UGnI(fW*6g;8#5@W*OVda1-0aP_s97r zbc)Ro-hS*xns)iIDc`N3Zk)fON?u@pd-c+tFkQJ{DE7NbcsIhgjpPwimPrUDt?;mI zRi=lhd{MiMi3_c~yOADXcU2%R9`(_cfKmLLc#T$)0798okkw;cL%rjQD*{pKLwjRi z++d!ycmqXAc4>P}`5vZ+uP&7Q$s(tEbUWkSu)%E4V1an`Dr-@(hGf+7D=M-qvg_Mx z0eN90`VF&Cb^6^dHP~hZ#~|;do%bDGGBus<)0A!p5A{lg*5=3CsK~aX>O)%PrH0NKx*fNwL0_R|ncgH&!2je2y+fBbQ>>vED z(2FN-Vr#xk?`R#zO4^H-LoXs)MtHtIOuqeyW9>c5O9_w3KBm6$g`_c%n7VNKdTP8^WA?<3E`=bkul1YJlL5>B(=mJJCaFq~uVAptU%&ZZ_ zGpwzo^#c*O5(y@`I-36e7v)E1R%Q4t;mRq0CBcWQWR+PS!3VUiE`KH95ysIJ=kssD z>`d@&BmagC!-y+Jb#ZMMyYPd7Ea&ANqp`J}gg`Cn?4xu)Q$P=O4q;UeSu*7KAg2iT zc8U_S;0ZnE8^Df-*+~f0!gGS6^voJ*m{t%Lcf*b0*N3}T`Ma8bPBT4liC_VbL|?&| zC~3j?3l8L85xn*Wahh0>O_67b%uJazd2Wq~|Cw@!9?UJpP=W|tyA-8)FK@mf=QjP6 z;3^?d3)e1@O@6#Rw+{HzXi@(q#dTX+^&#pYvQnHGFK+eJuo(80VpImBJ@US!hF>Gz z@k@abUGWt~2_i6VB=&IUYVm31?ir(ZS7wMnE%Z5v_qLnZ@CJ|87!ylJN(j`FJR!>A z)P2T>(Up0z74@Y(9PY^E-(bDsBecu=tMe!p!K7afWC_W?k2do|jgFR8d2Qc@k}m^y zlk%Kcv;0=7kEzTHazmy4F79z z1Zv5#qQT`YSo!-+ctFYliV{R%)Jfbt+|Yql|9rq$J|>LeZyV!A^6z|3jyoIj!^8Na zK?CXhf#(4{izvz;ts@yd-_6+E^f!hQL?By8Fl)9(vYxg*jb$607)lUfi#ofQd9;{ESN(f76I+uYD0ScLmov0YGKxec)c#80(WiOT-{hMmSH63XlOHCS?Xwd*mZ^4a*+6Yr&IcW zq5$*bYV&4>$kvKfB?M{-U%xJ*0QLV91?aWImp8b3Q0wumC<^d@5=1n6-&9w+_000> zXO05&|Jj;*Wv^663@&eu0{kBWwJ@e5GLZ^v^0}>^3T7T-C_#iA`6(DMhDF&1(pAgC zsfSw($xSJyK8(C!!e6Q!X^0y%hV?&En|ic}q$oiI{^rGf02fEHT~U*1?b+@WnWTt7 z+ae2l;RtqGyv>oBRY^jiR=E-3WI+3^>gh%|OyX4ZVIXTV=Kw908%9xrQ6RLfD4CZ# zvGVi>E&0HW#`mm6IxhdH4s3iwV*g@Ef`wGN54$igho*;zOExgNg!V+ND5x{L<^G*c zm{*nJoPh|mEj;v-W7wdOaxC*qeF=eDGS@laa};yFTAm%UjFb?lh4YxWQLYVT3p-S2 zB|lW7owkYF0)DSd{KS|eXB+K_dj~H@FpINQS!APKc2jo^-|`@oK zphOkDE_h2rb119RhwaKF5(2g4oQB*7>*+=4@C(g>P{qT^!=7(b5ZXGt=>uJ zBoATUPpe7@)WUoU;h~?=kLErc#i*xBQGy8RoT&H}OrXoXM>6LVkrD#6q;sOugB}Er9m^tk7I9v1zy(Pt3oM<*)nkalXgsrhck~ zKrNYTP=97)UN_H~ojqJjI&)&J(4Jsm?{3SB`;}xv-iJsC)WY+p$Z6=%nfKWKg3P4LZBAzgA`>%yK#K;4i8#-wx?7pw1+iR zltnF*`1~1R+Bm1$6w5*zxJMCQwR1^4H+-u8b)P*&2_jnFkJc}4x6^JFwWGzlG5kcO zdWNS{D8)UFq$Qo`i)|Xif7@BZ=>I-aLMWgm`2&47@u&kM z`RB@0jcyiIsl;3a8(5M!c|97*^Ft>aGxoYk2-F%{qLH4{e~IQ)w0>lr9LT5r+HXvl z6fPl93)vSU!n?g2CzoCtj|SJGkLLyGIU^owOq7Lw4diGDPtm&`JhI|r=$u(mZ@;dho>HLCV~+YtHn3KR7Q5HO zu6)R_M!Z>84eF5iP}9VHdKN8in2;SU+gRdWjW4o@;CzceMF}FXw&JdrfTu?Bg*|vh zk7^Y8H)!wLz?IsOya@e2E9cKsmVAEy*8F;Q2u0s3+CZrroj`tW#C`u54 z_QXzqoCP;(wBtA1g-8h0!rF?Hm-QTD_L32NZx2_B^*#91QG1&otzQ?vZJARP{5-{& z9XN`wTH-@df(VT72;S1?KaF-b68Pd#%_RhCq32#?RNc)sE`I69+Z2zKYK8XXcBqyc z>7h15`Ja>h>7<)`)J~l0wZ->?oU5xZ8mYBoTk5C9DMQ>X;xvQqNgmFBm1sXv}r6|ER zVJ3;lKQE)OMHM@6ztW8<`o&O7_L2SJT#T&<>B#4o_oS$WHpbiiPz@(<-Lr|guO3F1 zVl$)L@`#glB?M~8HXi2wO`A3tz(x-X&{2X2IZKF~sKaKi58^HR+0w{EHAq>nUz$tv z8z#(MLbS-7?BK@e(FQ!YDx)Ytglr>xL<82#f(W!HRs+9w>|~(@U;MHT#Y{Ft%ZS5io!O5`-;C*B zTqFc)tqX2I?znH#J{7IbOMCQTzty>DES$w81Zv57cYik=#V&mrYXoQ3rQ=G+knn<% z+Su3|CiFUD2A|+SmKwpvj+ts4x)4E8f(Z0qD$3mUBiQV#bB#-mu96KzV-3aal!=2` z-{(7wV;w^&N)REpad|2rNlN0p1sq-!_eBv(@VKPIRBJ?p@-@eY16lrQ;b_QBuBErQZ&XWv1AA zRFVJ!&$uE}FRX_C{n-R|vr8Q*Mlaa|MuE5qq3d3K)Yl2D?WQUePrt}JkkHEh(G!g( le~)DGF@93S9npBE7BfTSJmb)lVQi&sjD$cfi~=gk{{T~N<^KQx literal 1906984 zcmb@vb$ArX`u^Qma0~95;0_67T95>Z62aYd@!;<6y1?SH*y56Obs>v8gb;MGMHYwP zvcKw@nwh&#GT(FF>w5WXF7D^kRn=2>SJl&1lYxDE_vl=-caJ{3+W8j!|KZ=)g%bQ5 zt95?nPlozju_gY9vn~4;K$`wN-u`)3ebTMWc|Y_20g(QKfT(|()+5W8WRsH;s4N5G z&8GTGZnwT{fgyukczJh2M>}R#;zlXLa*_{omg?wj2p|XLa-5 zC2ctp7=``KS}Sxd`VOyTB~U?v^(kWB`J}Z%g?$&qyu<%{%aLH;1u^e-(lW4C7==B? z+79!1$lS`mTlNgpO}CoYWggc}M<*=<7522z%_oH!g;#Q41`_7jXg-aSmVwv8DDhcI zN}#u~SDMdU_Eb%VKm`fB3)XfZfl=nDz@GKVlz|Eo*gk6+Y!0QHW31W2rS{MKx@;`h z%@HqY%TYmME*qJH>eor8R(Kcj?ha?8e~vx2WC&D{V6zzAoU@eOG+ub$3sof<&g8S8Oex`E%M@1}Z6@jJM7DX1}9&B`bjn61_{G_ggT_ z{%yJ^FbeyEl|bL2gIU?mduSz4L4vg}mbE;Y?*kRqj#$=m9)(wOUj`DaO);$H$&`WD z!YJ%-)-v#06QB8YnVV(yyi$^S5EUfY6GLXtt7K}$o;b2&oDiS+b(w=@_Pk1lKm`eN z)y1Ay$&xcsia8TEqyD!t zkYICm#hjHVEd#HGQFuqJ?ZA6tuG7qN%l@Rd=C$xHn9oLYR-UvBB+Qw;>HGhrt!3bKkucXD z=5r=#8AxCh-f3$YYz$P`6O-3heCF3RpV;QQDrp(0Ac5_(mVpFDnPZ2!@=IC?s$&`TvMzMUN!t$bW(ps^(u42yJ zOhtU=Q7nI{u)OGhAutNdv$g{jBv{5%VR_MH%0L36+_!_h1yI;q0G{(^Zvhnc7Qp_Q z&5qeyfS9B$w-6A8cf{HbRM=Yp=XF_rU#WGuNb+w1oOc(aSgv1TZvkvcYlRBS=_~9l z0FT15-PZ~Umfu&{TYzNBz-wWY`2S?Sk6XnL$)oq%*T~!2-j%C$sLG$`IQy{HYDtv{ zh5Zk|CuYkXpYgs~38Qo!rOqk)6X5!+hRQFyN9gALLEl&jRM3NXB`bjn68OY$Phgbo zl&^9w)j3{6E5YuS&h8a|>a%;LvwOuqvwP(xi-Y$H@6Y%`;mY#DTX;XVmXY>yHgdjs zUj7}F|6L;CzTW&Z<`%8Q+ll2#&r)xAeFu*$LUR9;juV)Zvl8rH5y$tzT1y$0gq2|4mL1+^o|he-$NY?yz$XA^n(>KYB~U@aoc*)0 zH<^2d1V-UA###m{NZ=b9_XI}algLUiPY^a2;htb4fOFRaj&N226(r17vs&^ixhF8n z{m98i9OwIG))SrYXvK3ZnKD?vGUo~WX~24h^Ubk%9`paV)(RCQ%oVt~!b|#uLjt4R z&wWJi`i*FkiaOM2U*KN1qobvyC*Qp{rpNicloLTR}(l#wU&Vj61b9aPhb?T6RZTz zym75A?uefB?xKQ(`xQMB7$v@^WXeDV2{X^j@|pjIz$lzQT3e2z3}ztRk2t6xf!R-M z8AxChj$Kv)6(rne?vTJJ9O0~G;4Bq$*24cJ>35C_67DnGNMMwBDkW0}DoB{mb+@CM zb9}`p_hT)4gXMfLi*GH9ul;GuaXc)US}`Top)6=xHg@uha2|zk%&d18SBkiwg?&%X zm8F$H1qt{2GLXP1*591#Piq;dAc6Zp+!GjuYX&QUvu&2^bMB@SqjoZ`MFj~lQvVkM zqr_Yy83Lnl_n&(L6(n#Up|#~mU=*7<6UUm`O0XxKnKh72ui-31d{0VJ4~p-cE6m%@ zJy$sUu$F-e5^N^x-0$U{z$l!fSP8L~<+T#CO#Yd9(9LcUoPXe(N}R7)%RmJQ;rV3l z6%rVQGaPFfs33uFFx?Xvh4UaQfpY`Qg)-|+^=i#`HIh7_C&Qgo~YKAW6r`H@y$JWrYFQan18kss35`Kg*o?;x+gG7 z_$HY$P(cFs5n9VY0;6!0uo7&ZNF2FIHtTclR%f$8H#_1{L4wTy-Ry`L&n4a)*qYqA z7hF8YlJ6zXwHgvEi|5>jZfyr%3!`w|W+iY<#%7kzoy2VZXy!|K2`$PuV(Jsd`6mgls%7~xqd5w3KDG2=-jL7p1>#^udD>hJGb(bK$+#93B;3EdLjt34rEjejDoEhF zLiYqlVLrf0;P{GrIo*%7s375fUmp?}#s1&9LbBEh6(n#Up?dN7=^QQD}f3UY)7+mFSmOFqcHPgCD6~f zi&^v@lC&qHf`qx-#_XB@H-S-N^_mQU3KHh-AhX9OEdvRR!uLDYmSd)XjX2KJlEP_v z(lSs%Liq8&5Evz%7|HB_Km`dl`nWm!iUdaCTEyCNd>XJ3$9ZnT{gVL|B-mKuJb_^? z0||^`|8K52m85qU6(rc`?5*X!vMuzi2=33{;7two?sTC?nFh9CE!Gi=w3Ew1B z1}aG4$p!1(MFOL6R%<2jo-o%sPjIj+nYq{GYvojsFvlm>Gye;LQS6SGZ)KAqP(cFs z?_1k}1V&+AOOn3)GMWZu$Uy?+c*W;n6qy7*xeSE zV>DgpF`hgLj8{-W0-YvF!#j?mBNm(>M{>j~7}aJ;B$-us8!y93MDHI-Lqb21S!LoC zRFGKuKAb$*o?bU=C`orFji7~M3mN(AS_zE8r;;T7k!d*n@SA4Pg7FGQU8&cYgj6fX zuWKd#y)u-(TGz~|mM>mG1&OWCLy6z>08y(vw+GXYMTQyE>sbkm68Q)5Ow97?7uuuh zJ|hKd$GPtfcIi$BC0;a66tNN*<=LekIl6n3 zD5LbXp0wz`KaJ9P;uTboz`HI<6`!`D>3;iS=sB(J@UC5xspCFQiak6OLEb@rQ;P;kSLa>6bU<%ir5{s@_Ix1aBxBTiG3ePV3f$!5c?Q) ztA9Out#k<*Q7B%)sHTy{$ehs`_;syBhQS)mdASrlmN#BO1&Jy-3XxS~vWi-L+EI%J zR;oxZFh?PQQ6e8CYBkKaBuzWJE`7ipb>x%>$+WU0zZPaZSA=x=p1lm$QN-=0 z8$?SoMA_K&LZDp@Ib7bxGPYEe$RFXLCB9ISSj+uH7yD ze6UZFHc3+7IzNpCi(1pue(?&{9f^0N4(pAHB5LI~`>ip%NPBvvk(IzGk)IR2WJse2 zMvEMsX+BmfjH(h5t51Ec^6OfOTgr8#X>3<|w^Y1>3KGkguh$n>_7}B^m~zrcC-|IQRW z)o+bNtu9|(ZiIFiKy&+B35*gmHBqaqeFKc+$A;0<%!A7>=hY7fh4X8PxfYM=78j+r z_!%O~xVyHE@p#lwI=^wef(jDWGBSIPF{X?dOw%$)A%RheAx-q~4~{Y>x1M2q`)d$= zT_s*Y1qo~u>+PpX7~>m`pf6e9#dgd+Bk8@%MI>pHByFFb(a2qOB%M$=UctH}u{+Jd z*o)&LMawszyh3{WjiRyaJ4XVe#0tRC6E{qg%g-52v$5V@|I7!!MJuEDwZt5rN3s8p zas0m|WohWI&s;E?hOyp`3KG^bUd{0%3!_HUVAk9JgK*}>I){~y?bz8~wj?d8HJhyY zGKywqy&V<2F1Cr^E7ftY*!_{=j@leM6&PW&+$+U#uTWw4%}HRJc&!vit&qSdR$H5^ z9jxVwqvfa|fp?wv64lX5upO+&$k6khHDoh@z5%MkA6R!JSf7?H{!ktMKmwy!KX&fe zlqBX475w467VG)4!xL75`9pR10~I8gKV-|3K{cNYdDxQy35;UT80X#=NqSXan`%CN znzE-4MzN=l49_bdvMfEII-YQNEhN~JPqsWoRr4vDz#N4HMzN=>^Rx;dKUBx~!Nv?3 zMj3NgAa@jd=F67xLv@TFsEC{#C#+=*ZS+8G&c=`Y_VL4cEsSC#gX|bfB#Dh5s$={> z1qp1EBz3ryS2IWF5^Qv4W3A#Ch1po^JW0StZP_vd&|n7ORFJ?n@mYrEm}TI#Fp7=Z zvSaqa$8!zFbEkp?-gQZ0a|SIxn=?$a&l#NUVDkh8W@pYeNfMjGX^uG@)*T5p?@}yt zIL$GKLjt4NT+4jBB%Zr$4yXNa&EcHaVzV>FF>kXHY!0V6=5VMW!RBy^W%jB$X0J$K z6r0tW@1sPm*bG^7%#bmP&5#wCQv<j@Lqh&CV6eOkZ=%^pU_QwgP~2ENqRV zIo3FAU8BHC$ayA;txFWk8b@=iaZq9F9VcNegROBiSmQXag;8wvqBzz&Y(<|cRCBCx zP(cFQ#8;5oK(T^k>p{h_Qe^8v=SeiS7F8^(R1H?CPQ^k%oA^ptbF75%TG(>7LRK6r zWWMIqGO#tL!JZ|kAc1#XlGwUdgLSR59c(SDKnB6tCN^hy^^4}nGhp43V7URsl4sBy zc?Kjfisb{Gr}o%rkT5`lJcILEEQ6ppatl_155Q!#S^oQ7przIC655#PV>O zBM*lP64)k5%C=>ccBA|brB6{dr=Aw6yvn!DX66$F!QVUj^p8>=2G->NFG<&GkJi*| zk;+6io}+>Uwn>so%pR>x%(Ot>UD8Tm)ZmR#itPPyuRWJ>YRPErPR&1KzcELlf&|Nc zI`6t9)yzIhYxViAaz3}U9b2CvPs2~ylZ?JNCYbQ~wet8CK{$t0h4edEg(+9kCj1o>0wR%SfYMnDJP&c!@C`N6% z6Q~?oI+|bCN}PV$U+YSKQ>(JvD=J8=Zq-m(R%DK-)v4TlwM*Z3sP$MD2MLT4PbE>S zsFaxrl!fo+ncxt&^T_h0{1-<7Zu z7}fk`EhVt?1yRQ3&h4}sbrMxISG5_s1oY2UdptxoZyBeXc?s9~L-%4=&@<<}B3 zeI9l9u%t9-S4Na^rbSMz>eEmyV{p8J3KG^buGKD}^*hx_8^OL0BrxiF<&?_zDy2mk zow60xHhvG#Ld&ry11Lyfo7l?h$P;zy?vC0S=BV)vW98jXRDLb7^5X5tl>LHSq@yqSo^0s=fR~M}qa}>5?>6YDcg*JUT*a%f1gJFlt(yBtOv{WlXtUNgaE9xK_P2_u(Ukqvh-xhz|q?1;_UrL z^YXDn+c?`{<`a24e%m^HUG5|H|F^%X?yz*U)}J{F71jzp7!INQOZV&S`S)=-kzH%J`cAl4lTcGqJq-ym^( zgGgW$yVJ3*y$0+XG~gR_UWS%XgfkpZ zIQCT2;W_Bsr_G*9y5$LHIG%8*u&14qu$IA|a0Wc#oY%rA_UzIfPdiCsPdLNzghK@h zY!e?pXlXWn__FbXjRv}7oM5AY?l|Mj#ueQ)MwNQ=(J;rTf%Y-VsUU%E;^Uy<7zgoM z7{$gF-7!8&QudR#4RgdPY9Dc&3KDqNC5eq{w3lmCbGCzxWID_roNbaMHp`%nSq9b} z2{tnzmRSaM%rcO`C^j2#o_#mhoCPS%GMv|9^9SOXSy%}+%b<=~1}aFfSq5>{AviFg;U2YoXxxm%+;MI1KG@(SZ3kWF$+h9tv{TEwG1{3r*B-d zaObr!ip{TyV@57XY!*%(vv5?9z&7zU4t1nNv! z1h$E<)u>~whS$O8H5^|RQCJl@6(sPkOA=doQCN97+rd^_1lG9DHc1j&2~)>P z80(G%TfGv?N|-uU!bo5gTd|tI4kcFGY$Z%#CG5NwTjLVP>eouJl`wUzgi%3)t%Qjs z2S6{28~_p+#c~7A^Iww0@(i?#$TMIR%QFzjOaQ@h8Pt)>z-uAFava2xFQJZn2@)8^ zGB4)&T5+#frieN+MJzi+AfIHOsN*>@mfaziOc8Zticn#BCMRJngJp`SnJFsDW_?It z6w3h-N7hJ^Sf+?NGDWB$fok($)*T6!10~D>d6qNTl9^&^7}ci zq&&AU_K(h|`DdSeYxNpUhbKdzg2a&8sr9{aN0K4145U|7sb*_1|76J*!VLwZdy*)XhSF%EwZ^a8K}Bi8k5(vxe4t zg*8D!v|LVluaLkf@%<-5V14KHJtR-KRpI}`caFrk^IPPMDLQi6+77%|7=`|~66l;J zjcj_!68rgevFBR}RFH^@>Z4znvoV=kA%RiDy=Lp%`z}a^z`H1D`G5Zgkq~8Y+S(5M z1~E$1Fd0JJQLc#ZgMSwHFc|_BBt&1}z0z7MECXrr4JK0tDoBXu<9{JAN<1r*A;c4h zE8^M3Ka1ylG6dd5(Mxy~-gRrsQ9%ORV$^^E^4GUPO13{f)RLq^&8ury zeQIbkcSR_emB;*k#&da;9XWFeqC?pr)c31@`!&b z5YdiIo7IQW{b`yu5en|o!u?+K?iBgRsz!q7T!(A9{Li7$Ob`J_a~Zi`j?`i^1)I57XMPW}gMBeXp|sI``wY>Uu&SG{dEj|Rraxb zb3$dsRyxGnBkwu+RjZoH+3O+R`+A>~f7x79nfvY^AGU&=6sk0vcUIZnZ8Sv%2`_b* z96C!A#I~!)m7L#$)Ds(qSqO}pIBA#M_ok-w3VG(sPVnTpt9a}jr&i80n4*G2j&_UW zv_}I3@t|dP_3E3ws?WaO76PLVELkL{&Rk#Fwr5;TN%Hc{u2y<>NnQA`D@6r~hf05W z;;TSG{QAI4ZIw5L7FM!_g}|t?^ZLv4s|P8~FFjyo+>Oeo9vhfNds;J`qJl(?Mn3Y4 zbYX%RmZ_M!C99X#bhKt6FsjB_A30TnFlGAC3hY@@EO&Z!aF#0Cs9iNEDo8Bol4u)~ zHbM|Dzok}JZSmJ?3@>USFlx)%MB7hWgi^otKvu@0`X`i=>q50F*>h1;kZ4{%+BW}D zq#(}C-=cW;Xsh`=|6(A4QT3yvZG|#NDaGfkW@SuYQ&Gursf)IJ@;w6;B(~=rzV7F* z4&p$_ez`)<{@Rl}TP*}e^`10xU4i{k%9w^{SQ+)E9oFxSjn+0VpKG9k#KMKqv878p zh^imz67P#6w3c70SO|=2zb-oVZFPsEMm{@6{8Eq7@=SO~P(i}#+R7!y%gWo9+=I&B z3+0%i0m@b1Q19%8`^nwEH&RYN3Gv=DuAl7NI8Zps*6fkICdD1@K~#`vGqQ&Ks7RN*`4+n$_N2NXfdg052Av^y`F+9LjQlf;TzP_BVUuamJ zdk_^Q@}-ZC{r!(fK`ePwkd*dqz&(frMzNkB>vEJ|>>83-JWRXFJctSs%xSSM*G_$U zowPgKM)PGJL;|CRT~3Ux**U`D!7urZdZ#;b52Av^$xCdES{o*az>Kwwi(7hg4X@I`-?;t^x$Tra!#@_sx9z+78*!)U&&99`_vao&1&Oas7wd9{24Wm6-pyampS>OTAiAhxl^XKcGa<^^x*^`!^CjtQ;yQWb z%zNB}s37rc`uDa$w;Kx&HoD}gyxG@IJJipC7hzb(zHV#-*ZcWJb)47Ga@6(pF`VqLC%aNC2V+GY135*UR&Uy{^)Gs*T5)wl;yL4u7}v959O zV!b28<3|AZAQBjbJztXk>X*rASR%wR4m!Pt#MSLS`jz2fVjP^fvz&3ozZLf&UJIkJ z=Sz~7wzXmF+D`kGjf1Elan*l-zUOR^@L-0&Mj8?OyK7I`IA|dt3VS}=`_W^GabaZ- zJ`SRS*L@zcSXY167alwwx6x?vdi0;8BWV_hTX zw)~Yy>8wtlI~63@h#Kn}o$pSYNOmpo&>FM(E?x_xUKB`-t#&G0jI{%+oFaQWWasl; zRFGivQr$J*y_zkRk!im-A8V1oC^oCrUGv=&AIckfb5(N8cby6nnQ!*jAM_6rW9_`( z!i}^8YimCC`L2_|sIj>R==%B~;adM0V~x%40{B>q3KHoHFV=4u^#yUmbD^>MLIn3Y z5*T&NZ?S&=QGMas$`!X8M@lu}K1T(KU#IWZe@(0{h&2Td8$&9$;bScl7}ajgZoNk4 zI>NPIa^EnTH)_p&jtUYzJuc`I^ZNr=hFUsXYTPPb%psqUS*2hl|zkM&!(jpa}h+BfpXo-awvgRu?|qJji- zTCB^prC!(5@3pmi5DARJp3hD}tbeHg-qJqSqJjh)QDa^6UH^#MRW-$ez9QZLTyXH)tK5BjiQr5L`W3HKlp7==AwlBPBOY}CCU$vub)5+j;F)%#Ye zDm*xAd20HkdsFT~BrwYAsGJ|N(!a-r^RX5cB)%Szh|#``@SxYHT=eOXFl`|lYmvYx z+%qFd{UZv{W_g3O4s(Ld-MG$uGDzSK7)fGtYTYrXW@BxvIo8I?0p4tetebP{g0XeY zIkoOurLuLc?pW8Nf&^Q=>aLaWq)`J%-T^K7Sc?Qk&3MpH-?1i8jJ1>ecan{%CiAft z6(m>=NO$Fy4DXc2sf!1=&ym0=mO;{8xus{#N*R;(o^#}uoC*?gr*`R;O4JrUAAGO5 zq0jlOirkWuz^LjTyY&fOYKyUU`-SnwM8DL0tVIQh0g>nRn?q{}V($5s#)l!fxzCZn zsIK$Q>z8)c60W_qalg@Kd;#urRFIe$_e8gysUnEig{~MoXO!VSM*^b;XL+h`{a8h~ zwzTxZnB2D5QRKa(a&G2bDtxDQJ2^ruf*DAgllgf%1SqGs>Xee z3KGMnXCjTJ6cNOd+y&_Q%{95tk-(@fD>9Ka%Zmut_B-!Q2gudA&rw0*@zFeFPsUt= zXuGTuefqFE_c;<6#ohuC*IR%JYiiN;zgN)mvauEwBvzL$PD+yW!sjfvq&sp;=pwep z)y>?}fcKi2TLMQ#|Cya^3QKV0mYfO_9wip(lLrKd`ELC|OUdxDP58PNuZ2ON(S)4bgQy@;u)joFe=IFLI6eJ8#+^yUxCfEIDD3%?R3=+W+HP2J?m<+L zSk^ZaIn}+0@Ze>VmHw5v9QPm+7==Awl9n|tNY7p>ZO<)%*N~X~2lL10oWg@uQkJGM z-^<%`OF&>0_Iyd2*sdCV9aD`6=&mjYpRTaG#@sg#VMrdZV0G1o5SKsL_7%2JUktFzSl> zMDNqAig0a({v(X7ul8}Dqk=^F!V;-Ft+XIYHC<)&?RSg&90`o-8Yq!|$4U#=j$L-p zSWxOQ_c*N*&Nm7blQjr$xGBxcVnM_QHtCfncqtSYV1{ZbB|zd{0| z`mQZUIt71|?eB43ZD>Txmd(V+T2zpDUAsEj`PY3x_;iS%E1zZHK1Twh&IPf*|MK#_ zaIL(mC0({V1)o!+f<&dSHZm>zq#)S4RNe6|66nD0`-QT1E*B54;N z<6|uIvyjRV4sdz1n!k*9GJ6}&lPv`xp zn(tCkLE^;GVq{I%^umK(QskncOH%W(772{Pp3i;}=zTF-=RivCK~#`9(yJVa`u

      17*@|{1AJrD@Jq{8WWpz}!9-XLHxreHm zTS5hiKepE;bn8~(!Av{4(M+dqsAdis35>#>>yp&FQBUe|^qe{@bBK9v+qqjE3EYP+ zNh81KCi6O$<74f*4FBqt4wq6sj;ZMVH83MtU9hmy;Fq%ACnjbjwzh?ZYdd^dL8=_s zz&21{XFAz$T;qEBrqznWij$Jb9&+0O3k(zUl&a0K1T(KwpYrM!v(&|_FWbewd+RX z#P!_gNMKa6%;iX)0bgbNo{44?-x=-FZdT1XH7ZE7T3?NfC~#j8`yOYe@?SCB=SX1G z?3>j{*LL@1dp4?^8xO2RFEh<(MDRtoe)GvkBYR~bCz#sIbc?&y$>?!X zxVA$*KYDZLA=TV7feI4uJJlsIJ+}(tj|PFX=1HQO?`x63DDP=?$&?veg=?E1j-szi z{h^wBCQw1*ux~^1In5kFY%SD*_IbKZHTO&)fl-aZ8xo(qbA)SC)#^d}Tv?`?dnQmp zqRxk4l6`e2L9~$j)5ZhltLFP!Brs}uiV$*odne)A$K%-?yxdUL+%tg+66(UnB<(+? z1o7L4;-qlKqTGY%qC-t{lMEYkDBr7ldt=XM=RYQGCjTTZ;~qo>iRjx!$-isU2@kf+ zUDl{}KNt5P5*UR&Uy{c7v^Lgss?0rz3KF~Kl_goo7umkk>HXthjZ1fXa}OecQP}e( zDbu5U#)~;4xCc=|qIcJ7HHKQMCtT*y6$1V&-cm!!@qe;V!cEao0W1&I|w zHuB5T6T*Z42IOSFBfNoo5DARJp3nAQ^({vCoLtR4hzb%ts?{Ygw5`H}bAGK(F9rRs zn){ZJz$onb?6;7H*QTQ)f8!oR1&N{A8fAQBjbJ)gB>VoUn( z&pF(Ks31}7Rxrstp_B07z(2dv%AaR&4=2lx4vWkpGsp6QeWw~Kkt^C(MNz5OiL z?^(#Za7bCQsreV#{`Pg*OP%b@JC^$#6(mO7tV$*nz9)#I4;7=swoi(=KM@Ix8dJO) zIXd*7aBab`fyUoAvv8lIf<(EB3I(p_+JMME-kf^_| z0eQB3wjg?KEleMMAHaQ%1V)Yjs{wg)VzzK?y2x_$&w3rW&rv}lVQertRk)KNw5KY~ zo2wi5IT9H4aZfOr)vS|nZO*%m=-sJ-+~=qup$0T2eYTVm#Lssv=--Av_c;<6mG_s% zWWt$J!nJFD?MQ=6K}Jx zYmJaWbnT^+iaFMzf`ryJinOm&QxFxJj-an=u2jsi772`E`@)H9U-;ErqiI6f_p&+G zqJl)Gm?*M2K03y}bNTkHI;8FNce1%h7+ut9ZdJ1N$Y1i3hk3oR=d(RU+mDm+bvttp zqJl*6VSc2}q2t1XOQY%=TUOoT9z+78u;;T=@!v)o#cqC4%ss-WAhES~9kO-q7U98_ zWT$a0wj}o;5*UR&pS|ycG8!Do6}$+knuXvxNu!B7PXfmeo z5GR6L7+-wHai1fBQFHzXA}xJ73fI~`PBm(%Q@GDjK_XNRBVO0M1+k&AVca|YyJDUN zKmwy4P7fp9bCwdWJ^Sc}v99P6#XJju3KCyaMUZwQuG#GC+J*T&XlVFq#e83j1V#-H zjv$`Lui5PD+7Bl@>5Xx{6?0vS3KGWlND{urR}d4smZ3!lG*-;~6%rV=;$2ct((lGN^NMKa-%TV&>MSyO1?Y@K2v~;!chUs%ukche*NFwHq6~y(N ztw~(3LEMArqF>Snk%UnlwCiNm6z66(01jmX?#?&wg`Ya1Ofp&P3VFA)|uC$izs} z{N11!yK9R+E<>Bu2(XzRL;|C*=d=87`RX)2>o?u>ASy^?Y#&J`crJ^zdvJV;2J}aC zQ)1?pkiaNQ&zJ7$p)_h0U2DG8Ao_^vUM8XmUJztVyGIgZK zBg+})Sc@(~V%3RIa^_@!@L-X%z3AKgf!u>gU=;RzNov{d7rOS$2<|~tkSKUOkSv%s zR(PP*8NYmvYxtD`D*>_ncZ1#2S+^C17`|6V1=cpiYhenW(S9}C^`6Mx~dD45YrV?|kMFokTRl`a3O6hewu~;ch?@cGf^f?k3HLZU*S=v0kZg=g*vQ_B9 zGaiQNb5xKR)hm>&>K7o0Tq)|&OKVFR=2(jaM&()+O1`WK5Uwp!q7f~Y(8MsuT2zpj zFfov42O9qTF!wnsNVM#(k-qZ}38GTZE;L`J%iQNk zU=%yOOkAgzdw=UdtDb+#eU1teMxC1E<6T2p*%%YVG} z!k#Zl-)cT0Q~pY2Gsjv~kO=XJB)R??7-M(s@;x1mW>fC_nz+kX?7$HyRnyh5EUd6!!&Yg_#xrJ2EAHQ zzwD>D2a&)i?D_2PW(2mR6;s~l9z+F+^*%L8f&Fp9gAMDqq4ih1=bsF4&>8?9J)Eyro0_a#(h~5n>NdRuS{>l$l%uL^gq(x@QP~Cm}FR#PPe-@ z?)YCM*lVwD`WzJ`76*io@y+}N(WrYH!!NEbF~?dYFiKq-LgsDs*X^#&Reh=v_kBJw zeU1tekH$A5Yln{!#I9_y#=JteiRp7BFe>C?BQpNh7~$IR*O!cIud*4Y&rv}l%T|9< z?cfSQL}mYJ6x*N}=2(jaM!kFGPeNX;5Uy>yAT3?Fw7X%BwWuJG>!?cPw+980Vp4uO zxWO#$b0jco-8Yq_FLOw^_CT$obnlD}+~=quk?Mjk2~y$&k?(s&+Ib-5V=WRGmH5q< zG#?NrT)T9B6*@l84eoPPkoX#3iCpdfN)R6|*q8_3ai1fBQL8^!A_G^w60WUK-bO#3 zPD9N(H7ZE>J@F>{cc&uub?vKDwQ06H*{Hd$MFOKHeD@~fkEJ5^b?p*Kp_k7Uq~^L7 z6(n+JEJS>VW);N2Vk+%0(~FwxS|l)PX3j$7_Sme%zOJnp?Ms&?R^mQK1&Mo&J&7?m zzaVaxY)kGBkK!Ig7tMMTOv-uq>s?x1_QIYoN%P;_A~WkHau1?{#QiFb$cr3fga^+w zZehGHIF5S|35>#?&;FiQ)ky~Z=MeWGDo8A8?@w-zTp>KzV)=ff*PrPO(}PH06!v^} z_O;AeqwKzl+=Hkf5iwRJ!*?AN9;`U`qml7)2kt>6FbaFVBpqNo;>XUJ!aaxz5~~*b zk|sZ{3J<1ClZ)P|v5tEX35>#?&)%P3%SR8&I`<$dNO*3oL>l_M5+2O7sub;3J%M`= z35>#?FG)Y^m!YXkz2hE41&PKdy~)&Nsfc}Do3N-VEfnBE&G{}87==Bbo#9Peg;sy( z$vub)64^f$Brm&U6&?(Ut3j7^Da<{H1V&-cXYHs`g^o>ImU|EtB(gU2B>jHLFFg3? z&MGudd{yp2BrwYAsD2I0(j2->&D;_yNIXC7L5BWTQg|@i6K^^{e_cM-B7srXzt4HM zbWysaK?AxcYlP+Rr6PfU=~I#dDn*f*xqjz9pK`Y$sk3FY-Z{q^ubzkNky<~N>s@Od z^ID(XpS)LA2-jx0eTjHhs7cJR78N88JXc7!Vh07W>1c?dMj6DMQzL; zIVwo3uT_Z*UGY*7?Tv@Vzcm+dpCf@$#RgX*qhGxgu3dZawbA14R_=3DkcjT(O)`b2 zBKCFdfrDvj<{sy`&ym2Wtt-9B)}g70eO){Ij|?>D+{fJKs37rZS3wfvomCKL8t10V z^QWTboEiy?%5tM186TKcxVCog+_Xi-Y}8!WqJl(pK2M^^`2|s=Yax1kL1FH5BrvLH z4Nr2oMSkJhs_FC7lYf`xK1T(KRXaV%{4pg3@pth;H2S#@HTOUwfl=p6(m|`{h+6~S3wYd`Et{bGXuHLk-#YS8(X^TH@2QO%S_qdec@v*DoFTu zxTUub^$|Y*Iwgc$t#^`p5M7jEr9z5cJD|^r*S)akvvZJJPm@0JO}Gb9K_cvw4=IrK zs_@`1t?C=nlv{kPMFOL+=S$Msiv5hB%sIISQ9&Z;Q$;ei?n~jpeCyU319C=j46J_kWEWga6_lL;|C*=S$Lv6e;QJFJHI^Q9*(C@>>kvNk{WASy`QUF<;$w=XF?czQ;5I&4xI?m;9l3VS{~j}wxa zdd;iBJ%|btMcyRp*H2dv9?U)^EA>28hmW;LU=;RzNs1hsjyCfO<{m@^iOf;A^v?Bs zga?P_NlS;^jN%?d0;8;s8X5h~nDeqV_aG`rtQd1xPc#(aL2c$c<6-{})XX6xfl>Ik zrP(`{z`u?CQ##XTy+SR2bs7o$d(x70HMANTJ~A^g*R_kfS0vxYzR-^^+2wVRcHZahWcTp}+~=quar#OD^0Z|ZL2NBj)>s{%%P_}UBrs}f z_JYK=FblD-YX_1*<7Z8O?sHU-Sl%u>$uKmZAUsn~GoI?xxzCZnsMy8XiEVd2;o6CN z7Z^7dt>->R1&MxzJxGT0B?Pgi%}!&ybbOvFT%V?sHU-*yD3p&pkvD#Luo*jo%Xd zsrlP&NMO{6R)_Uw%N60;0k4l6+joa?pQD0A@zLw`=*<3tn40#u@j8ENKGq_EQ3V&Q z*9Uw13)gnPvD+APpfmS5DoD(UpQ0~c&`1#FTW&L6|I?ecWb0ZaFpB*;rSAH5%Ir%Q z8^g}9zjDmx)Tkh##z*NzrBLDXMQcivkSzJR2hm0H`~u{4ku2ov{LNn2^Cjun&9%gM zvx<8V6(q`fWhc%2@(B<6-z{v^I#i5%5DARJo-av*Gs{MaW)a+js35WVc^Z;tP6^?` zbwQ(yCiNC_4;4i=G#=IkyxCfEIDD3$xhx~fC5%bhW&EIZA1&JMP*Xv)N)Ds>Y*?+%r z@k0+Ea=<1-4Q|Rkhzb(g@hSR0!x{+>h8Lc1i%IV&2yUyY!(YeguiAi@5=yYBcq^=x;-o@}J& zp~~Fn>7QjIcfRH&H$JTQ`ek$)vNC-M;{SP#*X4a_NWG8}!nIjTOebLn_Hm!1f<)TV z?{#@{c|nYPoyPEb>cf4G1V+7?_Fmt6w!Cm{uge9D8@|1`&rv~Q(x)5xv0^m@aq~-< zar@nR?sFtCs(j#0eL&Y5!nJ>s7Dmfahq=#DL1O=Os?RGs-wyI}J5+$fzJuD)oBZb7Vb1q#85bc;Qum`y2_3T32Jep5;J2;o8}$ zCm2;cO7pQ66(qV(o1zyk)<_VE8KxSK$JqFs8VQVQv~`N!IkJ&(ZOX)GV@h0oKGvdw z#F|M_dV$>`f;hZspb`D4Dfc-N7!|Z5N*{6~#4$ro)7VH^xIH!B*P?=ix<9X8-#c6o zw-(kja+c`LeU1c19Xy>^e^)zPxOV=QyvB_s1GvvoL89vS1F?S(jugbo7paZDPlj=y zBY{zk(jJUmHz88E_9NXw3Wbc~K1T(KuIE0)^jZ}q2*3HMNdLWl+=J+%;A8LfV`_O) z^S4!A*z+YRC~6ovT7z;AqJqSuRX6mv3Dt!MkDPczs^qQBJ%|KGVb5o0W%^|>d~QT@ z52AuZ<+@b&oGc3u=33)x>`b$bdk_hX!k*90e{@ld6bUD}2T?&{`Pp^)j+*s^2OAl! zjmi5yaStMaQP}e(sd|Q{#*d-tsX5<81&O)sr|9DzH549fIjWm6mlWY1L;|C*=SxzW zTTw>&#^t#OQ9)vE<0#!29U?sFS+|7|_*~;-t%ZOn?D_0(FTb!E+i4*8AS!s>jLY)s zjea&39&Goey5V=eC9TQkyGURZ_I&mm*k`gB`5SfO9z+ER`shIHTeerm{vKyx+z+xZ zQ(x{uBrpnlz9dy0v!49eKZu&=Yf(XB3HcDSVt$nH;Gi@8$)t@VXe&0~MFOL&j;gS= zw%)wrXlkDMLFGRPKbHqbU-FkXeqrlPwys5jeRf9GKl8zF(aI=d|2w>2MwC*_q9l1)WU30`lZ?-!nNNvr#1qNtla0QAn~t%UcJJM#)24HAiZJh z?#+FU1V+6bkXO%lrm=8s^ILbx<_cB$oEjA*_AEFMd*)|^AUgiMM6#0r?sFtCYSEDc zu~Vu=3fHC{GM%*S8peH&3KAiGKg2u?jS|EHb`B;_`gYvsNMMxzZy#bN42cr1z2jL* zUz(*W_c<#6LHN0d6q{?y%Zm2r>sln(XJ-_1m!HeE<5Krgf{RA;u@)61n44{`v36?7 zEz0=nBluX01V*tD)#e&&i}mqPw|*MI*R`l1!REfQYfgRlz)pSZstE2ubW!DW>-0av z>XIg7S9oF1m!wI7#mJj!*SH5!L88y8$@<}x4TT4<%w9_L5ly%Uk-#YI`I6LX?|M?> z)nx8LRFG&iBvS9cEm(N)_Tek!u^!7khy+Gq&u72sl;;F#G37e#?&(_Wx_mOW$v-9~bDoC_%eIT|v+s|o#j}zT*7il%1H1{A9 z7==Awk}6;CLz*3`#>ZMzkVswiL(E_KqJ#$*|0Wy8Fmed$i;8T_o6NXB75)N$T{jof5dAi^GFX7a_sMM4M}@9q+SF$=R@< z!-Gx&qp;^o(zbjl)#p71au1?{1e?{$t{L)+mW9+5sfY0#G7=bNbyS55q3ZqzL%9c0 zL4vJbWmj&=yGVDnP1G=I{zfAb7}YHNw_nLUJlTiZ}U1&PFv zCUW=(2XQTHNqzgS_T1;^&qU~B(*%=%!z;aVw#uVl3=AV{+OG0?uq=;$Wp$WvZQkA! zbm_r;?sHU-h?u=Uw*8fGK|HzgNWb#1ystszr-8t1Ofm1AD^dtDrMyye5^$U3Fb$e%jb*Fc2~}_T@Ypt83~MH z-n6+!&SrxSE9GLVI(+U_kYFRK>>8chM|@TGeP{VymP5vCVHBIm%B~r*_m?v2EIo+( z92F$k%vpA=YriQ$>XZd7xX+QmD7F@rUF+KBUL(~x{%v^v3Kb++o=JA)uRfQWqxv-H z>R8u0uZ2-8=Onu_!WSxTRtv{=b>y#{3KA?+EW5JK{T?4s_vk$x`70-ZQS9#($*#Xw z^yiO@YQp<&d|itQ66~Fh?0Q$UV$Si{j@dhL52A~9*WDjGa6~xyxo(XY_I&o+hJU8g zD{gtnJ%|btPvhRlJa`@2c0fLqD-L!wwZ(3c>w-bd+wCADJ^n4J?JDb z3VXgJC3ya(9IEWe$68d7U?ZyRn(uD7cumQ6x)k>y5*UR&Uy>Tn&7qE;QrR)zb$Sg6 zw*Hh|>)Q7_Yp9xUUB`UaNnjNAeD=P!NoRF^iH44KtEjs>_QvYKnw*+=Hkf!QRTsu00d&!hWdjhqUGE zS|l*4UAtTI`CuP0)_zD#t)1`Cl76#=DX1WE@XI~9=CJC5U_Q4weExUe_kQCRMvy;q zZ}wuYwV6JjZ`)@2+~yiN*;p$(##&U6U?ZyR8l5*R^;CQhwsZL0c`b~38J|b~B{58l zoD*mDRFt37xX)2Rg3Wzp*POa_!#zrgYXZyir=g_$DG=!Ai-9z zvTG&W`BpJCd(RYnti@|#6w4aPu56U=-+^kY$r-rMQ9*)bsbp6UdFqa#sz>3%+~-JO z6wCX{t{k$QxIjHRv?TXADoC(*IaXb-B-xz^J@6Z^>oK`-pXIwdWtzG9~NsIW;Osu>BLVYhT8n zJ|0?7^M-s*jRZ!qy%e%*r_Fqm-<~Ij4{Yw3@5<(Uw?pmyUQ6drmLL7mfTYf$ zd$HA|>{_L=b*3B%B)@;q4tPA$~}k*66|e_?0WMPynV9TxWjWt z4%vAvjACy|W!KwRueHCatB!p(%=b8`Ai>_s%C0>VwR#e@L6*$igGgW$+vgy=_DuNK zxUR~Fvhn#YDoE6g_E2*8mK5vSk~2T3U8)q~9z+78*p4K{wbLm_LRziTwnE&4s35_1 zKq;>MiS$Y?E&i|<_aG7&#r6~`uKkHLw7B*%YY9HqqJjk5FRZxsA-^qIQOkYNn|lxm zjADC-71z%G6JfQq5?;l)2T?(S?f6$*rw3LPt*ezxD9Y!%NMIEEYnzJeuWd$z2Whz$ zrDFbaD<+s|;< zQ~NbK2lpTieM?AS6!v`fcP%$o&>p{FdwAKqR8){)JN^~d zd7RuawX~-f^6~jD5*UR&Uy^PN^4A8oWWPILKab<|8WP#FR#qO6SK{2A>KCG2=;_Hl zh}Xg>tD~}mMNwcpH^TIrB9e7=hWMtRq+spLKqr`vN&w~DpZ zE?4+rY+4bfpn}AMSGAPN-7g4&y{}aq?`zq69NB!2v$yvpFZT9THs9B#%$#7pua#Xp zAlRM>#j$4s6(rcs2*tI_VrutH>ZtEkxX+QmD7GU>aqV>K^P#5tceW7+~=quu|K$=5_BeuSl3?m{!<-aHny?U9km6eT?oarcA0#k}ozqcVr|8lbucVc_f6sB|$EhH}PS+`} zlX}KARZH9bDL;3I*TSeWMQSQPe~lC8?lPti)S4H+&Cl1Of&@DUtGLeBz8cU}+cy6; zKVNGhAc~!dRa__5)#>fDTrJN!&eu8>ye>P*uDDLcuYS@^TY306KjV(q!YK9&5{m1W zDfCu-v=P7WG|cz4s35_9u|jeEo($Wcs5tf~vVBX6xo;_blc!#6x1nP0PfYvdjk!Nj zaqakJdxRCo9${3FU^{^o*RJBqohqr-*JtJVT_iB7^m{L*=)06+&H1@+NA+z)Y3@N( zkYIcE71vpSJvmmXsit<|9z+78*#3RRb-Jcf;~4c!y*}K7s35^k-6*aTJQc4zQPUlm z$vub!MzPawit7~Jk~Jx`{a0pk52AtuJ6)%^&c41Vmq%NiXF2yE5*WqKt17Ouua#^i zwVSCI@v{J^Akn65fU>dBO5J{f=je1_t(w;g$JtlswJ?gEELU77*0WLBB*!-FJZ#toZ1pAFO#r4~5Y@fd3*r$&!V*7;^bDw_oJzvay`rxPv z6%Q(Xu1)6oT~v@r+*wg6{P2Z1k25`}mO6PwNoqQ%|ro!wx?p-|klI7I?Ktni+l?7j2w(!cWg zoaejAE%%(Aot^WXgi^)$DSal8Kox%T$%p=NZGLY` zCz*p7L4q7zm~w|nmAVPbql}zPoutg4o7A=iPA+Qv^^K9kcuHiVRN^K)rHIb+S_L zEA#ZeVgw25aAm4nHa1N|BX6HAviB7UR8eO+QyuF!M~pEpY(5}++%bX#b+R+%Gf{H! zUSn>~&(dcC2~?3c1XDf}87EvYb`DICeli$AqQXD*S)tc8o!-~=0m=BNEj}{Okw6u> zxG?1oGqqtRu8m2Mo=zA+f?Q*m@^sq$Er2gA_(^&?A%QCLVPeYD>C>8W{CTz`!tr$S zMvx$nHKx4Vrk4uk4La@=j;E8CKo$9|G3AE1eNzOF_}Ikb-R6xTK`x0*IW87ut$FSL zd_CT6UIJD5X2!5F>*Dq&o;J*sxg(!BBp9$(eXLkR2Czo#kxkfPCXJSP|zX0-vV9L3Lyk3~c>jfi7kfRGz z?lA9@wlp|lDVMa#J8l>+Q{9oiY8XL++|!tHV*55Y75`)6CbxZV2?F@glSBr@e;`tYw}Jb3j6-9FEN1gaLlh-S*ebnub#Jju8Y%+5iKAn{^S6q}La zlH+>XH8zwNUb%|dIfw+R$RU_1=izVe`aDa;&&*!$Vgw0tBxcGlJbls@e8u0n4BKY{ z2~?5CH&cG${>|I)&)4f3_TCakkRbnlrse{i{OcDUlCqm&=O7ZOA}@cYCT+Zb-GwJf zm}=O2OBg|dCU7t{&Es9G9(-%iQlmNDYmq=z^Okkk#r)IsM6VY=qdPA$bGKo8I$;C} znw7)U3?A}ZVjjOG%p&rAVYc5=w`;ir@S9Kji9PSJ;8GnueoNk5Ln3>5`Zo`r?@H`s zUD>Lw;oIP_+wM!nYoQ9i`IYcDVP7n%bM_ipEZ*?hy<$en@=8eIa=@oX~s#?aJK2cM=+YezQ*Q(b z@)Tyut2p7&0i%E8!qTf4uZ1e|7iP-+yY!T6MzO5pJzmA$2omH9&XmLWd{l7ButG^~Q?02acL4y4InVJg_v#l^c{xQI?^Bf6Ok(WPH zlQyypDan6Y7G>D?T8tn;6F8Wf=FvZf@n>HK8TP#v2~^SK8>S}eOf6NNzd1g~uzO!I zf&@+4VQLOmhoKGl>dotAo+E)Onq9@z9IRzUBKhhhhvmH%BS<{D6vFbCJgO(Ikn^u^ z%r_ssY}j5eNT7fcL5v_l^QxGdgOw^GnD-kx zU*;eZsKRf)rVX#D^Q&FA$$KqEkf4ckOii!zKUtgi^EoDS5D8S_H(%3Q{8oo&nRr*` zAV!d&*^o@loD6Ol!CN$bFLMwHRN*&Y(_UYx$1C-wrxsf8Vgw1A?#k4p*fCEV@b)P( z$s9xiRo`b++RkBoclKP|UhiTA37X=})Qt6MX>0QupYn6NCk_czRW4GHy>mwAp6Bt9L`nAxV7L(qI2=9!O!SwwR>m^~loL;1?~d>qKA zdg(5(Egy?A+uIN$NIcG4jpeMjUQc|ky^@jkcbjgJIfw+R@SCq`>5mOF2L1X*<{(Cp zplMf3&7zx9c(bv;56yO>97Fr9aE(S|m_~-+WCw5SWVxY)HfH=UR*)L6g*(n#$fUMIk=-grCeo zBv6Ild`)}*Q+~dzvOl-?mN0_Ez~9obu<`j=;(E8*%0hfq{y>?7NT3S8`I`3PNFIK< ztS)m9BS=)d71`ty^9ef26ud{m#k9G z$-$hjGVupVqq*%Djs&U(#y-}64=(52IcJqh!~5lK%(E|xWEeqW(EB_3g}xOW;_9g| zw&UYP-F~j6Iath|gXJ2n2iz-Bg*EAPL^tQ~0Gcw#)bu)1PPkr%+y5a-9yhCe|%mq^Bf6OrJPxSRc1ac@ws;U`RhjN6Nlx! z79&W|ymhALxHpXdpYiLo$1=~6Ko!kiXX*B2Wr=rA{oE&G&4MJ{ey+s`5)^x&1)*}wMd}qLY6bS%fE_~wI>@t zGj>I_mG@eVAW>-JcKwQ9HHV;?lgu-760?XVNHTlo>kO6DL&kf15fOwCvy6*SLS9^6mnAQGs; zZ$5d8{JzRqv}TsfL5v{rGEEMaqH$K1_*{E*;SuA)zI`$Wkw6uG^J&jA-D#s`p$jqx zF@i+Zg6Y_oO!=IwO&k4>apJ;9nS)563cvZ9_E+2^<6uM@nS&TXB6ly1wRm6D$-($_ zAB%WGrL(Hb%bF@i*q=co0PNvk+HSbo4;<3X`VnS)563cvX@m#q4Iqrk4FG6yk& zMC%pX^@{1MIXO6E<}IUSP&;|AMFLgdXA}!MVI;5e3%Ab>Vg!j#jppiln%YhdMz@Kl zqifyeb1f36+WhleeN5`w&YiRNnjOZKc0KsAv2__nkk}SKOTXRUL(m*|=9%M8^PQPJ z-#J6M+5t3`o!N8Tmlp}M=eV;5_kCI73c2ma#Vl~oYPqJy2oiseNy|c7<#mY6FZ_%N z&5Fo8M*>v|?zBu>nwKR$*Jf%|!N~BniOh41AQ5x@o8CLDs6(9T*4ywC^JShRfvS>u zHCBCMQ73ELryXhJnYTmcIYy8;Z#>d}Z5-$jg)%NM9^SYu^Bf6Ot(p2rUpqU{$=aXR zE;Mph|18(k7(t?U^lAOtfXWWBBV>c|OMDh??;#_Bs*W>G>wj&n>|`yUv&OiVkWc10 zMv!r|*V(F0)@HA|+AxxHndcZm!YA)s{i+%2 z5O3$NHE!gMka>;-st#3|tKWSP>SXQ18}p1BrJKq;#|RRC*X*tDI9b;rM%12dwCLYK z<~b6m+S|UjzV%^UCu`p}9$|D!+g;{4Mv(A(9HeU^!XZ8f_cWGW=_~KGNT4du+aP`H z@dzhtFLbSLR2el;uBkDCMBi@-A#Qqyp75PMK17!{(fhzpwYg*Hag^gi7JIEZw z2og0P{iBCv4Rmrae|&SJYW5W}2a!M(e)BbL+3-$A${uc+gBU^Lk94Q?C&87S9Nar{ zf^jG6smwtnP=()oO`Dc?g0bXoQf}`dV+4r`DYxsRJ5+UYaQ~t?M#{;4G6#`B6@K&S zeQl;`#?Hz9+&-s|5hSL3n4?#o66)k&mSJ;@f1d@*97FOqm|4-j39CJFZ#Cs9^vHR>nRnIxCkKCeQPf!Q+W?t^NTBNbjQV== zEt}PHh|EEZAkk)JT*&JRF-{KNd~=vBKQoNmUN1X zNaN3a1!SHhfvWV^dg=Fi)pfEq^kRrnC0}WIuf+%w6-NZ=$!bS9#Lc5`dD6!?M7L#oS*A2SWu7B}s@b#SLW&lRak92(w-8pgUYxww zVg!k9V~4EFwcA6){1&g5O+7^BITEPKlXm#Z7Y99Ad$i3Fx0P?0e6Ga^5|ocFmFIu& zC?bqw!}-PLzq^n?6=khUWo@yW??i0jVRFZdDuc^&-){V0g6rwTC|M1V*0j)thefYZ z!+8B(br?pFpo-!8u9gT-EkOcR-~UxB&szF}x)HLLr1U$bzib}NPF}7bus30={+4kz zq+Ejle`A~8U$KIUb(QyCg%f5x4V;rK^yEXc} zR;}e884{@4(O`tyE;Fsb3hx=NGQWF!CMoI>^26XoR!M z$lGCsUUbvXGS4wn*~8iT{`|Gr-<28!V0LL*+~Le@ZNwFs=NLg^$H<;~rO0q6&yBPb zS;-sxZ4WZN;TE zEL*9oGS4xB#NnfFL+%c5=;XQIA3Io!y(wg#BY`T+F536$F^P>Dl11h@Mv$m#^$oe% zgHB;fN4eS?M=-rmF`4H`pbE2#oycViNiJ#p*7pVV8 z`ao{Y7jL$H-%YLn=C9xGE|sI2jL@E(+p}9odvb2I*GD^drf264BS_HBom=hPWvjW) zZ2o62J}vUJ3kg)=U#MyG+AcN&d-UO*meO|(J|PkzJ$t(=y{hYcj=47`nU$Z!@%MY8 zz9Ufe{U<*(GMQd2RXbU)N(WZdN1Uk7PFAlU@O;&qke6d4*^aP!0SkTJhV;Ebrx&*IbTt79~n-b zk3EpdT5u#v)~j3bnyB5nn2gZ-dbj6IKE1DZt8)PKR^Rfx)yD`D^j6=k-s;!LpTcsl zYsSxRU*$pqRrnWb+S!P2<}YJf@(CLw8Agyum-&o4U*Rgw=U7?!m3e4eTYf&I;dcb8 zzW?M0u8wx?Kigi`tM`X`uG~nK?n;}mfLgWtxYC!1V*l$~JAkT$OI07LS8h+e!Uz&n zm0YUArD^}bz3^chS+9^lRsXJUT~o_8bgIvwN!3N!_rJ+{g%KoZ9pqN)t7`}6iCr}; zS+9^l6|ITf>Zzz<eAVE8x4L1%x2I#aaARAo1fBO2>Lg&nR{5>3 z6KnH$pCk5}BJZ_Ob-8R(@g=aRljnV(7q*VIsllVx)MFSyV(rRw;?~N14ngY@w`W~~ znM$h+m%T1=>9y>231scbgq7|!lka%eCEf@UEr(QeKgid>S(jWsQ%)4C+RC#o@e-)Q z?9#NA`6mi?CGj~5BS_HGl3VSUq?ma|1gCP#JVydmm|dFIx22CcuHt#meu+1qk)Sq(7O<~ddCvHX}p>CNG_S@cr8?6 zcF~M=*D`a#wgR4aEZ%%Zg5GAj)tk|WIro{Bx0IF7QFtv>VRq4coYm*eTO-QLJjVzU zbnd{d&NKM(XXd!~Oy)TfsKV@`nMm!ET6?E5ZhJsr1PMAhB-AOSug%k2-CEU<>k=eT zh1sQPt`<41UruwG=NLhPP6!Hhes_2Fg4WCI)nuL{fhx={P5XICN$beMDso+d5hT){ z${{vq&E`Bu)ht@p@{g~~4@b;)A%UtoL$Zi6KmFunZST{e*3nb><+`Nqh7zJh)6cT^ zjn3=~&uM--voBOH0G;f&JSY1xf&`uH7wTkxi9?39cz1DbtvlyJ0#*1IYTCh8Rjh+) z%kWFSbs0vGaG%H_VtunYpCeBbn*SM8kx$+h^&Nq#?>{;1`?x*(KAH3Oba(y|#(KZy z0kn(bw)cH{Khf=dAGg}ArTtyu+26$o610o!Ry)Fxw|0w1y&?>IE&vj!qBk^d_2y^9 zyw9TKlp%6mf)OO>jgVWtT`IJ@qWSmujj~=Lfhu|v>sD`g{~h1PTt42E^$H_M(3@Yk zI+sx``!qAE@mql z)+@Xgs_4{{P^YPejJa#hG1JL6fqmo-SwFY6T&sG{@9LUj-9$zIf2;g?75?_vZA>M9VbLt$F_ z3fAFY^2>UK1gfs*Ehw(+^l_e}0+VuUO4FZYy}}3*)c+$?U(wMswXJ-voO0g>2~<%p zkWig^W41+FV+&@M?}Rae1oiw0)eX3*UbOXoY$o2e+)}%*$a^hRy&6+mWPbg|>Bv2~ zH`bc5=z(Fs`AM>|x~Q>!gN#r=ukdvGQa`UyeZtiBYk9hUF@gkj{R-9f+pJ3~tKx|N zj5-z9x{yE>{)L)WGkJ6C{y)k1_7;&0BS^6D3Zm(=yUyo$+q02%uVPwWWN^dp2vmLl z$?4s;+w*Rl-bcCZ_fg;S2HEen-S)ffMV-po@3!6Q-S(s*qs7KK`{nuyBS_F$6Sq3U zlKVjlbHJ-0xxPXIRdnvetxkot@DDT(FKjOB6-JPt(_%uMJj=IguvzYZvt_+P0#&bH zrxpI!@;duIEf>r+eO|AS^$H_M(78^b&WpCIAYWzmCsx@PnS7v z*zcn-f&`t+7V4DugE#+~@qga+oEP<83suw+AylWuoi^#LmEG?d_8At8AVD1%LiI=K zW%62^zPyqBQAnVQdYXjlk6QY!xOJn=3r~NPH-g0IR2774-d#QMl=rjIRjj?K-^)Ho zycVjc`%tK^#!N43S$Stam3@#HL4vv+h3ZAV5*=k-dh$&6K_Y=F>K_)W7rFAj=2o#5 z*FC++-Ut%p4InysJqNOviM5PYmkg&D*-M~`d;)}W@tBjWtM&N60gvZ^H-bd-mUV=3 z3K{>Yn{{gS0V6*50T*5iRipdV5a;68I(eS=&97Fkx4VpCh3YemAhEo89kC$aG>5oU zIgJRtSW)hmV5ZV}7Poz#<^Ax|0hnF#teWtgRl^7pbRtct^P<_zEN0HrC1su?fhx={ zO*=fks`-RBka>;~B*eMw;(Fe!&JN2}Ho=@be3Hy_Bv6IfMH7f0tT5BAoh$PkBS_Hc zZ=rfKjvPB-w#~3p<~b6m!tBztB?ljxKjqjb^Bf~cP_L9wJy@wuq_li)p7Hc%cq;&^ zFuQ2xOX;ju*zD7u9xQJ@BSGDcLUm5QnHXUGI_|p6bG#O+FuOD@N!IdKZ1xM%a{wbq zP+zi8{m!=^Rksceyk^*E)sR3HW|yYTzf<4x>vY<%pQA8>1UU-`(Kx%yh`f)^Sgn`gU_K-Jot;bPzXVNTZmab~df=kI}XU9urVv>5Q) zr4ai~RnM7`V)o-AQbj&qLiu?8F>jEyDxj{>yGuB={;CKP7g|M%m$geczoY;BfmW+A z?Tvp6UUDIUD*Own!|hsst90OCBl*~Hh7lw#eXA$VZD{ZOj!rYh(HP~vJ8xH?Z zQ1$&MubPe4XSaN1y`rP2@TvKiglPG z*CiN1g8EH_>SGxkSHY}N$w$^JBv3`YCqi|G-E7&}%$z2_tXCL8f;z^8>OO0pcBT33 z;m@*OA%QCD)D)@%wD2&~EU>PPtXCL8f;vNm>f25h|J+PkZH%l}NT7;(t%d5_-jhAK zm9F(@`5c82B<_ExCL+^qa9mYlZ|Ahy`A(Ph3JFw^D}qpN3!VQ8u&QU8DC-qQkRTTZ zp*&KyvMSbq6H{f+C=#e5UlXA`QqpX#Wt}cKO0G*Vf&_UM3FU>9aN%d`-i(p5ULk=h z@-Gs~U94{5)|M#I#^Z(LjUYj;V?sHYu}WR7S_@-5UPxX7Rhz~~iYK>=IL<~fH+xwH ziWQgj3L{96cb`z6fL&`0w2HpXF4rYUpo*OTgz^M@czcNTdxNvg?qk6S5@~7D>!5nU zA&KYP18)tpt`>@?_bQ8BNT6!b#Axv{=SEqTG;LV_;ns%YC58PQRsVjpnBHrF%dS`C z11dZYq2vQ9l)ossg<2lBP>di!ZlOZCg|_@O+|t|C(%0Sl!-WK@@GsP~ts{n8DNgya zk*OjXMvw^V6(jD42RommZJOcM<)c&C4e~oe0#)CCa_W5*p59mLoD+7h-MssLcJHgO zdtY}o$ZGe#3f23Xv*T&;rC@DYuP}lH^`Z;aQgmR`RQ+c;p^;8;Jukc!^>eH&Wu)0ij++p^VId6U%;Unu6Mvx%i z7oq%QR-aE|rJ0yp)+;1XMIJChIW&FAo6&lZJfo~v7(s%Zn}l+Kx^d9oD*sb9S+9^l z6*;B}<-|5%b)Z#d>IdoFh7lylp-m|NL|?s@m2&J0>7R%Ms>t(DDF4JA=_9NQ9oBjL z6TJ~6W*3YRn^FdcBtA!VIoQg|-0e5!_$PV^RFQM2P>!T8K6J1`dtA|Np9zd0K~AMY zxt{hZ+{;@0X+wzZGl2xELN>*SD@Wt@C;CjBZx&}wDp5q(@6R!U1bGSzRd=uKamP%hes^K_yNhiZ z12DVDrzqV8;qkJ-2omI2A(Wp??JP0oMYf#T`@2Y>3bTuLii(djlXlze@ssi9GZNFb z)D_Kw+Bpt1lMd`RZ-m~FzEOBBRAF{$TK@%?%xlXoO5Z4qAVKa>LV346Zjju{6!}7W zw;_Ql%r5c^kIrl@+IT{GG-3n^@=_Gaqw%lgMXeU%ICH$)ycGadm|dE7ty_8PLGu|N zk4A4kBSCJcLOHAcb0gGpXYa@C9(TMJsxZ4Wt!3&+E1Ni=+g=tJL4rJmh4LzH*S)n> zcEY?6yT29*RAF{$TE`n5tP?Zy2;0j7BS^Fq(IQ8q1+GLdizbVET9JcC2>bjl5~#xL z(zG1!`&jj~yE4x)f&@8_3pE$u*DV9B?M>3kxd2F@3bTuH@aRA*?3C`A3*gOXB;sB) z5U-xsawo1!`aK+EJ?&7}JQp&@h1WvWd73g_zkCTNYmffb%PLW3jcKn-POYjXDh*#E zBeTwii;B}n$e(HchfwoB>i^ZpD(SP(Tzn~vVFZaUAH&5!G0gcLQ4iv*cE3zDb@Q4F z2~^=8fdi+Zg2X`iu#T~)%Ty={j{}6 zQlo;bSLD4TY|pE*15yT%7nZQSu%13j67b*S2Eun{fa9dIx9VN7X!k7L_TIq=668lG zl+PV&)W(eZJ*ixmAb~3KrW49J@=M3bX0s>PrPm}zkRV4%q1-7u_c~}kIr>Dmy?2m6 z6*;*Iy?CEukc!^B1dzfoYEf_EN_{M)(G2^10zU~ z8@o_$?77C)vKn8wDeQg&Bv5sKbwlxDkdHfYmCtW2;tHK>lu~U9T{L1Wi5>YVt|<37xFg=f;`#x&#SSk2fwk zYYN+obJ2gV{mG+K*xtCi+CT9pKU<-^anC%zFT(a6aoP0>BS>T~PwRHC2lj>B?aVQ& zM@bKCBv3`Z)k3+-r}Ld`-pGzVb?1pP(||_gqj7hbV3GeQXW6ku2&dA z;zQPO@hs;EcVfNr$y&(jy2dc=dW8h4Xwr&M6I^~DP}~|5+tsw|6-JPt$u2_8U3&AX zid8b(Bsud12~^RnB%$Umy=%g);N2@_y}}3*ZAx&_u<<^p!UcxbwUQ0qXWHv4Bv3^Y z$Ap?>mUnPHYwF|kvR+{X37T*w)U>p(%cHGaL61y(eT4+7Rs{u%T)Qtg)o1p?hL(8# z&9r?vF@glmA{1)IVaCtV)_;9dTeepi5~!lNghEXXJ$1W*)qan!Wqadd1PPiyD%51s zMh7CSpJ!&XcI?>aLIPD6rd`R=I5N1kBW=HyR4t4?9(cyZ)G6((7J$yzViA1UcFZHE*I;lQ!nqE=h&`9EAj` zFuOGE>+s*qxH*kvo?`?FV}5-xV@*wGLPhJzra5NvYMJLqpbE1~)5a{lXcjv2K;}6{ zkf6yfLQRR;nlGu9bBLd5=Q$Fn!tA1XMP1WcN3T~k?f1?YL4sy52{qg4NKiiOLvVMQ z=SZLmvrE&?9QC)ve^X?hV+0AByC&2`wgo*ZS~s?@Hf^6GBv6IfrD=h$gRScSm@>~X zf&|SX6l%s{=kztLfS)hPJVydmm|dE-p;1jM^47mH&oP3;@(*Q1pJgwdsfbnG;a0g> zNiBO_f&{8CyEN_P`P$aa_zaev=NLhPCYA~{Px$HVFl$eT95T<5Kow?}re)bw!>U!i zpk?ouU<8TDS@Vb+BQlD_=cvBtt6O_A2Us0H%yA)ssz%WT#I#{)oUGj+UBW7RhRJow zfnzB}x+R5WWN}0m(K+rX`7_N87iw-edsD`$Jif9ej4*}~B&yELBBll=(wY`IyMk4$ zPetqWz}qe)P=$Y?rnTJ^Z0)&J*2>mAj9~GjD?+8?V z|H)gpnu>)feskOPie_^NdnQhY=I8urR*tY|<;41)@V^@vCZ78acP7gndUr`Yn37Z2 z>k^D0L9?WUno(6PM~vCO&~jn>sv&_YnkyyLjH;)@Mw;XA+?MqUBS-`W8)9fDw+T%)MUA|F^A2lnRQM3ISM04(8M{R=0Uza^1?jcX_Ty2NT7;l zI0`invfJFx=AU^M%6f$nBntE^BZj?v;jByYni;H~;d^DhLIPDZ300^GtK(N?u|~c* zXAYxv2}Y2h$*V$5ajnxXpLO-Zzp`E-fvU)(0b;^}WFql7s$b6h*7}dhE&DkNBS_GU zWT9p+xBIoI^~;$omc1@P0#!6GS*U5|VgK{Dq8jD1?B^(qAVE{kg_@ZD^?5OC=T9YM zy+Q(28S7*bJ-h!T68Co>_A6{vZyhA-6-JOabs(jfGP|%ttc@yc#ygO1b8EM`6y8Cp!Ao+96w%6Tl8U#7N<6S~>>vY>@*5{B2h7lz8 ze!Sxj9$3No9sg^V#tLiS*gEgp;z9yd_!rV{ZB#}pc3-p=UO$3i1c{`%-?=|OF6I1= zv#qmR0}eH?f^$TDN1*EaPu}WGEm5TN16i+VDxR?C=uNxi_NV!J!k(|!@$GK^h+{z_ zSH{1cdiB5V2SkT>?1S+6jH1kHLDYKC-F z=~L!}0o!H0LIPDZ_gSbJ(rnfR^UC~F@;M44Nc?v!vj~5bQzSk|Ee!nEY~Sp)tXD{& ziYBxRHTnHy-PfjX+LV@kt`8$f&_sCQTdA-}bZ_;$o5cFoI)`QNQzL<@TXR#2ylo0Q z^=i&<-^@OB3d?$h5hTJ7B)Au^E9DU7{!MPZoL%0s_kEB+RlZjV?#stZiNsy!A?v@H zrNX%-XX-%&3BTa$?qVf_9Aa~cBv$(0>soT38VFRSkGbxStr6r@pQabym`nQoY}xxh z7(pUg-+1@f9n2xl9eim%NZZP4M$b`5plb2(cz1%yoXRli*)?-bw+?cBg%KoDEm`HR zQ?8~%gbul8hK=cDm8`tmg#@Ysqg?I@{~Au7H%fZe?0ozeYs#<&3?oP^TC~bNw`@&^ zIFOEsbEPz4uS+mf=X5SDK96|rJ~D5cKV}zsS(M%@JTr1Jf&@*%6>3g(vSAg>v?YDy zoN6Rch1sQPH(E6@6S7v6d5#ezCS=YnLS|xtU7DtsTV_rf zzCh+VMv$P1@IpZKHOQxtacd~uPR z=A-{K%ib?R0#%q@nl>})rdg+B2Fu$vnph5~VU+cgOeyIeFf^`oHF`ox03(Bv6IfMILmq_svJi>d18oMvxfX zJl@@S5p(kVXzd4P)ow9zU4jIvFuQ1uN&COe&+A*tJjVzUxo53%_Y0`$L=7fFSyQ`2NF+TUGt&d(iRx1o%5x)9@T`nA6N*|-$r&aX9ae#h#M!_9nC`&*xX zufs5cL_+{uJURH{hQQr}$`u>yGr01})=lx~9qM6>}-+URwrgeV$|zH$VA_ ztM69%7x&LB8du3F5`88X-JdI>LN~~D2}Y1Ow=0FHQNNHwTsW4+{B)?KX+K9HfvR=S zQiv4O3OUthV7rp$t%3Au_Q}=AC3qWW7QHRbl_UbyrSb%2}8A zCiFE=7T7E66-JOK8Gg;(yJJO%SafH)>2Exg^$H18jh}PPoq2Udr~2d`Jj0A{q*?a9 z4@Qua(%wJTvK?YO-Eo1c|T>VvS*uMo;ccE)+>x4QFn8UyZ_bt4pCvrXtU1OPO@GhfvT>@ zW88b*)_1DU$*@-D%L+YYy}}3*dyo6M-&Aer5aoB(GtXY@C)XuNpz6hWKljx74V}sm zRU@x?Cg)(eF2M*AVX5}IR*sH#hzqZ?nYZ3&+io#n-7u@y;|2^PNNi8B*L8MewDUO%Z1^O~yN6nT zlCu{QsQUhsXCM8{U1xU=LzL})LENZaN3O4sKvmi5mOINh-KjnmHoX#k$_s1%*od|7V0tXD{&YSGD+?#;n9oa!?nV}A4BB4^B5wC{rvBpw8g zck^X+9HML2U^9KHZ?aw?fvV|k#=A#8sN+E(qrx!F!>?|YKR~SL!b#Fg+&J&RiQL|nFb7G?!a(#sa zs?sj-bBEDcu*7|z|DI@O<;C@7y}}3*a}MlrjV~YV5cjt~6(5JSl>0tNpvro%$Mw2- zv{QY2eqSK2*6bkb6-JP#x%A!s(fwl_qHfcUB79FzS+9^l)jaWT|6)1~n7HpVynB#) z^t3oxuQ2leh$@OmJ+hWAvJH{-3JLnztD7KO~RX$x+Q9WyEqua~DR@KT;3?oQT zWzbbkq$+Aa74=>VRrnWb8dV<#)yMk@k)TQxqUu%oY`Ym$I4^;!?>{-M;SA3jj#gp1 zXRStSINh^0q_v%{R9G(77>j37blM_sK&bEThT%pBQQ-f@sX72UgZbswB@F4piL zA17Dg7(s&WSGu|n&PiU!SpREJ&z;kIEmRr1{q)d)hMxPmmEE{m`d9gF#|RRX1tBV< z>hlCP)F;+jLOZEQpo+39L}l%`UGvzq!XZIFdsX=!C+ttSN@tg( z8)Dr-`NSWKipeU95hU8Q*yE~TMLERf%+*Ce3SU{Nkw8_kJbPS|`$ai-1OMlf#ll`G ztw?%ni4i15X7Y2_p_6)vJ9nvDjTh0sU6U(hBvAF@QVw_bgb3%Z)-?HIaX+0U?`jx9 zBCLP3yVu5g4)JB(AaQ*1M0w{#0#!8&M!SnPtLNOEukPqAqJM2BpC&MZ#IMK3x#N@8 zaR@VgQc>jeHMs&n0#);;k8?lRQd?v_x!9ljCT`4dH|*0yt}-x!MA_6U-G?Kpi=Ri> z#Qh<$?yLbVe;`huh;oleQBTy0U*eCyThoq&9(Ff=e(Q(73W<9Qa=6bgk8nOm-jwA< zJJ#xlPmU`5f2e6Y78Vyr`%L=b|1J_2F7I~T2#9k2J%azOBObOq@Wa0#s_?s@X*+Lc z6w7|O@x!+SiEXnI_CK2*?R>9B9{cRB(=wH1zdy%op$fm#^iFu8>B>3U*Rs#aVC4T1 zRa8c8P425Nxc6g55$#oBZfaVqse!DH_G8u}v18VrkP}~{oXQ{)#Kfg9NQUbhVNZPtqFCH@2|seonj=s<2jS+OB0GMkCf%u1he21U>KQ z>N#qE&gRB}%Uyn`)TqL{1idloJ}5@`=P6SpS$`S<5`)ua$Q1i zlyuKKD0(-gd)`gaPO+|bojZg-G351DqI4cK+|UJF(D7it>q zIvbu{XN(|0yUx1Wb&kzr83_ftTa(&FF(gp+{U<;2Z!%Zv>ant3ZLhxD)n{-+@pa`2 z|A#%^?jJcjN;I0X%K!0&xBKrsi*l-uM*oef{y^3%jQl^MiXvv`7!?w_zMZUBNYKw- zRgOvtRsO0P?Npz9U1#dlG5Hq8byT?t=v;|H=yG zzwW75-Ut$OztYuxFk{pPmghkVPrdRIsQOmZPcJno(z!e9>EE#8?J~)`Ge(f0=N(-= zM`g*7%ZTmjFINCapo*S-boCrHsz9j0I+yZ1M|mSibe=d~&s!kOsaKUlyBjlqHRMVL zuZ1ewZPC>(&XM@3#-iahWWB-&612OctDT|~f9JWf2OJCDjCpM0A z8xQX{l=TWDNYH+=uJ)-5ygO?go7Gg-D+0P$y{YD&H`N$Hg5E*v>P;~BwA#Arzg2n%2}7B zsgaIP7~D|iITEPC?4n+>?m2j`lJ(@%Hb#)3(=be(tf6x<+;dI_2~^Q(5vI<`Y#42D zw{sqj&b=|ui9b3I$2_Oz=wuyJX9tHL3+D5S2U>Gz?h;0jpwoLyodhh-%JcB56=c0a z0#$T!h^bRZAqhqK>f9mn{}o1%pwmK3okIGnOn&~YP!;*_fds0SZB5B$4lnH74bnwr z@9)Et?GKi_21uZa-k9p@%tYz4AB?^8Dtq3gdLu~CTT)%U zeZANJwlRE88JQn=EmRGNqTwmd}P_^^xI6W-7j0Vd62JxpBvuR_-%XK0WsG_HBUF{k)J5KwELtDr_eT*PMPsO@=+NS4o9iGp<*Fsg+ z<~j7U;SnO}{Z`roxR|l9zG+(Gl}^es z&k0=2E=}Wa%JAUvl`Sjr{H`~jk)X4@%yase?zLk|@B==EtPFT9RAD93wEWux_@;Z+ zfq)_;@tQ4|$FRyYU8q z!MBXAtNeeciKxQrs%d{z{$RvpD)K|!MS@PfF?E9O@ch=^yTcNMui&hgBMo(OH+= zPZq>a{aX5mdo8N)uB~a6k8+;sYJgmqU<3*3DqyOwi24na_PVmR)6TDM@BB9H zc+kJ>8dI*`H)$F=v^rN%X7y+Q(2WB+$m zKUAQibLXtk($8o-pu4PB7(s&0v*_xaOi)5oqr~T*hHjJf z3L{AL%$t&>IbF!9SL=(cHOfx9=s73jy%wtIG#yi?^e!BaH!?Q9ZQAE#FoFb~-ecdXi#cduP}lHbrmqxq2QOVB(K;ngRECbpsLEF0JeL3GG~RnCVMdN zsil$UcQJwl^)WHkAJw#RP2M|6I=QAs0#(%0#8g+~?pY0Z&XdVyy}}3*)a}Sr=j8ip zjd_MD$z;7k0#(%2%v6VTZxas^59q%lf?Pn@`f80SQ!LcG0?hX=9!|+cW9UfDt5`b>^(c%zaLWbi3khc=XPH zq(1`^sKV^hv@b0>@l6ZP%RI*j66C_bl%oUrGjNYT0}`krmjb5z8OVo)+deF*XGJmc zTVWoj8S-Ia9=8^9bYaS~W@rEYJR$XH)7~$^2omHP!;}L}^W1&;(9=^)yPp#YRFPu^ zQ|=c{di=^iA6_ZFcQAqkxl}Oaeo>=tM{Z49@A1pZeTm9VAAOpzd6zx_--_ z2;vu$ANBMJd#{D6WM?X|y6l2Gu~%kcY;oST`B|BR7(s%1{+Q|?JbN++e{LR>_j4pr zMZJVf^(YSLk%lMxc39RDj35!$HGrjSn9SKPc^v-S*t>D7>?=Y7Rn(!xRJT+5BIk^v zOE;SKDGQ7sLA?%4bvv!Ayw><**K}ETkw6voP%zb-(Z1{yqrlK{vbJLciAAk5vor&8 zI_t#CS8E&Dir1F+4usLPXK|as02EQ_aw~VGJ{s9GaNN z`3bX2)5tf9gKv~KpOGLBDdusVB7Zo)-n>xfHKskm9_l@*D`+W~8k-=7;=1VpZibY{23dj&n;PnjYE3cZpn=;I&YN z*{o?7x_vNS7F+g1o+CkB%}jMj&ncamXB)ZohgyOvtV)^|+&wRU5VP@zdW8h}C@|&E zknPt%{*?Sb?fyZ$7OJowYg+6u#vkV0_(R=Ag4|Y^a&CDtvpye_Zj1Dd!fT-l?-H6; z?a#(M_vU4$-9LyCB*@>1Dc`94IbwN_-xf!G_eV{8cBLyne0RbR_dz87yVHOr zyIadymt5N0haY)4!s8p|y>p@p@7lDco;QFG?HnW5B^W`1-0Yb0vm~E8?(w-p0#&&B z(6qM&hSM9~@zQ^n9CVq-bC5LK-H7X zm6%`b-;UeDsRjd##-CEidW8`r$VY)Ge}-FYHW}gV17*EJ0#)Rxz?45jld;E*fBb`F zy}}3*88*~p<@YXj>Q&?)AB~2GqGi280#)SV!jwDA%r0qoyl*{OuP}lHxyCT%8`bt; zem?SPb6KyDKoxmCG36We!YIW@wW%ZP6-JO4N~fTf^{nNr;Tqnm%Ad5TE7x#Hpo-k( zm~yRaKD{olR<)F@R~SKp-0YZg#;Z7|Id>KIm-PyX?^I_RvXD7G&I)_;Pw9NRZ1eQ;xki?+)fS zGZYiesNWf{g(`B>X3Cj+ZQw9|F7JsD`~(^s`)-U<8Rh&lu}e zV6WqZ(7AZH@ulc#ndeBL3bTv)g#Q>}1a^BQeONGp1i7s+<=oP0!49MS%^Wh%kw6t@ zm!?&kan`6X&rjw#Mvx$XC#HO(>PBlkx^x+t=SZLmvy0|txYP5r^9#v5#|RSS0>_l2 z+_naVdF1PoGS87f6=s*FZR}i@yRT-Gd5#ez$aj({Kg&a@YjVA~ugr5KP=(p0X$y-s z;3u*_5RRXvH=mKXGdr3c30~kz?BI#|uO+Xy;e>GfEWHG(FuOD@&Fl{R#+RNl&oP1o zx$H9Kvwh;jd4-bG#O+FuOGEdY7R*eWPV^E&xW5AoqW!CJE470PdL!fCQ?@9iOSW05t!D+w(tk zn*Tv_KA3013C;gto+%+T7lf%ShKYuNuDNTBNO<0zIP_EJcq`^CZA zJ$Tj!N0{vuh7lylbDb&w_Tf1ggj(nkkQXpXk;+ca0mm{oTa~666Za zl-u;8Jdu3RgZ&|nKehK-sOniEhE>($_9yO_+zhMDcV|c@Y|jCVAVFTUO!?McdS9Mz zxK~Bk`=UsoiaczY^2WVi3g*?*zbdeJL|;zYsMS@d$~~FKafBbIf60eF4p$%Mn=}Zr+d7@yb&bG1&k?o zG4dm0;78^qP}L>A2CMwvBKP$?83X7fV3`;;Iolu7LkJ^Ckhc)Cy@iSlPea7OdINdO zvh9sM1Ydr9w4DEe5hQ40 z2vZY7t{biRj!S!(?GJ|ps_-sB?^t@b=WS-DF>HT0j37aCg_xRGWcBOL%RMh**nUe$ zpbGDHE-E^-bSicsj-QBL`4j?yOX8Z5%izpC4p1Dl9W|Pl0 z^Z0CI1POA}X3Cj+?38v!{n%vEXB!Drg*K07b*lBy+Q(2@s;YZ4=JYUi7VvHTN?2teOJqRg%KoZZX;9kAOr8W z;+o%HIbRJ4RM8Aarlz=Ftk{aL$$3uJD~upPlVX{g6nkrETYhffU0JV?Kow1KW@;kz zlNBxb@c(^~b6+un1Wj>fYECsxgyt|2+IuZjHF;5)sTtBi%foq_gk0SAjjCLvAbacb zVYZ)k-3=vJi>9A-`)8VX&D8Yl*+U}u<2Kp&+MW#=Mv$P1&`iz3rs>%nre}Mvg)00D zY1g@DBMwuiy`K;Xnn2CeoNAhE&0(^&mq69`pZw^YcC2*tKOwfy9nA$`_FRB6kBbF# z@oC654!IC=`&+31njXT`R1%tF!WKDmOfZ53O)Ft)^2zWNt&NHM3o_d`3JFv-&?A`t z#Q;6AUVZ2}(MZvI7_;jYMv$QSNKDOL%J|Z4@OSZY?h+EHqFG5yO-n1+%;flj4|x>6-JPtxs6QC zgUt3JH{Y0QlwsE^Bv3^&9GRL2`8ii1-r?2)S+6jHMBXtWtm%b6oqDw>x*UJAb-S!r zNT7sWg3v+4G9Zya=@C6+zZk)o!sHjW2lS6?r2_Y;0MVb-vzKPjr+kIkLI& z&&GB#&+%HQ!tBzt{l~`{bEd74d5#ezXo?zBa}@6<>@~W5c`x%E2~=TrY1+2ZXN;}S z^T|BN2olM6S7S}it#>9bP8syc`159j%yT4Ah1o?1+y%$IqN1gbE*H0@)7JUl+hHaU+TBS=iWR-UOj)up?X;IH1DlyhH^Kow?}rX84A ziZ4F$Q06&Ckf5paOii%=7Fmh69PmxfqelW&m|dFIBRGhUi%ZAt=O~OIQ8rCM7QWJl zC9Y&1b`Rle_UGXCa}*M&!tA2w^GcO?pRt8xo?`@we-7qgJJM!z^88(@VE$kIk}}Vc zKow?}rZxRimLKaE#O-rr7(wFJs&tGt9i2R{S+p$okFU%RN6dC1fvP$~vam8g{p4h= z-|1|;TcrrOE*Tj6SpPk^oQ&Lx*I4b=#pKVQ4rt75Q_T4ty`pmQ#(s5q+iCR}Mv%B% zHYxiOSk(C)1zY9kUnkb)@jgdfNT3S;LQU)Yyf8o3rUs8%Q;%T;iM1=!v0E$iIltpv zrxN@n)y4EXqP`&wluqQ`i@h53YXk#BwXk#>lH?jXm!3gi_i7RA$HZiWrQ_d zB~a}*M&nldv7t8^nP zOMJVu=2#})b!0YfuS+n3#DX5_*s;#}9HQ#X96VXk!rb1|M*>v?e@n;0#^-aYPqM?l z{6UklvR+{XiNF5PSVGle4w3EG?7Y%IU9L-zKvm`a8k^Xtm{WZk9LvaeWUDRf6-JO4 z+~l#|qf9x6D84lV?|3Of)+;1X^?#I|3B0Xi`Tmz#GBlt;nGRAig>ueb13EdCRD_iJ zg*p@pAwvg8=1S5aQsfwlN{Ddw+H0F-3K1Df2$f73EAhXt=eh59f1mxn%klqxKKTI+qky3^m<@0|87&kR2~Wue~ByW6IH2|Z-o_PXD-M^~NZjQ6g%P_O^9 zPxfv)|MXEZh&tfezqD`LdwrkhR~>SFcg64SlJeC#TOZ#(Y|$CXbHdr@x7U2b#>t-Y zi}TxmeB;KhvB>&&b?<-A&b@8c*`h-a8DD$-Y#JTZMWdz*ddr`!J9cT1bD`|HlzXCBkh zJvBXK>~qhGotNe;+R6K?x9+xfck>gM>gpUt22mq#U8%F+U5j?|IqGfaZP7j8>UPRk z^pG)j%d(xjmtWc$dp~|mceh_3p7IqLL_N0H8#)VpeCbZU#c3ULVt3g;jF z>dyGo`L}krduYL)&QW9#^_D$boliZxx@VuSJox+W`!;`FPxn6bka5^;54T6ITh|%C znSEdPydzh!Uka^QFo^ofl7DOe{MmIq`#f;iUEMFNyl%=@^pJ7Ql{dDh-8-THr<_4K_yddT?U*UxYN@ac`5@%HO)>t49? zwkcncLDXkXJ-@xd5*vH=*`#+x_mA7yuXyYnMGqN|Y<_&Z`{Jg~`1Q79-6zicLQn5k zBZH{_Y;%0Oz1R%T4A(CFv+iR5*gfSdddS%7%U^E)=gG~SvCQXNb zqRzYYyX|}T%~`3{`oRuA>aM%{UcH@9-mF6p86$gqx&59eHuKD|(K2?Y^XJ#6dCr;o z`x95}%-m(s&XVt%u^MMrt99++KkNMC=@ZjDr-zK?zQ1he!wrKoy)g6n;gBm&-3@+{Il*V?c35kCxa-?E_?UD4!`K0yyxR-p3_6dncsT2 z{nPKQ>+^i&=f=BFth0EU=VTDY+0|;DHZs;d?8rBzc}@=*I~{jp`{r|}`aHj2jcdE- zwC(qOHqXf*inGgpQ@!J*-2=b1VVdXkkg@OQ&u?FN(?&keS6t$%?m0)jKh1M8h~n(B zCkWj1o9=llf2^nPGtfiE71NGy-}l!|eV(s8|ApQ25Bp3yN0C7kXP144*x2y}Nz* zwIA_$e&3YY-8pye+nc@O_eRMeYHW?I+poH9bDyAZ$9Ei<_9Yviy3fd4*4rw1 zKK{R_NB(j2mdW1xrKd;w->}aJfA!2%`;7kbWxC5gI;%Ij_=h_5ka6^Ft@gwA#OwU# z#q~eDR(H!yX7x5-?%Gi@h++xtjUgZ1wA;SzfZhqKe5gYY8Am_)?)D|ue8e@LTHy2D zuf4cmZ{LfzEEzzRHNSo8Vx3L@utCaK|M}pnJ3o2L@}2Mf?t`nHw%AMUwJ&{J=fYJ! zwA#LVztp~Nq18S6d}G$3onL%^Zpv5mkg@yMA8Nnx#&w*r)qyW|zG_b^)cYXGAZq%< z54AtA^tzsX4w(A-?yt|?Bjqc4$XIy%hW2m&wV^ZK`Ph5AUpV1sDPNI6)LDz)*#7&5 zQ$734{`F?vJvO^C8^$f8q1nhtAx{v(LGg zexZBtUW@c}ze^7p+g<Igh+QIsZvXy(k2qt&y|?Oqd*M%{d_@LP*W7HgcFspU`@DGA+TGrrJEVOHJ!I^E%hMwp zer`)=eC?Afb-y$I#gwneAnN=lo*r4ke*K?sYj=L_Bc0{!mqOZ?&_l-ezPHcF>Z@<% zj6)B;taJAh2c&#O22tCew$I3u_N}d)86J9Olg^v}c3|3<&_l*sUw!atk6s>(TYvqw zPWQJ5_x`ZmoKZ4}`q8%U9NF*FIV-hVAA9!b_I9Tp+UUfI54{(rj0H}>4GckVM^sWFHOJ8SGW zeb3(7YyUhk=m}dI$L)Se`_Q}Bv|6hk2mEfg-h*Geyv86Z?5y#RksW(0o&0!W&=a=e z9&+Q^?N`sYqibxt!l!z-oj?D$d0K%|ETY2B8ZT`B;ocqly&*B^30oS69(h9hlCzI; zjkU)&?Y(ikm1+#4!p<7=ulVlX+y1s*V$c(|G(I@rq3zzTKX#2%R$jCB+;`eF22o*W zjV=H8rrte=d?+#K30oT9+J5WypKdGt81#fK zjm_V+V*89)eb>1Du|IeB+-Ij6gQ&2x#&OG>*WG5lJraYSu%+>z^==xOf0e6UW7jXA z*gbq??;3-su(QU}v$yPSchmuiK~LDy_|dxSjm-GY^{#R94l8vRxN%mEK~&gTV}Tv_ z@9cWS!HGdn*wVQ66T8p-{aH7-#$|unwEfQi))_>Foiz^H^qjE|zAiK930oTT-|)TB zUw!Uc*Z9q~iw@4b;J{R>Kq(ecVP}nFuh?a<$6EU*20dX*W8aMy>|b!(Wv;RRH;x(n zX`!#w7(|7gHTFNRKbZf&UrY>o!j{I?9~kMcGUYd}@!MbCI+**$FVq-Bg`G7{`R_}E zUDp^tWcBe=F5aldAS&#v(cWX)`0Za>J2B`9TN>|v)13YW+Z^B;hh4SF_|q$` zR$~wqcGfuO#Vy94-sN?PK~LDyIOK%$`)lp{e%Cne{%yx^Z!KD55EXXT_~h$nj(_Ic ze@(fap0K5{?FYvD+i&?g*VuUbUB)+m>c$#_sIarfYMbsgKG^k?#Gof^X&m^_HT_+d zKi}8ERqy@Ec=wPaYYd{o&Kf`Xz^w7_T)t*v&=a;a9^dGO{@>Ple6DO;&zC!Be5+qQ zpVsq0DHc&-XN^PtdGPpoH(aB3XwefkG^S+@XS9bf63W@rvW7~v^{<{!I~jVyR$MRb zNY?P0ccGDD5fygU@YYQXdcsy*?;Dle+RA&d#vm%}tf5iz;iqm)40^&=Tpweu;Ulre zAS&#v;iJ8$n$r`uG<>eOhR>)PgQ&2x#-VxECI&rWOT*{9YfQ_Tp~fI8?5yG0Co$*= zTN<9bT*EV5jX_k{S;MnvV$c(|G&~2phG*&;gQ&2xhOY*RK~LDy@U_G>e8s6ThzdJv z_^Or|^n@)9UlU#97+X2_TxH?1*< z3Oj4~twCDP=?PmJymPRBSN}J=`cA6-DNv`$CcA>0F?*b4kMF9zJcF^wi0{dXU22d) zRD6TB&S0;__gREuX-f@y$oS%`HtYQHz#V*CO>oMZ6U91B;MG=A>*O=DXcIT^7 zT$Z+E&_hOi%SMrgGl*iHO2%XFc&L5Xq3dYGRQJ@fnTbjUJ#kMh2J=eEpa$6szww6l zW7}<*v`Yp(WH1L0XApJq)91FI>hu~kxW{!n?bYu)XUnlA57^81?Gq}q$9>0|P7U^Z zlQI3?#Qc+X`eZOJ8TNaVG5tbC>+0J5TzP_Oc$smd?QkIGyGUD^$ddw)=UW*wg`iAVo3`fQ>Pkd->jfJNtc3CPih+?)Y z8Gc?)vFw-EWBTQ_O2yKa40_10-zbmim)>FzXAs3Yl?*>&r&#t(mN7kVNpV@)l0gp{ z_Dq&BJ;g=r;S8c!r;_1k@)RrHG_SZUZONdA411o`n4Tvk_HYJKtW(MGQ+z6wJy&l` zPbXAdmbPTjLxw$9Z%j|(6MHy=DAuWD#JiRh%d=f7q0g0u{_uI1Jn=pSv4=D0AtT;U zA$D0RGKgYnONOrisZ{nJ&9>gKskkg{$)Jafc*}#>!x==eP9=l4L%fZ$HE~Se#j0y~ zrcU*U_l66_(Nk*BLq@!_yskk8Q5<8X23MB%&Dd*ni8Z!NW#{@>GUy@0zIk-oFD}aL z;S8dDEVS$OC_NK#O>ZPhSZa_#)bQ27+bXHsj=Uecey*sc20dih?!4c;ZzqE&uDhiM z$B*sE#$u<(@m4bEA;b2JWBSI8p(l-YGKgY}lp6GqVY}MCzR6S9AcH8jTdBc&W7|`Y z>08W-%h^>j=pn=QqGS5rbG=k#5XDw6HF#rgC&)4V{zGwD+LA#J8Fn@pi!<(U22re2 z$>3)NcG@0`GdW9JGUy@0PQqjQeT$(djS@15Vx3A2p2_SsVobm1Ra~AdO9nk;*uBP> zegRxB6&XaaMM@2N$grD7~TU!j4wq(#lM!erb?BNWeSf`S~(H>8*Qe2Mw zl0gp{@f1n1hck%s`=Hb!CBtuP(_FLjU?)zE!{;D9WW+P1>ZKxsD7HvhD&7@a*6zgp zp5KM1TkeuU4;k^Kn0l$mAc`$gYS2SQJjPjSiiDV^pIgC>YHYR z1{p+I3-qmC4UE$_JEMQa&EHNQYuUclE7|}1@9F(DKl8l?20dh`MWUa|dazBb$NJV1 zDK6WvWY9wf^@cNuQfar{A>*KD?bL#fCh z%KE5(#n1O^U}*HkSkl;yIiXf>9wqdUA#H1k1`RTZQr|R>D|*OKOWVI2H0UA2+G$7+ zl0lTUQ#Gc`{tzQZxb=PCMn@{i@Ucq|8R`!kDGl`?gDCZ8=#`~n-%2A!hFYO{M$tnC zTcp$=gDACI^E{`AjNz@z8fvshOS47FQqe<(W?E#4;S8dbUG3iu{Xq{I%8$b{b;Ke{ zIoST~8nzN18*9`)t8PE{;8*`8c^13lw7Jud{&Qt-{hHAsjOD&{N%EZa!v`+;&Z!qC z`**MV%#?Fx+}FUMhm76+ZRgqI45ExZHS|h`>Jg$H;q1jOyMG>4>6*j${sY0s)n+o z?8AGIp2>{PVs|u@iVWF-;^-+$#j#{{8jU(JQpuo)3`N?pd+j_*MU+a_+`4RcwQj^^ zKb57ThYa@9a0XFUzmaISl0gp{wLVWYoujmJ#d@dJE!J1<-(t_`;Pju_JzMqLv4#_6 zJC63mPG*8LyGIWhw!>*p?3T!&hDtH-QZX(W+5<=ZCKOb2GKkXdxLD7fHoGT}keX5Y zZ|tL0y4V?%8uXB%5=vi@hBJs#i`Z_hfx%KykM%1x=pjSx)Le5ih~nreH8_^ETWuOK zC4(AdXdl`u8APdsp*MloNL1UXe>ECZ zQ|ZW7B#nXQQ4$_9G@GRP@(iNXn=z)#QgI%rrDKG%)k_9FWT?f}qxDjeL6q7_?Nw*c zqxO&5GScu;k)cS@(!&`z`40^~I zJ`!0E>T$%B8uXB%%n+z$j#^Q>RqaP*YsYW9*}3)B)j1|mIt4v+ zz&SN`St`aQ!y{c%*C2za;ic04R(nOoN_#8YAIjE_Pb+s_LnjIChUL*NKWaN%gB~)x zv<>wjgDAFo*;cFv%kHI3bt)NbtF$}znrjChEmAUwBAa?8gB~)x6&gxK22sQ7!Cuo2 zEP9QRhL?&A?ZCAwtM@r$5vBdR_KkH0J=z^>=O+{+4KEcL+Ql|&FcwkT9XHp5eXG;8 zPOT~x`=%@vJ!JR@ZRkNVh~oS&H9YQImBf29*_;I>gB~(`79{p?22q^NC4;5%cB_@J zWUwS;_`GQ-6&XZ%&yLo|mG^D(_()9la0WeO_{eY2AcH8DwyZfz}FV?v@h6>ZJRtWSgGuOB*!kA;a`^*W19Lhm7H+qK6D?5#6>mXpljaO4~dV z*}A5oo6Qt=cn{JunPGFip;TnZ4wT<6WvBK@S;LC*8I+Fz6verM1j74+c@vwyfH~P(O3*+8UBj95Ll+r$=@$SlZzX zqGU&JmJE8x7+w$a=q@ak-D<9z&14&UNG_p=3~OoKkv6my8ASOFTLXh0F=A9QQmy7y zdC5=-o5wC=5v3Ms9*Ld9F6y6o(v{O5IAgia^nYK{U*WPBlD*AO?v*`Pe=kc#4;i0Y z=6*$LVBCAcJ^dL!T6R>ij$HQ6{;cWmNcKtV|DiwQ(hZYcYIvzqtSc|Lu>Y4?M7hpbYsIX%vpCKMwLFBKVH!o(iVAd3A|GG2G+ zrE1X;mE@(*U8xpL_U1?Zw*S(}8z;MDcuysD_Mq2ec&Ta(@7Z~1-2T@G)Pps4St^!< zj9<1MR1Y?kiVUJQ+5W-)37?(a(1Y|iW3Jkbk%pIw3@>3~4`&ed%H{{>#48(DWNiN0 zTh!;H^|8xXL}@)d^Q7qw40?PlB@`o-HK&IRAC(OnWDwCSF7_06he>+g2!IS&oHGuF485=wQ`zw4)MddN_z>=t?+47HPxipv%$>p>40 zYA3Zsy;NinCAM0-&R{F59?_eOG`v)k8Fp{oput$O1Eqekd*lWNJ?cTbc}^%s8eS?g zURj?LC2d8hw-r5PaEz6uQtiZ2EY(`&m#w~N9wqdU!SPmVkU^A2h`#4luLnJ33?I9i z=P@TVgH-!hUJo+Vlg+KmdJx4nENjkDt$L`GD%C3+C1j|j=bagdQmJB8mZhRc2>tt& zmx>IPNSgH?WDSX8J}yh8kq|k9V^^b4EnnB5hYXE_XzAe^Vn>D}yJXNqhBTVa= z?@1&LE0I2NpGT>vL58)mK5=iT2N^`!IM6pa8W=YE^!N{^8xq12@M;?CnjLusZJ~Y`&Tsxz4^_JI7)8B_P zh-!axdgr)VuWi>E^pNqj`_nW1r@TCasJ%~}(fQN2R~oG|==t=YH|?Cb#;FNK?Xn*9 zka5O|@9V6++>;F&WDw-+MO%bJhWf02W!sSUcb*Kon020Iu8a>)GO;j zPr6y|K)eJRoj^-zq7O2an~lhEL9tf z`3_vSv-o`%)z~G2ammOl_~ ztY29wGKl*90qb@S{QE@>8uXAcymg=Y>7UyxEU?;``rzZ|FW!0bKTC9EUvu8;JFA?# zaI(u%8M-5uP(m9kv4u8PvP*{g*jh4qtTkn)xYRBg^pLT@%tzYaKX#?WE*UIu=RPB8f+7l$aGRG3}?_ohDv0biCt=tK@>|{ zGT4d_@9^LD*}EUp;}wL=FuNSajuja$`>}*Q!HDn+Lj%XZF#b-SzNCNJ!H7uz~C(6 ze6)PnR>rGq&_jl@wB?gj!m=J@5M>#=tvp=Upoa|BuhgK24CO=1ehsA}gDAFosi8fT zt+6TAv1WH{U!}5ZEw>e~L4zJLR$63g`(|6A>osRju?J6C^U(I;whO2;=pjS97~8Wn zl#1%VeDO2w=WK<3<@F$g+GSg@=0s`NWP728Qqe=k@Ou3B+&!o5edml+_R}x=^vKOS zXM5c*F4AB9rQA*$Z|Y*HVI^jy8jp`&-( zspXYxka5-)*Ueqj&N+1rmWn8jg<8$4naUY#k*YQ<8T620^&7F8kJU>>kJV$uYMxMx zG+cuWtJ5^Ad4mRH5ykOVYOvSX|28-K+M(C$K@S<0G5VIT8cJmuryuK*+bOQi;J)Rn z1_nK3*gWs+j8!ic)h+wNR%h8sPv;w3&l?!@kYTH6U+05*&B-82Coo&j z8#L%4gY_F;b24nD?&~yDFBM}E#a1shY%ki^K2EW8TCts2D!WcAwnJ~IhoQ&B5<_V1 zT4f8ZlSaK%Y*F?NwTG9A4DDQPpW09=mRBbUJ0GMHzA_Cmbds>MLc$pt7=Jxt-$b{H6?4*Pw?C*00ncgD9PE zl=12s^pG*Uby*VDNhb-dY;_HKw6oW`IJp(ddQgK5ouRaH*EPr>%I*`#>|V58XXu=! z{f|6uCzRb^j@iBFJQze#udD|>1;h3yb}!nXL5AInR;c0iuulQT>{Ebr=WU+?jM=9E z$+p}2G5Zu?ZoTGY5XBZL>p>40cE7JDy|wBZWDsR{{bTkiz(}1zkKO5y*{1*r#Yn?T zMTXt)kJ+aH4H}F^l>fcnAH9bTJ$K~Ov%cKcC!;U5*BklOiusqm_V-cyJ3cGQWt%NV z@vBZTx&q@o@LgD7KG@G{D@>}UQ^=0dlL6ox_G`tntDv7slvaNnqt}Hd^ zA%p!ioI#Yen=)KOThT+t@IGg|Td6cBQe5^^tyI;lCByVI9~(-=SVUQ?SDC2Q`pj_$ z_dfgAFQ(t}M7wW0b^Q+eBW(S>Vx;w&p0L$7?EhBl|E3?*``lk2tucrSJ8OL9&HMMR zU1qm|+JK(0F%msreY>+yZ^~c3Q)BoTZ6VP_4^zoAO7Exhm4Yh1!IC{dChOZx(&@Vg`G9jgEkKngPyRZ;XUiS3?C&m22o*W z4Iha;)q|d}rQsvgHGH(!7(|7gHGD=T20dX*!)Kan_^holhzdJvcxFfpdcu~5XAIZy z>{DY96?WF}43`-6ge?uve6FGSXT4Zs5EXXT@JyW;^n@)9&)}}%t3i!HRM=U=SDeJ4 zCv0i(9G%udt!gy}QDJ8dUpW(lp0K?hTF<>6zB<MxYdnsIaq!@5mB^p0K51<5+hx-d4Wrt1*ZQ zJ8SsPGBM~0TN;Y5f6H#QY}RV`T4N9ucGj@WpdE5z&=a=eT3*quk!x7?(Js8kAS&#v zVHr+4{gmP830oSLAFErcR!hC7{itWSq^?**g`G7lQ|rVMSv19(%+R>iILmEitAS2M zH3m^(XAN6%bn;3o4n1KjuB}8kpZmBPS3T@I?fOM#TPXWRynYSV{^u4OR(39xkE_H8 z)MSQ!KcVmNi`{DZxT-OT3Oj4~xJnFq!d6_1-?x9ehL5WngQ&2xhL5YnpeJl;SPSTv zdamK)s>UEH?5yGAYM|DoCv0h0i|ZF|uHoaV#vm%}ta0HEd-hsiKRYq#30oTPc=zf3 z{WcDbZ$7$D?@jA}tHvP8em&CHuNSI%RQp8zHbUiL=#Gof^Y3LUz)}yZBJAfL4 zsIaq!?*I~mp0K5%U+-9tx`yunY7C;n&KkZ0NDO+ymWF;`q+bomZnb;|P-74kcGmD6 zKw{7nw&Ln{WcpoG*5J7|P>MxV*jdAO07-+Muoc(FE$ZPrfEt6Su(QSYkyiaTO@VA}Z{x!ILmOVM{~5ptBL=8a!dl94D$@mUA zwJtqji=khu7d@y?Oll0G!mfI-`izC1u%lEHBa!>|Kq;0=6{xVY2G0icge?v204HV? z&mVzOETY2B8rq9$)zL_#Cv0hGCp(cDc#aB`Vi6T~*5FxMxV*jdA8ZOU-;gsr&tyv9*IV>oO0tgSJK3Oj4~tW6Ah!d6^=W~OWKlo}|-A}Z{x z!ILmOVN1iFL0P>esQjEWP>MxV*ja-odV0c^hCg@I>%m)tKq(ecVP_5AOwbdyH2kTz zuEE=nKq(ecVP_5Au+S5>H2i70uHmzGTw^y-ibYh|S;KE26N8?xrJ<(<>zU}X)9J4I zoHJ00MO4^XgXbuE!dBe!4PZR01xm4q3Oj3Poz?zFHK!+RuLs^s#xrN2ydD+Gw3D4R zc&?=M1`F- zY{jWQ=cFfWY1m3sz1yw)oHJ00MO4^XgC`bx!j5|AY5B6#_kC2VwAKbH>Jcbu%g!1+ zdC?QL;;KdTJpZi0(_Nqxi>R=(hI%k|uk?hixaxnsWgu(tlo}|-A}Z{x!ILmOVJogi zXnLnYZmayMeoq-LP>MxV*ja-odV0c^hGv@H^pNYpTZ2F;7Exhm4c<)96Sm?iW9VHJ zS%bG9fl@4@!p<7JVWB5%#Z~6hJ2kR~-*Tq53Y20I6?WF(O%Xj|E3PuQ-T{&|cpDWc z#Ud)~tic;Edcsy*zB{%2oHJ00MO4^X!&lB!b9%z|dg#3XUJqZLYYfw?P+?~ctGRXn zi9t`;(y$iM+X`I6cNsMXQDJ8d&A&K*&=a;atY`JKdDq|>Cs2w-RM=UA=O}u@mWGYc zxfAn)XSF~n7Exhm4W0+-30oRA)AY=KuLsYZfl@4@!p<5z*U}TVG%RE2O#-gLvvZ&n zi>R=(2G8g8ge?ure0Z;=dN1zb0;O0)g`G8c&p=Pu(y$DkPGqvvI#_+q87RdfD(tMm z`x1J>R$N<&s`r6bb8uXFSNC9c1Cm-%_dIsvlGdfLbE&v{r6+8aM0YcaluPAvFlhuz zv4{#gYxo>Y40^&=T;1TDr3Oj4~987IRPuSAX z4UXNVxCT$cfl@4@!p<5zZPOFBG<1VwH!iN>b1>~J1Ep9*g`G9{nJ_(JOG7s}cH`n2 z{7g7diba&&`?fWAs(MtP32S_+yz*!qMf-%E8Qizi6ShjF5i-$(JR1Z`v4{#gYw-L* zPuS8>eEnN?`gU~nUCux$7Exhm4W6Uu30ra10xEIV;8`tDibYh|S%c?6dcsy*wfID4 z@ZC}xyMa-IcxAlAE>BDprkE3Yw)u>dcsy*&DbKhSD)PlO0kGi8*1)k4Sse< zPZJ~8Lw&AWFV&oku!YiC(A>!kes_6`8p>f4Gm3laKq(ecVP_5P8RGVX zp0K5%+&GaLcs2->Vi6T~*5LVrp0K5%3_6kFc*Y5oVi6T~*5Emcp0K5%`1-f(>eo&w zCk9HfhzdJv@H|LQ*ov!mQi-z$&zyl$ETY2B8a&t16Sm^2zt!?tLm5=Ps8JFq#Ud)~ ztikg+Jz*=ZMx;hi*5DmLpcIR!u(Jm58R!XHag{+e6S4;HG6JPoM1`F-{8NBbb9%y7 zT;;=wdib89#vm%}tf6lWC4)C-^nD6Kq(ecVP_4VSm+5`as4g6)3OFnEP+xi zqQcG^Jh9Ldw&JGGSL_}+YxvG`Tw^y-ibYh|S%W7Qdcsy*yD&-btj-!du>?x7hzdJv z@Wet-*ov#qSL}voBx~@*5-7zYD(tM`_q(a)^n|Ur{vKY}@cZ2wgQ&2x2G1Y#ge?tw ze^`2xcCLr#tE3Sq#Ud)~tiih_dcsy*eOhAoSzZs%yGbKZibYh|S%Y^=^n@)9e_yg| z@NOwkibYh|S%Y^=^n@)9-B;Spp=MxV*jdB(qKQFI*wWDF681TQuOGhOtucrS+uI6H5TGY) zY1o^y+YcRZPFms0rxXNAv4{#gYjCGePuQr(C9M1`F-xYMU6Y-xA~cMb0J1Ep9*g`G9H)2AnFY4}Ry8rOp$KmWJ;iT*G%6H3m^(XASP#=?PmJzQb`1-z_DL zKq(ecVP_5AS<(}>G<>J#^TT(2Nh45-MO4^XgLjtnge?uia%pYO6pg7Exhm4W0+-30oRE7g%O;4W0)BrC3CToi%tKq$g}?Xdh}B)-`w@43uIK z6?WF(d61s4rD31Mr?<7sPTza2p5hTG#Ud)~tikgjJz*=Z_Mx`oc|CX@43uIK6?WF( zd61s4rJ;SOt=z7`^I)J9i>R=(2G4`^ge?v2Lv07*8axjMO0kFvJ8SSfNKe?(&_2|5 zQm(=CV4xI>sIapJ&x7=YEsf94*zPpj5xNG?gMm^kqQcG^JP*H9uj51t1DrC3CToi%tKq$g}?SjN!z zeO!a*!9Xb%QDJ8do(Jg(TN;-6^nD-K;CV1mibYh|S%c?6dcu~5WpI7p$2E8!43uIK z6?WF(CqMLrEe%_V^nD-K@Y7vdqXMN^M1`F-cpjuD?5KxURN3WuFi=sCKuJ5+;PRVJ z^n|UrY7yHJx(3gKfszJMVdr}AJV;O2(ooM@Q@94tgMm^kqQcG^JP*^p;CV1mibYh|S%c?6dcu~* zeBa&aG~1852G4_mQY@mv&Kf)q(i67VL%-&54W0)B<@Kmgrk(7p!Sf(JVS9h*Hyf_O z^I)J9%i66%g`G8c9;7F1X;{zd_aCmo^I)J9i>R=(2G4`^ge?slq5A!YYw$c6D8(Ww z?5x4_AU$DA!)BU(|KS=u4+cuHhzdJv@H|LQ*wV0!q2GVF2G4_mQY@mv&Kf)q(i65c zEc1;_aJDend<)dQ$tWDU-9dcu~*OP{+kwTSHMcV0;& zP>MxV*jeL4zrSek&Bwl!81#g#xLd7tMSt6=>w8=M>ixG4e!BJ-Y7C-Ycj%@4S<~N< z`l;3W{c9c@oOAk)iP40TM#*4ipeJlGMq6Y389!RqOU29(DAkatuyf6s8R!XH8q@!M zNq>dQUTC-}3Y20I6?WEOW}qi*X><;|$VTFo4L3!BQY@mv&Kk@N^n@*qD=)aP|Cd=u zG~5&gO0kFvJ8LjA&=a;a9zEfL{!7O$>KeQ$3Y20I6?WEOW}qi*X>2?7g8shkLspSp z-V_B&v4{#gYw)Isp0H7mX<38c90(NZkx;HZEo<?=?`0MO4^XgEvL=ge?u9X(O`B z?>Yxcv4{#gYj|cDSL@Ofw&Hrma1GBsH3m^(XARyI(G#{bJfpe>Z;Aq?SVV=LHF#4* zPuSA%obMXGex!N?O0kFvJ8ST!h@P;e;cJ&`_&S(00;O0)g`G8gtxXJi!cO(bYrAXk zrYKOU9zgl3J(4wi&yY*ysL2f9OSlGaiWrNiu(Jklis%Vj^*D0bJGBnF25*W2rC3CT zoi+Tdmg+%I*wVQ7gnP6Ox`v+zYYd{o&KkTaq9<%=Z1ap`u9uECq4Kq(ecVP_5A6wwp5G&b4(!Tt%KojtJ*R^Jg0lwuJTcGloc5j|m} z9&=@vH${O$Jrc^b=VlGBc~^Otp0E|yTf{ZIb!!Zw!p<7JDWWHAX?V}NhL4h@5h%qX zD(tMmn<9F`mWGeeXe-X?9Ce6EqdKxw}+PL zO_{Ml&z?uD_ZXB;D^}YApJ-GU&rFzf3XM-L+Wc+rg zb=s>;+tO?P_nuHNLjiQscKT_^0lP zYm_}m6#J&tvYL0J=6c$5)X?hDkDAAmr*m6<_=t6#!7Saq~@%#^kZ-9Z2tN6Q_bliV}--lnDe3c z9PJv$7;9n>Wu?`-KwQI0HHK1E9x_aCWTGBc^8spJF^IBO*SkPm!&-NM)~!5bSi6l( z^oRA}06kbSh~i9ZwQQ6OG)go-=pn=UzdbRoHb3Ixfkxu}c_db|mMG50R?9M6FEX6w zxJILT%H~8rGMr|BWXiRBNW(|!g ztOgZ>DE4ftr7@)pq*BpChQ^d~OV+Set@jaI)gH;KS~W_DV*gj;YTzrUMoC*WbW~e$ zT|50ft(-kuIS0OSN~6Yby~M8SG4PeMVi4u6>u=8Twi>AB^pN4LFp_KT{ZV5O+y&E*6;1{=jA(Z z*sL7wL~$Hf>)^QW0JN&5{_t6p`oQO=_n^T`O?@GRjPp05VJ1E@wKQ5==2=GyzDnrqym9@_h)xSo%_RJH?9-W~THfbwqC zykd9`_ELFnANL(V#URR89M|ymBefMhWcbS98oox=7)1HX=^DNcCI&rZ_zLG5zShUvUlJmqe-b=9AuG3X&fS=#2kYxo|n#vn@TZ;YO_1JFJ(G3X&fS=#cKYuFAzd(m;<0aUSw z;tWoiT4$V;silm(t20iDs~Hd(yw&nO^}u%kmB(gL#jx3>UAUJ@b6m4l^PI7W;!I0B zfPr@VnjiF#q4@fD&TxMIi0o6%TB3aK;|$BxKSp<$Bo4sWWG+oRx= z^R||ru*I;aV(2N&iCurMjN&R5QDJ8d-qz9+wlwUi7<$^YYw)%

      MxV*jadKq(ecVP_5A*3uKUH0-GudK$ZH@OyoMQY@mv&KkU}r6=sDhyC)~HM~@IFO{C+ zk<_Cefs(fDtl`hHNcW=jge?twc7~p(?;8HRr5b}MwV~!t*6?RKB}NlU8YP4GyYz%D zhQ@+snC$9}w@D*VQYR|xTq@r0(i67gYD{bHWDTDm>0UHYibYh|S%dex^n|Urim!iX z4WH*pBT$M(RM=UA_q+6jt+;9@l{jngem78xMO4^XgWm+CCv3%4f2-xQ2EPdyD8(Ww z?5r{Q`R$4|nW0gr5tKD1KfgT~L}{dJEN2Zqzr6{ixFv(%9i%60F*L_DCv&OzouWWV zov5&Lsra2Ddcsy*Vlr-oGTXF44B<1>{XFAmwMA`FE$~8*wd`XNZlr&0) ze|smbgY<+ghCSz{T%E@?bJeU!S58& z6Sm^2r8Rf52ES7jD8(Ww?5v?a*UVMT=?PnLH5N3(vWAbV8iS~?vxbk|acR&Kw&H3` zYwlzXpC2^_QDJ8dTWhQLRMQi-;wrxWoi%)(CyhWU7Exhm4bLTsK~LClsu@-C9A#c zyRmf>N}fPT!}=*j%B7mrx)p<{u(Jlgu|-eVifiLdPZ#snTt&nrrYITY*w6qQcG^zNbz-NKe?(uq>gcy}5?(+iMJ>!p<6gHb@M5!j^``*Hi0U zgLeRdQY@mv&KkS}peJl;SUc(Id#>TMxV*ja;j0Q7_{4P~N zETY2B8vMoR=(2JZmq30rY(6qf5pbq5eA#Ujc^XSqgIcK}T&X_O4!0nih+7&gbt)w#L@2$V`i zRM@%ZyaS*o>?oCGjfvH{dJk5h6ia%63Oj4?4uGDprJ**o?B^Q10|=C25fygU;2i)x zVM{|}!Lqn(@D3nQibYh|S%Y@~^n@)9jcHqrqOI_|qChDYQDJ8d-T}}Pwlp+@ZB=y* z-T?$kv4{#gYw!+$p0K5%9Amo!*WevMpcIR!u(Jm50O$!@8p@Tn7jg~W0R&31hzdJv zcy1rpJf|mYX(;Cx=i1^O3Q|`rqO|(hj?i~~zD6YtdYTy0t9~t8V+30$t)jNG^_r{v z`Tu73xHsf3Q{MwH%?5^l4xBvxIdHO7!uUR9#Mggk_gE6vV>n~_NUuL~`$H+NzKgNo zMUPeXZ+~}AvP+FCe{pWx{+B#YedPRhpzObuT{8T4)NQqo|BgD@s=4VUyJV;y$_~-b z%Bo>^ue-W|@#`J_*q?HDegd~Kb!VAShSvRV1A`tiEc5B^wSi${S9cc4^Xi2j(|1yn zZKG26B@GOE$gmPs?6T(6u=%JP!J1ylU|cdRW9ZJZp;TlLrEy^6p@BgU8J78U_c{*- zQS7I(9`ul58C-YB4H{$+#ojD6w2J9W=rgsiGpLWNA^lCv}`6UzRpZ}}!$S-QD( zZR}KWZ5&s6!~2|`$qZ!*m9VS_8L|V#@m4aFlVVhBo*OI0RX)^gt836hhH`GOOAWS( zR>~N=Y{Qa44;fm^W2Oyf5LJF_a)L9vM-Lg=lQhp-wv}2Ta*0|YzH>RDpu9^D8Cr#! z$1WK}ag3E3^pK&oym=0iK@|I`)X-Rp{Hl={Iap&_JHq-XA%iH(#eJKf4Gi_Ob~B2l zR)`fqeWRUJU4tGneC?VCgDCa6c7$~eddL`F4>E{Sj)`_FTbCX(*ls0*ZKYn*4sCL~ zl?=8I8R~!Sz3Me5gDCyId7jflhDN1!Xw4cCi>TqbgsZUfdE_Xr+GWk@A;b0#L+U{W zQU5pf>i!4cd_qG#=pjR^Pjk)5AWAzZ?WF2$MGqNT6PtUG45GAB$A~H0iXQD5Vm>lb z$)JY}?N^#-Eg3{v%l55R8fs1t8CunvXDt~-F)Nkzpl328cA3K&Vh4)(v1Djh5o@ij z2D&LowY7QEj#*GLGYA%aSO*SV9di6+L8F&et74g9aHyv3_M+(L;vf>)-WykUQr!_3wJk6-%uuk2KV(vRS{nMzkUs%BJ!6;S8eK zPbEWfV)rULGPTz7p({@1Aw%_1DeE<7ETUBNXv4Bp^pK(UYhF3YAc}ocYG@8be<)MO zo?7`T`le*iLk9Ew%QK?av{r>(GU#Dku8AeXcE#;DHE0H@uhj>NA3a+#=pjR^+RzhA z6^kg%{m?5l*t*J9F(=q=C4(L^lpAAq4QCLg`xv`@X&8z0kfB`MJg&$fimhIjiXJkQ zd79@38AP#fN)0|EBc8UQKA*C~^ZjkB-!4sXX7}hJ9_vf%o zljoloJ=fo7udk(F2F0^%>I{0wm~!{O`&ZxcL3@(<B;~)EWMCvGhzAe^ywk zt<8cVZN(bKb6*sfZ8*_V+F#K_Mm(9OUMez(Vx1;wpiRi&b9ja`h#KBj>_M+btv5>z z_8J-9hKW6#LDU%^f3kns*7G&YT7SMv8cV!~^>Lj3UTV-o#&8WXi1Lx&pg|8AtW#O4 zcy^mcLp&=^wnk#}u8$rv_{_UfgAAhL8GH4SsHY*?7*5Zi@~0N2xiWlyFjhPt@Riqt zjCg`!y;Q6RQNv3`4;k?!#%7JkmPD~d%GTvbjHk;fF2`8Opoffj{$0IPWDvy`DK+RJ zBc9_|*C2x^j?hwrBg0#F9;2k8KN7?HKiQ=Q8ALIImkh6M%IDs0ebv_Ml>S~a=pn;f zB(X~dHTZNXvP%X%Wbipv!x=<*UTG*5S2E8GskUsxQiC2c_$1%q45Eg&6+LA5xN7JR zGKgY7m8Ig|hpQ;ttz^(chOb=>r6Pl<;r*c}rRxoL8hzZi>*?lt>s);f(nE%xRjzl) z)fv>#)8F-0zR7xJ%^8=BR%`nydT(G|gAAhV?|tj528PAe)BN4D{S>_g%HytVyP2@7 zg3Z=9s^FPm_!I5t!5}K_FfV$pfk98f$WO{|V5sJC2Auqfdvnd%R%Gb2d%bn;2tN}Y)OWmPp|g|)-@Q5sNo}#BSZakM_EgQ{)L6llVZ<=e=&>JI?N0}&4oHu1#(L;ttiQbskps|;o z|Gd0JX_s%Aw1HuBLhq{8AMsB zs*F*ViXJlj-3kpFWDv#g0o63BHep*?Y5UEsOO(c|eX%IoY6yd|$k51-mM%+022mW9 zC4(L^G#`hKt7;w)HGH(I>@hpl3Xy9yu7>9J%0q@m=+N9=F^G~z^Vp?_3|mX|{;1|r zQpF-l?3g!Y>+(LDH_*HXJhYZ~~>$bR_OKeYFeKMlE zJ>AO*C3f@KnI1B9SE?Jgx&|3Uv4r)uirSK)d)N5;a0XGsYpy+%#YpFKzF|{qiq@8T zJ;)%+_P%(s(L}js_musW(-ljrf~`QwR`yPL-~K*<*Dix?B|Fa1+6h>xrq)YE4;k8r zwpy3^vydiKX7^ZjFI74<4zCA2WO)4=&YWZrrOcz;Qm+Twgl)xEpQuH;9Yhb3;q_~1 zE5;&<{aS2E}!L#u-FWxeKP5EX9?t}~Qpl|AKA{*Aco|FTp>#aph$ z9?qbL4DJ4!dyovGw5!w_Qm+Tcu6C<2KNM-+*@q0*m{!+dETX)G4GgXF+M6gA^P~62 zNL_NWOkSt@$S@EJUhQ9=~+SgAn|8J=SrG{_)|>q@D?QSGxf z#Z?>5dq$Dr8KYseGZs-kN*WmS__#_aMk?z;4;em=8#KruiZi&>poa{fj}01R5XJFU zYWNPRk6e;$FKx0*20gBqP(DKE!5~VJV*gOr2oD)P-bU-$hp~uaR;p_lE0uThZ!>HU z*H90leBYK((r#wZLx%4F8#KruN`JTcF@zBwGJIb;4+c>j3uRkrPirMevHV*d$yTZ2 z? z?vX(hTY3VY+6wR6wRY3JMkr3M)#YJ0pRcY>oEdU_^WdU)$vALuqS zl~;RcTlte+mXI3skfA-h?I9X!P6kod>bk#bV%S)+y<3z@pTs1a^M9gD>JNG}c7vf= zV0)GZ4UG)jHzbekR(13L|Di#Ke}>SYQI=}rt*RW;^?KN?Q;Nm7(z6}G5RG6E#gSiX zuuU|=ZCCdHQFAghS8Rtiq*Rf2iDIkQN>z;?)6hL-iaUIi&_jml;oamDDrufqBaSHR z58cl-)I)KjeKdAsEQt~In^5qPSb50MT!~RRoI#Z4X3T<;!LnP6>b^aCa7aB^Lo#f{ z=mxT(=424{%4$xA-*^tuh*l&@?3j;b&FN7+Vg|pmQjwuH96ENZ9wdrmp)3`9N?F@Z zkyU?0{YnPQONKJIojd2zRzz8(SFl?mL#siQuvV%n7ExNMn@6JU?)2N9R9@Tf=+`dE zwtZ05hNT8QlNqsd8qN?qP;A4JK@S)KCvHh+=8Wde}F|_4!ANrIrm_@fD$dR-=au^}TxZ zJ?J4rBgDR6-=IMTQTn@n3t2A} z%dVQ+_ox$Ucs=MLLnG9_k=>v{22pl)*7E=w81#^#@n+u>p9g~|wtCs;^pK$uYTtKn z&>({-j?hwr@0hSYsBUifUWk%G4;iv;l(g$TIGGVBz89j@;4kv{Yq#MV^pL?fNt7C7 z5cM*pn)C#L_~o3|6-BGpoF3W1;QL?7QjtLv-!W4%=;7OL7^!5?Lx!R7o}UR${&hcU zSfMPE?#P;JPEW-!J-z8~9t@(aetK_T1B1Usk$mrR_`#; zsHyikJ!A~8hjNnYqFBmq_|2&DZi9x6@XAAm)uH-(S#vUovO4I^at#{vkYRnH_uVzz zQwtUMyL@|@#B=)8CL%MJp0DydK_GeU;Z+A=$2- z?8Z{n7_QN9v&~pU>F?2ob&c?l;dL6K5e%Z(H>HL@_aoKAMq#xtv2k4O0856-8|$`q zF=DCRSid^M`Xiypu$-@_#-zUwXAs4HDjD`0-s)|X_M74A?U!0LW2aU!7}sZ1D#>sS zddTqE+)xiPh++xLQqe<(b{MhC9L^wWc+Kfi+r-X-ZCGm1LxxJ!y!Ro4D2*%2t_^KP z4;k83swL{VgkzWERU=aUQ)l?vmps0TCY$WC=2T}~mbPTjGnt_|QZE%5EQ#+18W{AD z!8(BT%ep>&!XBX zSqYLy{T(-HHl~N%4icr27x!Yr8T62$QQv&yMFvsIJi0}w*F(D{-OI?MJfd3`*{WOf zEhjyb8M+OtYmgy3P--*XxYQXeuX3*LOoU?n${wVL4DB$QHOL@}r7bn+Aw$_M+HE+4 zD7JdZu)e6Clx#7p+-`kQt-B?|TCvJFHm0hqCPvJHl0gp{Hm0hKI-Eh2jj1848a>u~ z6D#K{Dis;ldwM!d!zf`rh#KBj^pK&JR{zvTA{j)npUSqfQPMV6iX}TnyRvBWD4|Dr zH|8TF4c8z;dA?bLv52x+P?fgSpoa|W3q3ERp{>XuO6z0H;8KGgt@~G*_DI!B|9T zZZ@|SJ(}myAB;4-RAeZxH1|1U5ycT&YS2T5GGFsZB!ejZJ?3Mn!O@`oXY?A!Tgjkj zGQ)J{F+ao(l-d30*_uY>nal|G%QC7x3im4|gC3P6;%Xlnv!Gg*^9>RzTx$L95ej6iuCI^*YWdROnF zb^bf{nsqnmeSG78+iJOx?hZRE-| zw_Es4H;dA?Xem;w_3BxF8;pE?v2khqa^K(d^*?Dmv+R%it6g$KviW&^tM%q%*BQU( z__qwiu#)tnB#Id&)c3peJ)K&_?usM)1bfh20g`8Y-#Wl%m?$e!Z&4%oA%v0H2Wz|~$FtiMp%=Vb7caeFVoV4?B< z9rV=T-)oi(qS&*o)+SFbHaXSJ%bk)EEz{N_`_?A->~`yJ&n8=)yh{f^3~t!U5&R^Yn^`{G}!xNZy&$(PjY5q^G3X(K-!*Bqw%+RU!2(CVvBn^Z^U=nY%_hw%%_w@vuAU~k%})YJF8KP1bgzS{tdsec@?UgziRtKCvtVBJm9~FbBvQ#$G zd$DKWj>Sf|eiNBWW!byh;iPr2hjp;>kYQ^g?lNqx?P0C07)05)Z7YlCT=M4C-`-ne zui1m+-?TxG9x`lh=-2DsgErE8*fUhIh_Z3pwsGbfHqv`q5j3OdA;ac|e&g;Mwi5KT zB1~ow#h$fM^8TfJS`mDIRrNU;HaDu1MOtfnSZgZ=QSAS;>+5MnP^rA9+G<7bkG4j* z?@LE=>-z4sBL+QW_*n2y^)2W2v?6Hil0lTM1ReX|l&oQS-54*l#h`}_{W^Q0Gk0G( z&p~JOCo_n0?X?+r!aAM)`ZSUtP9dZ`z!*#@=pwxPpOS^m7*E z9<&{D7d@C-*ZU*2u8*Gd_g2gDVNZF{cgPxXHHPi@nB@NHJ$@UEH8lI_p%GC6D4o)aWsxo!Y_teUXDJ~hF6J5jh>^sDiz3~M+22Gi@|_a!~umoOGl9Qn2m=95>965Wv` zb?bATwo+UhZ#oZpsdSH_Y^_X94;fnhl~r@=>K;S;1|PdsETXiFiJ8`F`6)Fq=pjS9 z7-iM0p?eHvYiW={6h~-v+K$Yi6HBTg8GinlXkDFHqID|6QO(fEBysySm3Wx7?*R(E8HK@S<)TPv&P*7ehN zWQHmhQSATfrYP3IzDA>Fr>$!JxIMN0*8P=_E8D$}+wQgNyVuG?hV{3;-|nT-IZe4& zea=`!*|^m`oNMTurrawAJ!IIp)$a{lL-!cUy^|S4v1ilXXI$qs-}_X3PKM1a-9WpB z&S_ZHDh5&P|5i)45^yiIT;(Cdc71*8BmZWm z?GwkbPplY3S#}+p|LL`t$a(knyVf87=t1Z77kqQty;dGFEa&3c>bl3kes_Wal-I*| z;kw7bo?4|!9>(=L`7T`d7m_J?wS3w#Q4NYyN({c&isk-vmfp~y3^J3CB{l89yU5-*0c6htDT=d8QvFO0F_;=A?s|Jl)leZTpw!QpFe(D~c+_UP9>d~MR$>{G{$ zKEG+dt$HlH>PDk?ykXQB)89R_x7pW@A3X8?pAYC!++fIF;j&qyuR7`?V|;$OnZ0$_ zIdrht0;8!O;SuW0lctZp@Z<9*X{`C`nZ3VW_{G6CJ6uuI2!`0(pS02Fj2+K6jTNTP z?EU<(tp=Yw_}UsHP-6UL*21H&dg&b1e8$Y)R(D-A_|Gm!q*DE2?eCA?JTjI_^5Y%9 zKl+!ST$fs5#*dC4eeU=%V_a)B|MC|v9lYw~y%QrmY6UW8O+S0|%#*G(#K(J! z-GfCIoG~W#?wMDN-nr*pxd%_aY;?IZZ%aM+@VVa^-F5n%#(3;?JNGtw!ySWP-!ML= z9t@AzFF8Z@j7u*bJ@_*>7~|W^?9zM9LRSrTyQ-D?oQy!Rgtn7eYG&`6{catcHNIwQ zE0#SN(wJ}li$>dfTyGl7Sr5K&{EdULwP(~Aff8e)=8rzHQ*W=I-7{Eymvj2^M9nAH z$=YdjxwZdf8uQ=3Yj34fuO9s1=NF{*2@e^vuUYb#(ZyeQ*cd0TzH@Kp#di+6#~zqw z5gCD!c51haA2i0sEAP^~X1xmrJ3qQvS8Wn=O{lLdbmr*KH+?SkN3dJ1mEN{<@0lN6 zF?iDvALvq@4B4vrv6nw%8W%3HbMNkVT|d}jfi=4H$X4rK^x~tFH0FP5r`}C#+&cK; zDf87df+6bY zGLBH1kIU{lIs3e0-I=}hzyH(0(qliYwN)@uoos$|uX({rwbPqt_73P@G#J0)$Qna) zMJO?%rCY68OYYXY; z{UOyOa;;FB+sFTEa^5}J#_qp&>kanb<)&0B#tnwp$}4aE%L10EzyF?@y-R-c`N6MW zdu5FgsIpY|J+f18^FMy0|E}BbNu_$?r;D97{~C*=QTdZy_q^nRWfn>Ow8sPYTyn-! zEz?-+xt)4zjBhaZho9b^`aC>}8w}a8uC!Vov_3!Jpa1FXfBCIR!^%FQ+6rYW!?b0- zyl~R6)nM9jAC!jHj}KgUW#?1d-;p%JLxyWi)7n+7A01miY78q$LWvRet8#nSa(gP3 zjf@eEC84aXM%1FdN{sy9rZ3qj@!a0E+@4z3R+i);L$+n@k>~!W{_x!1wcK7~1WJr( zk!p?V+8R}qiX{=l)~k{38(y?h`8wF$@0;IBjPQ`*>*L4;OFe0f!SY||t?-poy3Z`} zje)#guB|wU5gut+4j$Qh?C~@|Y_5#t8RaWZ*H)aw2+w4OWuK9p zeSF2~+KQ951xf75+dDqnHBw&JAmW9vuqsO-UzZJB69 zxvN@ny0+q^Q9?$bSi)+>>Dr2uda$Ui$CZYyB_scS^fA-$6{l+}PK^;LF(zv6D^Ax| zoK)MWIcqD1tr8=}iqo|fr%w+Vo?S=YzT@w$RKDVLZN(Xz%&;{hq4f9EZnm~pD^Ax| zoPpZJR-BQ??zh)3p^R)x%btX~ofu*uZpQZ9)#)%zfwIk*P5T8E##NAIBpzCE~kgZI@|=h!*`&&*~e{`is?l6rGr_)laWgm<74p`>Y!MC5=DUGW*N0Ff(j8jIdHJ;ax z!Lv(zqhJsvJI+*wa&m&eu=w zT3e-cJ2Ev<-fq5rcz<-QKjzXyhHUHek-bK5o#^wf^?AxAv3?MxNRd%nEsd)?F50ha zYchr@A7BoA3WZg)1`+DFJam_w_4YqwomWl zi(WLg?cAdZ22pCawHBQ+cflK)MaVtpY-38e*HFeX zC6#$5(|@gV&i?xBZolW>^SsadeXR94ds=&~wLg2Ea}RhYze{5vqV)*&w&PTHdc6F? z23PROtJ8pyGHsU<{-UHJ4oVQgzaQ?}{Ut`rxY^gd0oxk8|3+vn{`YUc9lIg_VMq4ZSIkzNxD8c9QnDpMH>{ShyIZLMV7bX?-5rJBaPXFbM4WC}#PHl|OFhmac zpr+sZ;LyM`XbB>CZ65L^2cI1z3pUB_uQ)NoK%f?{>_Zl(Sk7MZ<*lXsw?Fm*+tm_8 zuw79siMWjDY~az^z(AlD|JDqWWxc$=x9t4rxAxQ%-v^ecGkUbKs8`WxBKKc|rCj4B zR2ecmuq%C5vm4iEq`aTsax?TQ6WA5a zZXiJf+Ja?uC_Y*?7?s7@pZ#1AKQschqLr;#;J_(rqrs6evRS>AZj)8}Y?S;5BC@Lp zVK-g1FR(#+4X341G}Pm4a-bax4 zaqwBF#c1+fQLK$ToI@VYMhPPLx3-0t7Zv11btV%$3$^%34`XfQsU7mv!J2EyzY*Gc zV$ncQG%yhST&>09)0uND;y4s>f=otB5P`N3i)w3V|{kUE7#jH+;q!ad~t_SU@ z^RhW*j&Szc_2ee8<#ZpJ_vR!QC5WiL>~DMPsZ7pjb&wDPM}I4xxz|r-THeM(1ZurL z@}RwAdN$|4D;zoJizQ;{yaBRzs-HZRWXyQd9@i#|Q~j-7cH$=o?b4H|x52q~?cYm9 zhm!qezKZF5lpvz`6Nl}=UREdMso$NvPmKPhom}?nNB*EeC+(dxGdlNP-C&okeB8dY zK9j>|wKF5m+GA2@bUMGl=h_+04pCuVC)ra?@KJ(@nd^_*-@TTFPxXWt-g1|y_)1rK z_=Q#m0=2M*mX-ap)#9J>y=3|OO?{LgVr%N7_M+r0PVO!2cQX$DO1Sm=$k#uvVjxh< z9J#YJjeP1>9r?dwKl*=NxL|+qavFzEjops@ZMW>4)|tBeYrEXVtM<_!9&s|x=R1}Q zjqi*4{Ts-le{bRDRuUuPmv%j{Lz(KTex7P;h%{K`LgE|rsG)?GVak{@^*_B#KRS{L{i z_A{9Zt)OwlHEk%XRlg~Qcl^<3|HOW(=3=@_Bdg$5WXoV*rO}qP;y_&~%2;v}F%u|3 z1Y0LtX?ROkrDKA;ye)&QF#e!{KrQxq4||nVv7H=qbiWw({3kx|Yu>HAw=12^=q%lJ z!cN~J(LT{IgH!C{Is2xnaV(V@HSDqm)CK5KT=zI+Ijjw+r^`>;-Dvco6t?UVmn@*{`z)+Lw{I{ex3b0`E~<=TDY>7#eSXrJNb5FcOKd(zv*}oT@cE`qS67xsPV!zJ*oqW5%{8L9~whTm*7bU;W{+)cg zKnWsr_Q4ivS?t%@zmsn_5U6GL>Wy_fMXh%_%K6pb5;{ZT-KjG&-nH!4*^5tp>=s!& zM*@xr6b%GQ5W!J_eSP_?d_TyMfFlA$0|S9tI^zg!_m8*Niv_Rrk`Gc<7drD|zr>M% zBSQTN*KCdu94T`Cd5+rP*ugP`;)g&9B5-_kV?utN{X6;gz~k$@J(l~Df5eR3ve>V) ze<$A_#15U^BZB=pd+rCrxt@XjI{SC>?FIt1aD0~4JaZA5`M{Gh`~9uP`2+13?ai`2 zJ5WjPc(bS+S7C)=iHN}cXjv~UsV*mPD<%)sm}($UYebVY&J_QyU8yO1(am-vIe2?^ znW^jqff7WR{wnu|XJv+*Ib`2T&lm{QDl{>@Q@_bI``{;kQyU#WYA2gLcTKear=ma! zBGBhsR^k^OWTxv^MDah4IEX+kK11ouz_R*R=`CkHvrVj+w#q>XA~2#_7N5EX)9EYo z@-_wnwJ?7mhMu0!?NA%W$qUbFcrKypPZ|S{rPv=wJd_}U=ZVMo%J)e$S3FNVUo=<7 zi3PRHvjMLKuL-S(k?A9X*PB;2Z9Ma$yxzR-wB`l^wJ?XbEVe1OEwU@)#DWOSgX!jn z?3V49Y}Y`b7G~!(SF|^Hk7T>Q)yUfsVP>yxlAno zg~1x24@S>tS^t}#O|D;FU*70H$MA57Fn6tO=aR=uHjwl7yVHs6 z_UK<+HhL|$KnWsnr&-pG^>t;tZ;HuMO%^+dK&?-zr*+C7ykl?P@f)=<{6)vA=lpq54re&?!-byarpG7V>(j^fQsFihL2B&-66}wC}W3LU{Nr)M88LC*(iICok?1_l$bw zp#%|V3zo&B=FvZY=e&VHE#9#_6H7Ympf-4Bd4_3reUu;qt;e!>_4?B)Ze7>NK%f?$ zscD~+g|Ma6o7m1cZ6iXTkixSwXMCLbQPyW5P)ncN!nzE$bhdc1_TVJSHp>|qTA!IM z@owT>_2J8FjNAtird>^=9m_j+NZE}>=7m}q6KUk+71%q>JJKZqC5S*`5EGmfJ@JYGF(yFG^mTy)}7iA0>!D>!Dan zk$@utMFRtYS{M^8>lj5Fhoa8>eQy|S6e3K!T1OF$BO66E1A$t|IZ+KHMNN*L6gdrU z2@(4I8S*~N&NE9-484IsEo8zhtJIM~YHY3&a@Om=3p$^ulbDQ4}x zhrCav&yif{0S(vUy&ULw2T1$<#)jjNR4wGD+golTZ3*^JMa}wfM`f z^W+cAs(6|gL$qbxJJwr`ue4U=Pg}%C2_k4Gdk?v#l0*Bc#ywVvan~<+h(Il~SFdk> zS>2g)T#T>vp8wk8>AlC_IA@nlmB>tyr&TSHtZuT?~sD)!9M%Zbn()@W-3447O)&8wSB_IOhs;Ct5n#jUGx&HjJm)wP4rgJLJ_U$?u|8l!No6dRg$ZDG` z#ATK(yp=gHb+3Q>{jTzE7Ta%_@0{zF%j8t+zQ8wuPLqFJkj-Gat`e$<5 zq~aT_#9!C@Q{7kP#ev;?lpun3ugkGFjLv;FZSLMHFndqa0c9Y9dnIkej$+GhF z`N996-$9;yb-K|8B8v4p;a<(3$$9J`-$#vkKgqw|xt-k5>r(@PT4ePu`{B@2Kj(hw zr#s$H%H)iG=U)%IFLcT39JY7Z(KP)uhrOk`rAljk z^6!#-yFdvd^sI-RKKXT@{JSLIZp;;G;jCL0`E{TCyCmN($gjKP|C~(iA22%@SR%87 z*jsx4eCc+d{JSLIZj1vFYLqlWr2;m zh4v-Pf0AE!$-g_frlfVSx0Xebz^8~HDH<5#K!o1sAwy4*z^8~HDH;fr=sm$arP&5W z0-qv+q-bEYfe4BOF8O-LYRe2gMFO89f~06*AW#eEjZUc*GAoJ*91V<-QzUT7zdNb^ zylqn?aLMmG&9*QjOp!oQMBr#3P=W|ETcSvyC?aq)Fc7GvJ!*IhK#@REMBr#3P=W}| z&ZtuMSUE-Bnmx53kMEIxw?Ce3IXaf`bG4@q8G84TTB`WjbTa=3JB5zUyiz(Q^7`YG zsMer-4OM$+R*pDE8;GFD<54`ZQ&;4h28uR{q7FwK1A$uDL(6)-aC3Dd(|NHnd5zFf zpDlx8het8Qp1nMcLovmp*kY&Ma)+#)qK%@cBPikslpq4fM_k{cE{Y<8plBd;j>FzS z=Lx(ADcX1x5$vPw_$H1bfue{YC>jWqAc7)+N50<9JBe?wC=w`&2!f)4fj})BpJh=* zQxw?*MKz;W*dE10kD{FY*hGH2hN7mT=qV_23X~v%qNztw)lPNmPeNQA)>F-ywozD1 zN*M^$qA281G_u=1eu)s|a~1hsalA?|2Q&RxeogTMb9nl$!Q26g;*==ZGRZ*+B6RK> zdQpmjiejOlI4BT-T4t|y{E|Txzf(`9yZ?=`Ytet;ezdG!bstfWh#6kxVsMWRQWj9-@jL!J<$Eb~!B~SX5mv)nd@8q*lf(VR{l=Tfc?`P=QS#Fr# z%0mQdVctb~`_v!&jvw}v7wcbT+lgglh`@ZsvOb-*(I?xIsh5;8ayZn&?2PUvKJ2N^ zPW?ep8xF25S|ZwlWziTEjYWJny_I2Ch@g4mG1}j}$cz`wlcM<&h3@3zd?9u+MJ+s$ zSr)B@qBW6iN-Q+aYKWlq_Gqo_BmORGgVtNs{`sb$H8;+KsAZnj$fgw87Tc9^@ky>?i`LeXDQ79jI&+-)FG3r~7b|^~>^dyTU=1)vnepR)V@s&@JIl*c&PpR1AOiO$-O=AFr;7I~FL#uA-$0;Nm3LEl zQwv$nyN8^5uBQa$jeIBn!- zuUGa_f(Y|e)V^vOmFso7Z74FpK%f?$`uLr=Gk)<@t!0|{S;lz~5jvj>Pel~{eaZqP zWdH^OweU1awFd9hSKfp4vTu&nMka&ShnWH0G?Wu+)7Jd5NR{bE&VUHC9?No0*Hc-K z=9NpE^)wKuMKkNsJlex&^4pmgo77Z`R+f?Nek?9ff(Wz)>eUUY?hGm=@4fSrg9y|j z3*ptZ=jY=0Qa3HDtg4r(F8eOJZ=(beXg&0PZJFwdP_o~m`)qBoXQ38Zx<^lNejK@v z+MpgO>KXTn_dra72(%u{qERavy=?nqaUT(=MLX7`nQ&I-=6X?@Sw%CM2@9UO@waTF7xwE$4&uiY$e##NaXzq0c2DGeOz0qAZy+WCMX(`m_{!(PF7ut6SI4 z2(oq~dqwNR?98%gH>q}2)9{Wm@=_)C zAOdZ{vdHtO##^(p_c0Ktg)z~x$h#@>a&q3bA2?fyMPWpsEzrF|rKW1@?!4?pJw%`u z#zf2dX11d)bS}l7+D8c@(0VNE*WOZ5MBr#(AW#cqqGeIEQMYfElRuSt-$w}|OuM3p zrYN#;R5K8$g)AO@b6|NfMbVQZr;idu=(AeLsu4S{h^1$S-aw$1$qru6+f5bEzr%0* zcq^YO_&xsi26JKjyZxPS62EHjBfpXB6*&EV;?{{j&>n1azq>lr;1_@Kn0@@-wny(c z2VYO&-}J_^{tiokC{~N_gx8+wu9g%!>~AgmKEIr#)%>+1 z{-7llQy{b!BdDj*7f+6s=%!M=?fbO{j4;N5eP;xJJ0rYT+aA|Vy*j$1zv}Vr0pe7# ziisce`8pUmf0=^!HlsJzteDvQd*($`7w)DqoE+n4D(~@I5HU&ElMunb`HLQ5j4D&N zn>zHu2mXrwU!_23Ek+!e@or*)N0}YGP`R60RIPzuv+ORTSO0GB;rnWNa`jTv-pS(+ zy0$SuXbB>C)(21Rv*FRKJdQW-c2{qX`NhjtkYjtKsJdrY4V>sK&OUH(*em2T}! zFL{6Py(I&owai{sDbY){SzcOvmNB*-3A|FQMXQ;>tBJj}tjCJIs+_m-h~Z0irx=Gu zFq+?+3O#i+S5DT4a}`LUo&@iMn{Dto9$7on+5K=FvANQ3)G(UHR5Kj;Gc;FKw$^t3 zcsN%vgw|q&o@si!KeQ{scEu91p9Hoa{;l8ckJdk!kxbV8n}G+JBZCzbDB6QN$4xae`j)&e=Qckzn3<-!ZGoZL=MpZo*$3 ziXsm0+Mo?B2}c_u_&4w1uznXjLkfh}VnpCE8gY$q6mbMa9HUp*6GrHFN$Jijj5vZK zPJqx7MDWUTlz9IO9*6d#6mbj$YH=IvA46t4@}eGj(E!1*h$XDW(LfvwzR(mziLi~x zi+bcmMfBVaEI|bSzFeYb(U94OsFnhuwXlb=sOC^q(}-Y%_}r+yn%u)!RC6e*r9iN6 zXDvoN964ke!N_UVf-j1(7Uv~kC5fSxM4s9wPp#KHkRXD8lf5Ofz0oaM7&(24oGB1m z3+FHvIem(pdK|IY)d+5bvyZSM9mgUUAOJyOXtO7bR*>M7t~c zK3o(He2NCaTm^X)S#{*w6KAcv5};}SC-VM}MFXFrL4eQ_L`3^PXglUhe2NAJ0=2k@ zoLRD$i1`xEMFWJE{2TFb94}K&eUNhMC1dsl*1$P6_}WDFwZU9*eoY?L$f-m7i6p#g zJZ~Do*>dPbtK{sXw%!>hy7c(S=V$4hLGN15oG>N^-~CWMj+Yim8)x#H#j*H`2)#eT z%#yw>q8_Zc>Uq4hzi0e71A$uF zVmRZV9YwRd`OY}MGtDka5E0FKl@NffxT8!q^46~)4ZM!ME>MH;8 zPt$yqAcB9hO^3Npl*zE|ra)*dMzDp3r=qA0L2YPj4v*-jCs2MV4qFP>azz+6CXJcE`XLR-&srTM*yXw4m3a|3}|+Q!28 z5!sbZcBTDQ;M)GGhU?ry~mJD{Smi!yRc}eIQF7_MA>)}kze~G^V5qnm&9)T8p-68Nw{gSwijsr%r z_py%+EzRE+iAfL<{f@j3eVKwioSTsAGJn71--tjf`u7cC8}#*yz)CKsDW%&8B=}st zn&DjaRKo)+IbY?xZX-aT7NcoK62rNgkYNbVuD`KrQ9W0I1QF5NMBeAXvxC(5^t1gs z@BOalDnOuCw6cleiDmzzy;Rmb8~t?a3g|TtB#2pT}F`ZxDInybjJ`Zj+(u*7e&u8mnW zKMS?=@9RDIR778(QLmD}dVc;U7bW^PuL0Tu*;Vn;DivAc^P9ZbbNN}QrGIaKkK3Rx z=>(QIf6*ovCHgnpQuI5rs|eu|LQ87$vrtR_4%^^fvA=4u$a>^Ne z8hPxwj6f~@JDjU%c72*%Jy(e=(ONuL(b`0I#Va_0ERj|)ro{-<(!awskF3Oh?Bt#$ zDAB)p%_HlH_(WhJ^_er4Q)$+b5fAgL$l3*2dl1$1xi4xXfqSC8U3li?9Yy01w4;J^ zAA3udAR?NDgmA8S*S<(TaZ}Zzfv468)Y9HAj34Y7IEN$8z+ch{JRD09p)Dp{^T_)+ za#*MZ-84c{rOq9Dg?|CPBo%>?-u4E_qS$ABe!lqJIyfDBY5Up4xji|0Uf< zAi?J{f<0U~R~!v!5Bd}hbQ=KzwY0Yj=PHUgK1CcoSHTGa5!zxxyW*(EmPk=e&sBgx zE$!{XHIE{vPmxovU~tYrg!XWJ0ti{PN8*!xV$}=;YVmJ}NyYzTPM@E{n*6NjuE=FhAJLYzdl$WOf1#{mP9G(Rcyi`- z_hMSh3z_YOTOL*KY_6!1hzmyqYMH$%(7CR9SEX0X>GLY_hsc^H+YXQ zr;iBK!g-^biJ86Cp^K~7`}k3voy(qq{RsOL_9g5`cu$7Dggp;?Aoe~eK}1wd>9SX% zw>je5s_Jci^&1nXk0T%RM|yAb=a*d0ano1N-5=6v$tkXjR@4jb)w8NXJ2)A=xU!ieZ2SL7`WWIX%5L%)RNg31cm+ zpg;*C^a_TYKG?2-KrNiZhdYWQj?g=YIaa-+n61@2Eo5t9*9w#%Lhs;^(+AIBAW$o| zZ-Ns&M;neh6mg7RVSC#1g={TH8;&{@arg@~{I-+J5=3Y}7IGQdi!!H=2-MR4G34~w zgR&=OPG5U{mgs1}T)2)BVH@m0*^`nN6(~W3_M#!D4^hoPpceL!zV$-S=g7vKK1vXw zy>`gyb425@P*gJzsAY~EvJC#N0l(Yh@!IMvgRMlz_RvanCc~UQN)VxQiICIhsL9cj zIekQ+7S18PA4O4Ep9dOWRl& zKiH<&wwTjL2_m%hgl(|hvi&lrj|kM#HWs#Vi1tQ0+9S;AqXZG!7Q(sW{m1)|IekQ+ zmbS5QuD}uv-;Riw#RMyu@!=`eK%f>zBKp#8)n4kzHQykbrtC5X_g8MZO8 zcLlZUL3PEPJ|a+ypU<+ejoDWVsO`(2QOxP11QB{Q!?{{LIHy`#x|uploIWB@i|2{Q z7|zw=Yj^xo#o8+7^ihHc^fB}o*|PlQcP!CaF{h6R)Y8!>T=PGxZ}D&T@2Qy6M+qWy zY!5koK6~&PggJdgpq7r0A*WxiMqib8*hZf@eLMr8#pvJRiKT4AE^1wiv;JY?^iiUJ zbKlVx=v&3FwO0vEEw!3BeXYgMLM{C}47iT=&DgtkE6*(Pm9F{iJ!_*tl>e}`>wkGN;d z>7zvd<~Gn4i1(pUZ>7<^iRwm@&C(CYCj(hA0& z%g;hB{X1OqJY*qkDFunsM~VK;Yi{z1z(6`$i=TyBW`4z%&KA#{KA!u~Vzjpl&z!uQ zcvmr}j}k;^iwWn7cP#H*=JXMPTH4!%@q@hrdk69i4oVP#wm_9<Bf=lV z=_3NQw6_cAsxd{ITNHJe(?gwVGWizE3A!kj)z5JCKmqq!{lg22@QQZrtNKrR0M1Mjeq z(ocd1y$zTN z88H(+N)SOa%U}PGZcJ#NBr{UX>7#_^hQCE0+fcvP}Tp@xupx_HiA*WA! zLolz;oIXAawQ$}ni@cABypK;FCt!lvGmsw%c>U;pFv$EvUqYTo=o>}yFfj=t$Rh>c z!wNZlVsS*o;`lgn@~8nL!8tCSSOZ=^Jl7J7BO(^ZM+qXZ?SRD*5sPCWP>cLXzz~Ng zVe&je-zcI45#~6^y9s@3NnR}YS{ZvX@__-b&zwH_`5=c3y(oE5!F)J#`Y1sJu{-RC zgL_r_s$;3IguZ=61Zv?rSr+Bgf^%x-^z|BWoX}bk&lL13%$A@Hjs(G)vsSE)kY@sf z9tU&!x>x)xMCdVvY!u9ufj}*sLt_P*hYPHMIX%5L%)RNg31cm+AVy@Da1 z2)1h=Pz&cUxJ3?j6m$A|=P<{rcT~jI275C+pTn-@({@aP2)%JT-IrC_#kw+99XU z(IC31HV~*~jvTTKeup>6CU|XimJ!|j1ldPuB|4K~PG3iTmLNiBI3cG`QBy{@;RXV= za1Mjpa2ef(8*_ySolAsP0$GNEKrLKZBNycpOOUtm9@M!gdm^3Ng?o@9fsAf=nH>!C zD6(ogiv(FY=jz1gJIrB*oIXVY8Qt(QXBm?q0^1Jm2W51_YamcdXO>p#gLbJ{>4?sDC-nE=LVN9gIwDEiv z8S#nCI>+KGBJ?f@GfU$0CG+~s=_3NQ=zL}KIWAR+FUstBOo9k)iD4VWy~>Dt zH4vyp&ks(1VH?EfOXl^N(? z^@Qx2@aznhXdqBa+gRw~h|ibI>ocd15=3b02{{1b^Ck28%;_Tn zwX}_e@q=tiMt4Pqr$&Ufg|H2>TN&L)83@$UHWs!)e76{M4dWL}>tgbV~~VI-oj+>F^IB4)zK^!1vvz3SX9%wCDl z7ZLlxY;7#BMTB0>a7PiJFPPV7P9G7dMQlsJfQCFZu{e@h9Om>ES!nq=LP%=BnoIXkrfj)-neM)qe5d+EhAF*el zmX1E*niI<@BbJlzaX5Dm>XQ(mV|&Qy)7e8Zug{!5B2Y`m$B@$}K3_0f%bY%*0nlRf z@9@MzjIf9pVHYL(H}@TFfxeQ~)RGbF9J6YE7Ha9=A)iRhwq#zPIenDq-@FEB3zkLf zxs2HJ*mL<=sHK00d^<7pGGgeNZx8G$V(4QwhPFVrGSzCx=oTRMTt=Xl{vEbKJ(AH) zgNqXVo9z{C!Lo?Ym(1%kr?0j6S*WFdhjT?UE2A3|7bW^P&lTE&Wzp)%=vF57Tz(d6 z>EGd+lZ8m;^_kO0iT=%NZt{u1Kyn>fV7vS*)H3rcvUCyMU>Rp;ZC8xe-Yz_I(ryyb zEg9#!u`?$kw8eyTMLSk7ug{!5B2Y_vyD)x`SCG+dA7{it4#yHip!Lw-H@I3rGOy2^ zJ|a*{d%G|Wl6RBQttDq&K@P_fM4&BL7V-Hqx*27@J%&In?d`%gh|ibI>ocd15=3Z= z3FnF;fn;8vIekQ+miBhxToIoynb&7dA0>!DTcGc3-{>fr*Jn;25vZlTUAX2HHDz=g zZk%xtp*>v4=@X+Sqe@u=fm+%>hMfN5reoAIJwNf-CpH;nd9Qz$kodY^*eQD8f!lS% zq{NqMRCP+EOXa1$Rv|0@rqkV(VQTcse!IMjuAOhPXZmG&BmHAfg6bRJnFyn!{>Z3_f8&wlVtGE{~1>-;o zB5-{4rNVTtt2JFGr5MM|;kVp1PUaM2vaFIH4^b=1eG(wB?}%tw=(2nCaP~+ zQ018VWeNmpsaG$!ZO7IR=8ahA_d2RN2d@W+!%dI5qtA~Go^|StV{VCb;{vVeo6oqZ zu5^ytxUr_2x|QZ+fItZ%%r0ZzMX*9dNdq1s`r&bCOKQvnF?rFR>c-D&7*Sh>aw%vkLH@bIsEQ{K( z?@3jp^%DUCC5SNFNLRUma&{F-fk3UFX6|$s+?^A(@dbSq`25QJ0Rkn6z%kL^$h}fo zeGpeY#W=ore3ff|;-(lA#oAJ3)f*i|fWW>ZVn(gGZr^=BMZKDJwz&FmXWbMC)Z&@t zUWT4wQq6*@>8{2B0=3p;{nX98d}r`n6LH+it&R_B79dc9h+Wy=ab<@?QLi@a&Y~XO z*(wDBwRoSf1%iC0!U2%g2UgMBY+4N0{(amM1iQ5!WEHuke#qPL6bKa?QCY~zO- zL;cF5hNVED*7(6`-6zuAj@o#t*cAWkaYF+HN)Ul#qOZ#P54p*MOZzFLvu zB1Jgtp=I^yveuhpbgYIJT9&M zHDxxu<|bmz%nwA{e)RnW`VS?D7`4BgoxbGN$P&LhzF5>vOW*$Z7Xr0tZ`#@u(RWh! zCyLKX_6rcGHR{>=_DfI1_BkL9SKc9RR1Ck4htER9!B#KXgB$)G_3D!ezlr?Qx(96_ z0=38!*$=(wrM_3hi4mOw#D8h=T$zZYU#64qu4@w@P@;b`Vp-A*yWXC?QLox&${{Z= zXqf_mS`;PhhY{z^k`-m*<{AOQ?y}b2(J2AW%Zu zF@)L18;uIfg*_UkK%mxw^KuF*hBhG(Z&SXAYJ(Yff7WlE&GFg_|U>=I3{{4KFu&WVdJP2<2cskj=k#IpTYSIdq@>2gNDoI zrCtaSC_#kv`2+jsci)XpcURMml>1j#Nr6BuiibAG;c#}Z`=jKjkJAST)GEFGf&Jc^ z@YHA`T7NNGzW3Um-~@>hMErfqa-Kh%xPg5aeWm%mF|zBo15zMRi(QJRc0Rkn6Fx!ZBZ3+ZxMY}m_gZIbyjiUkt zN)Ul#;)=%JvdsMNQ;Z|pcPYk1?}k6!L(Um}AV6T>5fS;Ws8^G2bdj@e{h0!RT9N0A zW;gQGlGi-)yTP*}zZ+;pK0j(BiUt7!C5SNFh$2o31ZqVdJZgh|d!G4sgK?k)5jZBx zisDC#aYQjA#hB=?l9a70%Y0cPKw#ey5yjo8SG&48@~&Mj1p>9As2$C2lmP??)QYm2 z;JGFu%6$R^N)QocI8m>n+$RMBwW1s)>J{fc3wksR5U3SpHNkUDM3nmk2$Ucq%6+0< zMOj}81ZqV&W7MlCvkVabrNw*RL`2zZfIx}<&4?(gjd~Sj$SDx06=lv*ucEU-fQZfm z!Ly=sLZB7p^HCeo*&slm1QBK%(b*sc0=1&7KWZa78-$4P1QAFOfn%cYYlo+z6yu0a zNGZld@7KQ2MSMEvjR1jtM?`dPi+WX}ZGu?0VnhlAYDH(bXm+DhYJiB&oDQ$rFB!@# z-Pj_ACc zVodZGZ#&iW3cF(h1oj;f5$6z%{D*Uky{jcsB2bHZn8qGDuMy5hoKMP=W{?lVwG`Pl|CwTu+KIS=PHV z=K4*04h|65cSJ;dS=6gFPp$Od`ffl91ZvUlVs0^--H5ph5U3Tgk->9KM8sJJ2$Ucq zVkV~uKnWtuHlo{%6bRIcZaJbhqI-h? zff7XEn5Zs1yqicdj_5uj#h5IsV4oJMiJdb*VBZlD-RVTV>VEV^mGorh6bRHJyXE_@ zXm+C;tRU-)?xTWd(VlZTva#((cVST*d`osa&B*|P5=5A7L^p9M5U3U1Y(;HEcV59b zP=W{?lVwHsYAMDM-KC`%6Q$nS2C6KbmInyzJ0ha{$f#FYjt*8Ocg;?LKrQmve0Lko zZgevmAW$p1?G2u5BBDFt0D%%jL^r?D=`OkxPJuuzicfq89h{0|cftVzwW8ZzedYv2 zbSE5~o$*~b#K|Q+4i{>>+N^Hc-ou(*C)a6zXq1@(ry?R{MOq1|6?U; zeO9K1_fDZ1{~rWC3lW1~tl{OZ_Wpmgfe6%M^!z68{s#ibf#^M}pYlqsn)@FJlptbu zi{jqc%M<=T2-GS+s+c!x>|6hVKuPX9MPq%(w$0f^2_hOM75zWv3K6K)t$8)?{?G;g z(JP!qUQOM1oCUL2C_x0z`hU+AB2bHa``>njeUBeln!bs%DCqmVr^|SQJAVEj<3LH# zLgltX4mljP;7=@V^l#K?JsKjsp>>#WNk3dB}hC ziuZ^1IJ~2@Ct~z}?^>L99<8J(Q~UaTjl zA)g;$D?tccr@AWL*C(o8#%m|jlzGotOwKbs{QXhEBhoBHzbJI zmOIXClv5)<$Xi)uQ`KbVXOBA{p2*>?9F=T;S8S2d-u|C+cz=JGY!|Jvh+^``!?UOX z4_e9Bj}*7@S=h$2&|?9Iwe&UOR6i0=0fhjPp9bq1%|(sFdpZT6wvA^%nyBUg%5?Z`8NRc8>uIZF3xH z&lgjwKv{We%O-&mM2LTKc;v1&(*?D zE_)L*jFyjom)Ag`)=!Vdd!M(_Z7jY2x|i?eG4j!kc^#A>VpLs33{AZ_F+;I2^38Qi z9F!p9w?6USGo6#{_nL688g}mDq@y;n6@JPY)m&=OnL_e((ex4}h*+LC&YP8YkNw90UXQ_h)2nMo3d_QNyn#Ti zgSU0zff4B1QDZ4k?(qHkDb06Bc93gw|{nRygZ$+yn#Ti zag*XatHK`po|;dH2Q4r84I5>U#adUDC_zMP5$9d%vd8XmjS($+oN=-h7%iVF{*;5W zh_l=9(|E9}Zl9JFr>c&SpS`--K?x$B`##<)Ha^LIxdyM`pxZq};cLU>ur$vZ2-K?Z zQ#|a!Yne{?J?C1o_#7dzzZF}>c?&<-WB<5%zK!Fvtj|B(>*w5ZMeJ|fz!*6q+V+a` zZYJ)re|?)r-g5L;{=FL4#HsSl3ejvJ+drcmC3Mm||y z@UpIXSNzgyh=D+@H|xZEEBo!WAN`FHr)rdz^XfVBN|)RM`~K0YoU!O!Zgo!Y=zGcb zw?o)U+TY6~|9InB*}88p2S2Jqzv zh1L5R8_Klpt{XYksrWcAYk}k--@!bHYSo5iQ0aebE&Gq0>YxM>^OAs>e|u#IxqY08KrPH4EUWFME&iniz2t@*7aWuz;?q@eoxE+$Zdh(77bmkdp^CtTvW8e6QWzxAo%a{7Sm1_HG( zidxpZQ7yeSQ-(|VVH1H8L}cq2@BJ|%$!@ll+nAE|CHq{Rk+SH4Ck+H@p`WLk#M4)u zR!_Vx3yHo0C5YI&F5W9RKgk|4pWAr+k}brdq4LVzXAA^tp?{>Hu$FJiB zN)VAXOHS|a6G?W)N!&)!?yE(WQ9b3%ye}IF)Iz^vS))&$5=#obEUV_7Do}z5v}w!Q z_F5|WSLIf+*tG5j0<~~=(HCgOIR_BuPcE1E!d|q<{fm-M# z=xi_~my~0kkh8N~6-{JL@3Ggy4D#IxIb*rc7a!#GPVY&!>*nXV>a?ebI`rc+@=l9} z4xXb*WQ+6OE}k6Z(YU)TE2qq?zRlB0Cbm4}pac=;Ux@RL9n$+FbKATAXR4hno%Vu( zKrP%|mi5*1yZrAjb(8B}dRm|a5!V-zmspl$pHAj+eA@jh|8SN*vU?X3fm*n`=-Q%{pGUpqXkM3@!Rz{Z_F%hS1k(H^pmO&k;}yp1A$t&yXc!7rN8usj2a}%Oq?rF zf{3C`;yv&4B)eyQ9>>9rZ@8=P43Qf<&M*+Dg}aO1INb7u6Su9e^sMg$N)S0pR0wsv(awR@Ed3X4mv)3N^ z7Koo;>?kX3-e4e53wIaQj*Z_X+FyK5wit6%pac$qRDmPrHF7pgIV8kdynEPW%tH*4PF-BgK%f@xF3ZX~{jfi?c?VfK z`w)Q=MD%?>&MTCx_s5LeuK!BiZu0)1(FOvwaCgz)+phG!-+onhIb`b>0wsvZ{9Bw? z^2a3mrxI+tlM21!r+&J(9GYw*Pz!gLW&OS(wf}R@S7q4&dj(1m;g^s1CjXWcowh$4 z)z>?ksh8Z*a+iTXE!vdfn10wsuu9~T zFFb1?Pz!gLWu1JymKbsCdD&%e2CA5SxStU*Eh*kR^K!DiqCK}!`0a_}>-V0QtGlH# z5U7Q_%d&d8E5w}4QZAhpFHwRBv}wA1?YLJ|Id98V88R9O)WY3mS>@{86^V^Y%hlK8 zBuWrr?vL)(v&(dKi_0P{(-{cV!U#wEquvqWu1GD*{x0N>^YLC`I=S;1`Nv8*V<*Uk z4RgXtc)`8mYSyQ9WRH)Q7<=&h2RXb3wUYxj0(Td!dFEVdOOvLu(z{Ozlptc>({bL& z_~asP`vK^4pH;Acxc1BLcN> zchTEU{cV5F;+N#JHy#L-Ai~WYA7mVB`?KwS_Sc`@o7>vT!;e@J5vYZ`i?Y{e zQG$qhpT&DWtV*_P{>~@im-EyWH>cH-J4ZZjAW#c;mt{RUexkT{p^R)jrm{o{BG9Jk z3z)T+iywY{LhjE|)Z?k@Uff4=>qTeV#Bs~@WvF$xjp{`mOsTOx66oJ=_Xgn>XU zjBxZ9j?R7|+NItn#`JC@mwre5&e)JiIea%h#!MW_lap3?kKJo5&(*g-mQoY!*^V^GAgY+0~ujo5%u5 zeGCL@;qJ1mIXCY6$%USkY4$A@C_zNQ4so8UoE+s>`H!9Q=Onj~hrRU%0<~~=(f4KcDcZcI8 zN)S=u6fq%mW(fC3-6A#o&;Qq0rXBgHfj}+XUGz5j%ro9c-zCUT7L=7JLBx_W@!r4< z$@ZMByylIw6!ZoycH}QBOayA-?xMPk`oG(is*&k)(?xnVYKrP%|^cU=lmJ?U2<&+=aYAR8J2()R->c4iR*!Xw6Z2dYpXHZ1~eJ#vbf>E{B(@M{>YZ;_jl6 zClpaH6{scmjcFrLf{2mC=&;`n&*vky(BP<%XA}l83@$E-9_i9f+zeZ6ND^XGL=LLA|4Ej^X%z5 zzj|ZOX8+F@Ys+8fXD|?`g}aOH2VYw3*ZsJvd{Fmsi4sISzc$W$B}vDRpFSV&CugrN z2lgmwAW#c;mt}Q1+tlAXu!Q_)f-O;kh>JJlypx6X{^+sO@(WfiC2!K_?ht`mxVz|Y z7EhY$RgrP>(Hzf9lpx|jLcG`d%{_LJ8f;g|^$OZm6XIpFf+hmBaCedIwj1xHseDuNVl_!rf(A6*{#OXU1(7g`0IZViY3G{qfeGkHxAp z8-?80(LkUUMmYM*?-Ry4S^DM@ZGRjoYj=}K?L5nSyuY}r~UaqSCAK9h&K?Zh5M1R z*S<;q(#%EViSNrulptc9aTC|I$x8nb?{WG1GnEYlYTY7M*Bk4_+$AOgwQxTYtCoAWll8!4QD^vT zMpQ$Dxj$-mt0@LFoGk7Q9b_O-3u7X2$cG2IYt9UE-kdl_@=bL@zkO7PI?u)(JSAhi z_rgDW?cFQOJqy*ZxKtP7gf%Qw zDWa%iB&Zfa2_mR!#HCsghbu=ciz-DFRg47HA}B!wRf@P&PvL~sB2+1&sA43j7C{Lj zs8YlwPvL~sB2<&1s5T?0%RmHbQGJF>RTmD|XwZ4^#d?aWgn|ko96414xl|bx%mP&k zxpa@@aJ7(SQFV}_Dxsi42qlQ1>L8aYdjhm&ebB#+diqQ{*}n628xg2Ql{+roBROI9 z4poXMsu&5XMXx7Pn-SDypacx7Pn-SDyAOf|hCc~u~3MZ_~Xxnap`rxCl#I%Fw zZR|VMDY;Z*6pYp!2UQ>`szef8g@h7BPz91pl|9j1)%oKMmFnG=;!5_n97LcNRqnWS zujho-JLR9urhZv&$2&ye{DFQiR zeF@cMsH>Sy2(HUO1Zq)zhD%i!4%cW9pLk$|`gms*k#r-kgMFtuC6}s_g3+4epb8{K zl}HX(A)y2jRDtADy-_q**Y1v1%i3gdy8OJvK%f@Y6S;Ih>4Y^!u0KY7^iI`;liir`A`i|qHXi#9ZqM9F% z>wQpy2%c%G?1@HBwLXe!etfR?K?G`1t&dALvrbs=L$xJ7)tChJB}RW?98_E4QU!(+ z)|XIiiBB~qL4AoK0R+{SxRgUUVSNczarjit5ma&@0=1~3!=*Y6hpRe>3%@o@Q6-Yk zRY=%(wo0nz2}Wy^>OKj*$L}? zsJ6tX8k3;D1pABQpxP3bV!9L7mr!kqPcbDV~T@%ttCsBe3;$vJol{w*^ z*At0l)U^zkM5=nZ3m|4 zY9I_P^z+ubXL75*ewrZMmh~h?OGFSKF>(q zw$zJVGmCS-zbrAbAcFW9mri9)$jMwdebistF0JS=xvPOdE%YnI4qo}mkBiT0f4Qrd zLrW9-r<|f(Ubeyf?@3^BmgiF<*iR z)Z+cGy@X{EgX0sE<1>px_Yy9#LO~Sfctz|@5MPNCb&1t+LSB?OQAONnz>DG@qOSltC#yMeaRQs`Y)b2icWg~y0fj}+XU6wWf z)H7=2+O+c0gVh2hh@g83m-tL4to@iWtd5%7AeC&tbB}>QE!9$kIA2Ultpcd{fs)0P0pjt2cL=@>;P@)78bT8o&JL!aX z6Zik9s0Q4eCK?SZV<1oqcNg8C`%kK(>&l9cGgp@=K?L1PxWs2V;oZa$I!*L`vXD4y z)iV&Ng}ckL>ek7xvK-Cid|9ZeL+3$6V79%)8(A}U*w;N7)KS+0jitY%5 z`$61;bU*LX?O%}H^yF9e;_m|MLw5YT@ppo6+no zRldRNM9YT91xgS>_wz2@>qQ(uiR{m+dmWdF_J!^n2-L#eMR(f`o>T4q?j~9`$|6yM z2&xEl>0ZwX@92kStgozY%|z1&`3(eW;qJ1mMm6iI+|!pi3#t^CC_x1KF}l}__Iau_ z)zzZM$2;HDs%#)o3wM`gb+2AoRTw(NTUnfLO<+GGg6`*Cy4Tb3ylXM#?w#X3ov)sO zKrP%|bU(PUfXdh8Ie*podJ-jwK%1uO=&hO5$%5_t4!4>a2-L#eMStOF`YoUC2z|aE zLdpA9a$13V4oVO~ z_1Z4gc}A!07hASg`)8$*rAw3(h(ImeUG#0k)}7U76ZVUKGusN3AcE?(U8?hR!kXILG{`$)pj`rfMjbH|<8E0jP9BB);5r8>_jo?k59T|Ir_BWF+iuLc6OaCceOpWk#- zKXz&EB~LjnP=W}m*LJDSGs@e4&f8wydv}HB_PlQ(Pz!e#)%7iZNmaP=qJQpx{|J;I zg6}M-&NDinZ)^IjnwDv(pZ$?65)r6{yNkX_p02*i{LOd%Zxho=lpq3a+OnEHU0pqQ z<9ol+v|I)PwQzS)jA~q3QO&5&^`a<2gtjtU04F`y+tJ?~cAcEdoa_N1C zD4tioJ5X)ST33wua3xSNZ|_xbkb2|C zgZ8qWpBo6&!ret*Dfn!lTDW1mS8CD%ff7W}drL08?+~5O>mTc-?BiMe&(HY=0<~~= zQH@us?&@ICNq+sVYXnLVLGLZO^u9ynuS&e$PNjc&mfxZFUIT$zxVxx=u60YbrR6Vv z^0rL^C5S+qwyajo8>mht&-gEuKV~3M3wIY)a$Kmc=-mm$?@gct5$67&w~+oHWp5o{ z#qs_BFYcB=aSg5s4tHk`ZpGb;1b25Y6evz9#U)T^acHrd?6y#}NCL&J#a#ly<#%T9 z-SC=1zrWA>4<76z=REJs?v9+9Ip?g+(MYz6L_z|!aE4`ufX_FDDa+;d>; zkA_kHXmfkUlteTkO>Kb^B=9toGY^;g%C6Vvg{(Gpg+`zj_D9a^{Go^aTgl($hqk{6 zlpukpfSl3#$3C`Ma;=nu4T%J5VSnUZ=YXMh^$RWKw)*b`N|3q_|>>R!0 zSw)I_BubFLvls3kQwQ1&rj@iFR~euYsD=HJGmM|;ZJ*gU-?|mrK%xW*JhNcWv#ee0 zVQV&8`O{C*2-L#x9yBB}i~Cve;kxZvwSA*H$=Zz4=TT zs#ctt%aL$Sq;Sr&=4q;SrS^#4Pk7S{H^YlVa=@AI|7-$E^XhI$!zhnyQMw(j^# zI)M@-I8RtOX9fDqog;x-oNFtb^9y~3Kndr;3g=8mju!sXf7c2L&X&ddi3LAX2L2Xm zaW<%M&eHT50wtXFDV*~<{SUQ5Lj4lwk@`#-SS!?0HRQZipCM49?woUA{SUQ5LOpfP zn)R77uvVz0-X>>I`wW2+)k-+4-2YH3BvcD^d)I%zbJS8j*zKD-@$a7M)(U%a{`%5~{q<_dzV3Gy28$D6Fks21<~?^8TAZE%k0bKVG2(349`Y8QecicgEqi zYq~Q4w@UN#Belxz=FVzdp6T`?^-Jyy_h}if1POj3rrRq2n?Nn@1uA>!XL>D4R1Mu; z^na_>zX|t={CBPJxv5N{?i0}olpyhcd%EhL+;@P_O)mo_NT}!LzRmw8P)q&N=i3$5 zUEP!Wbg{+gWuOEJb?2XdgGiv3`upcw3C}X7I~Vb6V7h&q$9dE3|9Y+P4!KXnYT+~d zlyF-(5AKR=&iYv7qWcJ#s4qnCjaBvdQ;?=sw;gIcPMef~bM^wqThd$bE;+9=kvJXy^QW@rI~s{g!#uvQn694|DKAC zay@p~tH&Ht#r0@xw6P3@%*#b7N6eAD*JHYo2)r^iUH^Yxy_$y#r}0M*ylqsTlH4mw z6La)dt5lV3%2_EQ%_~cl7u3IkjA>Yzl11gB(2e)inln~{1g|E|23g#lRF#oSW#;m) zQez3!;z+V-%sJAXXc(QY2~~6^UU^gl=5ga zT?rEUvx=9hfqdHdm00}KP>nz>_RBEAQ?~zXd93_1k$>6%LJ1P=;bFc{=z8NGY_v)y ztUOT0gmu>l)Z%kz^P}gowdqf}`iI`KZJ~~Y5+wKp+iY;u^^T6&cR_BRyG0fm)kGsu zi_g`}kG|(BH=N25=idW}eeU=^cn?73Q1!nLm48mU>@|*h0;1d(#6BFq_F)@4W@OdusexmvPcRo)^-Y+#bRd+o(s(&x! zrFN$xKI9wjyg|25sOUe}M-<8&pPwDRO~?0~R2EF-dyc<_Ww1}W=|)7bKOAS+?82EgmDfE= zkl-CpGjk?4ra@)#RM|Y0XFn3C#a{mA$G8bTgCstK6#g?v(`26;6+gshA*S*XRlZ7i zPn@-GQf4~TDP8CGkW4Pda2Inkw7gz?KfLpb-i)f7l+svM=D<&lpw)AI%dYSuFu`D&>&)e zAEEqxkU%Z=95NfWc0B>vuaDTTFGBhCp#%x`_cN2tbjx7hLF!&4o27gQkw7i>LNwP# zx?V`^BTVcgY$+dMlpvvUy$&-1{qZ>LhfE`SdM)LLj09@2N3)r!w9l)Db6NZ_NtVhX ztt{>P6OIOIoOgZCu?KTDlClfs**2Z5W7T^p|J~R*90`>@;G?JPs0+3{^=%g`UD3`O zp=oIrK+X%6JkV#M^>lSR<%b+=8z7-(3D+~1BM$FH%93N(TPw@9&TY#B=qr$eZ1(OEUl&T@j?Q% zu*EpOoHXI-F`;}pQGx`HkA}hiqQw59;mThW3DnYBjPeVoW}(R}*G0=ik2Y98zHq$NKekbLoBI3Us4e2Ctq6bAmU(obFOp4-Q4qTX zBOFI<5l3x#{ZU)75+v01$EYopH(KS7R=K19Jr25B`k2VRAH=>N5q{qf^U>M>$Cr!G zpv^3^1DrEj93LHz6k?AQ%kPn5PJiyx;*)VR{`COI(*{W`y$0L1Hfm-ZGYBss;`jN4hH?fzurM$dRf&_bi zo3B#@`n|%~lbqO-+)|$8NT3#bn45X42Ks$iIAVmFTzh6oju=4+65*Uzy>+P1%ZmL) zGn68ZO0kb|R05YBB_{fS(bHp(iVs|I1KRwIM!xr}2lpZ0M!YmS_> zROBQ|kYEon^P`_7M`u!sLsu;oorwf$>0>)bfD%W5+BZ1@6eUQgk|THjO|nm8I~b=h+`A3)702FDO~98xmJrXbtGr>x5>7=t!P8)GaKT@@|W@YmvZt z-tiEk`p@^v8tfs21ZrW+cRT@UcE#_c@&rT)5;)Hr274P4dmBpSZHNSFVaqp+E@g@n zdld`iRg4lOaGvL!PVveRdoD*P&t)V~3tK*0eO3_)+EK`w#}NuBK|-774UU2!j)JgM z6a*5eg)QGu(N4tCPL_&xLJ1PsdN`-7w;;tNery>WQH2C*VPD~_5nXc7*KHHqn^&e$ zF<7yE4GFznacnqoY`CRj!`UOjG>-9Xz+Z4+4+!&Ju0Y3|O059g=tIuZ+`2Du6t?A$ z!j6?F8{Un`#9!i^HT)e2^*soG6n1PGNGR*vjRrLgj>0C6!nXWT*s%m^v2R1{+~veO z)4U@kEEVsJ5+sy${xQB*eQ`m3dBGp=9Q#|Sg)^MvXG!d5Y5Dyu&D}E4@v~xoFEe>@ zU$i97KJ4AbxkXiuQI%g*?S8mt^lH>TH8jxm7d5Mn;cMqx5bQ5X>@RBj{Y7IXNMLz} z!TzFjYC$|(`HP~2Jwan@$bO`;zvTFZ6Z?hR$}b!xNU*=SS@N4ef84gp&&a;#w(>nk z0=4k|41+yPsYSNmtr+$&#b?64qp>qJmgjhqQ~Z4{@i@fsIQBt~$3X(M@F_TPcf@gbc1Mo8LkSXbIFs4z zg>DqK%6F#no~fK?NT8PfblKyV*yA@sdHkY1$iBR>>u7v#j%PoyXTPO9`%!`f`|q17 zj^3BWgQEv{KXJOHq6d&bEqrcHln`;0kfox8P=W+U51E(p1^T^;ITDFD63J4LNJyX- zJ~xgAyjG1k;?RD?5r-&2Ld|xg2f7}O9Mwo1)o81zMkG)RpR{3ISZ@+XFWYlCdKo21 za8$F|Wwjd{&Joh2a$u?aS4g0i{s!Z9$xfGUrL|MOPe3>qDZ9k=y2rVT{oxkorh-{A z*^%9&B}$M`dDTDq2oJeem{OF@Y_GUf6 z$a^GE3)?Y&5utoZN*h|hz7z1Ziq((p2T17eyiTeTw5xkDyZe)R8i88sWW)8db+RXs z^NltBz8dx%br$0K@~PEpF^)=!&7MT+8*A$OYA8WMoqv4v(&Ow&#MzT33AGRZG0%khQkwc=nmW@X zab;2V#zg|PaOcJG_@!CTj(L>FFG`SL-(hnGXT|VE1F}~!u~%_~@+w9Gwb0gfJeP?* zmo4SFj1nZ+quFe8I=~+V!QRot-qDuwjz$8t^wk7=U=w>_Tgn3)B}lMmw)ty*_C0sL zM8jU*#9rQ(^72LkwXjV)p5#=w&kIX=lA{C(_DMI>^IYr8F2>&K#NO(*@>WLzwXkm* zhWh>vd&Jx78$2jM0{cIYS0&5S@wlmJy*Q-p0c3^MJ+^!&-hkTWy(OD*ya7s(P-VO4 zUmPpbtP$;LbXuyI1|(1mTfSlB9@3f;wp<`vbKC?qIAZi8yx2Qn5=&pcb}#!{GQR;`k^_#Ydq830$!{F<3NuXA-*y$6z6W zTG;aWt3CW}9QBPH^?e+aAffk<+5eQJN+QHQbUmFjf4Fn1`hJ%i(}J@$*D8ByYB;R8 zePrmb0wqZ3W#n(4i85^ZlI|z(A?mQt!jCn4-z;sIDvh|C)pvb0EuUBxh%`%ZhDTm` z&3GvL26UhaW(U!SPrP^Xe5CR~4&hvFPk5YC*C$)15o=EzH!l}Z#BUi^%C1BElYOR< zsKqC&Gv@iUhOI~=UQPC0kNz=@h&PvaKuRj&_w%`A#K4iXMpO_ZIlEiu&VJ%a8ZnDc zD^(eZp7VKkkK?AdvLZGdNo6N)*O1P}>=pS&1d2PnBk_1?nAwYWA_f+TG!sq?GcQ&M z6k#`y^H&iS5%MIL-7-g2D&4%KKrN)z{)T#9syw#(9;dY1wrNZubJCjMa{ejz&eskJ zjD1#9c^70ucK*u4ZbgJX$Yh^C_$9sQmDWTF66<+w?ml(i{Wy5a$~C7eZ9X%{+|2pF z+-EhO^H{h~w?YZFl>R(!?&tgCuf&vmY-LW|fz~gYW1<8JtSx^xCeY&;$ zhvUU|pW*$U)ho5jdTt1mD8VO+&yaJ(*AKK8T&zpG zg5zieYL%N9C{mP*G#B<#WxSr3+nzI`GJpAGpg;){`ulim6}Mj{DouBf{v=Q`oa4PJ zavxd5F<Jyw)q6CRGTLQ(c*^y>k=R3Srix;;0zAi;` z2Q}0P)GESnu=>PE^U-{jEwp;8!gl;~#i>Kg5Q!2ba<2^(_g6)lZ}%u7Zi>lP-CqXN zt$Sz8(VQ>OZS7-k1jP1_RDAZ4e#UXL-Ph__l`vOX_uBQRC4JABC_w^Sk74{h*RnQ_ zYe@xv-YuJ73lQ@Car5T;6(+v_Wt@?%Y#h#e-d)w|YSiCW$*)_|yU8;pN|3;|U>H?0 zy|%KYYeFRhCusy~_2GEfLm4B@6PHyP%WI{uAC0O{orji@C_w_-0FrtlYSFS` zSu_H*zM2*&TJU*MhZgEt-P@YiUf#AMHM{b?KnW7qdiYtLEMU*98%&Ll&6D`10#*fz z)Egqrc>JAWe6##jtC4x_s8@yQVmSL1L2E#w(wsoCC6b?RMs?@COJuWqn?hIbrEV<#pP$Xc6_X7Y~H zkyerB{l+UyY-5As28v;3q*?uUl_B52#{Fpmdu!3!lx*z+jXKLblMxfT3?|ANN#v?-w=M9!A zU_U!2sqcY}0wqZ3ZTHWSS?#iM^U=mtS0%Qk9XAJ@Q*SV9eZy+IW*D8^Q(mG33B9#nOkzjmn>&b>j-RX%sI|B= zpVcoqZq^S~Wn6hZ*=ks(D7{@)l%lo=h>8y)&8xeXo7h)gJqi%ZH%6LuvN=z8{R)eg znv@|$MnVY^*l&1t9`u{Fa%?$@b2(5WQ0r>$K+$kqq$ zu-|a5`+QHW%w;Rkra1RB0<~o0Kry&8e_J-ay7Rg(;@hWVs?v8Qc1x5Xf>P+wO7h zk}{QO!)%U6hTlT1Ya_W`@viWUA5|GSyJfO_epQ)Xck3llf&}&(!}xY*F1ye`qWu}F zXas6SEeRB!?vdtAQ?yKrYPHwru1GXQG$ft zKNi-gWM*jEg)SDopb@CGs!V{m_3*g)`>(3)Zm2odYCItUMg3Wy`fLplH-F}DQ_JNh z_OAMO0z`#|QRb4lD!Xx;4&PY^GH0TR!zG~v3G8V+!VUe^TJ|zMg*+>(5vY|VOQ5)! zkUhiRsxms>IB0E)Q-Gpkf(Ru@U{B*%{Tw%~gzNHB`gvJ20=4u}v`M#@RyS`6+Sexm zp#%x+H~hu)sfq2v6+`I6!Iu&V)WQ**S4G!TbJo-H)U(L}Z8ksxdm8uiA2ZocN0gzg zt+#3fYN1VJ7^C9m;v5hjdU=18X8Rz4J&nIs5R>1oUZxzKE?-Y0Pz&vO!zh!lnBC}Z zSsI+-m_P{UQWG?3EUV-jMgzwm7AQdi`zD_v4;(BX zryD>ouGEo8pjM|}(}<|e$IUU$YU0e8ax!P)fz)aJ5Q!2bus0jVh;c`WL5a;8 zfm*xS8-66O+i%2Ey>@lw0GX~_cUs3M4JbhZd$VB-xtm?q8_Yg3Xs88ia5hNce?F9xz_STZ#-v`p}q zocDcKN;|WIz}*PkbI^At^3UHT55(z3Q%7A8C_w_>6Mu_t%6|D*`%e7T^fnR+)beuf z_My?o&6siO={`BPRxZ!nmA+a(NumS^e6xm;IC`6`@kMJ|wl_i}Q0tek(}?bQBhBvD z)txUKH&+hq(}p~)Pe_y?fp69@@;#a_&!(+QStrCJBv9+wnl$2G&qy z>UHV%$z+5QB=F6$f8sBl<>12}8k8ruMxa*rlWD~1y^&_d3u+WSyf&*mm%&3R%NHb+ zAfdnWZV3c(zfi6(#gs(sprhe+Kta_}d(F zbey|?5?nUR9bkPXZ+Q#$av&F~FD=QTd znrWK#&(&^}{P_Zj5+p_*h$5;<1{h{vfT%@oTNQEc|Th{ctfP~}NU2?^9%%>MJI%SM_ZbrkWo z#jp*a z8nrs&&A}Y>d(LWv5+tIA2Z*0N91qY<5v7_Xi71&d8J&%2su8F)NCb!n^P|iMMHI28 z>!gSl%dg6)$DxE0Bu)+u5NlJOFdrF;=rr?uc(Jw{<=h2*H3GG6av6amPMBFPs2uTM z#7SXiXqu5S9!*QQKI`6xPm{igGJom4!bHn}?W>Im?H$PjsqEAonw5dXN?zSPX&+^N z|3uYle~D;oY|FG1a;<d~lRK?Z-WQ?~sD*1>_O0zg)~WOS zt;ToRw7n%Hu+MXAA27mNI=?RcJt~Ptpcd{kvE9CEq*Z%POG>-*uC_0V1dd(YuEwme z#sz;x**Q7|e+#v6kJKR~sHhY1#-;M;1!G^K(Sfq7mVh0jGbk+#e!o7F4 z$lhMI60GV#TcYwxlpuj~36Ip};@eMWw4hP!tA+$>;aLcu8`Mr=Px-qsy)86GJ7Ylt z=R}^PqH@~BDpaE}*Dsp*Td1X5;j(=mdwZwKlyF^I6Hi7^3u(hR(KID3tJ;|Utk6T? zsTH10=_gp@zlcj?=C!1Fscs3BAc3|WpF5A@?>fC}Kz9~)kw~Ccmpo}i+FHD`Jy6Y@ zc}_o;KlW})CyULHC_w_PLH0QOk5+z8WZO12Z#V^W*3(8Ro&K`*bYP}6jBj^x+9ayL`I#k>(tLFC5xoNJf0a}E<)xL63TXstW#d!82|@e?*$6elHTh+>v@YeP!_P_(N{~Qnkk7V%`$qO@ zmx{i5P(ve7tIK|V9~?E5qp2#RW<+IqGdd;ZT3eS;f`o1-#_OC{4k~e1PK^9YBT$Qs z0I}~wlzA$NDr4u}qEw@Cd78$t;VLfNJvqd4RTW{b{G)u|yLSLsXvE$70wqXb zdt)z)(7cqtV>#OXp@&2QwN&J~^4jx#y>3leI^=;t!6y!Nmf|9PiE>VI6wm1I%$JZ(7%=jEM$SYqDu_C#&p;?a0$V71&^>x8Cq8E{z#+vn0<~0>w-Y<#d}Yjv6D3!VN=de- z9H9gWY@xg_dj1bt=FDB$`inXmfm$kBUBwgnzP0s!?=m?p;-0K#Hzt%Ifi0AMAWO}Z z{fhr8=L`$g2-H$h_bQUo_l>GFi5tl8NBtsW{_I95K|*i4ORE-;?`V)*bZ?+Wpq9!J zpmGKHzU}lVQxmJ@!a4GG&pw)6lAL$BGfz2T9(uCOM2o{PHqI|%Rs3$0^pqG#C_y6q z>Hv|57t9BdCKlprx;6rX?c*EZYz zsmj=0J~Sd>f#kAV@FcwuS!#VRgiwM6 zuKEn)anng+(y-i=Wng8EKrNgZ_`J4!0TI19Ic-_ogiwM6uKEmPNz`UB-E&*UP1{i; zPz(Db?^7?RD;A&JEWf|W13b({NMJAEvm$GoXmg^U46uf11ZwI1yvu?eX7RbH<;}LE z)R$soM*t-B{!yslLNoBpI5C;CksyIu>SRM@D)D{E>|;imv83|usGL+PXQs-1r7~Kn zYn6jZWsXtTAN37mETNXl!liO~{l5wPEhJQqGL`A-(=w1iEk&#BR-Y1hA4sd5I4bMW zrvyrnP`R&EUY`Fqfm$lRmdc>@DS;A|!^^EZmaRWslpvupq<#KbA%R*dBbUnS^l7c| zDXO>W)*YXMUMrL!p`QBZpA{0QrE2^6c7=6US)WvXDphxtMM-71`t&|fqH=1f3|dMH ze@VX&lpvupK&dQUpO%3HYN-rRZh3kcc!%m8s60#Rckzkn1WJ%l`PEcTsZVQ#1Zt^# zXDW}>r-XWrTT|E;;0_wjzo(7e6Pjl zuI|=t8Tg*`TA>69_1xSx_TL0*{dbST=dNn#-Yq@_y$qBfq1u?rHumYWLISn^`|0AH ztFgo#sj+wIwL%FJ_@4foKrPi`K0o@P1PT3}Pg<6fruC?1XFYeq%<()}%$OSO8N4FQ z9Q`s_3||uM`Ntb(Hr^d9(msFe@%f9!&6S(d+^KAryVhO2y&o)kSB&;-?iXfOj1Cs_ zdqjK2P5w7=EoEK`ep}Iw+k3V~;O`E;87#`Bi1viFQ6~-6+T^F>8_2%g|0i+baU58tJ4ae4_&E_jFXve$ zT^1}ZL_KnzF48)|?}GT9IPas+{9uuA-XrHtA*~bqzKP$v^Um+g3Kl2YJ#tzJ(mKIy zinwh#?P}Gx!Q!XVkDRuIv`&2JT$R#s+;++Fg~h&a_zk9i_{KlLw+5 zV&kh|k#V{28haP7aWds3F2^YYB}nLH@Ldz%y>sW-@305!M8Vl#(SmBPtgbnxnOVjL zi#SJo_pz>Fu*lrN0Pg4Y zE`^AR6Ji`<`^pe;tBCKK_w*l+5O>y$v`-GpAS>l8E?U-)@#Md;(wtqWxJa@z#rZLURoV!l~ns_UBTo_gY3USYm}5h6SZpLs^5Pc(+*h9dANJ z^d|StrDce6_843JuWB-Lk57VH>hFqZ&Hme*H|pVfQE299`_E((9Kw|#f#vaO#ADgmuq_xyRP*Paf4(1XkFM50BT!3~q1sgo z$CG@)iVvR0e^jy0*g>Qu9U4Y^inLf^M&>9kR*#GJv<~&Xe>F$>&hGa1&ntedM0Sa@ z1suYaATjGzh*(|yiRW1gwIf{ox-F9YUC8cJ!lV;NL&UZ_k31g^FLzqWh2I`|7H(c{ z>co`Z3B}P#MQxeULnu)-bP09+aKK}ad0OqH9;%a2WFB17{;7SbPY72_5pHeyeI#2b zCK_+8%W>P%muEvnjw}y64fxykN^3#e`<}bGmYb=Q7Z-JQKlFS*Qk8M7@p{wf9@k!1 zt~H?q33dJY#RE_4wu(scYMnXnFz5H_+V~T~)l!5SG4hU5L}-c$=6Cn^SQ|F=r2B!~ z+UMQ#JWt`PRhLV5J$XMYb84u@mC9U0!&s1Yf|;ZF8f)*Ze$M-Fwf;>f*mlRW;+pE` z&7VyZlS?nQ-sT(N5UvD?<~%AzAH3r^6s?GHUo;nwLPuLg7Y)$})Kd2mbM&^S&^bkP zt~AzMHtl`Ht~a9`qG`2To?856^!{m!i`hwTJ0p(stnS|QWZSEV3B6~EZa0rdY)LlS zAzu3>Na*8L(}itC-&z$T5;Yy85vZlgP$Qpj*B}c=nD&-q!*j-rARGsiUhs{HYJU%D zj$K-uR{rG~8=k1rC_)JmWgh$JqzBb~d^l{0`s2rjUq3%uBT!4PmG$KrIXvNn@C=@= zl!Sc0rOtjE)$v{5J96?v>S3P6+S2xF?|miMu0x^r&~LR_*7n zm3^*Fi`bjCpGKh8%ViUJ8$mENVDRu4{sEw4n6%l*m;UeH!U}>vGuB+s5)go z8Ye^)?|ReUKi1t$MJYe53%AxbB9tJJFq5xVS)BfHwP8XUb8?5=xLzR)%`gzHxWXkdkE8Nf=S8T`7$~ zE&a|bH||b*HYbgE)cdHs)57;#%A3DlbGFVB-*V>g-sOFNR}m^4gGIe*!MmmrBf9RA zC_!Rkg<#RI)=mF>o_hU2%3StzcyxmAH3GGg6$=(?ts9QL!ZEyiMpM?ZKkRPZ_>ho6 zzS8sj5N0mQu3xa>x-El$!i4r8r<@3?L7_1jfN7D67 zDZ}&DFRT%$rPu0J$Kf;~-gEEakSH7CD`V#s^{iG^8ba}zm@)5bjX*7YhJ3>N zbTlP+yguT)5(&iZ0>NV4%Uh1smw}&x8tv2?a9<8z8NT)4oH}F84ma{z)4m<4jiNZ# z;`qqEQ6;8{sP(O^Lmb6}5+rcc<~`&zZ$)Uu+}615!!-i6aOC3^Wc6CI=*nEyrLZB| z2#16|mMlI$N?J{)MTm|%fm&#za-_wg#qvSg<`E@Y4bZGtByj99jOe%H&0Td*SP$E> z*9(vO?hL7}-T546IKxOccc%E`_<5_A-T9Nb)+Nv~V4I=vThX%QZ`QcNJv0Kf@G0=u z%zM?4kA_>8QKKuN1c^Fq>6hqv&vVN0_j%E{myG#tvNdZ&AB{jQdy!qjyfLZlzutfm%4P@a)_$O8#c$vQDS$tj!-t=p%K_ zp;u(#?`KAwTi!_{Pzz@}!}x3GOPOI}n~2j*zS8DFByeWnDC|V*&2}Lf?0^GxoOkZp zQR~`hKMmI?)aZoo7;)0 zd4Ymfz4VPW0=3ZkU=O-!=_%{$VC(mZH8m>(3A7~)c2EWcP?#$KAHh(@3mwn~o8$lh1(uU5+5GPa<$ zRzu?HY;ISl9(&FfR%M**GFBG-HkW-owMQdR3tJ_x&%3OU2^QtB|E^h@P=dsw)a&a;)^~~WXx1wd z8Gqot@I-g~ZMQ+0s#IRyk67?c4vj!9w9XCV`mc5AVuz$wgb}D&;YjQo6f6cmyXEvQ zj*3s%hz3s?5|JlUYK=fGTr(KP^MbADQH3oL>wCu4Ruf2|wahz^McY!hACg9FvfoMk zEz~;S!DscIyyW!SHXUhfyQC3|f4(bGf&|+0Jc`yBLxt0{h&ZvOnLrB??Q66+`B_aJ zO|O1w6Y=b&SF=TtKwH}|f?kcFb=hu3{1co^;%}kWq2j?}JKgsDlS1v0%_}~Fy2hUx zu{)-$L5&i za4o`P$+KQmRTQ!k)n2O+sFkS+zmJA@JYTm|WkglzPLtavwmLl6BT<3`z8mhfe|4ap z;mxeLy-sQbYAxy&EUJ8Q*JGwqWeoea4c#i?vFcoWC{cn0wlR+9j{li?JDlTx@67fosgiUgc2mMukb#@m8vx1z-nvI#$+0SS}%VJ7DZm& z^K5ZqGfs3ARQb*lYiQbxgc2mM&+|(7R7sk4@qo1>e|n8Ttzt)l#jT_dJVTtwup}o6 z(#hm|t=4CQ2qj41*u@dKn{&}OdGA}jCuGwI)VlmAShUIi(6hXkdREOVq^A;+hi$fSMQlg zBT(x}ix3er^ojqSe|u?%+|Vu9u9Gt-p#%w>+u0+&##Xs-89Pl5Nv#p6wP#p}7&#=` z-*!)qpDUBhuVk;vn2u0_1llMZeU@U5Oc+tmZa+J&Mxa*R??c4pR!{wX@W`!DIVM{p z`-G8zP=W;7TAW$+eRr8Yep`E5nX3{B)H=2?MEsronSU(l-E|ms?%T;)Cy$veO9TtG z_o~+VxCc{kcRdyOwAV0>JReRkDpj-+F6b#xf&`AooL#K;AZm5&8>_&o3mSo1 zxhwN7&c?f*B_35q;#-4han1JD#gpkIN|3-2oP8j#_oe+yW?AEION~ISuj=v$m-wEi z^iws$)s_8d;{74k>v26LN|3-2ocEA}yHl@(ORd|X6Ey<0ergje=CJLPXp1UiV^B95 zS7@45z3ozo5+ra0=e>-!?P>kbo2=AZ*JuQ4&F{&HpKV#MM5o;uZ38DUc!(hqHRS@hH25+z9B2+nau zoU1s&vP+h=_mW1SmWR)ybI*L>*^on(k>KYlbSm2^%Sil6q67&X!3|^lMUzTxd}(b> z`B)=RYuzsPVe0VE6DN@>z_Ia2qj412+q4|1B%isJE`5^=o^UyYKc?9 zq69tiynm%e>Y*$1(2MVr*f$3zC6pk6BREIo&d5$wSu1ni{sfI`^zZT zI31O`kOQXxCIl6<4~Hfp zlpuj4I7iDqh(l+qma#97h>=L3R`Gm1!X10!f9J2Z+?50VE@!7N6^~GY1dibRKH}Y$ ze}+`GUGv3JnPp=QyXnZHM7*o~)ZYge=HDuF#IS-p=^bPKgpE^sznds8upBrn5c2!(5F(t&~G~UEAcDe@y&x?GNU$zWwdJ zxmP*oweFd@+P`woX!Y~+N@Y%)eNGIrtJIw#QGx`X_8La~I~zo!MT6}nt;cHwYUPLu z5j~5?`0e)Ig`Np1hubT&7MCbN0?)ZQGsV%?(nvVezBuQVKmxV$Obro(Z$9(SYE_>N zml=K^Vn+q^6evML_kd_$Yn|L!pr5_*+))z=)H=y0X37V_w|m~bOHbNf`44M*-DxKJ zV&J^1`(-Rl*_TdD*=&Ud7ZE5y0_R}v=M%fq_GKrm-3u0J1Zw^IRj_FM=Dw$_leO;6 z;GXn2ces@z>t%rwBybKkjCP@&=*HEvR^jJ~Boe6AvP-ZSS@wbFfis^Ms@#=kP5Z-& zcdD2~2@*I5^NMA0JNl{rRV#IOsS&8Pw_mXM{o4ngODUDjFxAt6PArPF)*kO6QGx`{ z!G^K5UQ4Qw{E<~-eIJcLtsh4Ri_6guJe6;$`J?#MmNfqT6)S4PEQt~%a1J(%cRw|x z4b9$LeTz@m2-I3PJy^u;@z7IpzbfNGXag!*Guj$IZjD3<5;zAN#@@ecQmU9l_HVx| z)d zj@th1u@3}p)(F&k{W@3-JN3l>&hMW{Mw7Nndws?~BubFL8I?22y-Y?`E>*S1om-_5 zsI@&=h-lj?+TV8D?=dLgKu!Cb?|zjiK?3JsUQO(aONmm~v(x36rxB>-qG zb9c9kRyrzCf&|XLp!2F0=WWc^n2 ztwjRodG>lK)tD|^N?}_q7ik1)p=U0yYbUj!0h!|43)Wu}C_w@(13v#4+JGu7N^J*v z&uau~p}#PXS382{3D~L% zP1=#wZZWouMxYjYd~;6O5mo3|?u>TBOFbk?kU-0TchC7$=~ROt`_Dumh7f&i^Fls*ZNCW;CHT8& z85l;x`Nb*y$YOTKE=@E7wa{mucP0`QrC$~lv+rK}TA~CAvYlaYre8+~YM2k=B4!w%h<)YkC!Mx0xbj1HeE3<^^5Y@tG3kE2-L#(2DYgqvr+j-Y4>_G zOrit{v<%qWuzwC3x4fd=`4Z^_SQZ#{!QZ>vlb%vtu4)%r(M6&Je-|wSUTvq(OuODx zvs)i6q7kTtu^=3m+9VC#sa4zV9jBf|2@+@-7{>M{U(hcRU)n!?_(CI43*%e(jAeT= zx_zgCT{t{gq67)F3=E@W-2f`Rubv&4@1+*`f?DXm&)<+vo`{alZE7D}l|rHf3A7B@ zTO?~L%Kp5e{c4I=Ac0yK7r<+rq46kD{+9NPc1HzDkkD<08t0NzQ28eI%%uY~0<|!5 zf%D?z`rsLUsg9jEe+I|v#r4@%HiL?Y$iz8!(W8L(6LWs>WZGKaPEjGP=4*h2x^_MO z4P(HRA>!*74ehXEsXrlHE!^ccjAWIzh}BtJ+3_aCC6wUrqJ_if=f(IdoyW4NT9vKr%NgJNNapId#yLSMxYkHP4-*5^p`BurHh?+%~638B+$Y!j2wY+=!fa8 z?c=)#Xas8Mt>oD5H}dX@wsx)HlUl?X61uf?EN5bRb+|dtI4Lv&wJ_?2_m-mLQ`xBV z=8&ITx*l6z<+<#6@0@3Qi;P`vw$04DgPU%87q?bk7Nv)bqP!(5i8?hB$#OoQO|SCV z4E1?`dZ)DyGn*C+7G1a9^44gm_8DgO3^i+gC`x4`%R8-|J@~!KBUZJm?QtG^J=StF zPx|7b{?^CdT31yWE9<2adD@kcC%27oi1SJBc%O1^Geu1N?Y4IYN4^w#9wJ(#zvWGE zSb0Zhtj)xMr1H}6QG^mC)HQo)dVSvNC#s|pa}rG!UsNCS3E^rfg8g^BKHu}F&CZLz z3YVAXX}Ct@j|dS1uiW;2^~hI4x3+waQ{l8oIB2|lkzufQA4pW>NQ+fJ-SxhDqwXW9 zNFwoM{Zv`CrcR)isuiC)d3~_}gBm6hog4iuyH@o@54e(l6RT6+_twd*o^F97Q$*;m zmt>JFot;{-pQTqtB5dCqB3?GR?;TLi_ip}La^IVwutO~RO+<%0l&c!GcL-O4MBaGC z#oh-G{H-L;mGfq|@OU(_Q!9-?Ep;F4@8|W!O-%gey!kbc))n(Mb_iGUZ(``#hu(c- zRIQ3noh=%4%tu{LS0HRZ>UZ6CHRoiAXx;sh_lc9??{uo1VlG>LC8C3<&!Z6W{?QX} znTo#nm_FO0y-7JzUD0-uC*D3UR2dUa4-?CVG@(rWk~_8H(b=m;=dm0GGvq_Gcjaau z(KOdnZ>lhLnsI#fe35Gre|6zfJcn>4NX*SpTq}C;R>#R9l z0<~1Fdi?X$TQ^3P@ieTGD4lX7ZD~|k{(Ln=Bp4jy^fjf`Y-Nl$oco}<<{fCSFG^_R zws>;Rs!`Ojd=Y^}^yLuo+uRth+HZ||6CzTs_Fc0-LvSTAJNsywv-z46?d1M0(y9!O z&GP!9wi5lkLKGc4nmQJk@5W#`5+w98;zSxE*d9aG{E=bqZ=sedgCoYA8gh2AEo11$ zB|}7oXB0T%_euY12QxL0}FPpBR&-X6N?z0*YPs{QBZ3OMKeMBXvwO`0ll8i>7=Bvx4v|1h66D($>y6KGP{`dxG z%;z#*7Nw^=Bg8pVo=}3s`Ln(<1~|FGjzs6Cf7XVY1+B`25+wW)Dqdga$g>%8(W9Sd zi#v6y5=xNx^B()d6~65s8D7`VK!+}L6AR2b8i86kCvxu3LDBNZCFjkaU$xg}PMj_4 zRdr%zyfX@^v1DA~hq4@xq-mS9CzK%3yl#kyzwWj(1{+4jpU=zP$EOJMbZ3n~t?kWx zWz@@}%E)watEkyMm8f{h7lY-_UjAq&uZoYt`H^E9_}dB3JgLO;ts}Kr4T;3R`^va< zM$J)!6PJ{WzdSFlexuKWsD(2epKWJsBijv{BdXOJMkqnzzz$y-buX$i<_#P#`>WYA z<6wDEdt<^BdEXvx4L0!L09;fyf$tO;_*t5s9_$|;A2P|csV3zQ)7lD%=aUwG#2S4CM% z>$lC70VfC2@Ft`YsC8*Ndl8GZr3@KlbTP zEBfviDA5RRyMr%1_0}n`YISM#Kk{DRPBeN+ZH*`fT1P5`h?$04#ut0v$U@(?r48xp z2$Udkkt4v(KX~5d*@wrg$ix)ya8p`VI!d4fi3)6&t{)fe&EjNGPINdeO}kN#&g^Qe z5vaA9Bg+f?=$3KoV0OwMM_h1PT@Y@;|bU@zbZg*Dsd+?9>w&hp)~){exZNg;w}-}SC^auuiTI7g;_ z)Jz_&t@jVq!rshT{@)Ilf8Gg`SE_W^dMy%YGaAM}xq{{STYPrjsJBL-7Fx1AGAubN zGL||d13z>llpvvO2G^=(ugOx0#H}m)WWJal8i88s`lE%MU|Rrf`E{L`zO_E#sE@M& zj@s5#w)9Ki^}e63M(WNp-^c~Kt4ga!3ynZ6d^d(sY42@$ z_WmN7x>{302@>ZThlmF`?|UmwP-WasxnH&lTP7n4w$%vK!gs^pN;$bnW}wq@AvGhE zAW>;fi1^{32mbrG_RY8Q%eH6bp6YEh0=4knu*dI}Q2F<)1eEfRhJ+F%bh|xSOeUG> zXac%(u&G9%7OoTcYv$M2iM2U0(tw1u2_;CVckZqe*faC`d9&i*>FB#&^)v#t)b+>p z$MGe-Y2W6pvf1eUqAPo`m0!jyEFLYFi(v7*>|JL(pI9zf9By&f-)nPa=|Ov=56WeM zbp%SLHDbEieMbv_iFciO%vEEr8h25GL;{WsZM?@v^PXjyHdL?PTRBujX#{HFxMCPF zz0GvGef=B}n8S#@_0!Z#%0nZo5SrQ0@6g#qfq{Gy=8I4rZ^(akZ$|!^W~| ztw7D*MIz;rV3B0yUGL1P%0j-lOVWe=J>|&4IWz*bn*JUv4vo3v?Gvbok+(`y?M<6x zw+vYbB}gRuGg$Q4ci-D^fFfp>D?o{V-z5v@$*&Qp_50&s@$3A1-qFq~HP27k=7$v4;Jv91}2N*B@y)XKq8@jq93><9dg8geR7z3`Pps>rN3u2@=>sxkoiG zMC&SMmlxia(+JeU8IJd_&IQr@Ia6ec>SYNfNML*8@4o(%mb#>wEwh)YtP!Y%GaTo$ zjF*g-2OpASUJF7A64*ldt5#KGWTo@RWVbQZH3GG8hT~X(+LvU;i*cyLB}phj0$V7r zqh{`w`?toU^E<0)1Zv?7XBdy3FO?Jj%1mF}DNiUt0$V6&B&|4DHe8;Cj@_=H5vYYT z9A`?G<>X&yLg;MS;)D_;^tQXI&sEW3ZV0U?U0Neh3wPT%XFs>XJ4?!uXMZtm9}WrC zc0cZ_y>A$5*5sXo$?U&`zlB=r+TAJUuZ;1x)z)lYArh_&)AoIEuSef?R=Ztl*Guhq zp#+I#d4okz)Ghz)eEr2R`m#h#x!Aj1BTx(HcJ70nhf>B@{pI%UBv69H4<&=eFPrc9 z%TOyjwZc=YJ0wsGEdyRVUms4rpKcRX=9kv?+wq=oUyD7RrVpX1Q%D*)LbM$(B(Q8g zqaV>z0&s;d8m|Q5}gAB+&XW3~%xV{LbT(_uV*+K&=7a z2a7`8AA03HRmK>zGS!O8La#S8mMB32*KK@?oVzTQe3YAZ$DgPXsI`Tooq{_)_U4+c z%CPd~qX})wlbN`wL-`ve9-HWjrfm)(rh)6u>ssDYvFTYK>~LWI2%d2 zpX8h4-6-wb0UCi?ML3Q=>F{U%b~R|p0GX>2=L*kQUZMmE+&kes6VuDc7BdD>i@(3p z2-Mp7fIXeE#yI=F{H3O(zla-&htaGttt3j2P@~Vs-ScNH^N8~422q@0b2I|A)b;P% zpLrMcQ}4X&i-A<;uj#_-I!oftFZNX2Ddv^%!M;>sNNy=hEztImk-(nD-XdkXQ;+^% z%FVa8X#{GW<#kEvGIzXx6j8O>G&PhaPF*Vh_->6v2@=@TIA?!EE0WzeOJl_zjXm|f+k4&?sZ|*r#xx9O3$)k{^zwh!58 zXsP0~w$)CF5+tyv8OHPkX=qR1GE}~8q(-1t%3L9$bjK(D`*^+ao%}ZVOIonu7l{%i zu&42uxaf-9f2l5I?0Q%uP-|ruj_yAc?SCKRo^O}!;(bMtJ=RNYHYjXQ|?k%vrP--8s5Uq67)-X@)VSU3yt!LN99DWs^pr)|n3> zoT>Dg|BR*RuIb|FU;U_Y$SR2vB=kP`-KBfxrb9g`eX>0ofm-UC{W`rW=b`$tHJ^y~ zC?pQWIawz7a7Us93G8Y7rKb0FY5%?NWrMbH2?^A~^`~J}_`VuP~Xk zk3MzE)9Tw7x5*2np1} z^(TJ~YE=MTI+urLO*aT7NMKK6kFECcDBIBj)VmLV;}F)!sD}mY{sF)LCUy=^AaLiqeKrKAAHjH|m3W;88 zy3pK9XC+FI(EH%D0Zq(KDMM-A_}dzRTI%}aY52!n(7rDTa4z_8mATrVBi_08=MHzS zKkBP537`ZCe}4MU5Ge6~7vO&=0}1s@oDcgmWnisPOVyBbm4AjniT^tU|3j^i@aOXX zOc_`!)bi&f{|tc=e-`uqp;k!vv!;Kh46GGu`LneD{}BF+-;S0)`}=1Il=$<7J6c%w zf43_n{29$ZQwIJPYWXv$e}+JbBKXS=|3j^iP&MQ)Fnp#AtQBhcGr@m`KnW7+8M=K_ ze^&UW{NFeDAMOK*9}+oVVE9a}@IFw>|NVx~5dNLC5&nl-A>scT!)MCCTA`Nz zYZad%uvY$W9eh$l{pn&&kWf#7zY*}6GLS$mf5!jM5Ge6~N#K8|6%zih7<{G-tQBgh zQG&lJ@fiZ&t^cb6jut+3{aK;p-vob2;4@_)p{`vm99MWhaZSQioqjGx*~*r;o3-MV z`|l$?Nha@bvPI%`^~K+NUVI*^wnt|FjsY5RDMUOa6b|6K#*FP?*;>r4V zJmHj)o6E4d443e_T1>=Va~WQF;H|HWRa}P6Ww^ESLak!2xeV{yC0m)8etke#$LqZ! zzM4J8Rz6p`KBNx|Nxa@vHT-)2tCjBchnbUiw>rStmW>(LpN55Ae-P2O%IHrBS4;hp zdulL_VO!pnvB!T1aR^s}gu4E+^=$9U zYT;bQt##SLo(`yJ&-gjtCxok|i1o$hc_TflwU=A7G;H6umF*s7^EmIrl_)K@JiS(9 zGF=K&?N+s4lpvw5M^^dS`{SZNxQu)~{|r;lNjA@d~5AoNpR6SPpT>LFncb8DtABj=h3x*BOG|WDfuBY{H z!qw96yn5v$NftjFW1o%qAslO^uCWaFnlp39FPuw_JUjw9G)bheOPmvM$%$7sKs`$!kfJ;P0yID$x<%6M61%8M{k<$dzN!5IbR#@t+W` zmV4(r-alYsUZMg)v%3tiODtO|@we2qdV@+!Cmt-B6Lc?44?D%)!%i8l782@OwO#g> z||=!|u(UTDe;4 zcU>)=i0PguH@`iL-=b57tA&KRRx{D}n-XxX=DjYEJLTTP7Ppj72vCX{Pb4P zA4h(+ZZ+xW5UvD&S6xq>@^W|Q3#yD!B_0M<9Xi9>bZyWlgsY{>P&0L}KNB)BaP8Be zvPC;u$CnOs2v>r?tFGO@^BcTaCb!>a_=Iq^R2gAEUtSrv5c_-@V^_ok1(cZ`k-XIy zhj1nMyXty*kAAzZrBg)sh37$A^EM1${CbS@K3s{?a%sJcI7iFoRwECOK%bQ168`ea z`|iA~?>+>NK%WqNAC8v)S@{XJeS+Bbk!<_8ckW2=chxo9E9KMmS5KF1pCGnvF$@_`+P#U zT8dx`$I~g-J0{rn31Zua*!FSWhbvK9Zh3mG*!Brh>jJetKnW7+n#XpJZ#H1tCrCXf z^}PN~xLWG(?zLn41hMTyZ2LI#hbzI~Ro86QcwRkt$oIjvPY~Na#J0~TgsbJ0{o78D zZysdZCx~qyV%x`^qZ|qTuDa&g&QGxI6U4R;vF-B-;c6*@=XOtKXFg}!Cl}j3#I}!6 z61IIjt?yrPZ66QVK7PV)GZ2qJ4&nZmsyka84xz5yzw?;5y)Y9+# zT;ar1*!Cf|eH_cnt(B@Fmf>DIw$Dm6@~G7p)&z;zJ9n%;zYVAE;}gQEA#26f&>`6N zS;@8!vF&4_1bEgQw}oNb?#Z2J(~KA#Y-mV4(udzWpWFt&Y&Z6C)@bhXs) zsyC>#bb@W4Fg2sG?ceI(gFeuCRJ&#>^k{M-Ax-}YI;eHG8@@m#3Izqua^%JXEk3WOr4wZP{KS?kTd*iWf`9W!6qwPI?ei1aK7y^} z|0Fyu{=4_vZ~H7E+eeV?<0m``o|k`p1+#4Mccoyot$)4eqL z2v}sS%@p4UYcs{qgteLC-yXqUBl=2ZnNo@l8B=G6GcC<&)7_uS;@l{Iq#sW-9Aco0C+=yB|v^I%M>_JT6M2 z=bSe4ji>UcAH*{m#)Pn9iVp7EwK9+h%YWAF@1(Q>J>19L3oAN!jM50yitKsXOmHbE zmMBv$T+tzesE0!d5?lU0Yu1>Pf=36sk268J6&*5Bmy0fH?T&xmT;dC|KH9a{)QK^r zvMD;`p`$NclpyilmhNF~cP<^`LG{wA zU%xBnq3@DeZ@O+XUpQCH0-KUp+(+p|)zt|U9sV8;B}mj7c+nhnHd$;Ljfw{=I^-Gh z`yhc@c(s&;RP~`the+~;)UN8(&}-)0Z?J_2| z0zF)xyL(+a1pAkeK&>7dZki7(B#I@RN^4y@#JwNdDwH76`O45MlBgn|xt+PYy1`#~gbUNS7}+7mN*Huh{^EmBy} z;a-|CL?ckk|Gw$H2j2PC+T zj9x70V9$g`pcdD3uGaygOYV(=4!7H~)(Ry^Ov;+rdfx4pSs{wO=NFUxCg^a>oNBBQ zsKtE>x3+-obD+U#L5DlzliCU;NN{`SRvaMQUM~b4Zg%o7A%R-l^Kjo1=-~?AHzXY@ z>erGAB}f#%lgwIi_zyEl{b;(6av76KI@E{*`4mdH*W~_-&x>cGZ&Xq5#=RW(a4127 zdui^61ET@=(%f5fPmKg>@z}xrVt}|kH>;#WUAy?VixMPC{v2feRQJ63=*%9vkCI>J zl60s7lmE~N)Z!71$FIOR*y3`yq(kNHve!ik5U@kwtuqE zd*ZjPxP1f&wv^anB5O(DxsdSMN`QbiD3L%duLTEuOKd5z#YEPUWJ`%Hrt;6;`7I^x z)i`#m6KpB5#l*gFlz4p?6JGldlmUH-MxYj6t>0P_Y%!6wq+ONQ!*Ll{p5Iy$Y%!6w zBvFEd*Utxh;cO|f#l#*dBv8v6B?1InN^CKawIor31Y1gMU`vTDCiY071PRY(2zZ3qQeumVy+uf%mS-6R2)2~i zVj^ovq67)Hl-RO)>0^&DTS{y(k+q}|sO4EWfw>x6N^CKawIor3gl7kNv%7pWAI#_X zg(HDlo;?@154M!pVj^ovqJ%9awtu=G&}Wl=YsqDciL52**@=8EB-m17E9awyeCKQ_ zvBgBzl18AGXQKw*Ia^9>F_E<-QOmP;SxYC_QeumVJyIw^!n5H6b(bwAwwTx>g#>DO zGk^fWmJ(Y`WGzXQAi-yCAOHzTG9yA^5!Mnf(?T$CAOHzT9PP1!kg~| z2)2~iVj^ovBT&nmg#~&awv^anB5O&a1PQj3*e)uP@*RyhY$>tDMAni-i8s^Z^WvHO z){-|L)XG4@o3Y0A)ZV;SBT&nmK?Vr6l-Ob-Ye}F43AU8jviW%IUvwXADY3;w){;h` zmN(N6jB0EtvBgBzl0XR(-b_Dk}=-u&KONuQfj;-OjP>U@kwu|Dd zC691Wf<)Yz{GRQVGqTI+$*QSDt)7}!LxQc8nSJ(d`eyNgbitNL=d*imUSjU@rLp!- z^x1)3JlY@0AvK z!Pc28G5+Vi=c8b&dT8Js;JY!5i022y;uk&ChL=U)W15zcECW9&^uJcPrQ`(LJDbFgn=k@Oj|(t1ZD+!jUntZ*axi!B)l= zBUQTX8LSaiLae3DV~KR{e-{b~v97cug5E6cTiflXlPdEUs%%&ptJ?gKxH5|NeNSBM z8Df3XA;$k^>8euBaJv*5sLmv;V|D#2BtUrXA=bKl$L!$Wel)Wt2(gCV zJ8F0Sop(=~IPFLC{Mxkc8FPe02@+pc4zYgeebi2Ok%^LHM>#>g(z-4850|KQVa)sU z>cmH9jyltRu-vM}hDwwm@#LovtM1C9_K=%g#_u2f?gX8h;8q?wP$N+5?~x&v^W=!V zDv0+rsMxuJ+o#$D_syVw61A%D46&Bn~GT4!H}Sfl?w zVn432(A0@+cb2=Y;vaKI(ta{1LE=pMQ0vP*N9-Q7t0(PFS@|b-+sqg4;$rnQ0<{j@ z3$e0iIAXt1OiZhI&<$z&)a}`&nnbPr#Y3&dGmhB%*Do}6Vs7L)*Ipf86}%=SN|0Dw zE!2A0@rd2+FD_$b#^Y}1(rMM2{UtR5wGLzowX(TB`(w!~^=99G;YN=NRuT8|OVk?H zHq;Vjj@U^`FEVvvMUe#RPWcS#(cEkjB}gpo8*1GNK4N$Bf3dJoLDoDCC8)S5gt)XH+#XYV+$$kd4f1JWuvGQXM^^hBTp ziRCjwt?Ng8c9l%LUM+ZUO115NS(RbHDUCp_VlAlsOP_siAQQ_PXH|pRmr$*mI0CiK z{}^hG*yyvn^;vA{MC*Gw)Wk~^@BR9{>bxMO+=#O z;}E~C)%G^Gk1Xwux+U+KYHiYF63>NN*ftHLhrQbUA%#>c=7wl(5Q%9qA=b?nK6`a* zE~9FtRqnnE`PK0>1vLV-uvem0bYsT3Z|)aRO-Gi{dLJZyq!DM|TAy9v8uwSdHVt>T z-wshtZ&cL?)WZIl{BXGnxlc-ms#z~;Y5gt|m-~fSk!g?En?`dP7xScb%T0OY{>Dl2r=5ch89!5V>DXiHE`cym56_3dDH z{GI`tm4U>syMyCKYTDg6>wY(9{7+TysJ0ebNN8(e%_nPV<4U)~%Foob5~nPbAfa1i zxw@=(OOEKSzRS=;Ac0y~^9>{4!f)IR6?>{Q7sd#bAaQhah?Qkwj6Gl>x4|wM7r7^z zv{S`*Zqo?V!kSMzO${36E;-y@E&AiIKnW5B7lv5fV`A*L{fbL)CknVnr|3qKfY#{3@M-{ zm6j4ENGvN5V)fnTvwzsl?IR{Ki(M)rMAgmGKqF8KYd)=UA3ue@av7}BrD-5hg2aR8 z!Pb@RUOWH!+Ab@@y!-C3LhUsIwXo(>Mq^BIQRc;6cg4gu5+z7n-VtmWlRe8aLC=Pw z;>C?_-p<`M0=4uOb%DO!R;a{Ax2otQQG!H{Nx^Y;sbTbc+0D)V*AO)%K^+U{H8?}U znr|3g=NELZmKvsh>blcH2@?7|D(6Gf6-x%G$Mkg-Bv1=$zF{=D{={jVf3V6XdI^*u zk*ZyYbz@kJU3WLP!KO1ayD4h*RwKfH)(F(Xnon!ocP)2<_w-VZu~nc1iCi^l{;@R1 z?*1{CvD`lD9B|vKw~Oy+1ZrW;r`7!{U)TxzwNo8;JryWH!YvYFO}H2nYm0u_CcBfh zb$wOu?+}RuYGKW%oxf@aTgT_rRmCQxlPE#LP7&hwer)=T+hC2LELOiLOPyR@P$N(a zYd-DP^W9DB+pQ65&Z2@6B}f##N_{)o)PZ*1^^hU5l*+4KHfB-mP82>#Tp04&B6?$T8EBKV)A9A z%wEPqZv^@^u;x=nWBjOyq`60`FE=ltj~wY}Z98i86^^T`L0?`Lbkh<>WzxCH_w zNL+jxY>k}j*}FfD=w+Qx-a{Q|cvvG)3u``kakj-5CqlcbB7KeulpvAfVz3pyKgK?o zhwmfm)}J)@ZmG^CG$azJg*Bf%^q-mHhp1+%_Oo{aB}lB?9&BAp;LSO!4ISEQB`j|KeTj=@TD%R`gRM~2-L!wPxJF; zQKHK1QtDlmoDwBSyc-g1nKM1Ry;IF!L_#O08vIEKjX*7|`IL*(D@LqHkwabCTR@@& ziOcnZtzlO^uR+n$=S22uDb)V0!#uV^N6`B)-T?{^VGngJCS1 z^T-;P^b3`1YX<8e_z=+>i8Y_nG8dH=_gfEBL!M8tP=bW+vmBW_m)KoqsQRW)YJmi5 zVa=znC|zkUCe$0Gw(QI;P=dt#wZWDWL0JTaC&F5~zhWpY~78@`orAAymHbcoHQ@9Iq5?)$8T61M~AF$FGZpCyJ^EjY2d6wXo*X z`VS+X9JQ~o8oM>ALVAM*zH@f$7_CAm#%t%_zO+S~DxKBaeqU$=YGKW%Z-&i0 zE557OR)wb?AW(ut#cIJ;g(u#4e)Xr{#im}Z)S8Y9Gy=7-=F>M{YTOYI{%WG;6#iDA z1c@KZ1zW>Ie6e@E_ zm*+GBwXo(J#+H^J$xfn-+L~*RKnW7L-=whyeC2tBODD`IA4eBZ%lBW^2-MPBRN4)> zWbzyN)r=SW1xk>}b~8j z5vYYV-!MXD3b`qLV`VoyW1$2Ij1QBCesX*{rd=~NB`UW-0=2N_8^+wQ)Us%a`l?2? z)B+_)U_{w4=9Et=XRdFcX4S8$5vYYVpT6jsBCXt2vz978xv)S95*UM~m{-!&^6zUk zRpywU8i86^^C|b^P)0d@(kH6Wq)!A&kie)lef@OTM{;fcNY!x47>z(JtogL}XG9L! zEOSM5Y-DqR5+pFrP5!H*+2v6uLLFH@StC#jYd+0!!t=`f#mcLdXF3a%Ac2u_iW?-) zC$C*8p)Spwp%JL1x2UI0i^yYdi>sw&KNToJ0weL{-<_609-CTQ^^6HKG0HxJvIxBR zFxGtf9)0C7`E`>>H7QdbEl&aoJ*rPJXGyVV$#G|jEt?dda5!^-BKju9LmbYmpt4Mg z()fQH21R`&MSmnmeo#Vr7$!x6{8|+CF)3o>1R_5a^^p|)ksSF!0=2MgdLNOrPk8x! zk|RGTL4qV{9ClG^7TqR6W98%_>7$i!Npctn~@ku8T=cK5pr0A&R$S6u^PGeGZ)ZthvMP50c z>I9;%6nT{tffXEmMF|oV-8CsP>jWaa!A+lv=@k!(PbrE_v1N`JI~-r82(n3WVTYs0 z6s0yP!t4Yh)f5RA6OYUm91W)!IY+)7j+0X)+@$!n!_jbxwwn|wcLEW2is*|Qk(rBlr%-`zfMtQk>r5s6J&4m=y7M0+|DpnII@b!Q$)$%2_Ze*5Pp80%bgylyBg0 z)&pfia7Ki~*%0&Zr(Op0{GmO-%(Nih(?@ehTs?R#U=_3l-E+u5T_`I1qsxm3>%Ytzp-VIH&~KaSg=PJB}h4X_Pj>%!JdYxT>OmGz$O71gGt)!I1{6csfoV&eoNqdgOU zER(O>DlU%Gdj`}J>3k+dg`B{Aa8Iq;a(ePXB2B^|i4r6z>SL0B*$G5`rmbowi#%>3 z?tcGDAc0yGi!#Yi?gZjdCo;5_Zzr#|?Cx&`N{}G0wn_f8*dFfBb)DtDj`b|xq{|wC zTI6dt$q(oR{Ou3Iy2x_(XE{egE(nw$L0&tPJPJ<0bGK{Dr?PdO%g(&jN+VEf;j9(T#^2LdHX;1wE1 zmFG?5@2iuzYkY|%5~xMFi6;30oq&hl7u-a?+!Sv2YZD|m>BubFL8be=?NLxWRE0A9_i7KEGs729slOlmm zAmU!MP6;`^(zl{tNIr=YB(Ua_r|5Vt8Ci6JIFX>VMxYjsM20~bNRl#<1ZN?k1POgq zb5_Tf-$kAioauxFYT*b+yO_`FA%E^V(Y=*)t{@+kN%Loa{UM*2N%M7w{bG8(%6+bm z3_5VjP4vAhXeMfsmF#e|80#2$iA}+J?P#64wtUlW zrQ15&Ta7?1@&=pacZzN2FRIp&t!{UA8&(gJC_w`28$}wDeJqX6b=_L;GHC>AQPjsI zk92Iks$QXr{AlJ%XHm&8i4r8RzL8fgL0P#Z=NM;Q#S$8US`^(iDe~k5BD`J7mXJjU z4X}O*D=Sfg1lBkDMsBCv(mwiwRW4(sMxYjDahMcgb^@6kMYd;_8Ee)NYsW-Nlpuk% zhq4oPCzn^Uv=VJ!)YS;oLYs)jsF^QB-^xFUMU>Zv5+ro{it+{pK=e};r@p5FPW%JTP~8B}$5oS=Md&b;>9gV^S|R?-YMcEnkD^%FUKQzG^7 z-Fkr%B(VJ(#-t&Y<$|j5RO>@WGy=8A8*GxND%Jv6+#yoR!^hnoMP3P%Ac5_lc8!=~ z${d{!xpIFBi3Dm<)W;-`bgW%+^=^c0x^j-2qgNJ*5+tzw8^+rk#blr7)7!a=6vzuxJYEib9Ntq;0AY_)6q{i9Gx4u6K}kI5?P%QzuORXFkCd^s%9Qt3`Sf9-KrV+AI~X|vSbQnmcx5SyVZA<(g;nf=n-@D_+Y=UhV1rFK9aW%j&<#Zk&-f7;v`65 z&u18WFDI54f=0VvAF8Vnn$~2pmUaaDy*q|+|06>->6F5~d##0}47NB464>(*as9kl z(JGPKc0wnOKrPBgH7Qrl?+-Ez`S_p+4oPYMe7J{12@=?kk$14-Qjww2)aWZU`)LGf zp$Ew@Ql6S1Xl07Ut5Q&cgzk-+`hz9XpE+vr$`>S13q4b0?=C7WX&sh-4HmX2Y%A=) zB(HF+mviKt(z1pspx%AfU7!RBYz2nVF?DhI8|70^P4bOKpceZt$s_Iec#?gUuc%z# zH>>Kpa-Tp664(k1V|T8+vh(~b>W9_WGy=8Qe@T%izsJ)s+I*T@UT>X3WvQD&q67(S z1@uMeuncn1yyR-Al|ds=i~W}rVfK4G={vleLgXjuZ@bqs7Lh1H0$YJ$-2O75{7(Jp zMocfS5vaxULCPfYdpr$eNt(aKx@w!;JwMfyngm)GwgT!ImY)%o!#BD|t2WjNXe(^D zQ^uIzM@qRL@%D>y_UG=ngdL?O0RmeA#k}S%5&a$yb~}vkp%JLX<2hx9`n{@@2e5m( zDBJ9YG@DnSp#%xt zTT83kEL!De^9na4P>WW*`8{{M@{QtA#k$EgRu8vis*M8Y;pmgWahGxp?zWXBx6XH0 z%~0Bm9toUzQ+C^>=5qe_V{V4|OEm(uaNMPp7Jci>ZuOqI-77Dmc+~rm9tpJi4P$zz z8gkymG-}_Dej0&VI8qzNqjpu~si#>~$BXp@N|3;Dm%fU)%#^g!)W6CU3Dm+~iRK?o zB4u#pFn@FjB^=YC2$SCeWUnE`q#RzIYZ%9;)|M2-@<*^xf&}~FDY_LqSDW!!b6M_Y zV%56CQxgf)!Wk>A23*-%X1x8*b?6I}C_#e#@DzuREra6PlH%Jg$F`9`Eqx|TYojEs zk&?VV3S&hW1;U5`eV6RV1~Sv0HzLQNsaiY=30l2l(#nF^`C#`Ww3lVITcURP_8Ng& z=-)StOIf?h&zJoo@}(ayP=W-lPB1BR+V69s@7EsfEl=*5Bd&LCw?w-^iCj(l!(v>)IzU1Mf*k#mDB(FJtF#L1A!7G zD7)08%s2lm+%QTk87>b!E$*aklwBiG3upTDK28sjyXNI}gX$I%C_#d<=S<4eiM3w) zgba~Y&$V#Z*L$OR4Nwbx9EOoR>N9DUTJDNLhCm4tlpSPJ=7JN*5OUsqDz}%~;l69L zLGyl~7S>S17*o2ftn=A(_mfGBc-?fI=LQK{DbFkB{T?0qHpk&+a_Uz})R^E}8i88a z(x~@IR!!3Cd;iLNlpulapY{W|Uslq}M#-xhG0vHlJc3?q6KlR?kjhvtm2ORd4fO*5;)(bJmk&& z3doxeOJrj@7>Y&yG;7tmjCxhrKg+pr8)m^Pn-WAB~gL|eLKvgFM|CS z0=4)|^aZkiAv_6v-!AUFSoXhP6%zEVySRJ$cLKFm4w)DCM0BE(9c9vYs{Gfxq*Ihh zU!C&*{@<<&iT>@Dl82?hKioN%9=>*gNne5bKa_z4eMicq?@9eb8F;;@HJ7X;`exNX z5Gdhmr|)9@AFc`sehTzOuzx56uL`yBsq60ppCVr&eaGwna8*d~Q=qSd{gDU zy|w>BaBZirFZ#8xrRn#95+t~F(N`J&p$sHYi~mkve)|W4zS9<0U+G(Caqqe1jS>G+ zOYjc4R(j{f_oUwkN|4~z_0RW#1Zr^$_MV$w2Hs(!ZKLDf0X~rr39pAkg75sF-#MNO zwfMPtbxbbD?1|8b4Q+*8oY;H&bU6<@per12@}1WJ(Lr{LKS z|4yJ5pUG>R9}=E~YK-mGB`o_x!h6q1P`$GMc^t%Zp%&Bs+_zJku)VR5>aOjzJ8F-% zXBp^MMWa`oghsVEf_m4ud(sJ%@LThq!oR;klpw+H|DWFn5~zjsO}{FNnN?f;G9iQPH6$%(rQ2RsI{Er+FI)Xm zTH3>pvZJSNV-Mu^hox29WhG=u-$wr)MP7#bjgdZkOjM{-l5*X7kD~Y4>MPfkQU`hz zmrqlFBv66`#a`_9x#!O=l~8Bq6qT1U*W(yVoCFE-8rtu3&!c`RsaD;|FGn@-`xE0N zNF1HwvlCAab&d|;wU)Qy7gdpy^T`es{MqVp1Zq*V#`ZGT4deCL=Bjv1VmUSC1rwhM zKC48u^WKlSD06uMKdVIj3aS^c!sM&_Hpg+|&V^<0PFC;p+Yclvq>`o0B4<|e`+edh zNMu{*v!`?obxI%MJqK#14pV*RWs*NEe9WGrI0CgOB4m5n@rLo+=GLmmzIS5ZsBd^x zLfm^MZ>{a+Y3uh9K@LISlOkBG4c z9}aO6kKlo+TXAF>Sj;qC8FWv|5Cii~5!RqlT)#Rw_BLBXU5+z9dR_=)1Dp9Dj%Hh3U zrcQq6cAa`fY~Lm{0<|bYXM3v^3}eUjVQPHck|NKZWd2<4bP?~aOb zq8i5sW?o%1f9@7LqB4jtqEp8rql+RlLzB}h~pcGTWpBgDyaj^nk7TbFkS4ZL7Y5<@it zwJ7pyd#iaUd#7kMb+1Quxna-+lYFeUH=g4NHz%XdZq+~3+3O$Gta#1UqXtQ2i=c8A zN|3-lpK>PX`#uBbJQEQoXJ`a!)!iLqN9GN6%68+YYqaXAy7$~JuCG~ap#%x+D=E@Y zt&h5UI!erVbWvneQwx+Jfvwpv5{?_D;^iu0f81MW1Zwpi z7-RpMJH$D9(Z6ei7^-qDO6;EgJ)b}c64(k1qvwW!%KWCh`*vzejXm7Gza7}>{B&ueieLph?JEQz>aQxebYH}Sz-JCi~BTy@GS)aWmU$FCF4wsRqY#KLD z@vklC%y7MfQTvNzAx^u4+y>M5`Z-00 z_qFGb8>tbf#d`~LKOe}lIGnS)`_-wm?z3To7qLY#Yrxr~0+2{*b`T9IRSXN^ED9DQgf&%8U` zG@txoj@sK(q67)7)AX(1qVwHtDVCTsXZ6gw>f54QZ=1y^7AK+ z1xk=;RoQ3P>=NpX^!HcMqbsToT{6ihB`0bGYGLc5_i?Iq(R#(XiAJJ7*a6CEdA<+4B;p_)9BU$z@B8KrL)t^u38*Pu=}{ zzjc1N(N>}a39QqUIZ*JZ+rH3BXZC<@8i88ax@e{MiC^3`X-m65)a$8@QAp_Rm&AZ%H`}_o1ayI9YPg6lTVf`cR*`{t*ZHKcT%VmU1f=ht&8>$s!>(VNS0BqzFtM3 z1c}}`Xs5Tvq0WsB+&=RDUR6EI7%CqZ8?F(kg{_OS^nR|bw*US{6#8?yKnW71Xs4d< zXm$UUB3#B|Uk&xuzDMHg^LsP`wXk*3s+1$ORo0_BM6E-&1xk>}oXuzVI2PjU*vRdp z(=Sz3(RUlggHs745~zi(i)ItiRaJ(Vk>Ykth(rkzzfoUueo}~2yf&AyYM4+FRl18c z`*LUmYGLc5td|)PDih6demhW5q6CT1FMW3IiXl$>7yQmQ4J)cjE^@7J&zI8()WX(9 zyFmStU*-J#tZh%15+z7vqIN!(Rxe-K%4Ni4&#ZbaDC68|SW_cV3tJauz5EcO62Hpt zHW^b}q67)7(}r<4VSH7iVR^Ua_f0hdwXk&=M)6u#-O&lAx#ylX*TyI$^!Bkf+I5%x z{H_-dDj5Cke zcPVGP%qD(TeR@<<*NcYBBF#2vZSY+=pPgn*s8gfK5))e&?I_o?mRfi-R3=JPSfB)n zLh*feN!m4{{~2x{0|(Sm%lik(I=kCz1ZrXHqAb1fP1Mu$cSXXkvjj?zcz!*`9vUyy zsn?0iNK~n@+I921C|vtjjX*7IU54T0YN7fSTOq=HF#;t>m{i8AO(9O-SKK}pd`J5r z75H9^>U>utPzzfZ?X8}xsTx+iviSIQJc$w{;u${sWw#I~<&Rv(rvvJ$D(&)!N=4IX z1ZrXHqIDDB)mBHZ7PXe=&LB~O#K6)%`#5>k?l$5wzIj(!HA^>ZOwBTx%l7wv|) z-%^A6opKiZl3$_(i5Fvh_7j?O*3QOd4TjOy%(8J%O0^? z(7ZNNS$PSJ?=xJW1c_qgRhxaE_N-aV zZLo8%HY)zK1ENs7?=%9nuys-2{(C1i_4G`UaMK!r5+r`!K%T+{A9?bV@m zqs5zQ2Q>n}6?N|1PF`s{wogPlt=xePJ1ifSEP*B$dZi$||MgP0Os-54 zB}ibMCcmh!kUCp&om*~fxJIBBwl3O5Fh@2u`sGb``qVIOj6y zXLV`S$7;~MoU+KN!CD(^kkeV_6-XqNPKlH#=cS{ z)G1H1N$N!lHCKN|$CD+KWEDuD7Pc-LIjQcBEa(#%&Q%pCLE^xo7`x-85GT!Z|i+2s#W`1pah9IQ)29V6a@%c%4HNz*HcyK*g~W% zxKtxh3tJam)xgix^}Rc+GW~uLC_!Qh`P)?~+O4ODzl`fW)Xf2Htf?#ZYXoXx>!QhQ zXb%}*WWWn^m5P<1Xh!ClquokpM*wk}%fUA2bF+;F$s&-a%=2@+VR zX+7rxOTE5u%so9Ki9`amuyxUW6fdeS1|?EE?#9=~C?xdu@w8PA^<~`@D)dq+jX*6N z;pqEnTS}|DYjdb=wEhnLxM^1V>_4xhaT3g2Y(ClKv(M04%PM{OSrsW*RptFGhwM16 zwAKbOPJykfsD-VIyn|&1s4;1Jh`eV$5hy_dBM`JkG2;Mr zrCtT``1wGMKrL)thOutnV6~wA7uK9sp9_>Afe{Gu^{pMCx=kEoCap1BBTx%l7kST* z_gCNEKjTy`^o>9X5*UG?X!wa<>bvxr+^>RGYXoXx>!QBBUpJMg=+|y;bBRC+5*UG? z8U41l>TI%wZu6g{D8A2HC z!?+>su#x;zRj1K@*Jx9ncgBm0fO7tXw-*k^bf{jP=%i+bU2`Lw>#cY9wbjKm8I+kyCs2!X zro5G!hVkpMaw_MJ+^R{?1c7}NzK=VU&vb&;pI6Gs<9X3-k*f4JnN;)V%>+u2z^kRW z^9fUJ{5`Mgd@zqjpw`V9KD*(GG*0}IT*mINtEj@MbF0GXPFN^GLcfnk?JKB1UKLRV zIyBJ;)Z%yU?NUPDm8r1NP1CT4+ORxQa72%5IY;$4Ue51_W9FP^!12OBuE8aGviyWC zdb<1s`P{rWDnEaI!u*>feSDRHXdlmrcxJSYW<@;nVcU&oKRhGiaf4??JX7Lvif2nS z8jv4@{Tb}bV1EVAxY%dGehjwu*q6cn4Yn@X$6**_$@|D&NcKRomy!J>>}h20BhS&; z1Ib=Vo)fZXl2%Al%-}M`4mfVWu>tmOa(sYe2JBhkxB`b z@(Qy@7$r#HGc=5AWP!6K&Q>^E+H5PZwaped_fu?zvt`cxB3tJ)cc$Krd%2Xfhix5R$Gmb}5ODD#E0UQmJr z=M!G33MkipM7&r+AFQcYp-;kF*0#=lE(sx+ZG!A9V#1sD)3O zY*G7$dt_KkHFd=o0wqXbe@x#|O!?HkU8at@cX6FYpcb|Q!F74G-q67)fA>)j(z+T0i5yqKeoE3%yYUyt< zb*9=8hg0TK1qy#6IX1vPMUD?}td4#B9IwN-X&B!XOCvH&Dy7c6yb^86JHeg_lpvvxQKkQI+}R6Ds1(<-Xas7p zKZa*z0iVp(aogN&?LJoDZ%!mpf&|YV+3F0;AQzsT=9XL3R23L^M<9V(Jf~$_I54kG z++?hKJ5gsP=Wi1zL4vb`*kTT32xY01#|>N9NA-U@S0hl1bC%eS59BQ!zwpL+S$~N7 zF|3I|2@;&g$$3nHT+Vnq#@b^a4_8GFWYGxJ;w)Ltt_ozzvQ^2}C0mx*?${1x>yle7 zwiUx*%atuywq8+!1n2azWy>^06y+*+^SRH|SG#s-1ZwHF&)I4-+*G9osuGl+h!P|? zH<5D*17&bFBWE>oMk5la#kr82;TRxzrp+_%v^3jB3kgS2tTEIx&}^P(^*p0T2@?O& zGnBjFR;pE5P3innAc0y~W5~}i{NkNBB(NubjqjyaCF(6uf&@N8!)V{WqFcJ#V6~%PNsT})tYhSd`=yYZvBNNRCe<1X zB}nM+qwll3VrI!;b*FO?$ywH%^TV0eoSn`&Mx3F}dFPzZ%{$D~?C$g<5!N?}$~lDg zBLfL%b#o3k?<9|BqFheO*XF!!&e=u@5}dE?&x58N=E-_puvJ7(eeT|QR#PKT3;TT9 z6Y#JS<(6J{M`Wz8jRr_?E;VOP2X?OK%xKP#=Im%Z7i!_iU>GYKO%{X3R#MGMWRM)c z=C~KfusNTE%Zqv{-u3QOS-M(FoMyxE=fZ1F^gOr|^tc(&RNN|*a zy_11R!{?hPJBMyGQwvTc)(F(%*a!Pe1M!bSw;DLU-JMm+a+d{4kYG|mnoqmjP~?>(upE6w2@+^`QBKj}Iqt8sv#TcM%4-B_Va+!Tx7A!X@1atv zeYr4+5+u-yqJ8d0baLCDsHXB{OREv6g*D$W8fI(e4!_b&)&23MKnW6PchUas!(TXq z+ICUCAtyBgwXo(>++h87XW^>xrPTBk5((5oYk(}7Pg2P* z`)5)=eHtQBf&{OJ<8^U?Z`bhZHeTh%E8LJkEwm*JW5r+b<>dL*RjT`I1n0bQt_4j`LnQ_l`4rIRB2?$M2bC#nFXyS5sYYKOpQf))ps$FaL7BHyhBYHQ8~+S5gXvz$0P zB9Q6yS&0;K&BnT_;f9tPfm(QlG~50*Sf<`yM>RU1U7!RB&H>?gG3S9$-K9(s&KTir z5hPGczw>5SSBtuKP1U!NA<>RP>kRLSqT$2ViNqrst31iiX%-n0oO{JN8-e_*zn-2F zceXZFA2(X55vYatM3IJjSH$4VE!EsU69r0;;QSSidk1n@5`LXXW@z15wO>;~BTx&U z0_|KsF{SKquz{LzEWSVq5**#<*da&w$>T*i0GtcJc>qYDmi~0RbZsOSudAYVSIHvL zu0<~eJ~zV{(XyGiJEuPF5Svu9kdff5GtO2CWS;eV@QtWkrn&05;;O)Np%y+j8gcf` z6W^R{r;?qs1xk?M%pH#S2eNl=Hr^{9f7MQ<>M%niPz#?MjUTyA2%phGo!r|-pacod ze&DESAOoVrlpw*Y+c@GISmBnBBFKd) zlH7r!$Vi};{s#A7oosbnUs@IUyre`Q5_+ca-B5O0x=GgDhE>(1joCGC6cU`%$GJd( zyuRSQA>w(aMyleBNwCbW)e8 zheHCj@ZHd^r|Tz*SM7SJ&l7zwP=W;KmT*iukY5sZXtOx}dsh{+sjEhy7QP$9cwX&* z*w(A7DpoA7KnW7Oc97%gf%StszI!F?d9Bst>8C6tPz&ECWqGGdDwD`&>e1wp7D|xd zT@X0#8Q2No0j-+k)syRKa5p1+KG zhAGzt?+L*B0U&`|ypw?E7pFMq^qJ26yt&jL5g$wR%Hr%7Yd(EnEzu%p=HF#hr5nXH z|1J_Zd!-d_-_MT@{<@mFnkBnNpcdAAT0QWhOvERbnyR7SCzB{a0%xy=(RBKHt8a@A zYV7UX0twW@nonLF^Ri_v`&7kCv|XSC37oxBPEr4QqRfoms_pu@8i86^^J&ESw75W5;zwnFXx6;Lbd3nuKg9R5vZlre53nMJ4L*TpQ^ggPg*EJ0_y@Z3)fk>It1yyhsdey~8b(bm{oYut!S zpJ@bYVSI;noBrlc%c^?a&6c907WqMf*Ff^xslYnOk(=6T1Ztt5k>WUQ z`-?zXNbp)tUIP|b&pG_&4`O7l_sl1jgur9U3AIC)&kyQ;|Ur-}Z3+HgO-eAogk@aLD_2Z0CZFYwQudU@Zd4ct{ zdkZFz#itciw+AQF2-L#4DD{agQp)HSWmNVP7qodT61+y3*A@oW3E#e%Ue@@zl)6-6 zuSTF2)=chCTO3A8wAUc1Gy4(3jw&VEB*M1a!VPbI=nYDmK z2@*K7r0<`PTO-QdEvnW%&#e)tg*BgYoi`s8m5!RqTA4zk1PPqC8%AWWKSiUl71X0T z2{Zz=u;$a#Z5&U=Z(CXIPjXbC1PSz5P|Pb^N*U2#sxF-!jX*7|`Q$aYoIxf?T3K!A zFnO85P1PQ%;@IGO@Ul{KdhGQ!4 z8Rlhg;izpGoHxk%gPc2v5+w98-tT%gO7gCOyuTsu>&$xq@~(^gn|FQV-QW24dwt&5 z86`;YevrJ&+co8F*Ew#aGBX7k)^fgr5TML-@a66%xGX zB=7k4VHtQ;sKvX<@qTe15-8yv>v$i!|NW|v;Jxp754;b{z^g(n-ldXvwEO=Pyg#FN zx4e(0_uTYaf)d^r)q4k6woae~3EutmzrS8rN|4|y^xDe5 z6R5?{jrUOe@adui34VrN+tkazH^uvj@-B$~do4kNcU%1L?;N#wXUc!BSG*e~?=i_& z!u8neKkymq_kj{5xUKy2vqA#3upiUQz^meG=RGw4^9pqWuLKEx3cOF}hi?!G)Z!=2 zdx3sPpoHJ1cV0Zxzh4y++=9J(`ga1gxR>zWlTP5f<>&T)>wW%{_~#xD-yr|?w6I^H zZ*y!arTFN0t(Q~hPD*D@!;@y_q8Chee=28Mn$!N@`NpSmqUX@>sN*z7RXSKw@zMF( zJ&i!EEz43m=g!iZ{KUMD#T6fQgKD`bK_YLVRE|^gjG6qQkIMMtO%cUMNa8UXfm#VJ z1v!yDPn#p#9wMTeQAqKTWX_K+YV~(gI$`6k6(i_E7W?pCAm|u#AUyhPBc80K=Dzd zZ&8I3BwqcP)JfmznptM~W-8;j`@-epMZ5|cfm#JNC2?LjSIlG+nMfRT%jM(DpH&oU z&HXm1b86@{zm`s{DRbK8qiy5b3MELi%b3`y(f5}5dj2{pqtD&FE+03pHP#5!dRQTm z(__QUSYl^_pIkoTm+z!df<(WW37otm?wcuVtf4ZhKA7(EQEyHUjXXs6n_9FL=ovQ8IwSb_X-f{*OwDrf|1QGaMtUuFgR#L6?{Nj|3TDxpv-cke&!Cz+C4Sx-ls zI&o-yQpv}In7j%lNKkKTQy&>yMx)}vl8-Z2GH3*9(b!>AUvCA*54%d3@#T;vuOmfcqG#a8f_#WJmR1P2^wu|8e3w^cq!6LJ`$}6Qb?c{-k)J? zXqZ>>alOed?W#IlIBPfRn9@3H9?-6k_8dr`U-B_(?Rwp# zk^AyD8i875Vc295SOJ?MWMC=D$EnJToF6Nmwm1En$|@6n)+GDHCOgGq8$~C`CXsxw zU4jxM$R?q^v5EHEB@@DmNj~**qaT6lkkk^1jal8=^^SJ-$}WGUHXG5N0w%k$e; zlI$x<_LYSaB;v~6a-CWf+=oV>R@@c(39_vuA7oz%lpsO2l}&b$Rj~IhDuZk*$p_h2 z8i88goo{}7j|j4@Bp+m73Dol5AZzIa*;bMdvabY6knn2gw4G0>45;lIfm&WY4iIEp zNj}KFk|;rfY%81WA}dLX=TrvSR+100uQUR+y!Ih}drbt{R+100uOw=D?VPoAf@~|v z2iaE=B}kBMWs_ZG87<>ke)~$0eI>}g(g@V@`pS~RA7o!?1ZsJsM1UaMO7KDUl|%^=WLw!}7g=d1C89FOwi0}h zeWeko<&Ac;*Dyi0mEeQyD~Vd(ILKN$LAI6PgX}Ab5+umBvdJ#8>h9t)$hH!EkbR{Q zsO63Ay$&WOf@~|n2iaE=wLJTQwRD1PD~k`ZuOv#4Alu3&TgZHnI|-FRww1*P*;g8Y zTAq~=zaSH2TSf3e_LW2l5}xH0Ajr0I_#pdABT&n;00VbUww22V*;kTmD~D_>Gk&qe zmS@TG`_Kuptz16HzLF?G!m~I7Wsq$}SGC+B`${8F3-8ZwU%6yoxny5ySLNB%d{tPU z-@bCmzH-UFk|;sKn?@5xEpMI}=o87dQhbnoB~gL| z*;x)*PiBVkZ>bk0+e-04_LW45H|ON@;+bgeYw=*k2iaFz8Ay2Z=)h<|c8}tNY#)t4 zEpHYcH{$qb^qYLw1xk?cd;@`TknA_b2ib4}B}kB6=a7A8W*zs4?wo8Z#Ru6}8i875 zXE|g&nJsfZB!X-!#Ru6}0wtbjg0BS2_S;vA>?=j~l~x84ao!fc%|LdK;)84-jXCVZvQhbnoWg>xE=$SH%q@yZE zwV@I1G}V%(EsHxHBL?|LuED_DKhFBu*HxbbRyWKaj zdpOSp*-m7wcMEnzvjxdC{;s-xOLV{+wfR=(@afh-ejgtYo|eD7IAY(emf_`w^j1$w zZSxbJmj4Q4wfJ}Izt=^tsk)z@Rk{I9!rL$Frm8PE@d4p!aT)LLV^WoR;b&8HP_-LA z^b?*0&&$8PztjF#cW|V{xZCCA;G^-eLFcibGm4{^X(@iT6|tlOD9$~N*&HMglh^)kl^1@^CF`Iv+aQw6NK|~ z;^+0Bgr~)S_kPp9Q9YmJNj~_wyCq9IKjBI6y!`uW?qbn1dj3jxZY(~VXYJeb?!LQS zJ|H|TF5~j>#L)q7)U}WudCs{z+$GO?`tRJ+;`4f1I+0`DS9!SJa{WaK68!t!w29jS z9+qB>TIb=m!ENL}2~Ugv?)|2{6V`|4dGS2Id$ZqgKjBI6y!`v+$e!D_tY%Nqf?F5E z`X{^SY#8yy2ZX1^Wh9EfAy>e+^vnJ>VZ)2maqg@d>A!PNi_hz6eL(y~gvA6(kchpi z3UOEU6J3?%U6prU)QY|H3V~-ucfOSFT=1Qv7XPNF;MdX#db&%wm-e2nr-cOnrneap zc<1y6m-0y9y+I^AEiS|RZ5Zc2a+jv0c^dncP=e>>zf%p32-Nm>i_R`x^Y*;pnuuEb zo9b8u*H@jO+P;)(yMWs6KNk}G`+XVIqM~>#_ga)EK`s7GEjS|3&Z%dJqMku=&%hFD z=Mmgz@Rjh$!2P^Vs5N0xoqsMWvypEJB}nk^_hnGe5XGYn_YD6@cv||MQx6wKJ)Gno z4zG%TQ=b?CeWL#g{k>=u^`eq{QM?i)__udY+BoBP%HO`_P=Wp5Npkl^3%%b@Wiif519Fa9UtY2p1*HtwyKQ8W%p z9tZKN_&1G-{;R_BXifF4&QVm;{k|oXAi=+Bq>c#qeP}$7;<<-6o_ps-Ek4tGqW$AO zQPb8Am!reNyz$(BE+qJO`}#X0PAoY|{nh0I{i4<^{X*WZa@4_dp%(w0-bDoavZ#kU z(m(2`J5qLCQpQhs5+wMy_jlT*`TwzX)=^d*&)e_aMT5J$yX%e+f`UFTX$boH<+1=gyU`uIlQZ?zw-gR^v2PTf)~uRn)yH zhl6)T1bsqjLBhXZ%dorhUBM?e(4ww=I`AIw?HXu7LS3tG-OH)r7yNws25 zgm1yuRoALbk4dhwaA@s65WY&?L$yjTPn6lxYMCvWGFu|Tx8UolYybb0E%~k8#MeTV zx>o+^jiY3?#G6@=o9H4z6uF-t$J{8Bn*A~4}`B$_wcVNTk_)v5xxaq zS6!>j}*3vzE z6%y)N#bB?N0rC6?!dIz#_}7#z`8fj-z6D=bUCRuov~gKgqhz+^=OsT7zDnI=+{}TQ zy}FOgmi*j@KDn<_uj{LRApHD_?%}JD;CB@k^{)IJ?gv6;XG+DNJk0y9AW!t)6{*zg z%5Q;Gfdu5D{wF6D66#w1PT}5f4*Bj6gs)Qf@UJOb$|kcVsuZCGUswHKw$N~|waaWN zo6MF}-cFyxe=SAGHWsehYajt*1A15fYayYo{r}7LqW>Fz{6P3BMM&Qa_xv2jQS`2) zpNFTBeTI4`vR?^TJx(AYv!(1ZTXJQ#M1=oZNT_T7|7!P(sBzQ}gs%$x`f`mSi-eJI)lRi1Vcb`zS|9{Gs{2IUygs)PB?Ayb=XaJ*aii2u|ts)D3aydR% zkt~pq*-~~j^D46?BK+4vLS6g+4;XFJC-*I=BAS02ii3XDAmClmr{#Br_oHmduT1!H zFzUU_C>nJwV|#cS${C>g@dM$j)II!b${DiDY{`|`5)r;dy(_$y*;2TdWz5dpC%ep+ zT$wHTc?sQJ5xz>@L*_o=UbeJl=z#1pTXJQ##Gd0>kWknEBiu@Tva3}CYNZpt7OJ8? z2h9({yCQ<#JJ)^u*Y)q`WqmSR@;|wQuZ1dg?Y~k~l~c_kn_Stnl;3eJl&-llX?ZP? z=bcqu)a4l^Ta9aYrire3E=+xTnE~)TC)KZbe$ZB#FwYOtHP6b~Uj2&aYpH&P1gdyW zkBNm#a+>mw>Q`t%qE!BC)`QY=jTzOiE{(`)%0H@KA%UvE&#~uX22=jI)nxq&ElBXp zAAfS54X64Q5~#xOP>6!@W1I4i>Q`v_QtY-Bv&2uf8mr+qEyRR8F--YK^((X>5$nTk zE9hcu+pAwKTPaNW=f0JrR3uQvGjz5$uH7E%l_CEeRlh#VtRerXeuXNYyCYQ~v1DfrL;g|y3N1+R9GmUcWO%&~)vu6170=LF9#OKz3tj%% zs)~aaB=XIDYdw!HY_C%EQ7qEsAJwmrKo!qmSzi6>>aj$+{G<96s(2=jR6h{5qE!6~ zEl8+$q+TuRUD@iLsrnTXsNy-c|9x^>eR}oDQN{CkqzWW>wvXypXhDMK*evfiSHGV6 z6;=HT2~_b69TRHa&R-ja79@DS&GK4%1KA4YAJwl=rP``$XR5sh5~`)E7O(18XhDMK z@%SFfn|S^_fIt<`m|32mt6o9%4ytER{e|*%)o1w8K=t#11kc?Ws(ytQBzP8(@1fRM z@;ZP30#*3=sE2b^FQ@8P_^wocsCqfoC*u967j;!ns_Iv0LBfxA>N5qz!2kkPJjZ5v zQBB1T6+=}0N<|eF1yp3=nK4U6vOq$u-St;fp#=#))_V8g8AYmJA%QCVd_t%gsA8e2 zU*WsrnK*h^c)zH*JE~uy1qq%pv!d25sku9dHT=Um<}io}sh6jO_YFxf|)lqEx>^3lcnc#{{oEr}`BVsEWEb<)Z$( zdMxuqv>@T%&&w>~lN)G>`sDI;@s%iB^1odJElBvkjaR=?Gq1e5Er39k|2ugEv=V>z z)lwED{MO^uub{OD5UBE7rI#nFOi5)-GF$TJwkd-|!f(?a0j=G{*Fu%=k6txOWlHSl z0okkX=W49x`-exUOo{sve~zAVTqL6U7^+`EpBO-(%I~|pajnXfRK}$0SE%y)N2LlR zpilHyKv+tJgx_m>BYNoD0|-?4y{Jb({P0(DSjvKgA4|OYmCBS<#-yqS_*$s)qn%gF zP??g-m{k1=RepqnRWFuDK&-&8Hncr1giX~?GY+d;+(-m3le@V;Z=%M zro?$k0D&q$U-9Z!DpTUz$3&H%`zX~9gr8seE1fK*Lc-6xqTZFC!vzqi@^ibWPwwZ5 zCaU~AQKmeCe;#A zByNAk@lvk%9vFB3N1+ZV;}DxFpdf!P=)U{U_2P`uKe+!>J#yP0b@>o^{1`g zI}-j_)ayl|1`t4?${*u;eY?t(R1A^XlHre+Rb=r;-YWV861*Ch>Q`t%!XHyd#SgXi zT#dF(Bv2Lj$yKJLVxi2I0^XHhHBj#g?-#X_TvaCgHNv)1ArV#Apqv4!9{~iaqG}vO zs7y)a4XS>H79>=rr1A+b%TSq;%1u=L3JFy4>Tf$LTQXI~r0Q2_L4wzaGoeW$ss9#aOD?bB$!|HR$j7(SWMqSIy zNmp$kpngR;H4>(2w~S1Kb@Bgm-NlKGXc`eCICB)H#ItJPh!AR#j+T}6k0`juL(9zdWFNU zJc47CKcbJaAR)6Tidg~mE2Vsu~iglAl^rS!dKISGg!v?ocK3D^2C2N)+jWNlj(U0re}YKq7%EnRlt*oe8dAsToD}q+XN-37KV3MJk|vr7|)XRWiTQ zROYYRYaqen55HO)^;$?sZ_?CwB+8>y{fa8W_*$rv-b)p!fch0xwq<{zsnM6JU-{8M z_3eQK*RNDYrk>P`dMzYmuBCbhu7&ehjVjwnpbFn@RQ-x7^!To1f2gT(C)e~TUU}6h z9@o+=0KO9>{AlM95C>IFKkBtmCHr-%NCnidR7U2=sG_NHxvF2um_#)!6_)}Du3xE) zOg#-4^;$^yu{J7x_$%Vo(|}O~s_@-L)vstC2j7*9tyG;*?+Wi1RllOSBD5eOqqK_F zlzl{1SZF>92~^4KgX%I~#fz&rDkD>QNt6W%nWJbbBMYcssf>(vBJgt`RLLxgR+&d- zWU79pGBVl)K~O#ve$a%5Rlk zp2+npHQQ&P1qr`RM~y%H)~=rIi^@4s<@=*Ijsib7(c=3#kJX|w*?_)8jl7~PNJRB9 zSihoCDiWyj`z~+H$@MEW+owj5UN0(N%kS-!Dv*FaQ9Y?gy`@qi;rH56qiw%$4iBb-tN5?sGhu~t2)N0C#h zknkh5SCfHw9zdYVkJ?dH96x7J6&A`SxF$n6gSz%}iKt4Es$Z$RB!EDbpRWYeuT<`% zDn*pzsMqpyAFf|feicQi`jyJBR5dEff`p%UMZGIOhYKK3<>z)$pIp_iRGz4+YLpME z*Yfj3`sAEhdIZ<6R4%G2ca(D~3le@N>;2}C?* zwOy`Xsl44pm7kHT_8LgQ*g(}@X>6cg3kiRm;N64kS8DtbK%mMWy?A~O<0w_9_C`h0 z&;2o#>Z1Y)u3xFyJ`*iS_@gE79x#pyAW(&$FJL?v@UHyvAlLM11R2$fsx=d8%&98$ zQ5Gcpv8YEt4IqF(l|RPy`gRy?8~%7%MHYYLt>RK3!SyS(THQbk68@MvDt`E*Z4(Jp z;pd}lN!71Z)ga(q`Bek;uJC?Q^($4GQ1ducflw+WqUsuyGjRP%RX+jjQnGaE=Dk@u2^(!^or=IPLvLGR6<#bhR ziprM!oeejY)UVVhSNleJpF_SDs-nIHy2tnyecX~i zjWrg`Z?EUh`q7FQ6MIWrPwc=>oAEuXUYjbTVrBAOj)EvC4 zy?%CXvK<4T2wf2mZp97Fw%fbj@+NL*$>T!zi1UeSndhP z_KRBOk5lM+Y`Kftuy|AX9+_%2FvstV?GBRnh+aKX>-Tt=rS8E5T{B^M_b6X!r#@l& z5Lew}-ICFve=qz_Dt=eCqWN9f9&zt+D>q^3$Id``kE_)ptszgnd(7B(-wJxwisXUZmFZnNzIS4!)Z6QrTNpy z?<&o+A@|L(H~S7KU5Zq7e~y^p)_}7d^Utoy+0l zGY0GG^T}PaKbN$sB)p{enl{AD)+9!F&wkN~`0H|y@SuGjJ!4Gw@Q}FCnE2ZBN!W>y zEBfQfL*!2UMM@9d?h(y5lnu)>%e#KNfUvw^oc@m&h?248768YcAwWHXACii_dgOkw^<0itB$Mw3N8QKyKb^;ZD@*8 zA^fg}J-?tOm>Hp0Sun(WcQt`_DMApjazHd~VgDeyzF>!Ful5NhlBVshp9)%||Fdm~ zxqa|DZEo@i`bM7>p0Bm)b(OAjRhg&t&vk{r-F?T$>Alx4))TBAVm8SVuC+?#l4@D2 zjar|9$LacQyA9f3wU04z==eN+|BV@XXZfx^^*g4;IJk*aC9}9%(o11<{Zn#B`zvBM z6H^MU)jymYt-q6>JVxuw+NI))NEK1zloqmXEnVL$6rqjSvxbSa>$dCP*Z-j(l;7^i zBlon%lgE?FIV4ATsb|r3!@1YB;nim{QSODK@9t7ve<**!f-|0LnXh&s)zglTw5~OW z(e>5b5497&3}s^Wkwg0DRk`)nvX!j=`-9f|NjXx*%^>pS-yK)k)(Xnje)CkYKBn8v zP}SP+6%E#nUtiL7y#YabulLVGy|(+dz;S)?wq4t@)# zFm?U(Kr}twjJ;tV5%T7w9$BiVrF@X@LBzH{qUpxMX>?tAeTcsC@YHaRi1X>B-gd$v zOZgyw4h!BD5&W*0_-Gv0A1{e*D<9ZH*Zd1Ik-y!4SES-rLf70%m{_o5wXSU& zYbzh*wo58*iFC~^k%^#ObM*-eX4%RI**{3dt(~s9wKEa6Bd1>SLAb4a@Oq!p+UzZ# zNcAFbOKs4BS9Cq~a&xVFy_ZZBi5Xk(y8e)@e31RzR=>v|@r!61|NTrv%vgoBI(eIlv2hofum;h1Q;wru$4cb9GDgWT_uihEJI=3bPEjbE!;)lXlvl@D^?PAcxH z>6&|LCPoe4Vs-v_##TPa@q<(x4d|Mq0TZ)}f3#XmK4vQ)@kJb*~$kw4wC9nx~bN}3b*N+qbL)Dst>pS$+^N-KDg_{R%^+DL!{!!N!J`Xndtv< znw@#-JX`tT>yP`aS}Fe_RiU0ct%XhZ)AjPMJFFt*_A$|<#4s_2BbbV~m1#3W| z#Y~(}5oUku*n)g;V5>*gs;k3DHNNgW>;9GTbbU45UF&k%@l52(x8J@Rp^*<(Yxu^> zF|!e=!b4tI<70H9>rB=&tM8$XOiZ(n+LPj@Bp+-%=ZjV6NdZ#j-2Kst*U_Ns&n-S! z4O;6=+**0kPI~9ArF^i{*dTjutmvdFzggH7OD3f2w{K(y)inVVbBi3Y)AxNJZX6h5 z23yf>`E;339`)jv==ScoMW}}>*(931uf@;Y!)?xZ+#cJ1jCDnN?Y6AZ?X$zml4{!Z z5c@-?t#mzTN3gwi`W_}KH92n22|8z0kY0=L3g5|-ULp34wR?${&%`y=?a*Xf?2__b zWvw;Ex^UiWOG_{GwX(%}N}q!>HU1ngI%Tj|mI}9b$dY%;#e;FC6u!VDWM*kOL($`jcpH-`D@4FhM4PSnrEDu)A)$C>0=$dl| zzDN3hN9bXn7TfB(;>?0noN>@K=L}37YdS;kW6iSFcZIzu_MDt?5G}-^tw;3K18Rk; z@9NW{==%Gj+bH(&b!mu$rM(`m{P&}J$qMg%|=aq zR~Vf!B6AcaTF#|*%%?v{yF-WXN>i`jPUF_;>K8-{66^(hkEK61 zu}4f^Pwxr|RB<27M9Xqh?a!eLbk(;E{#99 zf2G&rewS3-A2ZR>>v#2@GOBU^N(A@2q~iXV3Dxg@@7RLIAKbqZ!Tm0&xIbos`&}A; zaQ{jK_q(Lx{+NkD*N@l_2B)Pg94*}Ml8XCXdL<#ar=}4LT9Du#obOTW%?Z1Dtf!jF zOVGkSHL19NUHKkOYed)&zc0~LwuBb$Yspi&r)EF@Eh566 zx_Y)2DWC913liMVv!CC8aKiqjNDfWqaA@JkKq`(Oe2=!pPTFTflWKz`ffgh<`tUuz z_8sPAe!R)Za-+T3F~c(J_NY_Zn#pN&9Fy0Nz1+&P?KF?i3#~2XEN(d3Xt}J1i54W# zZ`8hnnVd7p8&eGc2~-7+=-tsf?UG&X;E$yoSG-PtOF~IWn2y>XVmk7DAC)U4Kdwjjp}QgwboSGdjgJV?e>$X5x-p zt;aE4Z9=@XI(}~>>uj@L2JfNoQ0`RNc!6{4XqXXS-UBU2;5QPCa@*3MLW`S&PWyOvXN>j3&a(1HYhBQgUhUexI}z6$*wNT3RPCAm{!ozr&8p!a&# z)#opdKWkA=HF+PGB;|g)}+<( zn|}1uek*3QP4uk`G5+FBr|sBCWBs(sCR&id?@)+lGtN8f<{Y745D8Qji*vx*@?aDH zf@ij@cgoydZ>Uy+79{XHlxGRWSnP!Cn@PVQ5~#Y67G^XHOw^b4W| z3H%O)h;ygB)1hW5`UR0d6-EiUFK5*|_WpL)^)MMZ(Sk%^#96s!iJhX;6sj{IfhvqX zGPm`rYBZX_aSe`;FawllFZWDi+sRWo>Rq7)iNJAG_56M8O(B0es-B1hs$#^v6h6OU zknMTx;1W&kyKk2|s=q=D68(~P3(xR#2opxJo_6ZH7ai3nB7v&gySs+37#VD|GhUw%zxbCB=F(+1_u$G0n zuiTO&IHl2fQXXo%Xh9;d;&poGaN~ZLMY?JwNT6!=!%teaS=rbJPv@Lx^qYD|SFHps zNMvgGN?SLkHWLl19W}CsW+p#J0#)Tdz0krN)Z)J6NbhS#qi!`R8lVLU(dR#{@~?xK z_%&6qxhUf(>aUPM)y_))YTZKya-SIQUQBb!kfqco23X*APd&b@<-a(MiSp-Dm=pH8 z)bApJs)6q=X=b5m)E~<|8Xu%G3r)CToRO^rEl6~~aa8-K^hze4eavcZKmEnXD_aQ? zsJfcvs209rh32)A2Mx2h{e}xuwX1x;owok2IiD;T8MVpk?m1Er~IVs6mgJ16^=55s8;^1eJ=4~eW&c((Sk(ah~;*r zjdtz9!>JaI1gdcKBEFnuYdu%mVgw+VFEd*93k_~NQuYQ}tQJD-{kifViMCW}u^*IsJ1Vn83lbPtgm7}Mvh@uKDdHf3sw2a@goj)S;)pZ&-)i>Os$RrF z3lbPtWKX>!iM^$+7jck4RnjSXSh8fn96wsbj0}CTNT-N{79=nd$<2*31nXTk)^Jr{ zf&{82PKg)#kIVqPz9cB)20h+``fjB^Vw-3|A}~gktNKhYQ&67oT;rC31gcJCTN&D< z-ghfW8a2avtx<$Nt7S_~wM4A-VC5#T?z1g+2IJ7$yP9f=Xh8yFmk{0e{%OoD*o2}Q z5~ymkP3Z3EXQ5t8e7<3k(c;lx6xGmz1ja7u=a)_yC;$DZtK0_(R5cm;QA@o#EB9Bq zW8O1{{gs0>qb-eZc1t(LP`M9Ukigg_ zM6t&i%)*UUP~VOOs@j#mr%k!vpX0~q23gFp%l8;6_dyF17`tR0?q~sX(Eb~Sicv_Q z>REwH+Wz%ZIjU7_Qot;j_lu!gB3h6LjDux%7dM~WjbnC^EfEP+)n9N#TUT_2=C#Bp z;%B$*noovmyIJ2|x0W{_O%{xzBPZUll7x-scQt)XAvbBXcl55%f&|7#A@VoL@21u7 z&?iR%RnHpUv|1G(!{6?>M`_$~S1wU>Mhg-cABFg|Ik{V~=6?DGkwDeRdXd)WQ)9T5 zY&;X>zV5$`qBB~M!1yS{=hknX+=muZOGE-yp9kEsdW;y$t$ps7!_NL! z(Gwy`h7hM&`px=w8J*FBL|}C==$brMcUWuvft*)E0##Tkl;?lQ`fkcy+ig|f#n}a% zLkOH{=yGbbUAbC9N7a4Mf&|83A&zgkY(E*J4w+Q2~;&QQ&|(Lf402wV5+!ZYx))VUtRDO5N< zMQ0>Xm3a60@LrF2hoBA#$X{be>`q)bPKto<#-SYRORj6IXqVd ze>|8WLqEIKS8qIs79=nR%hfwG^VyfX2ck7)$XrKj&z<9p%%2)mD?w)S8 zqEiA0RQ0~SA~eC{Z@khef02>K{Ijj-9yf~S(-v=hO}W9jJVGly;S*iQ9VxW1VxKK9 zFL~SQxc=L`>7mL$a7GE|jd+y>&n_ifpWevQrm3d<11(5kW*~R?+dA5~(BZYFM#4y- z>eH=Yz0|`goHI%39ymyMJ&Ac3j^ufJ>U@;?pr{NvL0 zN5?r9Nm^BC>Ea_#{8TbG-Q!Bw8twhX19W%e z`7UkJ!R>UNvdeC5dYK*k$y@y1$hCj|*HHK1RfY6gnAM#A<$*P&TWkItelTCR{c0__+6d;6zVSAao(sbb2zjhf%%FMvmcjm zo6Xrvzc~`9+OzAS<=$w+?P^xCY;L1@VU#VQ1qsYoS2m3?H+%%7Q_t?S1WKU)%#{GXdE8yMYR<#ySQamg*i!fWj|%Q+?A6%we*8U3Tx zctRY@dskg1bamTY=(-X+qv@J`p5N7g-Sylo&MSIXXhDMgpNV?mHQkMSt~;tP zK>}6m%^c77&8+2)P3Aai_em9db%C@wjqDcf`omjv5alfvO`pUt3zoQkGYt ze^H^Fdwt7TM^!)2g2eZkpRA6Z;xaM$Mp5^_o2?yH7exY9Yqos0p8gb%Gs}ol`Q4)b z<#W`$0a}nKG*;Mio7v%BE?T-!YPa#Q7>=5WLjqOF3kBI->pL{ZD#V}d6S}FVZL`(< z2U?K8Sy|~H312!(mv^^S&VU4}u1yKCR~9c5?o~e?&$#S#su*dhS_WE>2%Op2Ss)7%^Ibm;Q4bSRZYE~atY2liyz!h6(#-w-JHcMca+&jo$2S97Nkl-~4 zmUoZO%||*@R*$k(4u`LWs!g4~S;?ly=P^#UnG2jmJr3FGbD#x@CU@Rhjml_DBsy}! z$zdm;F%A-_dO7&5HM3wSk8%F}80p+FG^#+N1qtrKnP~AXnwzX@4@dpxNT7=23b({) z?c=y*-_CGU-3Kj5aJ*t7bL_P4C~FI~T_jM&QI!4T$T~%DxArPuUpf!=RiW`Y zT9D}Tri-;}(Z5XePWjw<@75>(Kmt|mrggD08vk-@&vN9F)8}DJS7l3RL89=zvR0v# z&zVqFHEmdHTCI-jn{lNywo0#Z*F61Z@(;8i!Bsr=kBeKIIX!<$Oa6fbs<2hcnTEDQ zoxW45l7FBD37#ut|7hi`a&o4bNdAEYs<2hc9pCr-?Hsh$Q2am(61>WW{UiNvC!Gdw zPLY2gfhug3a=CTHDQDC4r{o`KLE>PwrPjFZqeqOdx?OY?X3_>Ajmy zg-)qlH5-l=B+}~>EwlJF_KyPTA30sDJmeoppbA^1oF6QH!f2XL75<`FAwl5#sW| zDbA*vz1=R$+UsaRVr0+gR<4kbOsJJk$vaJHOZP+^9B=(YOQqo?R-f-hy<#-T%Tx_D{!4X>UI5P&hr&9 zT{Sj93lbAXbhBlh!H$drGE z)A6Uqu9~|;0#(f}C%57@f6pFuu6SSP(Vf=hgJ?lwN}sdgeT#f$B6xcnC-kR3$On-? z)ywo}!{ZXP5BFAbiFMTcr@S`<=AM zJ$-KPkvSY%kl?kW>>o#4=5g93s!jfZ1gfxA%9G!NOs9G8KgmDPf&{NgX8$NYx2Lmt z={E8YBv6H|Ql6spwy#tC`Duz#XhC9@)7`pU{vrEE=e3iZx@*3Ze;|P>Y?bl^7ctfe z{yjeV2U?JbQ@y;EFa9g`kH15vITb5rCI3JIRoE(JmGja_r|^kF*}r`SLK4qwzbCImvfdvWPCxD6f zJ;xh4*8D-4uh85tB%w&palt>r;;Ze_1$4~ zZq|YBfdr~b^=ha!>iCH7!OytUvwirqBtCZ;_~hi%;(4sGv(hvvn^9u>N~(hBMs(1Jt_Ght|!lm3d|S`DUZw=Q0$o&gC| zCHf;l==J#i`rY;$%Igz0zoec4El7myUmcozTM)0t zvHkT|Gq1kTUp-1qGrVX)BFn@e?P2Iw?inV2O=rx>Q-FE~Bv7^VqtHgC`@(+yUxPZv zm~_RdXFv-QAFJfoZWn#aMDHF$jUq?NQ_p||s;qVSv>tWdu%Ab?U1Z$MRGE4Pv>*|q zRU_^8?~j@Ib;x#O`{p{-Ga!Mgfe{V0l*b=&9IRRBoUx@~9U9%C1&Nf^hifC=MKY1; z^#fyO*M{UDNTBMMl*6_1^CG#mXRj4v?nz#kdIq#0G4{bf;a)je8}`2BUT zR{Ya-RH zQ6nS{t+GG@RqqoP(7INA#~$^3T{|Po{lpZV(Sk(R%uTdGHJ>t(DeEL-ar$iJgGiui zUhc+P%5qQGqgvhj%h)+K7x^Gskl2}SgqE)PZ6;Fxe9*Y?vN)}QL;_XGR}a@7Prk(- zwR81dqt&Dm$+JcMcm>68}o000WNj``Ks@7zlrJb*Ejy-Bds`%!x=^906 zv>?GVzfAOYQ<*3Cn&g8>pelOrHCpsh2iT)7OwM5zJyDWk6k3odvwW9Ub-;F?@OC_* zC%ti>0o<_wTcr>k%Uc2Kc@7aN-6!#+U?m$Uo46M60q*wK`*;v44C| z-_96QKL+^+5~#vfDKpFIlZ;z&kp9_+IAc3mD z)}C~I33JNvoD`$bf&{P2VE>reyo@=heRg+_tgs+~s-1a`XjiW+=ZLf8SVgmY`wXs{ zcSZ{myk`{?J<{dVzkUj{)pM!10|`H|ZmFl&19u~t)_AI(eqdbZg!DnQAW`tapW2cl z|M3Vi>`IWac266 zX|diMVvmaKdfu4W{UKF3(SpRR$6;EJojaM>JNlzBI$IF=AQGr5kTOg=b$(mEYIe-MJb`7|rb$HpA zJ?dQB=4OWXw`t7;T96oU`iXXJ_peN(j6POhT5hSWW|49K3fzq%a4(B*3$E*T>}NEK zj20wtUkh2wFm&T-#ZAytm#bLdGORIcla;z4% z>;0Hmo>?=auii|v$Vi}S_4%jT%>~uDwSV4G$^0~S39S}E3le4YciP&anVCpaqoFw? z(IQ%rf&{8E&VH*kOO%;g`>IZ@%zUp$(W)1;Ad%q3XKhZOhr9}@(8eyN+hG9t2NI~t zJLa?2F4;p`!z4u9<-JTR*Dtiv2`xzccjUV^ed$CdcqcZRMaF%#aEGqIJ+^wkk6~O% zzLI9i(1JwZK3+HH{cg03^k$KfK-HWB_qEyKgSoX=e?HA9IWaN$2U?KeXFHiVvhjeC zYgh^L4Mk#Iy|%Hhz01g~giqI!?mW`Q{s$Ul%k6|ZjP*50RG3iDB} z!W2Kyg2arK-?Ta(9`kyi>)Y~~x04np|3Cs&v;O?5^?Ld!+*`NQHmJ1u_uwStA80|M z?|q@Sv?nnU^0k_|I#+C3>4XHT-gFas!q7>)D(v&o`ew&+J8ZR@3N1)%85yKkIB$h{ z>&UM5Z)+Y-HQrV$wva&8u{=R~y1G`FS5J(dva?y@awAKv3Pa2PL6r80ZF_o~L%;Oa z)Ot81_?lE9?}WZ1x>efSWpmc?K6%tyI;HSjc zKN1!@VRZhGnEV3?RAH+W;%kEVLl;uiOc5QnKLSN z(v*K7!Plh1Rw-v+J9jd-E}yEaRY+(-;&3XV7rQnw)bo#Nt$LXY+MUtCKgcIg71-K? z-}g3CY1s|6`V%cka9m;knA@?x+zF_np=ObhKviVx&)ViU4?@+hw?e$E)z5sHriYhm4RjjPRdf!x2 z*rVG1_0rgXxuUI}MMet}9ZJiyi|V*x-t!;RoJ3~DS$SynClaW-GC5d3(#Q$(R+vsW zna)i7cd(^=5H0@)QQ9LS#}_g8$1SU=Rjf$xHL1Aem-alWetg|5aP@ax<#1?0f;}zN zBRa0AZoaC#RaZWU1gbc$gnAzJ_<3Ek@#uu~GzVIc7_s1s)-Ty3CN?km&1{{s7(JnY z1gbc5VvoA`a~t#g#_seK1X_^bOilBA@R#|W%p$=P4dsJKpz2P6x7xoaGihGLv77&H zUc9)Dd=M>2@EC`Q7~U?lmf9ta_x%W0<9^&N7F(qdt;?n{4nDkZsaa&SAi+;1v40GW z7-f7Pn~(eh2~=UL6e6t8awEt25QsKQn$M7kHH&077x=@6sH50KzYjs2tR-l}Hw7g^}Z7kn*L zVXGA4?SYzR;oq8(f1m{k9*bz6MzAHRoE(pD0-%uneyr~@(;8iQM$-e zZDoS$>>vM>ZDYo+xRd+?2~-8P_EpP%Gw1F-PyT@xB)B%f{xNP_D>LK9|0qTwfvV?? z?`R7n`f6T`idnXWnfKZUL(L+i1qt2>o{4qO@|wRKE@G<4$+bSZJ3fQORds$>xt?V; zdzUV5s-6KYNN{D6zpIQl)0lPll{F*eJ&-^Z&t~yGc$a3{DINE{#vQadXVknE@guzK zRadjfXhDK=R3_%$?q*Cp@j+K>=#fAbkH|F7&vQ1PXwpjMNTA8#dUG^^JEuen1AicX{ziMEl6-3o{7JU{$!RH zB~6vRB7rKNb>g<0Nba{(GfsI^jqcEb1kd&|v8!;989#X~@((0X#WTO$+B3#_Vr)9l zgnSS!Nbo8PCh{e}Ys6U4+Ef*KBv5s^UPG;CrAO@NgA<-MF7)nb7Ll{aXhCA|ujRFd zxt=k>yO`5Xp18j~?v&3}5%#Fu(Z1>7N5geBi;NZ|0{7F8Y*ybW{UMv7d=Lp#aovwS z>gtW&M){BR$p_Jb1lJjvcwT6UQE>PS@`}FzuQ8HM{hNFcEl6-B zor(F|_8WzgUm+hv0##g9XOFTD9WY)Td1t8SSkQvRY-_eQW5NX{PISIxeBO}2R6d9V zs(5aSJu2ST(?;5Q=}i@#(Siieg)tG+xN4ldQ_xh;k|BXAp7~{uT9NXEk*={pK8O}1 zc*O-1?F*hX%6|Qod=Lp#@#+iqs2YFnGIBO*WU3J)T9DusNlZ*{wbdvbvn}}`5~$+! zOzcrDM$I+SkLY5mb^2&Qf>&8F!F%@8F0^=J1fD&Ctx|~8F`nq*ug~ae78xx_a3!5R z>Po8$#_&TW$v==l6}C#b15LHxjL2@C$v@D7M8f9lwc}}yvVT;_FwNN9d>Q!%5~#vf zDMZN%bBs!997AQVXhDMKsn|c-X8+r;KR+b@Kmt|RDuswWYNHW!KEzbnD_W4?*Bl=}) zjq{f(kbj^B30}{{{*nLIY9npm`s5!-pbA^1+*!5MRHOdImgFC3L4w!#v43RzHpW<7 zurv7w5~vDn?TK4AGKTi>r1>nZ}qC{mof2Mj?T!-p5viRyzERBhHQm zDUHNogUqCI78xx_@To*h)cduIKCtrmeX1oQcvM${0z;?;{^X z0#&?zf<4M|HRI6DNQzNtL4wz7FmWzk9phHTSfyw+Kb{OL=P526JL-Z@nFGRv@IX^c5Js*w*OfhyjW zP4~uwE9+g?x0I+)K8O}1c;6Q$rd{2p{}iJw`5+Rg;$35OuU^vPkGT5iH=QU?L<#}D-;A4CFGy!u!7DlA`C)w3U`=ubX~79@DJF%#3L$J5I{J1EZ| zh&uCyd;<6B58UOy+Wj(m)#7Ok^(-=4kiZ@PWljJ4ba^7e2#Qfipo&)~acl2bZGzro z{1QV|Akl&ZulLivk=NXLOZ6KSFOYvAfht}Dt9#?9aVLA~$6~&u7=;!jc+D*nXBW5B zJM>9ps@1qipo(|B)xB}l#`4>>{QsmQ|3C{8ylWv7Zl*Dz%cd5g91aOo@h(T)+S@$O zX4h??(>Mw(Nbs&oOk7?#(Vm{72KfgPs5-KsQ+SP2f?NB7!k_F0+v|~kpaltDPtP%` z;Ixd+%DJt`KafBbudU~Z6MCVkb7Xp3icx4mf}d7lB8EBKnVz`|`3DlH;wQK`;(X4q z)OlB?Gv#n-L4uzcV}j2TqCGkAgfu*BjaRqoUY#L*_co!~AEYx>odGRK@TzhqZf&(n z{WWO}`3DlH;uYrH+I!}nYvqc*g5n2Skl=l!nRpX7g{>96O#Xocs(6o1ZtZQX$@ZT$ zUr_u&3lh9<7!&!=oU}7vOF;gC1gdxsF^&c^hbML7wN7QKF%DXg5PefxBE}~sj{c)N z4+`cZ|3Cs&{PYONj|~-jIkQF;q4*JCf!F1yRhVczcbc0&~CdSV=>_lr;gZu+u3swAlB)4|A@PAIF+||iH(1HX%am>Wa4qu$; z4{DQtAc3m7SteKq2VddVKJr3b_xF3hQv5&*68x+_6MS+OonD7$4&v#B*eZqKr#Z+! z(1HX%v%&sxwDLYHU$EyNNT3Q^r4XZ=mbGsTSVsPV79@DrTlSCbSLfL+=6LY~2~-8N zO3`ETzxK1lPbhw%1qt4jkMpai5viS(kK&$yNEa+}IDl3q378xx_9I3q1I#XpQ6MV89ow|T$i{dGzd~yMM)LQQh1w%cHj20w# z=V>0}+?g@Wo-)JB;gCQT?^MY-T#G5^?cE*blMkW=3Eml#iE1%YIU7d=my0ov>?IHL^2Vp!4PNa%n% zCytq@e0-Pl=tC;wxSQWnOGVtrCW1PUW!pjpo({KVUNnxE4$mfZw?ycpaluu zHHL|@T?)IIV&@_sL;_XW*Y2^>++EKel{S~@?k<~=d=M>2@cv#*@HvWf))t=Di|77g zs}$lv%G&m~*GUaEi;NZ|c<)#CkM{lc*sFUErW_6lRAH->efyK>&fVuT$v@D7#N>26 ztv}~JV*l7yM|aXy-B1331gfxA%Fl7Xi<9EwIr0y*Ai+-@vwvKiKHHfw{1esTkU$l- zN+Hgy+v>!Ub08{*LkkkTuLb)@tXT3yoo5NjKafBbwn`xe$9m<&{F;dT11(7Kt}*N% z30lN+ zb3d&8iDDEIs46t@x^*+jXpT6sS~qdyWDYUaEHYY<;IqD&C^klS^WNBNshNgRTY_zM zuB93yZ=Vrlm#(SP`puo`y#ISuoU+~Ie*Iy;+G?f&ElA8r8)WBOuJKyVO_2@Uj&rWi zS~Vn4m3(y&-P^1Cbl=?8U0J&ot>r`u60Z&jJ9}o0S1!j5>g;Zb_t;W14M?CWWp(c! zUft)P+P&RZZM)fOHXJQT)Sn{kbLT>N<#Mrl{oR%JTT9I}Ac3l1QhN8`wVZbbyJyGu zwN;jZ79^?;mQRxJ4h{F#0Zi;S)GgLPo-cd4eE@-~Y%#ohctoeB_1#(}&e>{=gTDdp zvWVZC+{L_SYxnPaahy(aE)^|E;C_ulgg5!!Em`b8TYbAopbEb?A>0=|+-b>@(Moc( zAc4DK3h`xLUw7@)SGHQufCQ@Wdz1U`#vA0Go*&E6_ubdgf<%j%->uEFM)S9OrSK4U zXR-^ndLkDIRN*%*MD~Asx}~noby~{b19#S(JK%%0U5{g_-vD>RlqZ?B=;N07X{_7a~ zYVsg50|`{&w;;rgYwg|6X)Za_x3$-2?7MFTy=q187k4M+oqR2? zwU52k(e3v6u=9NXeH|@G;J%~s)KI;hoAbL%PY)o0s-r7kTCIOBX?b3oJZ}g0_ZrKn zU7-aD+;>#&Twne-_opF~=qU&!P_=l|N2}(eIF{G@WUkx7eH*7aJ!yd!B+ysniEN4M zxJ|Q`pr<*IK-HS3->t4=Eb39^$g9JzZt;d+X~i#EkU(!1B1a+3otrhxR(pRUfvWr2 zgY8N=3|_hXutX6zX7M7nns-JE64>XtX!oRtGZix=I|eWb0lylSJ}fgZsexUKj(*b zg(_^JLUg&`$o=Kk4tl~3ElA*wv_gd5YT>@RaqI{GKoxqLJlkn?q@1Eg~OmvLe6%wf8UBN9c zBimr=ZuxWTsqLZ#3EVAM?#%r>zuT+HblOK42~-8?Z>;N~r7ds9I20f{V1gctp`C|QYAfDyT{G8t(&%OCPo}=bD(Sii-7A(ZJT2Gyx z;xw&RM*>xAo&?zke|LFBe1nb`ony^L(~5YsAc4CD%T>i+mpOCqXQfreNT7<(=jD~l zpUpAOhlJBCwKfVZNCfUY+~Y(#XTdLL!Y|5kEfT20Q|IOS-4jP_`nr?#3iRk%rBv6IDggk#Rw7%P+Z5&tSS72d59^=q{OGuz9u=i;rPf|V; zn$)5v)_;j^?~Yr9R;%+#%5;t2x)5fv49=vmwU%))@b^FhcW;)F^TsIW;F8?5S{+{t zRoHrjh~Hz0Gb+}kAKDcXxO=k@&-S@^jB0{2U3~y;(-Jep%c?OJ@Gim!JxJCE4#z&f$Ka zx`p<2Mhgae7ycQt`D=h0#v#t^T~IyI@zI zAL1YqxZkrpg|ApKchZo;ZloMX;cKA^qqY!*y2WsZv~1+IThm^Dba$9F&xj=NJegpE zWwy9N*E~Sd zzALog>*DU#LQMT9joWQVA&Tcnpo%L<9MAK8%;ZM)%|g2rpalusrCXj$HYu%}<5*JK zYZ3`m@wuiP&#T1C;3hp9-Bs(U(Sii-HZJ4&_N4Bo+K(xoBY`SDIgR7_rRquC(=AVu z526JL+%;W(j+D{d9a}e$pCf@PJ`057d54={owygKQeT1=Byjh4AxaFs=#(zfhISA@ z0#$s{T5~%vz;)B(owQhMU2UgA) z>ilziJN4~oLE`P3?^fTg37GiwD4EmwY6V-Z7exY9jpux^>O3hx`=!V;4&R)xtH*k3 zbzU$;KHc~~3lilw3%g>;giNf?klej{wYr=AWP2UGXnVXxR-6sqj$+vI<+)@{)4Kce zS8+eglLUAX5;Myzwz`}<&at-J=S=RXH03A@M*>yYOUT;N#+>fV7-d{lzd{QVJbT9X z;CVGy&8s1Ss=(f7(DftsgTZO-cQb~VId^}w;&n9WJE_+2jg@0&Bf7?KUDlA#By^hQ zA7rcb?Px&)cbgX?XVpGVo<()39Ot--FUI->;%uJ3c7n6q?Z_vDr&KlF*H!roPS zRLl78xel3K^^6HxkigyMg?RNxVmJM$LKM%DKov#_S<86#lbh$U@k9JTf@iQfM*TJO zC%4$wDnG<1RAICe;^wjMPUSrHe~5!f;QsXT>E$NhoN^VLx-n!t$Jas?Ms4|_zs0gl;)=Mrbs*Y;89t#guVHZNYJf|^(NiF+?QNP^vao#?l-r+%uA3! zRp2LA=Tz4mJlt+QO`bZv|DyFS&JyZB_?&9G#+~xLv#`%5K5WBT*wpJIfxChWk!MbI z=jEgVjv5c*YoQ8v$`|6)xlT^V%ikRJyc$}Nz+J(Gh*oQ^^Lp-l>PwJ774DQT>xl=K zIC_kKs4qba61Xe45c=ZX&dme2sV_kSRk%~W9OE?D?fg9GJM|@KL4s!*IWHNO;h6JZ zm!z($St5Zd+$mpH)e`P=UOdW7yIG+H3EUN2wyQ@+ojU7_QD1@ts(5V+XMM{ihdHZH zl%>7|ElA+5;IcAND$I%2qc-&=NT3RL%9l?_k6-EZsojjm253P7cLf(BW#dK8rYjw& zFF^uTxKq9mS)CEi#_(>`m!Jg++(%sQ0daq*vnpR7_onPikU&-74*cnhth4{!HiR+& z+z&Z@f4L8NL2uV&+*w(Oc9&k;B@PUxIs;mec(i16_^XXF$D$n_dPk&i;*A*S);WA% zM*>y&4uvR^rG&Go*Fg8I-Cjov61{@XhR&&E60{(}>kc@lUizq(Gy1JfeF+k%;x!1I=`VOz z)7jhL8ucY;L4sHHFwu8aC+E2p-Bqb377ksL2=kMN|`Vu5ig*%$d+EO~9b?V-q`VzDtvE@zN(2~dfvj^U<@2yR(GsNvA z=M9iRRp3tPxi*y2r`H+k4&K#XM+*`UZp97Fw%gy0ou5Q<;YlR&XMXyKt^?2dec`^+ zzm6N^s##04Ac6N2Vrj>Nx>?%WRUQdc@pB>k?N0uZTo?1bZx<~{;P)nXm9O(9v{2g4 zw7)14sKWD-<(V&&%Gjk({dkfx68QTIktNM!`=Hr?DiioxsKRrf<*fdbC$|32ue4V& zT9CkYEVJ-GgPo_xOS@{;5(!lCdU5vJ$P(F|`CIan*P;ap^kBKyeZ8#Crxq!xXFvi~ zcn-I$Y{w|=j2QnD^*#X>@biFvMeN9%(+PflmnsuTpo-UiaW85Q&F{4T=MeRxXh8z| zMY5yx3Fbq4j+NT3SOMVEEzp}|hF<=#H2Xh8z|c{v;YVX>WRKrH99j5tW3Dr>DN z)`j!8DPGCe{&N$1#N_pK@;h3PIFxRxwXlLul)jb4FcNq@96zaLtC=c1F`J*w;vR1D zn#xAR*p}48p#=#%>p-4g8&TNEex*J2a7dsE&-a$qk9ZA?<>$TARnUS2KkdjB$hNaJ z#gC@D2iekLCaEF`_l?r2pr#NhLJwV2so^F4Y-EHI{I>OtRC00Aoe-h?n_O)*Ya z>+Lo^Cih5zb2IRDuMUr{ZOQ6?yV<7&}yFagab2e$#SXn|`g8vGZBG%A6r4 zui3WM&PHvkEDX1*MWbt8XKj1c!H7hMt@0n!IBGnI79{Yj3z_w0NM^?<=k36c1giL1 z2ivQ1hIBe%eLB9JdIq#0!A}n{vCmy^-QDM%f`J687PK_OCe-y$!6;&^4ejv!74>jv zK?2XZkR$qoGAWIgn0iqpP{q&6+1@O2#+pO)p&{w0r$!4Bc-Dmw1@v&eV(h}MTKj%n^C{-Y+;!=VKU-XVdB@=Nv@12VRv91aOop*PFt z&p+NY4rXsbIUHJ$z_Tud`1JgR@msW(|-=55sIhyDr)JRL*s1KIOQ z*olxU_T$MzOn!EW{Ena0qicTNh<%Ws?W2=u(1HY>bs-NE9A|1*I(aA2Ab~18|3!#n zO=Ie*J9$2c79{Yj3n5Z1ZmUP8zeE`T5~#xSUxc_;KTQAJ?HTzXT9ClAF66AtS78(# z7oSd|K>}5H{)-UFDi$;jj!Qv4h!!O9tP43m7_XU8>#8@7LIPEI{)=4Q)_AkTj4&*Rt9EAj`cuxiPsOok08iTU_Og@MfB=D>YA#Te(QmQVfLOzHD zs_^_5`7A)#2V>yQN|c481qnRsLe8IWh-prhE4{r{#s52_232_ei>$*XNN!#zSCM=W zElA+$7(!&2pT?|Jtg@@ty&{3Cz;k8p$^EGt1?6*_%UK!R<-ft$UE2GW+bJUBc>zMa zOHteuO^Ud4W#mK)5?bq>+Ogkuay)-;6)?}=F5&(qSFs|2Dtw1Ri+S#=(A&uH8* z1@$FpL4x-U<9OaEQ?S`Ier6h_B7rJAr$hFl1rnL7|I0vq30jay*=4sjz03~oeX`jZ z%$RGkQD1@ts_>i+Iaa%$&z$^E2I@=Df<*lVN3?ZCS8zNZ_`H<)tDTYh5+qQC=X40M z^XCfY)ix=pFF^|uW6NFChQ*u8W1R70tD5B}rgWdl>IV|23OxVgeBxT>xoAmTwJsbj zNc72mQLFrM3VSW@WkDw*@NN_|w!Ge_v^IOoC%VR#FXwAdcGk0XN$l*GK8O}1@LUif zRyDY!r#aP+d=Lp#VapeyY=b05E^8Y3AX<>Xb3x?OP7kUZzaDYO2a!M(wtOMh_8Vs0 zE)qfU94$!TxgbL9Ic*ux7PKIN=Yj}vr%pmM)1+h+&yheCwtRW^a>fj1f!K-32hoBA zo(m$x_bmC%o!yd?4{K6p(h|8L<$?+&C`Q|sV<5Hs(9~D_NXC6dYL`%&34q>1n*o;mj3bH zY6bquMAy8NFZ=oLG5;`QJlg1}eFxEk1n*SJM5;aQ%||nL(X$yypo(`u<^HN>hvsI> z(r0MxIa-jwb5rEA;S*|`&G%fO_3cQYYFy8|T0~HP?svZruV8BD9?*Jfv><`!zsU8w zFN>S|=lx6T`j9}?z;~B4v(Pk-A9rHpG7H~&Noxnuf&`vpBP(~8lACMJ{7dVvkU$mh zzR5l~_-jnF(%46i+Vc!8NZ@%qLcBlxz*v>@0{J--sNx+AIiBw-b=;_v;4JkeXhDMa zbYo(`mK8?9(c36zKmt{~R~+XhA=Snjm+r2mJ`pWQ;Q2^Gtlv`JX!?0L^}9%*ig)Yc z{3`F8;}f#+4pdg8k-=ER9%&X>dOb@ZZxWu9rvTa_mt#Fj5a#^6q7j*my2^>RHmT97dQ zexiL|_$&MQ>`d*<&g(8a>iIz=P=&pO5J4APn=}5pPtU8N1qt3?nD4zyHu1gfz0 z$ho_bO^s6zy8Y0ukl!q-9-_DVwhy)L79tLssE zJ_;>J;5kNeJ$3CO=C@2|f9MlYg}tjB-7PI+&TF~g9kc8kYUsZL@?$dAn z-=33mdb!W9Yo@1eRdv;^x+LA1v&q_aRADcnC|!C7khsPB#NIx%AR*8AmVMOO-+jrL z=s%P7QK-V+j_tLqIE0kmJug{5hy-RnVl6|Zk;K;Z5929&KgWBa3VUru$v-xftl9J> zjK?jp-M#9}@okIoNQamgirV^}>m zbtMl<1&QArEl6O#Dz@6^-GaQ(M~Hfb1geG?`QluWvzYA9tM{r)+8>@L>MmN4z`R?E zQmdAY*xt+${W%h-a?&_wX1|uQKYy^yn;aOiQurWRkih(5iqiOYCenTQd=VRkghe&# zwX;#P39@&7+WDsz5xhjSB??%Oz&vPd#w*JW?d#!5;{5{&RLS$nWt*5P{D8LTukoTy zL<88X|A!L!{Ufhue3v%tPX{d#MLh^Ln4A&X}sPyZIz_|)0Dfq7oIh^Iyi5}0>Q zQ9S&*XzR8XNcNkf3Tuy|oZdBCYcaljvU-IC=3QeRHQl9coYE;--LLe<#QrF>AR)7E$o=R3sT+|ZrQ0NH6H$e&E1T=P+lFlISvpy}iv;Ff zQ zvj&bO{aOtO2p#oi1gP=z_;SQP7(wOX1PN5!5Wv><^Qwb=fT zj5oDMLm!I0mPnuqbH=fAKYD%88uWMR{A_i!Ac6U@*zZv`8)-UcgOQ(y6LFO!xrSAVAWUj4@ z;Vnq<>m8ktIZF_jMGJGrv01hD?a9OVX)0u|6Zz+m!2DP&-}a5(Wai#;DrBz{1gfO} z%gkAIZv>KS+Y4%ZuRdCk!2DQj-^4$``>C#BUI!0anOQ< zd;@Tr<97LOpz(JDBv56|MK`c|KQj8^1C5UWFf)*Rqjz#om2(5K3^~uB!90VoAR*@* z1kHN2%L7Tl3nw%lPmT9N6@EfC%ef<%>?*ZK zj9YqJg|S%nQ7g~^z;}xfQ zmW6Mn2Bc-TK^kvMkU$mY_EMChPa2czm6vM#{42B|A?E{}=J`Gg540uT;kz{6mLP#D zIh)`#PaR4(yDf>EepzH0Lkkje23itd(gcud>7R(U1PN5h**595?^3rXX`+8>{QVp) zNXXRzNyv2r!sDrtK$V=ilRoI(sy&%?G(8#5;;GSsgj~Cm#9vn$kfHqw6EBw8K}HS; zi(L5=*K*xZek#7A=r=bH;qlaHK?2KT`*AimCO^k}5HP-%=9Z zQlkY4d~WPbcw!UMU`CwAcitm`Dmi~8Ysu;K%}BN{5gI=w4J}CE@6YDQ8rLNw#vj*s zuZ9GwL;HAc6jZ z%{g$w!FTGR<^LdL|IsO~pw=xZ&q*FnjRf`v-`Ay9zf?JVlE;y<+%-L~sy$XMc6D{J znF+8UF>gs~m7F{yiF{>?k-1Yc6JD?6`jDtUa?MlJSGj^I>+UP93~|KfC%lD23lf<1 zPf@gc>wz~pGdqh?tN5_^FK8O}1FfSpStzGCOcbXRyC&VIwD)fIg z4_CoKf@_v1eEkD0NXUpJ*h@LbHYy%L<qmVoS7^sFLwavK5t)PK3u(qXh{W^(4y} zp_e6vW;(^QLIPFz+}J$zY#TXqvj*wN;;GSsgp9?KWyq*70#RY&^P&o$w4!{|uBz`g zq*r-7waldKix3v-%2DBlNF9#4%HBrxkE%Q)pTUYnP6Rpnlb1gc~Pa;Mpr zT`vN##;uoAc0vQ*;`Sr(;6w~r}5SY35&{{TXLEsvWM9twKNk)YkUkR=az&8 z3C#M)%JBH2ZFR2Icq@tos^kidY}+H#Dx~I|XtdELP_gWqj`8*ThV>l#Gg)NbyTwb4(M4ZVlS~#>Ifmt6F zWm=bft$VC zy{@&&ZO;?PV;ArYs`eIC?mh5(eCHkDsr--1qsah$Yz8W_tu_W z_SCo!B7rJ7zbk$4jL$S}`w1d^5G_bx)<<@#W5RCja?mv4gGitXGoiBG167V`qZe+_ z_$UJ{NXQjl>9spI-PMZqW-*G)2a!M(WHuR-5$Tt_|swkNoKGCAHv=pNZv>+k(9>`I~nx>DmxGw>O zpV5c}s^mTd*>mp9c~*;A-beT#T9Cjzk!&n#?sg)u+ezFDRn`ovY0`JoJ`Wx%Mj4pz zPVOZVy`|i5BtKOtwi79T_tAu(3XB#cf)*rXw2&mu z-=C~Kd$m`zB}kwOGgh*5qdHI5s(M`&{W)5YkP(}*E!kdTl@|Z;t7uD*Kow@JWaHgi zOSPBfG7{dFpaqG+-T}@DEn{VWJ~ncL_UJ|t(Uu^AD$H1^DA`^v(cZ7EDDsk_1qrzW zL$*HN3zlm=Pt+D|2@SMxkdV7JWm^)MP($Z^lNxjowGQEEMf7~XhA~maaYY%nLMdysvGNV6uAL6_1xU>xDAX<=+I~Sx6rh7VB zOZP4%;r%%hsKT1h)(5YS)aG~g6h4R+Brrp!qI`NgS(_19O86iWsKT1hcK2uKrxjXP zMfB%rL1N=K#W}U$Pw9h^{rYHK&ovPFosmEl)_g_r-{jER+-fa+5G_bxhDc z$u8dlTBGq-M4N~fB;?)`Ni10MQ*E(wxoCHhK$YCnBHQ-Gx#QINZH9}s9W6*;#$z_? zJZ7;P7@JY!@zhA5O2$)*-bYbhd}yj}JiJGRcxqum0y8%=B0P`r>DUDF{bD~Ay(q>! z`APU7)_g??G|!D9{CsM(AR*6?l7620+fKdy=!wE>kw6u;5{eSPucPkc8!ATnXhA}r zawW@nM@NTkUJxpB@F0OIYwI(tU=3YG`)kAe+#rrv0kdV8YWiHcUyB?@5mSq+FITENsZ)SVq)@@Kv&n+PO zbF?6V8GYG)=L~byRVREze~tvIuvKEw31j|t#)X=>e$j#iX7puy!_eYZFn0 ztt&gbt+zvW?M&Y8A|cP=k!|~tq}BSx=4LKzyceplmtZk>{nHsCTl(Yk5AT?9cZ!`P*1uuaC%ij}|1X8HjHTx?(K*ryeCl#wBJ>ZzND9PbraYNy~G!9C6;+MO%UvBrqem zqKtbr!@1&mg6PkYK$Se{LFTWmd$hRPB9ocl87)X)W^+Yp(W9vPKI3N5?jnJzfa5zH zxodi;=8DO{NA=Ze4W^6!94$y-hIZC-lHblT2l8qBd}<_6HF@kM$I31qs<~=;a?>^E zy~5!tkEccp5^{gNB;J;eFnojilM*bR8ofxK-YR?$YyQ7y$`UwJR(K~8@_boAE6Upa z2aR=Y2Me#od!Y(j33i&*yDi4b+{47|Ia-jAC*aC5?vGz!>}xra@OWw@P-Sg>j_;o0 zjLm*W<>yoP-?r0HKhAuLKD)X(Mk=Yr^TDUi)(ytbcaHp6K;!3AqXh}fK&~i-%3N}; z`ZgokZ;mRgJ&N*ovvSVuRn6SwXh8xqkh9)k;v?TtX F90^pR7qEA=4-doq7bf=) zBrpTHqTJokP#?X@Gno&f3cZ<~v+Z+S-&(}%&(VT}JOxh9k$rjmLvMH4MtIy35~#vf ziJd_6#ctg5uOZ&g(SihKAZMec@&U%3@eRcs84{?%)|K^x?`InmCN~v%EzyDmW*}FT z=IJ*XUQ632YuizUy@aAfP-Yew8xl)`-CE5>px|q1e?CI=Nndgyd zeEl3PNMNRD773VCM{nA}>_3n|6=qLo@uE}L=pL)ri#`f1NMNRDMOpOrwH{P8QnV#V zph}*rDBrfvISU#Kp1u-&En1L}XDLeJ(ZFU#jmUI_=b}RbRhT`U<(pVO${;Hv-9-RtTpC_6&3FWNT3R{r?WGJN}e#jOe`VV60{(JnWEWVnIm_M!u5PaTY?0t zFnhY9oGARs7+BFqjN#CN1ZIj>lzRu$(l&qB6m1C-sFG*h%a$SgtX%Z$+p3~1K?@R? zDVm)X*3z406Rcs*w?l?^RLP7F(rZ^m0#*14*|U05 zhd%7iY6**{Mhg-$YnLpevzb#*%vmCVD(g32eZHW+_~a>-$5Xes*(hw}@-JeZA)!f& zuv?2hi)+ks%|;nhr|Jh*Wz~2*HCm96r-;gVhK=W9^;z4^xg{h}B~K@n^H)tr6fyEU z=8LujEl9{ys3kEmYj>mm(-WdCK>}5n<(iEdPRugu7QZCg60{&8&!m@aiE(m|vEjly zjjtOZfhx>$%}$3|e%ZM5I6=e#paqHS{SSq`OH1XrWLr`&T^)LGZW_^+palt;AyE>|ayO@o-=`LB2@^XhA~e&Xr!fC4LaCz3rsN z&!?6-YenfYx3Eyje7Ta4xocGZZXom32v3!HY=qy*95d1fZ^n!>(zm%T;^EMOgv?ze zJu0BkGGl&$)WQdmK$XmCBZ(c`FB#`6WPZp%RtNsa`nWOh$U?406H zcdk634Pxs!XhA||kahc@y*;ho<&4!4p>QOAA8c2=fcFE2DBi7by`vCwdh4> zO}H+65D8SFudw`4W)5i$a!3pRK*H)DJWuuD{P#4zevbD-mDLAjb}p6Ae#l%~!lRPR z9A3hU&{tT_mo<}(mv`3-k3tI)GN+>Sk45uV8`YoPRC$Cc5~xC7VWaT&;l@E=+0#)cMiV_{@M?Gha79NEbBxJT` z=^tgho6^2{=LwHO0#)cMEIZeZ09va0EU`-nEl9|W;L<-T7wbmT3|wvQ5^9tXcEPA2 zN=Fs?3R|048bt5^wOHfPZD>J4W|x|RC!RoGv#yZ~478mC`p6)|1|W~R_rrb{h6O6D?k@Oet~ z6?PipzG=oPudc$Q(1L`_mn!#v#2#61{JOkK<@wc+Ko$B5`&2D%8~wi@7CT1Jf`rWb zEBCQPUjJI`yF&t1=qoJWc5D`U>~x~o`GOWCWY%%Hi>^WaytG45E)lbh1gg+i zSpKM$m1tzWT*9N!Vj;}z@(yzsU66MTdZcny;ZaD)%;rLczQRrguHJ+eYhO`#6k3pw zx#=C|F1lZbThYQ7n+uOZ0#)cMY%TR?cUr1XZP7=e1&M}j{|Q^u$tCyjCOZ1i$$fi@ zJ-kSu3Vns0$`Y5y@(f8f2ur--nau4tJ(!=P2&>^CaLIPFjE9}&|tz+of zKJA1@p#_Pv7k`BXB%G9c_2d1=(CTl8YW(DSBv4hBomzimdTQx|4}3!C(VTZwzQ?59 z0!6=d%OO5*lZhXexXVEl9*h zrqoLnCDI40`F%8gL@W?H!;nA~dKa5L&*w=So}Vpz5G_c&DVb7lSW1&Vm@i8K+A3$5 z%6GUSfhzPawm+(&4=p@zx5{I-(SpR0B`I{@ma6o@y%QbuR>E^t?4zHl=qtPEqI6WD zcd=dZ?V8h5eJ`qf-vnBaSW+N`USYFS`ryx*ZE57z6v79QKoxoyTNxeRn@*e>CHB#y z1&M@nieA#&DSdF@;QsVzjx53lkw6uCm!kajb2#0m#j1RFCR&idI?YaRT{Vh!9hgh( zeMJIQ=v|63B=ZCsu{xc`cT}MT39EnHC^UhddQnQ_JF1XC75by1tfvJH|1n=2*O*6P zE_KYYj=sW9Jem53;a@*e>>or665sQu(wSc<=1!!|8Mhd#vM&;Q6p=s``U=}En|R-N zKeeXVO^y~M>U8lCWtcmWI?YWmQa5?xD)beWwP(*rx-;85C-*3{AW=7uS%!Je#Ejo#X!F2e zmG34;0#)cMic(Syp^a&hlaCY8f&@G3MLa7r4*6T5P`Yc*XqE3oLIPFTU$KbaBtJT2 zb`cuYrmgyHrcFP7_k*KAl`YOz(`O z+S;8)Hoft^Xh-N@o1Gg~oBp{*jALlMEzZC$Hr;o_dq*?hEl!pv&Q?cXR5*k#KJY@# zQo%=0*q`L+JYtKJU$@_!MwDC7HY_r{E8U&;r-l|zy9s{X&O6bObqgof zMi$Xm6>3H=-OEF`<<`XnN4^Q0L>WU4Cpa>U+TBlZ`pO1Ic(!Otk6tUHUwNOGyk<|7tBwrb z*X_#M^uWV!FHn8bGFTZv~x82OX$F8r#>5F3T!#ed@t)T^p=ao$Q zSqvv?d>KKj-=3!%feS4Js(M$o>7P2iaompJMC}yg=**5K^oTwkG_)X5vy@pz%F4W! z zd%grMNN_*rHFSAAC%(7LLoYw-udi}8BaVMeONB`romk%0cQ(C9`L~Yvy_~4M>!EQn ze3tIK+m{?|Zx{D!QDCF9MSb&nez}d#4$bX)s@-oL!)tQlSpUVw4trW%DLaxppK8|+ z{PWuJ?Z*b^#bYMX{O=9UjC0KE%kkW!^5^YhbRW4`_iH?spsKWP*GD{g>*yA@!I|!~ zNkrY_#He&tjI~W3>d*feN6>3sa^5JFG(fZ^`8&OL)b-vd+LCQqSj(AzqqFumyS{a2 zjCdmKd$dlg2e#Q|1lAu)(8BNQCir#g!_kgSFZib_Rw1n(zh|~lztN~alhZ&+B ziH|t3kkybTzbn!j5x(M69Zm7k;V?EjOXT*^TORr->Jle-Z(!Dve_HnrYgD8Po%y7y zAl#P!C20D1#}H9>Q$#4bjfPS`LlM2ff-^~?jpFxp_Y9Fg?0S}M=D)K{X1g}&6(@zz zo@G|BvHO1(B&_`hZx4C9$lF9DP?hl5uAf@sF5^P0@w9O|%~(64f{HEY$|^Sf$bsnp zqZOTXc{JTRE7)kX^Qfg|Kmz+jcAD6Vz>mu@=nSudRau7yC=eKuOERz2Erj=e^*tP9nH zXwa}G#-X=|HMAgsza~37dUkI*efE0e+|oZS1gb^_+4Sqx-aAHb;$>*tdsC!Zd zAc0R^QQkJ~NWW&8X{7!gZ6Q$gFw~}RpYzVqF&lrnL=T`^&;jH3#xojPkie&|C_N{) zrg>hxHZC7OXdzHFe7Q|87xclQE#qalGPR<652vE8Uz0VoAYuJILY;MK$^dPw`FN!L5-Hq+QCAg>cBTPM%~WF z*JA8b=GrX1_g_&)g#vv=|8aZWdqtEZxmt%%y>#pm0s$Mp{e)lJ6 z;k|*I!2XeCKJm60kKSxGva}g&Ay9>*0YwR}byrU_a*FXK&nSWxBzSrM^_+?AAL_Tu z`x+0)I17O)91XCOBU@zEOLVVp+&Vm-paltjJ^j>M$Nc-ech1|C5f?KUQR5~iBit%Z zxZg`y?tv!{!-B#*=(Iio;_0Ti_Q6qdqWN^)Pr9UskA5~b*0HuTACZ+=b4pLJe=xST z=|RxK@9QS;sk4z~Qa&T!_0%-_QacNQs>QeLdgq`xIZnKv$D79OTBJuet8W>-;<(g0 zvYgYQ9Nk^Ju<__;O@bCA+MTxPmqVi+L%g`37kf~Qu2?+F$lRcYg+SHmk2d|U74IA& zVqCJQW*M6P^a-PUiP8iuNMyWf(+8Y??`S=omr-J8A^LRuM;&~D3yC*X(5|@#n1&L}eYQ@wV&Ldc`|> z|HFxSsXghL;Of-3YlMatBqB4~^};z5WLxrm-!Eg1tqEPV_lSi+mD<{_ryH3l`;W?H z5{%&D9ca!klQgs-QHhQEM@1#dIe>qBFBluP^`&788(IideO+YNk3RY&W)N7tYSMzv zk13+Bd6tvl`!crk_=dzH0V}qmO;=pk$F=q(Xh8zoe0FmEQ+2Y;h}V=oJVsx0el zdiu>Vjs>&%)AjhLIlb_1xzVa?N`e+7u+3*D2rT!bw=#trKQeyRkU-UeJ?#DJc&z*d zYaVDoJMQ~zOc-=cLkkkv<}1qJA`V*fuN<^+mtz(JRR^!xbX%{F4(~<0|M*_K2CWiT zoSsZIT|)~J*ygjfiBhHL)Gof%nXa9MKvgaFp15anf|x;4lsA_O(*jle=*$CmRkR>s z?G4hf-k*;G?ywO65~%w7w@r7RbN3&Q*t>_)rgzx4$1DyK-e2*38CwbV9<{zEJ?zy< z-+sQ5-<)*d!TcBdl!+&>+i75Q630#(>buq;Z8 zD$-X0`Ke!~NDVDWVC`WeN5F9lfhuez*tt=Q^3mfzYthborfFzF0_y^M zOTC+huB+6BHce_}Ay9?w3OiwgjYIi(l#fNxf`qkR-OXB5UlLG{R!%4;dQSI@Anym= z@3Pj}!DFmWMX#$#9TzGQv><_R#cb|%$aB5t5p9HnPRFH?B8j zxnE$e2Z^{DcAYGWacr)@Kh?ya#6opLx8DCQo`BPZy@9SW3xO*B3%cjX6=iAEyRiM22h!Xb&xjfN(?>r!)(kag=-spR_kP>;)pI||Iph|7 z%ISmt>_?YH-Ph2<@9QRT=3Y_OB;C}{rSC~sg~nJ2RN*I7lyLSg=)I;BEgR)Q(1HXn z@4r=m>37HK>qobx`G#h)5U8?#^AEQV8vd2j>aU}R5S*LD8BeU0in6-M1;erQx?b+j zAj>Q#64rUq!+#z%mTYcg9QW;SAy9?2lD(y7xnKlr*s6Ca} z-8r}R8+piGV>M}SAy9?2l8tv4oHQ;T@}Lio`w_GtQKYY3-&H40j;Z55uQ#UO&QEhi z`&tN8VXb5*F1BZ@uPz(S$xcc`3levx+4Xu)8~Ovq%TYJ++-N7mdH0##TS*s6ZY ziN?3-{xs$D-x^wwupP4NpC2U3Ihpkn${Vp`d(zQM9$N@hVV!2V2fF7rDo-6myY|~} zsk=xVkG1QI3MR?*kBTSe>DO-$rT+G<76MhgCb~V1MOkzzq5I|>NmGnnZ1KVWCEip> za&$byM}3J~>gd(7OrQtbloy11^^M=xt-?7{wyK}ui2f?wSh_GYKtl@>SRPw_ombuH zIDaJV__UjaKvjkHc0I$mPh#DWjjx)uH;PsqM5C{7(9nVeJ~!5X%wAy}&(MSVwWbyV zRh#?S^=Fq8~k&77bAFyz%Gy+BC6mT7m?s`q#4S-Ge{M z_rW}y&Ks-CRAP}xg$P=ZzthzwCzFAfp9!wx;ZtW>Ne*YH2mjiw&pXu8@_QhGGcPQ= zxgVd88r?m* z(TD+iECi~sbybuCId>XA!u!)4KZjddQ6#Xwu~TT*4L7{&jG(vj`dSE7VK2enao7qO zUn%3OWN1M`vD96@3ddLD*0Gg1Bv55tyKCyvkotM%BM%0a(JpSX>F3_Wxr#O1;vBw; z&1P?lb8YFc#krA1TZbf+w_)w z5?r&UZDEmCc0FWrqAM4RhGB0LZ#4R|SQ%3O)_xW5i{;5#ZkIW;{gv&I4y|6Fj2l>0 z#rtA;R$@o~v~=x*^y=ICtQ9p^^<8{bpQxf$b0zp}bS}+l*9W9|<0{*iw{RYtmK$#) zJ=AhDN4UqLF1}9wV4q2>e7eDTDU{8_eR}O$@DHCu&c{}&8wF)mVWrx|*RXki&Q_;g z5X0g!V_0ULORrDpo1k4{Gs0Z8s_T1Kj9jVSeDA$$VwH`~MqllEjshR#r|Q{r;YrHg zJx*3=?4EUYxo4dn`{G;&_H1;vE$5?OITGg@xQ~C2KFt=MY+A&d^eN;=(89}e6a4zo zsW{i_1Dr^jTqG=J<^=L|Z7DI530Rfn3U0f_nVa4B)ygE-cXqw4u#Y~hZj!6^eg2z2 zyVOzl>K{TXmb)a@oloyea=C_?QAljv*~KH0c0I7`#;7FMr~&*p|0{JTo#qH7%_3&F zoUEaR({6%a zXRVp!+7QW~RoAZ>!@f)&M`~Pcos4j+IN^TktasiJA6B$aFzMKRzlG2;`RKkoKDie6 z{P*2Zd|K8frVQ5St_>tH`)^sk2NKcoY=nF#(N$T@g)i%tPtV(~Cs{W9gM~m9|5O+I zCc37b;=_r z?fBl2Waf9fKJ-eA@J_Be>mTiE^ThN=7Ng-ZBROQ`nd*)_b9*W$*lLf9N1@3zBu5u4}%doE5L;Xyps@lA9uqI z%vsb(uVqz(|77O~KQdb!-j?7e=|;_e-ziqGH1Dd$^kxs$vh18jv>;(EBYXDV#+}iN z)!nbgSO`>MYsXIIx*l$X)QeDeO${VHo7wey=ia)WI5s-vILO7vhSoOmaNlsFTdarb z9o?Ux1&KE7PW-9I6z8o^)RLpdm>AaXrX6A-P$lOEM0>0#{byCAr}I`)OC|Y|`fQc8 z)u1=7Zb=(OY$d-hua%DHHhs~6S1u}|siKV1^v?EyzB#AXB50Ab+=57aD&n$S>-Y0d z6`$XmuIMw+_eW7b3xTQ_Rt7JxHfw`f#BZ)1G+V2DYDCdQcO;;TM*`j*V5&ly7xnIH z(}Qcikv^F1L;!s@B%ivA9*4V&ATbbkB{wzMDU! z*N{M!jPY}sv4h`^jiG&0WpYmQAEu#2Ml`y34CD@*OPm`sJ?VVEAK;1&Ld% zUhx*(>_A>!%V{A{wVbVg@OH%{qVvWW!>@HFBl30C{_btp%Y`MnI&Rr) z8NDPGx9k2T5?%9B^G~(taatO5t}XGJlS4xbj(2dp!q$p%dC`@>nv-;&QdkI7ZDEms z+p8tGz76DM_>C`4D=(}|{C!8MXhFg{_NlX~18p%WLHisuPFvK&rr+E2PJ9m>w+&=* zuNgPR%I}ePXbbw>o`u}1L^QM@fg?56t3@@XRjTJCKN@DU5U8rN*ru-<5GTJ!s^Hpm z#F~<1#Dx_qT9B}QkLt00^moCcWZ#aQ?zn03OL2-g65Z9sXIy7~htR>T;TClkA zoFsGYoKCbLQGmrQvDtI^n@=v;o{pWLfy`a;*g~MHI*T3d#YShmR=THy@wJH z+XLs(&34i2^ZJAJ>iI0Y9`N#$>)ljNd@Oj)cpVx<)WOwMv><`?SWzAqa2aKlL8L+T z3l;)ZWQtw)`}32lwTR!fPr75Y%-fHgI&fb_3livQiW0=K*Y|!LND5{tts#M`izDs& zth%3Ehu`p#%-nXmk#a#N@_nyMJ2l^~4=kMM8u4?J6Mf}(3%lMpC-a*?PMm%4#5lgG z6B*oLp@tSD&~I3jUdwMrYkOO=|K1D>fvVHF*xL5t1o{5aC3R-HVO>iSIj4q(79`Mb zSgzlhx#{ycjft~wK?{MZ;V;?y&aZg!zQdvo*Oa8J{))Pb79^~7cj>V}+Bfwkt=XqJ zTHSg!edg7-E<`LsVFBGbfW=FUTUK+ zHLwtBuN&0Szrkpl|Z1mzH!ad$plm)v%w?bj32SX1IbkIAubWwG zd}*SFqati2im*uOVU6F)nmEKKm$3l8d#ruNztjR8?fH zQrOWL*?&wM-;b6nc|j}pq=tqTB+&m^#*nDqwCC3c+BdJP76Mg4-EI0eC02~>6lF`g zj?u6rlwP z>+ex_PB+@B{WopH-6c-!^>??n@fb)kPOy#ucJv%bzxkijN~T-tL<gR8)=IAxmt8w)D z-r8F3tz%UrP=)UdEQ4fh2xYS@DxYCN3leg7jV$9-?NIvhdq;IzrfwDjRrqG1DE}1S zda`}%5Hh-8jF|Uv&vNkhW%sNR&NC@Wv)HbB5AP6`_4aQSEl6Ms&UT-bo2>h^m_U5a z7SWJE70%VLc6Z8G{Y%(bvh0wNUin!T0#!KM!cGfK$ZMQv zIgDH^yjVjE64>S|O5;5q#*i@s$j58Cg+LX~&#)a;Y3dpDYCp0qiS0gv`5h#zy+N+v z8pebMUCI6(?=1wXhDF--sK^9Y&$YZa_*MK5ASSbYJy4*HNlw(>F-RnJEU45&+jZw%JZ zf&}&}Y$kQNH;tM|NUz%UEd;9G++^?0!SSvi4nC48o1#2znZZeF&pe}|1qo}LxF@P3 zZI`>TR=@Z+t;|Rk^WQo~jP!Aq;!%iAFRs3owWRN{4zzv#^Xk?#X$V@7u+C-F`qYA! zYp_h+QZ$E!Kvn%EHoZm8*K$5_b@%3U$(sSrr-O16v>+jOhPwF9P&NaZu@TM1h?l{I zECi}Oizw^-OjPfhz2YSnT7!7E{UaOcmmElEhKFhAv&L9@P9$)=!p_U+5J;b= zxTSe#-fAIGh5bD14Za4@lesHYWgubo^V`As^l5(v5T&SxnA3O9_G4ed``!QM+tmW+^@BS*kc$P<2*Pba z!rFiQ?YB%X{;CDJS1pHyKozbIu(*tXcY4Y0^~v&1MJ%fTNDO?(W+v`_6!X4pPG(YH zeM%h%d7M*%Xa?u#F zwKPd_wm3lx64=|Z)xNlw#>%!ONtT|aL23tuYG}dxVsFQGC`6T}bF0@R ztw*%95U9#=ne7boj(5!#E7eB|RHElT)F2i7!&S5(VfCn^^_$c4i@s_*_wLnlu->cD z@(k%K7tk`to`|; z12t)`fO6{BSCuRTs`xL+`*w2|wsIrAp6zXFl0H=@(O$XN<$3$T=Z*R5yLF9zU7alY z$mkrzp0OoC3lg{z&wQ}XIz3gUBBb^mKMR2>Y`fUAdQ(YX8C06gnNW+M1qoi>f2;cE zdX>|=oU2GePWxI2RPpQo+QgF?Q|X;f?9M$qy=KZ){7snesmC=|mQ^>(L*LN# zinb`_fMlz$Zi3V9I0qJmR53zd>3LQAHNSr{!mYygn5_?1xTP0-7OMr8>|trC@xJ)f zS?lvxWnf`#BcN`?}sk67#*^P{J{cWV*Y#$4O zDtzBzD<+*CM(L?_Na$aME%R_lU=PO*7kfL}=+?hExmG5Fg+LX~$+35Xs$-3)&`#vW z>vxtJdL-~oPf@yL*=Vfs?M8+^J!K(Kg|qc6yJPtsMr5%*WN5$DmQ^w&a5j>S6KS~d zcwbM_{Z&5;fht@vW4%F!$41WEJxR>@QtUL(|6+%bz;y~1dG^|a)(Y!LE@i&YPD=Za zKov#{v5Y$DGt*5O+LFEPCRyT^kg%>nvauCqV=OVg!h500+8eOGgR(wE^dD&Xy^F0{ z**}W+v&bXtM4(9@Wsg&*r<1liRDz8Evx$ZlBpPnB>CvU)2p7-uH4u zcKJkM8eMCPR(*Rlf)*qm#M<=O=(l24gq`TnAUmy?ev_6ta~%tTs`*9i`r^-AJS z;M0##VY*oi<3s?yKp zhG;Pj%M!F8fny>?dAhm`eSfC6)+lXt3xO)EW9%(;a!K0f%{w)qN-csGBrtx4#d6lk zLthkrr0)CD#6qA7>zJbSyPB7_4#}*J8`YGc1qo|p&6+1U>D{pOs=Z4K3xO((@nkzK zy86)cd#jQ@x9+Ie?#kV=E`BBhj_28Kj-Hk1hJ!xjMys|OT9A;tC|%~R-xsgS(0qDj zvZv@Y3xO(pFJWg>?I=OB*vk|9#bcKD4=#BWKsg+LX)U$LCU z5xHsRprRy?k3!Ibgp93rnfvIkugye%ZS^LHK4-8HsKU2C_B|@4q4Ddolg%BATHYX$ zkdfprbEk!`5^wZ=;YFg3m9-G4!uMS^bJyp&v7nSfHc!_q@3lzCJrpi;57vy6XN-=6 zQ;>1B{44~j@V%Yw^E!FRn3Z^2JN>nt<^3E9x&O;$?t{EGXMvG^*gY-g@6HwiRo2mK zSl)@oSl_LhfA%2DSQH72zhkoo!|lexRok_MFM})us;r~%fL*us$ZnIh40T6Y#?(mg z(Xu=8kgcV@@z7)LOxG%Wwi2k~*X{^PmgCSh!$`OMwpwz|NP;nfSO&)XvH7dhON>s% z+H0M?t#N%w;8S2L)vb;j@q4lH6JP=#Y6cH;ZJf;2^tC%H5~qh;)a z1hx`vKhDNd^f=32x9;IT8r}<4I8tL{YOk{N&v8Xa{hkq)Q6Cc6+Oe#Nzic%AQ4vyo z#Ze1^DjcJ-Q{{8|(E9Vrk)gAvS;nGBV5_YtdQw$-r%-v4;z%0{fhrtpD+=p7DC>jHDKILj6y@(iO2_puXt@@_OE4DmfdQCMUfWf5*7x(zKzSj(8$d^nx_ zC8Kk2nGG7oR^mDZ&b_l3uSY{^{?_r%zl;BAi8Vk1*DP4QN*G3~%(|-XF2Bk`pbFy- z*hnVtKsqGcM+;qYz!K?%1g=@IoyFDr(Il^h+Qfuy76Mfm^~6@QoHwNxrIO#MmH+Tr%Em9$ek(3)#Hmbv><`wQboDy)ri^`fgdXMo*j*IEi{(C-Px9w^Ey*48U_RR^_U(Wyk6I_+~mtD^^Jju}{M_QHn$AM7Y zHpwK=!ut&O8H9LNprWK{oS>hn93nmy5~%ugm+j`LoaC4}fR{0+ekP;Z@`-{#3li47 zOZU>(G5+j4J{f_kXDkA0&HGP|Qa5-Rd7AYyGOrse2(%#abgNxY@$8es{#bmfUHyz3 zolOEQNZ{@&MX`TbY!vhzDat?sRbG=>MB}zkj{InxvC8IgwtEU>rBvR_e& zKXbsCS0^|bfvWuhcKt%XPmasec^RG`P8rpT4iW@fkicD(EXHfd9V7jrz+?ofjpu5E1O`rs8`N9I5@&t3OlQb^TO=V_4(#D$*<><@PV5LYuCF zKnoJZD%$lAGZGywKJYS*lze4ei|w6^K$Z1V^|txZfDGP(D8*)e<8FR*#C=Pz;>mb5 z7TWY>nUqiF|0paluscgtc@59gs9#xzStplaP?o8I%Ec*oVP>Di~cw;?Yrbg8Kz(1OGP z)?fX1qTKY7CFt|jb(0aO8W3jFXTAF9*!GE+F{x5HI<12y2(%y}+bf6J`c&*)mCo44 zP99?aA%QCVoml+tA&sWFT2>HfLBe{r;kKF$>GWxZlM$%GUz6>3{ydU?{W{O!p9)X% zT*TtKwz5-UOE$`=;u)Q+Ki7xT%QM#s0xd{1s%_IZ<$32IMKiKzwe0R-daU{JWCW`4 zj7~NRUmQfYWxg&5v>?&14LfC(ofaA&&uij{b$zKucseel<&0LAQ73vl z4c4j&0#zy4j+%of-#Ds{`d?yu{8(BtsEZ)5mLPG4o#j2fWwgWL&wuj*qej#HMW-es zP=z%{QEoSxKqt?ykc_~Sb@BVL6Pmh*Q15Q9bzXPTg2c$;%+KZN=B&1t4yE4tw8b-w1c4SLtS57OB!yBnT8^iv)e&6aiTN7S-X#$-eQB)9a6}PyrIpIrc z>XWlBVVP+7zPpTnh0q%duCvnE{%Uz&PM~UdyPA5gstcWF8K<9)rTtcS{r`R{uFCtV zhCVpMa%b=nUPe{F(bP6;njp}E<;~quLthfTLY6UG8BT54Hzgxb<-WeRmzVKJnn1d% z?R`NMzFl44J!Xx#*VcwL^asaRId3zSn=rq}{pka#_lvWFKnoIs$JEf3n=74nMHyA= z4xz5xN0Sk#a^K1PRQW3T(>%Ue34gkghpXu&53CoTs^seG`lu3Xo!-YbIPude%DEDq zY04cb1%a0Tix@7R?!opwXx~o>$-cRp<|_P7>{R*lp|q@{g80qUD??PzgdbAtbx8=K6P^{Q*V5Ze1?Y%&5>?rZb+7?p1``Rp{Pz_(&XICXbpv8U7 z%jnaxsvhuqqAY`}Ipwa2ymWpqRJpIsGWaLz%03w<(Bi)4W$ZXoSufsatSp0nYyR#3 zmq3;K+AM=VS^k7Mffn~QFQY&#+tutfN|up@{d)XY{9gi9?rXCQUPE|I;RIUT*Sw6C zX>Gb^#u2g%UJH3`{9gi9?rXCQUekGv=LA~Z*Sw6V>=pGp0mEe(+?%*p{V#zk_qACD zBUCqm7WXwT!@E#<_#W(2sqRnZR`GkG%6)B?!M?fX{^n?LU-L3H)F=zT2Yb4j`{}w> z{9dSXUz=qx|I^&RAX?nlyo~HaOGCY4wM28*61R%q3svrGvkX=fiMuAE#eL1oXnUt5 z_y?=)#9iCnDt<3ixv$MKm`4$}N1?@i&C7@$S_1r>sfpWb-70=BRJpIsGT0{~?v?>9 z?rUDgnpVZ3y<*>*xLY5$ir))W?rXCQ_GF2>g+q(`nwL>=VlilU*{?^qAM(2ER`GkG z%6)B?!D%STaW8M2lnBT(hOHp`GTk?=Cm z;=bnheg4 zE$(Yx2Jd(O`yR4)PDY^0eQlN@M*xCAi~E|F!N(8({T_0Zk&Hl<``Rpnk3-$RAX?nl zybL}L`mbKe(UK^`t>X7WmHXN(LypJPtqT%6)B?AxD;iK#TjD zm%+!S|M@xZHMt-1mcgy!_d=EX+AJfgo*!)%UsMoiabNQ?4*aO5pZm2=*4=M2n$hAL z^CTlsh3`~sO}KR>dV997AkIc)(=W`7aPs$X_cfobJNhY`{@O3XS$Z0OKmXdb3~lw9 z2m&ogEc%>HZ__BkY0mYHtW}KGwbxHZpvo^Po1TG{ac(Lv!+7U13V06|L`)w~{q?bM zajzwdJ@sBI%4i8^u)zl-Xn9XTprv~~PksOW zaA$eHj4GDRvPY!;X}rJNHCY)*>>!@{+Q;Eedt+XP_uAAnU)N5_2vnWV<*7IFa{nH4 zPGzKC6Wa*_El8Zo>#0}F65*T_#LH;=EH^Ehqj@p{RrqVNx9#frY4nmNfTp5y`;`6PR&7vXcKz$>aHrqqbZVum+2Naaezsh@uxW%K(1OIR z2if&6lfs<`p7K?)u_Z=o_2!RBMxe@Ccgu|Eq_xU#K3%jR(Rx#M-8VSg*@>;=v2$zl zSJuKZPY`7wfhzPHw&pcDD;b~KUl8{~z4WDJBAj2Eq*WUY^U}lfM>tatN~_lK^MaOo z$($S{GNffP0#$hydFhuLL^ucL=IgcZooUI(&K(7T_buGmOHY*;?)<>kfstm!{UL8MI1d!#ZC<1TOUYx2Lau)Ju#Xc(3oi=5Ys#a{PxU@nmO<@Uag*-KxP} z|MpAPU-0Dpf@I;GMuI>K5?D5iLw;9`^x0A`8G)+MWnOwniwLJj23|`RrYuV)_922m z3li4vG5&lN%Kk`;X6-B^BsOXaW8)u{fAg5d5n;FQWK+Gx2~FWMSLp0dt+6tM_RQT_zB;Ai>l+vpG#7=3*g({b^6njkOS{ zS~BZqSeZyqwbmzI#>IKWV1HV^XQK#OkYH+^*_kHis+qcG3y;7O)&U{;V zg~9%`+M5CiT99CBo!OiwG49t+gZ*i1)AY0usG9sEGOWmKPc@-2FGHKT-(Y{*-B;ZR zT99CBo!OiwG5#Sn*q=5eZ$}G(sxPj{uz(;>HEI?wW60<$2K&>F*Yqc7L4v7uW^?IMIX^P2K&=` ztHeT}>SM3Su=bj#8u*Eq;TrbUV1L@xD!v3QNHDd|Y)+Gi-Q_{qA9=sGl7&E(RxL6t zq?D(cwkqGrn%_4qWq)L6rLqJqNHDd|Y)+H--8M62e`I)KVGDt(Re2)A_T=$YUkCFt z7RP3#?2q)Qlb@gk38vPW&1n)b*>X|#M*_-bwGgN(@IE4Ja7s`0^c7x4#i@BI`y-Wh zrX^@Wf~j?8bDG4RR)r}0Bg53M8WN}qdlV6-eb1%_u~XpKX+5_JQ}#zv_WP)z1qr6s znaybuQ$vbV_D4P+zhfa#HSw>AutIOLse!?K*YE1!Qk4CXz=dZtwEREHzB|5(B5Hd9 z=|w`2UXqYdMG~6A-Puv3NH0oP1f&Ski*$lwK{`lLdJ9biM5Nu#UBv<_8W2Q85m4#9 z2?)w}&dg5oTrR%v`~5LL4mr;=XLok)?Ck8EXOThZRPx!HkuR;HM@5c&YfTsfQEBV< zy1V|!FV>M#C4EnLY$cD1Tyti*gC1lMI+c93W?Z0eJ5iBW2fZD}Kvb?-d);ma^NSlX ztjUpmVWLMx{xrEW%>*($$RKno`E1SDKB%fkMfUu=QWyhK;dh*W7FG4A$RTlM9rPfB z?oX-Yv-Le{a<=Lo71^@sL4gcJ;nTfk-7b*H=5pyyvc!8)z0}gF-*maC?n}47ES|Ym0!xelo-=mUC z|5A$`^dMvCb1|vQ@13z<{+zF1jX-6|W&HG6VGKlVTNR!9Wy)T=i((XuN|apI{L$Az z4>DeF7L%GK?TkICEMLLD8zf0C@!6Y)F%UI-V>DdB_?*=wmoF+8cF=>2dJSSycW*so zpX$powxv{)TLQfGZ~#{N(- zdakK1x$IgyE{uUFGxyP}I0Y|Omt1DAw*-2SG2f0!ojUuBzwR?@eKE=9@xLFEDFdTZ z&qeLCyNz9H@9q$j+Hvw(yZzCn_T)FBVe~2gV`<6di;kBa^dRGO`)-OkzvsrS&A zVrRxmF4c~n3}YY)`y0((kHxsx{N-=UbJZl%N%Q5N=D<`=O>$)?Hfhg>i z^kvd)l*2-0=AG(tYvY*I2K~<24t*nYH`xpOp0oFoz3iE2xJMQ5{E+0bYr$g@J;->Q zdi#ok=j`cqdEEW__w15O@wf_M3`C83F&ges?cT{JxitO0q(l!gF1CqDt#|CKoqHU| z=n)kqx%4SrG>m~Lyt1^9?5Bc~%g#+vVb>fPAGM81-JEvT{&gnD*!Ff2$>sDfIl~x; z!s}0&dLP|#xD?J^JFIoF-KN%!NsZZh&VG3t&lw6{zU*+JWLAkDWPF_z4fB$;e~vj^ z3QT_{jDe`lPsF4qgg+o7;Ah=s`y4Sb@~- z)qb##CNRSln;b6o{%{7Oo~RU)y6xrjcI^htm_70@o6CwX!tVxn2Y9MSfz(aq_uEms z_--&cZyUkot0u`3J;?a&Kqa`h_Ya2e8jWEcZc z*H#orZT`Uz_V828Xj$b^hs(pOhfDMzBlT|S)H@w6*vl1TWT93Lm$bV>!Wf8ZxU&E} z{fvE6)b!&Kq5SO)o3|G&bbWPOrE48LeZ6~-z zPj|TB9=KatG*fL==*lN9m$gTeCCx)znvbX_Yu@5sF3mPzZcwh50(}kcJVbo>TF8o@?qYw zVGKltA6229lTx`9{eG-O4>Go9z36^_ptK08-$%ZiHBz}u7@Hi%KoqtJeSN6Wmmw~9 zQrbuwpIjPs1dmb6OPqIW*NhR@UtMDJvnY)e{!?nF-rGW41~hqIJ#!ilGD^R8-hHfG zj2Km$uX%xHt3zD&uId`bKopHUF7+UxN1r=Q7l*iv|Gm3J4>CU7aNd2pRE+qtEXUZE zI6cHA(+|DF7>MGv0s1BQs|IDJP6}~(>2bXVU_8jUa_GGKOQ9IikNj0DD0K=rSZGHLR^kMJxHPl8CByixWDCy5&ds)FDZ4nafnOBl%Zh^L}3rLtO0?_ z9+!4gXE`*db!i4GcwW2v-Wj*&b1~u#viWI=X3zd}RLq`A9+w<#ma3;B<3Yyea%bJ+ z?PA1pLwN3UymonyOP3s}VGKmkT;8QQmf-n3Jv+yi^|*BC@U4R$WOV9&)}7ZrMhqy< zjM#T$Judd)lVJ=*@v|t+2>s{U1(!;BTsB7CP*17GgN$#MopoDwh!KD8<{yO77F)2h4@J;)ez?5z7un;0=k&6c`GM|oU6C|)#- zfhb;0pt+a7&QL#FUXRP=u&BMkk zWX#Ta-Yr-wM!fPm$FKt5hq(OEvsD-aQ8;$dJ?dh0kIU_qmY}CAm!72rKVk9uEpKJ(U-naW~M}#-=W}u_pS)$h7Jnmq`O>gvCHcp-;}Z zAJ>l&AFF4zBAcptTKUQM89MSq>4z{+YKm+vOs5$Hk2OIy#l?Hk01EdBTi zGP*!jk4w4eC)7HFsS8m!#!!aaKS>^!0<&v}jXubD{lFP_a`PC`wy1h`{=JI#HZg(DH=@ZPNDO}?mi{LX5(*L{aZ8O~}n*Mr|K7+XK3_G=@(@sy9uZyFxNVAPdX zw0<=uTIj6Cdw)re1Orizm*4B|=o2k;R^z;v zntD6Z^j>H5AcNk|yYzO$kMUvc*51Umc~uN#AnNSRH1}qMXrZ$j52dyDri{;~80bO9 z!D+Xhf8m_{1~hE_VTKZ-m79D15tMtrnzrqq0vWWH6E(o*XuXs zQ^i0JGHBO`OYg({7{A@??;WYMDT0Bh>vPiF^~BIwjotnn&p*`bo_m&Jpa&WBUfZR2x&BeT;tuy7sy--!fvB1N)7-b077(08NqG~CMtZOB zZ=o3IK}PewY3^qW3JA`@Bn`Sivv3EkU_vYDGBN&L9&@s(@joz5)jKlhW zCVO4$U357HdXT|3zhl!Q!;yQ*-iEYnfd?@RY7xb#^JD?RnW40MhcZU8%+nbo=)roE zUPyB*JybyGoY9B6CVRz7O(iakkKjQD+q9p;KdO6|#&~zPWpWg2&Fq4VzQOdH`{b-F1AdXO>h zwKVs+bx}fR11^7axYzijp^AYXWN;s&JsbW}ZGCr$_p&`Vf`Ol)f(ic^5Bx*DH#F9%S(NNIS#)7?s+-;QhPU zlH5y>fvD7TY3``%Q9@@NwyV?LTiP?bVxR{ZJkHbpFF(e*x1RN0s+vE7fv61$d)+NL zqXg$flBQEa6L0UZVv2ztWc*xzuRHffe!)4I^!3vz4ZY?EODYC>kiqvv+A-!I)#zeR zdvT$J2nM1`b=m8#I+0)K97XS2;l257CB;AwGWgzZ-q+Jtb(=on&0Cig!9bL;b&ewK zvGi!KrDD+TOPBUns&xk1?dj6)Ou_p%DbvlRy_SNr-Dq=L?T0Zp)mY(`;= z&`iJJn9!g3^u8s^7H}ySPPNG(G23mKqn2t>JX+GgJ~KH~sifZHg&t&7&pF3^`uY=M zsLCIFIOoz(zRY_66*3TI{;sncDPJ^|@wtN-*S|Sfeb|9Igujil~|AV2`k2fdLr*H!9GTN zk9AI*VxY&^%%GjoF6~iP=R_+Luyfg6}qDXF!j!IR<48xU|#XkHPtHoI$`b42tVQl(BUT zpOMN8^cdTm2W2eyF*t+Hq3;V zbqxO(rDCAR*c^j@X_V39$MAo(5e!5bTgUKo8WaOP#^xA222*B|AH&a^h+rVf*gA%v zo1qx!F*e8GQIs;Q{1}+YYEWDkqKvI$_&Fvj26~LmF?g(`Off%(pT`oxK$Nj{3_n*! zG0Q ze69D_2+Vcg~XE0f7;P+S+HjICo}CM$Z3%`qsGJpIl<>feybYEWDk zqKvI$U?wYijLk79lRW%Bn4ZaMP+S+HjICo}CM$Z3ZO$X(evX-}24&8}pg1<$I);Dd zY6gHFW1H)dF)zVPR)gZYxZMoO*g6JZL6gaf9%FM1zOotfE6ijyD6R`p#?~<~lNCM2 z<`~>VGv5M^u~!yg$G13kv( zdU;&oCodhtAAKSih%&a0;g4{NfgWRXy*%>qGn|frnXCrIbs@^wI)*<|s~G4pHrLDJ zJU=bz82;TLf`KSw>lpqWM={W2Y_6B@SLWG=RO_@pLj(g+#?~?XJEvlx$JiW$@4M!y zkKV+Q8W5=hDF&+nkt&d2MIb`4PKscCA7kqntOi7?K#GALV>5%*fXs6n>AjK~ka@Z@ zD6R`pbcC!BXH@rLr0jsRAhm&97M3Mb*V>K%|EwSP{rDbX&0+5UBzw26~XeYCxp-BeWtAs{z5v zM8@#~%G9Kfiq(M3>Icm~Ip!mSR^#vWne`1MXAj;S}2CikG$Jksi-Ag#z+aD8o#>X>1f7X}Y6A@)>9Rt@g&|_?l zL3caONB3jkT82S!U5GNaj)7|#=rK0Opu09_-}^CeEyJL=E<_ny$H27=^cb6C(CmX% z1pFAdmSIp_7ov= z>q3;Vbqrj~K##FG2H%Muyp~~5Toe!U5GNaj)7|#=rK0OptVK#o%>H-DuzLEU5GNaj)7|#=rK0Opw&+puW&8H zptvqX8C%D|wG8wan`6)_Zu*Ey-z9^!41?mj5M^u~1J^RpV{DE=E8FUBz;^grhCy*% zh%&a0fomD)F*esrtLowR!SuBZgW|dnWo#V-*D}y!Y;ztN_j6p!Feq~#2F0--yq19; zV{;5{k&Jl>u4Nb$$3T>^^?Bf026~LmG5E@6%&%}Q!=Sh>L>XJhz_kqY7@K2o56ze- z;#!75ab1WqwvOTdq9or3(PM0m!N0TzuVok%*M%r!>lmyCWZw3n$JiW$)qu?VX!?RZ zsR5Zc)dt0NAqtSyDZ^il4D`<2Hv8V_4LE1@tM~H8*4h26A4EDr>de{0Z`S!e zxv_cw4eJMyT9D8hLaZM|Izozp9%OLrjC}yCA4EDr5e!7Jeh?|d2(2N+`az^4q}JhR zXN7HcY|u^)+w2fw{UFli5L!cs^@B)9D1w0~+CO1u?8{*NAkq<14D=v_^@B(uNN5cq z)(;{bp$G<|SU-r=f`rx(V*Mb}5mF5FuznD!0twa-!q~L8mh^*2M<^l&GFU%|^nQfa z5Muox(h*Xvi*+H2_Gs7{yG2+(h;)P$13k!K{UFl&5n4lt^@B)9D1w0~yqcE9`az^4 zq!{Qy2I~irLXglJLP|fVNNfZHQQ^I0?6I-3_!3V&v9P`l>EQ_0*kK(U(ybA!g+qIo z?2O%1tZ+k0H>!2fgA7)J@hOm@cJC|0;3r5nXS4>DNch7@Up zR=Ht?8&bN7U?2*6KJ6nSg&R`3Q4I7TgB5N_!$xS88&rJD!_qOj-FP7YFMB9$if z-kH^zNTo@zLKE#(v(276R%arG7@-xKSe=PfniK;)$Y48T?;xu)kxEmD$KCrG2F2GY zV@G4AT*-1>gOAiT$1BM7nmu>e7bt6sw3bM7iRJ>Np9#GL8F+;Bl^D`<^6Do9AH*BLlA4EDr5e!7( zm9?zjKWi;({-)KYdAu?^lzAjFd#G7Uh_rtM>j_yFs{xTJkjK{pJ*);q8b5*+fv_f8 z*(Nn0QUy{+g&t(E8W5@X2(1XjYCxn46v03g--$BzI zc1T%Au-*=j;ASpC?{P?}hZK7h13k!KJtxxs5n9uU)qqG9D1w0~y#AI|^M}UrjT6Nb z13k!K^(j)J60AT)`>B(g%UqWpiC`cKdkdUWH!`1-z({n9JwS!bP1S@y&IhnjE`nn@2cu?`OY*aZ|=^obk zFbs@M%Bmk#lT^G<>)cc=XzD@~YkrulG}?i!RXjXa@jwqU!q3CkVewdpg*8}A-X?3X zkcNd|9TvX+CNq@2)~t0{Jl0`B4>DMTg)~z{m=24_IxNUQ6t*F~;ng}U9_z562N|rv zLYgT;>#)2QQ&m#&Dz~Z`#y}LdG-ZQnH4=~2NLY!)WO}j^3F%7+RwLnGm&pvZEMJYp zV>J@=AcK`iNI67=sgZcBMuH4PVXLRBk$9{|f*xeB5(#OIh%hx0kJU(!fhfE->1re% ztC6r02`Q2YRwH3064DnDtVY6WStieua(J~GiN|Ur=s^Z6k&tqT2vZ~RSd9c3h~n|l zWVl+EuSVjr8VP!k!Ac~g93sNhNIX^}K?b7m%BHK4c&tW(9%Qf*32BXpFf|g7)ku(m zD7^mZY9t|6Bf-|iR$wI((j5_DY9t|6BS8-`)EzB7zt&eH39%XpG7!Z|B%~rD!qiAY ztVV(;Rw6N({^1N?jU>csBFU3zh(JqBq3HKK?b5&iG*}VM3@>$h}B5YgA7(8 z$M+mJ(;_GFESTBQhH;hsQD{7DehG109gjg>FJ;-3K3{t}oVR{)M*2_Q!qQcMI*I{v4 zhXwD0c<*BkmJIa^Uxy`?by(1Y4Ax*F{S*DMf zg;Z7qYqD6@TTL=MR6^x`7!}4q6kb`%wJVU-p%VIZ`KYjKjto|9A(a)Om0NrrmJsW( zU|op9>rdKkcRq2c*sDle1ZVnZ0wZMMlma3<_1}6Y7u&3GLfQ{DtDKA)Lu)9c7TWn+ZmZVuc|%m3 z*F3Drcx1O%a4`lK?bXxkUEL2 z6;GyrF)5Xb$V>Vq$Us#1nIGNlhNw8(2Xv5}!B08*HfQm(5((w#+pI>C?|1=Gghq!) z<2k#(-^vXkDvovdMTsa@A0f36dlV^@1=s^bSijZ=Mt+hqIIMO&o#o4`LXcz-g*kkBByay_KROEZV zOm*T{M~m|-_S$!MF0)xzgmUz4))pzSB3k7CkkoXQeq!mtk9t(3{9wL=9%Qht2> zT3ck*zvVqD^8K+}!x)IFGc#Izw0E!lVo_EKSr}8+qavrg@U4R$WU#IX>44Z;TV(I8 zIFE|#^2={w3`C`o7Qoz}_uBXVW`&J!`owrt_Lk8cWBRT_9u@hDL+gmge`tt~QaO0-8s_HR-!jDe`$ z{Yn3&&^~)}KaTO}(uX}Na#>n&i5_IIt_bOX*jig;UhbS86*=U|a$yWaEo&Gpu5{UF z&$+_CL0?-$vbG3%kiohlqyu7WZINFaTn$li&ew9n7>Md#l9Y&c?6bGO#W4n*KN+Ip ztgcW`q6ZmwNNIy~Ky0lok~aEah>G*B-7JiOsDVYIMXN9N+3{mJM(@85gs3=u9%?Sp zgA5#%Xl9vxXNZc^BDP%^15w|eDl)v*yDWC3=v7V+^e=krD|% zsao`uI+Bz~o}y>J`Sg^^Z{f_-FF&njC@zj8B@!yKMxQu=9#$eDeG!}0NU$b)e@;py zRAj!PGs0pZgOx}~ImFg#B;W6==24N;dY%hoAZpb|(c;vMy>@1$f!*z^Y919?bNeNM z9%Qf*2`PuzT8-qBr>c5X6RdQ8;#4R>MrC<@u%0NM1v3^>CCpTT-t;G^K3imCtCKbDb%(+1B~aMN=y} zb9?K3$Rn;qiRoSScMSO5P>&wk=FEP|$jr^8LYuViYvC(VfpQa3SOg|T8$kUh{B$4S*-IydN1mz(1Q$Cj3FHu zn^j{dzm~LQNK+<)fhbdxez*NmuCGF;3+Ua^8%Ygh>TG@0Sbc=FMr>9fd7YlquI$o( zx2)Y~=!@xd^bTzFAcOT$NZZ8L8Y$CHoeRa*cu5@XYps`y`?Gna7wIn|AOlf&W$CGCS9b67Y?^@{WU%@SY0cPLfo8#}eBOp0 zI>#Luh{Ee{S?yQ#2_1+Uq0XE&N=T8!W}OmNI3Ya~n^jJ*)h+A03vY#SN|NOVxR{Ztn)&uF1FTsd9VDY&~QtC5dj&9!mCL-sZUG}y;M^l z6*9)1C?IZ6&{qx5&$4>ed@=O!p~y2w##qu|F{1?SVtwk7P_erD>nd0mqF9546jyAm z!_qTf{?L;{Gy^@zcx`rp^ihev*8A_;)Jnzmj(B7siZxhBamCg;EW2v7No`4AD&R2@ zJ;>mvrB(Etm1_hRqroc$c7iRNp9h zXubXl26~Xe3Ld1_VQUqS8f$XMrNi5)7|1|We^Lp_7#R*MvgDz*FDM3jkikkMq#|N# zHIhB^|8k1A?;OEE)G&I-k}<+{EPuvnc~*~C=s^Z6s*rw)?SJ!r+V{>8p}%8-3`8}e zeK=-xC3VWw9nSC<^cTR;gA7)NAsrZ7tHZ>1SnVADTz`WH8HgIOG%Ee~NUH{)E_Rwc zp|fkygA7)wDbdW_BW z@@_`nU$0}}9$|yxx)5b-9Rv3vqsQ1>FYn6aJOLd8_c|LC*M%r!>lnD78a>A5dUae&(ddcN~M_x)5b-9Rv4;qsQ1>FYkHfybT=#_nsRR*M%r!>lnDd9X-b8dO7Qb z^G|dP+(U0rTo@yVuJ;vr3ob{5?uP`^mptvqX8C%Ejv(Hov^cb6CaMnx4?*ns8 z42tVQl(BUT`bDLGT^>Eg<`}%IKjU|fxiSXDbs@^wI)4KV{;77vd9>BX%uB8od^b^jICqPNX<$*ih&+ua}3TFF?WXW z94v$4x)5b-zpWt83q8i>7@YOO_eZwXU5%A=)Sf$o;<^xJY#oE{oXntSNy|cyvCVm8 z+-vDR$Vxg9431||#?~<~?+!i2<`~=}oPVOv!*5-OkIJC9E<_ny$KWey6a>&?Y_6BD zKj)w57=ABNF${|9LX@#}48JEzJ}UGWo9pF%%=^-H48ONWFc4*I9mD@cDF%9s&Gqsx zjrZ5<82+y|f`KSw>lpsXpcv>eHrLA|2ImRr82;!J!9bL;bqs%mQw;PNo9pF~kMkXL z4F3J`Y=&FcptvqX8C%EjM{31DkFmL49>FLHq9%FO8d?(`k z6CK09t3@ynWo#XTe}6oK!V_QM$%~vW3UGqtj|b#ini8hWPL``X^dbX3R{G}^hf%Pq|>Mv=y?!BYbUVM0xK@u z-@1m)C~PH?{2kiMacfzO$&Wk_m;HtQMUlci;`t|93gDh7Ix!Rn5rZ>X-OWw8b% zX+cIX5Eb6KtN}?{kcxpGWUvM#sXW?R2a+`)NeeQ9fhbdx*0MN0rhpuErKQJhH9lLC z82RbdK%0g+MRMjOv2^v-z%2UG^qhN%V*jqI0lngNbV?8T;XA*Dn9;jKqNw}j`9MMX zZgA0O6GiWK=L4_P7tB9sl_-jLIPWvQI+iSV{Cd}A#+NaPqE6=%0bYqWHrM+{T%zdm z=gB}oeU*LxxMW!TumI&(ZjJo66K5=GXJ&-h2>z1>f?Jh5Fd z(1VPUjT6O!}WU zc;d*JKu^l3!q}un^3khuQ`&@x7|6&&=W$^3nLru!RrY<|N6LA5TSqVuh3#fp`}d8K zZ#Q{DG0=kys{-|&)~5q&)K}Thd@@G1TahDzfvE87QLAu0dE!OA>wfNzL{a(r0L^RV(A62N~Fgq`+QjxpR2sAQfZFvLtb; z@(tCZ*;7cbnn42aey8%I zM!ezFd1hDy15tQwXrKNz5>T zKj-~>z8z%y@yq(}xpwnB5vR1<()2#mFPhRw;|08f_g4GD{pB!Hu|pc_sL-l zMEQ0=GkQGvz4J)#9x2V5_m<7;sp!F}m6q7KC+Q>M9c?+K{=448(y*B8>^@i^<$RHT z5bEtxzv|`l!|%;?_NNag4JqEnmt_Yq&%YGInj%N7(FF zX5?Dm&>4O3_Z98#jtpZU3a_kXCC_=r+5RIja*YbR=E%tLnT~PfCyr6%g(T>m{+>pQW*u=Zt4*rzBn{%DcPvhtsY7V=04bcMrRQ z4`2lJHUIVTf1Rmuuce%+*(r?S*Q-#0f7Ki{Sed>bM|mu>a>+Y6r=}E>Z6$h;@y9LA z(0jZ_M`x4g`aP3!qF@ITL)DwDm_CmZotD_)j8~dPN$ck>Dc3)5CDHQ$MnK0HcB{C& zx^!MjNvm-f!)Ghh;Y0eU2B-3QOw1G`2RE&o^39J8Bzll>?U z#_-t+b#SXb+CJ)=VZ90q`NOEWDVJtED$#?CT2u8A9%;wt@xsx1vVPm8DRukCg)tCy z@(mqB?`W*QqbX@8%ul(|p@>A!0~i6#C^NpfoW1s9O6RkWgfV=!LTz|m$G9|9YA-MExt{X=`s`s0M1>z!y&t;D^MyZ1`J?Lv2m6m7BfxzO z<5||hUwg?XCTCgscD=n0dXUktwmPbS-tqgC)n6tI$hI>6)vaL+MEQ15GfvR{r?*vV!VSMWIU0ik80adW>gvUCWL6542N@1M(es@l;XRJA_iD2IIaoI3Oq&%p)`cisL9ndm1(u~e(xR<5 zXJjtPvxyh}xEi?e_EMW|UhybK`MZM*17%YvXF}&%{_%9g+>np` z`i-YW-z7H!`rG7hJ@RqN%(2N{xs~GtdN>BoEP2NHy!t|3;j%KNciLDlQ>`x}7zXvk z&8J25q8kDIjrD=2H>D))8SCw;^OZmk$1n`GKU;qz5FEs9_3qBHDSeBM^<>f85e$Qx z@=#scg?1yLa}-B+TAOnB>%LyT)u|5G#ZN!8iY&8>m9HyO4_yy%t|kBd<%QP+{W^2s z&6QR*<-pH_yy!bi6~lOtajj@wF|g!~fX=nd6|*sA$)q9PwgGd)7>ME+{6yBC_U~KP zz;3ltirgFS-9Fw|F^mTp;pcI??#7f~R*v#ITnvOU5XCV%QtLKUefMZ+Wy<+;W4x(P zWL6C0xu0R$jlN)iaAnHziqCsJ7H1CYSJ;<0M#B%T1v34{{c2Zg*_3bgboCAmyP#qi z4>HC*RadMjbv>Z7Gbhzwn=-6+cdsSQfv_$_@!!pLvaGhBS56sJxtG_EvNO?xjAtLO zE2{Up9?;pDznrL?;{4dhyU=B47z0swHR+mP$exm|MnL6S)|g#aJbwIgfHN{LjjAg; zC%axKw=j6L1! z3Y$g@oom_W>5?gbe$v+ansP0XfhfG1mQ|wD$dt=HV!auk)K`pOKD`u}w{eLb?a^;y z$Hf5WK5|VL2VV}@G!L?@r_Ys5saGw|JDX24j0YKo*47n$PG1V>?98go=B8YDwz9Xn zyRBjv2BJ8IX?4qboMvMM4_EOx0~9^T=uTJm_HUO1oOesB=bvX!c`jcKm63}KL}6dB ztgkYcOX+N9@-p3hUd4F7)A_*JxFz(KX4r8Ft>uy?ZFb72fbaSUD^EIWo{6#ez7loO+hct@8uRSe^~ zpJA>OX;Z~DUQuXM-O#+iD8=BF-=%*nR>ywhyVHS6KQFdFuUJo<%yufEvjO>;w$zQN z(9d1RNc8ZL7zW#I>YoZUQu%|-s5|07YKKK*BNzsCw^BW^`pn6I&T2e8b^7v;x22`# zSU*;x2kT{;GWsi|}g?q?X(?m#_YEGX4@MTIJM=m6zGVq4uQUQhIR`E-DD zA326;b;?TluF;C4$%8``DGw4o$Oz@GCzh{26VTtIPkba>%C^bxhSroB8pc2r*VOaK z*+AKQ+*Ut+wQ@zv21`N(;sz^*@gU>jyLH8$GiL)jzqZ|z2`PE+1w&0s^$TMlievB_ zlc(udKngT#manMa_}fr2<=3JI8Cg%&6<@YEAJF-=@{xp;&Q%YG4$SEp#y}L;WPWLu z74`Yb6_=Wv2-W_xn_?IbGX6S9=h5{-K<6SS-d(w3&XadTCBNzv#y}MQ9!c3~XA60_ zQbEbrz9l{V)VOm|&Ecles{FpMwf!uux3~QAVo+y{lswnMnYeJIVjNqMBr+Yp9^^g$ z$3I9C^Uq%o^4|P?v__UM<%T~`oRD0_XzJ z&gQ69=ns3}$w&sGOig+P@|*7}J0%+GGsp9|`dgCt^j&=<*oKq`xwfbC{quVNE_#q* zEl(0R%9!&=x;fJ+S$k;2^*~fKt!!^exgON{A1}>)-}$7*5XA`dK)pw%B#B9PulsFv zW#>j`N*$e{fDA-!=$ItF>Ulk=zmXet@l&T}Y+n@vJ;C5=+ocLCO^i3oCdl9C>C7->AnFx*kMqun%R!x+F|JA_`9?cOojH1t!Rs?Llkv~v zv2HcwTPf8e7>FuIj7vXU4(i;Djhh^q?c0iqfgWVwIA&QX1MA5dSK}fWhQtbgYBQU}YgCoE75^dO_*Q;A|}k#j*mr{Q2fxwYB02nM1i(;NQUZO{8L-ksT7 zrsUOXq3A(IPhxB)hR$givapAYZupyufeb`trB%b{cA6Lq=692~`kqt_^dRGEr$li( z?m|%KG`R1-Agff?-gqCMT%#c#YO9@}D~yM*$>c6pDJ>dg-`R+Wi$ zMx~8bGcw~r#yWcb=$-vkP-|H@-t;n)`{i^BZ5R{AKveiq6`wM_jI;DhQI6Cv(1VPl z^!)L|nUg`S`!S5pd?u}S%^;-^WFQJ#g!a=`ZyaCirESiVANt7xG_P&a>U@wjE5zlx zB5~8XAZtr-O*GRF^79ojwyuny`)prlPWBOD=fSAMxy}Ty{j%7`Hngm1S+gY!?J>^T zvTs;e>mnmO#jvdae4ggZnvC&NWTOptN!Ft&qe&}NG%Va+DJVjQ;mv}u+I^WleU>FpR67)3x z{>X&CS0%_Mm7kXA!Ft)=lIe0V5aJkt7IPD3bxxG?C)J8z7!)%yMxVjQmL~ij-BOO+ z9<5rp|Hm}*qFv*RqE)USuWT2jHL|bQUkz$aj#o?MNNBpDj=UWx8#cmWz2S^qo8~6m zohW6CLlq=?kioW>^GdM4S}CeoZdF45#m~qS50#E!7!)(i(OOo;7RwUmkLW0S?#`ml zqfOkk;KTH$Y6`7|ep~E%kaba*Va|ydBTFWf%=v=6nvh8`j0YLJ+SV1Z1Fr?O;z{?U zk_ks>T}iIW8^%Bso*%83GV7ENfk@wF!S$>mj$?JsQS96vuew__biO8@%@V z``r^S<>-3YSo2i9a+WuKG@Gdd*83w>sU#X!apdMh(x*^Qvq{WyDO zQ^M^nW97iV_JlDI#WC6v!&UFRe)*tm!gs4_4X))r#V{UZ#L-)sWs7eFweClW0UHzM z21m=w(PdOy83v*_hUq=D?z6a7!oOQa$>-m#tr*6GjM~}jidD2~pmjeUZdWVeNa}Fe zsKlT!2BNT!(JH6jd+zbv!QTb#@_uuFceD%p+m)@pI3-QakDvRhJbsR<%QG2c>wV#V z?yH(7qQ}_G;C;xHgQeJXHy~|a&N<+tGAOPKQO4FW{M=W?K##FG2A>nvTM1(e(8$G{8)gW|dn zWo#V-vmnr8Y>vS>6qKXr$G}VrgW|dnWo#V-vpLXXY>vUXAe3wA$H1?K8Wh)sC}Zmw zn3aMaV{?r6bndGk12bO?it9p@v2_g0u0fBnIR@wEQ0}WA12cFGit9p@v2_g05<-u$ zIR@t#QSPfBgN`bdbI|$sVNhHbqKvI$V73!_jLk7PS1RLrU`CZeab1WqwvOTFzN(`_ zkFhxhXLDurE6fZtD6R`p#?~<~`wTtC<`|s2mht<*3^#+~x)5b-9RsuI&|_?l!8v#t zzjMsgGbpYLQO4FWFdGm(#^xBDOPDcUVaB0Bab1WqwvK^Wjp#8p$KY(ojB(e`eN|(k zL2+G(GPaI^*_r4uHpk$sP0D@s`z~gH8Wh)sC}Zmwm}QC{V{;5YN7avknXCrIbs@^w zI)=|kxemkFhxhk9?GC>BsPMUn3ZZGPaK4kJO5R9%FM19>FPR)Q{oc4I&tbGPaK4-*FTJ zJ;vr3d?%vZS3ib-SBqdE%Gf%Ff9F&T^cb6C@EtYdJp8+J1OrjV)-n7UfMTG>*c^jr z1{v4GpJhZa5M^u~!_R$H4D=YAWAF?oqhI;6r3eP1jICq%Gcv_MkFhxh&(t!0AO5T_ zf`KSw>lpsbQZdkDY>vS*&Wzu=KYNW}Aj;S}hM$+J80axJ$MADh{eI==zD6(*g-%&PT}KaHlV} zyZSrs{0(>dmb+r02hWM0src@r+ls&8PTz8mU?9raI?L40$W>PmuM|Ha@qLLia*eHH z@VC$D8|W$qdW_8s{sKIG1Ks7Xz>_99eJ7s27azeulsPILgTE6`--}la^dN)36HniZ zclEd8{S4^{2BJ(&`pn-b+fo)@94+|@#+@i5w%=Z;`cLyJiV<;3on zB901=y1AZkbF zI5Ewe>(*(Li(oBrw>dXUlW@iN{8+6?%}7KU17|^oLn)QnzdFM$)}9zp6RnH>l`P-uG?jjhw3Y=PWVGEE zD?a>YhI_pp$0&R_SvkCih&+vv_Bdv&!t0ubd4CNR%E02E!9@z(h|h)6-K*p zFXRzxe~uTKE+?xNZQHV}hQnVIX;iMu?^*iFP4g6APRd7X=Z-kNWM_3gkqov8Lj8Xi$b%ZD?z2N^Snae3!Zx55{E$H|nCTNeMlO#}l`cx^0eRE{WF{CX?J zKo2thDP2yy^U!d2WM965yGIn0XUjB+U?3{|n%_EB)Y)5DXBO8T{-`*;zP~y{WAp4~ zRH%{|T5f=U<}>m==CrIoTE##QGA0q@cEthiiAy~9sdIj~Q>E4L2nM32?x`Tkw;trj zSd(?MQ#M93(1VPnODlOu!6YUW{|t?p_~G1vaHU_K62U?)d~XWLB^=>Du{==4stK&3e5#1I<7WGG1I(K@6EiM<_VP+Ru+Uqq6i+F_3{M?9+Vr8z*Vk z&q}s<2TkeEMh6PLl1XK7HCQkw;Ox3kG8TVN}F#U(O^@i6M%qR#@wx1IR^I4WeUoc~3jc$Fg$h=E6CQ2w5xfX;Bczpa?T z9!4QU#ansc0WplnoNe-pd(zM2e~-bfU>MwP6!QTw@Td$*#iOfvb581m8R|_gqmGTv z7R-5Xy?;)1gLfBhdN3pXnlF{V28!*}>OiLVL|#GT;TVPyBD=?cb%7ou_-=52>ly~4 zn7wj--9X7>SsuVJ9%O7M#P6LhhZR!W89lIp?2SIc}%>YVLZqfON_NLN8rrl2gNW9L~#tuI<_oxB_84KkHNoG z?hTCMmd-h0>;FejL)~U6C=6VNlGba|-gv7tX*IZAGXXR}yP{zCEuRAOE{`jRzUciT%?2`0W)_ zA9Mu`15tcbbY*w^XD?A6WK1N+tP!!nJ|i9!!_zYWJN7{_Om9FG z*JOH6crRfO|IW?G$-l>ryVjY$`+vB9AS3Qx;pIs=);+lIrr&W4${f{y-apdEc4Tm0 z;3JGY4?aWlt2HS9{M4P{e`fHnmhVfuZOLaO9x3YFD6GF};Xe=9`~+ca zu6Ns~mBfiw1MJPTs!Ga6*&lP}*Vp+`=s|}6l;Ou{R=bt+&}5x`h73ftsa#3CdvJig zO0A1d>GOt@r;+}K0(y|)&(8fA0}jk}Dvs9qQOH14e4C2mr#S=dr)lMu)ZPxSaTbo# z--197GX6SJK`d-D$eweD8A}iUD4oWfhase%latrne%d# z&e}o`GERJ7L9FRF$nKMipFiRoe&p=0pfkgefvE5^ulsdonYF<45oeC)ba!w$u|3l; zdwLQ-*KS&sPcEPFoMNB{8U7Qp-&P6b3d&kvwTNIKs!_#q^bNOR_UWD+f9M+7jBon zUg95B)0Y$FQ*YFYh=GjcDrLolPerg2&s3J*_qQV$h{AKStSKMI$vG+Y6aziT zXxO5xSpDKidtDBWF*CY^Y;dko1OrjwZFT#br{tA-*`d(8xdqR;22BMDkiWfB>e$9TNJkLwM>Dfu9O#a8=U(~;} z-y?p>n|5bfp_@x@Ns?NRx06QY709N1*EieCt9P=g80bMp*HvXilUn2LTEjTTjrz~Y z9fh@G=kq8E&u+{0SRvUWA5&voidXTa2(>Sr<)3@wc6=VG7ZZc19ov(%r zL}Blt@4nU;E5G>p3bjG{`w!Lbcpt=eBPE2N$H>DY_1g^eAR|QYCW`NyVsCqxTX$f^ zF>>~`!s^VCfvE87F|*A``9`HSAwDX+Z{z*kf0N?(lA5DN%3UL#RSfhXlJ zn0fY3nR5!PiN0kz?`3)N#~&kNAS3B~oaoVSp1nCY&obsG_LE7=f)NZv;je&H>vH#( zF9xIYnw3{XFc5_^XUn?&Pz}k2uX)`*hwLmz^9X+W z*>>l!-DqxZULmykyQ%zbOZ}{d4D=wQ$Gu&_#7kK%EaLIF>G!(!;Wk#^dQ5;&}&P09>_oxw=%b#URy$j zX;Jp{DE)&yC~JQ4>Swvd)>((`&^Nh7SG6vR47|?296o4oTa{PvTDWQT$n!uCGB!MW z&~A2)*lH~tV;}=j=I{S=FF{6nJhc}7pcq^iqRjc}RRd&T|0$K{nq9fnJ)74r{%=Qx zjIxj1wz=pP7L0*)ABs;5i&7&T^+LXiyk3H_|2qcvTf^X9$h{`ACt_WQGJlWk?dU;9 zdOWpW@}TR%bs-8zjPUaqwfnq1ZewO)P0B0Q=DBTmC~@1~Kr6!L`s?*}jDa3x6uEcX z{-eSzyP;YU{x1fiOpnnk!pJ}mGX7ncMXXMv@3^ZK;s0VF%JetAB8&|5AY&$l=T_Eoo8hK#Xywl$C2YMdXRCN#@@aw58IoQ z?~j2DL}7mmKPnvCaXdHo#K<$pI{>oHs1(`T(Sr1Wdr+qq@O^Aqog&t)5ck3bpQG1_0YCk$SrwGt2B>X(kgABZy zw6;*Vvn)5^ro*$ouHO!^C)19R?`b79^PZvho43n}%Ae)pogy}`PU)3YelFnW17^@J zQk!S^{5)W6M$xWQo1X$SqxAP#yvnb3RE+$y=iBnJG9ufnIYg_=3+#t!J>${I*?FHT zFm7kg!IY_?CC9YV z)bf-$cI`l%_}R-P>isa+9{6&c7~3Eh@5;1!zOB!rYM%w6IXefd80ZOOq`YTWm=Grl zT;o~zhnLoe{+X-S6OmC4P_(<$<|hgrBQ5vWp$Y@^cgfI$jIZcP!nqJ9DypZ64l6E( zj*sc8jtUuw!WN-toW7Sr`<~GZ^dRHk$@A=U*QiC*`fk-Ak^APTQ6sUg;T zEwpa4UZ=*^#a8Hgezx6-R*N#{;x)@M*7II7pe(Sr=yk81OCwQj2kW0OL6OY8M^ zWFTtR=d<)#f!JeFcA>74Q7} zfxd#sKvbp2C)-DE#L}q5F_s_R?@Y|sOU0Nq`3?Jcoibw2?7SlM-COoa+5uXeW@fYt z)aErh9i#iA&z=0U`X~l^kdf=>x9qB0;=~|gTh@k>o1Em#`d5pdtk1t=AFUrJZp^qp zM$oM@z@qMc$7Wh4bg-ov}8r zFLH}+Z!*qayqz)#GI5NjL`hmT(Ch8!K?dytwRvq^UysM5%FAzxJ*CbA8HmbxFWL5v z#EZq}x$hPl{+N8CZ9p;5gN(ob9&JBAGeNX`iy5V6N6RUd_1yr^}ncDEt*z*5Ak4NUv;e6$9_vct59owKl&^ z(buC-^)~YRDmv2wJ;?aA#H;pid&`NRPVh=zvYY_}Y zEv!1gzDoO2|2WSxnawW@mTP`lq!?K5r`-qH|NdA(jHfkAWYafBq6f(C-bado9%TGO zZ$+2W+tKILo6-DV_Lf=7?ulR^3i})F7hT><&a1yqG0=mImS+dquk@)P)(+y?Qeunl z^6>mWA{dCmIjUtjt%l3z&kc__D%#;|^BZw)(eSqFNbl#@C#Y2F!^(&rJhciNx zM|$HPZKW9KK}N-v1Kc^Zr$NuDr_j#mvN?5IAp=q72=$qtuhZEZbY5qMW!gK`&GvUW zHK%r04sjdOUI3m`Q(tg1o+k2s@RAo*`m8!C^dO_g!NG3*6XpFm^*gtFdYz{nieMm$ z`m~$ziyASluQz;8NHNfZj4OQxxf7|k>pAr|Zw>LTPMaISKoqtJ=`F1u;(fklj$)t( z8IRCWU8Q{!dQQFJ^iXe0>!}e8L@k6XOS)>mJnt16oJo&9(7M=eRo;Hp-M^xoKc}uT zptbjV`@D*Q9%Rs1>1Nyw{#w=2d+3xN+mV5&iYJD-gJ{2jo>Ny7mAs@TS|^o8QPRZEd#r24Cirve>TRofn^r%rjtV^$bB}hf9ZpblYOKk!j#jMg_1~60 zQm4m2MmEYX>Cw2XKd1h)nD9zZ)prA|3sHDZl*3!EzSrk+tU4<6AS1s0NcR`IbLu(u zwiAuK?~3Vt0LVa8cw3#VU(So8{RaFy$M(S^>_2^+J0d0CpHtuLQNqjqfu3KX2N^W` zaLw$D?#?qG@#gMqu3{hqQ8iA!=I$>N@6V}^fBkW2$)^5_aiRP>?kmmW)SUW5%BDJ# zF{gGj=G33cFG4AU(&yCa9%LN->@D}+4l}3jG4jXIq77OP89iUU@P<3Tc^NaOPOr(b zYRotv%91mE?vw68#>->IyM^YK@#oYhKffL-cUaHJXttEjKoqtDW$=v8=KYY?UY$95 zknyz`?{@s4j6bLTGEW|_bz{9Ufeb{2w{Gz=xkA@h>!+gJKTL5C(EDGWQ`3yxHBUk@ z_Eh(qgR%acdP0kTQa{U~pYG6u40@(=&C@I04VFzwE%K6nRzn7&z9U9XdScac>N!iI zQfD004D=u)am#eK-kw;|O3kTHKmJ(gox1v24bNlWvPtfx%yDW?jYmlDw(qtN9gR(Y z{zyMtWZYdn(cKUe=g+BIU7i}M^Mk%~VqJ*BD{EP~zn>8r&?EghD*c)xLpT%N9+l(# zId#tb3ql?D=~W!83sLwhps%YWwsD%#4h8R$>?tbLO*e>ny+5Eb4NCvU&wG(6u)F`_yybdx?Rqvq6W|6br`eXop~ zQ*+LC#;V$aPMPG*Q_n{*5Y_*$g>HY^p`ho~@BDPiDf^^WO2>K+kDBL-D{*R0jcm*M z;>RDI<+K-o&jUTksM2qqyN*`w^ql(K>L7h#wO<4SQP|(8_x0c6Os%R%YV;uE!>#YT z*+P_+ujbUtJ1loDE*hj_AOlf2N2NWGbF#?K=IYg2JP%s;bIqD=cw7CpFj{sgr=Pab zgACRi;FV%Mr=GF1u>96vLq-OojIC#uQ(IM$2PW3`xOM%v7B0V0FgCy2+;Tm?I9Y$M zTV8$B`&Oq4vgKb=G0=mI8Gq#$&oNlgKw-uK)lNu|=mxZE4!)WbknK?@2ue#R_ zl4^E1!zvOhXWgi;80bMp{TsAjf{yA7^%d};PnMBSC)JB!APSF`GFi_Bof2{V6yt37 zC~ZLRF(1VP}UXK!|7pA#A)px^7v^(rvn$lCnKn9}HdPj*eo73Dk)px^7Hn`~Yp3_w^ z(9^kYl-O`6&3%-<8;&*64yvqoo%07fMZ`eHY8fRK{Fde>HR5%KxCL2du}&Q#7>L3v z`~MjG?l>um=k0+b2jT9>pd3lENHTCUJBok-ML|FTMTsVIQjjQ!5+q0zK?DT>2?|QO z?i~RmsCOVpPzj16IjMkvyj30cp4rv!`}?Cm*SGaNUDG{19jmM9Eb=D>{nTOlBr8gg z@k!}q@22ar#7N~kVdvW7{v%5sR63A>D185pQ}*q^8-8%OV!U)$iuXj@Oz{}q8(zL( ziZ{GdrWi)2b5|ct_Ub)j-^cc+%S0BX3{wo0AY&*o(w@!~P1U{O3;%i`vh>p-2@FJS z%Sa}h469>Gfew)}shWWjWR%&J>{aPO40Uh#?h@l8Jw^{wI*@@Vtd+FxQ+--wPQ8JO zff8i2eLLC9nvf~BALP1Qa_^EzbVc6;2BNT5I?mGTR?FRaM<|BhH^sX`B^r4*zc-9Z zdQm%_+f#E>ypz2$#pG7J&ah?phw_>Hnt>8z)S;9to9v-lr$(!^)$aoth`MK93cSJP zcYo;RD4=!V8{AerJ6)^`j#H=9DYxZe%|Hn<@CnIhf3qqX+pZ-t5Y_wc6z`2TnWC4v zoBW}XIpxOvnt>8zU>Q=czkPmmXv6-hbf5YoCD!8fJfGrSoRcY<(aqm=wxvM5dhF25 z=;sRtC=?Y?jE~Gq2aUSt_*c(CE_^GjyW40v9XiVff8h(KF2w}|5~(*d^~}HsPgxv zdb!SLic@q46Wx90<_%6i)=n`{f($GLdV`TV!TfoR6yxbBsj;5^*0re~SrVvT)W-D< zN9!*q2g&zqF9n!x!#=68(LlJYHtxATm@?sBr2{3%K;7h9{dlFI+dEAX7>F7%Bh?%J zV3tTKz&W3ivqmtio39usK}I+q#cr+UQIO3^vi-#sxoLLth&mr;U@wDHN_sLR{Mx%=32ebT6f5eiZEy^IV*5!$8y zrDpUw@p*(olzlIw1Q|ECN%j^_-7dab!#Y;ovL`|z`b3)tLJUL^+NJ-cW<+~lj8KS{ zzpasv5@Zaon(Rex*)H-nWWVQkuSoJK1neOX8HggZOaDvFXk9nirx5J@xs;C*Wb~qu zY`GIzV$)XEaVb*Lrx38GKV%?^&@TNiHRHL>6?_W8+N@tAC_%;zM~ZsGKF$(P_hBFL zx7>E4Pa!C@Wow9mC_=mRztoJT&(!uQ1nd*m;RTUap$)BK82v$;gg(BOo9xYCpgZ=wGDg<0eg@{2BM60lGL+_ODQ=7htrow z`1sv5mF2yyoldE5@X}}Hy?5_CCG;JK#ZEN{ILuh-cr%)%dDA~WD)>&{H{CRE(u|{_ z_DbtmnOra6(6#(+k@fGTdY>)I5}oKSfTnk+d0(zOD)_eE86TuVS*=)9Kj4t`!DSC6 zAqMECy`m562OK_Wd?CcZC#;T;Jbc*oSzEy>W=Gb1srL4>cAV)e%LE*5{X3VxsBfxwJbAn5I(&iqW&1R*!^C5PZ-JgTCKbNgYP-q@96s%E zCV~=V{N66jo7eT2&^Pz`uU7~-)IacBh=C|9b?P|}RSr1(NjLYR1Q`#Ij)M0d6Z+=f zrq5RmI6U8ZbBKW`d^cq8lg9}-yneZXzpiLqKcDL-4xdIMf%)QA+2{K-xcm8g%B+dIM z^O(?g{jPtdRKVePy6YDih{E^pIJG~#80EmX>SF0)xlL-4=B2GWE}mY`rCaRGnJ9Lh;sONT^k=I$k=x!1x5fb`JY8ORC~W|h=Hif4b!~)uRkI9-e1S@ z`mTv`_~?<2K1z@gJ(%KcsJ}xTsKN~4t&VbVzY8-Ebz99eZ~fCJgucskNQqWa4w-a| z%lUUxya(UkAzq-nw&a!a-sScu1>X*P@8%R3Efq}d8s%{DLO&lR$QV^P%_~v(q|o=i zE}8#wl*6tQJwpsc;S*BN`N`xcht72GD@u^j;f6Ht;Hncs-}_o3=fWt5nrFI(7>Ekz ze8!N!1c!I&=3eXvvG2RHdy2QZ+IJ#Z-9S9Ca9hdYbGjWECCJ#nv%GgC_bH)oAnx_` zO37hY+VBtqQ9q5w@$TMAt0jk~*A4ekf{a<;m-lj9J1O){%46@(8RbxQ$BQ8bqVUa< z?O;moD2GqzK4Fv~qx13d-rV<33cg#IX4`dYML86q`-G8!D18598+G<$m%}o;@dn53 zRGKc8o#Yaw(S}Q-4mAUCoa-($^foqko8jDEekxDiz7!4cU0@YaZcHgKkSh2{L|ff70D~rM%=@?Pw(PLiGrTWxu=- zVjzm=B~%~G94EP1a)d+AZ9~+I#Y&J7*>uuv@mqPxx8;$y&~8~ChXZYfg&2s!l6IWi zyRPs!OsqECM+q{v(Ydc_-iF#X2!}rRKc?n5R)UQ3qfWRtRZWvGsvFr-S}cih z$a=4Hh=C}qJ&tqvf%y>*qv_T+lptfpsuS)jH>63vozHR3&YltB@Iv`#LJUM<9V4Hz z>9u_hk4~B%q0up&I7^j0LjLmFQTM6VX_9Zw;yDA2Awn`riCaPpSm;xkvvAF5%QNMd=4GyCNq>Equ;?}?$)+xQs4U4IW^hm@P66SAqJv& zE=prBGp}uyr?AiA%!o8KOSKYYRJrB2`%B9-$v0$@2i?Ybd=AUj)(kNaMWad{T}nN& zY_uY$&!H~ewuusC?CyEo{h@i9XbGWqF;W?j6Gd#)jKA!#3tWM2-X|~FaJ;)CiVSlrB>JX zIW)cXLWqGVp10GS*Q^1gEUxc!_-4XoHKVr@WOP|~)NOZnn$-8JrKZ&LIaE!(ErMww z3fmYO0bH%?b4Z!dDAf8O6Ca-Y>)bduK!? z?~HbNI@29@G+7p-J)s7jGTmH-QsjMPc}P1MY7J1&wqM^l!vCv8am7FhGS0Qhbc;7m zk;O0b>iPESgZ%MRCPrCD>hw(a&#B4s3hgzvoRI0BB}zn0NkG{t^D; z&wZGngZ0slhC<=f(!G6chxzmGOI12hf{d_^>2qH6-}%E$U?A$%9+~c2yOQPAdAz%H zeac{e!onVkff8h3o*bun*XR8M?~PUrMA1H)OM74{A6O!^M_;$UzwG#Y#Xt!%Xy4YQ z{V-Ej)gSBQ54iP%1O}pRdLz@lZCtYa>ni7?!r`9&#>!GLP=btyKF)LxJxeR8*YnP3 zo{G=-JH~vc7$`wT(w6q3qHef9%YFZBQF-=deyWdN@%^M9t1AXdkP%+x ze5q6;|L1LW5*UcGaeV@`bmg{w#yy36Zc9#I$aF8=ohqx-4iD>~9S!yDDQ7a>t9Pc# z+iAbeaRxoo%75T^vSOeF8C(jq=VEexu4{Y$?3COI3`FtUq&*(PnEhBwzeB6kgr`cc zmgQ#jNR{KB3qK)wg06nAf2z$5ih)mpjB~BB+{kOGvPCh@$JxJpzcE>*aL$o|DC|Ya zzP+vQZ%D177$`x;%ty1_@iemhA|LCRbK!RXgHv@97>Ked={>J)$%Fkr-|G?Krz+eh z(|uw=ihPRpO!+&f-9J@6M|x(uU(8LBa~|g2;H7TQ`Ac|We+Ql?a^-JBJevY}HC98~+6xp)ka6aVOt){PRCyEaK|9Wn4xRiCznxP$kbx-t zZfNI+?Co+5?7NY3jy?TS>h=54USYmV`Qye6?6>xE`=8b^1IG-=SVnB#Y5a?9Td3!x zGmt;jJ;h_p5Cc)164_9g(mgeKgkP^uZ{li(l^|myF_seJkEN{Ry1R$_kJdVwz(7>E zUS-`n+)uk*`@cd7GS0WpbejxFkr`w~LOVZAhWYJoF0M)!8HmEKz;V8v{EbJqH3giH z669x+ZckEcFQbY~a)@P0Lm z;z&0%#EI^tWaX(tb=Z-I`FPWl-M}ypc`EI20Np}+~^tQ z+HO&t7NTri>%coFQDWn)gKnbboA`_lyw}pAI4wlkxYmJpXQIT$SqI&y%Qp%d9e6*d zMR8h)vT>~g?*K)KjoWo7NZsum6T8 zqHJ92Fg=c9pv1;m2lqsD1Fq3wdbI=wqHJ92Fg>SYpv1;m2luGi`7k$nCNL0X<64Kg z(Ni%{V&klXZYzZMVQ%zHU?9rIwGMNmr(&SQ##sm5TnP2b+~}FWK$MMZ9p*+)#XyOT zvktmx6TS~~qh|sGQ8uo1m>WG610^=jI_Snw_|DCZo(T*@*|^q$ciyAK##sm5d%Eq-0euF$7 zWgRH7an`}_KYM&-YDoeEQ8uo1n3@={4wTq9>);xiJx(;WJ%NEJ8`nDUj$D-3IP2i= zF?+mgzFMWjqBt!?*|^qGx=|6obRBJn%8fm@0q3hQkUfP=?+`z&0u#ZBCjdQv*hZDB9i;V!34vXTn5M|?92lllnv2oTx zb5X%FVVw``&n=46LX?eb9fqOC3@EX2n~&^yt$C^h2J5pZ8`nB;?1K^;XB}K3Jjd1f z!10wuaaxG7ajnCQ03zHwqr}EJU4FAX6V^I#oM=&;7NTri>%g%nN^G3dN}VXXtl zyB5W1Az&0aE^l#8|QSn<>Q&K*1;oievAADEsE1Zl#Od0I9Ef7jdQx(&hrdX>%jS-MR8h) zvT>~g=bR|9aZZ2%Nt|&N)hKoYSRV8}h*;aQ+VC8HloR zt%Gu|&igO}B{t4FsCS0bwu@uqaLo zQ8uo1P)!W@J7fk*Y@BuQm?8W7z;z#s;!6k);O~$bD6w(YK{E?zuPE2*yiYs>Q8uo1Pzx8pOjxDG5{qITG(&=Rm%hIM zX2LNBqHJ92pq5&l_u;2PiH)-kn(4)Q2GtL$^FHwmMA^70t0uz({tlUe5*ue7G-D0- zgX+9bJOfcSu65A&#|%5KRcW!rqHI30`*ZsK_^A>Y{8ScY<64JV5mqArl-M}y;Bw0z zmzdH`U?9rIwGMuRFcVg3vBaWS2fzR9@s+71N{2-;15q}vb(oqMaOtAN##sl~LV+=&$Oor?%yWJU`*;UWgzN$1sEH8Y!ynDTF&w0l3w#bg_r<#;iAv)d62f1~& zvpXAS2F(+N-H%kemeTH8S`?>+DDF$_Y{_wIq}P^@eWp*7qvYQhx^zvirb-tXHqI#S z?d&X!&XUdP7~OPmuwwjM&iM&@6__bX(+skYnnB(?ZcMacv*#59C737fC9-!dZ%$bd z9q;HlCo&La<9g0X^Yg&Y&+$!h&%kp|o}b&eejnZcI2Zl!k=PnQY-Vav%-FmB4e>6m zGwf9B49nW=iN2CYuQON_r-dl{R9Z*HU$#W|yc}E0h~*F&&W_ol7p;VRuXNCQNfg#g zVhluC9VX}Gq2St6r|C;^oQ%$yA{Xt&SD}6Kx#VMj_x^Kf%K;VF)`q{N4hyQ@Q%1E6 z#mP5AlY%Mo4f1&L_fwf-B-smgAzMY-R~Ol~gZs$O%d4%lO%d6u2s&da*>=drIbHVi zLVi-D_Vv=1{Jfm+sO^?ef(){_5!tp;$8K&K9J)i>Mj-=H*O899$o}ecWq+0VSo

    2. FSZRPZ7!%7C_x7M6(P?da+LBdQma^t zpxL342@FKx6VgkV-aPPc)plekK}HesT|*v8q)?V;jmck4_fi#<4rCxIob&A!dIh(g z)b|yU)r+tee`GTwtQF%kd%jd|445maj zMg5-*roH)%VxR;W70H)O7FjgDs{F|mZQm^@FyNO22BPpi(b$l@&x~w#N-$I126xT1O}q;Z92|T^1<@S*#{H@YcP2b`vhg`o)X+LkX=u#1&D7Mto1Kh|B(-t0}sS(goTwL1Iy5H#!nj& z9C__IHCjRmGUiZAG?-eV!qgIxKY&BSgQNjL0s~RlD$%?@--uw&?hlC@Zs9ObU3zDV zlVlIqT=|o^hw{;6yk?*T863CvOpbG=&9LB~cBv885znwF&R@1YoKHSjKHV{2Gw8ds zmU+&bnWFFc6v=*Axb|e*+^tzSAn5Re_DC9%0OJ_>U=e#$g4QJlDjmo` zRQRdBE;l47)~>x`padE7$p_0VWK-Be`C&=Aj(o}%ub;p`6qX3hWec-&+C0k-cDNfqf;W}@r1wTY+KH!Mn4o(ez{lz15w|Rx0AADHQ7aZJZVFI zMSk=0Dh8%|?Odj)a$l-EOZKVArW@JBK&r=Zi= zvk44Dam$x&ZFtADu0f^A`gTW@AcH;8++HzN-k~f3Gxj|jxSO{r9mqfwfB&)C<5VDj zHSMzk#Xt!%+L6DSm4Bzm11rGsI~G9zrj4@gXNjM*DD<;K?dq3ziJDc1W6|lta=lgM5@AgV8M0j7K*<73JWM z>lb1m>L2n96Y0A{e0q&_JiWYkl*6*AeSMT5gV8M0j7KMoi*l&-ZI2KGQ8&GrEZ@3* zhxp`XJ|C4-a#oZ>m3N=^QGyIcvrIFd`EzNM!=n71LkvVMA@4I&u51_G9$+1PGPm;i z!S@>F4LEGOsfLddWH6d#no;4A!U2c=XUm5eh?+v@OFEU!So2jAof;1P|X3a9Cdd zVgwn8s(GoXoV7PgT>G1K)Fn?O9Nr*rBq%`!qgkdIlSYzn5eiQ(-xXpYYA<;MI=_}? zUw!%PYx{mx0~N+>j-Uh?jAof;EX}GBaCmj_(hvhtzyDlR7F|I;wx+R;jU#FX9MXSy zCxQ}WFq&nWard;F0uBYcy%J&|Y8QDNI!=Cy?ySImaW2feIpEM_;FA%QAcN5?(~J)N z>jfMh`L$+jfOf6}&Nm5@ax%Wt#Cro(2Jj+_k>!ieUyVtS!DyCghVg~uvM(g;$=DB)^-REikjTS>4EaLx*%uP~ zK_cHll6@huA0&IS)b_Pnhw+8vvo9p}gA_aIO@5Hb=Z<7wNOWpb*mItAJD2u_RUr0XtLP7?j*bkCD6C3k|N|3>RkjQV54EaLx*%uNr5QSwJ^M&NIFC>&8gZ&_prz08i zh2*m@BxE28OFHHY$!A|k><7u7GiN_YEm$Eijw4+WonA)y2r><5Yb z7Rit=B%ggDAp=oZ>M>tPKKnvK2{PCZ5_vk3Azw&7`$9qnqVV0&xm5CMM8RjzM(q2D zJQ_*%f5e`Q$n%h7Z$|6~Df`5_@oeO?XCss#gU-glQp)PWKCY zhTn0FFQf?jLP7~L*w+$yR+8G^QY!gcq7d0a{+5t|D15UqpH30>>4Xwwuoo@z_axbq zR?Nqi&px)0fheqRj$^#_xa_S5TWV~b$>)f$zGWQ8c+#rI z4>Ax%eprO{wn8^&X>UCqd+R|7GT2iOdDf93Z#@zA)`JX0u@9zfe=^2fPlUboAd0>7 zkpCUY9(uwIKy+9!YQRGQSSbsTmzk&7w6=5$> zC_x5$fFh4gGUNp+!d{?|fhhK5Wxe>syg)_R3lvI_!5*N<$CK1vpj_{rD1}JHkzGR! zMB%qd!uPYL8jJT-X?;5NUH;hY$l%_yvNE^>zag45c|1v+7T>_VofN~<`$_Q3OXJ!Y8IGS#p6c*}s-mJqd(PW;|lEla#g zr+&kXiFD$3N_Fk;6(z{v6TfF$(YRWj`mIMNeyBO(RaJ$L}G7x2d*DEX)={)tcN3^F~d@5dD;WZO3A1p&!L#Ff8 z*L7>Jbf5$oyavbXHM(^796lHMxr5&GLI$FG(J9trUu23JYW?cSo4-Z!PwA?3padDb zKE`WXT1UO1S&=1K&m=GqHHJ>(UZ$Oguhfa$Uax%;+0#IKX+{Y$czujl!?cc{YOap# zzoxB!x$EJ6D(A>RRQRbnH$CMxGakly^@-P{ zIftVt{%VIzvFMNd9@2N?HsPnpDb5Zq4n261wG#5w5V2RD880?SmhyO}NN>&iY73sq8$8;$T>=A9yuX^=mi#l{32Hv_xMH9L8K-F%cFuuJ zaij7rlCSgG=!aW$>w^qL@lIxTTOxP;65W1hH>Cq5$f!f>V~5vd3cmv9V@cVsqF?rS zE`fn4-XYCyOLA@67~S=lzRd$A$f!?@ax*f;*|S_rdK{S_-B;IG#6wz$;@!mT+Ww3? zE4qG~_P~!4WVBwMEJu#Y6q(<#j(a~G7=7nuZP||uMB!IJUIQXsqm3u)77iuI`0e{- zd4yWK_upV0eIIh8%@%4K7Gxj_zZJ(xTVFO9YVKpfnuv957VXdPrG5HuUgG!hAo)ib z_?qsWQGyJ%0mvQ!RE$;$hL*WYy+LFk>b+l!${RXSUptX?yu7Vu5Nz`l10~47RT1*Z zvAk}u>4Do47>KfQ?IXqbXq4=ukw@A*N@h=v?30l^`w8~T$X_#$(6wbv($$Y$3Su$& zfkX*1c%{X9o~D~($@3nCD0|;yFMi~8PrOK;{Mg$b`O_2ZagWD{JR&@xyq+5Gdr|hj zhZ1D4KS=VxC)g(>y$|g+(2Ndwe&ZBctp&5+%rBuaV^CQG`54M%i;D zG7!b1d>(IyJV!>^b0kWT!CoWD%cBT+j*PPBNMs<2XDd9@(BAQl=g25~jzkGE*lQ$t zc@!bfk&-<}A_Gxa7h;|xC3}uU2{PDgB>9CDA8@Y$ibo-uPM-0QfhhL8N1pP8_P%$LJnvD6 zviCidAcN=sYVNM?1u!1|qU_-h8Hi#Jg5>c}XfJ|?$%7z;XcBo5Lez`qI#LLh zlUGNSAcI%)c!ekAIWl0+k;p(4d!{5$k|N}tGGOnNC_x6V4Dza;zOBG`zzo;}CNdDk z9yZA%rU-f24A{#iN|3?pvAn7m^5hw?Cr@M`iamvrXHOCG78vrRioGq8cSNB*E?!+!-=`3a zn0DDi2{L%CombZN-2;1SH}EM0ElPhDVjzmWMv|9Dp*=?$f0hCJv$S($o;C0;gS~YD z+2rF_`?Cz#pCw9=!G0~tTcu#%mN9>p0sFH=2BN}G#rDB$C(J7oY&p!f!Q9icr7~L< zv&AQ$bY$yOK5I*}2|A5iiq1kZ10~2{+f=qC)%K!n`Nop-;=QB`#a! zaz2n@wz{_{ zejkXkaa|M5c^st!B{t6K^63OVO`vs{Gd~FoMA^93Va^pP21;z4)8$hZeBMFpFn(AP z7>KfQt;3v;QVf*XIH$|!K=^cr)?v>C{7DeHm-HxDQuM3IP2ikpV{vNPhndWr-djR z*E;YNHcD)qb@1uW?0RL+D5`u|6sLtK8`nDU6gEn1oOST&&+PAm&v^0a7cMJ{;z&0@Dw&mY@E~O)1TaTX&rp}lfOgGhedH(h_Z3515aV2#Kt*YKK;qPgw|osA}bvh z#c3hR#8X(7tSwGKRmjS?HT`QQ^aIv?h#XjQ{; zEXwA?qF6V_wGNZ>2s2P(MR8h)vT?10-yna7tOF%B>@-<@3E- z2cE*VC{7DeHm-G;n&`6*l-M|@%k`MgDQg|3wkI$UW#d{0^@IFHDF#YxoYUnmjn7+a z9p6xs7NTri>%ddkD6w%)ms@Z?$FFtZDQt`4v=C+ET8HUzR6bB*oC1q z0s~Ptu63B6Q!!9tkKsQ8uo1;3;gB*f{Ip@k93ez*E>3#c3hR#`Ze&FD3OfhZf-I?TCL#XyOTvksn%WVcs%3frPMEkxP4)`6$6QDWn) zgJ%=j?Jl0ewkS>uQ8uo1;3;gB*f{Ip`G@Tp!l$q;iqk@rjcXk|;^Xg--v>%;oOR&b zNA-iTQ`i>8X(7tSwGKRmjS?HT`LMG-$N3{y!+?T%gZIrUDA!-!=T6@Ir<-)3kZjUp zkGqcU-!Uunu3n)>#>jp7<^2QqyBB847>ZXAY)XsY{FKI5$Uuorml;;yh$p^|V^|44 z$@=#S%OCcA@0MNvYfN9_Q`vM`f{Yf&3(Hjx6T8k&aXOHJDEqtKOT~Pk1Q{`Xi+BEq z4o(YEHh+mZr}7sh^;FI;?-NvZ9={u7Vd^F393}K7V+?vng5H%E`Ql34Qy~LU7v;~Q z#@f7IiRW@qjm4bbSp1Tp;O4BE*Q=dAyMyp%%I&NRv`pZ(~Fd;P(rI3379RIUE`W!7B> z+;l4WaL!SJjOf;aa^3WOZs)=A43r>)N>)+{yNRWX3`F(MO}8PG-{B70#5-~LK2U-T zTSF6T2}+P*zvjeRf(%62ubFFQ_^E8&x{8Ig*D0%IYd#{ZDqL6_o`rZY7#p;_6>p%%ImXO`+Kg*N6 z34`NxAOlg*iY?rvsk~QMRlSbB+>Z z*c!@D7%p98Aj;Oa#GIqV))+2POzFRMAj8%Lew+WzKvcLDt@`SP=szW&RHMF$L#oNn z+XlGb(rsBUU#co|em&5wy{Uj#|6)}+d(%Ld$Bd3Myhe-Q;%4oiq3*+#W$~Kx-ERu! z@obz?6@RTHH(Z)$7`MLLJ-AwHzgj6ee!imoXW|@p@8x`+e^Vt{bjF)*o58)Hj#=*Ty9;<-Z>=b+E}3a^K4WwL!0jaSLm)fdfnQ_l10 z{>!ua1nW+(Okf}iON360^m#7WTktEzKnXG;Co9U&d(Clc6l5JkMm`-3y!-nE2BPrI zl4a&c&j-IX9idrbUEE*9!H2)EbQ9aJAARk>cNu@PwcLn+9;z{niM+b>Kjq`@xQ)$BXf?bEuDhbcMETCy(9+x3Kq*MSU4 z`B<>{b$44~)-fz&MDUfDF5?-9!aUL5Chd|v_ln*nLkTka?5iMiP+8S0$T}X}H!K+3 zE|)4RWFRVBR{0+q5w!Sw25}t+%LjA&;=u~?lhd!cpXTBIeA#cqf?_}Bj4%Tw$XHaS zqO84mym^EFygxM9F}-pE15rQySwYsibt1J&tYiFj&jj!8`%WsKoV zN)9xuD04qHj&A;o*U`E5fS~!;ZzSkIM#&l#<(4PLyIs}Tr{SvugR@7cBrp(#r9k(% zR~Q`Rn)94upadDGDpZuuEgkRn?8o`2Jb6g4@}HIo3`B)XmkwP8|C}wOdV^ALRF)qu z80nTQTG%VHsFM7=;b>K&^EXtM8}1+J7SF*t{>XJ-;Ct6A21<~zY;R?mDKFfl7$`x;W3N|{SN!cr%>>01I<7QGWKUxl|Pjm z8tOGNWFRVB6Ia|dF8bTsgOrY?oodQs1Nyi(cg*X3QM;xry0(woVn$wX(%02xwKo0C z``FZfRCLA4=Mxx+Iv1@e->TQg{pAFYGM4`ER`jFC`zr>f`_HcG@{?};+|fDn$LZ)6 zd>Fl$+D9=kU1YrTZFPCIS3kFP0UiM)-S~C1=x5I+Fc5|H&2ippwmsVGoo5sSCCGTL zM|IiiSU-1JKi0AT&0nH*9_p6BKopKq9p|y*FGM4)UPySV7pZ&(R_&uoG_I@)-xTf8 zY^Y+O1Q|_Us3m`2+1tF2i$9l+%96tp7>KfQJ?bN`y8+psE#`jkv$UJ#-Jh&a=b1al zhc;Q3&TAwbZ~Wx1>3Y>5o-DR69X5x|u&99I{d+G@pEjJosCdS~p?NZRzQl}c zlV9D)vn}&f|A(9-!*M>TsON+6I=FOgSy`0Pk^Y~ht0as<2I*_0=YyyNbI1&v^C-nj z-|$xYuJ!RbM+q`GzWB{1>3U@Xb;L6)Y5_4;59ppgy%P5y$Uq6E%W*38biKmzzZe!Z zo*2^xS4i)nMl#4i38u?&E-PLg4nI{q!=fG}#?xWBnC@_5yyxf3I65(&ff8hxC)}8r^LPf=T}CY=9UqMAo>5V) zUt!Ksg6VRcznjE27|*b%4a7LtW@^SmhvI7@N-$lHQyt4ltcmdqi{cvEz0dND?rJR@ z^MMjfm*e!UWF)pF@eGS%#(e+Bj53>flz}=>g6VSHwyuc`D~V@NYnP$d!sB%y!=ji? zt!su}3y){mHiJ?8McLMlQu;r%KFHv2Ua!N&>#%9D4vR8*O4lnz@eKRCjH3Q3!}eD; zfB(CzkfC}UwXz+r!=}YLEJ{D2?%@)3*xt)N74IQ%oKyPGmRd>T8Js`8)9`OkWqSjQ zQfzwXdZ!_t!R8bt?WrYkXr*yq56R*Rj z#pzm<)$yO>tJp{e8A{)O)!i7wqF9F=+mS!@IZp?l?%Jj1YTnt3a^H({1dqIz(@I*M zUULMGqs?lY&?^%UUm6%p{P{J-$WJSR#R>TPU>1i&K=WN@OtYintzsWot6d8!Z5^ zAmiLm)n)NE{RFR(JI<;$lcFE|K2YTY8HmC+>p02%a|D-vcr2lGvD|jPTUFll${?ZF zUVmy=IH=dBjbfk#8D@TN%E~#C5?p#udyPN_qWaaSDr@}uywGc}H{Tx#8hSOA4l{RF zY5jSivV17#NWp8bIVx0z%=|W>pmf%Lkuu@S@7H_mq)Buf67d|GwZt_i~DX z5@eWFD)RK0{bReU|tV;6fVWWj!d#$?f$>6sweMg7L=@1Kt0vYpDM@#J6;pK_G;F8 zRc^O_UqPn1lZ0M--IQ;5F!G_RlHUhPkYU!|O<9%dG9oCn@U;X6qVm(u#y5*53BC3@ z_4^S)NAifxI#7a)re9Z(b=OW2dhK;wlcB*cx89VHkJC9T%Iym$2wr=|Cv=>H6@~=4 zuC!AOlpteOT19zf$#|jHUK{Ti7_>U0_tlVrD6DU^8qlJ#GAY*OK zit?_9W(vLby5aPT!Sx#(Djmo`)FCSA(krG5z4p3m*svhu+I5P7k_Eq2kYy%J6TJ3{ zDLKwxPYe%Iy8lLByyKt*8T0m6kgHd|F7(=Kp^YPgP4&D42BNUW(4N(d%Zv&Jbu4^d?S7;WFRVB6Yr_hD>%L+L**PtUN|Dd_vARQ)$1M9 z>b*AM4I(2?w4z+O?hT>WEKk1GFLj!K=ggv~()rM8{z2hRX^0Kt}G_mE^L&=L%j=rv1S?x(4HSA4y;!3dg9l zn=z|HP zP76^se<7PY#lV_jtn?(?A=@%cd@7V6!&n8%#GE4oQTF%${mzjQ)2DU;{;QTC%H~h6 zGav(NgRyiHy#D=vdn#lY%PJAF*ixm7X(7tK*~FZq1R2IcOg-U$*F;1ai!|}ywVi8& z{erobu(}i9IZBXWzw?l7Z9+{%l(D}PAsb=Eu({|g$!F0^%^p^444+8Y&}lw)vzX#)v{n)WUyQodLIXMU~NZ6scV-6TN#Hem(}|~ z2BPdYuXklo2TG7ZR?CvDj6;^oN(V9!WlKHri$V!9$ZA=#m2t>&S?NFqqU^g#{Gw2T zjDar|kZfffvRqa=kbx-sHWR-OlpuqwmL=OIhb)(s4rCz8)*k(RkUeU^cBwoRqY56IYDW2Qll3l0%Il(G2HA@GY%|I_P=XAy6%}j^s@FxyR@7&k(Rc=;>=Wwo zF4>Ak*k+U&WGgDza+23Y$yQXb1t_nJlC7xVS&PocEj{K&W|GY)Gf;wzYKvwIw(ZpG zqH9jCj9ej`(Rc=;$P!oZEI{knS@5e!b+Q>{21<}YwxWWqLG`+5`*%-84h`#^z(5q1 zA*I{%bY%NInt>8zklnCgD^tBLTCe~-Y2_M&Igt*mRpw- zGXz_o=2SMRs}47hY$Ur>W}pNaWREI%maNO__2G3RY?m6(Kor@d3bwV>>!N+)>`?_qNnplX_j0>`|j^m&y#XM-^<5_cg7Hl0B+mD^p$!Pc!UmYDmcB#xj3E86xwld{)QB28k9{Bo=DBGpR>p%wCqYAbk)$5{U zj~ZpW)OZG>uoN7J>`|j^m&y#3AcO2t1zVizbe(^@+odvt z>`?{VrSiHc*`o?xS>+NXdsM;Jr+Qt~_pYatta`m2CCDIqRKaWG`hAc+YQT1>tOFT{ zB70Q9)~9-1H2H;_0=7$K21<}|_3xpAtpQspn^dw#4cIP~8JG{UM-^;k%Il)|gmgDx zn*zZ*WS7belpurbQ3czN>UB}FM~$*wYCHo`;aWoWs8O~{Wd=%+LH4MEEl%~iDA}V% z*)BDnfhhb6$j1zYnrU4cIP~87M&p*`o@!IMwT-WRDuK zU1~f7QDl!Q*!onji{3f*{$Lo{r7{C0WREJ?%9PhdQ8)SeaPJ8QkX>rL4rGu$s!;Z$ z$|jZUQ3JM1jb|VVYYh2lymouQcB#xj2{OnYRj|dWUKb4-HVn#;U1~f7QQ?|M_Nc)J zWS7bevPTtcm&&V-WREJ?ew5b`$sSekj;4Me%U3=hd`fny@eD+fJ*r@fN^O%$_NW2d zr7{E4C3{rCR;Ii&j%>PDCbdt%cB#xj2{OnYRj~c2wn-&>)PU_$;~9v;`sO%fj~dJ; zyHsYN1Q}$HDxM>|RK31S_Nc)@vP+F;APUE*jzjjS0o$d()GjMrLn#a^+XW;T~1COa` zRO4okEXmHmXL|!?ur(}e=d^5`pM-5}ZJy|k!*}}nxl@-a2JK(FyhF`nwRvOuy1YZp z<7;}eZg#!uGf#%QqWxI_@U?3{|RAkHGvrPl%10~2H zTLzb{74*2BY#DsEX^3Ya%9esIU9x5H*`|RRWXs^PO#_eH$(F%o3k4pxQ+;!@XDrvf z-^DLVHVw=`2{Iaf-`{2113hjZcj+nrNwR5(XCMm8kWOt)?&&{IHVw=`2{Oo*!DZV6 zJ#K%$dLQ4pFZK<_-V~zn%{tDdA0G2dki7xxz?@^A>bx?@Wg7uKrmoYcjen5r4VZxv zWbo;P?B3wwdoBGWvNwolAd2h^T;4<1W9s@|O}{SL8!&@fQP=kLWM|;=emak-$9y^5 zb;#a8kE!cFQqNyQ_6E#A3E3IAY(2nZYD~#-4%BGm_a=LTcpb>d(`AUub^&@!eYlM0 zmnVCJcm|>{PmVLQX*0hE*&8qeCCDH<1D7oc^q89L41BgXh-V-wTvlXf;Iq8}Gq8Lx zw`6DFvQ>c|Qh`QysQSJ`1H_&71pTAlY zVS58+kez|cJFPsXCOZR{tq07Q+RYwQlbu0??G2bgBbk^48DwYRvQ>c|Q+FJ)EAlqk z8!!VUUpzj>W$OVmrjDgVW8A4HB6-N(AYKPD$j-oJy8u0=COd-&+Z)6)5QU{cXYEGk z@!8&h87M&p*%`QONubBnTM8BO+mgLOJOfeT(k)Y|K!oiLm{D-YYcAUx@R*v$@UEQ+ zk)46dRt0)Y{mMgEJ+?Ps21<}Yb1K))UL7ZO;cFh-8^kjZMRo=*TNUUr_1w3UJ+?Ps z21<}|^V%sc@AB#~^@&?=im<%_GcX@yXW+8+0FSBh2?=$jUE~1S8!!VU$RIldm+b=d zn40ViB5ZFE&p;H`H`4L#)Ck)fFassXAUgxM8`&G^F*Vs4L^_bYK|BLd_!T$~*%?IH z-hdg{Z)1N>vv4Fv|7@@eD+foq@|%1$s=q z^xAdN@5$bP87L_|VVcX<13aci-89GP_M5yw_6G4fkU@3^F53lYTLZE)kZf-d&p;H` z7_v2(d|0r(0W(m746-wD*^)qysc$SXek0o(#4`{Tu8EU2T#nvL`}E96?l8~gy?Gu} z)1JJ`yY4)u=JV~@t7>yQ<_Ip3EkHa2QDht7^4_{0Q;*wyB+5Jc%)oTX($wYMd>&IH z+i}PqHOh9W%s>e;$Trnw`vyIxCVPn}+fBqX5QX)PMi#x-MkkTo1T#>Aj1}wNaM>b4 zkE!2j|4#H2*-gYV5QSq@I>|aSDPRkQ_@|7ry?fceMI=KhmZY+g*w==!uj+Eq*F`3bo_IPeMx6 z@?K8jQ{nT{`o71zSiC=EpXz_-92v9&;qlH~%sL_VRG1c`XkWzR9md#xZH$3Ar@d|E zXUlj5ij{)eC5tgIx5%KqbeAm&Vte%e%0QG&De--v1Q{`X);b|U2d9N7o4=TKLX3em zgX|fUA0gurB%sDa;Wq<$Q?;II1ebzc5mJdt|Q8s@u>x38s zYXj}dxxBy4)(MzW_?@E!8MJTc^4?+0Iw7V58HloPHZkWYK?XgY%X^3V{2;a^$Uqd; zbXV;JT3ejhQ(x5e9MgdeMA7%IdTN7i}39+1GT8Ogs_+NT8sH0?=;Ih4e zu})AeL(DoMrUPp`GRQK)WlMsXb;7?g5M{slm~}#off8hpWrE9=1TpJ`e`O%bmU`kB zg%V_tWrE9=1TpJ`m=0th%D$V#FA62dAj<@oEeT@Q2{9eWK$Lx(iQflGkU^FSF54c& ztP^57kbx*$d-V5FrrTRGdVh|{MlOIFQSEOHYua*n;6(fV3xh3dJYh?rAZ$G4u(C5o@5 zr&alwIbxAGc~^-@Zeom`F)Jfy{&I@()XsGoljfFH@fXT2%lPr1B8G8!VUl=ZNXf|V zTEqNpZ*JXKs_69!wIS~f8O5(^c4m4?MoLr4lhU!|k#Xs>mX?exBu3t$TN~|5(TuS> zTQypHmyW+x@~%d`##%=6d&j!JXO)ONMT~+oW~HYm>vWfo8=Zcxw~iO+(?5Oi=AuT& z><&lWug?~X+(?Xe(=VrgU#N_Fs_9=JPj5C_$6v0uFMayo*BQqAK2^MDi=;&M*Bs{W zxO|g)K3_@2$lsv4TXmF<&wag|d$w*N!&p$NjrZG-$j?sKR1q}ro$K4l{;ra1iI`K=%jh*op`v%Bcpc_HrQ(O%KK{Ae@9pyn)%4Xb z-NW6_sd&{X8{8!=h^=Z#R)H1X8*g8dTuWAdu-ZM}JBQ>q_~wK)?u#{ad_v{L?t_I+ z8^+}~Hp=UYpO#!p9@+M}xaUQ!V{wD1s5kR(rQ<-355#MSju=Lc)!)ePf8DQYNrPao z*t|yPW9O(HV%^rGicxCYW|8}mJ%*9o?SO1l?;BN12HtmE)E=PADrcKtMb8eq6=U2j zJ4MnxUl_)q>8ItFr8cTsQu3k8g3QGfs>{T`M6YMIsQ9tUheeI=J~E7wmH&~$HZD@N z;r(iT`Xn$2pb}lF?JCD$Hx5}C#^3!7@6rA)h3eIz zlpHg-oQj{kTu8RwR@5*WeO5gB?!qqw*OKzLmz6bl=7Lg^0&I1 z%~u(ZHj)8UZIlK@%xeF zbkRbi>MeUBeW0V`;r=7}tw!#U=EJ;)NXIjamZmp7our;*)Zj1EXFsmv;r^rX?XS9z zj(NemnHcX5$>q)+oI^4G+E>Kg{jH*8&oJT%zN{pW`f`O zn%=p*$lR$4wLg>F+WjgX?hSgZf8Hy2;5EVT{BVPuUgUwZ3iWj!$Gd4>8NoWjy+P*U zKHgI=uM_;vKhC`BRv1=Qq26D0(H(fAiHe7NgR(zA9WV&eak!*5BCO-7Tdj1p*mE`a66X{R6N`p)VfyLn_aD$kHB5^oI(SGH<)^DlJy=aNC~qr`Gbw4@K4cIJf0{@mIn53bpNv{bEA7a>4Js+J;M_@G}vGYCr3Wc=$ve6%V)VRqq}wZ=3Lv z;CJ5i14rI{TTz92?$sP}cD~#y9&X$BlpQYT_;m!o^AiJ-8{4lYRIe2X3DxHM))W}hMBQQJuXT6^^_QT zva4J~I*@@V(-RpT7q@;cE*0!0j}XK3OG;w;C6%t}i43D&&OgL~F$?5sdMcD4!}L++ zsa8<0HsfS}Rojt)DAU6k9cAbQ<}-r^$};pmP=XB8+Zo2{4c$ck3NOk#iDCLa34Nb> z64TqM-yP>_snJ5VTPiD-jP-*F4AT#qe3+h7eNmVeqD(JpbQGvpM0}oegzP|1g%V_# z9@Q}J|GHzwN8?AzXNY0?S0yq1t9laCqZ-DoosMnvyDpb4C?6<6hUsffK1}bdT54n< z%JkGm$Ch%;43MI%ey|!VbuRWdq!sZe3G0KPO!W~ zpd@CTpq|8x4D9!D&mK4P*gJ9;eIF=6h8Z)Me6-P{4AtWx15swgVRR&)$Z&6U`^cm8 z)uIF$XKFp^4*m3;VLUkSu-kIVQ>yhjwWW*OI!Q~+Tvk0vPVurkYT*&XNV=<{cXHlr z)%u_W8FMC0b=Q}>Vn)al8szo{)O}p(Kn9|ICy&{3!4F2qZONm&Imjv9wtZWB>rMw5zR#)&HKIA&z&!pKskg(x%1G&;6LdwHF5Y;w6x zLf(%5Nk*v|NeOG(0#lpNEKNU)lVMeuvQEhY!uhq`d9=C~RjH@JOjH{l+jA{*| z|CzB~+3jsTZWB?03^U#}`7k47H7h~}qReR7=(uU!9bU_GH9T$;QGyIJayE>!uh#Vz z?{DOBn`p+-N@B**>PgJV*)W#w?&e+ma-_#?B1({9#?&SsJPLoKS~E5CLI$GDh}`Jd zkX*qVJ?vhO+eDNg<5aylZs!5}4C8c|GddOuHn z-Q(5=CCD(Xoyo`iqnF&Je{@nhkbx-E9vdCsF1{c>oz__~%s5d=%y>@4!|T-B2b7b~ zm3hG9_R7pT6w1sw)RUN5hS8C^slEJk=F1+pS13V-nSYpkm>G*&nLq}j%5@eWpl*xygdATt2QfVQ|%)*S02M=|YZM&aWttd*6VP<58ab|E2 z+5E?CF1J@^ex@X5ex{zp%*ZTb=-cv%x39R|UZDgTX0B%P!Lz$HLzlZSyHjZ)%FOhP zj{V&S$c#M;U2d;Xf($e3GmJmp7$W;O?(1@UW#)iNV&;JANzAOz^qhyTE|KkCndowR zg%V_#`Jm~~%?#3o8Kg=JQD!!2bZp5xLT>%LjLYp6N|0e@mWHwIyOA=oZ)`fZS7x56 zBxateo+PKpE!h%EkCq+~%jNx}?o8M1Rkj2fb0%rOQhKzsqSz>z(S5cWkzrbh!Z|Ma zx?i|lcHB2MgLR+;8R405_iu7UTWW7x@IK1z@g{j{9iJ@P)as_Hlm+Lw%OdF&p+ z>+Q%u)I&iz+2M^=hVjDY643*d#)-+aZ-5e9xy6*oK5>l`y>m95zKnY+WQ5lMu6yBq zxuZ)JF_ChPX(0;N2FMS&e&>SUIZBX$YYucmHnUiCLh1?eIpqUansLn<*^bkC&{gSW z{3b3?K2U;;@ao4ws_l=yGEs1CM+TyBRfJA`(ihdYabLk-6iSeRt1XUGe_wL6;D%uc z!EFgjkb&z=biVdT;pl?;ZDj@8$HCnN+^0ac;XR#b2+ ziVQ^IN*JvaQA>T_kJ|*d)F?p)uCS5+tE>5WmU(;O+_C=T&PB zoi_SI&Zd0eo_YOAtHmpi=pA=tJ5G(?rpbHy?~-{>5A#ui3|vWfoUG^WlD7<-B%h@B zfeb|9{*L2Jezky{@_ReA-i{Jv;95U@=bNU;#cu8>+btQ(BV{>&EA+;mN&Qae7{6EUh0=$Z&>*I@)1WRrbTnYr2P@LS^EhV_Sd$Hi|30j~?DOy|; z+$nZ<@08*Na)W!Z;vPtgm40*P?oI#O+`RPTdHTNl{tC-p-83PIQ zGIdgBjI3&m@p#Q&25Fnd4Gp?b+*zkNhR)gIIPXaE(puqdvC6?sIXSLGwW*(962oSJkZ$l4=pOAc3oZ;j1+*Fmyvg1mesZ}-GYUs@DY)PxP2F=gWf&|7BV+ObG)d{*+c`o$wacf}B z7(-gwSVD-+NwaOVAc5^BMtyFjtdrDjSPxS*o1{)6m+`bJ`-QzSC|`nQM*`Oh6{X^a zbgb2d}R!!=|urT(f&JS{h7YX#T zuGe;6Wn+7{HRye8>_(CAJR&QTYP3S*>2J+^IUr#3j{ zbB-1ytje?XVwLRAZ1Lc2vfo7u5?0OKl!K$#_B4HEzl#KVp%zb3XbrMad@-rZKnoJ6@l%xB>mIX* zVL!_}9BRQ)RgSb6UyVA=zRA2o=HbwSgjH=wtFO7vw2+DvB+v_0h~hi_VuiQq`Rr2l zf)*rD-6--5Ti>yq6*tQ~9ID_^Pmi>sIL}{U0~XDcc{sEnVbxjA`|f*|kVBK>5+u+I z^_Plr!M(OE^H*p=0(G5Y+&(^)x-;EEnTJFDKkg(zT2U7N^gG+pahS}*p#=%6!qi;V zmw7lO&(Z4s8c{sEn zVb#`NS-XtI#rer`I}+%Hnp^Q54!34Pr!`2lAc0z5@k=DRGO5KzHBv><^hW<|O3!C#$! zr-01E;cge)H-ogI+&lAuxl(`9DG!GhB&>Sszw57Kl>;{Dl!rqCy-;VZD5e%ir?qXg zAc6XAMfr3+P(9e@zD{`t+~tCKqeo+`V3hw8;B(7rTUR7SkyY zhZZDIy(PXgQFSxRpW>o}@^DC?7i#MjWwy|G-DnW%AdMGVkTA7hQeUPh?dN7yAH5qL z=H5S;n{7XSwhHawLG4(jqPd0Q%wB;0PIC&^+wE|-Cn2!i#O>kU+s7ymXFlh$9%k>8q)v(bm7V%4 zEISfruViW_%>K$w{S^}EWmN)3h#e!oH)q;u_W)XuK!u>9oOHiG80F#2_lGRI+0V<8 zm~RI8_r&)H`%TmXEl6NI@ve36YGkmhQJxFE%s$_YL2rY3cM34d!=VKUY&Y?BDfd1| zMtL}_hxv9+QYS^J=6;_u%EMvVkucxd=Jhb&=Zx0XkU%f1qA|PJU32jKO*`#;K?@S7 zbW9vyG0MZ4<11Nqa~vc~Vvd~5wlc?8jPh`3K?36`in#-n!46P)F7z_TL}mtT*}8Lc}bfnHW+<|eTd>E~@h za)%pQkU+&|;{1bA9?qP9$g-RB1X&VuW?{CKIsagkheHbz7*G6;qIFlXD0@^END0^3cDecXGI8Rg;3JcB%!nf;K*Si;1738Oq5T97ca zBIfll^CgV(a7dt+RVi!ceHi88(1HXiXvJ^CiTu@v^eI%x!!dfFn|UT#5;HR;|DKq? zVw8tN3lbPltk=4CVKdl;EzgBsX3oisVP>NkWTTQ0*lvoFN#qj`Zcme>9{6nlETLF^ zb>|ahJC)IgdUNEI@W zvgY_z1f<>h-Gl6vysyxLgqg)P>tW`1<$Z+&dRa?F`&i1^2T08}T9ClKw(fj;idC6a z$hXUS;P)Vq7GE27=iB9Tjus@$ytrA9P_ct2_VF62R!0K8a5u1`n7f3eA|5SB;4WiP zDtCrng$%u{2Yv|yY4`d^?IVB5eitoBn5!ISJne{MthRIzJNT3()02d<}vHNV~FHv%* z1zM26o#jHwAy%-u70;@|3YM$~e*FY#_xfP@{V7x$m!Jg+a~066hq*o|$0bOh7w&x* zUyc;}?wlLPNhLX2kib3liR-m0tk=qV;CEk;Rupr+R;6(wT97c;Rn2--cJDZpYIP*g z3wQmC6-BYDao2b5dY}af{F;EG&u%^)U4%jOMjSpcj7QLcD9mKH-RAL**V5v><`s&T#8}(lySkQl0_7%7ou{ zLRwKwy$_>216q(Ubvb4|%pKBlcMTHggbVyCwK6m1qu9Wi1_sYw?aq- zg^;`+_+=}k-TJFA*JDO`AG9E0s;ta|FE^J2U?IY^?v5~iWGDY*ZjpmK_|;@s^;V|(uw*+c|FjAgsDO_>tX5><@G=U zy{x5T;>#3z%|`MIG-yErcZ|99q8p9k&T&k=sC+)qf&|7B zdLQvEqzpkX7<>y!o(sK9ji(u7uUq}e=x#>~64-9y_XgZwPm*~!tcR(_O;V>s{jTh< zunEGAWUm<~B)*WtV#8*57)>gam6&&fO-T9CkYQxx+{Q!)>S z^)S`yN$QlSZrTBC;)^HuuVs;WAG9EWJNOd!8^}DI zx!*vR-P{)-OJeRMFx$%9Zy@ttXKZNK&W7{U0(9hh;~?+~r|j4|D&A9Pc85Ue+Cld&Jja(v`d* z^P*@$0(T<1_v5T7+d}5y%>6jB?B>21SrT)njoDV_ejJ&HLkkiZPf^V8k;yz966j^_ zp)q5ayK7_~4lPJvyNTY%{RK0bhr@c9yPcBMDRF<4oDX8zkuY~bnb*VIA7!UJ91`ed z-8orEd`YL`^a*zOl8$`eA%Qz86=k)1znY!q=jMJjxng4OE0gOu=1w%Tt<3#ucFMz{ z1qqBNzTD#ecALz@A%R}z9y2qBx%*7!;n0Evwwt1uUwgAt9uDha?gmU!r^Nk(cFMzH z*^w}J37YF_=KeuD<>8P(FY6A_QR1sZ9WrhYqdXj1kieaxiem1Av{T*(OJeScl=VPb zQOdjbTH0Z+r7SNJ=DtfwD~h?FGmJ8KcrNt9y`73ueOp%N<+t;~C_9K2B&OHPO*>gv zyH`eQxCzI<3G^~)hnt9uxg>r=p{GV`woxt17`2MNarF2;J!{;sjB(la#*u4vdUmdU z8KYC#HxBpLjc<<);GwK6 zvA`3DUmha996p5id$UjyXenDR)Tnghk)uZqKZdatCFPD`e5Y$_k{C#25cN2}`;ntS z9g1E^ymWMU>%;Ob3^gt-dg16Qeq}D#xKJa-spsbPI9aj*ALGm_ z3A7*)K0egwarn8T*f?KNsw;C^^St-dCLz!Z?**ZNXx^6ZOr2U1XhEXnkWgcO_;W{z z6%=D@m(G0g$#_|FB+v_=G_n3Mxgc+pKU~I`ax>I$U4G@rzs83(6Ri;V$4gmTe1b)` z_RqY$+;24{ffgjTz6&+7uk<|UM!7&fS8tSrKrd_0kn3tqUhrdHNnq>RCWji;KDe&| zUMKMk)>U~owYVhEf&`XO?5Un#j`tr@J_&(dAM{Y;TfbM1-SIx6b!+7+&5s*ZB!Lzr zuniR@q~jas^n^~5z}^yjQESa#p8M!*zO;iR(1L`$Y#HOLUtc>K-$^e@b+5WFe=)FS z5(2%jKNfkon5xcUokvUJ>hEO?V@ZOeOucmM-NiCSyWt6r=e^UhJ*&$Y4@xGOcYC{) zMV$+VjY&eF*M$#djBM)@9KEup6Q!!Nw1;y|`;n5s^H$kh#%P%?!Ljl5zhk@{Im!8T zt>Kcu^CFQhx{NXW%^SxTzfp{-#n(8m#tceApcl5f7-j6(>a4v+{63)ghZZEZj4xxH zU--uHrWCdAYWr#+W?OO;}quP=9C)Z5b(JpaltxttdUV>@!j%Bqh-6U5YP_ zZkrMujeMweALSotG@s?J2U?J@*5g{oE+HvmEAcN2m(dho7Q9+1-{N9Le4Ap#i1s=jR-NAGVf0Hz>wI1=H+n_wB-MV7T5VqoElAMuKQV^ASYNP7!P(AQ(L<9E9Ap&LeRRnC4-V(UJpE+NJtd(S(V3ox)z7)oj%_G@vv}CTkjz;wISV)GX=z;~==h%) z!)v7vc~JYdbM2jONeGXZ<9fL9EbX(f(N(Ba_9^K@=700n`PbEs8d~tYSSLjZc)Tzq zD#xErwL&LZ56^jtIKS*^Shf-??bssX-aWM~q+yNp{NSkOtk760)zJ)< zLS8Kl=8e)cOhS0Pe%cjoIC{JYE54kFs7~8L#$FEQ^)EKi(1Pcs;}MsihaHI`B15*q zA-N{x=W1;AB!tHcdkLW&xDXfeeq9K!SF)Oh7CbKy~B+YTjRr~k6R^T zHGTvS5~5_HUcUWN4+{i7HmA9x>6l96qBkK?IiJzC^{9hP~`D*Mc;;l{}vZ^8!TTy3e7SZN5G z7?RtkJ&zAbAqh`ykvP^e-1uVP>#*N{p_)g1njn7Hq&e5tWwa3Jh4m9_+spG6O7(FF zuQGR@O63)!iLlncthWD=J>1xvDC zgjzh@$amyTShFESEqcUZC*w2v#n1`!ec=K zTR~CQJxp8ZecA4O&&Qh<0=+0k@7u4#8YEC#o$c^GCBoA6vGMTsd; zppY0da4~jZbS^Pw2x~WFjl61N%n(NN+Ie@Y(fC0gi*@IS6(LclqWH_U`59WWJ*;MY zbuc093&Tx&&LqAR(rHD=4{f6OvpzpqVjyuNp_(yrbwb!K5nEB>Kjbg;Zcij1_{S*= zfnHSFmV(eb6LD=*Ovvf=k^E5OGm`LFkjVdMHDmRPgs@coh`5)Kuh2rr82-{$K(>{K zKrf2nxqE~La@*pNPkTo5c5|yp!ec?AO1f}k-ROj{mf0yrh9QeXZWtqYom_(~1bX2; zrYLDjTr_H&IKFoMkCB@1wK8%n(&?miTw?y+L4PNrg&=CJZ5h5#RD!$Tg*2zJ2^3mLX|2dR;xNGZAIs+U-qQh=QXlOyAsmLu+ zcIRx``PL-e33-7ExpnP+miV^q00-ud?Rk+n-#4!5+`m96gc{&;JJr-Wft zLh*~)hvzs$ZdZ@qRduN4dUzpZox~bT^KH%ngZ4y^nLNNkU_JJT+!5}89RM#tha*htU7yYP02Md8-c%8(4=i=@7^`B=&=U<*u zd(_%}uD{=}vhNt<&dEhiTV=o4+kG7MGxdpo?DOL(=Iha^CbaNY4+qr)ODOupuX6A; zh4tv{4eM!WF^?tj_>Mb9)y-57pDlTL^r#)tt+Lm$5a@OFvb(f{4S8S16yRZ73Pta{ z9F_v#5qNZAmH(q-uNt7vHPLO9&S zqM_w^yEUa_(#JA2fI#eRV)-4J}BVU*@hy({gk@PPVPa z>puAuoqu46g+Q1th-Gh4sx6@rRLyk)(pB&3)b;=)8Fjra?ElAvQ6OM|_sZ{gIM)6;t6^f~_dKE(g zz05TPb42#{#3+97c1-lEE2BN@5z>N$D%K4|sT?6cQjECxD1OBe6aA>gT05Q#y>OjE zj9zmpF+q)5Y70jB%29axyYY^MDTy-{2hCVYGzvG$?t1NLeUt9pu0DlhjvpSQwJM!o zj(yrLN^lGiHKegf=E@0<6=zo4D~S=AZFz#@L0>A>y4U$)YR(v?)hORYMGF#iOxZyi z&x<_u_QlaJ9*)*VG^&t<@OaHk9d0z5oZy&Vh+;Bp?NsclOmVF;R!O=!jQl-)UO?bSB@H{tS&8tS2=w_M9 zYjZx7)4GW~<-6ZrI#lsaEiaBM-hSzb`zL2MDLGmqOIBKFA0wYiBsLe z4ZG-LuFoN2QpSnVzyH)yJ8{j&LZBD6x|kIW=@K1ywX~MiuZpF0sU)6u3*H!R^m+Kg z(Q_Y-uMWo?j&5?is8)25rlAE1I==Sv3&-N^L^L~DD7yNnJldKJwUZDYFPq334m|MO zF=C=54#z~Fu8~`t{8w#R504j}H*D(*$96HAv=XiQZHqn-luaA;tiFa8BweG zLi?>y^uC3P_O5OFB!tK75Ap5XQ(c}ps?;Q+hEXWmuhV0-#p13STJXGSL~i*=qo2POj z=XFURU8C+vHR?@762jw^`J<@EqsNX}f6-iRHftYUj?p%1Y zPwUsZp3GI71r1F?c)Xk<-@az+BgYzW2n{WG-VZse8{K<8bi9tE zQZ-IhIJ(u&D(d$?jh1b7sM#Y&)0^(BLBi>Wj^bBV*guNZjP;N1J4(ydjIY(ZYn|EC zt3MnVtD%KrcnCTsb%J{}qj>69YjU()$j;P@NcC$IeWvV1Mx;DdF)lS8Gh7L3okqluhcZ*-wwM)coId^0c(b z>G$5Sc2CLNYWqLONWx=5;*eOCxu5odBZXX*DH*v{VjRhjB7P~v8So1=n)*)v6C@gDE+_f*=s2V?r<3}HFc*ZE^ zs1FIxd1)kr#PU6wjNQ1wd2v0GBhU*odR79#45(++CA;=D~JSIkf@MJGn(G(X1}qAp26e@^z!MT8Fd`p z?2A|Yo4`_GJWrjH)&ng_T&!Nj$QIGlzSFq)uTmj_Ui}tUHeMX*X+M_v`o9RYy!Wka z+|S(0zNghKJD$l}bF?5aXK*EBRmWa-$GW@!ih%@rRjg6bX!@y_eK~vlF9I#~gDM(< z*&^((Y)}4UsgP(krM&2=BkZobul^MSONCym`<6FC|BSHr(dhZWYmSzSsmmHE?0xJ} z7sW52ns?>@zJf^97x~0;dHULO?EU*+G4NdIg--$X44!}Ev>EFw8H>hEm3RBvVwH`R zb!W)qz2oeLI&{1|_IT6(kJHeC#NZZ{jo|XLKSQ8b6|J%{KJ#2JM5(a_jJb~%N=xvE z{KoV=^W<^SD_hdE^9pW-6oIE?5bcC+P>TiffgjTf2d#_ z{%e^R0%NS-UDjB%cTJLb*0#d)B9ZG^8Dns#XfH94K(DroN*nr2-3x&hBz{a6YOMJt z#tVU#8v&(^s=C_?&t$C!T9C+}r$jO_kU*~$m5L=(bG){A%_Ci37_Fjbd8r3lkf`O# zpUj-w8JkN@?t&l*kh5PawgHM0!B?elMpr^p|Y+7R=fnJ%T z3m8YsPxKN4El4bBT+kTzYSL#2^xAl(ppoKblotXmNIV)CVx&3XtuH|Wy|OeYWMpeT z%1aEiAkq9nA*1d6v7aH(tL)pt#*YVwdLht)M8LozM!{|)KSQ9`tW!meBFzVRA<%*Z zJs$&Y!#+cx*Jx*PV`$+4UI?@xLC>SV-;mD`=!NeU>z#-eB&e6T&~~tw7)YQOj&Q6o z(2M#mPuY_v(1HZ@kKS7s3G|{~+xs=g{_2~G`HjNs7s%S;yUSV+v>>tiL4Kptki}lw z3JLV0r)$%QC0+=$Ad&xG0b~C=Z*Mgu(2Jff?{7}DAW^1iK_jU63NNKX0=?+z^1QXJ zZG{#j@V$~efnM}w6J|w<`QGV@D z=Bx+_v>>roFKz68q}$v4L~|S@JlC1#XIJKh7{i4k=(`=MnCI{A5wbTzj{1O@-%k9( zeb74lgab4}PL4pY3+)RV^Rlh8XWIR50xf|bix~A9ZL;@n|EK-Gl?sVsSBe@lW^b_% z%ujQJ}FA;)5*SrM&(hON9hp zCuA$sAnVkOXmMDo`hYdAQxxKStb4*M_d9{$IAAQ8Wd5KZV6+c1&M-zS&e1km+bXLM#oB^*Aja^W7hmfvLt$~+{T$L zcg<%IV_?|}?#gZ~oN(R#_NUkXp&nFrB;xO8H7fpo*}gdIU&+**2=q$69$4NXgL4@y z)g5~&<>r4Z6%sQa|2{*YmpH#6&gSLKi54V8=?oFmOAI8?OVrH}bu?p$yM)t! zR3mXm>*C&GbOk-fbRTE=a9(f!B8a*3qDY|SO0`S+AzM~P8AuOJXOh>$YYZeN)wrT( z56Z^e8AyzQ=R&VdSFY<@f6LC?8Av41k|*^I{lV+(Y`(}q;+c{!6%x50-qi1P%gNjs zNQ{B!La*p2xAgT7ax%&kTVtT*)R%YkD${eZha!iJXR;D#K|(y^x_EY&I|G?qsnARG z5W46o;Y2P$7rnK-e+I|udg#v5jIx~KU9O9s+l+w(T9DZBNY~fs zrI|a+nH+&$VjQ81@dR^cIgwCfHs~u_6=5?(UhLu@G5Xy`g&AeJ#Hdmiy|{U|BY_qq zrW$MY;lm2CxgzgttvM3t<@q~}K9VPbi|^JCcP_yw7h1E4%<@=dICYW3H1EWJm~k3fkPsP8U1U1F5O|k}Y@jaY z9nwo=?Q}7h_ClaVWbJe@GnQU>rhm#r*;=$9L1z*(V=pm~KrfL|)kSvF3xO6Ss7_)o z{TTwi#5_$Gb1W}}$Oh|THY_b-=BtZYt2`EST3yURy%1S6}#rBq0u7q-vPAm*T6N`(Y^iCnuba_(LTu?nY)*|4;TnRa5SL_Q{&y9A$FkvY}Hd{)xPYR2MU2FQq~Py|A>_7-&I4%>R>VD@~Q z*(onIM*_XX>WnV()?Ns-AR*Rpbdf*%41r$MyNdj~7XmFvh&2OU4)P(<^1tm^&|ugr~MNGfA_gpI&5A zDHbL2qMpCIXA|BCvLI0+u&>@Kq6~BAMUx}YE4!_)-lb0&=FW>EftKI4_12$fD#uQW zyy$-`6%u9RBlH}@%d-J8FN!hnT~ik ztjJsjmI^JT&=MLfnKk%tr9z^aP-~T|QITztSp$rL=Rz-1ZZ!z1Xl4zNKnp3fnocRt z&Wo%8o+Q z$@{EGjQZ@Jd5sul+969}_hc!or4loiL<5Gb3GuGAd(Q!&MU3YXTN=-ld<-PSh%=e%f#*UmY!Pb=v>+iy&h}(ykcrm= zz3|FfW8i%y=IV*C(w&xd%v&Hf&^)=lAT8-o(sLGxAT4{q6G=kkR>}GOgtBQQD5n~kF7OF3lgM- zOLktHcrNs!9@YEZjus?H)0gc0Jn>xUMLnwbyB#e^kTx;dJVWBS(2M$D?{_;|kRXj^ zviXw4bD-uR(PZ;JiRVHudbcN=ze=a$o@_ob@m%PYeD8x6BuL+vY+f|+dY~8fd~(f;dsbgbN#$7q zB_);6N6D;#SotGG)jzARi3D1ZASIPh*O*xYvF4RX;M>4+OmmJ=LREEjUI?2aG6>dE zeI=AlSw0qFQ^YKubV@>rBL0M&d;$_7@ZVaLW3o<5&ta) z5~S7=+AK3Ofidu0=!NyO)*Q=QS16E#u80|8wvA`95@79@g%?n|hISeVd$ zB~PFisl$ZQijhLhJ3(q1j7N$vq5onQRhVomv>-u>Frlbo7FC!eFgoeGgldcZDKuV4 zdoLBKbdVr@mr!sqi^faFz;mIOwN(F%GsbD8r1GeZNJ-_ZS*25=1qo78c~?{6 zxzLNwPd0adg{49Z5>z^h`M(MDqPlt1VzPBf>7-FCx}&MRsC7NZbp1ODB~{>u^Y&lm zE>n6oJOt^6gi6Rx+MzI^4m$ni9s3=j5c1F#HC2)rNYIl-&x=JNl!QPpdM-UWLTf#+ zyrl0Esx3Qdy#8CMkjN?YT~lgYu{V{wOtI#8F7zUOmr!%rEgCOb541cK`mTJbZ`fxG zjTfHDS`V}!abM`W@;tn0A0l^|CRZx-!s{dzrW*C{bj?X=B(y|!QXA21j{0GG*LsfK z_Z7YUJp|3DsV5~1X|IH$O71eHw?Fl&?kk7{T96>^l~7liyG)ZK(2GVM9xb=E9#|@j zmwY|Yf&^)ngeu8?TI!atR7ju~sj7r_$=qd%1X@UMC3H;o^CC})XR_7H<7&Fw zX{JSa06M0u1Z5Q5&xgmKR4wyG% zQKp`9rb+9879=Rc?YaKeQXzp}bp5@z6KeZMn4 zgS6s6nF?wje7dYL(1HZz!6}!Lv~`g{ujHQ(v>-usqMT6D7)YQOKAYBhV9!8VO`6Hm zd9fd}5@r=1WB1KnoJsS6Z(i66i&5IPcd3ElA)vNPZ(lrB!!|MtTy@_iso^ zCG=5pmnmsWNF9;*?VUsdEl7}(N~mkhU8ba8@x<`dmgZ-HNF?97Si^wK<=Clhz3mM}J{ewmhS+nYlBN zNT3CYzh6{f^er@Z1`-L3p8pVI^gS}ly&|1_J&+i2*3RgAWU9=)VhlVNdiA2W zJNJqNTAr<~!sx4I??he{&y;+rkhm38N!DqJ-1~|#@LcHi@3x{i^lu#f!V#ly5>sD7 zwC8x;i5hIyyKeIDZeRERj?>VB#P|j^#rn;F0!iNnXhFg}6MW(CUooTw3G?{B5z@=7 zUm}r(zP=~>b~=~myS|=dx+`BcF3-f*_Z(-!k@7(=Epk<;GCcT!43?#-*zEnsY@?%VV=gu)f zW+0QR2YQL`+|e`WaPKlj0xe56s`P9-Ub??j_#fH|3A0~uxZkxH18az0W!aAPMumBrQmg zPE{yC^~A65(Fh<3fnMh5Lr?trULt{|!g$Ho11(6L6PnKK5k2)-&)4@7V<3TEq~jDy zO+E4Jdx->E5`=d1QRZIyMfcbDWJ@P)U5tSQX*z{cQ&0T*USbR+(5tl2akl)_OaI05 z^}R#_Eu`HPN==>eqIf3jU4j-Q8VgP5hDQmAKD5D(h3U&u%7t!J+GxgFMJBzJ+AwI<=6LU{wnWwGutAM&8&#| zeEh@6ukTSVGznp5KR-jDmzfv!LYVm^X)!ZU^4QE8c_Gk(gqd6NLYSE}X)$wh^4QFm zc_Gk(1jhTPrRc4L1bUg-HZL*If&{jRH3rth%s?iola;`-BVlGgy_5EE5@y!$GX#2> zSv)TUT97cahMytO%go|=A<%*ZwVS60w_Xn<(96u?d5M7*B+RVgX9)B%vv^(zv>;(- z4L?Jmmzl-$LZAf+Gi&%60=>*Eo)-cwNSIl}&k*QkX7RibXhFivGk%6ZFEfkhg+L1u zW}fjg1bX3^$a*KD1qn0H=p_ac=#_l$gBB#rtf7|}NT3(?eAaqkKWMJq$n)ZvtOQz+ zFjs*-Q!4cOZzD1!%(W>mG4NdIWv-Z+gt_9bQH@N+hMbv@R#YfJb@S_cq!uw}MM#)h z3~51vw4y?(rzd`Wj}$2~Mn<9htlVgmzEEWANck!BoI35u#J6^$azGMjK|&MC&+aR? z=u13btxJqSI!B>u)JM6$TE~P&Q8&L@N17QgHOCmFfAkPozvN4WUN~N{5@_>t3y=MV@N;SWn+JhjMKj=Mln_#J?9)Qep}Y@%3qD1Wn=sE#_7SC z(z6Z1%cp&uo?=Tn*7LHBof{ITuRKjep5>S9ZF-F0r}7O`&wgoR%j>yxZqtdc3u%}^-Fqobw?oU-XTt({Y`rIi#XHpusD6q znDm11ua{Rn{iXxIvGKXuD`OyQ)7ho-Q9f*Ctw2^{vrE63$A|S7*XhhemmXA+>alHG z3T;4@f_(mPn|A$N0P7hLtLN~lX)<;kDV{@YdnELFr{)3C^(SL3VZS&kp zJa_$gHKtDh+tWB!@4MEIO%4cP>juT@7a#huttkW8r6aNWn0-X7&Rj%mD}JwM?yYy~ zR|m4N-p^e6h(#ILF(V6``_`pj{yqb{=jYGzb$97+BQpr1%%`GS-{@c-UHqwv79*Zjqi?HNUaZH= z?f&e~KVtP^Z>S#ae)rSX4=BTfw!Bo)g2eCp{8`V9vAPmMF(#e$*Pa*tl56*FS_t%d z(9xge(p>tvLPVr%on5OD@YWMFIOXJI*`Tza>cLc6;r3wyWL zrN6mEM1EHmt^2dH&Zf62XdQ25VfTKF)r)@=EgF@D1yytD1+r#j=VoVNaRXiY`?o~g z862#wd-~W}|Hon)o)_a;i4_BES|7jL&bC8BHMAg6wZ1@K6u?NwddD1_ULe|eteQI>*i}?4I*Rp(XV`2(?0^(7n@@BKQ2>$ zRW9W*waxPSe0%-}Dq4_uyC;CH8XBwLtV-8>yX&~x@rQ{rHoYh$c*tgfD*>(Q;x@9Lo~75JPQz8YGPXqel^ zGSrXN7pA9DHEw=ht-g%$$j0d`1bSr~Xk)H!vHBOgDTc4#QMFy=8vJ2-MMDb`E!x=F zt%b3=wv32AF`LwzdVT)tzy}ox^y=}<#wI7k>PwzcFY26f)85kFfsgs+FBN-d?C1Z= z62u0qjnm`vP*2_KLN&FP(U>3UXlm#WWRf>UtET>{nw| z-$k|gt4Ucjv>;KrQV?r!)up#sLoqhbPstXXYQwk3q_(_q@GWC4Rf!_g+51v0_@(@Q z8d{LJ*D{E$PkBZ!dy3vslPb8_s$5O^;^CPr1bQ_X7{n$$iPLwUCt}bsU#;;^HXij& zF3WR{Z<+Q90qk6l(|Uz#ANU(S}c$5wD^Ji6^IRti~5E zz1ju3cfY%;s`ZO@;5p7eu@LBm;}!8+*c<({Y28!vx@U@L=^F;Kr#oEw_aD=-u4RLm zZzl0(nB~K!mkVaKp1AY}f6;w)vR*pvbao$Jd_@rrEl6C+7Q}vU5vzBdLZw>YCPA$l z8qCA;7Pb)R^{W!hjH+?^rneNM#2-)8c`0)7ABu)(XhCA?hd}meX{=skEX6n;c0rw% zI)op~SI|PBm+fT`+aSiJ@Bg3}udfDbuA4WU!PP^pBTE=f_Lv^XhJJZk-`$h0dFI$) zEqvT<=kNg~wK27WSmooV^}};~7Z zYF{x6fnL}Oin6b#kG3~D4Ii6KQX4k5c-U!umzbA`U-WFNXtnMH@M$MPEChOC zyD3V0?QivGzhJ&&d;twDNX*)7V;}dN)>k~E80Tg^P~X-mz{}6iYa!5U`L#e+`DU#C zu0LJD?XIKhxiQ6fqs#>~yiyqN>^af5kB`%ry`(F+ar6mw-k=h^SmAscT9B~D_%v&i z+Hhb+US?@73xQtNzI|Hu&FTPq7(a18tA-XNy6hKogIq5CVn?dSk)ZkNow?yWYe0a7 zKrei+C`$ExKd^~c+wvT@Q)u{B!#4xIyA-8P?wc&Aa&un&f%UD1g!OH3VpDdt`K`v> z7?#oU9z-vE!zs$C$ZBf+Qg!&iupkXBNEBZi#6pcYefK@O9^cm*q8@%$8mo(HNR7&wKF)?DBk58e+z+L{doY3>F3g$_as7{n&6Dy(vctS z7{l_zq)i5N-^|7PUozCeffhaIW5-!y{x4w-|v>w>D!&>DY@K^ z79_4#v$1tgU3&T7sI3n4z3W_DK(tlOd<+Tn!ZuWt57*y0A9U%+ZxxNUqXmh)b!;s4 zYnT2!mSU9q`jc~YLVNyI$3m9YMK8Rvit;GCFW)|YQYYK(9+tHa4$loc?EBBF0{dbM_eDmB;sPp{^?s$m*Vt)5B+3^Drmg z+t^@doPMPb5yM{n=KOME7oNgZR7DGBZtxxxJ$2(hoX$G!`SNK&76QG7T(GfME8_I# zvQ!Pzq~M*tZOaGsJ;%_31h$BxY$=(64=vQ3{~o^4LZFv58}-M<0KTekW4`T3F@_c- ztZj99axQ)?st(`#$96js=!KauMJe^`H0Q6mhVX5pebtaK8(Xl?rTd&t&xUrlv271s zdWC-J*&kDF?4YdmCP{pSMk$e6b` z&$$1Pg+Q+w;=Y<28mHg=j);gf-x#+?M(|Vh=@!*Ud`*VPkJnJzW>ndc=es|&auf&HZdjQgOY0(9iKyWypz)>Q+~|_dLZDZTge=Tg5QoKDh#1Md4$xA~ zZ_K-2nqbGWW1SkO^k-SVjME*Xh`6^tt2W)g0e^NsEkg?uk?H)|r$VClnNLI`BcE2F zTut8c>;yX!=w&U{j?F2wDcjrep9W8`V=HzF_h;KKyYvz@{20bllmclI)L)#Pc;zJ% zE!P7HSA;(+u-m0i&O@bI>wKa*g1hpP2-q3#xILPb8f^wjtL*s1ek#iUQ1p7EI*#p`l}V z$CBUM$2<}%RXtsL^>Mze+!q0CTr-zGJmTMLsckRRP`Cd%imQV%TUJ?-*zwSx{UKK9 z?0c!dT6SuZIzDhX?{PGvg+MQBTMd2ZtM*wqmhXIREmdB>02V3EJGQ>Hgo={y&(+Ks z62*(Bnq$Y3ATdFF=cQu{m)`Cz_0*&DjbXjoMDf3C`dey?UiDf9u-8podOn%u%-8U1 z`?;4<{7ufecJ%6BGk`5>E@pJ`KFmsNoWD@7`8bNlubg8?3liGE0QOPTNnJ~&s$TTH zK67sruhu2NaxU~LJ2QagZRgTA9wcJ@w)2KEFOt8^HN%b;B%Ut~V9&%%`1>YAJlOfd z=o%EsyT8iBkU%f%+<8LA!p^^^j^UjPO|hc|i6*N8Sd{@Ty-gj8QE^p$XLmk|zX_af zA<)a31E{h$w{y$&L3~HAnU*nJu5&gv^p#kh{xvzM50!t zjSX|S^wU06s`BmgIXAx^#=l72+Crcgj)TQq?aMUI1tBAO!Sr8S#=A)DE^cG@z8CY7 zS`;JG^C0KTMx%JiiP>td+W=Njb?G}BQO~e;-7;3D z{8%2cP_Yo`)wh2Dt58>rEXxs5BPg4?cG4*Bc;T<21&Qx!i%d~vm)>wS5#!SoR-Lm) z@#vDD7!v5!zkC22T-&8L{+5W?p8Zuv^3yFQF(Y!E+Trw2 zet!K2h6H-Wz4K>LqDMV^mWbo!*Qzbg_2-Y%WLD9F#IL`KUbKx%UtE@Y>eKDEs*5)F zH%h4!1)j<3x6ouwW~ z;8;SehWAcT%PsH7=YHB^Ak+8mN3*R`bKC9E4ug$vM zLZBDk3t~(?WQ96t#UNg5%S_8%f&{+X6{S$SdFlma2)F0mX(7-H?`cKZ|4TcyON)^_ zN5k(ecRLdJo)?+ambF#er;&Wa+g%m{z3|x-ZFTn@%Rg`|KYwJl<*7vi-`a{|kGRb4 z&KS!lochT^pcnQrB2QiOqkTl>C_cCP982$m1iph6<+*dJ{qeI%-YsFTg+MRtT@|I^ zwLV7p!$@AZ>0E{uB=D^*GV}*#8Z%o&@{^DDSqSvPw}kjg+JXRQ>Fr~9{EfK`El6PQ zU94?uxtu+ojOGn8IV=QvS>J;_HurG8i5|h9UtGY@f&^x~6=g!3{?3~Rhx4&DxrIP4 z%w>sO-}9x;#}5Yao;j9S@?uC}{#sEkyH+?$|2dGioPF3rpcm#AMJ_yizjJM~zI;l| zaZ8>O30x5n`Q6#uoTV@Jfbtc@i>UwAN<^qZ;_{t`Ni2Ws556D=U52zLdB-Y;>^vU?JrTCuL_P))wTX?N+p;6 z_Z_tp5Q;H@fJkhtC6pB-%P(z|CQ z#n#ZgxwMtvROXlB)>;YhI%xA}`OgZiVh$pl%S&tT`WN9T)2&dexx_sD>o|RN`3wxb zdc|g8KL`z^>nkGmmMo+dU00gNSp_Y3WiR$zG*(EXR8$F$3oUQ&=4Y<*q|1oxwg+Q-G zcg2XTm`hJ9GE*WuSoNNoaY}nW;k)iCT9BA=$)Al5cj=EC5HV$(OKmcvGr#=nNDF~p ztBM7%(g7~LX9y9qGC9>vBfInA$9t-1LE=G<0Jgk@OHc1hM2TG+)QN?A@tozySP1mu z0|HncKbQXW3XQ2BRamGlis;LyX6UV=1&Ma;1K8<;E?sjH(XaI+HP4%VJX2hxg+Q;% zy93w^k*!TLjfn0?I;#z)4&sqN_Eph>#NA~=HCf!Hr|3&W{6$r5kz+7VpK`o~K(E6> z6_!$5kFs)(^Xg%cs=gn}x7{9~q6LYbVs^J&XlqYqr5M$Q9A%9M59e=Q4YCmEg^F)Q zshR$vdahv;-Zx~2Y8Nw;!;gh3WVs)^`rMz@${=PbB8PZGUmnll?NyF7S zGkWreo42ZHLE=tk8~ZwwOHV0h!hfx+uf9AP!DA|Jw-D&nu91zkDJz~qnZH_8BuHI3 zdH~Pyc)5xeBvA1$asbV@utv)V^Dz|{S_t&Y-p9sXiuYiii8P~sT~N1&-%mE<2BMvu@LArbCr!16{@#wg(*gga0i>(d>CITXnu~A3o^u4;BKwuvb!)g;jr4r#3xvEyHZj5{XLd&{qSQ)Uj5@N3xQtvmJmwWve(snUE1(3 zYl{9C-YiI9FCj|RDPHaVV>3Rv!vYI|Ue@$f}JV%I9bLPQ@G|-mjSVQjnty%EZXwVM z^L}E};Gk?wpF4^#Ez&?m3ljJ)5qY2BifrKE(Y*hIhy!sji|02^=|zjMrXWeRHrE-_-w03xQsk_fwRIxo)W0w|C}S{Hv*GK>|mBic)O$ z19e8qPJGVVPz!-xnD-Mg8mH2HyR_ipd8?{uK>|mzV$I9XN9%T|Derx|l!ZVq%=;wDja%)rMHgOaU@*Ja!=;~npN{pf5X`QL zT|%i^lFH&h#UQQS<9KJ(O{vZOh^NZjT7Iidwp)y;{qeA?(H-~OG?{p}uMT!w*fikD{NwqRCpCV%4U5(Rv zNZSmoXh;A%w)M2$B#h>R?VVY)kt1(7e?MMULkki+4~ty*^wawL`9!4Q{@Q|^Pn=cf zl(G=$g*&(u<>_#LZA*(Q&I?1!S$3Zx@j&eJT9!(vEaW~fHJ87p6u;v9>6Dc~FWmDb zvYhj?Xct!9c2-*crKY|SD{e1N>6_yG7`6iL@=%ntgEDIwTE{ypDy1yDIgr2>`9H4C zI;^TDZ1)>QMF9c3s7<$ly=TVm4(!4JBt;Yz3s6Kv?C!)4EY#U+Ub`E+1-rZT%<`P? zI`@44adF?jJu7F;JoC(qoWXO@mc9C0T(li;R0wq895aLA{w#auv#zMvb>67VNjV>TNM%?MmjN6kWlCLwcP8-dOx)k&$7!a1iBV( zv?sfBFYtHA^?P2pkeruV?Y1`KVl{?yQ8%tHO-4OC%M)dv12gaqhK5$9S+~BowBiq{ zGgOek`y^Y)KTEQ}oOjxzkAVt-F3i9;7-sLWWls0LX*Zk#7%E7p_xx?wV(iZq8&Pb$ zheDtWbN1!;}y?$XO6M&*_G<9%5Et6@@?-=F`g<+44NPc5pRe z_pls81qqzlBcI)TPLKQ56%Ns56#`wDfp0Lh__Bkx9M({ri7ClYK>}y?$QJUNrF5&z z7SWef#@G|0>pnAeOhoChuIt3!{?7YYW5W*?tZ%rL|`)tD71 z=eU=hWX^3hK%C5fM^QlnXYI*Zrn@GYBT@#5zH+W266nILK$+upe-Yo=YM}54eMwP4 z0_Rg03?Vhsc-LM-M91p)6#`wD6=*PAs#{>{Fk_I|9q@#rf`odl>V7XuW=4hyi^jJU z0$rFDC}+htUQFhf9xNubct}w}0`HB%@W;4`9NioyN^Q8R5a`0JK!d^g#xFAW!XQ!U zzdIBaB-EK<@r8=h%B8|YTH+;zKo@2O%2{+Zs?uuv2a2xSZctQ^z?o=rc4p}gwBnpl zksNtVA<%_+gz~EvHJTQ_+e?^opHNhg!1-|oL;v(ldiZM(p2 zuxcbGHvgj#=)(EKGWPoY8GYEgjtKE9%1}W9X8_B%=;}{&*N0#+XKE3JK$kj0x@wYv zU90IQG9zplDoEh`QQ21`mh5J>pBT{5N+HmNGyM&Qx0Q;sk_Mv)@wQ{AAfdK0R+P74 z!4EyehZV&X0$sQ^fXu})mSSZrT*Xc2Vhj}|)LHQ(tCnN7U46v5T5l;5=u+1l*q<_6 zi*p$yYP8=?apexo_{LEu8E>B!ukCOcB2vF`WpoJ%%>I^bAG}bS3jaf{Viv>mHBHPw>3^YAF^5@(1lSExqb;I_+oIVrHrbqFj z+1%v{fi8@l7!0-_=JG$^hl$nq*HcuG!0c}svwUY;FZKIy;ZtUbLZAy{nQ~Q?uxjLL zpLlVr*BT{ei3DbU%b3i*P2^bNcyYV;DuqB7#$@Fzh>%kBu4A+anxCV@UXj4;Z@IRJ zdmGxLc!ap9?NgWv-p%bchqlb^C%opKR0wooj9k98 zIcw;>O1(r~<3%MFjs&hhA)`?;2Hv%KFR_juR|s@rtY1dYubJtW)*<5e`*TW69|>H4 zLVj`Tou&$4aPb?hzJ?l;ZE^q2oB1iI9irSrq0>{qFVV*G}a z6cr?JMHiXLQOb^arVvpkL?{HhaJ1K8XkD)iTOVIr9ItYMqJo54?{;2Xg*BgBRSar( zTp`efqrLKb9_YyaWP1y@x%Vh4NMJoL>ykz;Y-$4+(Xsp+g+Ldsup{%YE>~u!YgQ0r z#}#F$Ac4JCgTZFHD;w9olyHL7tGT=z%Lo7n2gJ{qir?RHy+3KD9+cKhKVG1Z}- zsFSns-#(vmS5L05w6E{rDfi6e`WpH>>X#>{GOzP#gAB4KT(%%k1V61O8jMQ*w}YqL zmy>^!tJUlKipm{6xxT*rL_;OgtK41QJWt#@~qX<3M8X-9*-JPpzmEPcckU|9tus$Rv|ap zL;mDlz9bf33>0a9>xsg*0u==beSciJ8!rF9d*r@M2om)o>Is)O+v=mj|L;zr|JDcG z6X{3>Kg;Jo`{c-=v+PVWA{YmNyMj5-z8S=1Iz#KPO&TeznBU(%lQU7Txo>| zPNdw`0>1cao~cZ0Ct|xkpO3tM$JE-+iI_L#^Yv%$$TCJ6TWY-=M~k}?zmQj9P9*7c z0k_y>t|kk+ZJ=}8DmA8PIeRtbgAdDb5F4O^^|d9 z&$yx#6(r8BcOp|{89PqsWpsSK`=H0NapG5BYlT1;UPBopo1kf<&PR!#av`DMuZ|=v ztAN*@n`iR;=}73T0-iQ6&$ND!BdHyc&qq(zua(=eEn2IRaiU%2jRX}Wb_O_+rF#l^ z^Y!{sC0|*hMNEztxfjkT1iIAw@h)kq_N(6r5mx^wK?R9dK~ALhK6z)e^)g~7M{6TC zCJK)g7Zd_r_$(L<`GF6#>Wv4B-9=ZEN0C)XtsM`!v08!2aMF=@4JzO>QvdgvUu8G6 z!vn*__=IW7c_7i{wj=32rhxy*(2uHM|4D7ap`oH@>-h?SF1+e;hQdN0v1vaO0}qV) zw-@#QyleOtsc&tCg>K@*wI-t0mi5Y8i$s@LN0Rs^pD*tB?|vMtBCgkLB?ihlKKNVc zqO=NGoAi*Mw3k=J(7%6q(Xc@~@nX3>LD$&nj^w9H0k0CBXHtp$zxLu@ZYR-9^B|}o zac!<6iSjAnZ({YMY8quFwwLTK9Nvsp2y`j;$x!5{LG)VNTl75~soX&%0*^Y9WBm$v zg%rJv4&~l!hZ+nJ%Vwr1gyMqxFZ0L}s*36|OV6{+_W#)h_}{vW`u^Jg^WDW6j&hz? zD?f4g7ZImqZHx*M>eu<^HlwiI(?nb)OB4cKIKxq9W_GF~77b}BUc~Pws32j}zdTtd zu5<5Xy#-Kzh=cGu*j~&pY)g?q7tU~$nNAI@L{gcqBBz%VMFojB>E%hIm)CjK<$4+Y zqYc9Frki-SwuwTZ3v(`IE!zC8mO8w*h<@0HqJo6g-txq*Yr#uOrzxI`BQW19ggPYjdS&o*$Z=vgQdPVYHwi)*h(#wddELYcD z;U%KRm0_qLG5uzFvh&pye&(p&hHLTe0X?uSSUhM_QX$Y~)2kwBGWj}>=&P6UU-K-w zdKD9$oGLL~5vKjR@+3DfPp%MaNz~P0l6}|Ev4e>yzoWdeA`lXeTgsD40eL)Ewld{h z{ZnUYg*&yyj3W*Vj|5%nQMr}eM)#d;D2m)I$xuN8%abj#Dr@Mgku5}L%}OEA73f`& zJl=Jk@93zXdDx?5n)|qe;9o5nDo8|pu0V2MUFYqZ>%_&$ZfxYLFWU9_6&bdpu|kSJxUC)PY$ zYQp{*wsEo6*5~8+iZ{iX2#mEnkq?h6R>W#LiPG7MgD?lO8g|)Uks_S>OuDe3Tu60!@DoFfIsYKqdzst|} z*2^#+`A^%_bBHkH3{VJksb7Pev$kjr2M-ko$M&bFATeuiCDP%jyjD~7GVXZH&n`7MTQ9@^_H6SF z#~86MG*=|7JQpo29&ob&|TxcP9vVWXtb!7)d1&QMQDwBnm@A9m_dKqUrI*>85 zhKdeN&ME}DJVga^+5QI4sHKPn>8(*H0;1&LM*E0db$yZoNhCs{^Ff&*>) zZlKs3eODpSrPjLzFPhMD0|$xLZ7)$&kf?XDGO4%ZF1M+xmvQc55?wc>r*N3_QX$ZV zb-v7c8Mc6qvF|As^u9|`LE>DIDr9@~U9Pp&%kV$2gSIxc6Gzj(CdT)}Eqw z{n`pG?g>Q&3CB8B$j_R0`K8`^8Sy5a_~|fgBBQ{*9KeC|5Dhctue` zB7R5}a_;jT-fM_n#$>yq>_B>u7#D4!v>DKa?G+jK33Xr>n+J$%$KO&^kZ3)#3i-P2 z4qq)JIx>^|Ohv}-IEp)@kka-+7q--7R&ifkiaOF!N6*?U{4;E7g=GAX}bX~#O#>QKmE>A;y#`Y zTu4l0KJWH7PoBArVABSjcNl4E!42n#*tE`ApXyA0PkqG8R=O*XYFbDQw)tt0*j2x&LZFLyx)8Sw`8>*S zRT3?X0qlWgEm764DMbZ|%*rmLV84tl{X43_Uv6xKW)kJD_oApEQNM>XaliD4-zl#j z)%qun>{NVXVJzQ7A<%X8oioWZ$f(F4{pzm!Qktc?w-(}CBZ>+V?13}sU!{Ogk@rdN zp}F3gomk#pEQ;w)Q9+`OuQPFQkddiU`cZkWwPb%+bQOtJ8Yl$1`X6#8w^;%2@%^ zt1ydPn=@9fols7R!&&D$5qlYd>Ud3!$;mr-;y%ewO%h`lRH7KIL*heaXR`gj0>1m9 zUdF`zrRkZ_(c=D_Y6^j_!D&up;hcPa@SPrwvQ6tiD+DHr63;y-Do6yFoQa!^MtMEc z%Q$*6f&Te5Tx_pO6#`xM|2dKS!}GcOU%iam_E~hRL%djBERdptgja|&skXX+2fWhD z*ncUT#;u4FqpP)02z23?~`7}og3$9i}Qnp ze@-2RK$m(4ziUm|=qqIfnJ|`OtQcd~_y)^p)HcSpjH@haJei_Iosq!!wQN~l3uarh zyu~St$qIokd>;*lMN0yhrw9;-LuOJ`kT|i=iQM@7fVa2Pqvwxbxiaf(^~AZ;lN177 z_;$%Pm+w|&7ZxzFV$KYT3KB=BJCWC>hdka!FXL^N4XeMUwTP^ksu1YHw@dcV_ZMdE zZnYQHe5X@XkTCRfB5%h&<7yK_SqE&w|XkJ9&*Rw3B;U{7F~t zITGLfoQTElhrG*AJ#yDBX)i7A8z%hCBNPH%_)N_{RX zJmeQ&>1FJ?GJ!Vu7AJa74p#_t;kzkUBrP98v)06mwi8Dx?;sMv+>snMJmN!c>1FJ5 zE=lcnC5mDdx+?^_u#S;y2(>;z+JlX4lO0LnGLLxIqk0+Poi3VAdnAd( zy-gGXT^NU#>l&O-;VFm4h)dJkD)DwCS~hbe8!JBIMK|kZ46C)~N5x1D3m+``~jdrZaDB+n?P9e~RQFYluK0jPL zuxf}?0i`v(4|I%dz~9g+m~u0vVW9UVoSJIF-BYD z8&y%Z6%t#BjpNHQRFJ^clnsX6h1=26hdPK(?@K5Iy0Fh6r+@f4(0PTr$hGcEFjSDh zJpyE#db$N|!g`5Kt_Fob7xsPRJJ@moDJy#ujgDH%+VubTmyp1n3uG&Nwvk-lK0r8M zdZ+Y?(1m?C`8C+ni0}Q}PZWRuRq3lCfw`ly&uKBqyy4;yVe|8rLZA!#qH?Cimgi=> z@Im6l{`*Rw6A8?2H5lfN_0s}ghl}u@hZO={*r%4O2s*dctd0#9UMo*2eP<*vdrRh1 z=TFqKNw}!EaEn5q3u6OvEsMGfv`*&-iQAX9C@}yeFuzP@F4x+wRU0`_gpOOP5a?1P z+nLV;#i&R1#LA`Pm67~VQkneEXfH-|Wb`B4N4V!Pk>PYw8Sh5|M}!Q9fCAZ*DAiJ2 zp4^4tZ=nk#I&viLWjS$zwG-W!MH5tzz!4!?Q(r1B`i=<^S(Oeb1iCPyBgZBVTZnZ7 zdx_{oji7>rS~Eo1J=Go_+G6J zi4+5y1}Fr&Frp*ZFzvHi>t8iiRG;BVQ9%OhM}whFWQx}O;xMtN*>jP z%I5L6M~J6Arz-@yFrp*p(L36h#*9uBlRl?VRFJ^$uEB6`{5*29=x|XgZK*<_3nMym zrI6)ch@CcElzupaqJjjrALLxJR`uz|uTdg%{zipB7e;jC?kZ;@X`xe5;>xwf6cr?} z9VBCY_2<&88v{lCPP-KXT^P}k**lh7=;`yJB4*PXiV70go|6$smy@*B`)`j6(q1-YB20c`bIykY$?cq!wP{ejOfUiOqF8nhHGIDm>@=qxr>7hc2ZQ3!2XWRlQ~p}{oGzwT-jk(2z04gNVmKju)_5n zM3Jbi6cr@YoFeyKJy=!aac$@1y>#<3U-D+_E`BBDjVbM^FR_i3duN8dGVzjr^KnX&oR*J>|1m0?LC9;9aV^*sBBCD~{8AV=$F^TX9G$=#P8(%_Lr~KR6lT>QCp7*!W%UJE+k!2;6W_iD! zm~anB+(B~ocrT(&$mT08^>}-S@*P?Abh(dPiN_{Xkigw5sClXFeIf60AV ze{bcT27OTWWL5Xhe6YVGo3x`88`CUTaUqTSkIFft+1=R6tm16dcn^XK5(g~&$c*(n zcxJVi@}94}(vcO+Da8UmEioa1F5IP5K3C7Wv7OC|vsrRA6I75me$S7jJ;~woPUzWf zf%iMIF&U-UiX~%BNT3V%HI*|hHg#lk@0Vg#*ISwzln)@c%I)RL!tzYGi!1ILE7$#y z=dpE3DHhgyjIu{6mZ9#KTGypJbGItaGDh4rp@M|^e%yQ3kyS}4#cF+Pq!8#*k1DTo zcV>6mip|}$-h>Jg_&&<0nsayd#G^QCeq@S5pbM{v?6I^~Lass1Rorbq)VXO#;@1&KDD14y4!xxB+| zJ>oU%^=MYh$5tEp$yXuJWqZM&wEeZ0x7@FnG4VkHE8j9vTiMo2IVvo#CJ7*JvHSUj zH+mWN+v8ZK+br!wdP9l|65d<6W>lulh%rZNu28)We!xYI}+b5-w@77M+#LJ-_Nl zm3=*w9qD>g`!Jg-1iCKBI=I04z`yYXxi*z4nt8>})Si*?)aIifdER6%-?_iQgk{Vq z;ZNr7+ruj^)BER6?}xGEb|bX~vqLE=NZ@sot5ZH2$#!Ix(Po6J1iBuT_b2a-a@XlG zdKrPIN3+k4=gmvXHK(W`q2BYfuq5_hVx@zQ?hO?JT_r2|lhxC9^WaW;8R1>Wvahr{ z`FquqqJl(?i~i)lfqVJ&Mf%k}*0d)pJ>`_P=HqsXU(4{;e&q7dJ$!H0^Z)hb-1)md zvwN~vJD0zT;x`ouyy`N`;&=qp;xn|xm6s|6x}v@O$l91)+$UK7I=8tO!%7a1)CS7c zhfqNR@00why&2A4d6m%OjMEfCan+}P za@MSUyEs81(1lOFjH=D(&)mA^X)jMFQdE#Q)!m;Abj;=FBJ?sUKkCoc7QU)Y+z_V_ z=)yNx&L+P$ob|bT*fe6q68hEGmkjdR!QTz|XnGgqOQPm&=l(t)O)bB9lX?zY`S&qD zWEnFz4riUr3rOt&3n?l{6#eT>x=h%@Th-HvkAZQlo>ytoq>h}84Znr1m=#`R<@}A@ zCtGh{S^LJZqAhojI{P+LRFLr9;6;iT+sG|bb;74)6l=7j6?r`Is6wFYlB*}_WM0RU zUKEzZ=re;@>WdbneER~rZ;CrP-e?ss^rk2olI%{dPFlrt3Kb(Nu|8xV%N}{h^zzRO ziV70fC%O~M^i_O%VSQ(ZXf}}bJ$%WOBxf%pfv#}g(Pk^3g@ zc-)}0qt$l%qf!mo#LwAU#0m$7t$VA1p5*HN4Ltipq5sv=fAp;-`}k$PHr1j8!{0(e zJt~JqA#7FiKH5+(gF>JSk5=|lC-r097MQfSN>3>&NZ?g47}msgWwT6p#Ewp5pU^{T+PX3Ip{8)Jhk-)2NFdUB`%JQzaH#>YkqY&uA8bi*m z`5Vs8g`GD)r^$6X6wAj>oFVngPsNw>*GthTW;rLUg-0qQU*k` z+C5_EDEIjkU6%fy(J*KPbF7s`>+pqSSzFnIsJ@TCUzTTTDF1#R zw2w#1zpw1@CwXKK&+MeP$Sm^W+0gpSX{O_Jf(jCA8U~QQ7xwbxOuZHEaxsQ|xw?n8 z`ZZD^&{amZ+ixw~%TNECJ#eViSe87^Z0?onK(Wu^*FAvz9+=Bx&*ho0%_wJpCXHkD zzEm-{zgnE4f<#iU0OH`B%l{tHkE%kSLitQVeL-xXX{giK-U;ad^x#~&;LiPiRj7FTNh?wPYx4|E#O^K z;|x1f`?0AFKhP3;-Vs!g!22&(3zgr&;m>Z<+*%eC33S~n?@J0LZR4dj=B9|$ZF4>yj!H+7R^~Wj1BdeNAI<9p{O7+ zs+u1O$&ugrwK`EeDwf&XY@$uS{2)l6Ys)V`@+5p0Z}L@-Oe9(jXUX+u)8zq0DJn=@ zw)ZESzU<TaU+RS^SLZAzu1%qMd_E47M@sg5=naWdw1je%D z3j7a-Foz!3sr}zm3V|+s3uJWg#{jnA*elv^=q7>+5*U+{`3xZg*n>`Q=x#T&LZA!Z zO*v=OvK#x_vjp32*IIeckx=7_3u<&^NBWj#Ya*X1u~&3q6jw%TH#cVyiBVdoXJr_+ zqslgOCuioZ=A)Vx`(JI*KH<$-Slt*cuxweSMTW$mrtZXH{%Ss1((+p6HfHDMW@=kn zsRX((;w@M4=vI&A{9USDGdL=-a3p$FaVK@`*YKx3^)jaUH)Ah5ZqqKWuwvLM{@uWf zj4HR8&wFkl*pf9E8jWkoeuv~}y}A}+s30-2r8il}1tBG_{=^ zy@dAeM)~)YQ7d_a4Qkt0e$UMjETZdd`s3?difvpZK1#aD*p>X$M!lVAJ2H|btWBVM zhptcvbg8ZI2@yjXX+Ds)n7Nsvf`q#)#muWiudX?u5a=RV?j-Zi zO1}1nPWYW4%gz;lPU`=L%utP?Fq4? zlj=B7{4I2;F|veXquAeKjp+8@c1n~J32Y6>Y!T1Vtn$^eG$FpGLZA!db26LCC6QV8 zX+gEyRh4%T32fEK2utZimb~7Pp3%B11iJ8jG#EPjj$l_lwx{3nJ5W@Rz}A`UZD%L2 z;-@|7O3x&PKo>@)mScn2y|gAOGZ-v zi(z5bg#I-zr>G!-PpI6Lya9mz$)+o_c*RpTB=@u{ zsT`2Si;c6D?}tTpI&Iu*gs8FqJn6FCpLmRk{WqSuYo|YXkQn=~4>-AxAGsSE$2XtR zzns=TsMg5EEbr~N(ns$l$HwL{k$(L;S5W~wk{afWfyD1z0HD7xX@QfCTbtA=s zQh89nl4R*TccK|4@@j8w$srk;+?+Xq7c-WWWvub;%C@gtsoAfSYc#%gB`h_AkM3QP zgiSG$+xyda^~ojWz8ps4zAlX~$<>LprTtjh4fV8RZcpj+C9b4cwb^_~OU@yBoV`f7QpzVyC{x+VxVswhDPiB>Ot z$V+29-{hjNJp4FfEj5P43wODLBogTQc+H2r3yJ4j{_P?CdFMTvB=;CO+#u65D#M$c zOitjZqe_sZG2Z0X@dUnE?i$)}wGT;{D+!{P5&q;7UDqu_tjw|^NT3VLGZ-FLK0t>K zm$T@KrJGPeBI%qDu?&sp?@H=rT=(5aix-I%Sx=@Y1iIAo*zwnfom<&e*!fO1E%Wsv z29d}cWLcBn&R%4yIN%>d$VlOHtPKQ4g_Tq7^{`U3h+SE^?(` zbm;NE;*Mpya;=bP_t%Sj-7$g}{M##KPsPvFC%3=I49-vpbm5hj?cG!5Sjp?{M5j9` zCOmdLLh~F?GJDKu?tEK+&&dW?mJ-rTlrCyPP(k9wRS%N;Es490)mH`1Tj9ZC{Tqw? z$lfL-(ABM@Cvh1#hC3Gfw~lb1ChS>lcQL@Sg{kWjcT#TNL>}&7ORVp^lO&6Ye7LNM zp2`28oHda@4A5&h=XlC4TlD1EQJLZC}M^URa2S;n(U zA~B$sa^`qW-%h%bbeRV~ELuPFhwVGF^)2j0Y`6tM1&KY=+{n!7sr=DWow&ELJF{$S zCHh@VG$Dbm)QxWBX}whLJyIuzWJj^`C68!d*Jhg7ej|DFFpZyBZA|vd_RcI(1G4z5q)@8a06(j=6xsjAwlliyhIuW{H5IcAMv9@|?3FWuY zg-0mAYD4?7F9UvSzl%>cp@PKs>2Bo2qEvqB-*<3Rhn`HPK#1wLk`w}6>Y0n*(JUdB zYnNK9XO8DoI@3sY?3}_^uGP=ueuH>6YS~(?UAGbh6(nNZjAX))3?8&tCo-##Wa;HH zwfc)wOh}+B)!Rs(HO%17$vP2bHG$2y*ovmveSxsnHOr}IoJ zTaqgOKi(pXzwp+H;#0@7>Gf`!>y~YALIsJ8$FAgUrRm%=P$x7omffE1tff5rr4Z=C zBb4h*lulx++BVl_WJH-zLBhw`NOH0>_|y@48Q;E*V&-Gfnkja)LZC}Mb2@th+p{9f z9Q&@ha^`qW<7L~&r{+xlbd~-N);&9c#kk($gLl6-p@M|f1=(_%K8r_=(1|ZkCotpj zW2QixmI{Hc7m}zqau%=DLnof!OJdf2Yf;nIsU~|1Bk{jHm$#Msb{#Yr$>Fne`L#%E z5>?1Za-YxTgVOX`w1ww5W|3K*-fTU=gbETp?#uSdw%L3_5xoqD1LIlN@k69d*}n>b zE<8fnD;ht61vVW^l2baFP(h;GC0DZb^eq0Vsa{5n+zD*%<~qbGwyi>-OFi@4C1Y6K z-W_OdlCGRNp3^ClkrY}#pMNv!-@&4?SM-p^(gI5>f(jCoBaCG0&jozVAf5Oya|9F7 zGwF#!Q%y*q>p*`anIRVNMj<+Jx8^W*v(;u=`9!)26(k0}mG5BmV(ww3w*Ycx#IV30 zxil`gC_x2@yRMZKwAc8&Zc!_q7O*0{ZF80|-Hceg3qkrgoL45fg#_F`Y zLASKcFrk7(D=#&LDh z_)d3pk}VndEp#O;b0ZmVmh$z}bYiv4tnu1igbkUUVnPLp!EfBi)Yr@S&Ifwywcv0! zW}i`ls34(cW-eIYfmt;x!?v#&Z$biHnAa)C2m6Jxj*C8D{`Xu%uMFk1$>B&3zE1Wey z89;rr4k-k>FcM-gj0@?=W=2|Q35V@i;j%_j#~^NIbcn)Wu4f~VF@oiRxhLCRDV{_e}-1tHi)6p-N{Iv8kcgv!qx^&wevw)Rm7bgAd@tXvQ~;WJZf)5@Qrg2bF* zM&gjQjBgCp&%Ai!AU31fT#XPvg+N#QX(PGiu!1+;r`JBdjcPL5ZJ}2BqZ`ARH^#zM z!pYUdwhWo1B~ElOzo;D=Ya%{ zC&;z#e>P&pzIM}MZ>a>j@OhIf0l3nL!^9A>9iIt@*`Qkr^w?4186VKl6#!m2|+OhB7lrr#l)tJop z6Rlal2FY4bo()3WzR-z}nZaz-oQax!u8%^XYj#an61gOcw;rhzb7nX( zl9Hk&R-kO#23OLiQ#zj?WJeB#x{`A789d+Gjvy_s?sg}3YJaMB<^*A=AhDyNE2%$x z8ZY!yFT**+lMT&I)qGuQD+IdKqpJ4FnRRrWq_tgVVyGbT+s2jHWM}d53-mJH40K_E z_a!naG#ir?0j%`bXX`y2n9Vk{J+s#!hV$i$+le8g=1ezbJ-WllB9i(t7<+@pMN zlGZAoM>e!3<@$S(UwuaK?c;1nr@P)Hbz?k#;;nx<&oA+3NA1dsa=r2?DoD)i<3)mP zM)DbL^!`VcDqgJ3QV%ip$|;3FSBtB%j6%bC+`rvu?JaCs|FnAI^015aT+aYf&^G#C zPOAMaKT>#Q3||;#MOrrxAbI~q|G%*!uX)9pmyKL+sq`s|3KIFv0?4$((Y*G*(WM!Y zZCL3myR;e|ekj)pua6o--c+m+3+6AN3PtmSr~3V|*h9gy$f z6(ei-V6ql}yDl@F@*pGEjN;9Y*^-v~JVUFxyL$ zwHSkm72WAZ&W@eP2VO5pru1sZQV4Y6{g+vKhy2<2(zi6* z7M0lN*WRRJU>twD!I~tz@g`mEhjF=wBl(`}OZq3p@CViO7P59afDPL(w9ngJS?p9_ z@+BpjXLcz;kj_l=B}s-DUb2Z!?7HmFrUvC{2WS2HJrd~p(c6nOS((7wZPM%A0S^LL zzfPC510||3RFJ^yCRf;~62J;FxwgNXn?j%~xr-Nhc6~U{x}=vO2Kh0&ZA-Me69O12 zNK}$nfkwpg8i)1o$Am3`EIew4Hs`Lta?eZ1`@eKc6u&O_@jiIVhr}(3=G0Or-sT0c zZUY{p$WI?8%z9P1kPEtfdg>+MDJ{c2^(4fBzddu+DD6MmMe~E_4s4II7!wr8}wG zdLn}ypg zG5^VEr3@TVMq0K@7BykE(WS-hDKjW4NVqL`C#{1g^6~riqiQm`E$dLkQVdC0q!8#* zkIJ*cQF`Z7gcx_JIK@%#9SMHqYPC3?@uV0Dckm@|j|}6VL-gME#4-=)7VA*a=U@Ou z1qqXzFPWA$jJw3^#QL`ew%~dFn(ai?w?PyY zB#IsKCVf^8=lyT#HC&HRl~{+ejl}ARQ3`>smhHVr_m?Ai{xAL6J#xT})fib@e2d7U zs2~yE)r+iIKayKj(4VX1TS4sGZ6ERJ!~%stR|7f!{8P~+{;jBfKPLIqV(T|LiL?M?s?9oE`Ma8E^8b%Wxk2 zxdg$sVPH=$;@W#8Usqi}k3Hpl+2%ZV@u9_GiV70g%9QgtHMv7<#|k3w@)?Cd*OC_= zBrJ6d_ciI~;dHtND_g9jhzc#Bs33v$v5eeJsm0!RoyjN z6LOsfY$u`%+l(^$VRm98f~ttA8NVpzmtaoG&gcNL_+He%xoa{*$lu5+bSW?5m;a@x zAhCP6FX=TnmY=cG-@)XTm6+od58=G@jY6Oc`y~cLYFHI^znX_=aq)%HV?m8H15Wx8TgzBZ+v}0-Pxl?zg!A>qhPh^n3KB0m%35?`9B*?-FJtp) zEB1M3Gtn+=i$b8Q_8vcSwr?zdS5q(JYL61ETA}7*)P=Pa6(m+S_9Z*s#qo*RdKpeb z|I&yy9Yw>2a})wyVx=EhzCD&dsjQcggV6#`v;)BH%uFR{FrgAxs5ry+Ahr|n8I$u3KKe4>!auaC zSL_%nNMP&CU~nz)X5({AV6f03Ct0+SS32bG`C-Ip(`_r?6 z7;5-Jkw6zdV{(rXXHS-vSy9y9{+6PG1V$6&lep7`ohs)c9-8he1iJ7UGZ@~78`;M_ z9^!hZ8x$2JF#aG%s`plAG4|EO#(pOh0$uow$u$~3IWi~LYU2J!K~X^hza{dE^S3O! zSj{9l&Do|9=)z}AjzONPz^WdoFAnha6cr@!YbV!ESZK%Yhcy$2ip*08bm3Deql4#f z&{JPS#i@CeV(SH;S8Q>}QOms_XhA?v(Pn%oMFk19jPcX0nC+VOBKZ6Wg+Ld!IAjLh z$5M>NH5D^%Wl~g-z;lvWdK;Ztn%pI(!@Btjfi7%u$T2VC#m=M#iaF~yP*jk>mVxZ6 zt**v;g}I7lRdN&pUD!s^S4peITC#HDQPvTP3KG~dFc{hoka1my;-d2RvkHMOwe9ny z0bxD+8pH|X6S-{9b=XOpds=d3YlaFE z*fNl7E`P4Y9A2K$epV~35a_}vh0G-HSd~>jkgIw8c44R>f!}$#7k0k@)@AMn?Z_~1 zg+LcZDda4nw;pVpd6u^Jd@xfKXp5+^CHsc1%;!m}c4BsYg+SL2B~s+uryuK^`+i;S4^xj_|FYH2qX>(ZTqM?Ed3J?7j`-TK(eWY_>PaaY^7? z*OVah7I~AZT@$!py57pzaLkS!xzj}T$Wq+_=>O_9KrA|E7+OzB39YkolEky;1*bFzac}yy=byX*JtnA74GDGN=lN|HvuM<0Gj$vMfe6{NCUkDQDT5#2s zw6f3Q`Au|UcE(utdswd7Xtbe<0>7Jj%9XhAS-k32{V8etVH_K@KiC|;=mS9lUB2gB z$)UBgIGd#tKjf_6#rCgF7b@9MRFF6zbFnJ*W04j3*%X%D+_3c8y^S~=z1$7 z^u=E+=F@|9Vn2^&8P9jnZ>}XMDo9{GCPys~MzDT1C#mJzw*(1vwcqMS4u&q{rB3KM zMH8=uvbvid(}bFD2`Wgabz+zFK5WI5pVaHrX@x)+uF7VRA;?_%yH1P<&z(XrLmg{W z%>I_M8s+S{u?~YpebW|#3KCem%G&4oOS&v8R1|73RUy!&=4^)!F3t`<4H02gw<+1` zNMKzl=iTkIW6j(;i+V-rzt*j6Qz90{x|4Tj&7d|0>gOhja- zDFnJOqgiI8gwovFcVmg;|v)i{Z zS%aW<+Ft8z1QjH(u9R1|&setB)=9fsZ;C>o3v*!Q_<8Jj<~MJidGWlBO7<`kSXauK zVFM?yIO9paW8fr(Ko@47%H6a1c-B+vO-dixL{LEj>q^--_%n_b^u9r+T}W35bYbqO ztbKluVe1amq>YoeDOtBjU|lI!Lp(T&ovjm2d;XfL5a_~8P`OKtPXfDOot+gtnQn8w8)_} zg+Lc(Y05t5`hM)~jL-D-?`(n!5^BA>WI+$M{YDYyyL6I5pbPUl<)~%Y5Z2x6IBn9f zt+E=)umf)7(Wzzp(63?yS3;39U)Dshv*&lvUyu7KE1n?H%Irq^TP)|T%Igu98QsFz z?5dnj`O;q@(1k0y7!03x3}r?5GD`eXl$BeMm?X>iQExf#Tum=yi~mrzt5gQPSYk27 z*{e8PRwbr;4Q2b@WzfF^7Ex4?z?r&oHIl&*?91cjbl%OW3V|;5Jjkm^=HL4*c{0^Z zO&?`GrTtP~=t^;7e^6%1j$F=Hwz49He;Uc$J4<-k19}VK_2(!iK31g_25h0IAc03K zBPG!-PmJ6z^;aw_w_z$>ni#4O=(;M) zDBElae=}4sW7EriEcj7d^Sw)7=>DJn?dvmjfR<09Dw&&uTQ?Gp-tuCl$1B_Yx+uU^Kr?BQ&5%kDHcZy-el3H7-e)^#Wgc9=jPd|IW{ zCHQ`*S>7WWN3v2Qy3>(^H&IlOz&BW~16h42YrM1?op<1XLZAzC(&d=fP+7y>cu(eU zJF4WKBZ2o{?sw-B&VEc>O->fiQwVgaS@+R9hcMrRwTaWQJ4y~c68Id;x_$gWc4fq2 zQ~jhD3V|-nZk2O0It*ZrIfZzmVrmvE68JvK+}dJ&*rbi#W_r-T@VC%~S-J*8(9K@# zY~iWqI>ps&TqLl@kTt`PuFPxtZS$SW#g+VBbYVWd!BDmBXckg|82$3gm5ggK zkB_@)t<3bU@zs^|iI~U#e$wCC`KD1UBQb~nmGkIP!MWi$XWU>YeQN|WzB_-=cW0JD zpeydJD_M{+j~ngv-uBmoVQhe(o!QNABi$kAjD6ock8@ueg08u{T*=`=vw0nZ9s|g% zm%!TPG&E;rE}*C&f#u140R|_qXR9uozgf&s2y~ebyOMA9viPfodKoQhjARQx{xW|W zH-@5uggPt!>eK`_Y-R(k{L=`9K-YRXpJG#D2G4n;m$At;iczN&^PW;i=%1Ueq~p1H zd`%M@f>&Xs%+j^1G@H9t)`?y1Vp+iBx#r~-ITRHn@QTR3+NfC8{^WP_gL@kl0$ru| zyORDbvUtjFy^KBo4P!MO?X3|@O_k-PIHH` z>NN_C~$yz=4AZ30O5|tadl7aut=jIoB8T~(cv(VPlHJAMA3V|-1 z^CkBtzgmfH``%0xTTqSSm#&Ed%v%aSo>dNiV6~#^(NQLh^)$7y@SO_ zxsnbN=)!Rdc?UaFHp|&vjQ!P!qJo54GYIP@>{phPXy#r`A<%{66ms-6yFK$7U@PX? zG^MC0gi>Ewv#!jgdr`4_d<})b`U=M>fgQEh@yf7ei`J5$+;wU{#-k9r%g45Ko^cv z$nW{a(QH?v$E16s#uODKuqPwOYu}7wp;oTccTrV^Ko^cv$mrnm5iEXch+M_9Aw>lV zwO16rWjL!aIEA(nfeL{x9H)@6zN}c*tHvT)wgjW7Ac4Jm*(;hH#j>t%r>T4W6#`v2 zP9b;BDjCjx%|A?AN1G@rNZ=~Fa^1m$q3l!c1A4ApWraW&jt|SM`!s*{-@G@P&(Ts! zCV7KJ0pv)-$baizV-~xd$y!OSM$+KAR&GRjC0iYdoofQf#{Y)?zcsMG6syWswmPBt zJySE{(S^D7GMg%>Iy=$*kanqS6(yec2XIkNWIPRwQ99IbQk4`tmboXvxC3FRvPHJh{D z{T6949c>vZNZ_m+eJ#Dltaj)OZSmJK3V|-1ODMmbUuv;F?PhBK-FIWCAc6CAWd7Cb zYV1h#RBhRRz6yaZoFyn{HJ)~7Yc@{SdV1GUW&39+WO7)^ZxukulfGx z!}EGF_uid5_sp3yXS#{ww()PF3imFGFHZ7W-aBfb1y{(*M7D;XTG&=NF=4ELX?&ln7K|PNA5w486>chQ?Uz5(i4TgGem@Q-`g& zk)&Rjt=&h{!*4h{)y48Nc7{Zt3UecMx^XjJ@x{5FE$K_8m%lfDs7YqRAG*%*nM_7hhOoHu)OH7L(1huVxN~MYgaYtzp9QqTG&$QuMI85 z#f}{OTd2ZZRZ;h2SOK!^X<})Sc3jFyMWVXilf_m}Qiq+?p4F0Kw)CT41Ivs>rz8SZ z^4`9)4-$Fd0V6Cww@;DkwPBS!TwNA9+im7@mnTCkJqm7@)}4{SJ}us;{d;(W1N|+J ztBb0@P}L1pxCSkvoC~h<5hoHX3kIf38A3=TNIMiJt`+AR{O)c^8s@<9Z=ni3XK`ZT z(1OHu9W1dMyd<9*3EYPuDzR-UP7^*gv)p-7Um{S2{^7f+{iyxW}OKL0dtZFoo`P=)aau~MBFPT7$k%$Fn2 zOK}DyaCfe#-FBk`DXs39n*D4ZP zkdXJdyF3h{J-4FGhPl-w0#z765LtQ)JZQq73Fa}=y$LNy$Whsfvp*M+MrZ{nGlY!rI8e@4e;fV3JjSsUn_EYEF z&o^#J^kw>-J|a6S!?o`KQ$&T z4P@WWC8!r%o*M5o3Sy=Ei2pa;7evX%2Hv*P7>ny1Yh$rVLF{3(1hsX`yGEaLL9C{0 zf;w27sVEb33rF#;w?XS5}G=6Iu5V}I81PjB@!`(#`&IDoB>>a8kU-xxoi31BNL^;V0%)Xr(}Z|cL( zT92{p+B#OUAdyu#kbQLNEq2bn6vUFcK75gGjAd2wYGdnZzHIx)KI)S<>Bg4D{h3>- zK59m>&&CIx{h8B?-fCooc6x+=5g+bYV2q{7pjDCu3A|eI3*PqRL0)4lzmL8#hIcfu zdKD7YGDrU!+paUPhp+mn%UyJA;SVo1<58lz=%tnLONKt?Ji6g%OT$QS$$|vdeigOu zYn9|FwZ>Y`J)CI7zlAESH7iyv-;|=&+iF`1M81`FBH`|%VorMYV`5+R&Ufv6oQiwh zXr+HW%jK|J94$!XzV>2cd-qdqE@{N_=hdl!T?tXiGn+rIt7qrO^-(QFZ5Zxp!M`LT zsc$P#g1(aF_`7te4J2@HmQJ_meOXGLUCq*`@@I)a74FRvGsx`*y0P%1xzaLc!kH<~ zgz;*{`Of=2X-GYt<+`W^ffgiiKewpx$7@mLo(`6uHEbjTRd`QgujTeo+EQ?(d03nq z?F!ekX5k6yw?G?)qs06sdNwOw%sD-^Q+2~j8EInZesi@B#R)A)$YaTkResd6>T~n5 zR7Z(G72col;g0lbIC1BH)jM| zwwpKc0!_V{Yu&zTjX64YU~oP5+og~CxkJ8j)P{O&L0$3AFV)UB7^=EcuRy(J*pMR< zfvUMfyjf^iAGPxV?R>TT-+KD_w49~I-!mL7NF2XdkM+_gsN-*FZIrb4rFHd-S{~KE zClRRHz08|6YSvrrd`oLXcOaA;8swW#ba~Fvg2dv~dMu`5yn5@G*2b_84d^X*EDtK{A=B)1w2~@3| z9n9=|#{G9*(HvtHaxB`wvSi$Qh8865%?xJs;^S27f9DnDeCk1|b+(#I4L-mpya`~3 z%lA@e1%EacS{cB)h4xbCPDwNJc>yfEWvp6%sCKU9g|AT*ymza4;EN+1El31-1hDQS zdZ~NG8QEec{JJ-}9ouSdyKxwIvkhkHE-~teyywR5UxV1zvN5V<`U@lJgV|19FSTgC zcISu2cB5zN7jxL{P@e4+%;wt1stevcHTt?3S)G$H|4yKl3BEUm3RQh*KDO3}qXmic z#f1_0wsAH{tvTEM7pTusZvdyY~s8F?m{rA>=f zn~8I<@b?$F1|=KNlEdznwTp{zv>@UCHkg(C*z3Que(UaRMmNuvw7jY3ArYv;XDG5> zy0)g-W+%(fot31gi$vbHVD@@xFLkpxjabwW+SG}1Z(CXXSPh9l6+UTk8f{f?{dYJYi5jPb-xX4Ufm$3tDK-V?fKMruWB$;CdU6e?<{bD@Vgeot5#FBp4h&} zFP?I-o2BTpO$;qa*t860FU!ZPKUQhaYGt}Tv7`=`2HTEG1giQb2D4u`>r>Vjw#@Bwj7tS0g5D zDNd2w!z>Fjd?f-^?~4Vns|Mkh=4k$v>ya8X&@0GNe|l?<79`dm31st^#i?;3li$9K(>8dtXlnu*2dq* z4JoUzo5gYZOo>2MwE+QaR+l(+TN|y70;Aec_QXGC+X8bqT9ClES|2xh^%;??2e6hx|&gJZ(2ZB2a}rU#E+#HP58}S&%13LWNAMw zn4tv;`95Y{IKVTS_P4aXF-;;+Rjp7UyR0UtFI==7vLkkl4-sp60 z>^omJJIdlb)0QKFs*uP2Eb4QDTH>_!e!OYwK$~i}v2^Wh;AlYt-y2aQ3&R_8R;W~s;8Ri!A~AWOpyqc~cS!1qQ(af*9T!F0VP`t~e|K$ZO> zKh{&c=ffvxZA|kBrnc|PTY?%a=4e3z-y5-yB`}0`Y$#?)xUxwiQ01Zeu}!}5>Y4*u z8#R}N)AlvL%|{n)=V(Dfexs({X+^z;y*JyQJ|+>Ul4ta9;<`|YX(sb>f0d&J3E3}M z-*rhMP=(P1k=-UT=iW?Cv^?x;;28PGm4>@d3@m6|Kb3+tKe5;BrF`Q1 zftJ?qoH<&Mz_k!jVdKm^-s9k4%cU>h84{?%`KL~Ix#uu$)pWS!TJC9v79=prE%pfy ziRM{vMp&F5t&#{-;fz&$KPH^uSB588-mYjX-8o(%u2YELyueL9FE`p!p;t6V3lc-z zyqQy4Uo|UMdsdU;pYf>Kk(OgV(4j-l6N4bOo)F(8|V!vh& zM+*|TvZ2#`s`8WDxVEuO3|t}+sKTcpzBqR>`Ej>4mVh zu3aV(sFI)V^on))JdZJ!9o18%cnLY|5zJ+f*h|4|{*P$2Q=w;K zOzhK3>|^P<)x6Q%Um{S2vn8>D^`t$eMsG0hd6LR8vUxha9{c4Gr+zB&(}*)x@io}p zhB6)3o7?$jaI_#{>R*pVHIGwEf6`7x46hPSudW|4yPe6B2vo^4VZX8AbnVO<^Nl_Q z2rWn?AM<7hE5)m!ncDjiySN!8JYQuVon|KysM^}Vz%Jg4SML|q;#dBGZnVum!ZNYR zMTWjJ&SlZ}6+11em8RN%!z{(Oq)A>l5;!Z?>CP1@MNuchEDvTE;rO>ug}$$-nK`XC zjSdg8Eb^ zNuCT682u8bt3>QW{-JB-&o6*%|99bEmWaDFDkbj z-N#S1>u(vqYP&QyKtf*47*%K$kL)qn;_lE-B2a}h8If6&9>vcd8fj^}>AAG>gM_^P z;c?W5=Ua`jgf(s?5vam-BM}ik(w&bwHqz3vxC6s=4r~J>A>wq$hAa5cq`{U|SLZRb zAc0Roj8}E`@HMghEj=e+mIzegS5%xhHR?VuHzL+Db)g$a3ljKi>U2$vdO{_dP8l5vaoT9i6Vh)sB=FVnzG(oaf9AVLOZbR+R5gjZ=4qur>StC{_PHHNF@U z$_l^vt=I;EXc&2H@xLaW~-}$X+>f+LL%*~HI zHrlA{mksOJ$d7GdHtI#Q4cpM#kJTS)t+u(StuCGVT9Ea5luRtRwsGYS&gP%aQojFs zW^8(fv1Q`l8!w5~Oe@Y3?`J9RzH6(m_J!@(?mNkJs?`MJBwaAuCRD5aGmPV32mSl^ zm2DZu7cRl9wIG_@)#9QH(z1-d?62n|815MenHFe z`W9=;((WeH$a!O=tHLWe~idgu^q&9lY6Al|$WP2Mmc4($C{Fsp?h<|U5&om~V zFfzA!)@rdnnWBx!lcK5f#^0tQ`Kc0tsS*qCq|b;DWBZx2-3(2S@wlW!YmQCrrZ zIfvS)!;V?AU+V(cp~g0nbGiFc#?gXAot2?%Wspwo znx(x_*P15M8h5c9H?g%upz8MN5Z2pUr;aPEwNbN2U)u2Y0DpTXfTIP8Nh?Cx_j)?j z{a+iux5rU*$~mrPg-Hae@SPX6!j8n#_Rr_|_1eB1El8YN9?E*x)v3=jwfks$AcmYf zJ>+X+y(I!w@>nwY!f-nFv5@)0$}Sw=iE@WR+1VtUf3sBV`8wUI4gy18^GX4=cp2^KhB=L;Jav~hpEwc7b#8;=d6DWzLk^achqAR-3#dQ;wQ;eJ*f-%ki#C&~n>@J$o>iKFXLg~HeQ_Ho7O*(x8_&{3xzN-e~CkRQu?s8c7N zuwhMR_^@+B|0oCUYH#gDr;?=sL_Jbs->DPl!q!f$^7>$j_bx-VY4k6|_uWHoLt`~2HYB2bmr!jF}|Y^7c~t9cod z*0d(Oml^E)MHfN~65DqLh?;;_>XBYr8_x=~p!@;#x#fCMi9pqw27YYfSDkvyq_t7^ zVmMW~)Qi7!cOtYPVZSkeEzH)by}N5|bez|iGV_-3g3p{K0#(>6MGj=2CiJn^Hs023 zM`%G}_S^t=x~fjy*IH{MbVDe0SbT*mIW`i3D(saai?zK!C4Er%*8Gyv8#QjV5BpP8 zr;?~ck8O*7bv=;A#qHp2E0mGiK%)P4A2##7PF?+7>$_7{5v>`qjF;S3QX)`=&roEm z*C6_3Gm`%tS3!DKNSxW{!<_n9srlJj8>f3WqzzZw^0|G=N(8E~FNo?ex&Lcw1Q_P$m05`>ua8-hYrx4#w4zAC2C!>{Aa*Y0pXxNv7zs?vl5S zgzQthzJJIrJQQ`dx-OFlRMlzi&;Az6R%%Yr{C4V{$E-8Q5Fc`qp#_Pa1H9Rmzrvq? zsrl`-9|h>;z7WuBOe)Jb&^hjus^P?lQ8s)>i7RNUe?7>^4+$-6H-8KmB`qtu2aq7S{qLD!ian>^Xj(WBm!0PNPSYA z05;&kWB%3l5l0IWr=}X2W%VD$F;Ht`<3OT;W&ZHi=Uzz!s?dKB9zcZ#ptX^6#6T-om!w_;Zb<~HWWS_`!9X$PD$>u#3P%ePVPQsgZ@lni z{{G7xSn5uH8`Y&2VP=UymAPsFODvPG9CgsXgGW;<(x%eBbfx=tjus@AR5h|mRr8g7 zPqa3+_HrT5h4pFp!EF+Os=z<~EctV;GB!hdYp*YHq!!DX(&E#LI9iZ+lON118M#V< zLs}aPZE|=4k9O3r%6y4H)rY(OEb?=XlJr1pqeaX&-n~g@GG&e7XhEXF^?-+Hm`pz%#Rl(WVE5Bmz}9 zf{Xmbt*v-?m660_A4^{YBtpfi27`Q3i(NdIKYbuB0nsKO|fs26_RmPLrzQkyFir1%vQ82u7)IM$P& zWFx7_*O9DA9A_&gW-FBqZ;kGyLfAm@wfx%uuCcEVXJw0LD;Hh0oFc!sfqcUB(bU9T zjiCjJ43`jg+$visC-Sny4AQO)4}3j_2DPs&5vYtunE}H5zy~?(WXJVa|qf}e-)R=ZOgzfp3qu6Y{Ys9}KPCi-pk?VIy)A-JZq&ASa za5#jmc%P#**`l>^wv9NG{B9hzEW2GIP=!}0#@%Oa>GXVidg)SKiaKwK31yDue=B~k z?;0_FE$XWMY(>|do#}>aRVlKKM6GB+JN{M%h?x=@!Zs)W}y} zpTBFwza%{5{Wa+CQciPiY@{}jm}C{omd(vmqEG(2kAjt`?7oJSX6GaksLFN=Vej*D zm7|BX`v~e#n)u}~YG(DFp#_PSA4Aw>+dQT4F|Ca&#hhqzR9os$Cr2Vsg*{ZfQC*y9 zz^=AbIqR|1cadl>4yDM?%2jNRYHh5pT#y!*>r7SG-jE1XVLujcROTQW)v}=Z;r9hn z^c-XC7#A0Q;*gvCL zOQ+vT++(c`k5_G|)~15=YE(2w3lj2}xZS!5l__0sQQq{nN@DCVl`K5trhtsQSH( zvlH$)N_1ujHJh)=GZMAmI@O9ZN9zreK;rYjsDC5f9UTZ{~hDTbWx73KCebZ7T0#!I$5>-4dp5sF< zb*G+VS4p!XBoe-RvpVl`l)MP7jS0pleDAu>6pENDS_j9x$f!|=U&e^;#CFCt){vqcj0#z7i z68lnbBvG09kCX_`1Iu1e!|94$!TH&}RNgTv|8ubuFmfngMl&-fW-&spI zT9CkRu-M0Pj#GuxBHO9XI*C9P#+igKddf)cdRL%yOA1E|68H@kxgX+u>Y*z=sou2t z5`ij=Gl@33)uubM>roHSQ5-Eu;5S(8SkEg>uEpz9Kive0Ko!QB#G3Gp;xty@lnNc_ z%F%)ZeuKrnyR|mteWxusee5O?sKPjtPS>@}UvBfa6E#wTI9iavZ?I0+=Ft;=YFRX0 zSmG}csKPjth;n+|;%r9$ClGf&@l)#9m}m8Gd-~ z7;0E%oJ61s<4j`RIqoOpx5kpMoex6`5^~&U>4Y&XTSUCN7QG;4W}!;Xjp~wX&+_jl zQ%x^}5iLkyhM345TpdKiUp+AGsNqRArwpuHL;*F)zcAB_EUo%=tkvW5?b-G&-fZ>K z0;=a6t@_?akA~blYXo_E7L)uET*uke+?xd%vXy;d+E?uZU(O1Tu(z7Y8J}SZO9N2S%p7q@QQ5l`6 z5x)YuQrpTlRO{*>|9=$WpvlGyvkpc8+WvG0fw2{ z(~G-~^l0c*BdU;YJ3-G{pZltm`*#A^61S#wrQae`tu+;>^D{4YQTd`oOm<|I_Ia_> zZ{8`H4;)$Hn-0vcsi-*-o1uJv z@4!-yil^{ATlvyayN@o%IZf$&-&B5!I7e}vH?!Vkt-kfQXSnW&>yaWW%()p&8~=+9 zX%YZYem^ahqO=$CTgNny6ShNylr{kQTXO}q0dXX?|gouPdB*9!Db z^xu7Nb?WJTc5G0bHybfrr%vy0&(_C!vji_Ib?+FhmlT~^o(|S7NlW(>q_K6x`m%^X zb**5>(0f6zM*QYUe&llG2=`f6hO%@%EUS!8owvb`;c7T$s))6sFi$G_I-5W1=1ea$ zz1g81f0VcL?4-OEY+KZCUsZ#uBomfhwnV-mL%eU&;YL?e~~;H-I`- z-^_;}EJyf6@kwJ&fbe%`)T51&g{b+hba5);|F!<4u{XQl_op(pf<2SlD0wQ7t}U{n z``f>Av>*{#z?*IVp06w)rCn8x0wL7v(kDKyP^LtnD&?Gk^-lb$%>AMfH|95@dn;@6 z(`CyO_CD;#a!>4$(wN3}&SV1)R3NkW!`;1g)z+C=k zV0pq{3V%U-H$_E0KqWc=r#)R>_)qvvC?}0?lB?H^_{>O1tyaeod&(!46z)Tv8%Xg};p$8D53a zwux^c8bC(EI;aebf_g5`Pe@~U8 z5$AP;UltsL<*z}t$iO)s@`xum` zEM27$>ct3JvwkVhc&j5MP}MHj!1^`IS4JGvh5>A>ASI;|v zy5(18_gCHLXhCAtFE93>$48|?%YWxI-0V#WGb@=&OuE6*QX<2P*>!uTv`cVgZN7Q2 z5xw3iW0U^1F)fPD6&cQ!Y{}v6^1WE=%ru2MI!b;bwk=N1>d=FVf4jrhzWFX)6?&HF zaq4tFZFsM^)x|b4xDtscM)=OY7y0y!l&xwB|Ju4)-blq1wgKigKx{f1rF-NIZDw#hQ{I*cPiyrNuNyhJQ(?t2D@mUj4mpnx)pG0ZY7C zhrn-&<4s3~bduu5J|}-wtpA;)-1~bVS=Cr$D*dP~p#=%KjRxXA@_s#6jh8A*1gf~0 zAx+r#L%Ci|dsYt{hf(yg8%F2z#m1)^XW8WyEsrsyg)RMq6CxVy?VCMoTJ?PHy;dZ*pX5Tm*NGD1qm%k;JYF+OkZ`N zn!e9jVkbL^K-CPRo^37sLmB%=>m_?mbfGk-Ic)JAYeEYWcz@#LlY$+|a_pqB#I?c_ zfhwF?>U7GVPPFX$Lv`u4LeiWQ3Heza|K6Iuteb4IpHoC4P=zyA;Q^ehN6j64$t})> z^;Pw3M(THEbEZApbWzWq3`3Vi>YKHRrr1p(!d%&M=kT(_EmSRMr#tA+9 zcKf^XEl;M!>0AdyVG6Z2DQjjK@$VuLFi+1GkNT!O?5d6Jym4c)?02U@6P%)E)Q*~+~K z+Es0w)syT)Ren2i8Q(6h%GD!X39ahD@CrMLt6Dkxhw}V~M!aqqMZY#5<$t^E;AlYt zuU15HZgrs}&Cl>4-$N3Cs@cE92=_iqDQni+pnILD;Mo)0<>xt$79`~R_;{@yeQk7_ z7yf-iB2e{Ce4X=sa+OMxwKi&p4x^PtoAU*;LqxWoo_XF*Q$D6Ru&sJMYuVwG;=R#< z?e-M$puL|ISF`qX6TC->U8co(%HDDuEfP^h&s^TVS0?S#h}GvuQE1zzY{w%{iP#OQ z-R1P`ZTAmKeyT>y$QehG8B>BcuR6*`mDV$UF;#K;;=rc3>)EQt@01I(99S(u{9T`_ zbi4Mi4YAL1P}wkJb)BB`J*(d%RY_f<5gkX5qg#Pb+1oRdjTq&cAg;>w^E>65 z_{zu;uN_I_$av@yTNMy4S&+bc5@(DY8bfufI`GhxT@rz+!rppTO7}@=K3%)2;!j4A zyH{1d@J|Lq3ljLGMP7#IaB}(_%|{<|;7FiqhKOYa_DEA6^w-)rdS(b!jTy{6hj?+c zAc1{BoSRWMk$UW$$;X|T%)Mgu%>TnT<<%qyb|GHRjDllzUzDyVwKjH+Pon+f2l17qW=jOB@Tu!`OV19alT!z& zAIi+-H>~xngXcTtMu;QB`+C&Y1kG=B%6RDF5RMik@EPiKv*(VY z4{whKEzfE#5vc0sre|edrYg5}S{t#>W5_wzo3-rj$jtVR8+vo zj1yUh5Ir-Q4QvhND*^ZH8P39Vy5mEeQ17(oVpjByqXmh9V+_pPAy0Ybsg1jKZNsR= zmaDvr`HMuL3TI)$L!KH=5v8v1l5gH{v>+jm?d^_7(6I)``Q*Q!Bmz}93)AVgRBB7n z?+){l&0le}Ac5Z!aRPC82dYzXHNW)Wy+oi&p53*%-kCyiLDzAyl)PXme{g4;G$tZ}-hjwL3QeF>Q^Z+Y1(!+$s&IT1l_Oik(b1~A_@do& zI9iZEe?@r6Hxg*%mR&rajg$yf;fN~Qn7o$luANL#(L0Q|Cgdi1e$UZa$^|=dx;(5Q ziA>qs&zNDrIJ(nihY>AEIQ=#-$H7@jb2n{0YV~P%et7;EGIy&X{Vh}_&}gr^P#DONLTB+M4+l^nt=rt&Q>}&Y3mpF49x0Preb(rh!qo&sUw>+ zmD+kc_GyiQwWloQO-qgN|83&scO}xrA*+mNL1J%L13Mp|sa%?(5j`&4<+U~^(C!mu zq`!r#ih~Sn#)V8})gFz=o$`ct4~nN4$0bIzAaSInfvGhzmAM-=;_>?oo?5df4eMNj zA%UubjSZ}8olIqtqc&Fy9FxOGy7ZtT)8`veRi&*INud9fbNrcaKS-jx)shbGY@n89*Dh`e|Kjq{{6H! zDyjb%KC{UXYBbW5qXh|ko5eoJ+DrJB0t1ORuPqU%TEfLjyppZl__y=E?%^fe_4zp?HtV5`n5^4-M>dY_@WDme$72d4W8g#4Zd=Kkdks&%0q zy(>rrs@7~aupzo^g@4xC2<>D=D_Iw+8)VPXg2eP$1{T#mOSy7YBUm^ejp}+eA>=Mz$O+NObOIU?omxD&=cyM3Bh%ZN0Jq^?zGZ zB2YCuRD3^j(Y%`U5Q#7L4H!pfn%a43E7MBQA z)hJ?MPjCKEV)HfPM>TI6{=FV4tN=#~51K< z*%Frw#luJQUS9>y?E@M5W4CU}!-CM{tpW?RJ`5 zocmF-*IJ1{75@G@UC7@jyjr_Ba?e}E(1HYx$0GZ4emZa2s|S5Io{<_TMp2nN#Ykz}J!nRsBNBlsxhMV|+>mD1s6sPN%w=dnLXJQ>bi2sA zJc^_mHk&x+H)B5aGf^jXsb{VdyGQ#P%=mDg2epZ!hM7w_T96pISe$&)F-O_*FLT+i z{1aaJM;FRmvREQem6hzx(!+C=rvLn_oOX}-up-?k?)nUl79<>dc(WPe-%r5~gyrAn~G>H@ns|NBP!5BSP*J zrmneRG&ypPM4-yw(VGo*$yK^v)`%;O9H{2>7WCCPiK7LH=pVwrs-2@e-l-8Alu}fr zRj4=#e5OR8s`+ihTF7WS&``yekdnXhEWD1p~W2KT~lpsg3PP-J8;%8O5m5 z-T@MUsv>E6_Ot&F@T}TF>ep%TQ)UXhd4C2;v1@DC(Q9 zM4&3+u$~3=O;-x8*NBlxt!R54S86)PRa9d8KMNA4c8SxVu6|c+rf7s)>y9+%l`S3J zna_|w)v&1|qp|BZWzj8-=yAIf>6+Tog%$f5T9ClZL*X;zM^W*CS$y-oSrUP&v?x6* z+VG3w{4WcsUtSODb?^sYySgw#3lee;WG9bU`eyf*M{b{DL;_XuZT0L>$2289UAvE3 zBdw`oMNS(EKjpad0e4zd%JXJNyXGsMK5HXfmHGv!P__DGxA-PU3lb5Jz1a`1Jmuas zjd(S|kqV6qqOYm9Bmz|yF^c+(%~u?nY43TfLk@JhGN&aw&U3UNadfrFvS^#96sn^U z$1jzn+}GX|`|helplZW#Z&6n|U%9M+*||#3))lEKlJn8nJkN zWvV88pQg<&N(8D}`gt=upM0g9jrI#Fon5tYWb|-9CpMia9lB1|1lUh^+I@gqPFN;OL zH^(IcRSg0RtcZV(65i+ETiZh9s-3f<#^L)oT99z@Hn2gBvz0FYMxUxRT2auPbnd)d zoGT1}3sv3n#9EkrmeO;h*2bASt?A+NeBL8>B}WSq4}OTT#4l5MJxwDL+I66pwM2cC zCG#Z$Ro706_1dc$%GQS(;d!bfJ)e`w`#6r{XhEWqSosYqk)hqLUc_s@DIs69HY(~wl=I?kUZ;(> zM4&2OtO9joUzPpdS{p9qEvO@2MYiK7LH$-VUKj`~GuQ&J^X-QSmwsEu|fj+8;^{ItvOv{EexYRz0KoyRUqJI0#!lKSyV=8-f6GsaY z=%ea%Eqj!t<@)Od3f@$(<~E5y z6^@T$#^P0#vVQnb)1=iLEl8k`D!jgmUUWiamv-8*Ng_~%FbCl94$zo$0<$|ywQc?-SWBD zD<6qK6^@U>7ab&Oo;A+rze>1pv><^#s+dQ86P1&;yyf>-<^Vr`QK6D)w46I?uPgo+%Ni!tqgza5wtUM7qK&SF&elK|=OkT`nY&VY-R$ zyfWE{1gdaE6<>p^+j!Eqcrt&U#&J%Lv0j`-Q(Ouh^MB?Q6!-f&|8WMP~mk zN1C{&C0*IoMIs~>%%eqwMfixh%_AtPTqBNiawIVBD|RA1FH1+nX|e0Sw3i4};XGQ@ zr*2W6ZdGbXC%=Ypv><_TUs1oE)uzEu{prBz))Ij#oJWgjZJvk7>+>h-$v9e&z__od ze|6cPJm=M>cF8Rz0#!JV7CrHNAm!evMYHb*akL7Y>&Z9-GuzIa1{D2#k{^Y>Wf&}I&in-dJ*0keVQ5t`3sP2Wl0&}26^!!^xy8L5`sqmr75`ii?Q#Rm07?s|# zLyc@)PRe^l0&}2sI_I3$bnw>;qeJte5`ikr>lO8{O0}kzZzr*V=Zi}DyGY3S)PEba zp{5P4vJn?tBmz~KpDe~JkwHFa?@80M{XT^G=Dogpv3j+#m1&*--`w*vb$n^2|7laH zARj5e9f@xu?|qnGuJX-O%cgo35==K!#+d9Lc}fJTFgsqH$=bw^Tqhhd?P}{yXhCA_ za6PLv_m`4?K%236xCGHuw>hTy-|9*Ps`|Nz^{5?xm7ISw$Q|>1>3;YFlkX63LJJbh zbOx5tS*KnqrnS*@xgR-4Jv90EFh~TdZaaxRCZk1xR2z-hV;e!OCsyKhsuqzl$?-Rk z_mW*X+L9h8WwL{>ixFCoz+Y3R8*o01YJWM!YDSfj2vp%-LJ{$r+=Tk|s>g2YDiK*y%K>cIrFU3nRuG|tSPsDc~Z(FLqgv3bD(}Kg)HjNt6n-K5vamEIpM=u zMbq}BP5Jn_kEMJ#Byf+Bi0>}zPMuS_a)(=QBmz~K?=J!U$cZ{0S;uSW3&HiZZ+NZ@W2QP<#WODaBi0zY5QP9ji+ zJKw}8I->>EdOVhUHgJ^o#36w@XLY*jTf(T_rbYbxCVPoM74F~@zG!$8Iy7eyPa5GY z?d?MXcL3{jyL=kbh!Q(_mjR9vfhyd)sM8fWLX@|E7oTfiRNAA61ny+k>7I88rp3F? zaL1vp5`ijtcjn1@{&Z*eDSj`agtXTZ3AyG#u@nP!d+?Bl`4pE3RADs%aXN5eS323& zlgd8J;J7ap*Ftc|sfc*(aHhXyz3GiR{+w+j41qoai5w%|IeQE9kXByxBxkR7} z^Q=W?f3hz{+Y}|Iu6LyjY$R}9M0m&njJi!KNX3I5O9ZMg8(UPgcI7nAU`JMiZ*sIC zf$Jioj_~V-wAdksA6E_1XXfvX%kU2y$2w6Mor?l|e9M4$@y8;QvFlD6br{sqq- zctqM)gaodOh^*r3o#@v5dtxv0E{Q-D?wb;C)cwwMX~t7-leS#iAB6<2i-=6w+udo@ z`|JGTuelO|D$IKpe*2>yG`HYw?ml3&w9g9(To)0uZTC1z`DEcgDkew-s^om?oBa~# z+HW(@KHY$$1qoc`5c|ANC6Z6}R^H&9ULsH>?|fMys=akPw}D@L>?rNvK?2uB#Cu+L zD2*94m4`jdWcasGg}aADrNUOjX~eCOeE7cI(oQ5KaFs(4Ek@JFOMcw(^$dwXmAs>B zZ=KO}D!o46{l1X2KMDz~C#2KqXOE$w`>OLZQzskoZ=nk77m4#GyoXY$ALUJJ?#<^n zY{Y&QyWPqT4=0BEW^hN07)v@u(6g@#P5X7l$^VWQ8xpfynYqY`)jQzD=Fi%#ygcJ1 z)e{mqsl$`$m$BBdBleS7gxF;kv$E>(+9oH~M*KS~UGID5xD#7gUe8iT*7xPFv=~6j zx@215+$*^7j7T<4sCJND@W)wBY=ijsz8P`Bm8&|j&4LKH5f|*;QzOQ;@T4}+SDS)j zf~jPJ7Ylo_Qn?l8%nJ7PVl7YZRxVgMvu(4)4&eQ}l~Z3e;wtx|g^%}|uD1##v>*{Y z(2EUPbw?=|uMvYhJjk|fgvtFgqcT0cn7L~kW$Za;wldm_-SbLN+;%#%#Ob2F@(Iev zWzK>K9$bsAB=X~lZ;5g{i@HkFuIi76y0DMp-=AMpId-hR3;QwIi^Z>P;G0;^MGyl` zwW!CSW~!GsSqCjhtnKE-?mw%jEGnQ8+xpd}H7m&N{QnLbd*4 z`QZ9C|8E<^m0DCZwSlqu8o3Q5w5$C+i}@ZBS1U5f#eGa`k?uE8+y`D2s__2AY{J`% zaz5^5;gNx)J;j|X?*uF2DcXtOqvwU)!Go>;=l3Xnba(LXf4|4#j-IsU#u|2^eel2E z<9{tk%oe}wq4jHmuZ3z)*K{VC()uq6e!ZeDJ1%<0kM{F}TfGw155&LY2J8xs8|lat z(MuNX+!ee^(V_-9*OO^|^_1ZDBg;z`B(!~y>*;B5nbX>Ad)KsNIytk@iN(c7NPQRk zYl<6rPVD`6D--_pc5}68>Nt6lDRR#jjus?v_qup%-!`IF zx%*7X;!GsmJB@EG#NHcess4l(B=8EwH_B|JBFExQ-#gZk2vq&qBagTjaM!+t&QBx?dZk2NK?>rCqfGnID(6B zRQv9+!R?`fQ79_Mj-P5=`IPqU^Z`syBO}gDVvkDFL(H_!j=iT?;x z{r7$Z|4(JSsp9>peseR6{=fI*p9Kl+Nq?TdJNT;jChByRUvw3DWOG=>k5+`w>c4kB zSgRC)PeF{L?j5OX=u&oZxILi-iHV{nN5GAD!Qanociy5!Yx=cs9*b^KR3cC%UsXhG za~ijA8(U>lhR}kRIGv^%fUh(4zu=vtoIsbyU@C~P}Ys zpqEXK@^{_|fuJh=9qhd*RQ^;>e+T1m4wsNykIm5MaR0Y_0DBEUr6bP!C_)jhZSCXWvAR?etAYMl+gc;xfA4nawi0JYzf}& zy0JQU8SKHip{-Y#9Fth|+1q2Sfm$d*=UuqNn=FI7 zxx~(u!rVLLZ&8*0U5Wn_Dz7qpaiZhB;YG`6#b~9C;rsEQg%bVtIsf7|gpK-QSyKSpR^Yu1zu$oSq!&1fn z=5>LfD*A3>wx0f@z@u`Byg@xJyn~eJhHqL_R-0C*0`xYPKNtruTK80LMXV4As-j~I zdey>WVerCTvgM3KVJxAs!T1$j?9t zaqV36ZW7GydOWS5LaYBqQ9}j_O6cR`>_>Z3%jfD}oaH!D2l(fw{rta?+CWg1K5GBB zZkMFL-G{-{8I#i+U(fn)er3pcMRQ@%H3RNJz7B!x9ntBl8axwL6O^FY%rJM`%Sae8 z-Y4BG;i5oLm3UQ|$s@q`XrJ`k=-s9kO4K0P6~pNB-`trJ^p4<6|H>%XSSu&3Q~n8opelX5k{~p-ygqs$8>ysbA}IfuO3*NE{v)lDfQ+KELv;5ebWz2C~TyuJB&J9M}c)@_KhOXaDvq zSdy3(TsxD9%r zR$R=1dI707lFsKaAM#rVsAFQ9KIu+t!E;9m>f=BkauXREe3+FsbCbP5P!*leNmBct z-tgw#pR~cRngX>@g8De{%-w81uzwbnc4=uXfuJfnpTo0iSl7wT{bkzFT9trWC_z0I z7^yd9Ak>TPlGd!JBoI_Z=W~)Yar97t;iuBV=Y8SSLJ4tf@01b&MoQDPlgn=i1Xa=b z9OkW^F$!MPSeiET*eOmel%V4=p0ci114 zg14WlL{IAGtqG9uF(h^D$G(hOC?SsRfsd*|H0!Rp$#awhV<)zGSB|{AXE~N=>cl3V z$&q_^D#v{5I)m@`rPTb_+kJDo6c^5lT8 z@?%5f5Y?`JWo=&&_>!{DKME ztTt8ozd3|ty}~FW(N6jDPD3@1X077+n~vkO(+BK0wNQe#CrJZW%;jU(jMeJ$ z>H2myE8XWO&%{~@s~vvHJFr$lgZa+v>Cs~O&6%?7 z6xLHHeYIF#hV>LMhtP_q@M*85cEai%rxr^5!syKJql@I8hUm;|PwHc|VH2&MRi;2t z)hB#{^`{icw>s)=wAoY_ZWcReWuvZhYN5n#jORSxxlq>T=!Elys&MR#hqh|dd4Zs+ z*BE7L7EmZ(ZK)Ien^%MiL%p@>&+v>Fu~1?O#?j+PK;9Io6GdPOuP1fV-uB)h5L9J3 z)tQ~^`cpPDME7rrFoGK?-L>ACi#fGWqD2d5<{exhk2OTz|E~L$5BbqY+i-rCKv0z< z{_-!;1#$yJK7f(FS$xrff!c|@U`{QRD8%eAf41ezM-B0{DIae0-Q|aA`H#B`1XZ2D zoHdV9^W_zWoHYw&jNKg?rqu~-!l{K4Gcj*evRS_T(pynu#FUHz6(=b2S;%j;GLCg>K^etvKTAL?3bE=x2Wntu@kGcD^Cuuskbq*i7}t|VzPE>!hVHXC?Woi`^MQk zZb-29yxm&%8?)Km=#wYExn7pd$9z;juI9?e_myQ{8=aV+cb;r-$bWTbtqH77>8F+6 ztqCehKOBfz3oqo#&6?}uuF*Sla5MMUj9klbYN14f9Zu}CalYK^qy7XtV`Y_L`#NhQ z)Y<|;RR=JWPUCTT^6&PBv3*!A==i3CHl%eMPA!y}kMSR_*Yo8=WpyGx3u|Y70PRO4ATkAyoONAOxAoK$8&0-#B0nNapORNysD{A?3mXAG8Z{(0~^m0 z2&$U7+KElFDv;|;*NNvNY%zk)R?D+p%c+GDmoN&u?t!23_O?1vp}Y$?A8Vu~PuMCD zRP_mCsxQ{~DIeaT6S-SmVc8~2?W@rVPA!!9h_T_9U2wNPN(%Yawf>|yr-F#zUVHe7D`ko<;))ZD3bTb>BPqJUhvA)So6R7SRkls zyoTq(+Z4%dGjw9fOCJbsUZ9?w{g6|O*<>d+vtOZH4YOX-wk7GAS$n88p;%p2d_!o1 z5<_B~*eKthaw9`DdACMhP-(Qe_Ha|0Ku{IEhqz)H>J5zxDrk$39v1EuB}y>SoSEyLIrFM33jL>%}k&Kx_0;lH5S*qSf4f__b|BJg;W=0Qz zpep)qVs@AhEg|uUyXIxhgm;h&p_zVF zA=7F>^UGbd#9_+?f~w*$$5!QXxpHulPSnL55c_|$(TwMn;`G|7O8gy9ylTMPuYTIg zJ@g;8@R5_pXpfTX3tvd8^1tE42CdAK2N`Bd0bl3xNqu6p z$?dl))Itf*y-uu8nLK&7A>)b7p&7jT`xtG3PZLH7s-klgTzOdr@}$ZWwag#86>6bG zA?7e05Su4|G2}2kQR2!sf0(368}|qVRf%(kdeeQNSAJbB{Z3~-1oOaEy7xma!OZ@v zF{h8&vRwJ3UKaqf^~{d`A-^)G77BlO)+ReSI{no|oUwqg#U@Zou~wIPR)WuhNg z1eVvFeoYk!s>;CZ7n|L3<+q0H7jG|ifp2?EwHtpeYwy5L6Y2IXSMB%aey1a&o+@*&XT~{;rxG+|Q|n5(_Z9$5f93Im=Lczz?%! zdH7_i{nj2A2&$S}g4w^b^JGgy2L24!o-l4&h8ni&3a1uIxL|#pgjPT0Q;GWTNKOlY z=U&*@wQJ4>e~_ygYS;9y zFakbZuEvyh7df?1g07=654{hE53-H6_Gwk_gkFQ#Mn7an%>74uOf$^Tbo6A7yugqn z#q>#gIFVRKd)CT>Qwt?%@4>b6!tOBoh?#aHr=vhnRZ*%VYgjW!woBLV)nH$L*ng#z z)-z!wrxr@k-h-#3clLo$HCJ7DY>Gfo)%G)3|Knzk{M?XL<%VZ(*xvW6I^@+7PA!z6 zy+^Mz+7Ct_d#)CEt`P{TayakEk{AAvtK{mx#68-2))hrsn6+toE`hlMsM z(H84zNKd}Yu~_8;Q=T~l0lRcU9iOsWAgGGoL)_tw8v?rqq^Y0wt`hDQCB|bLMYiAN zsaUfE=j~~OV4T@)^<0m|0zp-@FJPX#OM~H1<9q6{y79s@r^F7t3uWhglk1n$+jznT zLKVnT*ME%=2&$reT9SgM_XpeJAL{Ar?S;Ne2_MXCR%66>SvKT6b2ayeHOtCr4_~(u z2&$s*Cgz!V)fuD-H8kg2m4$bZ626$pvwEc*+1@a=yWI8yv+hl_--(hyP!%09FuJCu zJ4}yu(!RVo!Kj52Uf&(rU$b)LWrj*Lr=y3%gEh%&Mzs`9dqxTR6T5%F>}k)*6_Txg9bI13ItV& zy<~PZ2e>}ZQ=9Kxg;5J7L?3dfcMtd!T2;Gwdx2s%4(k&6e35N8mS;ZG99igvFLDd4 z2<))Mku8+J$%73ufPI%bga6w)+JfkX3bjz8K{D2&Tm4lI?xK(FH;%S}`%Ri^gBLFr z2&ziPib{65-{e7t3}$s7MnT)UyVO%N@>x~~M|M5`ll%a)R#ESHIA*g_gFnmP4fR;Q zxsQZU<0GoHpaQ2BN>D#M`WalKq0xlZ>Zomw0zp*_+rInYvs`MP{(d}b8w-AuBGq^) zmlZkTJt_53)+^4?D_n^+e_r(aDC;$U@Qo@x9@?Fmu3o5b&Z&hG^lI^IuqFm3ng^&i zKHCcfRjtE%Ed7ssl>ezE)F^ZujNccjN;ck{S|}m@4i$6IzXHRkiPf*~*bNj;y57C)v!(jMeLmwS-=Ok~f)}u?v`^aZ~%h<@Sag zjn_tofy2m$>iaIU6>6bGZOphB(f6}FJxA{)X@AGVkjZt_IM*`lOJheiZqIx923Ec-PMy{2<30YM;%k84ppDoK*Yyi3+t)LTc{Fe0pWeDG~bf@Hi3& zJMD(36B>yGRhhduvW%l2?;9^<9LJ4}ccw#GYJlI@Ytp4nnB-~x9a&g5tmKPu7(DwROwN8zNi+84~H@y=T zYN3SqJ7%tohmPj0(=S$Sz*F$#V(gG?`ERTfMbBKOG;(B#@7~KXhKf@kr73Xb%(ArG zD@qu(P(nOsIcCiin0#Sh+Elx{0zp;uY$RqpnH2!GQ5Kr-Jqux!c|Qf`R1dz$epuO@ zj!O6hR}F-v=l`f@dQ}iCl%V}hlC;#paMvtP?U*o67~!ZY0;@avT>LCod!_fp=A}ZQ z?b=sr|LoZcwNOIryB@}F&~Wt;Hg|(FjKOM)4+a;>b$6JtIIP5;xT9E3#9HXA*ny3$ zQy|apsGr!fdfpzo#E(sHn$Q5Uv4Z)BaV7E~tYH2Va~%9V_m?~eE11*2gwe|#+QMn` zNolE*n+R=C;)Nw<)7|h}UQ?|9jzvxie5u@)ov^YK2&$r2h*<<(J)zcv1lHzY<%pWo>(^(*>%KRzjJx78YDw8hE?g8-?+Ni!A%EQqDJRN!R zryN_xj3r?$RR5JEwcWhw@`psr_$$ycpN7XA9*1-^w#e z_r>b+=QH!=hJAIyWOo2Gmc7*Q7N$Tgln~qSAJH4)Iy6RbppK=)1KBF|o%G~P)^QvA*Um8;tsD%=ZLmXM#F8T8I zTl(*4_1+&oCgi01gqaHjRf$)%>Q!&3e=Re;Zuhc4EtDw4uiA;Q9Jz6}-o|B|E&Zu# zsXF-Pa7s{B6MR2fH~KE$FjPOSpD`5n22@kS<6d)Wp@a{P)K4#ck^dMffKAT~g;VxT z)TEtP1cIviwRU8C+kKJeJk_u2QqxE{_o|fY)<@&iLWy5>9GT7SPjZtA`Wv->*C=Rd z_AC8St^EQ)Rks@A7iZKbxuxN%^5RBAR?Lp{t{K}nwNPRm)_yk78SW#wTm z5VZ9c`*YnDsD%=Bk)GuJRklT1l4iXc3AeY^QOen*3+MXi`3dR|!nzp+kzhSjO5gup z^b}DdxiX%)bNVbV#j45}mpVKIcG;9lw^{j8@GVi5g4K`JpP%J6Sp695JO4cdR@4bh z-{=07Qwt^P<5%14_E&j!W1aY6+Yj@8G*91KzYI`2& zrvz2ekqE1}Rviw$_fDjL&C2A|LJ9gbC82s_u3j|fskqFP+xs8O3g%i>* zNh+rnO3+@3nV>gDL)aMK^s;~N6$q-LBN67t%^D5cva6)FT(gr?3nj!eMGhCogV)^g zN>cSj0zp-D?81oLK~CWR_iGk9LL3?BXdu3|qcIa(;>X9V%v4997D|Y*WPLFcTk50p zY&&LRqXbpa5d-t$1hs)J?~ky@RhkH62_6|D}kUY{sNVxBL|Wau0vIo*+E;>m%#hS^eKR$tJj`>L_wC7fC)p$PL5=sWpX#=D!QhYq)i`VU`*17^nH)U3TtOdh%~N*e%i)T@BvVQuE?-oy_pElCpA*X9nWF(Z&4NX zSYUR_L+l=EOREHc}qp-j=h46Kgn9Qi3sy9G$~U(yF^|U^_U2O>gZ4 z)IteA+!uM|D=Fox=+FEK)?8Zc{e<U)8x;185uK%p9GJlpmAI zu_~d?tXZ6-+!$4kMWwi~dG94<{WpEra`zN~k|mGWLCpr7j=8XR&L+yeqB4x0(sVlE z!ji&EDT_)BgeAb}P3u^QOLL$WN{DAU-G_R?wxDgw;5*F(f~wL_y0EyL#>)F&dK-H; zc)?GrZK=&RGy`g(1Ppa%1Kt}cO=jx*=TeRr#@DV*|7K+)5L9*iunW6;#z@)oQ*YyU zsyAeHc$9vwc@v-(O3-_Vu}f9FAdxjuzc*+s5L9*kpbM)IVWbr0>ur2`$RVn3CpDmA zBcK*ah|l9yxEmZed0gGOtqx3C@4|jpkra4WhS?aou=#Z*B>?x#|IIq39L>_(xY@!T zq7R={Cj{02YN14xJZE-)&u@9>VtqG!Vv-Xyefn7a=22ZBsOsNrR`THty$#16SNP~B z1GJ`9w*8mg*l^bM-;D2aVYmN1_j>gAQ*PFvmuBsAR5(hM?JbtOni@_(%%~00QY)>`5hI`$N;Dhe!aUxT$eYgSZS0@e0Lm9u)2ug{2n1El zvUOoW^?u3Stn@al$8X^S%%Zfosm(b(>qt-I($kcUb<^+sW}O~d;-cNcDOO6*-h-#9S{p<1z)so?w<7{URrHiDp5J{}26x=Ow5MaP z2&Zu=L3OrPs zV{LusPXa+z^wc!^6Du}^oHn(z>-&ERr=uw$_N!yvnnCDx3$5gl5zxOyRrD-3X3WwW zfn5tTZA^Wv(nWgplmr*HeA_SC1yA`>8rSE^HsD)itObm-0BWIxI9?S_Yyn0!OKH+?t5_EjT7_2u~%WKXX)p%fefuO2BgRquRo!|1l&iXg1 zxRVS&kDXVSO|JyhLJ2x*OH#AF0M_bWwXjMRfuO3mVa|*v{*m_$(%U%a;i@PhwlO>11D4PEpg!*=5>!R+I?k`|xWa>l##-EX-caic|a+> zjXMd=Vea*MT9EQoAgGGQ1>hM-e~eJ*WTU-%eu+~HC7LyIX3^CPWd}p0rlMB$;il}U zHK?r#1Xa)$iGx@nZ)atU9>7X6m_ISTDvW#Pr4{tsA`nzX z;{qh<_@0UosCLjE4q3pdg%bC%rrs9Y0@=z?Q!i+aDfq;9(@e)E2?SNqxBy8SzseXU znfKC$1`p!YLWw_*vEFuQzFd30{yTQsedmGF0L|`rXMvz98W(_Pw!41dV>=Gk&a|=S z)Iy0}SP`0E$diAK(A%hV`92Q}4AJVDTL=VI(MST^iOcqfdj}S)ZCm~nR;dbeVzU)| z&g(?qyChv~gjwZh%vX1LNPPl?ECafu5GBomuK7s+B9#k=1!?15L88dS?E<;))BT2 z?4*9osv+#kP=c;S@Vw~b4siKUd3Bkir9e;>-J!vr*rOfvTy3g;Us)fhg%WgrElI4m z4{YrvggT4K(Cv5T9#pa*069}rJYf-G$+}{(Xb$!JCMB53g zR7%hoJUqSQp8$E!AEynjIQRdThvmQAD|A(ir`3lffTiig^u)_$gq2w8w`2- zPL}bM4Mt&Kp90ClPp5ZTQ$`@D${6=j=Y4u7rzPq{ien$JPb{acG+rd^bJ7Svx`T;d z=a+*aWz#qH<;O#eS|~x!Hed|z-C*#1@J^LxEf5H*qC1!vH}O{_BunSia~21My=_X+ zlM1*$xMdX7H9f9gdp%DesEY1$OVZ?waZuT6kvgjOenu^n5Iqx-jbrhI&{Q>3o+}Vk zMfbUJ|J-#F%nEW+!^ZCwP6$v!eCFpe;-LsCt7{t05eTZHXAtmPJ8lYWF1eh3Xh|30 zbOI&BXMS+n6!40EnqDg)QK5f}s)UmYQlA7rXzeneS?sF$UuFtJE-jj4OY|p}ec}(X zQ>HQJ+ZI4Al%QF_Fy6VKFO)iA&&o!X5eTZveB;2jz55`)#vFt=Qe%ZY<3FR>hG~B| zwNQfQDU&4Qyg{(cC6WcdE))o=67w2(>~e)}0cY6l%Pv57k?1ZE-KWC0*1;314cf>a zEU_2%qbMQzcLztegLZ8)mFG7b3ItWr9RVDv5BP#j)E;GcCre>pjS}>(V^+tz0r1Jr zCN16DLLjJ$?$%&#+}r)&=ehby$z)SuABPh3u49hIEkog@cj&3AwZ8~^MN}p3U~L#5 z3~o-pl`F$O3j0x%5TD2Rj1ahjXX^4hJr@Y7qUWq}r}~Zu7&qIl);(z{_@%!3APV7{*9^Kw;+wGarZqU!{#miD+alnz{^mb5P?tXL>P=O~iYyH{uE)+J(-JM=iE`yebyAU!{j7REtH_A0&%B$%ScFDmaG;gg$M*y z(UZBj2YC={(J5Qi2WD+KwNQedxy0zR&!G^s?4r7Dkh4Hg6+M}Y9^u)+usI=9P5s+~ zQwt^N%t?}>Ec?UUHIn8NT+ApzRrF-8B;9rofO(-6v}ZexFlwO$Jr65MJ*+#yu|D;* za?y(gf~x4rT=XX<1Jqm4Tq3$&z-ea@5HPTR7EpL;OZ{n z8|yn_vKDY@vk=`)^C-~xYTP9o(vp9!IY}!Oa6^bDrv%NZfO#PE{CMiiI4v_JMIfk( zMswkcB_@FfPL0t5uiX=()G0yzzL+yJa3QxXJ6_v*e!DSlqUDjHpf+1{Go;KxRWYmK6>2vKyDpet`lGT-x-yPXc! zuB^Er5L87Y%Q5?&UjdJf9jFbQUY=76C8$3DqchV>Lyr@^wTb@q1cIt)WI4{^E|!Hc z8+vN}ueRsZLJ8{Ez?|gfRp5L5&e{*legZ*NG_oA`?#fn&*-zSOPr6Ox)ItgBpTT{c z@Olt(a3V#gH#%TO>1{8W$gw|EtH^sCLF1^*ucm6_L}h*%uGR|->Hg5 zmSatC#}?52SyS!q%hQ}%C_(*Yk~C<6BW%1$8{KIIH8KULFw4?p14 zLJ8{kLl3=)2l%Zt)1KUZE)Y~jW6>pPE#?(HxY0=adh83Q7D`b6B}U|)v4%5~boDoF#S5Fmglw*rBrX#o?N4qtzo0Y|V5$f$j8G!F)1KSGeDe2(6^udKNs*i?wT5 zAiFQmQ0!-Tu?3C=^2`+(N*zqLKNbH!ZpL#Y#_|tJ`KJk*`{7keGt*XV$+W+*!+qdGfqr5_%>|W5tux_Y*X)3DcCnw|TN%s46`6LkZ9HWIOTS zTX*CrnH6Q$1Bnh9IoQU`l(ukn%yZ^-p&?wX>c;BICd#B@6Gl&t&@&-8!ufRp(`Rp3 zjdeAF+qtuk+(ZdaF2#a<+}L@fi_=ZmmL6`b&G=GE&nqT)RoANbff)ah=UUU(^>7D{MSJ=vGe zc(&zI2@*kThC{l^ANI8U6aM6=!nXA?QI-zNRT54stlHvIO4W#5CHs}aLVKGi-_m{{ z(QbGsd>LoNPs?{XwNRpJ9%EuoF(hD zl!-*Ymjz12*9ltVFZ*R`*>D_xIjVYe%}^}f0z3Fuo?JXI1BtCkrCBw+s^X(lg`P-z z->d2#hAUiKQ-9{a>UhAD)^^&UgVx*vyxD~W+}nJRq0Eo)VqX>%%Q2bHmA}2cSgd`K zyyLq5e%QV%;yymy| zk9#(P(NDa!&OIw~N>G(}ucmiu3Derh+Of%|oLVSxq=q+(^emDOUe?=a(#siM2e@h_ zgUkeis_1jVEdO>-_{Jq6+HLc*jE-bp%qnbTrffl?7UJSsEUsHn7?GmMD}WOf);#wf6QTT~V4!dczw`SO)Y z`Zp@HRb3wcI$ry@p%SAOO5{}ZVyBGqWy_Iz8>3$J=Oqi`w2s~}0zp;uuH$Ku9{u@< zlW|%S>n=PGN?6zOVxz0(%U`1OHl)qd_-KzuZX|iv+D{wF5%# zHu@E%S=l7%>r{VsG$uj2x}(0}1E7TXt+kzShAnI`May7o1%j%mKLFb>`olKn;N2Z_ zict$CYUW&Ira=p%93%2E}Ctd3Mg^EINs-M1f4Fp1R;_qXEILWzXQ z?kqbYUv}J}w=ri*EcZzmt7UKV5eTXh^I0Y>S;#FXMQbBpcMsm4}=R*JeDKCJY6vnSXV zePj)rS_rcYI!B@N2Rw_@u{&(E+{r2jRRwCHggBGgR2g%%mO! z8!5+!>21`6uHYG)pFU!8HJ}zs6n1fA^{yEy*DvTZvZlV>VEb1u^_7o>Ku}e=tsZPy zzNCZ?(%U$Ft2Ims*{%9piKkcxgBvS+EGg4ZoBYo?@SnZ8Y zJ29XUPzxpK$!x5oT(cwWp1M7KXKyQkpep*DFpI~Dws7gf*Ys=c8VXO467*y?)_2bJ zftq*QsZU?m6$q-LPZQ4+9m6bwiM`a{kLm-pP=cP!mZa)70L3P8YVi~+fuJhdLopv& zq=qXeD%N>ZQFZ&=pD$(sM+IRZgd zbkvrl?~AMO#O3kY_+A?swNSzvWVWqZz8qqtuW=@A@5GNai_=zr`YsSuMMrJ)c+DBf zl^-$M@5&OV7E1JrlG%i5`LeBp-bQQxCERZ9Xl?aEJAt4oI%?yo$RfFYx_!`mG> zwNS!mqs&&;FOY8y(A$WJP3NKILN)2|5P_g7@oR8x{9PV+cBqybKbTVsC9H1A%;Q^u z95P35qs5?Xz9F=qHoL`KfuO3^zuj5Fr=RlV9Q})v@mC4oQ7J$x?>CE63nktZ$xO@n zDH|Wv+xWGhEG)g;QQP3SMIfk3ZS28D)+v%tnCWB5jlZhEq{uefkYDRKwNPSZV}&I) z#(DcQy^Yjibzy&CEA7P4lLA3i8#{Qg#bb-*g$?yK%CBhxb{6)U@BM?ES}5V`tFQ-C zk@%yxF{P6&_>Qixb@#a;5LDGD#DmTKRwB=J)7vQH;0FEuYifH3pX1a*3HL~axf}hG zUs~m28~5IL!nK$(+Od%@1cIu>aW}`$2c$v2)Xsi)IkiyY>`aAe>wnAUt@SqcuUhaB88%oOKGj+f-6iKfR5{-MfSR;T`Jv+4%xN zRrK41{;NTKA$jRCRgHefsf7}edlmM!l#z0GfZoQOoZgTj4^hYZ{1ynRqB8^BH*gsQ z3l@5+Yv+FE)Iy2L#}#(;wUN?4L~mpB$3QSz_c49SNF!m+Kvi^xgOSAnLm=(u`t(Pa zzH(}zMA=jYPc9oPThKp))m4H9U>u}-+H+9P5+b%yMffrO%%X{N=|_Pk@51w^&G<{+wE<--r5x@I7BQ5q_SU&x$Vj z2n1C%!!{mnE~WG{wDIe498`#^z{~>%aB87M)?Z%i&UIs@dYu<|RaYY7;E2Wi^cs)) z^DZyFSj%rl%JZ5pl;5Yk*~S~jN-_RjkyvOw39QYpra883$Ek%9?Nhy3VX0Ee2=stv5G9FawWs_4~XorcHbV2Z_XHOA75C#QI``jw27fT9fL)nRY8ezlP@3-9#t z`(DhXvXOG4ivBy^q{V>QN-wqINN-Lplz55HDgLXG;{IEI9)yl{z|e-883(@#@1?ue@ev5BqW2BGoGnI!>bXd@ zPG-U{r@zT|tv6fiDJlK)^xtu_<4D+Gy;=P+vInOYO58i=#loE>WlDMdUNsvW30vMC zR^OiY5D2PDT;t8Yxk`$)p^b|Ukx=f_5q0Jk4^AzVIJ?@Lh1*NY%Uu1ck{5(Pe$`9r zp4YydS|~Adj~Cl;=(pVXkM33TKO77eeIKhEhdT=dRn491%@$!yoZV-=jcFqQx?XCc z8T-}{{D}>{z1i%=#d42_qHhs>mYdqaipo~nq~toBdL1dze5f}wH~%FceXY0g_c&jO z^sJ%1{Nf}KR8_FRi|wiWOHTc!{|;8%9d27#Xm=_#=F~!oZNboIrT?Vzc?LNFxx`>cyKs*gSot$C3v4(> z76_vcC8`|*Hm8D-@}#uh#%N_EEW5i%-MA@1AgGGIUAUK;7Y18eY*AnQp3SL+60zIx zcQ{~-YO(GeoL3kOdtP5uZPUjK1Xa=ghUc%24}$kMAE}2;5`}(6i4_Zg_1pVfzVlgc zW99lju&`H=I$%baKu{HZZ_qm!*#mZ;Dy?;$8Y8?Plvo-KtZRi|a>!G?4g2;TVU=kO ztxT=H0zp;u{m0!`PjC43yPkGqaj@{7QzF9;*togHa<2<|8>UWfU|nLX#UA$&2&$rf zcu6`IX%8D+T(vt3`~-hHC4M&ncE4qjY`RBpPFOLF#CKt?A(!0zp-xPyg^rW0-Qauh!G44yP7M zEWE~9`i}znU9{dt*{|>T(SV`a@uo$BPoJtp5B<~X5BTOSAzJazV!_`|iC?QYJ8fMc z5AC71Q7-H#PiigR@D!L-W-KE7g(CePL*5-l8pMZ|Xiuqj+OX{&_=o)ZYFqAPvO2hiXbHyhGkv)Oc2SkY60Mz7;|<@Yz=eYJ;HXVqST zpepLIz<7flkNF($KHBrUdj-z~C1@1BB;{PW$j4nBqz#?CP9UgC^tbODTZXZW1a0%W zDZ*(1x}!|}OxWA^PG+k|C1~@lt_WueC_#6fu(GvJF6(%IvUYz)0Hc44s=NjN)txDp zeEh(0y=6hu1*jLs-k`-^dWDygwMI&TGH+?PA!z6-z!OKl;0H8R9EeN-~xf5 zD(YuKAHW<(7&O{WOU#?jsf7~syNemKDz=6jo2|5}GuH_ORZ%|^`l*|?fs+erXjNY? z;?zP3I)A{N%X>P)^|7Yf{FNyJK~>bxgw@P3W^`FXv3l>}8cr>gpz|O}sy(9@WQIOb zJ$oJ%2&$rfCfu)e8VKX8E~`bUqs@EY-EtH_^9gHiA9|4yKUSjtTrV9jBi6@;JE*%9O(oDGNh<%(|C?TF( zGCkxCEwQ52$DY;T$Q}pwV{MqSv&e+K?%~K>JBKOfoK4uFE{?49@Ngx`M&IpoYc-F* zlw$zcPsQk=C!1mvraaWo6kNrVVCG>;R#=9T{i!wkoD`-sw$sAK&RSx<^mzH?JX{}R5ngZy}r=R}B>W(gKb1RStsO(sSuA3$$o&AJ}kqt-+i;Snbg zR3-lMb)L@rj%hsHo_121b-Wc@l^UV+9G0Whjcvu8b0U<{4Re$#6; z-DVB_6DxCSp~SuOGGjA`D^WM~HjdbOLPbAY==z|XKv0$V%L88ah1JnUu+h&(_~rCB zwW_Ev+cUw+?Js&8@1_of&)VPo@@#KTEtGI_mf6ui!Aj{*`n~F#8VtYkAMsDqT?B%v z3acvY*n(ii;k(|3*Y#oWq1Ao9X{IZu7D~LVhI@BO!OCU>F}GZ17@9QQ$)`0v%&CPE;cq&<4N4NA}_i=HCy-Z1ufHeXYBoj_34 z>=+N$uTO~5+*SV_rDpX6>m|SWu(b;~wNQfg1zZni`#@x+YM9k}oz?UZT>^4y2q8dwg^`WCl+BF_5ZShsu=6#F=Q2|7D}{GOr$_XF5RE z)C&SZRW?-|S~ay8J7d3GJCQ4vn;9YhI2}4jW_M zNr5<#Sr>A*G=cj?A33#9V(2J4_W1D#Wm+jcQ{fXcODO5p1cna!BoI`!1&K=!M<~|~ z#I9RiU}fKT{7mcX{PACI%&k#~BBlON>@T>n%}$|8-qIgRhcB+IR^3n~BU8V-L%+0x zIqQn~L9d&fS|~B-t}Cl#8>VbLtP?*y+Cx_5x4feDJAt68k*Urs)+tP>k*VL^uhl%j z?Lj_o*HD6Ko19r-yKtr6B}rI8h%1&q@7qFP$2B~BV`ZT08fkzNdw(@l*_mVfKWm&V zjy~Y|7gjMdDi6ZnB7}HVfzLTy@p{c8Y$So8DtfherYIPo=g2}HRp&jY7D~{&fT!+H zIKu(2eC~g_4AAuwT}KI5E4}&P1erx2_(w|%;i@RXR@<>}-jPZjcfFVF8PN)&7T)6z z&Q=i!syejQj-{N5P*(fs#Ibi)kmJ$-Rz3XAY5$=sJ=#Mh=~PxzC|jWh{OFP|^h8R~ z--mwDz0KhHt-9da?=OL%D*A3>Ov7qNn7^hn%<|6?-a$&xyN>(kIJUd4vV_Wo*9C&A z=oo`l!2h_xo#|EJUD{1yETM$>1f5s7!mT#-pv3%`Ku{GO`6Ma!m;!seszT!>$AmGF z67=oD{8#KRzTKcPB|Tt5P2TeyRgIAVfWwIUEn~)L8k#qWZ^}*;q58V_5d~Fivwd`16 z(kNxwPE$q+`)pelUO7tfjMdk*b(cNn_h$t`(w|sPEdoKV5LXjrFY*m*heM~@K>|Uq za7mUe3#bvL>>sDMaVFz3-*s&`^grH%Qwt^N9YJ4)bcnOwk&w05OCYG~*jrony=Ij1 zc&y%r9KDHGzZM1OYc=51LWv`XY}u>WD8;6YPIPg|=eu?Ufk)aZHm$qNuGI`xzOTk6Y5N<@y7S;?IcB|gQl#tDt#Pdmgy*t>I# z`Y-7H5q%j?t}o`_508cN$G$OYp#;6txQIi!uvr9v0wE(c7iuqGYZD~c4M?x zQ*WgBJ2o%b%pJFmfvyZsK$CZk5`ynUI&||epVl!7(i3J01Xa;{i06#C%R})L z-QkLzh4-8iqR;ZkU-mqxVLa@L%ohB+R7E|-_zsr1!Mn?s_}ll@fX-N8n;rXdG(w4K zSLT0aeb)8dp~1C_{A{)A!rX@vose#h^bDl&givh->IEO-dwoTMs;E~Tb2_z?VQ1nh z{!pqX_}eK__OKn>z9d|EAE>wS^IRtw^k*Hvzp*UP8EeP0&a9thsIuaN#ORz6V=ZU; zLH?r+ynioapcYE}iEw2L{X&$8!V(-Aj@$Xcg*V5!wm6Sdf~x3z9%I~3_k=u~&D^Bm zyD)F3#J56M_E(t@#ja4F>3`YL6CPDK#otYRB@k3aR~fjjmHWc?-dp+G>d%Gs2PJA2 zxUrKJhbx;O>*w1O4hKS|PTP3Wkh=mwRW>zo+?9qaX~T6QDY!9IEb9rUbK->cIbA_g z-vFNFY}yiXemKIKG4ll<042mZoUJ0mvd{IP_mkxUK~>bpfnJ<0UT`I)D%1$vCipTa zA z>ZQUR-f{z=)uA2y&grXy|B4dg^T-PQi&yR55B{`UF3c=H;w*FM^ihh}E^(HLYlG@< zxRXggC@NUa>1>h`(RJ+DhsmRqt10@7Y;Hn6_fdPm@raEAK~>^>*P{VutIP3&jM;lQ zwNPTMgB?5Ac$AW*>235+HG$rx+rx%+rv-wlI(M*R8D~Z++aBvg>Eq3yq62238Ssr! z?=qd8iQd5#<7z{fbG|U;_Gd;dl%QWxJhN?H3xZGkLXt;i!KY7EqBm;s+6v&)sweFK zRZ;L+Qi9F~@R=X14iPE7Fm6mMfuJht2}2*5zZtY`(G%2Xj>0=g2|BC6bA6AhK;AN6 zxUTjU2&$s*BW65VRTh%0dcw~)-8r>Tg3iwH?D_PH@Oh#yY-&15AgGG^fF!A&p9#FJ z*Aq;9;yATXg04j{N8`Nm&_2)?c4RFT2&$r9BiwfmEdx2s7k;O2;M771+C%X@FH;@* znzx2}>r{cDDsg?@F19jU&G3L-R@a2pHYLQq`|NHNXkqCJwVyr|2&$rfElKM2Ck!HY z*{RcJo#pixHD*0iHz_e^Oj(^?~;xMI#O?`h0}+D}#9##cbXV?Z3NtQDm=v<~IpQ?1$Xn@g0@ zpUhdO^VY2H@g>UP+vaR!ku~#lSfMDd^?bv0>;DFcT%F6o|GqU#=r>C#a;wNDR%^)qwx6lE zyH;ddTpO|_on|V#s#es0$8UdVIIbbDy{#OqjJIZmY^mZlssd|!+M2b@U7>86Y|fHa zTC>;AE0uP;^-Q-{h75onTSo9rb+UQQ9BVdX&|IZ>BYqlm} zp;GYwadqBtJ%8{2e<2M;TeN!>Z97HhoXaR=774|>j1uiosR*SAk-bMq*|S1Dv$vL! zy~A}uUUD5HQm=L zl}sGlioVTK(hIB7iRt`SG;M~Gdd^8Fi;HAJVF8fm^^0xLdC5$_wWIs}6N!&YOL}0d z4b{1pLQLPZqy{T&XbZm-Qg12~#?l0EHF+=T+*hH0R$J5LKO0Gl)oN6Gn>8Kgw253h zs77PHDCw9(>&YBTxyt{O{obJLX;5kzIEQo|VM7faw=}NH_Z@FTzmDG0xGsO;r8V{c zx{2o;$gODZEuM!Qu2I^fWmAeRn85z{I?m@Y(7vZ?Y0m3;1QS@bH`khO>#>Ox^K3g# zsEvhnSDKdo9+*b31rzxC_&R5H6xba;A`Nb?N=Khl(iOMXktY*0gsbfnqNMjE2qNT(^sVzT~Y}qI=@rWkjVAqsHRBsnb*lFF!M--)EQC5=Vxg8wcimQ7aDDTQmu zvcdAbTCElf37c}IBQ+v{RrntA)xPy9(C*^6l35Kyh#&t38+@}#Vt^KX^U#X^*uR|Q zscO+lWmfcMbT;{(B!5v~ty4f{#?BJ`&tnL-V50n)6*V8Wf&@R7ue@Z%Z20y1dda(A z{{#Z7#C!GhbuxT7Y$kB$DHL> zv~W=h{QeY4uWs!t5Lk7n+KR5u%_8xyWgi9?5}=<}3=5B+L(bbOsf$M@DcIPO{&P@L zf0ju$&S^=1S}1AeqD)eqB>VVgHWT*vg|X(-W)f^!Vy2|9E0ZiuXi4#3;^*BNCc!R; z{>;E|s^9|?8)~fReY%90ILJPxA4~>SD=RkiYO*2U<)Rs zN4zhoTtbSpWgkIbXG7Mr0;>MVQy{QPyjS&$LiO1jHt0lB$N z_Q5h^;q1E{cI%b~#THD&om5i2;&jsYj7(HbjD+ye6KrtIVuA^*8egKM<15pNd5%nE z@XB8%RjS|_5l1HMvZjN3q>>)-E$Ny~*0l4;RMMG0wbLuDX}_pcqOx8lE@u4)ulY`F zU0!JlTQKprK}l`4&L=^QK0bb#1R=q-Ovgh*_*+AwAD)Gv%C;39x;#Sagz*OPN@ijf3Vne%Y&n4sR&BsAc+EK5nB+_e!{0;8E-Vsc7crE(l z{Ry^U!hUW$`h?CR1I{M{nD{--me+KO zC(Am^KJx0cVPM_}Xz#sHAh1gORf!`Dm}ZA4fKKV;+e3T0$uE|yZcwMs%j{`>WGo49 zp+Se#+tWvFVu^QKdCc%U^8)ky5C&I6G6=R{V&ri=}t!is8xAhE*&fxs$!-}pMG z$pNNJkA}b_3xzAk*JR`8z-z(8kiPTf`G<|w4z_J{EVN$PoMH zchy^rV{2~B1U0)R6k9MMX0a~JcVM$7@_f;+$pjNvg>zu}{CtZsY+KL{W-b1}vOhS| ze;p%9>qK?>_O~Owelmi5SgKBO76FgL-E0HTKik6c;CBpLaCQRzOFa9t%n&-(JAv(v z=YkJRh%?Ap8}#`4e^W94Hw zg(^Ir-4}x9oE8YI!Vw)_Q}%@eq>lQ<3?yx6_+dw#en<1XP)(}LbfA&ZktEZh1wEbW zKtH{VBxhU8@9wk>PLPxKg1J911gygJwJZlZ@M{D)Ok_go?+h2(SFm}_%m7<3afJJ( zZKKJut#Zpyd(#=lyeeguYpetUtIlOR(E0HZ#9@f+V{5h}+#0rsrJwHvVV~{jl|fPD z!3j+|(aWBuEsiAm$(j_?d?jwP6QrKcVoS6-0=8fx`nEm&ej$tchoa9fCufyKI6EttWlwBZ>0)bUIV;t$p zq%h)HD7SFy)w)Cdrj<?DN=) z&DH{eRrvaN?jX-LjG26zc?>ZXt^*Tzm4mPRXmx^VQ!X;KyCQ*A`0e45JCjcE+OL|K zM;Hlj2_|qJ2>(9%JHwCvUa)9uLxI35{7&;7Jlh>%_pBexJ6~IP+cAN&Q~2()!S>M5 zqZ#;j))EM;62GWXo!Y~Q!CKHuT@A1W6FAp|kHWtw;dh7uY~kmPVgjphYsYt`n3==f z<7SZN@rz*#CU7)Hc6Z?&V_;uFXOiN|`*w4-L_@np^8mh@6hJGy2-JQ-9b zj}s@^^nn!bM{N76AA%43cf}}9#dQkhRp(g#buGXaOoR=xrV|V2k-nw!uW~GPgMJZb zSdgQEKw#C3IW~0H&Do@GkWAD(=?n=|cC-4f)_^UT5MzCybcVX99gH5c7YM8x!AIdG z180-|ak7sIm(1a0zf@*_kphk(w)3^7-(u#HrVXwBPdxEK6H6ExmBxG*5x{>J6Oo6l z>8V+B$b(z5k5#tqpeS)EoBzW_Ah1gORcW^^LB%eeUCVF>Y{A4yZyP%O;w&^ zvIK3XG&bRzNMMz2iVdAyolFRi;wcnm6?~LWf3Vc5Z$jh_Kh42)?daa~GfCKF`7QCd z>IUzg-DNY5X#%!j0zW6dBll4^NE&yO1z*t<2&{5@-i}VRo=GOGl6}lE=ma(&3)tV& zR)8&-z;}dau`YFj@do?Z!Y8%@fmQe`;BlYOcJNiXob7RO5xx&hi1(_=NF{u5OlK2G zPl3QH{B`l?an=vwJ=e0GJjWeJPjMV};4Lf4cuY2Ax%@mz#)ra%03#`1^)kcpZ^~og zi~nwITpto+;p^8=hN!0sNj0Q`VGAaTGi>OJKHD1eNcmXwcnB2zTwhWUaZezyD*U;U zT6f<_wCm-5aA4R($g;Uq+~M>ahAo)*dPhkkr*0%A>T+Le84v`H^IOuZpS}tNRvC9y z(hXzQk&C0{5kU3A(XiF~Bz0M!3fO{)&bmsfwQn7{)Oh}2x{Wu~)o)|J_<#8B;yWtF zsbBD_5qe%LS*}A%z!psS9kHTe{+UE^Mt&a6r}c)kqIJws#ZVxys>>)P-4~Khd|t_f zGRYMR=4LV7gVum8m{2USqHZHHiSoTnSg!5_gA4e$B&n}N5Fy7UQCdXxwaY?P{b8Rd7 zCnbwq+|Y^+HR5X_*-QA!s7zQq8Of`j&SObKehO<7cs&9?8%~rChJP<+vbta`z!pqs z2k}*z$ywyLx9p?+K~K1f{aho z^*$Pazarl&N;+ioMxtrnf{I_%DlZ?%d)S0klxYLDU}FDqIo7w4-03WT=f!OyN6 zd*)#*5LhLydD#>(_Mv-#!Nj1k?Dsw^fxs&D6-rvx zbrV_WD-*+ebbzDlvzf(1C%~5Ka3$4E*+iGKU@Z z0)bWd*Ye5~Q=Q=L{bek$s)O*WFwv{El17Dw4%4xuO{@p7B!0C-($pTvZzvyU&XCz2akd? z*^p)30b4Nfu#FY9saQ$=M96(@aPuKB;C3&jlA$ZCDB@K_ozZ-yF=RP$<#BkvZV=HM zJRL`|A2-bbTQGrr^BuWqJ-|^tg59@mFA!LT+ZY}rd*KL+KFniGtBcV3U_!i(@7~tH z7A<7$PrC^OR^hgbe;;Efz=JPMOI9rZz;I6%GS`OQO54`B(*l1t{9w7FASn1^T%6MR zE5jB{?B}D`4-2;aZ{LLWigDl^{f`*d{}TwT!e1BfYmbeE&Ys`MoWv%8Etn{tZbOyV zw>9pZ<~`>gKhXC*K--jP2n1H)uZw43cl3jkU60bD;1+-_m^jHt$iFmm8h2##vz^`# zg~fGR?BF6jfxs&KJ@Q^HHXf3^zS26wP=?pc!_QgK@V2}+*wm7ST;prdnpx!0T=~74 zP#puN=KYzTYX-v>OtjZf((VD7q=miQwhwiT2Qv61RnMI%_`vJ+nC3et2TX(B%{1AL zDN7l)VB!p4OHXQ_MaCbOf7O89k>Fl9jCC5dP9U&K{8inrjRTFzzoa|!%jorJ8@gf9 zmc||3`mr|j?9wfbx!}$BSW};XO(gBA9P6`bIT4QL)kZgt*B<&40v=euw>ETEQT$Zxc<(HRz$BN?~LR& zvER(;V3wCoeD|yo2&_7P*ov;L%_jF%V^nE!I?t16vbAxqMB5^3 zI`+&a(zA&ivs`;&3gmA)z)zPS&#(m(Z%$a#D?c}pOC~aLa%3dvE3+iEqF8~zs;YlV z8W*~Oyjv_k^S|$-z;Sn=l+bYz!xl{3{;j0z)^8xeyJVvJb__W8G?CuCUMUb*H9Am9 z5A9z|+J2Rvxy{vRApg#ne9y^c*n){TKBn$@cP$yMEkE=2cF~Y$*Pc_=0~f;A*3#hSavzXumuzS`MUG3!>dT*V3~MlHWe-pUPYaXuL=ZK>1?o~ zu6oOfA(5Z?XHLZ536oa$-_1Vryd{t1t&LfQHvHex@vV*7f7|#I%!u4fY=_CuW7oqe zVDfOKw0wIuJCJEZi(I#o{3WUs(`F~F>4>hI$t@R|=sG?O{A|LdHQL)5wqQc^(Ya{^ z{OjCFav!!=Ah0U(yOQ3%zJa)$mY?9kuVFBJ<@=I@vr8DZU}D2ZC9P<(k=Wgn3B3_v zaHVT(N$S9h0)bUwLzL7&WgV%slb_&1^-wU{W>kC@?l5e@glBIh{oY|68Pi)PUb{^M z|0N@7vypEE0;_P=6R+Ry5ekdF4@(O@V;KG>@SVo*F|Vi3tDXiYu9Ql=7BXzX1itG$ z`Y|LD_9-Sy7423C1Xkhqm}jJ9MZ)#-j*@x74u&n5z;~TjhiM-L2O{p2R3`2h2&}^I zu|jd+OE_d_k12_JSjw;k6Zo$4s`6f8uqip!{cFi(fxs&K=JV^QnFKce)9Bs-H4IxY zAwG}zmAu|->@9j^Sgk-{mH0(%uNnt)J#<-==2wO-n7~ z78Un!d{5ki5a^%Bqr=y@(M^`$i*aX{(N>ATr4i6 zo8!+iY{3M67kK^MWs_mR@z(6vvugr@RbpT3u_*|e+c~k_+AkQkU_yMag8lp-$|Gu&R}iH935{H(Z@Kl(jb01Z=?so-Oe!PxgY|2Ei=VNnaqa3dbCH9>6~e%c3G! z#!nvSMNtk+i1Vn_Zrvf{a}xU=$ur6kfmJx>z*j9F*+J~aR5tE|sq9+m@X=sONa`mYi#e4hkEA zF8oY4{!-F!_t%rv?i%#L6eZo;buC%2y#+Pk|8CN9Eortu9%VG~p9yUTyGcR&wHUTw zqSs%ZrKi1$%snsnICbht&?d%Qav1+j_*+!RrTIi0H(e+*>xb z)c@at2^UKxy)-P7=-iTtgz*V5vCfZa4Eav+-@>Z1HcC2fU?#a;Boi}V#DL4>HSETA zZH6tFP!uR>m%?;%_LoeYy%h-u2JB;TBO53tuxc8QMv)WgB>s_17>^AGdZ?P+?V!U1 z3;MeUR#?-g0jXqMRpYN(83g6K-ZPV_zbGcK>N(F<3kyjl)&(;0(`6(udkr}2(u!dV zCY*RCx$l@cuvO*S^8Is39RayZ$r(d&LJl}WMcB8K5&1K5}a>oGHk)b zpLgx3Vr~-A+}AkX&2)#<4UXXW`xC_kRtkUKxexaDas&cTUP6_ek(KeZ=(KLbx9nW6@etLko?-&4Dw;b`;}0<;xSLE^Hod`o4u(MB9Sw#pn859r zLUH&h$q zt(^v+53iHRrUe3lRXCShp#amFKqCXBn@jfz+2feNZ6$xN-Xy|=2@L+)upGZV6k9MMw3UkK&WSuRWGGYhSs)Nt zg|mNok8^PvZ2r266$Ts>@}@C?+e&`+fLAm;*5Ak0?^-MnScP+L`MChILqIX?9;?}O zh++#Sa9hbMv6+vDAs(OD+%1a)0;_P=EUyC9dL*cJ*Md$V`-B`}OyIVX?>Cq*6aq3@ z!{O|7fxs%9tI8|<@$6Eg!uGJJE{|dhCU9HH_wfF4gT_4oUy4;%s*Mj2E7S_y32cnyjM)%wvwM@W_pjs{0;%lstkd^Dx7o4 z>vF!3*rV0qKp*7`8K#)Ptt&sBtN$*x^1m2(WtlDzScNkvd7jL?EcWWpbcmm@i((5V z#CG@K(s0%>BLU|8O%({N!a0|G7ewxHrqN^yyf+*o)E4Qt)R7*nk0M)st5ICngzxhj zah+|JCW2mZpisXA6K{7oQm?&H#K}mGEk){_VgFf$z<_5#0)bVyJ`2w<9rl2okj4RP zGf$|)f{7W&9ce;96mjb;`v^^a%@$4dgRf22GrU6<@5mL2SGQj=+v9$a>%ER)3np-# z8GcGk?p>Bd$3fM_g#v+9;&pu8t_uU26ZkZ(gv||cp!OZ3$%iTpdgz)XJ)(#r3kRyx zrDGiEi>zq!=eRrq=*!f>^Jzb5?zNX;3nuWd<@+XdTY#y1fB3X-hd^MJ;~)nry@)2A zw#q)%J^ITMl6_#S)e43!n80_M=hoh60vh9epxAzqKw#B$cL!?IJ%${gFZ)=o@{WCa z=MQs^#4>Eb1b$=q&KJI`f8%6-xZyfMAh0US!GZ2hjv?2k%0Ap8Y(dM@5RA@#W9~d( zG`}i_WO{4TJxLDqo_`ccYSMzX{9s21xW*F89*y&;8`coN&J;SEd|=pui5D>r)b&yn zseB{*xc}N3njWzNt?Q2k0;>XE+R=>Fv1FsA?BnDR3-GkGhoIlL8Ma^ozYBZ~a;F8X zp5hDz7cL3}R&{)AN2QOkq`jK#zW$Cv*Q4}&hKQ{f(iWg@clU744@*g4=m`sN+7Um&lNlRddW0m zP$m0t8qpF4?(~9i^~DTZFoEA5K5oxx1+lXSfoa1GfxxO+k{xYUHI3XZkbSgkt_qu% z4TqU4Co*iog!o>avj4=aDu+XM?KYt;!QY3Nfqkx}0-Eg}49AD;X4rxW`~~xS<){kl zT6lux&JzNGRXAUqpLgf41Mi*O;qAI}LS8r~@bl;E=cf$eOJ)}s_5FrGV3n8=zu>nq z%pBkdn~ppX^4l?i-(!B3&|*_a?9vXj!`}!5R^eP#zBBBUB_zK#gC9TYg`8AO;O~)V zG@i7EX^#xR>X-uX-@+=KLCfQ!OKo9xkT!g1D(2Q=0=F1EljE2J9DLslW?t72vT?Br z=eqMc+u#J{e%;{IsL3pKxGnwMGM)t7)f9Gm>-pPKhw?b`|^$xbB;Sfi5 zIA~FFQ-vG@_y;ba>1YF&qSi2M!36fl$L)~-bv=yXK~0uGV3j71On7yk zL$0lreaw&b0A8jO2u)kbUIEci~yM zCa|vI47(U=OPxQ?AXy$-6yJqk{K{>%BocKKnb;oK9lTnbLc3Ro7`9*n-x0o=F$ExL zfIeuS%NGc&`jW?UCXDBh;G?n+3-AEtUR@aIzm{POCh#5MbI!kmq5l;X7!a^dAh7CW zhBY0?cWIAoFJ~wGIWruz(iE^TCxc-NCd7N?8t)HN%O10cso4U7RnKyi^mJ}Ic|TP4 zv2%M6G^?v*KF4M=Y{5jELwu+A;dG*ABokAw2gAysy)0&Bwm@K&n9p!?TNoHETF(ZJ zn9Z;S6RnMvG|V@X^!+5?-J2a^U|EY$7OFl=Ag~H&cqkOhjN3xL&mPe2cd*bK;4c{W zM7(m#Q%kUNrZDAjg3#k&0)NeX1Yl$i9p@4lvuKGxU={9BdA$9(4Y(cc2Hl^m7J5!h z;O|kP7!#`mw;o*~b;mA&z$!d4;H#E>?cm)Ez9Z$;L16@d3H;_O6t-6Fp~Ti6ZkwGJ z2&}>*9G(^S#Q_RtTfw^lSA>xaCh)h(&m}Xphl&7m(7t|GAg~IL)OfVEmorQa(uYZ( z-UuTyOe_zxrEa}ukbRB2Oau77qV3+=5I*atKwuSa=XvbawFA7FsemoJ)d5>DQN-Jr z-E*gt{*61y! zMc5yORd{a}-|f^X5yG^7l^h+`nc+1LT(bnPQ}A^IzAN6{*t+CIVqbl8ePWsfg3&ub3-4tp|e!36Hx`FTa*!=O`NZO|FoMIf*WuT${eprJ2JA8H0eJN9MR zf(bm<;%j$F6m+MwhwAQpO$x20U=?1c;7?G!GX#Zpft;m%7`9*n_Y6F0P-_RiJ>21! zN@szK&wA}7`9*n&t&)+BlGn^HGMEx4eulnScTUqcz<4~2BUV2 zfKPXOF>JwvI4ip6^P3Hd@rUmT9Rvca@Hzz_>5qNEg4go8{TCR+7EIvTJ!Z?Rbghy$b~&2g0xg6S!tB&oIs3#+qK^)hS;a3j|i-^XY>H)p|Vjn)W^UzYQ~iq@HRePF-J zXm<96sX$;A&M@ca;{^19>1iRX+SgRbB*%ntKb|4BDyOmTBwuOR;0BMYQdzG&8-c(o zoVl)0^oe$di~gx>^?WP97EJv0w4u7IbN*MIvUdz0h4)#>n!dLc2&|gMD*|P$-9nBw zW`CNcyFgCSTBgkAvpi(MM1ZLcb<^4Yzv`5mJiTCX@o8pe{Y$7Dg?HNEoq;^R-MB9d z7`Tr;9@rAF1rvA=4bNPDOQ1`u15CZ%Kp?OR?+oObXOp`@MA1gp?14343nqj;G>Xrm z9l$+qJ>yBK0)bU{&mZ3ei7aswfGlQgOY3#%(CJg~EfL^GdGx-D22+3A|&B@2?#n0;g@gid#B976`1uIet89pgjS8oM}nN zZ~4fu1rvD37~fO9_CM${HiwQ``%@sW3g?u`6)^q4ddnBO{D>N03nuW67=Go%8w}IT z*uC}I0)bU{M+DEZ_~8NMcwaU}%@nW&6XG6|8UqUR>i=VQBdrAjtMHBpg<>=91lI?p zF{9be!u}6T;CgflMW+^au>M09^A77O5Lkuxp71@qhsMCtz0FGxv-uR)Qp36Kxc(Vm z$GH*+?Nq-?DjV~Jb!SZAEOy>=_M8l}S654y7v>8DR^c^h{$4!^hj#0Vq@DNbgbX1} z;JkN*!ny4<@Y}phVosV2|1GS-BWHdx>7f}wRVGR213C(0YE0m~cV4r9Z31l8Fp!E@ z_YnxJ!sBbce(s+DdFzjr%;9whu>})2@10jR>XiT;`t&ZoS~yc6u<8@4V90m)D1=M+E|_a9oS8_UU=S(&X<<@&3FJzrqBrEWr07pX~z^8`NQ> zTCqT26^_sG?C8G~n)1q&2~VyGaX3ui`jGsbhN|u`XsSM3I(JndunI>Ic(nGP3pm_q z0g2t83-Lru;C<=57VGvdkT*{q#yEpQtWXotf%5w9`5?(RQ|AsxC zGW8`|tZBF#q>;vSJUa3x2Gcvv2iMs4K)_4Y_ijgxlZ(Ts9@v|XCVzK^c zuy@la4RXy8ESNBF>rD5U7BrrO%5x2TMnkXb>ZPnWS0Jzo|5}Bj%@-d~4c9A8Su}^t z{pvvTXB;G_=^L_iKd-$s>M%LEtA@BgaHKCEA0~QFh<4}$A27X+Qx%q z>@fL+iiW#Bke{hn+AnsaV8I0bwS2{-a0q~Rn^Hxyc|!G8{QU7)g6BX6j{x7V+ND9C zIt!x=Oo(sEwWgz?-EXzh@7p&D1Xke@2j8!@FBFdb)0A=wFEd;(VYhvI>SVW*s9bJF z@y<|%!gF~jG@Ez0WR+*7uxAt#2h7{kp2v2Q8+G#eI5w9j!F_M963tPy0)bU{|ENMS zzI6~kg^$tWq2JgF_4c%(S1u{lQ=xcwCZ_qS{?_rZswU!ONX;jPEttUjNBKUlArs;8 zuzST*m2U+CtHfV*JGVbLP6=lxKNKK4+d>Z5oiovyj0YlD2{Pbc>0=a@vY zHKvBby}~q}NAtZId;7xk-HVxxpCMoiCPW{bhV_JT#+%qLUik|XSS8NSBa&j^yT`7Q zd}#-pxZRfK{mLV@SqfVE(~j7&#d}6`rH_`rHx- ztU8fyOKsZhCSxjPA4M_a;pO|@?1cX#hAo&N=j~{@>3&lATlR7Mkw5g4LfOE=4+4Qz zUwMyuY|Cyk_KoZ#Gi4ThdfA%h6>G3bqn+vGz#>w1?IwA6-HE#YEFe8EJs?Q|&Q#Z; z=zk~P+J?`9>qCYVw+hl>*n)}X=@F-b2{~ejL$$=*BJ3oA!9kZI(8M=g?jJWb{itkC6f6ACT?6o#}t&1&!yOT{!1N zdtEt3nxxBb;)<4W;Mh4s(to&vVhbid40fiT&V}UjM)_W?beIW~{6u%HG$K$1vNxy30S7Co1t@!uBzqDc|pS9KDbOOW}_mRr|br`l_VwRB; z{grl|PtgAJXi zhv_lmu|oDy{5=6OOs<_|{UZees|>q1Qv1roB+*VjBe&8n9toKH5}7!q5p}OtmS`VL=v5;IEmV zC3JKO(5aa$GHatiU=?opc(%yzAXuv?WDBls6WT;fh%G~GZ-01`bD4F2eLx_v3b&|y zM7CiH94RZ8nrjcELoJ=DURU1wMBF4Nx;xXZ8w*H0KY0(o)BN-y{|M-sRU%0tVZwWb z2|YJwnwnEUj;6}*ZqnySh&4DS-SbTl2&}?yKF=5R4TP0fe@ZElKM0<4;9n@tKWYw6 zf@UvkCBF=JiY=HBuVZFtC_HSqA&n@{5D2WY{N+eJCmbPx8pJ@XEc)@S7JBf4!od`uc3jUCgOVGAbkcf;$$ zX~e_&Yi80G-!TG#RV^JI=$QovNY(&(UfZE09wtQ3DDlWiWY~fU{N3==JdENXc79s% zgsQ~?fmK@V9q2*RgCu^g>_fr#@D9z|N!|OdV%UNS{N3zhdkB%+EU~0vGtZ-#M!xl`4UsT7GU}%z;%2dx32?SP&F@RPvd0p>X z%&-L$;}#(J7uke{pVPPcb461DNJ9WbY8jeRocB$QZ$}1ry1rY6w3;^7KSF?R!Tm@aQZMSS9`{ zXa6a%G*l_Y_cP-%V^Fzi9bo zZrP_xeb=rPo(CpywGAFa?l~1c1#ght92N)!R^eyEPiivqfwLL8Sv0BX&3;I2bpye3L%ufgdI+TI6fr-SdWJ2Sh!|`~O;7J5ZQuOnzv|`zAJDq9 zmFb`TDiByD&N=%;c|ppk!>nRzQ@|EXEOxi0bJh2d-e2VJW4EFooUz-_lHREc1XjHr z(VliYo=0x$$SfTjde>6NR$Y)v2s)g?ZzxlY==4--BfOgY0>_#7ew?Av(4@%{I_J|~fxs#}ic%=9pNWMp z6;Fz-UT+gdOPIj%GM;T%IUVA5FD;orC|e+~3XcYPe*1>$(C=G&X;g8NFzUm^avKL) z@O?ii(2z%DWtKCbt*N&Z5$PikScONmd`E6}3|#EKO7cE#DU4n*k!$QoSD79nUJKQCdxE&MX+Qi@96Cv>aYspG8Tp+Lt z&oX%Y%5F4hHK>;k-|=X#B!Xr+8(%!N>&!au{4T8gU;>W}c$W7}UnmP0#XS0ms~K2@ z*AVz@qS6bFmaS%1{lqmEOo(F!hxfgpW7#ft@PV$d{()6^ErhSvUYgGS{+V=JfHj8e;SB0dXc4)cRO0v3(`SGJ^khDE)M^CvGdwp z$g|%MN#08ny7TQ5vi))m@h~){ci|~{Q75l+&Ux0MwD46=DDj?4UVUy$Emax7P_A$~m}>gpC^V%Uae^t($&bpB1w>KoC! zeXEISZv{Q*ZbUCHt|p5n$>S^cv7JiCC-#6N{|=GBkA~Es;U>9qv?+Bh(5Dv`RFJ@2 zRcdfkpN=f5AVV(7XYh<)ZVjQS-&p#pwy?~y4P9JXMd)u8+OBUKYNK+4T#{6%zg-*J zXY36!{F1y@q*mz(pB!4ldEW$PnPowH&U#8-FMLdvm0Hl^M^DLZ-G{_8&w^&qXJkuT zdA!>(+!OR_4B_af6oJ61+65N$RqRtze(flHwNoi3D|<7dVr3nnHOnbFbr9+Fm#>jvu& zxxwv&no#0-k8QtcO2@W-K!Rs{A%||8(rDucWY^>`Wb83hI&9(tqCfQu_pxYocj$ad z19W~p7YMA1?_)yOe7{3-&dFoyZ!hfOqnQF+hPQ&!+imD4yPG7gs2R=p*p|-oyG=C5 zHK8fxZRvo#+r(vj6MlC;cW{P7`%;2{nK9m`tDeiu<^)lg0Mw z#zKx-2Zp}`{C(K^S4LRpwkxgKGYK5 zUpL8M2MemJTSE%<8fQfpdA6kEIIvnn8Ma^|D%*m7iK`_6Uu7RG=OJryItV^T_y`16 zHTiB%pY^XHvs=hMz6F-CHV1;C_N*Jj7EF9!YC%;KYKc{&kDT-q?ANDIDET^2Ag~JG z1%<*$I>}~NO@T587ltjE=*PdC-ZN{-qc8Gxq^sw%qq8GmOK=x~z$)?XuHgIhl^u-W zEZ}4tUVdFVB!;4(l^}4m_{Fq{JO%PmwZo= zyC=gI+TM~{=hcvK#VvyW60dH|&q{fs(j7WEias#0*u;|79Bzp&&Deus3nsRHvY@H|Y6$$5?^WRbR*;`I1X5m% z76`1u?=+vWOxK1NQ-*>=O>g1d#l)>T3wl#gOI#a$JPy}_3#s1FDncZ%3V&&Qn^)Ta zwm5zOkKF@`klZ3Q`eQ*IfKHXF+HPkY1g zPb~mjFfrw88(Q?PnhfnPw^xCVx@=WbUszNr5?J+olp)P)T1mQIlYLxT(u8?H0PMC> z0JdPFeQ6uMc6*0pc9(tBk6J^Mwf*7GITeAxsvv4e8+0ql)>E<%>bJ0wdf`_SEF15LXBU{5X>0q*;7tBqS!UdgkW5DhT2(QpFFoLeRZGAYOlSqPr5^LE$&~+OAJ(n* zv%*Wgq4~pB0)bWdt>kytbUS+&HvmRR>VPen=wR2DK0i`T4*JMGCO@0Yik^Ez@pl!0 zz$*M!^8AwP$!wUO2kiP~Bz#fVcN)?oCo2f>TIbj|&ll~V#d5X*3^z9xd|;yLh9Qlf zTR}F}$?xu5hwUsmn1azkBZ0swd=Gg{->ZP_?${L?W}6H53KRNuhBSX%1^M+&_R+iM z3QHZ)36@SZ5eTfp?*h*+IdOxn%(a6zHI~9N$HWyyYg*E~g6#Pr`*8a6j`i~7XT+^D z69}xr?==5v-+pIFx7xz<>q_C>#l)g+t?7Wb<>cib*~iZvnqbjK2cA}$3j|i-Zgb_U^#Bsa(2+LB7J^i3IV68x4l~#}u-C0^q?B>dI zgPKay()w2efK5L|u>})uZ}n-%hZUr%@qEs$_q0nhDbJkj)0ANXt3E6+qJ7?0lTMpu z9}}*%D196-0(9S5Fl@m@e`5oBy+tJ{(3J1)x~wnK@i_qyqwOIOSfyTIM73MpAJxapk=1?`~C+cr*SqBRHp?)&fCMCvL=8DtitW1LJ_;R z1@zMG3iR#=hAo(g4dHXquMbE-$QM2?8NK2o%U#nG{A&LR1Xkhpk?)Eh`I>o7=nD;L zZy2^&;E+ zfry7h8Y26cIBO}ZF7g9g)sF&!RboqBG$x%*eLD_5s@`STf{C6LCbZ{|Y0@#TP^2K(A6=_E z14@ucr*+ndo`;K=A}Q!4S)l~rwe@)CUDGwuL9UQl=`&>_@&ca zAg~HY!g!9?rw*lq@AU-Vt8;}I876Rqjb|YRsh9p6HX4@C=}kMFGo$ANYe^fP-E@1U z84b6uB_E=062?sFj-;pLl8&73Q}a)!^ik1p=r6US*n)}VC1$k2vX+?goGHHdb+u9H zHqD_BJ5nhSSS3aW@BT3>HTU&`wyny9xFIHdqs(ahhZ?dzQ1(${Wna3Zm0cNyv zUrpoQ6Yis}qSV)I9G^=C2zM9XH^n70YCEZxEN#pR`_EcYdiwKN7*Vm1Vhbjog_+Xs z2cHsUXZd+N9Q|54&~qZp^IRYhSmk@4$NCa$$*)ZLI+~?OQbJicGy#QY zbN&O;zQK&L>{^n(>L%&--HcAo;$58pX2PQnodp7`3Th zswFuaP%x#rlKPFz(mmkb9$E3 z6HduK=7*J+ba79H_v$SL0;_u5G^2;N@hImp`8qy4)|9F%lc0Z-I*KirNDVWmg;#4y ziz3;_+8g~OKew6S=k#45unNDSd|j=!pY&tvOtAWTPk47R@ous?O}fJ0<3ia-)cgo( zMt(fB+fptNScTtXPK@mfFMArmox0^hgdWH7aqOMXIWqumt~G&~o(mYZU;;-b`HuDN zT|qm|77F_<69}xjSZGe~e0@TOX+P)Jkyh3LCSC3T&5Y(VY{7&WPkedO61HFM0jgh? z3ItZ2TVhV%lcywBOZL%6&xBW7>;=(Teo{8Pyi2tgHSPCq6; zC3l<4J`TTAfuk?I;Zf6hOo1$z5aWp#GG4Ow>&C!B|4f0vs-KSLw8_z@#J53iMUUCs zW!KvVLcBvV!xl{77&*^29CDO(>J|b$YSIJ(t0sRnqhU{;l8Se-kI{KM*y5{G;n9z1 zhAo)DF>-~%oaY!g>qNs1k|YpV)vef!o>4p_A@^h-bL0HkhmF(VS>gnSEtnA7#C8EK zn9+kcce3|lZEwpRs~CrVx~OXOJ)B7s$}G|lKq-Djl9 zQrSnBu6$~{IuU-ZZpW|%6S!64(T{mUrA^b~;mk`bfxxP%H%#gI-+Y}jTK3_5KU(VI z9S2kIYcXuWgxFrqxU@;~?hyn3TB-^JR+Vky^V<7Q$pjzShg$FblDi@bx@SM9*n$bM zcmC0>Qp#`)1(gw10)bU{{J`s9ovDyEp9+Qa`n?oeFd>c^z8l?>!k>n~YOfUnfmPzT zq%fpja{S^CRhvdJ9PvoBH=qmKR+8+tY81~hc=l)cZOPCw5a!>VE6gS^;T&Z^^+_f9 zI#iCZtkOCmWw}j)Lm8O@fmL|6#IrxUACNl7O@#5YHVU&MOq_}~poIJQIZXDkxpb{` zGk7u#trrQb!m~b}8`UjcayS1iWA?jV%s_6sb~}rD9^%O#|vnD@o=O*~gK9OC>(0{8ToBDuKW%JPYR|vh~|a z7SEdqJKbLjvu#XlQ8%RVohr%NeA$O--#*0yz6Qd9`tJgPRd~&U$9+cjgsGdgV5@x< z!>iMHJsZcF_-Y0}Q?~g*Lr6JT!mtGsxDV#{%GL=k4CVEyFJ2G`tio|7KL40t5A%ov zOb9r{umuyi59TL&y0nFYMP0$I*9C#VDja9xSx7mC@W+U+-Ss)humuyi59alEUp0e= zVII(I&RK!LDja9xD<<0iSYF6rP&41humuyi59aZ!dw1Bggc0C8RuTxT!f__PQoXW_ zJv-zNhj>L<^Dy3$OBEttT4u$+Ij@%ZQH8Q_wUEf83R<4nB&SoortStme{b0WhQOyEA4 z&v9y>m7F$>gD}Nhfxs#pXHqD9X0?(UlH)<`Z~(&=OyEA4?*?ohB*iS923oJj2?SQ* zI1`@<|4x=JZ<_}FPxfTkf(hIQbK>6)>DHGBxUkw)Ag~I@nfR$B4o9SvOW}~L+J<2Z zCU76j+pDVEQs9bUsCud`5LkudOgsxIrdHbCYa(dpy`tEH3ET(seUKqdO9RgP!+5uH zfxs#pXX0l;+*L2N2pa{j3${{h!32&u@DZ}RQK{#rA<)Nowm@JNjx+I=p|@FS#9=S! zuHKbm3ns+4k58O^>C=k@Tbmb8-HZbtrwIa0l~_oe8#J0%xJ|HAoF3a69#s z?Y4CW9p0y=47*MuU0cwz{rRe8*>!R}TZ1NcHKatlj5ue>rxk3_YgyVnayU3U>kH!& zypFT=mOhQ&T0ssDlzX+NpWOZ_Z zMHZIqxTY>OFsUG^2Q}%nn>y4myn?iRuSo~q(4pIc_o<&}pmmog1* zDf+L1n5$^fDP=k|+r5I6_tK&V^mXa9s&aDESSCLF(Smh3BjJM8eA0pG(xH#aNm7I+ zP3opgOZY0HyRRlK(9op^+EoyjIJvg^_fO3r&o2Nvd!-Sq!t_VbrRyJ;llERRQ87G@ zjfqVF`wtn!_q8q!oKQ~G_=y28ZtK#QQRQUMx)#)TuP&W4x15yUkWUhbavjQiiW1?@ zjC3NX5WR{2+cC79n9h-j=WC7ObASTuH=9G3|8%L#fif~IO^c4*u0wzBC?{X4wdjsj zI@BbkoCMd&SAJ~oKXymW72YrU#VR!QX!vFxSFF&az4i5Iz_c<__fnI(UDTt)`jwIQ zqvY#&Th zwr@ezH|W#fU#^pj_ghepefqR(;dS!4@hphYZ)ME$izBT2U=G*D8`7{X<>bskb-Lxg z0Uh|Hj4X)Kpi3JJs4@Sw2a@GC(V==N`O?oH*6eQ%J#-DJ`_2jyV6IN_2nmmz6pAa? z=CItgy`k$?V@P*1r1S2VlVv&T6tB4BY#2Uc`KQG~t9;<$xK^Om(vW)TRFK+b>OyV| z_RV)r(sCNE9089aTM54k=gi>T7Jg1chedRAH$P})tSJy!g|CU%z~=SN#^nA7=N~n& zTaOLs(Q_5VUsavz95$edffb~3qB{M@|Nm;je{GU{cFoU{B{ar05V|`2VAz6*Whn;q zRg(%b;j~QjsQW{E3>gbq^}huItAhA!;#68WIow@-9%D8xV~K{8ul$$-zN7d~Hq4J!Ir_tc!-`1#-et12AxAmfhWriHY5Th27oVja_ii#|}8yVk>sH*x%Z`*L%J9eE)g5?jL)f9kXZF ztf1>#-zl^pA#-@ijE*+3bcAtMzAjDFzO$`qwBr|zKvku;7Ww>ZikSV@Abfo8sB?FV z(to)F2%kQDj`b(8)xx)G$M1a9Z*Lw#3ljR%UOM=fdY&UEJ&P=$5vY2R(_6Zs`RmaaIcNZmcJbR z?H@pRr|=HqyU8Q8#$NPe&qviOXE8zx68gA%;;aif&$p-Yi;8Fjs_^OIeVi7K6xzUVl&d<*#5?e^g4u8Qqw*cq%wBz1+>B3JDx5d8WUpor-JKi1JO&t`Vpzu+U4cY07VHUE{5Nm4C2`u{I%};&y}JUxgMV+%{Qc=i@1&W_5!& z{B?^uytEEg4zVL7P_^c`MY_%6W3)Ah7L#@;ZlOeTLw+f=Ao0GnMdn+QA{MVOi1@Wf zmCMwc^y!I-kU-Vp{ub#Gog#+qGl+G!&!~WnH7Ox5L!kwU+=tCFbV!O=S<#qZy$AQICu{+=!?CG-gCF-B@u$ zp#_N(o}MypjZNgKZxB6t7pKvYd8q3wn?g&@Gal0Hmnxceca^73dB|g4sbWnZgVj^+`x zXw5^7KowpQ{tjNUr?{_@W_3%`t`!nZvzq19Gbv)(A>-=WCl#a%(FJH}&0E?p$6u@e zj%J4nlhdLAYExA|DDqiv8+J zUT^Y~xsX{7*qtoeM7qk0-^{XV_hj*Kql-N7$Sg~nJql! zytXMKYi94|!h=2O_rF&vS6V2c1quBaeP(#jiaib_&ga(%R6WRJmZQB>M2f|@R$u!$ zlj~~k6Mx2^(1L{i%l#V{qM4<0QtvsR6kgG@i5_x(hE3d>?JD)F>lGG6Li*6HPCvD0 z7m12TJ!G%9HZg3eaaQMA6y$N;i<&!`2>%wU)*bSY`JURusx<~NA>S)iD>#BaJa8iX z>f_qU|GHVeH>Zf}yt3q&qMbig?wnziO=KgqAc5}+dsyn()2)TU6w@-hMxbhCF0))w zEk%s}YaHWgZa11gKC)rseP=zZ?j`%H?hvYgh3f%3e ztvQj>sS&8c6)XG5HdQ^Ea&ruMN4v{$Rm^fq8=Khp#Yz5cX=bmE zO?>rnmP==vWn^2M_;cL&MkT}z5vAXcA+Igd1QL}in&m2{-~Z5Q_N3nEC^yU-L&sLl z5cqeI2(~xNQtkK|Yh#SSXicaEs#E}iH~+a;=Juvwll z+eD>;?EQccBe^~OYrRdO1qnP`u3X=CySj8HiXtQSYXqvo z9`jjUO%b`R#xW8W?o#G9ZOHxCX@wRf^xqM_V7;nWv<*4^v1tUVGAdhS@aYs07-t;A zZ@U9^e%hQy9Og>t)jZ`}n@!Z2;vy^7^^`}gHc@)Li>x-?QwmLJsrr;23$vTT0p zA@g)h6=!F-NTj(Z()VJtI#!W;|H%R^NSsXd$jl#oy2v=IlP)Fb3hzn9_&3r17OM2K zYBuYa$`aRvR^*(irfl$(#md`6o8vAr=Dnx<!8mG{LM1d!s@_sR!$lt>tzFvKzT5WAdM@vL&1ghL_c}m}EHj%BqLF~SpooHiS zYT9Ooc2;=2x2-*8uMsv;jAv^6b-wRPx6an3pTUC_T99yU>?sd!vk4EYK@_OqN3VS< zQbg_P8i6X^XIUgXFa4L5XjsfZg%%{%@~m&@FPr%J)HufG0l~EPcNi_dHb^5-h5l0B z`6>BYeJIqP$`-Ax@S5N|fxn5nBD&hq>|8CW_@ENn)kOl|E{@EMbf()5jcNYOiW-3` z{7sz08{>U5XZDX{-^b(yy+qW-HaTW;^;E{ZgR^>P)gluFq!^<*qwPT<@^=_uYL89R_i*)6Y`ca56!X4-}Q+49qjMmn-8i6WY?{M!L*ZHb){#N9hp03b> zgg%OHIJr*M=+u;9s&KtyGQIt>Ro!3OjC|@mQfNT}M{ScSCL>AJ_Gv&DZa&ut zRO#!eUDk8z#-;{zvgCb*79{YS$iCNhX{xua4oy9CS0hm6)7&hVZ%Yw{1{!bFncTP3 zaL%>dbN-@23ljLH=6KObk5#F6jp**ZBN~A!9J_c08I`7*+-pHMuWnIjK?1+Ke660{ zQOC!%Chu&EH3C&Q+OZEg?OSB+?SA;7%1irSO{@9UBMN>2aRY|ifa$I1l zXr9B^X|UM6ver7+i8|+7FVTVoUPG?KGX0Eo+UlOvtkQXnK-GX~i){JQCJx3J$Cy3l zq1D|nnkM{MCVp44NcRsmQR=><>{Ed6!CC%>m&`76SGUM7H*6xkzCqkSbKY8@LN7Wy zXoWxv5^-5A^4Ch6I6u)KhR@tpgIoDXBvAF~omr+$wTTI?#;WN3{h3y;_k+oE z%3Oh}zBaRLIMF5=yvr_i!fkG}bp%IwkKHj>paqG^Yt3>V?_dt7Z5-p$-!j%W2S(D0 z78dPqp=xZBS)S)PTwr&DSQJ~>x?#d7DjzUIpaqE&D|inwhG%3=4dU|X4~acIW2xaz z4~Yb-^!4C|-q#Z=&5fn8d1ncM?ILjzjR)(BML%93{) zI{dJ%UeJoHm+L8vv%`qJFF!3ZYf`Ex+uL}fy5u$`m21c4eTaP>%fvVSSEV3@I^wewP7-Ra5 zwC*}Pm_j3+6k3pQtH2}15q?T88AP*hrL1H8hf~$Jej0(Q<-rzNat`ml*D#(duc+eI z1V8Q;Tg^eC1&JN57TKPOfMNzwuIcH-ZQn*xzbC#LfvTJtX8E!w?~<-Fh>6(_CaSbi z^w^eFp#_QPJ7)Qh-`enr2C@IcjD+|yqbY2?w??39#0j&k+<+qoej3EHRlkp2d^wtq zN;`!XBpR`2Vrxs@eZ6N8XA0DkTQ-iSM2{>QfvQ6N%yM8In+OgwX0MYU{;)po6h+@s zR}1_?;;4<|JjWUgO}Ea=-<5I(<7JK8TYVfhxTJ+_!JzIBVFeA+%5~m1sc%$79YbN@-#( z(quR-dtlWFRN?*Sn&i1lSg%eVNnd>zNwgq=qbtXrZ~K?n{?#bj*7BG}pbGClKkb|2 z6I({b(wvY55-mvJc+5}9nL>$G5@P92?;{$4DtuyiRrFzHP&^~Hz{&RD8E}f#^b2zbsa0LE=gQFZt|Rs@Rknhum@hGOKs(?(})lLXALGk78c( z-n3LvGjo3Rx#BA8sqsCiTgp_079^C(OMZ;w_?gVvYr~d9tmCJ}5Z#=s5vV%F#Jfn2 zvg&P&iO;8vw7NX*Lt)(~DYPK5jlWU%nRs6}lZc71&fVRgCbZ?u7x-JKa=B`ek)Ld$ z{RM+aSWwPdIrl(%D<&wkAW>;2uPk^@eS5n>+?@F|@q7Frnv-|BMxZKstwrwTiVhPB z8{<{?S{__io+6J4 z2GM73MB<58Luo_VkqRwH46kF6FQ)M9wW~q6)jBBLEJJC+l!+RFs`Szv`%%{>X5BT2 zTPH6IyN<)C>+&HAEl9NVwn!Oe6Z?}4V&9h|@_UmZ6cjT-BT!Y5_ogbaS8ZzMNNp)| zS`HdCl)?fBDzqSRkH0vVc?UC}uQ9f#_x4uqc0+jIpr1ydDt;C3m;~Fz-ChPU%idkx z?L3UubgHe;f<*txX4yyC#PkLRvBXkF-8?&#qTWYn1ghHBHp^e^XUw+NApDae)VQX@ zspc#Xg%%{rl`+fYS~g)n(ID22>#XLj8A^w@|CC6eYUEE(`Hgo07F;%nql0^>e%$@! z?6N%)El6O5Ag>2Y&sJFr52j7mXJ`bfKJE6D*+<)iTV}k^ts8Syh8#?*Rys?xAfZPa z#-y!N{kIRGwp%9(jewZMuz8-+f1yo${Am1+Cy#=x>Cv5Oo%3CVc?_60F?*MntdW)~ zTD~?$xRrautz|lQrR)n+6fZz}*>G5@ zaH(ay=T$biS^HP$L5sJYQD{M8T5~UXYEr6jEN&3?b(SWM=1Oc`o?X%iRN0z($%%P5 z!gP~C^m)EB@zU#FwDHRcg%%{5^SC>cXUJ-rK_pb&lkjFrFREVaoJOE3BA=K1a*1O( z?TvSE$j1)}(Ys=(;nGBf79{Teu*e)wY~tN>;~1AkHkr|~H^n)e(g;*_d})!ZcsHX{ z2jdu5zT6Y@NB5zO1xFNGkf?RqA}ezI<=m&zK`rp`3fG_2vm*cad%90_GKJ1 zh{=z4$lnckrvK@HLJJb7W>{qIE;g}cwL#n*YF2#<_M)c;6Ep%q#~0#VfQR(Zz#*xtmS2&K!N3<{zq37j-AMrMol&Rh2K9B}co8j_ZwMOsx>3 z#*XhzQ5nk>T9DXtfM@#r%O6iRh#r3@s(${xX~v?t8iA^<{drH=#U?i2GKl|5#i=z8 zeW{mgtU?PCk?qa0Qjkq#BpAe=tc%srF)`FEvZqF%YGZD*EFNML_p=**(Fr}4sIzVQ z($$!13N1*~;b>!3#U?7gHI7lzwoCOH*qeeIm(~bWRlDdZr}5tHp3=rK-uB<8JoCm- z%BLI(ElAu?^pqvo&(PS{AYOJ(Rz5?z)4!A7Boe5qIgTT~*~4;_Bfd?h9L2Az<43wt zYscLZEl8{x;we9GT=d(++AW@=+ zr+l){CMchA47WAkRFV1}$ZkZO7OjpdJ@&j?=Ly!!t-8>`saAz!EzV1EeB^w!)^n}# z8@h7s!JP^%NZ=fmXMMBVS--jWpvg1$YXqureB>P7f!(Zc*7c+UZ?-73Ac1pKu8n&m zzxDHr-ZU_0yhfl3$49Qkx~`b@_ToO|e`$k43lccv-Y|#i*;rPgYpU$NdcefZwwfd}7Xh8z! zs2uwdyiJG}1E|%u4H|(e93M@lh(hbcTem^vP;Qw*3lca-ax*BEQk49XWuMw!i@zG?OGFU0cLIde)@>qoyByf((`5yy2s?tjaP=Uw2 zH3C&QK5`e=0a0pW@*sLQtcF4h5;)`JQFLXTx>H~vg+28$~%^xk$7ifl+}R!;)4?eKC)svB{IPY(P}$xqY@(9u)iMih7l$ zEM1$!@y7ja;zx$7d^(2nAbB2Lz&D4Sw#Y;F@nw&fXAYhxc75+b`yO0Thc1*Mw7mK5 zA*T=K9K6r2691CP)P8^`O}chPUFup!I|dRMJIpck_r1u={+@_d#j{+fZFPSw!W0RNHfBFVoI73Y znTuTNm^A`b7(vV4^U~Sr#`wH6;EY*|ltn_1Tn<}fM_vhqXxLeIjX)Jf0-H>yu6fX= zsrS^qJz<2A-5-jW<-1zRVsfkhKg#=Dbx(3jzo&9WhG~)HNL=X4bU?CrA7Vr8yjttTWRAHVUuOM4< zm5?HKYV?vF$b+{@lOrCR7@jKg;{Bwn^DM2_Jv<5r&*y|_8AiT{rFYi zn_4t}sE*_=p%JLUymX_}Unun(7et%h?^c-Ijd?5>8_B%~+H*A$hr-lSBx*5`NSx4e zWx|#QQrQ(@^Lar-#S2I5H&k z?3%A}@74Yxb*bR_6B>akjFaQ~4Er)vi)vM9?CjfGJRB03&BJ|uLf)z>5mm|ca=J#K z3gi7ureiPPsr^S4b#(fo#q}Y9Sr`1)Ca0;8qm}4c{=XW5D$M5MorZwhYFntFdG?Nk z79=n)gl96j&np{8{GRd8t`Vrh95dd19d}m!94jfL3ctOO$%X{xsG3YiMjlYFZ&jhw z8=N!(RhTQso#j&ERoK8v)MuERmPLmI=GyZ8h+Uz2m#;ys`?+casxV8CcbBp(RM}Ql zrP)qqEgKLC%o*m0twN*KfK9c?b+Cs;;kDKpZ4fLx$k{am;s7=A(-3A@o?kMB}QE7M3=L_&~o*Wz2L ztsa22(5<5*uSHX0=X+YNJ`%Vu!rzaW-m;NHSGtq-SR+t{dHejdpROXat?owecimEG zK?3(h*yH7PONQBZrLoQKYXqt=&YJ7>?LQ~`FX~2aZLVn%*ht{Mh{?2OPJr@?=t5qR zw>1J)XOjOfe%pxm$*HpKi>53CQx#f}z5qY4S! z7vX0&DN&7H5KW)*cGn10>G9NuHl9$Xhu!Gwe^s>H3?y)ugR{1VrK!$iJ5!ZsB{c$7 zn5V&G$>fKsR@=^W?zXE!3lg|5!dZ>ef2m)0+ftodU$o3ARAC+yzaNL}$l19K4UON) znT!9IgM|d{i}3fnqbEJg(wJNxPt^!iVTKat;}r0rsv!-?_oJhhiG+k+-={&%ytJTw zP3p5NPRn*e73NKG6l?2ny3wT&y?i=XEjZ>PKXkq=t`*OrRUOjvKN>v@p})&=(zkMV zv`kjaES6m9C|=wa`#Tvc`VAYysqVUPY7`SEbN>4w(u-z@T8TO2HrF4bwf_&X`$!JC zBl{0AKj#los(@(-txog=8^tM+o_xi?~Lyqz>n&mqlwpNJR79HcCmL;kncN{SG|$zdN$ZEw)!;`f%f{ z7VnIpRxaVRJ-C=$a*F$zF1amECAi8L{P$uu@%0(wDhH2umJNgMiGoLrv+9}ZNaOaV zsar=YP*jSO%s%0+_*C0X{>tJk@B7~sJ1e=#QG;FN)#Yiz?t^iR7t@Uj2x)3lrwW7? zBs`;BWLl3j@!igiiR;H)C}ZmlRpC&1jX)LpXH2F!kKU;68$PLj$wb=^z7y8}E5OEbV#7cj6KF0C&@700n@73AYL})?cML0hP|9uxPD;vbU z@GR8x_VdUpe?NRFPTLv8i9COm*q^Qj z+*5=WBog^dckmhe=Q4=cQxBD;d=^qQ6*WGPE>b!<$d*goWL#{zcvjOv_SxztTe`mz zxqsNnKK2H&ePf!6dF4pf?G>nCz+Lf>??b^VZnDkPG;uc8MTWl1A-_1>6`nbqIYXqvU^mCA%9iE5>eT=6hc#Jolc=t!`i7QBG zK?1KjM{IfKruLF9E27m@T&7Z&i;b5 za+5dB_xhudKvkY44)S#OCnCtjIK~Nn(tq<4Key^%Wz;S(uDwyez~@(*NZ#rqKhMvR zSrNf_`i-gxTmxc?7j@rWl;(H%q>Ne#|7$@ayx46q_K1s2&-@y^d3{Y)^l&57fO2Gb znT>bE@HFFlXLzEGr{C~Kn@l%W-&YBT-Dtma1fc~9e1kc!XyY@r;;t7t$AoAEs*H+t z#?${lRqHN9ne&kAo;2R5kaRct%+GI;Z&?Vhl~KXLcz%s4 z4tNzzrqM^8Y5dS2ni=OrXhCBCVH;QL^^hOV7{5GwNk{s2Jdn<}GHV2?^t0Oa%tQ`{ z^3XmPKSB!7vjH`RL;s1c~bE5hrj!~(RpYZ$#cu~r$?4-G$= zQ2}vSqub&te@PvJb4cgPsiKO_L#~T3j^Wp-Fzx*nMvX&eE3_a{rr&L`^rDMw&wB{` zXIZpJl|zFmgQ>LHXyd(B>aV=(CJ>|4LHx@CYhb%uC_lLRHTN zPsE?Y+^=|D{v=1syI!4MR){EgHe~IgL7Rc|{*nl&UR_pzIZgX#}e9ndV3*p7%Hw z_^W>2QG_!VoSoqehwpiT_lgFYsC=hLZSI2v&eXV@`K>={No8l+o-0%%P!-JGzkiH$ zkO48qJ$K3FKyQ1yQ1cyy2`xy}@17xQ56ckl9}QySGFNgO$m<;6oEm|up9PIF9j-$)eI!a$*==8S0~ra7f?^iF1Cgh4C*BCy(GA+9--D zT=khul2=`g{tKrXGe&9aK_qZB$$d;3Y~GKu%JH-*yjEBO>!kig0doJ}5IhFs2uP_>{^ z3N1+J>+^a+WhlcZlry~}v^v5_wExdVZXJJH6#Z(9KBEtW)4;1m$yz>EBT$9D0rv0q zFG11XdFc1r(+b!6=mXG+ZkJ0^mE!?a=i~{^&wvE(W^wJ$LZ#`-{y>VFvsWWfg}Y~5 zPv5N=^=V@!IrE#swG-Cc!g(q071b_AGuC@kj{9#FT9Cls$NT4picr(JIqCV+R~msT zeZE^PD1@9g=A|S1&MCAYp8iA^FdmQAG#3!O&rl;u6(FmGTJ&YWFFO_IPLid+!?!%S$%7oLb zR!SpKb(rTpL(V-B+u3VmGS!;vPoE!^pxF=4sU{^-Mf-~$vQh(%NZ<;B#79U=UOJy`oe)Uw?|2us*WkNAc1GgyBX{A()c1Fv~tHejX)KC?M$Znb8^z#qeW=e zy;s^-4GCOjaGWK-O;N`RQazVH8i6YO2J`P&;7VUCfwcc)4()r61gy^%D&5q z@=q=zmW|1lyBS1*s9JLeCU?2RDCGNq66<$tgtWJwq=S&b2t|rH6^0 zm3*(9x<+b#I3&sjJjku22cZQC^gr+n`Fb9*Z{bJpqfHutDx7O^-KgRP z$;-~4=IrMV#4x)<0!MJp3`;0XEcd{9WQ|L%n?+CDMO}r;4{+>84^a;}}E3qG|P+tJY&5J=KxCsbVA7 zr}1&iE}ggz&Q?}s+36^+4oVf>IfHpkW{zU(Zo??gs+;0c;1IQnvu>|&_H80(-gn3( z)!!2v=_*d>fyyToNOtU}eKmJSWM;ZBp$zR%& zXWhK&-nMtDHP_7V!L{>~xNd&&9X7FstMEVI3jCKR*hF8xPu|?|f!80A1!?#0EVOW_ zg}QTP)4NyAGB?*r{B z-ewuIf$I(qND&jwW_jaz_g& zB6=hB-_eFFw9dTdk3zZ&6Tb>H@sd` z3M#fo4cz=ty*!m7x^pejb6iKXer$^9>THoCIV(CJS52=XH|Uu z=L#)ItmR1TjDu$Rppx+$F= zDYPK*b!&5du4~BwXup&zt~@T$~w)%#EO_QL}3* zwvnSopvu-YMdakF@A>u{$7ox=Iyt+XQ7026xw1TQc0P}A3H7M=rtRwE z(O(J)R88cLB;DRx8OgQT2bx#%NT)pL{x!L8WCN>eumHsbhR{3{cT8qLej#eMzI0hXoNYuY=6Xm&g zPV>xqWQ#7frX36IWc((3?Hh&PCH<^^hBl|-MW)M}`CSMtNNlmYER60qVVTve*7`T0 zxH2}mY^a+?pepWlsxTt;_Fgl-gN+VYXuw%#8q>vJd(ZK^bhTTuX!q4D%WO8D#Gn~I z)Vi`Goj>JIXh8y>H;%I`>qk#&+mU1U0F6M^aqe`~Y8lt9x@+9?k)4at`5GTo%h_Ip z79{WqWiMyNF!EV_TiqFM)(BLsoX(vJxcf;!X6KWctpt^DO;*z{yAWECz~_yB$A!w2 zz0ff=K{;szs(NsbhGX2T;ag^(h7~L8&{v-=Dy**^p#=&3**%)jn0?3-Ramwx8i6W( zmXTJxHGQqpS&g5;72je0fkbt#m-?FH?y7LjRFkP*(e^a$wo-oAUTXxZaE8N~_tEyW zcAE>;xm<+aa0M8n=xwlkz&k^Numm`0_V{WeWh;vFjLTp z5JC$Qcs#B%aXAZ3xyuHryH5QogUAx zN~gUSDqpi%BT$9k6|Ne=m5r+%o-6$xWg+~k;g7nqHSWi$pVeqK$DbEy z&vmNd`-&>OhFpDbekFQxajcrR$xpjhNbEbt71}p)OSNalF-mwyYREm-?jG^i2vp&- z!23Ak2hz>ME3Ky|%@G;PY$E2fSytzMcTIS8_kt^tKH@5*-^bd-)ikq=e`w4Z3cqN(EM7>oQ~#~`|m>rA6>rdmJsYOd;Vy}Zp_H?Qg} z-E%Y0nkvq7J=V0$TCAlfbfO_2?_0CjiYm0AuLqwo?v+xz9mO~LW?ePaTO&~QadoN~ zbloDGWu8@sNo}Y>wk$~lVy;TGAc0qeJ&=W((asRpq$gFkX#}ct|JB-NRH5&TduRF&qR62Za;HTsp*J-Ug(|Fpu7V1yOk1n=4waKT@f`lDc%j&<^BA;c}l>L<6j~W!3 zVJ&c{jz*yBZ+Y$>%YL}k^^9Yzx)(!^_KU4~N_A0aLBfmc8d|u*V4=*hbymJt*_KjkrFUqff!?UAgyp0c(~;*A-fjm~ksrwBtH-?=x%A6)o7ECQQw1Z8hth zMxg5AL?*aK-1*GP`DzqR`lVh<`xDMUL%o=n#^7f*S!KsNkj-1p8 zRLw7$Dys8ym7ZB2?$Pj`)H7R`#H`~lDzqRG8;~jzxDMUG&Bh(9Ryu}eAC`$P^CxKp zswmy)bYziDUl@eLvtBgl)1RYL9-L8VK_d4h_E~csx-pqG=t?!~L*K?06fdrG`Xu}< zRP9;CmA|=0+>y-saP@oirspSG$nkUjQ)ofLk?YUR;5u|uGi%U|9My-~?V2j(%Yzz$ zsxzH!;u+V7+n-q;KK>(8y_r@eG$4Z7V$deI_3i^?%RK_gJr z%EEPud6tpK%UBz%c-w`BH?5}@-@l~Lg2Z*M4OfA?ZMcORL|*3(6l*_Dof&aeBT$82 zLzAggr|NXOU%sTv?}}^t5x9ea<1v5Fht;G}uL6?P_qE#Cjzo!jslwINF+O77DkQogD%FmHnn*xQhuhSpa&ru zfhzo>a+KcOR(SpP??yPk1i-#-{XAns% zs#5i11t_tTqeh_0nThJ$lj#)io^UR}!bUXuvzelAju&|D_?tXRr;0{)p7PiTgP87F zpPp{GdY!fQ~W6sWxPNFRr*;?j&DnQc4VOg1IG)z zio0*wM2D)LvUqjQtbwb}bqB2-s6e)_s{HZ^+WkPHz<%z1-qVvSZ5qGhm``WgV12DZ z#%0(37OHx3<-NXKfvfzZ;_(61EN1gxqs4i%$Vi*T2w{k)rH|I9eX zc?zdmRZ7u@uzU(FNMM{T&r3>7QQQ~48ux@B%T;H?xd+`)u3@R~ z*T!>&n>N?0D>cAfvmo(}cLDdj;QnWaj1g{}*HBt{DNc1elS3m=rC;6Ni$~MoAI@s; zXZ@^V`S0fC`j4aQ>1W7u>Yy+$P3z7r?fel{|a29z!DoN6CLR z_??Ddi>l9!ZK5vs3JlEji(dV}$7oPle91juplWF|ewJ!*{oqedQYUJ>8bjL_E>8Hg zW}ZL`62JL35m(w&8w@Yb%tK?STG5{gRXUlqzlEy2+^sN-yB2OcVGyPTv9x9PwZsqp zGXz?Yc*|?&ciahMc4LF+>>W$b_r6bz=J;PEP^GW7|4kW1<8u_Yb}TempaqG@eq1k; zJ9@Ov?B)@jG=j>mt!Mq>HC-c6rF#u_-W@=ZhXSm7dd$>jeS<%8Wm~S{eU9sQ_N_DmRXB6z?98CyG^BJk zYr*W5wHY!JPiONx7|bh~n#R@r&~OB~z4Nw)Ovt4XsKWU??`@k#(W%6fiMiYRYBPN# zlDJ2MBll|9mD#5u^zkT4?Xy4eXU(h{fvQ{FqoEmB&hD1kry(VBG!68aoKU%zw?YdN zKHQ_hg?lx4{4##Wme-@{xZks5-*eb$1ga*s;-1pA%OeY8q}38{$S#b?=<&*n3Zf79{3# zRqkoExbMq4gRpY-vT@l8tBoOlB@(C_$W^)fMwn%zNd|GO+7L?V-dFkb_E2a+;%H@? zSnSL(2=5G{eez(M5j$30+ww~yfvPb)#-#r6l&7v3M2o9^>0HDH^(vdYLJJb#xTnm8 z3!ZXWm@&35-O-1V+wM|ri~W#DplSnmy6MTaYh_M@nEEc7RO8F4)w~=EEl6zPeGwP# zRN1qiLA-v`g&dFERUgNHlSrT{l&joYxY})lW(IM&V;j2A{jVD2?W)j%M5NUw1b4<9 z#9c8t`>cISTHY}m%}D<&kw8^n8&}5XobFju3?fU}`c#}d#g19@NumV_oJDbu^=Z|p zeAE1tvt?b0^ADVt=)~Oib?I%{T-4y-6m5Qmgg!56`=lY2?O~>(4R>e+s_<;N8x*yr zp3Sq+8sBN!??3`)ADq>=DvEyh`l{yt-Ki0%!fVLB@PFOuZNz2u_x5z{>LQ_kYv0!H zMTPI3QX72ZH3C)mEO5lu>H)NC&}vn4=S=M>K?1++obPNJM1|TeP$KVMjX)JX(;RKs zd^jEXudVWHFk64xVP=6}ZT7wX9Zp+Y)KXhB_GtvF@ZIFP2K`6V+w>pu+UYskTZ;sK zwK?j3#%K~fZ^`kO4rm0baE#&j_VQ!sagE<%ezkep=z|1)gSk7`+gN&Mog%t^J){w+ z!qJuY)n3F>!8^SZ3pbfB(SihiwRx7&JeF=Aotb#?)Dg~dL*?be`|fWV;X@f{X6(&<1p&Bqnq{JjYSeINT83LBOp!;rSYx%T1VGN z(g;+c_lvLY^8wW0-3n`WzvY@I4GHvk^DqD2pKjS!TU*RIr4gt?ZzO-Cn#R!4sz48_mcZ7mbwrtoi}3cZmWlRB&?oz9tHUArtup#=%_Kyxl~a!;yS zWVbaiZzGLB6?!8%wsvGUnzQ$?)xo)^LJJc5+Ii!|Zq&Wf7HdZP=^BA5-OH(RcB1{G z&RB~UpRCY=1g_ON(#g9c?cDUARsNo*5vanbP>xP0UX9kyccryHo7CiT+_P(gr+m%b zfy?CL&cNF|<-gl5^2uh#Zx};Gl(C3i;#6y39@rst!2xi3iEC`8*p<8IuuffHU)0c zG8B-&;Mb<>5J8%|jfOiT8bB)<{UwQGf|V!R4mb?9*zwV4x4 zbq^0xXh8y3$R^XllaUm8B#??fou(0}!e@b>#3EIwnY$mIN*<`)b0i|RalaSt*xbl! zJXfQ#*Ce|&?o{f{bd5k2KB2t-QL7;}p6N&)4+d+`E)q9+)>n9K(FC8C|KC zp}vid(+E^W7Gs}fx~FttUlvDMOm0WFD?L@?r$sBYAThEk`(AH)%2%14tsBqiNR!9f z)U6A{H3C&7xEuW1V%()7$T-IK;n6h9&8mi;>#op(#H!-Fn(#Br?9K);p>Pi>zHh6_ z9WhEHP?d+fQzUWcw>N3VoO)@`7t`*Aa= z1x;CzrY!zj6>Af0(s#fPy#EOMxxy9WeS{>j> za;KxJ)4pvAEl4b4@A-@gW|{A+adlhoiK1&mx2xQf_G<*H3S8xg-$!OCk__TN^)9sh z>@rnp_zr~@B_+JGF`% zs$T5arO<*zW$yR#*xe%SGFQSMF7~89o9n4fW#cshRjtGL+2w9DuQL5tYq+<;(jwl< z@6{@W79=pMfIX0_2GYQ0JLRadi!}mOANV_%t2ggvWOf+~@*7H@3nqxPIujLIkkB&} z4nG`1SJQSRRCk=L5vVH4adI=cW7_V_ZfR4R4WTSmkIA)FCMbMH@fi3Pa969R{po0Y zPPMDlLj7s4`+qqUcoj@0^{X#g{c9+nNAooTRroe@7Tw_9)O1davK3yTy|qZ--Q-+L z=ic-&aFQDEYOY403P&YgpTF%!iz_Wr@zs`TqYo1JRGLgqtD`CA&ldHz-5iZT6^^bv zXZX~S%H%kzRvcQQjiN~4+r`zBmPApkx}>W8o~03}!mk9^pzG9{;==B#(lr)qUjrm? zl;Fx=OPW#{t|c?E{UVJ(mHr*PQN00~d;L)P=WW)$YDnNXW-{F!Qi~ck$V%_#?A8cW z;e5_y3LQC^`tIDHxX^8yLLVYNuju#V{iwL1G{$FA;+;*S6k3qLC!g0JAJ5<3&? z`!>}GRH5IGdxrHILEm%uCa$mCNTCG@d~Z1CXT(Sfzi3LV{7`5Fs?hJp75L|m;7UC? z<%%Np6Rp|HQ8Cm#n%BcHX_PJ6=p#=&2!f{8>YupXt z#BX_`YB`NS75e?ye-$=_4)3j^n!49gXh8zM)O^ne525_08>+ypWi$d+==U?3mUrt< zrl@Jk?oD-t79?=S!Bzf?^{0yE=BX+n;TnM|^!xE@g1Z|XiQA`&o2n_aAb~R{lj+Ne z9#sBNg4*7%_}^1IJ*z0RAb~SLu7PdWfr`y}uI6nhsS&6`zaQ5F z=+vBEG|Ea<^Hx%5K>}y8Jl{RpgnV3_sMn)VjX)Lp{dhNHQ%!od+?Q^~kU|R*I3wqA zw`O&&m>odp{QNZnRl0Z3=~4yCJD?aHoZzC+f`q=WmVUD=ttnTMhL^akc?VI2Rdv`K z<@{33-s?xzdluFr$)9$!iE{mYh&LrZErn*mG22 z)HLsHkAI@J1?Hk*UG(T^B%VJ`7A<>u%PqYPpMHnSk5%j)U&`lGT#Khh6~=P&lX&u; ziVX6k$L+(YK&fOA%QMKhny&I!^9QQSR3&TaqVLnir}OsKT5t&iQGcrrr$or0avjwR|-sR%T5R z&p9*9Ei*IB6r84%zb75Iq!XyZEHU1W>X6$~T_j!w%nLD@ zTw8ro4g=h&tSMB>|3Ct-h{^QkpA+>ymV@fW=GO>RVOAQ?05&?%gSlMWFeSg1$AW}@ zt;UUUp^pVDbhehB`GP9UcH{bqoWt@sUoQGIBoCnl2|XLI?Q?sobufTlZ1&X%RADtU z&OR%3N7>tX(X7-`g!!(+UR)AeH(BIRUUOi~KJT%#zpW}|w{RW$(u5Wy@ILX^VDASt z@Ru7s{v4_isKS_iuGVuuL(MyogKp&sA+#W&-}Ap$UFm%@M{wfgFL^Z#~tBZZy2rWopE)c)99AC0{{R(C6?Wz%|(sKc(UT;9P zj>f4SZ?kFHXGmZ!5I?)co6)(w6;-!}I)N%Zdmyn;TN<|2O}TXVrO<)|=00=QR*NXQ zzVf1cWcsQRsKQ)p?(X=cBfUBCG_m^UmkMJNF>f2=2zh>0yCdE4j!Qh3{z0Jy3C#23 zb?x{r6tpicu{~!tB7rK5BV@00?anmp!P11FPOlYOkiZNK?ugJPnwm#UN@!I2fkvPT z;|O_`I=c&9F8@UA4|%50f`opp=Je`D<$pNHELCo61gbEOkiQ?6u9T=aS_%ccTGzPHNK7%Nl_y zj3eaz^CO)pdss=;jBDMa1qsYu<5}PQPSnHFP>t(#LnBayk%t^dcCQT;>OEYE!_O32 zkid*Oj@bI%iaJc0p{%wi8i6W3qVY`KW>mi>zvq@WT81<`GwkDHj_R7?9#w|6Ls{$i|D$F?M`Bj~Abmhkj)jZgN z(1HZ!40BJ5Ph2@^-4``~YBr5Pm7Y_5BO;hejx^DX9-Q4p>6b)`?M9W??~SmS_ew`Ivk5&6xOme-Nc zf`pz&pQBk(t|sS08_T>`NT5ouozO3^3mq9h&l=WXzryMu7$c6mPMl-n8BL9+53o+i zNYHkdkid9x_HyRwL66->SYvi=(+E`Q(dz$(_M{&vHLatX?bC7rkid9xj$!E@Lq!)! zYt+C^8i6W|l;?Tk&lu|1BZsxur(Ie!6%rUP&h?gd_M_Tf{}NwDuhR%rp;v_SyvFpS zv1)B%(3x$TzXS=4{x+G!;{g<3bZlbv1*k6weyeul;hKagmn)#DYPJg@#4I1 z@M9o-{*WWGsMm6hKo$BjdEVY`0Ilv;O5Sd>Uh`QZf$`#8(<$o!`hIAeywi5AMxY9P zvYZ7G5JS0}n^lQLdo|xH5*RPezHsg`zOGFYIP$~{rQ-z`Sg*%iWQt8eYhEQh`gYDnw-)IRN5JK&yqYIz1gdbim%F$QC`)xB zy}0AlS%nrP^l`Vwf|Ar^nLl-@e?}uvg}c3ctu_~-N}&N%V8MNb79?<-XD?30K#H#% zNR52oX#}dU`VD8FMdYNOS8~&+(GG+bByjc0U(PL_)U0qm3LWgI5vanNJiNwf;!L$E zA4OkxBeWo)uWL_K>`3)}K3Z4I881&qJrSX&0%Xqd*F@niPlV}QfSf(ynkWm%IRH9?2`$99!cI$LX#>E8z&Zzzbgvv%O$@b_$=yP zzbj(z=923-eG+Ya?uoG`KUw42CqAoo0Trl9d}z|*zzE^J_<`sobIS_LUy44jABvgJ zbIX$F(?uFR5>>tZO>}*cE)MhxkiXhpW1>WIB-xuvB>mh!R{I@z?q#3c5}(q2 z%-vAkC7Z83VxJ*ifDDN6CZ#!kGc#*Yp(;*~dCV@=Oj z{R6%JZO*J#)YBA6y{rptb&RYT99!1d4uh2RfAtT_Dd2T7s}F~M@{Hf zo10=>rQ58-m6|+#_$SuY|27-AyC$y?{D~#>yv^o+tjXWyf0RU0zA3Go>P>r_T@+|R zqV|mXv~~+VG?tny_!{vPn7j#GTPo_Yd=`?bHyIBPRsAH zNtdm8W~s-Ln17}`?Yz>0zSheSXhC9h-@EKWtTivw`?(}?9V=7CvTZ0}mCS(P4_NCB zwfL%PMJ)31eYWLrE#A0d5o^BrKI^=`7XP;3jwBY%97BfYGqmr&kMPEO9W8f96)V1Hx86p2^NF;@zXab_WGO0NeZ;EXv*t^$USVeIAF_%a zt@+ryw^@?>|Jn7{eEV^|4YSV^$ZF5!ysfRR1X_?N*z}Nfw6NyuPwQ>GPMSzNc6$}< znpjdHP?aj%h+AXL9~{%$Xgp^EmEM|N(7A_&KnoJ;c|;tYK-#)<1w(It=SZOHuxw-R z3~TOpKySmpFpfHUnQLtZzvXB_0PH6o*E>s9qVV`d>Y}!ZE zc(H4t|Ne0ddpPXX)L!(%H6N7_fFAmH25W9DFE5Ay9?i zV0q7FUSIp@x`j>^w=sQn-v3`M62FPKic;S5Uz~n)a4$S5`y;d`mbH04-r^gzTKS z*s9dxbUB4URl=WZEOuu#zI~*TJgR`ol_@UALVl+z5n7O#vi>rwP`oN<|GbP-AMA-u zD?vMYmQx5+y_f#nr5V+D?r^=0@vEFEw8l3PI_w5g~#tV=4u6+2_ra7 zbz38$Gt}m=c=uM&zkN01`AB+Ep!~QkMEXSJAf`sbnPdreT!ko*| zi%TkjD!l&&Lk}Z!y1UJU_6)Qqv><_%&EyQPRZSYa=eOA4YpoEd!uur0gR<_`vVa%j zRBJos4kCe-&7_~mYSZDx7sRdmH539>csFH!d$HP7ROYDobG;U!1&NJ=u;$sOIt}P= z`&{vJlC?shN_}?AGjG~DzfR$rXUiFmop1z!y|(N`OOsr|<5pNZ!dMw$A%SBN868Y* zOCLjP753OUQz1}=y|#Q3<2#YXj;e)Yd#~bXL84!mB9`D>od+1{V}lA;dXmjd)566s z-zx;Fu-BHO)a8B2WVLbOA4`Kk3lh~Q7ctwO)wxFJh1b=2v0Zu_C1!-v<*bIdSCLvHa*+^`BKkN?sO_W12p2vikwy}=$QRpqI6dK*(cM$!3ph4~#W zZx?7mV)3OSR(ePcp88jBV|-dLo$fAc2m72+2vl7vcY`?Gu^S`Vk)TkU2HC;eGyIk!QYWtreMCwWNTS0|Z(yUV?EHxz_Ti z1HE0x>E|&Yg+SE{*~WXa;r;%#Q8UDi{9iUAvt9!QT9EiX^8xFcP>WZpUL=odjK-+; zFMFzVeSmPd_<%L*SBu}SQp6tZd&p91*zlk7cU9u9aU*JH=SlV4TMM)xVZY%a<4!g_ z)Noa{vH58on&sPoa+;|Gs_*sMSp&Q+m*(eraEd*MSxMFz3uD+9zsXzMtD7LCIy`5oBC-3!D z2vp$}ky*uW+fn8VxnpRrR?4+PBH`~tmhrw8r+;nS@7;<#%2<GAnd3Qq8vBSvq}AdBKI`XUbZ{t%Oj+|ath+!95)axwWJX`D`J^)XwW_*p z1brEDPCPo?L?KXBa@-^Kbxtk0nnQ0R>-h-!J?yMV%4{Ogf<%khN32b1Eq>>dPRuk9 zqI$pgiOu&r$Q2#`YeC}f=!dM_0c-B?SC5hHnj~wtnQRoRM$}gbRMpFT#GHL=anDzJ z8`tJdpi))Sc<~OEmB?K=8RaVb(3*F@rbhAPI^l#kYIpoDpRlO9z-S#3+YUTpA8OR% zyYB04oc4>QDf=pjyKm|#1gaL#d&ov4TJyYj`guHRGLEjd=i*{H2Z0tOjut**ldNm; zMi2Bh{xlv#Wp@k{wZ}7sKowpE*(Yv|rn}E$#J;C)0xd|`%cz1}MWjH3U_ zrHaf_wG{$Y>eY?CT#3GGt%*;bATW-L@nq~*WW9`uHK_4c*)2XvQX;}gU~E|)RjLbF zT=SxnM$;7nRoKVKS+YV;TC&WO4*AYidLJZie7?ty@3H1xE%eBC*=yeP_?0c4JvB`s zP^G@-=NAzr7geKG^X4dTEfTNUeRgEFHIFjY+h~^Ek=~}7Qb@G~g+LX)k8-`*t*#We zuQ=6no2~RdNW7hJpBaW&^P45~HaaiqPutEt7ppQRD+H?W?J^h^TMVYvC$5R2KQjbc zkTBYHpM7_?=DmLE(ZSMgBdJSVuJ9-rqY$XV=S_ZVj|WlI;7qZ@I6--?kO;YVpN;%% z#V@?l+i3o66y;o=ECx;wR0vezdn0Q)t%)MPD!!ugl(EYDfy5!h1Ll=)#RG2XZCK>Q z(4Jc6qEyws3V|wo|K+~n{m0RYj>q}gx&F#~jzsZ_4_MSxE8hEv-o`1%I121>fyLzd zCdu97Q(TRp4{5wnCr^qxCX+ zej%2oEhw(}yzmleK_buc0ee=~iW|+*+c;Wc9KA5^q&e-ZtPrSDWBU77k0IZ4qqQFO zstdFrarD=H7JOOG5028?_`5BVEKV-h_B#DgV*033BlLM8;nZ!?HtpxPpGv$PiL?LR zXXjSb-}>6_O@&A8_!g+P@Wr|w$bhX$OTAhLc`Q6gSgr5R&D(hHAiN2{w1 z5E~~|BD5fZb)@C^{9rfQRlJMn@xF{gpbAGaa=luyUNpqrQdaqw1Vo*Xz}*pKoe3I1 zCuSRoO|}MwKoyS2WHd^SadO%(;w_ID6IzhKJsadq!?s~GJ>8Diy7*2RtDy=%Q`>)Cf5(&(KmD$l30*Dz+D=__eOCeB&BV_rW2M(v3+0P4(@4Ksvgpt53 zUAb@g>p)sC!CedNe@G!vg(H2r3;59y6kV&M=A3a-8POwwS!mK*;(^rs;S{af;%tRL z6-F#%fdyc_TR;9B{G2o=E=zn)3N@vsL?jfZ{l)=K$RMAANRnUQl8f?%v?T6 znfu2XevC623=UU_>;hd2ldVrE83IV)tdop|mv2v=kE{wWP4C6=w@`&~CWGNPb)krt zl?(f>2;*o$0_Uk@O{ej`wBlmv!qn>f6#`WlXOb}h{{a+!$fz(ZM&oEfLhTvu8T=^J z;;9zhr-VQPRTyWIyVp$(pr=Jwv^Ac^1zM26o=6frgpx+*YW}Tdl}(6+p$g+na?MZO z2>LQ8Q>#D6NuUJ@>>uTBX%`}?Q%JnF*`$|3pbFzmG7q`Z7}^!uPb*y0PM`$|?B``( zM(7ywO0J?6ogAkSsKPjttX%&zhE_RTE||V4P@n|~{9YLhlm3%Ob-qTy)Bdv+0#z7i zl2M%47z(g5Wz#;#3$!4C-(7>@M9I-~XVL;*K5@B1pbFzmviH$O)0UNAc!m3O1X_?l z|G{9`_%)QCbZ9107H(7sRAHP+j#5vC(#g{y;_|hn0xd|OA0)k{8~${;*?iHg$1a6H z6~>vQCv(n^E*WQw@J(w3T9810&S2>9z7Kt}IUyVt=PLxNFwP_+UbTGboY`HG+GdkL z3liv;%Jpg)?P+)1H^GM;QV3LGoJqz-ZQGJj%~Dh#vl`KY#B0TGuj1R3-u5U@+q9z! zfhvqM$?|4SmP>Og5xPa71qn6Zr>@;G;gHjhc1+I| zZ?@#H%`4pa<@h(uEMyl;eCoyzk9@^m{m5bY=I(sG? z^L6A|KaBa2rde!Hfg?Xu-4Kl&Cjl8d!iko4n8DT^%_=q%?s z|1xcI7E7Px%rlJjS%CU8Din6B(w#!eJXS17jE~G@x8^(Yq#ea2!8%ke6ml1^MNi@x zS}M7(V)c4D@Uvx0a<6`?Sf61IJjX$=>wM~9xx&%MdeDQuZ54}Y@+#J2lmoYY0DfDPI`4r#l^= zx|gN=-ogg{a^*dSe_$zdw=lPxu6&f;2iCmXW>)T(3r`yKRo;(j+shZ;+b1g=w~+*> zkRG0~g^9baJmdF!No1s!F5HyWhgMH=V8_r zkU&*OiydrqU3XqE@R=lbv?*O!_^c15$*L@9K_cGw2*lN*6Y@=}XCD ziWpjuP~VT5@#PEeJnK%4zO_^cRH;X0amu9dO3%JDf75z~79{X}l(BHf(uHQV`cm7& zNeY1~ydttP_l9obM3)%ayva^{`?;6R?&QgRWW4R&x4rDM{QLR6E9^_!9+r2=gQs25 zuhp6o%>`>Vj&`oL5okeT(8;~5Q%_Ic?LR%@)yUOMq`j6^Vn4Yl1gbj!%4KHfJ$UR$A~HSqA8=ZvvO3}o_)kV){uMh^KbMvQtZ=2xoxB9_>2|;El60~>}4+59=ya$ zy^WXsHi{#DVe~4#fkL2aZ_+-tp|K~g^ImVGT;r`GFFKSm61@akkm!@Lk1cQH$yfg) z#w8pQ1!g13BB8553lhm`dznq52Y33aAJyUBH$~QUKbbQs6arO`%I;_9Wgo21au^KG z5pzXv7DmtbB=OuQmzjQa=R5X2V%Wy~J-gYQG9J9z3VnP&waZvx{XUWwrTYoAAc5CS zuK7u+D1JQ{OLGEM0#)zrcC!anb9% za%iCtsLGtRi<`^NoLkKml3btjHXd`vlIeV?f%=z42|5m zRT;evle9dZ)*yy#D#r@6Ac6Nu#sFeYQUDz_L3V|wo@?`{4?n>%AXDGcq6(i7sgum5Z zcCxPrKO3aCv9`Ee^ZH;YP1!I?Ay9>Hu*~c)I+UM&Z8VJ;vrG(k-Oj$cx$$?yKC;jS z+t|B0ZrsE5BlEW0!rFgx;oryqkZtrRSX3}~<7jF;Y_UKK61^s8vyy*Zcn5Et@OG|H z@UiwN@@cYNAyAdEa3c#}<;-2PbpNVk`|Sl~-9}N9J(~qukSJYhBXir}%#9OtqUH7u z1+M0y^mxhhP_k>RK1z8 znr)TD>3@V>;zY5sr5_bGJuTeZ>|losZrqUfk$L59XZNeS@z3cWS%%wImT}63U%9Ja z-4TXPV(p9Jw4?c1ffgj1t=_^$J#pcycIreQ>u|B|%s?t<`$Qp7)hK%tyB6lmE8o?x z?#PAiqE7*<#U#JAXhvEt+FKa?yuh6z)bv|c-Dtv z|Hsq+_+_DZ@U1<~G%7>*TS%x!wYu#fVY$SYf}ITtfhs&&dFG2`sgG$xXjJv50xd}3 zRWKORqm{cH_wf)j61!1~mE3h2#xh9w^~z*T`#5mx#`;qd zJfe?yyRQQUA1bd9s5(D4Q|@l>z?b;wM7(=YUfVUp$nWNRfzJ<)ckl_7Yj_U`{;cLu zTGsW8@+2aG=VvhVm31o5M~jd8XQ8@iF-K`L)!k$modP#V} z6X%4HL)vboPecOWF6p<2F4vmZ4X0VHy9$S|SH=J)y=cwggf zEW*`|kAI=BsA}9VT#FwTM&le73RL}Fzm^$$$dT#7;+*QPV<+U_IfwNA>QnJ7Ejcfc z=4MV4)nYQ(>^Tm6Q&vfiL>Z$Dxfiwr_m0s=chi1kYSF8MY1-cyffgjNZ5f#uzE3-D z97ye|4N(YGE&aKQ#ZPzOTchuv1KxUUUwFMUxr8-W%i4$oP|DnvPO=axEQ)hJbKQD+P_$zROh)!)Nb zboS)$S6pH5>+F#`%6sw<`S%sRn_b@S!BcwZ9$9d+m739&DEZdT=4e4;@cCS}riCY; znxgx=U#{-fY%YXThhJkA0#&zGs zae=mTaU|X8WFydmgzwHBY+OBeZdj`mZyZhC zPFz!-b|ku--OWB8_23O+^fzkjuvG2HyJ%{Aev3k&3g1oXx5xTwPg}-PhQnUvtwo|J zdJmh`+mlb&s6UC3GtO(@HpzU04qZ9EYZxh1&%^BTBW>l5;namUQ;rG=jBCgYp)Z%U z-ob&CKRHPuP=(h}?kjWkxn|_!Ps2usC|4H=jL*oi+PJG)^1hMO#$}^IpbDP_=>a&t z)OKu>RRn_ODo+U#7|W71Qum(?nB!wIx6ou5^6m0@ZbuCiyCyNwIR=x*ej|q ziYxb)9UCfwH@Btc&ngo7Q70B;${m3n__)@k{*N!3(j5Y)=Dv7bCPFk-2XR8{6K62Y>%1 z-zcLS8DgH+oeJlE7D%89M;Y=RwAd>u|LRP}U*9XE2_!<6Z)Hs~UAX6Wef)97EK9T- z=1Whe+*1ft;n>GuDBf8U_Un7l!%DZ6Q4tbeM|QBGcU<}E8+x|7iSRINU zTgNAsizeTj^A!SB7ArMf|4C)82nqFm z%&tFAGtUho$IkN=e>Z7d2HPlo-{u=s-&a;u>7A~vCTMib+(hemFNn5e z${kk0qeoTBpA5!R9r)TCI&rr2^8)vC6R6p*I~@He{Pv-zCRfXra@Hz;8BcFdJybk0 zB=9RLSMc~+Xn95BX<8FYfxm?+HAeQgR7)-T=s4Q;+d_$QB7xq3!BFFBCC$!BuD*|I zs1T^a_?*nl9Mn!*Z4*PpDOsVZ>OifHO%#>zi4|x;0!K)4txT+!R^BX< z);~^H2vlJ#OU7i%axLvZIQ=bHDbRuhK5sJTPCH$Y?;T23%Qb~Sl^Qj$*mkGDH8qGf zSf5g207$6M?xu$M1s~l<(%3uK6arNkZIdg*u5aQ4#*Cw9V@3-0GL7xex8>&_neug) z(^#1!w!Gp=Q(o0GmF+ua%Zp7klkdmjESd59y*}lR8Yv1|#IfY(jy&b1DUXVYV^f|u z@(brp`486^xg&xz?{{C{t-xYlyf80jP3>k0s^>JF{cdZ=e>Ae-(Y+Jd6jM9i*vo=f z8kNY_dD!vI6)Yt2XK7{XlweDPCmPYQYoRPN-1A?Au3N8A)^n2QzZvD7AHv!8I5%F= zTHkx1^!JD2Tvltk==MyMsguA;M%Z(YA?Ey`VG3KZz=79(YsPn^OlAjVoYC0MToPvM zGen4MZ~C(Oxey7-Z1QVcK4zdfzr8P!1tr<>+SARsu#`oOj;2AcD=4^XLC>-g%L2G(B@)A`S$X;7 zv1DB`L_7?bt`Mlgqm}tSI|Av%;VWW7Zxi1AMHCAOb>*9)N-IZrd1^F^PIlpkL-qSn z`9T<6{F5*E=R}6Y@9-$L=A0|QHl!*nBdP;h7_GU_=!AbJdk66w_-i zcN`f-ra@~(`=7}QfhxQTa-W~Z{m8XJDGHVR?V4lRoeR$V`r|SjkG)J`3|s2v%$ug_ z&u*T~*}lH~k4QI9Vn`G_Glot7?#w+8sM5-15(i$ToEhKOX$o7l&w*DmGUI2`rm&~W9QZ9yy}xpCaim7_?8gpo z!_b06>A#a%VUYu0^-8~1l``DP{4A%%p6?U_Rd@|$P4e^xY6$=Y4y1d^kHF7<;?M%mJEw$D_`65hC}o- z@04#zgSz*i%hrDxT98Peoxpa_vgiLT*NJt>ov(;eF9PY$ zxLFJ>NX$=}#_qSY=Vun^L|(=VVKmgAGPjjhehXE2gmV3du@Q+1gJ@src!m}vPAy50 zHhcc!-&ZYUO$j>Gtv@+di&Y3zsb~K5%yx0B(I^VoK2te!Jf{)^XR^C(?D*$2{X9A@ zTrAegC{FTy6OI-nCIuw3aC8&49oKE+U*W0M#Xs5(3(nN@MKO;@8@BwRiy3!soWhDe+sYotj3aF@T&mtvn8l8#{_7(cT963Yn9SbT z+VQX`y$x%pP;tOAmLej?DFmw2qq51V#E;4yo2NB@&vr%4VL4}Qd2{Jm;1RB!oyJVg z+w$RK^!H8olQM^(WD~MLiS(Rd^K)hEfx&Xs4Yf(tDFBZ2sZ-ET^O$Hw`Gujkcw; zQMYV){j#Qf$Mg9tw3rd~HrCzJm{Q?Urr%k5QFS;|dAh9Mgjd@+Q<)eD(S2ws(P=3^>$>h4EokE}r z?~~kJWkqXEdf=pOnyH*Qo|E6J1#ECFJ6`PHzGRoK57){LlRJ~-m~gZpvG(U8HZ91G zFCVUd2ftlQ(4O{+A%}j63<*@NS+|gRH?!k6|Lsu~-u9w4ZAlPac$mokq%37GKT69_ z6MigwDHE^lxLeuMynW$Pw(F}MA6-rN8TRfxtT`u!(%_UNh8858*DYqQGwgWzk2-Pf z>1M6m?@{z=u!-_psKO(Z9>ATInpe-!l-@aop#_Q7mlm)ofz>5H8XNXXpapXc@R#JO ztsU_NTN(|g8`+PQHjq$9Uh`x37x-rfP>rfL6#`W|cdleFciZ#Ne)=68``e&hTQri4 z!Y>H4Ab}%2xwh||r?&oAAbps1P$5u-kr25HMxc?X(MLug56aya4=-UQD%tUAab@}Y zd&}9_0y{p}tqkA3WjU*O&W@j{tUtSst?a~@O)<_b{D^`PE8r zS0B1w!ivy>#Gmp@S?()aJ}*P>MK^RAD0&`P{bhL{%VjLnZ!hHb#0I^WIMt^WJ&UmolyjfhzSpl3eGC zQdR1ZcLxtb3lf&8E7-h9JHF9RKl83_<_p(Wb;ymoD+H=;S*~JHr|fv^J$er(`YaZ1 zEgMpWkM^>v?*GQTF&3^8y#l6*X10t*PO%}hAc4_(xlhBrX`+_Q?(eb6ULjD0=O^=! zlLAD!VJ)d*mzv6XAc6Ae@RK4R<7melB$N}vj#H#w`nw1w!D)s9AoS5clTBrp#| z&KnGM5S_nvr2CGQ6arQF7RbF)s+ANWjk}ZOW((#0KmxNJw zm<=O$m#?!q|F`ils{i7nLZAwJS2-t~7AI~x4WOc{&jdzQFg|ls#%h*cu;u&a=n)q0 zZ8OBnZ+0}daZ~EHC7t!EW6MWqW<2L?I{RAOmM^+%#=m;ZVwA|MEY{ub zLnXg{Q`*4aRiik~nokvbPjn=Exg!l)kT^Oena$p6%R3h8M-{XvMywbpSHIM)s1l$W zHY=5N8f?qIcGQWs771d7u{W7EwkNdU?*@!dW>zz7x!((&7&LE+7(UyJR_t+A2vmhE zOJ(T|<(ZGw37`0Qv3-uUj7SOU++zmYy1|w&tYg6|M?Go&tltK*m9$vdK)9N62t&sC;D8gu|l9qJ*xIr(?s`AwWz^5Mrc98G%J<; zHnruG7U^v`-CXPLgcc<5KFMs{);)#zBFE?F$}0q_T$0k+=f1W)_}{qp zZSM%t(}R=AQCmU_5_m;qhUwEtF+8;~-FV=v5U9epK+ftfiWj?9xzPSb4VCu;3H4fa z%t;g@o7m97+LnZV}sx96kN_4_g2s|uM| zxzQ;97b2}g6npT{g$K4M%S#L%!zvGT=36G3^0^zMSob0qIeOK0_LeD;#NC4QDEU;iN*KYHqR7tj$#y9{O)r-MA!g>S8dXR}mM) zht6T_bbp!GBXd$MGs2nKEx8h9qzS)rAdGcv>-j%(MV-uuy3a370hT8PT98016guuC6oguD4+pw@);Qk~Ac0q1R$FK=O>CK8i<-%^M*>xN|7C7%rCZ|L z0S}thwmMnW9wo9+MqL+r(%QYH2zyQ>@Vd!3+~GHZ(3^Z1Z9L;UFPN+&`Z5L(W9MY7q&T=>~YQ;t_eW+x1qA>O7s(=z*p%C$n`x65dj z+0L2s*ZS3+(|Lv{Y3xKt<~C9YRPCxihUF$Y@!w&(w=~zM8vR=DLlwFN3Y-V_>NtfB z%y8iMSD110p;K6s)eijURGsiXRf-Nb=t6bl|c3^rP}BX-sLcooRQ(5`{pOdQ|Pc z1ktDpN5t-xp3=$anV+dyHIAF zDV2LOT%ZMs;Ed6%#6cH6;FjLQJ*eE0MtrPJGlz^*2viM!IhM8U>df!_(x2VDn8s9L zzdeZ&sRAuXY+FB;jqEK~302jfE59OHEBsa+8hCh-LZIqz$vDG**&UKvR0qgpF6D( zsESM&&z8M#YVC@_!r45+6D8 zR^fUZ1ABcCP30cEeK(dSv><^!xSR#ZD-!d~8_?ugmI{F?$1bs~-c3hN|7H~1k3K5O zpRY}iu3HmYkWl-plQX5iThWtj-JBExRp{Hv8Y%G$h0S$mYGqbm@%oTZ`>XJr>B6z5 z1Fe@e8t}JJg+8PFs>#{cC;8U&dgd>I87Y{BvhnHg&Jl$`RZZgvHu!`)_wK4kw(DPLM$hk9l1*BHKnoJT7ms4ky1ViA2lX~` za@tV8aV8Y$pREw6`fqRqYp~m$zigRVbNP=(K!!SHd02{qax`}f%;2`xyVmnpvn1FMqpGY7K# z^I0H)DtyM|9h_Z_9$Pz6cJ^C=79=p5AY*yBh+fp&DP z>kWYxBryIU*Q=GUM~2)Q)N0^yg+LWPV{#7Ct{!P0t*G_8LV*?}@LMAH7-_)h;Gaq~ ze9l&tfcOPIV{+CquNj>^QI!_$T`$mrzl&cx>GcJ*p(hJ1sH4#Wg+LWPmD02P?ng^b z-4Jh*g+T8GpI7ua42D^C`crVu2VoKIC(wd~+Q#m+U8#DC2{k=3Mj=pz9*4p3G_p0l zd0(C$Tul*ZK?2W7X37RMrNbL)(TR+O3V|y0IArb5>9xt9JJYbt4FWAlpl2Yxr9fM% znOTo!SKX-)s6rn_`V7r0)9^!$$YIuDffgjtGmv{PmoH6|h6$Sb`HVuKO7(pP4l$5p z3r@MUo(Qxcfu4a}ms;|*D8~gk`hQgjRAH1tesRq2h$_XJ(75Vl2`xyVXJ9Z4e|1_M z``n0X)T^KnsKO|P!O$viujtafE~WjlA+#WY-+Af7E!ZIZhj>!ANEd}b6-FrxhMHQM z*!0$sBF=dcT98mTYcv^Bk%LZC{G6jj;(LAx?=2(7pMz;Di9!7Sz6?~D7T zIIg?H6?}5f`%?p{)AgU?eCbcT`nO27{f{f()2uYtY@*r8EEk@&rVMY^JDR00ap8_L zbT6avoo>|Ohy}HJZ7R@$gqL3oYf7@-(ox;hcbX_GCnZ**@ejTzzlExo^J3VjhH`AM zQ70Bz5-r*4MCa<53A7;bIxCLVe&EO-=jcB5nIBClu!Sex`|*(@fhx1hacuQ%NB&`v zPV|g%r6-#i1?80$XhGsk)D))4@#o7Cy1(12lRbSu)so%}{>YI)m4Ct%_DPNhueR5T zE&VL%y4IC`$C(MVAhC6P0vnZV&+A^*iBhZN7c-+bUAy>|BY~>V(-PPLnREATuTCs3 z@lxcc52eIM76L6uB*@IVyIbw}!yh`atI2gy(IJ4I-TcXsK$WZgsTQ)RwzBv93+Tq;{E^OlNybfR_eUS4_D z1Ugp9RG%c3ZHUHE|`fvUgHm$El9LZ9fR6Fc8**Xrem zkyGU|0xd{jKV~o-v^=5J$qS;#*WPj@P_^A}1?#-Uo|_)mbBeBRd92;M>PJbAZ#i0! zQ2WHlSwFS$NrUM2-ct&JDy+&TBX{26^sV1sF?VH>l3kBID(0lioi@skpqdlziCnvE zB?}%2>|Lc_GRKd)KYl6hI?hxGRAIijtW)&dm(KW?rd5@@ z<<|xl1m{npyBjufv><_frNIyqe50VkpNaH**9?U~73QbP^|gl@YGJ>})5wuqmCRlw zu&-{Xv*%I&C!Ac_LT<1?cUkioH3)wqQ5*3 z$e~3Q=5@+B;Yr7}^Jjx;y5A-xixmm%U1iSQ$2(fiwGq@MD^Vd(g;|<1YOvt57QAi< zeS4I}(Sn59?=JnXM4{=zesnW_nnIuo^E%~>qWdvz_{ae2?A=+ZMsoe+3N~uLJUr!7d0UY4Duf0n7Km--mNOyqssCOo&6|u} z$;#!~^W_~(c*^Z%%=o7rx7@FL0AauCYE8d{lJ}r&ffgk2Xr-Tc!9!~~C7hZZUaJtO za^AR%4K>*Fwi$XGGaro9*06Be&}5!K3leyx4TcGqhH52lMbP;cvlIeVcg8MbU5eZD zOVjl>a#o~jt(%9F#nUK(79{YAk#$(IXKL+!MbMBiKZQV5**44ARoTX~V7(3R^PRc> zt06S`{1?$8VhJm1WXBhFE6dl#E@#=drB7v4h7a*s!hZYM@j6X)KQVmxTDDmF4gFl+ z2(%zkyY+Hb?YSMl`$BIcq{NwK6TAb+@%CMXK$WPrgjMNo$G6((Z6r`p{*ESr)WY<- zKnoK1EXYa-RHI<j0uxy|`_)5DpalthdSrIO z(yW3WTO+9Ao2?3gs*#5mvzLB$+~~FL@6P)9r691$D02R9oj?l``1Htrx4l6dek6+i zwp*YOsG=o{*=(7oU;C2Y#@a|XZD)KG?XpP`Xh8y>9=Wf~H+OBa7EN(=#wrA=K1VEO zze4Qz$6URQ_C5M)AG1bNz$t%$79`Z?YD1OD+L+$K)bhh>r7ywvL(TG@GO4e&v{eYL zAGS%L1qpnEWu>Wg^|X%lgUNo+euY34=A_HLOrO0ks2UPXKAVpyx#vjW{Wln9%*iYe zwt;l11yKwC`f99Zu_A%*qs+xw;KJ9H8bq!38wh_3RhXqKcU|}~gWtJ1fEt;o*|EZUOuH%a)J3DSIDS>D?!20rUE5 z%YS^*-&(V7J6Q`pj&i+Y1zM26HRA?DzxL;v9lJG#0xT%+{bUS*yKnoJ;s`!Da&BgrWXzF=8 zNFh+QF(#R1$@LUl-so*ytQ60u*oD$x^TVRk*#*oX*NXUiw<(%bN>ZXr?*M$-PM z#R4rz;1!W$oK~GgpR3_?X7mz;K$XYjWVY7Wj)yzxnH!$A5p+90NuUJ@^;-SS zSty(r1<|F1G=)G_l~ajq#xgrzva8-k54KS}HVdMSFDD7KATj@HB73yajyqJ*iIhsG zMVGK4bYV-HLZC{`{cw4ESLTBaqAfEg3A7-gg(tAWBzr#ey?%9fO*NvrsXghgn5Yn_ z!fY5h9?bh%uwa_3i&H;9`5NFGj9(&|ZFp)`L4qWPJRPTeage~bS=Nm@xVgZz{1|$- zX0}403csjwUaeRCg64yw>Ce}N%9j%fd>^Gx-H8_@E{LQ)`?C}RRp=SW_v5^Iez}ID z=)~{siU)uMKKXKvzH+JjhL&M;ukJyGKoxp8vW=o^?0`iGISx3bcrr-fyD1}gE}z)u z+eJ!;mPNxsZL1u;o+a+Flv!yW}f|hY5<8@g@8%RH-Yfa=yrn-!gTmtV11T zeH0S@2Ntp#Ep2(h3%!jx9cPR9k1ka9VSR-_6|VV`s|S9zp_x~z)4W;r1kQP2%@Ula zkYAjAO=v?uHwxL^N}vS^%z85zB3!*_P)J=WI$u{IP=)gp21CA$1MTY}sOI~Y0xd|W zJ%hzuYnoNohf=E6QwUVyJcZ13@-rjT4PD9EsI@=~64(>T?1a80sUG#FPf-mN0#!Iq zA@{Uc{6ws`9727&wH0VV0{cf9Vd;NG#7`VfkGnNg2vp%bh4hx@Z5Bhmg;3zJwgN3k zU_Wm#guYrR;sQrena4QaGpYrIZsFC-R}`ci%+!_ zXh8zM403h4BBSo0;G|LR_27Q3wV((<~vSG_J>jjp0( zt0S@TKrq{}#`Aw_V2|&3T)Zq*m)<{BGvZN&x%D#Fx!*xyUZ*~7>|ImIr$*w+u3*+; zt>?d*kTUP}MwWQzP>=p@a8L+TVg9yUy<9h2l>b?uo=>+Wv>@Rs+h{M__rJ00 zq8Hbv;;)?*0#*4gA(YXl$xhGzsT|pH-8^A* zwg;ux`=L~ta)jzqxRy|kyoN3j)Tk{D>t;r1K?2w5$U5|XbHvWEt!Vd`iVA@$TuW#$ ztm-mX-2T#tobTEbT9CkXI&z<%u$f}}>w4sLz)c}gg{uS&hQf{0MdwovWbe{MSq+E; zRsoYSWap`JS72*u)mJD4s&MV1!BE03hJH_*C{k8$P-psB%O;}C5r!iuMnuh3@ACqDT<_Nh9zQMZfPYq z3JI%@5p2py5ANGfuY_PcAcTf?$rYRWxGMyzFi%SEaO4w0yK3ze4{vjU79@f!BUtTc z9{*F5{IaZ~vpn{ku#6d|5U9euMft65=}%XpPKoUSkxG7|LYxn0^Z$78L$mes_*WbZ(eA#<3Ex4?}-$E67=W<6jBVY1~EL`9Y61dhu z)&zXjo@h-a%D>Q3Ay9=rysSX8n#f45KJ$^a4bg%Gu62+{wXPm*5B8)suVWPgRk+?n zW_iasQP;;_lyxFish@}hu62-YY_CEV+lZ!CU91qO!WAkq581pd)#)K?o`vNIv><`` zelj2K^-mFTr6WylzDprcg)t7fGHmcO!NNP!ufE5WSOyZf0$6%W-7kx~=Y7dOc(+2J z3S%{L576}o#EF)Ds9b~NN=ya`TyZSdG<;nrd=iFI$3?pp0#z7ulC^QGEfljB520NZ zk1MeyB(VN~>`O*Qiup%JQr~O46arNkJCnVr)?c`696?2fV@iw+39NS@_pXVv7q{jF zQ<<9i3V|w&0ZO02wxSr6HIiC>Jfp<=kie>ya%6s>MKd##bD{!d^GxN56bz^_&CP@mr1fiCcP|?HVH%i)QVc(U0O*G<#Vfo1a~WH~4AH z(PKqVR>sK8CQ!|_^~8gzxvUrqWmk#gF9l$`1w%5^4BW_s_-8syd9`WGx9}Hi^^hQzKDr6d z%X-L`*#xndhnw*7_w>CWjuf9jjoUR4Sy>Ym3ldK)g4nk*P5I%z_argjFo715@1BRu%Q}p8?o*Ff-}9H7<;zx+<$gU7vz7in87(&zRU1zM1p7!=CBJ*dNtPwGUjNo5*#$BBl9d=bYc z1+!bV>+-_##vIqp;4jHNi|g9ZvxnAH@5y_m4J2^=m+VDnJJS58H7MBbr9z+z*MG^e z+WhCD#KwALwAh?*^oyfyJX#qY^fJ)i9iEiEpfsTc30yNSbJd2GrCi}knzOM&pbF1P z`iUi$iNhOP(Aa>A)V^~d%kEs4zin#Fv6o008N|}s*5yw<^__d;TkH^>t1@!*twd-+ zLhVbsINTBE|39wIIxMTD>%)(Qf+%*Qbc29^#GYA#h#eTH7${wWib{xzilB%nwt~e` z!N3+!hrN#&*xjwD*a3Eav;E%lo;B}(&vmWe{mjnUGi%nYmFog4pXdq%R^jvGYZEQ* z(xIz5L3R7a!g*i<&+auEKfQa@VNxfk|E7^ZU=_aVJeG5w8|Zy$3tQxkw2@tuRI`U8 zG0)PFpL&tfo;WA+((jwJ*e*g!%Hy%bE7Tea!EW|2nHj>ANksyIRi3>frG=9m$?!dD z4Y%)ixYy&SJ@ol~gklROg6+el11FqF%6YYo^no#N3LwDkS;*Qk(eTa0r(BnTfks8K3!;aVX z&~Qv6iY=IEbURea-|kL|3)I>*?K@Jqx6cATWWFPqz$)#rp;FEQkN?y}(rwZevLs_z zKE0A)3nrYxLZz$oJxHxTHIbg!hjv>YEH$X*POe>gECtOElB{*zNznbrQgmgI zbko<3wCeVppGQ=v1uR`m;Ko&5;VF5Q9wH?k@gO~Utu1{2`ABBJAyl^P3hS0Nrr3gs zmd}Hw&W}C*Q&0H9(UxGhttV7CSqlVK;cLiaKja2*ZGp?d0 zipP9Dc&P^T+&Bzeh`B&u6~59uGP7hlqta$ zOo$_Z%9(L6yzNT5;_6m`z^YawBc-@E&cw1@9g%&U9|WTsRMIukc|>CrE-kWiCq2gA zkq*rYldhV0{HdvSV{w?|Hr}1oNK>E0j1!|^$e16r$=!_vTQKoJKTN9K&x2Iws@ICd z_(9HlZRlE1ED%`r<3gwuHO}Kd^`kmv20(}P)wG?@b>XORdp&K#rJ3E`2%~>$7CR4w z9?KfQdH+TfTQE^PDNNcm%Z=znsl>=FyPke^$p=6FRy> zqat(gn(Irk1rymTL!}KxZp3?u+QvE?2k?Dq2hcr6Ah61DaF`V2<4Te&)V?I%sXd$@ z3{d-IBE=R=Y*`;7v4?KNtVnI+qfRsUeajnk=gt=htjhEcl}yLGl7fM18=q$VqBWBS zf>zBeiY=JHZ?i_z>aS-8toYlKTRuJPVy+!e`VdzhqE--E=f)&0;j&3AL$ ziiB?)PSVoQDB-!nM7#Vj$)%wO**9B#cDwK#smmW-q<01<2n1H)Ctss^?=b~NI?bok zW4=gu27!-IoK1}SYa+NT+(3tJ$r?OzXOl`+DkA z@-R3Aw8r11*0;|P!Gf+2esB2hvjqXrjJ%@_=W9_+U{%1&aH-3!&ZI?|`hIM*;+3F! z)Q1tn9VoV70>3xBqRx_DFyUkqSU-5UKwuSX6d`pBav@ng)LCkPmOGRTHUaOvB#JGV z!0!!T1$b`{Ma``t@KUBgVAWXuo@+04A@MWSHU?GdL%OvGxOZJfu>}+Oz2RAh@|war zw=NLQGYDV;t2R1^N!HATtlguwv1RQ~YO%a86ffn~ppXR<;u{q_rIMy!9spWpB?5s} z;*7pUdMU5u;SZ}iGm0&k5XU9w*KMY`dL!Z8_LBmERoI)L(S*(!2PZAJP@`cE6np;h zN`w3KXz9vr2Lc}III+5N0!*I2f@VHyNU;SIcrAqQ6W$vKI!6}Kldsuci*eUevmokDan80f~JOlsZ1Q;@&dvY%13ItZ+87n6ec(vOZ2WiQQLBg5iBgE?z zeDtdBiq~AAzsCepY{5i>S5eZWW{%`z$e+2vf{{=w^e%O9oGTDmh1V%~L}OP1vrg6r zD|S-I;(>DziZkJ#dp+S}-+EBgy^LZDCd8G7wU$2M^0+Qs-?U30uu57SCH=BxtIxWa$7DCScR_w-+AABAXr`cK&Lscr`UoC zyxzih7B3kB-Q!==9cxz#1XhVxcae26%+XDNT00s{JnV+8`M@N9{%s|DuKX}5>Kj@wTt_H6#BA1al-cOoxZ ze3$TymFIQV-9U>92ZEn-6~z`z1oRG-N@JZ!>lbR}#fRtktj@SEG&}N9Ah1fD37c1-J z+#fo-HG^5*xu+hDo$*{2k9{>7tKYpq+q5+_-~37#g<}HGiut$pU@tgUw-sDp(3s-? z!YVxWpcYmtMJ&D$61E8hk2L0z-fMW ziY=HBXLnosHiM04dqBS*fdYY5c>duIy-R^bt+Mw64&3*JoBgQ0AyFtWr%#_0$t+}ec{X{)2Y%Ju`{Q${_A zj`0-;timH_?ls5`faLbCX#WES!U!1?ep4f)_?*t9=R9>3UKJGreS6-bn>T$Y_`k3U zkLP)m#o$=zU%ZQ^2AB|6Ge(YygQU8-)UbZEKwuS~$?*B$zC?KNK7bC`cu!dQ z!GyT}@vTNOSQU4o-F&(U1Xkg7Bc40DBoV@kM$l3`rf!n~I5RGPXOdObaucolb$+Km5Ejwea70cNMlzVdPbJUG*}Wf39-sxy^D+ejtMEvT*J|wV1Gh68 z!q{1>gb^7gu#cR-AGSVF7FHk3y*3F1R!tLDWd=CALFkVb;IY407+GQh`^fpu7o{Ui z?9>k0OgkkISS7CG+%sqgn?6}V-zm3*RT)fRA32Xa8`K!y#M*&f#w&rqDsgS1!`07p zRiQgC$N5=UUBUz&8Sog$p%3V({t|e5iK{YLg;!E|wSwb&=sYcNF!Iq6R!lGd`+5 ztgnphY6;N>wbiV3?4K&0d_9W&lLOf`Ig)+oWKYKEs% zZgqU++A2xO$@Qh94OMnbu5alJWCBCtS)Bm79-8(%k8$1Y0oi_w5MQeoSYQ>7ah2n%7QN%%3{;iKuImO2DmFcH%}f;BwhN|u$YEAFf6Br9dHm@*&rg|Rf7ZMe% zbEE0~(SJ$Uf(h|Fvf3ppPgXlnyUn!)0;_nu2Ky&ogRfNo&{o{a2En$iMl>!fm<@gJ zLA)PcksdAyW((eVkmr0|WktOZ_C(KvWM5H_>hRJA%Blok*tNlcVhbi(Jr8F8uKX-J z)>5gxqbE%HU?mV()#7&u+f(6AdLB^QST(+eGWgywSl8EFI4ay8U&mqptg-Q2lgexP zY04-lpX*7n1rz&z2Qddn4^ro)+Q!dM*X3b{g5c$>P6B~dd``{&T~~YVd|B>tIvCcc zIjOVl|5`B7IW>sgYbKEmf7b3cbuN`N%)&u$c7KX3m^fG+$inz++w8M?R23ca<#I9( zsuoj$z$!jhXaCIZc{bgE=knVN{_u=Ur?yLjS+Bb8WcPu`5^f`NZ3wG+;znApQN7N# zO@GS=*ZRTA#eo!CFoCZd&nGjWnR4T54_Fv35?D2Uc__Ph(2e*e{qbyvw^s^pctK8! z?i5=vA>Q+=LmiYJj*igI#8V)!YVpJ{b|=k^I1N{b*`@PK9em9a}wmi?390_|R8T1Ze+n2kN&3@{t zjHy|^9Qu6>%rx6Wu>})H^@CXiUymN>rS_ub{qp6%4~>P@<~u01On4K-Hg$C)MOn}P zrwwwO$rla>z`2SILK~RCcb3O;7Cn>edHTWXwz&db`F7#Vtqou8zo}l`S@!Nq?BC{4^TPm&EttU10wqT;HWf1fE1jlKCe)63cvb z)Ym1tg?8{1%D6>rEA&6dJsL@m;^@zc8`*Ml_4$mF?%( zQuEvm8f2;jG-wAG$G#K@tl}|cERPeX{}9WEJ(Ua2^?|?LPE!}-Py3(*{^mNqzq zF}tHKnh@x-M5g$#0vvLN_A~_;-t7GuJy3{o@*fNB81v!oSCA z`FCYkh*;Mc@SLOaWEj(obRhXvHUDS+;r?ikoM-P1b8F}T{x3|3M|GmhL)rfhg-COa zKwuR9V{8t#BZ&_8Ox7 zEQ;B+b0iP^c_>YJ1RK!Fg(SUDqj#!*_$sdBztaSh^w@@ch*R4*QXZ?!OI%OiTNzMn!319)X8-Q(>##XUX_r<> z=j$&ZHF?;j3jMfxs$p^s3j9Ds_r1z;om~f-RWf(Uk1pILiU|y_ALt#_+qa zQXsI(KQNTJ^T^EQf8s1}b&pq`hE1X2Ps<4QS>StsJuf`6W>1`Q^YkLBv;UpolfeYO zn|x(-ZLIQCDxf7UH7Ncstol4OlKFjdCQS;|H|puq5aq$bOZ0pLbBZmP5Z}RyDIrSd zMb~J4r)C0yRrM1h*xwsElc7=S$nxx>0Ogg_D|)Yw0mT+fw0aiKG9Pp%nvE*)Dl$ZI z@xMj8efmZ)fmQ1chO=JvdF0t=)t6D88KBtpeMi^YYEf*#gn@N9+tS;O)G|}&I9-E7 z6zinBbnnnJ1QUWvc-oK64^Y+>RMP<`t_e>&CPZIfhb;k$Wv`DkHNH?FunNCvJYTr) zaHV%j9dH}HOLzw{fqjd79<@3~8OZ&|alQHz{H|e-4t_T^8vDN{DjTvl(0;^2I4VqF zPYCz*^@vq=pWQ=CXQT@RR^e;NSFi%&6sv~0G%zkoxVo6Y9vzM5`Jh{Zuj@@KDEaVd}fyuMa`lhzkT45Rd~+8<9*CG$Z-b;LhaA*g}DJH9@PzH@4h+_+pp?u;(CJv@|(>A z;c3bPfxs#}li^d^q^E<*E2NNZFA*|(R7qa1oy87Cv=SF$P9)Cz3dr=^; zs+A^$nYZjrScppK)pJ);gG}IHRifYnz_V2Bf8eXH)%Hq&nKi7Qm?`)fFd>c;m%P$f zY$OlxySY>#unPN8_}o8d%;JtT?)jJERXoDJzS}3UO~ToUP|$Z6%#zhi~XBHz+3iJ zGG=_DMUm?S0;|L^wdLEsii_EI+I-YXd4qeri}fYK|oW}M{$vBLt)-Qfxs#r zf5-l)byIkEszMl%VFG_eHJYG8<|m5<0;{lR ziuXRGm$D+PF8nH8OR)tL_zC4zdvx8Dn{}Imey%JKSS9)ZPF`_Uy2Uq!g7&9`89gS% zXP2~gQf^-6wa@Qe69}xrzB3-#Ki`&)`xOooc=n5dht{(W3r+sy#Tfi^J@d>m`BO2w z<+inK{9fZfwYT}x{$aNK&8t0(;uY+x-BQ`vnLL9suVA0)H;b)lWc;Useaf6!?2D~2 z34Ebub!@TRKuI`B;n`%K(V_KJmiNJwoPVrKY7dyo;@_K+W;|0}FP{`vzRiTxoTlbz z+*&%GRSrvpVx9vc`D`|Oe#nqyzSJd7McK^jh#|RfUYCsQxQvB=GbFL}a z@N_olGS9i{qDNlarLm-DMx?Wo9?9yN#@0C*k!?-YTG;DSjO1zG2K}kkScfiVS;>Zf zsyIp?mNEB(hJPxizjR#ArY$%8PaWQh&C#;+sF85d>KUCgI)gQ=G9)$u4arNI#S-!i ziQU@|}y5nLM%~QI@5#iY%T3c}_z@ zQ_|S9$wp*ViArpTZ*sUkz%GMII?X?cwf$sDf}9(W=ci||ZM^P|-3$JE$PA{p#Dx5A zrxI`8zoK8u1EDNZi){Ut%j&E&CjFMxB^fqrSo;mefrXHRd20}NiFcbI07UxSHc!d;Pc}- z=r-)3-bZ3#>X3S*uy_^Il8wk#Uf&g;ttITEdAf^JZLijJ-u1=7bf2@@S- zR-Btg%{}DvIr=IX%oow1oXOz$AYH=$i;0Zl6-=9F=04X)y;jp_Y@)|H^Bp#?=L-Z@ z;cLii*Q^;ul+`n!=D7aSXTNNwf60(!jnXB1b}VLV?irF$EnQM)LN*ILXGq#5tGOl@ znrtUcn#_RDGe=3-f{E7im#_^_4N2-b^~~GNyh6rJn-1N)YY6{^RpPbMs$)nkP9#IE z_}LP+V4`*5QudJ75*i)*r;UUjbV$vq@N7VaNFWuy>O7y!$HS#Fu1trdSv{osmlm)q zcMVC)Mh%F8l*LY6GbGJxG$5W27cfVjk@%La+9&pFvb{8}=?q8+_K~m!6K6MNF>PL{ zY27RJS_S0wEj7!Y0jq4^2?SQ*YskOO(KT3?uQTB9zTU#s#e{v)BG&DUAsLvawqbqj zq2%>w2K;pHE)ZCS?<`**yi-fQePbHbTro&Eb9_!0^X9X+{OURfsAs-*tBXAU=v27Z z{?j=CS)`sG!UR@@Pn*qJtS~0Qi7FA(u$iLSJpdr` zmz0-~!rE>&Ar%%4i1X8#>~bp;-s3bNnC2OQPSsc5jq?Nl&9M@;VB#d1%|>i9CgUcm zZ6pV1DR6f?1z6v}#`b1wvc54My^-?6OC-H2el{wK3txrsbC$Zc8%!p%s zU1IfDJbUV7PDZ7vJ=~`nJryOnJ=i^umaqjAT0u!Hw6_^K-9YUbzFKxuhO{(>x&3|% z1XhXHs_S>EoS0w*=U(_q*n$bG`pK;NmMIxOSZyPGQD?;>!V#=j^$-ZG!uN?+IZhj_ z7#1`HW$QfQ%<(yOOrOFoZ!{-0b<{K8eQKD}@ljn+_SPfVf{CuNli2np79=-V{SGcm z8KvlS*MQ0JGzk+}RpY{BruEI7-2783{)%<1l0Bw~UaUxynh%-Cs_t5no8Rk^_t6ts z#yLx3RbQKIZ#9vHRaug_*6NtycWkt>SN|v-o0%?Q3nrYe#W9~J7NkkFO6<1_Q(kwu zO+SpTC;S&y;UnaEquhd(-^VLycHc}1TQI>kPhve&Ey(ol>X{F(7^65Pf1v%%<_ZK> ziD#Z(FkVqc?Vx@6mlK~kKBqOQ6IfO-uhu+8t=hAB%0xwX++Va&UoC4&Q&mVg7 zYR%i#aiVV66y?d<3|hB)x`YX=dUt6&+i7b}Y%*2C^-+RiRA%DV8Y6GJX`*^ zH5v6#9q&%Ol&F+>jG|9p)F9Y`2_f24V-c9F96fGD-!GjmVFIggbSuwOlwzvn{M82P zu6#oec8p=G-&hlqq^Ap);EDRt!@egRt?IHVbkwflaGPw9rRq}u7rQog_KxiW?wn{7qTwD|MvPJJqW&#{4y_nQM&VcPQJICeJ6iWEyK(Y3<`*~i}& zuGi5AY!QgoRAc|R*6RyxG`IfJZc9M``G}tV4{3uG~30`V@sfV9@e!M%9j52 zU`4D20;|~6D3&+ensh5x`>U!oOXbydU7%^TF6HbG&bwkPB;%t;8hMjy9+Lt-|O0g%Po<> zD*W{DSWe&TvfS1l;$m6~PYEV)tO>95H{_|jqlYa#G;J;rScRWy{_Mtok*{pDhQ`}? z6=L*GU;;)UatKE!tuW-{}^#-zsgh6K|* zUNk0E9#g{r9?q8lTQKqWv=kPz$C%u?sjBt;iAm+t*r5R?WcmuV4K3?b*+w>ir=LUutHxYUW=&_95Q%&7c+cSYMUFr34hJ86 z5G^dALkuB~zLDjh?0)bUN z#)-`3i7AQvGfO@9yhv`<)E=~t83MLo0$&l0rdV%>yduj6Zagv<2&}?y0ry!NES77B zo5DdCXW{+8gm|qAtkUFtgN@*!UVHUn{ug3co5t=`+{N%Cgw%vvNt!3 z$jN%@w|4s52BkBGj)BI%J_-a@?H<00HR)tTE)P>j0G*N!m3B@W21X0C09!E8wr~}* zZfr!(&sK@zcN^qfg8>lJ_nUBa@f8*Q)EB!il|8%m05kgrfGwDa^v_@ec$KkwW$OLN zC|V_-i}i$?^_mL=RuzP%F`J=AWcV|c$V^<>)8+uyz0y z2&}>@5E_kLPP$wfZv_6g-5@S=F^jS@B;AiSAZ7WB+5WnQq~K8l(zRta>-OD%(9Y_4 ztZy_&p4!d;`VW&}`jjj-y0ak}GqoZ4IU|ej^D!jlISom1_5#+gr6GCp=WAe)FiSqc zGdfg`_$sVT;PnW6Z+I-u^F-P9P#*}3(gkc0h_EbHZwz0}@KujWS7(l#yS*FKp4dzv z2vXsD!@r!*XUcE3@EpJUi~w6OfzOY}?>?I&yO2)spsAHWU=_YM8cnT(sq$Q&0et=$ z7r+)wh}Wv|mQ*?GZhJT$PXq$1@ZID)c)SmncH89#x_;V#-=d(kxvcLgBhswB4iVod z|F<>d03TmSzN81(f{D0`xvby-uQTePzUQ}{oMb<*?vT;FjX+@4|Ezf(lH|>9-Jln* znT9Qx2&lD&S>+p%2Ht8Lu@NKX8if=#?KBh!th(N54Xd-nh-3~{iJv*ya-pjoq};Uu zY-v1W4Z9xA*C`@(NC&4}cD}6StLJ>uz^#T z?1ZDjM67-;^K4;6${MO|Y#p2}cY0wBOFDNH2&}^EhCF}Cyi9rRZZlY8>(tn#D!c8?_-cLq4_C6pk%&0c^p9;f1B_ZYx9b zYn=K$PrTnn-d>|G%$VO8@QR|aiWs(-X%90b@c*7|$Dwj{q$gBdZx0$|!31ub`}%ap z$*pF&fuWU|KwuT_V|ccnx3lC^kFCMGfuqp-U_v~PJ@evz$)B#aj)8{ zn&hN^AS_?~hT<>T)zl3vbfyW}Q?o9??+wo&5ZXq1Q9K4hoj+1+!Ni-n8`us$dj0>s z8Lm~o+1o{<;KP^S0)bWd?cx=0&wXN(_Kt+n(`o>=V4};}4Xk*Q2{CM;dW!DO+*x|I zzz<&ktt}8(h2Jh7r$2CCskN;iGz-@OY{A60`g!aSA0dA>Q`^Y+rYo;`*$=W8G!Y1_ z!tW!G{fPQl+CL^9n)VB)c+EVqbruUcYDgZgX+Wy#XR!djj`Mw{`XoLz?=CxBo&e## z=@eTq;Wi?J>1!JiBTKb!H;y}08f_jAZg&!eHt>2qrg>k|q`s`@9S1dMFQnLli8Qk; zc7U&?Cmv9bs#@tU-`x}g`(sxL1XhVhwQkfmO3safYF<|+XZ||=)|&jOKEtasv8EGE z{?w9Lz*mtQ@l}9Lr`4-_X4zw!+9(L>@VYYCf{FYEYuE`sn@D}C5=Y$rrqN}QP<%|A zVgjogXy>p^zl_LRKXnW@1vbzTCaHY{dsda_@)Qi>?_OKwhUz1{#t@u>}*a$1h{YU-1z@E45E_O-g66lPAH* zBP#>~tF}MRW~F-!N%f!AjLfI0rNx>F;5A_j#THC#`ku{>Z#k|d zzV8?rbz(fMDA`Q01rsB0u4J)%OdYMK-t*9{+GK^vc<8@ymq1`uoyE)8w?~F#gQI%S zUDl6dTQ5gL_ikkrTQJdh?=nWO83Wu?}ombE)%OkO&xM0V|HdU8w@s1=T|1ruT$+iKg>^_p=I7qnd< zufYxvbQ{vqQxJ>~dLa;4 zg`=K$O$)k*TKa^8TB8cT6ZlHwCtsr(5U`Xc+ebkhuTh09n7~(^yZX+D((QeCCR%BU zKwuSqj(HyXRo3)*W(K)Xma7CKwuSq@_ALn{c)uM_k+P;SOvuvOo;bGfBDtYp9_N^ zD&Vm|V3qhrEg9HY?#REK$*n(9Y{3K`qw#O0fCGJu27mnxscypQt zJP3ttyuKQ?U;_89d<4LA8%CIngEtveAg~I5;rOojs<||$#dv5qDUf0dCWPKq)3Rkx zYBe?v+>TBb2&}?iI9}cHYC}rr#6iW?Oo}a-z`ZN?Y_HBHcE94_#QNm|fmQem$Kw-~ zjgse<2{1OVfMN?KaPP|JoLQYqT}xvjtJNNXz$*Mr~rAtSmMUX4}TC?_`?7M z3nIjM)aj2?Wm88N7%;&?Ag~Ji9C)^cHM8aNI~EXo&Pnj%U_$i!yedzV0}BkGaIuF# zU={WO@ex2-oU)PUFxzBUMXc<`vnvVKDeri&x)#6sKlWj!%MG_X%K#>KE)PH)c&=A74W#l zmm%u7#L03`X{hrwcsIJ5U;?Yk-Y#HXeC%_zr%Jp@vX?Cj6XE;R1{7N`ajt&`>&Ro( z?60as&Nn~##^?mNdGRyB1Xcz2%3!jI5&2T05{2O_8H{7x`|Rc;5<*m&-ZT76F?t`%OFNBM`q#Mnj@TQG5D#B5f$#F$LG zq!KOudM!sR83ToHz7b4dRY2%$_L#?!`4p){tf{tA>^uZgr!=J4f{8A}Qtf(fkBiA-TWTTIAZZEE=J zKEC#rU;?X*1IDw}W37p9xjLgSTQxzs7`T?Eo4zI3f(fxt?6Y*TvLh;;-YGdH5Q0j` zC^sPlRCWxQ>yts9m4Bx5u&^?f%{6nUi)KVseE}l z{4Por2&}>p#{5atHI*;0sj&CqHX$|}6S%MBnbO_*$(yW`K==M!fxs#p*UP^+pO?v# zkHta8(_I8xFoF9@Ui++Bq1?L1c%aS;1OlsYWG-J_>T^r}IxQ5EE%pd;$e6%=CEvH* z<-I(PkMz6SW(ovW;h0-~RF1kzRLdb?^uADt)5QetD|zJE>=sHvP(LW_kS-8dh2w1b zs{U>><)on}w3)g^h`_}J?kjmUC~JFVbqzNt>X9lCScM}`d8Lgl^wz9Yfxs#pbII2xzK1JUiVn~|?tO*)B~eweY}7()a_C20f^(5ll~5B8*9V-6!&@0X|VQcig(E39l0XWa<8AVwc;7=9I%RF3np+b8@|`F z^C+c!?@fB>+B|{4D)Bsme|RVpwls#(Y5WV#=N}oNR^<03Z4$1DWq+TsCb_-pku_QT z>pa|wG(M<~08DQ9D30Cgf!nC<6k9NXkCyL0ckHgrZKVUQM>YxsR!x37p1Jn6BHh=k zZG^=6D#mYr(E`^c6k9NXuQVTJ4D(f{->w1YJm(7pR^4%)z*0S|$fY@I8@7-Am1`|u zQN7BERIs2YLwI5|-$(l^Ep)2r=y8DpfmI>N6WDqyEAlK-ZQ~bduDppchm`Z5Xxya< zjPQ8TUKhw|GOb1rwjjW7+Eo zR^_EY^4R+VW75Q(#le)>DvK3b+1!w!32I5_}5^p ztrAzz0hZn<7YM9MdOMN1+_xYeb=5X{U2#%OwA;X|3YlUHCh*h4y@S17m6)wyVN;Tipklb;KKw#D17vtD`*@9FTscq=a z9jM&X)q>DdK@?jsAwE~_PY+a^_!&EcZf6@kDi zF(Tfki?x!dX$$?z?g;Vin844mMl;FER54l94$dUJ5D2Wov8sGb{g7u@KVkr1YKt+c zn85ENpQT=JrhF+i2Cst}!2g9+IOdkGa}L*2PAoD9mwIAsEhcb}!803G)>23j&&7IC zTZqQRDje&s(TwZwq;&MMfp1x1bbo_*mO0RzB;2eo?DT$dZVGGdZ%)2_P~Y0<71qkx zgicWGo=C9;?+wR$#(905eKv~q4?76mo+S`i^<~}^He!r9Y2QelZGVq2QSRwEz*Dm= zv?EMm-XZ3s#7dW7)xCR3Y%1S5?W9qC0NN%dN*_;Wc$dC{Vhbj4dwks9sg05s17P?w zOCYeSlS2yA;hu@gm1-MFtfjJXqBms4B~fg_gt#ky?E@XXsRfpC|lQ*6P6c&%2RxGyJ7@`uZ_ zvjqaH4sK3kxAXXVZGW{5_VS{9di@yK`f@tO7EHX@lg66tHXEMb1!EHOJ$3(89cB*ED%_QM>u>nJl;?-=T$IFN1PHyGMK>cCa;$|xV^HYy(ReG zy(th_g-2={&FbMzm9?I>Q2qObFe1Z5y)Kj4;wW=+;LpC)n!WUt-ixiFX~tK9z$)C& z^D2CkG)h|@*LQGdJ-`-B%$+%j74tr(U!L0UHaqrFzH4X;eRT8$0;|OD$L{F!a;-kx zFFHV9*tLa;VI^@ak@xK>eBUjv;_81`zPR27W=%8_2&}@pptx6UQ;xj8#1eE&#Qjm2 zSnzxz8#KtAl)g~g_*Q4W{4k0W6^_FGD6GPJv-k-4@K>_aE(w;-cc6I91LrKk>l8dr ze=Uy)XgU?5_jje(f(abS#YeBBETuLk$#D0)y+B|UUZ>z0FzuF>Cg&wVhxc9-TQDK^ z3_a^zDdoK)%x~o&5LkuRDfoCd&O?51ZVH&!=ti*x6SybhF_4x4GC4UJK1}Q+5LkuR zDR>VTu~I(b6$`@#bf?&Y3EV$wG~K>!mpg8XhNlCZ1p=$^I)z4)7IZ~koEijS$GcN( z!36H-`8>+|xxCOn09rnC5(uoq>lD25;>J44@2!KO=9_Lj{_5YA5lrB3JNHIWJ!MjK zf0#4hQ6R7iuT$_00zLGVZ9lrglgO?VTQGsgT0DL?kbBjV34DyR7YMAv>lA!dW~`%< zT;Bm!obsaBf(iU(&}ce1dMIYTSSxLZ4L>D-lK3nuVPhG(ao z-bWde*%Zna*b4+!;dKhWex5r>8LQNVl%}2(TQDKcimW2|`bW?Y`g^aPKwuSKr{Hli zJR@n&_@~t2H>KEu2|T;!8Bd}@l%__P=&)@z0)bU{oq|X2JPubTE|O_RphU3+6F4s~ zACd8lyZF!{EtojJD36`!ZbDXhtE)0g>JO9k-+Dn+WjleuDjZ?Xd$^2H`GCI{Y#Gu{ zh$P3viDh}Lg^vkI=%%)zxi(vFvDy`W6_^MFR^iBXepDl8%UgL4i05+*0b2xOc^>=K z&4kSP)5b)vrE-@Ej!^5hxj-~Vs?3$^Sll}!vVVf=VOd|YQf`~(493~UfGwDCZS)r# z(T>k1{MGXqRD4(t^y&$V9li;9qwr1}yfct{oqY;rla^g!?0^P2-E$!vUi9RnB6x9Y{3NHL&Ia}<5tVoVRm5tx0OI(72fm5^I6W# zkn5Z<24f3XVQ(KMa8572cj;lO9C}nAyoOPMz$%>CjPK608%k5ZMSx4mZi*ueamF+p zvBzT#4%ySAPLV(!9i-TT3A|&BU#m{<$guH|uzT-Ofxs#pvBz_yRLvxhjlv;3^eV*` zOyC`3yxOK)cj?xsP^j&GUm&mw$N2H6N$ZBC0rdl+aQj<|EttSN#&`^UT3%_@($P?J z(^rAODjZYBp$61#H0t-Vww1#AWNtZf*m>W}TiuU=`jG!E?PF=_)&X z^acl=c7QFI5cilI{5o2m-h_bfP-B6>D!e0t=T`5VDi4S)S2T(pb9w+lQ zOP;N50Vkq52?SQ*y(ipXl2-@Pi-yDDm2-sbYdF>&=Re~eT-679>s$a#{!k#SJ7WSz zvGeu8r0eu2gh5_|tpb5ncnzBGsG43vH&sM~-|+WBgb*fh+&j;uH)j!D+a?auBI{H9 zUs#1l&fJ%AEr>eoo(v6EbQH$an80!Gd~M=kQ`&Y#09rUAg~JWZ{U8P=EkMZH%x~76InuTLrmbfcRs$79+gI% zod~m9trQ5X!aE|k=gz2u+;l=T&-<~LVhbj4EFRz6M@Gt(ju9}u%RYg?D(rvYBbjl@ z^8Cmk_%ZCb;Ag-D-fPRhQKMGN%X0$3G;+T{U={YG@Z4>k3gk|MMndCG<$}Ki6L@d0 zTCwniyfty2x_Waxa0z3ub&nOtim1yJ_5L;qlEl+hJHRz1b-qX@V;~&tCn0(`IhGh zo-aQL1Xf`W0*~d?dLzG^+X?y%(*bP31m2gqgkc`fmPUppwSo{ST5h}ZVtWXIs&#}Ld*eSJ#MbN zbebugsNGp0unPMe_;|PDVfks{V91|&k+#;}!~DNmk{_L`rQ7>(g?TR ztn9lbIdMzPv#q_dDa_FIg`dS0(%jOGEPjd^S@NI;x%O!@s~BKT+7$nmCdTEnTZ!gm zm7ZElD2?ZnE!*G=_h%MKbn_OrZkPqhy!K5Bo>|EJFIy5`*G{T_SIE*nTas?G)yfV7 zXEcHG7rxMNURP;G(LQ#4kqtTLaYt%ly^kFoYeUNQ?nw4t``OJiHsn<4HBLzHn}FL| zUucw7OLE@0pG~T=A-?^tNbOq`vDz(dNgS`}C=!;g+K}0F7>wzhE?6+Jtz8jo-`bWu z30LcXbU9lO&iD=k$~FrGR^g-N5kk>Tpw$OozB@BT+B$g`oAuF(l#&42b_paZ30I3d?9DX z8fnJXLe`;zXa1^qFU6SeV$-i%k*cOIrPSPA?EX(HGP1u~p<+u$6Zn497rIT%6)c#* zN6Y)&-mM_G)u_ditj(p%c{{>zSDyZ;e()cZ%1L2feG;`IsU0G6xJCA=@)VZ z0;}+dgU7JEuTQUR4+krDlHz;`HWr)MR!cKd`(!PGcZTxH@1c9h+U#(s?s-wzGl~iK z{hQd%_GaYryITC&ZQHsh>3t#?Tt++=2&}^UM|lp2DYP`T`4|`*^@)D(vY9QZXGWAJ zwF%yxiD|x49UbLyecf2FfBK$c3nuXXQH|z)|69_pzCjRa^im+ON<6Bw(b00B&E28Z zyJmprnRs5Ce|$6B^~{u1+Nza%myQ@J-{02@`kiV5*n$Z>^XB=f?>fn!;s-)6o(CHf zScR_$Uso&8$mNMcVEZy{z!pqk-vIX^zbz>3@8J)!d2NBfDtz5Engv}q%EuIdDWT1T zqiWG9pYPN%C2!qolNFsdvwA~KNvH4XnV+zWk^O?Y!-sawg=>Y+3D2W>eYLHbvcvYS zVB*&tumuxh8>8B+k=OKhhi|p?1p=$Y`T1vW9XVEa)$DVxFZTTPJL1 z%2x~W((jv;TC0$KtFj=6R;YCv4m~#}BfiGKlu1PbfmO~Kygy!TPKNJMd+L-!L8aZA zL_?q7M<}*nB5_F}Yw^&6q?}jVcwc<9^lnTT-153A5Lji>YAZXK#@o24wo&=oQ!be> z77qH~qu7Fp^X+yp>6it%_(N^OM-G<{-1CQC#cu=xtM;$k%0BXSgOM-PHr`jZD9xBL z4GNex4GSn?!NY9HxieQJkFQ1S?pYh+e&UYQxI+n>I>MIxKBD&RXZ!Y*%%i74!!eC0 zwqRn{m?Bo^ybUQXQ0qr6`#F&q9iIjtGT#wQVAbc7#cVcjTmDl;X?C-HBxU3@ST?CfqNg``_(lhjpxp*W_1{Zoocv?U5B(IOmm=RJfO= ztg#|HdBsxh{jj@b#W_sZj}gG{}Z1bMH%9`X%hcRvXgf zn|dA{4YTEvZR4TmB~SV=tC-C@Y(o}T+>wl94=`t9OU}Q!@;^kC#TMBxavYSb>qPN? zVPbdM0anr3mbCa&@z$+dp}c)VG{jAH5(um+Nk6~}IMMMBvBdkFtY3c=?2gW%wzP;v zzq2OSEa*M zJ$ZF5d^dSS<4soDu}?CrTh^Fj3noULEMa{H*^&Xb)u&{naRa&b%S5PfvK9!e!q5>Lhpy}O>1Y0oC&9<1m>0?W(bJc4V>^F=qwMqo+y7 z`7jQ2=gt=htV#;r%aV+(Nx?w1jedbqa;pn5pj9)AVhbkl+pN)$$PD?-z6glP$`uH# z!abixvr6%%Q z_?c=O{jxTdYHCaZkFLuowqOFkH++>$`cXQ-cRYmi{pXm#s<<7y*sJDNWbGccjmQh5 z<&HX0P`q>t#THD6Z&Zzf*>cAjA)r-OA`n<5`T)vq?vNW!7zL|4Gm0&k5XU8Bf)C4~ zsebTo`$>VoD(rvYYbZ~p>CTWYtZrA8_4TJ$8r-5m-Pnc~IW-QC^G;O^v}z@P)Pw?$hVTHM{?OFD0v zCok>ye`hV$+|~X3PIAu4iR|no7J_>YAT7`Th(AH+H0;Cd1mx6w?S)>ACvZB8dLgvMbwP{V#1KjC&B`7*|H5%q>HQ-0aFK?LJJ=f&|Vq$yKHo ztI|%BdazZFn=}GdxAtu0UF5iA&`|YsM;Yy@rE_<7-`qgaf&|WmSuE+pd(m-?!&wEF zg&Kh>eCpCOk$oav^raiyv2wBYK9IoOHl$BKWEl-9-;EV3K3OABh3`i0)-%b<7I`&f zn{(ec(94CsEG%R4s~wz)dAw=H9=EDR(1HZ^yDXOc(_YcWVeQyZc10slg{4RCTz~Bv zEf^Zc_?iy{ElB7+GUL^5`cv-v5q7(*R<2N`Kiz{>kDJ4@bYV9>m7&-_PjEcU?b0vy z?)!g_4f>S0YE~}Pf#ozCYdw7=e$0`5>WKwOi}W{TeN`^-viasoJGS2Jr4gvYk&J8y zR~#{~t!covU%yY$PuXeKcAjrVUh*W%R|Cg}7Rxx-gXYA?by>6EHxw;M_#NBE!|UWF zS)ZtL6rEyMo0oPpWY**FH3C)om~&L~-Dag;HCc4G)C?_1jLEQtPcNT`RD7qtkH7M6 zH#b|Vv0=|LXauTC9@@yCHqK41xGQf|o*TL8wx+|_nCfQ;_G@v}i2YKTh9xr{dTAK5 zZg{5kkdeUgr)WUhHD(siahumFJv2Zrx{z#2L74}OlmRF-}W@yGRcG7*cHm*ei$LexU zcwe+xP_$)1u`@IRRX8fPSnloLWPYsPg3U~GRr@}$us8MZt1db825 zw`v5cuumj+T#UYBME=#6Wq-Uz>n$OH{xTV@zIhhu64Rees69s`P=&og>5cl3o32~d zpEc*hv|b+)`#)~yb93e=`!lK@SysOWG%9ca3-8%bBT$9CS~>e#Y5^TLrw?mzC{XLY zBC)`47vJDhfYh9#ddP#aZl-5C^7Fb-*@Sr>6fH>L+munop-XA0JiXYUdX+T-ReI}uykcvbE=yl_!W^RY zWRSp8DfbbcUYojK>CLjNovsn6!k(IpJwM`4H#x{XgvKt>dSpnTH(IW0G;-6ReLY#8 zN)Z}?D(rE}nqko~vf)rTD=$w1M+*|@jkZ`EgW8ZM2fHz!5oa|5RXCF(&l0+l$M&{n zXI5|EHEqTO3G_xwU*FdCwxPZqSmCM9Gy+vPXCceg_+sY5RUxcc#7AxB2MO#MSS(R; zjwRoaCag*&eKrGCIENt5&Wu`U4vMMCvRBjRSdh^B3`L^;H1j{Nz;@nn)8;==g>xZt z1?aba;;%FP>5ih5E}j?9!zKohBd=~4xBJC&*P{U>=TGS!-j~1&8QDmlN6MGcW!wj| z{oEXE;)1Mfy12k+2YM6o&4J`}xX5!=_9kac2U4l^Mcyi}H)(W6&9S_`R8EBbC@jjB z&u^SBevg-%=0_fVyJX zGFPwjXA$XRsUX@sTkrED)^6`)8pV!g6w?-#Vy<8A zYXqtmeT?OUD*2MNCsZ%|rN2ddc#w|;H*#jL^IqcOiZ>Z}Fbx^o>X zc!iI$XC=YyQ_1(SYkO+(ws0ZVB|bev3li=#P_!VC zZg2wsI4c{;o|wj$*ImTgiHE7}eJzbZ6+Q)dlE8(o!pl5Dqw)t+v>;J&NCK}Wzk*xu z)P3w787?Mf*hE)_71sz<=}$MPu$P!uzB+rjtQEzt$mSo<>$ML|9Hrv7BIDcJ28gGb zE3;M&t5CEc(X)Fz&s`yqH2c(Ew;U|X)etRLsLC00kC$(mjok23_i?vrWletx_`=OrIrtx(}=yqo|>Ol*QKoyp0xp#Eedg5b$7nVQ1qE>d1 zxMWG-mtSQgr4!RQHLiiU-NT7FhwB8Y@Jq8;rVpwi)?^K#n?`!FqPA#WV7({Vdp|un zSojjJAK^vD9(Ew(pGNa~eLTtTOX@qf9%~@>rm068z0SnYg2cgRS9#a>-lSf2Rr@SR z-9&^IaHG>={)+(B#?&$VesfP!;=D?u3JVcuW~8E)Ay< zBhHJQJE8g|CwAr&U&nr@ug@@i%2j@0a#phc50yrTHN{2X$?H_e^Kp^K%)1UXnx_MCt2}ImEGZCM2yM5 zj(Y9%(g;-HGnD5v6e%Ho)Z9 z->mdNZpbU99==GQ#0P5c90^;+Xnxj`g>3nx(x^~1hbZ{{8C|=?Un5Y3Wm-m!6TwEt0p z79@(?jOJyYTFHews;57dG!(0^xrj}bQd1;QRq5$f{$jEhDY{anaXX~3=x{!haC?@G zq6LY_OfkH=j|bWBsGjbj(IH~V%y(uVmns^8Di`Nio?*Wi2|A+EDB1T9DWgev?P0^&@6omB!VB z%|yo$vuK`lFEs*HdQIK!X&Z5{+|1$*lmDM*iDf#L#u~$RE99Gy+w6zhro1 zxNx0UhkU(ugrWtB#TRb!jG?|{=1=8&tsqAeT?V<>YS%I~0#&<9#`41ryvYGa)eh#& z)<=B4+sk&Y?IwyAB;w>qcwsJIvh%u11*R<9EiI(+l@^N|Ovr47X zDCu8Er1Q=y?tI^%5vbBzwa;y8i0sP(#EwS&wKfU~^cq<#O|mdCK2Lt}*)^?3pbGt3 zGCKNNIdS22VbSQ^7|r8_1p3RQXQF-!F|1t%F?V!Daxyf57e3)nyk&G#k9-OI%6xzF zqSqy3{jj^7Qa^IWRmJ<j|fYUZQW) zAdNtk?&}L^Qd7iz_ZL~6qckrd5`$jE^CrFg$f=fo{nF+k)M}Ja!z9O8~_7xAaEHew%I8Vk*i|47A`IB5LZy2QyB=BcN z0*J$(mkhj;#nSIyU(vhmGILDJy;>SbESEmyU4;Tj^$jYGTF$*ij+0x>dcK=90#%qp zx&A!MAki^rBYMvzx8{dCDH8a|fNZ4Hy-UVo@L$W=k1~VB)tZFHxaQP6+eqvdlWcVTf_?Y8F`GHV2?cCU%&WiR=Y1N+o{T#XqfUfgyxtEYNJ(1OH)a|wK0 z_W+XVph}}znIU5F#cF1=f*&;kRaio0#P8}MqEtdPGyD5%TG>Tn*jZVQJIiu>K&3HY z(;(4nLb#c0m0crHh2>bCALSu>wXV!!U(MD0?dX+9PrAi&X|b=UIEk?#RVP!lAc3Aq zxo_?GJR)|T+~=;^Y>hxw?E5?X^nn0U-{ro%k3aq{EXGF_W@)@8P_!VS`xDolD=Quz z31sQs&C&=|JvZ+16Eozzfs;xjFrtE}%Glx*PSR@kkIR^24(w*0cTd2KQpJ(2vkL0zssXm_>m3`RT||jy+rzo z+s#sQ?h~{ip|{SH3Um>lO2(KDjW1{fs<8hccY;3JMWp^K+MM`iD?tkqdY_@k-A>}8 z*EMrt&3PJuD!pG);9VZ>3sU2qf5zDnv5fX+> z<7jUW^0~fB<5E~>u~IBH>%GwlRN<&kj)YHyiB2Uan#*VI(?)kloU0teYaaF>y+^4u zvIce)Gus$uk)AebHR&vhCLhRH2_qj=ZLJ5@iQ3 zr8%mtrf5L|+hFOfZPQIyZ0)E^#8!<_Pu-tcWR39;; z)jiUn;A)LP75bUv9OUo;!n$z_c_pS&v><_Pusl(x_W%*JZ~39%Npmy;Rp@83SZI#H zBK?#Hyj`K86fH<#8*H&0^BX8?B;2!gw~WyURH2_quJj&0NHiSbY^L8GLeYW*w!w1U z-K>6MUfOo1)8jT8fhzPf$z4^}^bAWdgkia(BVhNoWCi-5uVqUoGq7kSijG79`N;AbsJl>xzBly+kFS zks5(2^fSr5ym!|W)hhanQW;7Rv>>7TeeRxSqT#@NqNV$3EtU&adNkDoOL_4zCj>&Y;!NeD!53*;z}qY5@-_iq!VpqUxjkWbn{v?z`7Y z7UxT^#g1W2nH)!j78j>77h{3vDpAiK(fs@+SCaX;BU#ffn%BDMN-kKO$e^!wzQ)as ze7UdoJ#V?GjredeLGBOViQdX@=Q$GGNKjWt;#Jkoonzfd+Io(pPft4^Ki`c!o~no? zYnzG}-<{a0>=TT7x9q$ybtA*V9f?iOA`UC*M#?vFBs+3N^Zgm!Nbo>KY-|=HKE6)F ziq#x%pbF`wx9$8Tb0fKHCg!T|U=iJDAkFt;k`da$&YL`TBkARd0S|lG`GYHNWXqCF zWb_#M_pNTkeo>ty(D2|;(W`Vl8arU3fhwd6bg}al@=AWA6;c0;i#T38JG0iv$ohYc z;x6so2y5;{x<9w`3Wr_E;3ZDv^LjgPz0Q@qyQ=ozjZI%#?A!X2KA-l5_E;IkqaEEz zm1sv2(l3fvw7Qd54;@MUYEit*X?OCxxw;Sk%MZ<`QCXSahP-T(HHt5o?@1C$XCyec ziF2MZwsv?<@p|`5I-s^MYhFK!&#CM|uH?%^zP*d&8J1be>Fb$Di35?m$~G%``%K+O z)prF%mk&{N$%_EieU+V`Z|_O|+L?jWx)a4$UH2f9du1d(GPkq7dXOE%RY`nTt(C}s zb(XPcds-}WG_(q$k+L!-ItZVwXEF#}m> zMDw5W?+L@y*)@Gihl$Fi=W$yC3gep%-JJB>iq!}qe}Kev)u z&lPdzMm~`x%XRvfuRp`mhvir=iCe#A7cCb&r@eQ}C<`c~Na&^gVPo`K@|30y%cYfeBruXk zdc1Dt5su$t=!|MX8i6XkBz`DdKyBZ2j?Tobpbspym6fzBwF zQ6o@=Es;FOeQZ-%Q|G6-SEbY1C?v41v{=TsY$$FnY(uk8%AgUbTHQqUq87-nwvPI0 z!_CIxNzeeArC@4?79{jqbnb$B;_TTuwEO@EjX+h*@hHB~(StlrqrRvLa~p_~i;Jh6fH=MUv1~dWDhx@o+A2{3lJT86l4o$+9_JxeWJPd zDOb{@ixWBG5zSAWa3yPcDx&C@ydolpl`Y)xkz&sh`-zygT%pjqn0RpCk*$h~YHd0Gb7hw6ij^g{$vq1gh|f$g=yMh}P#F*v!sx+OtAp%Bd*cB#k>+dO$thqn&by zA7)N=u12hO=XkgJef(J9FB%-k!=_cybA?2VLo|;$>Pk9~QO_z(sX(zlTOf;_^Fq51 zRN*s}zSrX3!mm+o7C!rp_H>b$_sPyr+gwTPER}{qvIvh7xmaw6FB*X=?Dfm_2Jf9j z&YE)d{j(s}cSj_5&+Se^$~loLT_X9p5ANhngd-V#Ba-jC>rRS|RnKZh{+s3i! zh~6c{oNZrdS|cq(3ldoJ<;Y8(Y<;_~0}F4FK_gJLylNC*k=31y_@UC6Rwj?Q@9WGK zTuj5zf`neKa@6$`<{2x?5}8ROP!+r*iWhI|M(U4O&#G;27t!Li536;|m7xU*eFXV7 z#3Jr5_F?%}251DTd`H>&`US2e?3GF*>gp)ba6^^Do}FCCPglYw1Yh|Bm8o7P^y8&gu>Jh-oUO`kkeL4ksvD zkjS$(ir@OvojB!H#9!^3iHXN-wDaajjX>43Em6GTM_CfDs$4B|>>xg0KSVFIUQAE9 z+j+MF?xbQ)M}j%@dmhEdjdv%v-YVjAWLpuGAmc1sZKh~J0&^?RyE_#szO~*$%LVV% z2vkkG7{yE6b0@y0O2a)QMDPXMsms@s6fGK|-ACPgA)@5`bu{C5yGG#M7C0HjKUK1l z!0{@LtujHVrz3f8xAWyy-AL`p>gnF@ zTu-bC@nG|QywNO395$uzq>dXYzD^Mx?>7@ZThg(i2OTM13sr_330IxwMy~c!gx#y9 zxVz~Y9d&rT=8ZxR)Eg%|4}a-K?v7JLDN$JTX;GB*zdnSbmupV>Xx=r-mDnr%x5uku zmSUoFM1D55)J%%LFeLh2u=5>OH*(2GeS?3cVIptIY;16NKaD`u{>^so)X0svnkrXM zvs4f{%KNb3TGJ?6kmx?t&Y!n(Bl%^2MaHn4t|JEAa$;W!4A2Nv;Zu-3vWPlj$BhiE zNyv1H79{eQwe!jA-AKq$l}4)ZjYZR$U+Hr185)5q{pn6yR#`CbT&&Wh2}WGCXujyZ zD~XitT|oP2{^xyHa(cR>R(j-q`Xi~>@i9Mh=`+c|a)pHQSssseCHEJqT(#X-LA*$p zmyK&vPrDYXu#8zO4ce6zY+n%;Tx6z*H zs)5nGfh0ObD&ke{w!%{MDJ`9^5=CDqmREf0@_d}EEyPBr)U06tBHGhM0!zM(j!xG| z#FWd#=FO;}5van_BS%G@Ym3X_S=iJaep)F(LVs49&Q}rl;{4g>IJtuelu=aSS0HDR zpOhC)_4Bize>!TV9SQwexyaKt|1MsPt*??@BT$9jXu0o4jW)twqa}UY=`lrr(z@(+ zek#&R%3RJ!aP%VgPPi5#`rjWcM-vYyT99y(HFbljR&uwHs^L1wxru$5maweM22 zAc3{EjA+bKUxa@W^z7A#8i6W(RCHxSeX-pwbvGt+QiW*r*3Ej zs+Mhz;#r!>_Pn3^K8DDZlc#)R>8`)eQM4d|Ewzk*c+pTioOqAkxOqq;P^H&Cjc+y= zYeVDc)r%V`T9CkYSB_Z5v=ZSDu2avni!=gNILl$NOxPDH27Wq6=WUbcrNaCN64*14 zCpB$uFP`SJ(=KF)MxY973|S{msw5US$t^-VY&LMdW`2ukK4p&d>1Rl<&F{#V)Ctwa z`+9-mQmf4d&io+px=}QzGpwYxhng#DRqKMk}XQ95rlKitDgCU;jvgUYSMmkw#g=fXJ&5~wLkiaJ* z_ilULUK9y@YFhF|X#}dq1V(c)(@L6UR`Uim&vX#h)KAQg+1C-YAc4CNW z%4}NkZ;e1zi^q1kcF9WihpRMP(svTGM%^*TeO_v~yt4Ce6|JP$t@Px{X*=(k!%FfO z%|PB=v2)*QRuW%N5jo0t7q?FRZJzGG+&~KwUsuTa!8BI#_XI^mAL%8A%-C&iKkTDj z3srw_wewhCD_Oo>5r_Qyh;gU4m>r!K8fZb{-9kIx{?47uTBnHlUIWCFO>@lwEwd0L zP!%`D&fmOnC*z#dsL12x0P*tH4AX7$90OGiCfIo|yF01>A_LKhp)zLMc}^#D^wv2B zT9BA4=OZVraVLFisWhJL8z#>GC}l2hZq=@Zs=wu2>S*Ck0=p<;{kY*`;mAB@S^wz< zT9Bw8F1=C9-AUReiskCAi-MM`PlyM zU#z5b5A{Wr z327-;W?Dp*A%!Sfkif55zQJ*!;?ti`Oj4qV$po!ZYwELNR`CoC(0cs_ermHlve(5DH-C1Y$AK*mMf`tB^*F4%^w3Lf8 zHg^rs2vpUPW3{ItRzjbuG`61}AV&2XW)?1&k)j0&mqRippuClwJFkdQenUjl55>$X z&wVrkRYhmp`LY65@~*lnSKMc)@CYqv`c_Rx(Sk%)*!*FbDAVMmt#^W# zMxg3(H#_(KB>g^X6+z?V>VdTTZTIYHC|Z#CDZkoI*WF3U35wWRYJ}MPYC12m&Ql{$ zRjIz64?X5i!oDct+~X1A!OCw(4wKXrEl6x?Vdo8{XJW}sMQn^1Ax`C}No=mEGy+xq zYTJ44-tMG83DtYO*CA9)y7Srm5WUL477}Z1tmoyKdO{-f9|x+E;OH@1qrN=LX>0Feg(E&mw3+ zLihEZvUC*XHf%O?JFKS|dyKKpu6O0W2K7Bi*mhM@&o}-M8w&0)tGru8(SpQ-OL9kt z93EstVpOqbtuCVd-lgW-g$pzSRX3+fA5eY|QX{c{bz*E+@wUQBvvbrGiWVeZkC%OF ziw6lw?7fbi8ZH{N7-+Jqb2I`~FUrZ8A4vrCP<5i?y`JLX)L~|cE)ywQkhmp@&9aSp zSw|6bcJvVs!-LInt!HWks>;2wbH|HT()O$(D*5&ke0~}8xiOBS1&R5xPhD}Fm0a7R zh>tt_i>ov4+h%8*rV*&xE%#^Ww8l!tMxZLPj-AIBx00DR6p_09U=e#f#t2(BkfH?%5^CoyJgsD}P{hZ^ z1I34Q0(QQ0r8~LNT@g1r4i+;VTA@{u2ok9JAZG!FeQ_i6V-(T5%3yJLKv#Nt=`Mm6Brsx6&JX4pAXXKhMK@fYt`Vrp zFhch9ceoMf#OR$*WPpghGKa2Qk%^!M2|aeO&z8O-JZ>#*y=j7h1giWN*m;S$ZshfA zbszDaI*Nq5xy-ehZctp6fU6*?$3@H2**r*#r>cf4)iF%0*j>`huppYE1&N*aqItEE z9^`VQA}W=YeNorc=8O9=8iA??gJrDRI1l1jQ+?-s%6Ao&*E^ewHlLzsLE^;3Xg;-> z2T5O05hLWjY7VuR*#3BMUL#O7At0LDn|P258x(Q=X?M}{;Wk^uyJHkBNX(Eurg&>HYm&BTzNdDtpM%!}7|iN}_{LxY)egjs85ho1z7Y=_TaozJZnSPbv+O zQNHs&i`<=l2(bePxQhr zqDjyo>bzvTMxaW@tny0d-AVg(Dvi-&dx$CJ!)fTJWfUz)JeGI9Yo9y0H%Sq_{d$P5 zKPJ%W3+HGAs+K$2`KCVZ5yJxT-U|)Vt7@G79?n8JFhKchbuf+Y4q&ZLlm`d zrv(}n*9cTim230ycAn`WB&Q}j~Bm2uLV(^W2;&{b3 zwEFF-8iA^MxBiV6mpeMRcNF$W8Qu1G27(qO686}6k*+c_JG)9FZ@qTHdG!aHdgyp9 z_8e7uBza8BKSbw_ulzDwvnO*3GAcF^*E1uh|yPq%zoZGH3C&wKg!vqMLor| zwfRlI^Xp|y+`lz464*zTtIv-05@)(c+Co2X(Fjyw{V2UrWBQ2r<*~MnpH@?}Ac1{U zIl7zQM-&RkWlNiPqeh?#>qogWMe}~*Q^(@Anmt!gv><_fR2lEnysx-lV6)M3^LmXy z71oay%X8=cA~^S2BVC!L6fH<#A64$}^P`XG(0miQv|x=!pbG0pIbXY^pV;zl3#rg& z5k(6U*hiHoLJ#XLs?6}9L)=zr1gfxpl>V!SeZ*UTZ(5|r0*V$Su#YNt#&hT`MsBM{ zhn}6M5vaoYQSMcoyPudmfYOVRqbXXDz&@&sNLk!hME7e?bKL8p5vaoYQLb={>@RBd z4W%yzSEpz}0(+bm%k>=nM9~%FY2mviGy+vvKgw06ZTgFDe@~>}vba#RAc1{U`3=_V zBSI>!qF0uFB1oVL>qj|n5Y|WJkZbk-thSS&1qtkN%5xN_^bpy$9i&-6n>QS^Hfqq{ZInbexSP(JVd~zXF zBT$9oXgNzZv#&^N8Dl=)S(Bm#3H1BQ)dL3yh($Handi2)(g;-HI9i@i@pPbg`mv1J z&aWy(3liw}mFK>igGJL(_iSsPH`NGK;W%2(K|UTL%0yhZi5C?pT981$uUuK&VW?P? z&BwOuuZ9|dDjY{!ERXvR6Ye+C*jRf)(Sii}eJz&vaz}@lKRrp4QS~$eRXC28-j9C6 zL~M9TGUG})iWVf$?`yI6O&==w+SBA&>arSvDjY}4np*C1lXJC6V*hfdXh8zKZE{q! zWtg~KG864S=Q}|HRXC28r`N3*F1(gI(sup!5VRnnd+wfo94ZRsB=ps%85)5q97jt( zb(`VhNBz9i`-vk#3lbO=C|94k4;Po?iqX-L6ScK{sM1&J)%{(bTEe#|vN>}b^o#v)l<(3DlKdGojph}PBEJNeXrqqMg zaWBHqf&|9(%6-)?{xH9Jd9h4;gERtF7

      3ESl*kDrdE_*46y92va05u2;@xbjvEX zj(1^>wcRxWRTx1l&lw$?O?Vg2!1|tY*CJ(+&|`!> z(>!s>mEGJ`f?*8xi<*)ARbF>8spWsiQ#;4sG|yCXW8URTXffMJyzr0YXM4#Q*g`6< zZ^6hn=9W1wEJIu&od6X^e9MvWoxA4ASXZ{SadCzgyl(#|=lM||EBUfpjaV+Feqol& z=E~;0EUXcz8dx%tho85SkBKA54EwK{v%6VYss6O8L!CuiKPDvgg{ubY>M z2P@UCm`0$g#mDpf;3F$p@1TgO#|w+g>7UVpIo-6FZF~p%8m!Bw@(BN+&vef{D?JtM+)8XG}zEB^HKozdRldDoPdx{6XY1su!AVUih_|#=<5a%Q=HA>H>49lev zsKQly(g%v%G{Tu_TcBq}!$usKRJd83$0dgjkZpkHz|!6fH>LN*lT3 z`+O##l&j_sxaP9?s;~YiX)F-(DoVMX>ol>;HnGR_c>fqG>wd-4}yMZ z1gdatmYkz6Y>37F*XUe_^b9RX;JOewi!7s~Z~OjDPx)og2vp&UF?r7DXd6z$PQQV2zNqY`<*4D%!fh%Wa)MVM} zV$jItv{i2>jX)Ky`ICDDt%Ss zrnJ?BdyW3|a{VmY8bu`ZwfZ$n))F;GRi?E{cxnWya239cdg@j^uV$!8i6W|#+LEaPyP_DN9)ixE|C;1NZ`DPJS*O@ohW&7G+nv;qDG(! zqp{`KphO38aPDYYu+>?L79?<9MEcv0hl;R5^QhCfGa7*^T-hVN=cE1*LyolVJ z>PBlZXWCa|5qAFplaletfbCmc^2LVb^ajc3N1PJWF?En-r%41z5O3^g~Xe9 zFH$-omM``C{$FWeu27}F5B0A9`EN9wtvCZ?-6pXYWbcQ z6MrYE)&EB``B!C4B&1qViNEDlh`d_j@01BtrJM#@kZAqFiO7G+q=5vg@ct6t2b1rF zsr<>3uAaS3mAItes^oioy<~*G^t7Fmr#|Y0+(pcgCsW$g$&``B?-}K%`PuHt6DyPG zUu8GhG?0*`UX^~ED*1XEcr8@PZ^n?{PGW9#0`n`+wKU|pmNs>+C00#))P0Yjd=X;UX}>I7N>9c~(r-e$GUmS=Th+B$(2Bmy4YHXele+WIG+ zovGela&Hh-_@3nc?N@z8$*i>#Yq-g_^~T_Vxoz|Aq#~XLRvE<_=d?vSru+3=>MkRf8HRbffgioJ?6$bUc`2D|9_`}1giRW zwHbdtFJfD|>c0uh71Bxf^!t6F1&QL7_8HgC7qlI-UHPv&M*>yy>}BIb`+~O9E^7aF zymPeFslg-Nvl#1#CzDROh~88c3jO`+%LsxcB*OyNNo> z6bZES%(K%NaW%i~jrHmOm@6bkZ{B7E#^&F8?+|4IXMg)00C^qP8g?dit){ACkMI~_2_ zI565s{GBCuw$ZQIKY!N=v>-9YWu8%vB}e=ixW;IDId|f9u^eM=^)xV7OGZyNrf)3s zTMl&sbArU^*W-mSaM*Uv2kySM2otoum-`2zaM4VVZ^!o z^LITBv>=gt=Sm}HPpM?mKmt`KzOOKLeoc)(6iRc7c`d9}Ve$R^~-Ys59C(wd~n`3`tar&akJS!wn^=Nx9qsrid$q;Bk;&Mno z}pPDsR)i#?15il1T$CNT}zws!aa>gFw~d zV*`v5pYkL_palu_X5IVb{XYm)c{d$uxYqmU``6z&T98m>EUCswnLt&lSEG#0aXFL8 z6l4ws#C$^43~%;$q;BkLVcUd8YY)3Bv92)&a*B$7?eyJXhA~Nc7;bI zmn$StRcOOhBf=-SG|+;Cs*kgL{l5rQwTPH$jI?J@=04DZglbo6*po{G2~;)QG1tf! zms}cXL1J3K{1om32~_3TxX}2cbaJ^u3lj4lFG}HkAc3lO{g)bRA10Ruww$W?&1T|^2s0}`lO_s515>MP7I-p8TOD~zD~$(2O3AhBievJ}1#Bv6%dp8+jM zs8%%j?;HtK;ZxV2E@y0bT?ADl(bE6^U)~rrkmkADA?9J=*|ClA4q(A*3C#YCfK&>yBdGsv%))1`mM&b z8J6`lg2orNP28nCcSzv1&YtUP6xmSP##=x7A9IC7-?m+iiv!Bo7R^*+HB2KZCu%f` zDtxm#f%z@y5pJ~TR?If`@X!A-S4d>Fh8rDv6tg++RimPma)l~ZoEN`9L>>D$!r19OFR%J+d5B(iqv!Y@`WXNyeq8ep!FK-J5WU3kw$W&h(f zKmsj~UApr3nabKOORoW5Nxu)YAh9O2E1%o1%zwNFm$T`BnyBwhCB2W9V`CwWz5FPwu9h$s1g^jt{~%P$KOvVYB!_Y@(4 zD(NZW$$N@0zv>M_fA@cQA4sUull%x0pB1WPZ;&hR@IQ6?zxO_xp#=$5rc>-${<;>b zWUrQ|*hBthK|=OqdGaGjycVit@0=$;nm`K@vPaI7A3-94Dmjwj$&ZSpr{LGOCP(zY zzFKUF{(ZJ;b_uVAX~+>7PjPhj%YuX)h4JJ^sdz0^$&n>bag_SYf`lr^DUMQq5vY=5 zYM$a~`rnGA9yWP$&o%!(QEL_f`t11lYi%UEmTR51y9lY@ymjQ^irfycJW%M zlD-Xj7 ze;;@)R7oEoPtiO0%YuaZHj{4+@LH&no=Kjfm-Cke3F(bYp^d_8p$dB+`kkW%3F%e+ z)rzJ}pep6s2Q5gb^pbDSkw6vJe0r|19#roA5&23n9% zUssAVCck+3YNMPD26R5(zgifFZiIndn zDOYNo*`v=|etCW_+gv${Px||>8Qx!ajus>uc>c*3w9b<_j@EO91ghqH|H&`6$@8DF zGd^9k^lY$&XaAPh79{-|c%_unKw`%1ZM;BSK3gB@2}zkiRrA%`c-h`~xHZ7Ve@y_vDsM4R+zxC*7rXs15VxUwcRZ?t}ilj=4nfh0+`n&3{ zNpV(6ofLniuA;8?`}hM1RHd8-T98nYRLMtEA%QBqzr^>UVsV7JBUPf+^HQZR>9;DC zZDk~t``1hSJVsL`5@=B|OEMCPtGJ~kT8pOoEe#}mWX#fpYH_?d#x4Cupi0Fo$p|H` z#VsWgD!xmd7O7&qRD73=+T!Gw@dGtilmWoGh9W}sIj@KlmGcXFb%XI zu|`JNRN1hJkCOf}Jq@&|NE#U{!&Nj5UP&j=f`p1Kn_^qf=gRo9lnGQNT}id`I&ob_ zWtFV7kMEW~)+Cj>TYPRhffgi`?@IMRet%X-pep6}fw@vqU^3>5t4J_RPtO%vkeDQ+ z!|K)A!}m*HZ^{I!R79AJ`QraXh2c9#%S0Ikwr{{rzEb*hG3}JoKte@_h3DDHU&{!w zlnGQ}2~}T3(to3w8c{2cgnI7EYooj@>bLUwD1XgA?;}aCS_3s6Q(mt`m5dHi-aGXh z-_5^zMJP|58p$h_^3&DUs#D&<8}UN3dslnJyTq5OQxFZX+{kU&++PZupnsIj^7FaDke z5~#vA`|o|LH>iBLN$**CgO!h0T^FyU6KFv~jZl-Wlrn)T<*8SG^55?REl4QOc~S}0 z(?9}Ms>CG!tk9y$Skha=E2W$U5^5BjRAN#lP^D%W)NI4=caC3_@`Z?N*@{+~FJ|9=8iswGlB%-;#LAfdd$%9H#5Cs3u@E9F`Joj?l`D%wK% ze*gajs#JTG{C%JW39KviH;4qPR125<`#=j4*mIJ*%F9S9HS4ZYQ_&hKYD0~qR3w#* zkK!ttN=1sOsEdC_kVv2f2^C2tBa!$&eo-XwZj*kiF-JBT9h7ldPd+sz4xboH|(f_;;B+!Dy&(XoQ@6WpNO^Kd6BrtUq>mwt0xQh3|E9uV) zEl8+X9~sTV|B3g(G>||Q-k+WZ=C`nni;~e!{FwA7;+1p)El8-iC>i<0|A~!CDOafS zkr8j7pLF5FrTjYYmz|xa4fhsJ=I)N4>^pf~^skf+hrx0sZ z_BzG0Uh!<%9mX|IEe7;ZI>*r^qrY$pR<@cFycKU4W zIFy;p^Zv}YX83GWzpIF09fQSizmjalleT2^&eXPHXPz0BX_?8RBk64JyAuqOGc$?f z>1==fnP4nzr-;cr~{fXhEV~w>VxW)RCM@?JNn~rYq)OM;uwJ17$S=Rk#bY$BWXEOd=JdbFej`%Hg zCfDvh=KEdKkdV}hub|%GYrn8kF6>qq1awa*w(%3vNKQ$=2cYbtBGDPxtNW3?fU~IJ&ZFd4?7wV!JrnMmCQ# zHl zjNKxbA`Z@tOy#)T@wI+L6HB)8roUJ>Hmg$7Esq9_G;qRL#5^$Ir;qDg#fd zXO(;UC-d!eUzYz_AVUihcqXshH)>p3@p?lx*4WKcBTzLr^EEzkwft%qs5H_>XB5ri zbFzEc92r`W&`+JF?Oa8k2YK1c>OUwFsKPU=<@r&QZklhM9N3DQMEeG@Cc>}FVo6sh z-aIugBeN|k&Cr5`{yti?{9qng?!wmeE2t5u>Xy4=^fct$bH&6ic0nMET|RkC~nA3iZ1`9M_~WfnMzHO_%7=woJv79{W)S}cP$ zc#0!?b27v8J4FIjC%Po?fW_%ZZby~In+JKto_4P6?T*F7W9jeky^{yr{?SkUVYO_Pv^p#=%Ig^o7s$vC6VaaG#yq{%B>;+`)ldEm-LA&wll)CeqM+3$E zBI#NBR_+>sDm_;p_6LZi4=n7WqYpz160O&{+T=HByt}H>$T8DbY@6|k_IMJg5val^ zB2Uf=DENRuy?R{Sg0f$)v1cs7s1v?@0U0p2^Kv_ z2{v=ia;?XLgx*FqE*UJI{46TH!5$Q^g{tod)7iSsPcSS?)jNOb6)d)VEzG7>E<@3R zgnl2BFBTWwn-^exmyXd0RQ1`J&h}_ff)Q~+rO}2J7XcmfvPoIzQM4d|&rPbN^DJ*S_NH(e&w>1qpeUuuZmw#y{r?SNeZky>(bs%@_B*RSZJmoI{C}3L<4< z&z@ysw_qm*2pAZsV1X@mCyHHwjmqp%Z(HG@V2cHIH}*T*=Y6hc&F?=i*Z0HhGked> znl)=?>euBDp4Nh|;}=T=R^fV66z`0>eB1CEFe^}@*n){Gd7{UN${}Un=sv@kx^?-h zqH3`Cj<-Z$6|OgNn@7{SeAMOuIG5atVhbiL#qY@ImqXkw^e?g5nmYVUv@eWqJV7F` z3V+jz(xJg0ZPL~P+Tk_@?5knF6#I6H;yhO2hbz6Kaf2F4ULPi~k1FnWZfeEX-~3H& zU8+e0R(+2v#r)nE5VvUkogav@=2_0A;KW`Zz!prjo=}w8KD>z7eb9+pF^;^`S{vBn zED! ziV3Wezuh+{EApwf?r{3qJBlrsIDf4u^V;bm(ke+W!ybHj(b-B+`^{yEz$)C*#8bWY zfmOK2P?W>>tMlByfly*y zqSP~BBGc-7X3mcyGNyuF#)jUtxy#}jptWu!5m<%$F-561vo`OsvKGJuN2!Oy1op4R z`uXc1J}R#^#QX1+dQq&x^F(pl+vy-qRt3S4qw5ti=Z;0;}Yw8qnLwm2!SCalu!L{c{|pz+R^4skb=r@HT!BcmIv#>0<)_ zK5>V_5@)U)tqOCVzLW^8lD*e=TRpgocOV2Gx!HvaghS zVx3;b{$JJj6303)u62EiEttSxzW5!*YVu{Z>Ojrv_7Z_rg{(01!v0cf`+t$5MZvZC zo#S<2^shB4wqQb@J1?&r#CMLU13!CGiNLDy7YZ{o(o3m(MAS&!G4iN7Z@k16PCdLp z`(3tUU90DiCLL{5=W}*Ud|RYjxQ!~$4bro!@xen}V19*MiY=HpbHL zT>|;rg-#HE{eeVa6`q%f`%<%OaZ{5@Fx_Xjai#-Ldh?sMo9ZR` z44A-kDsgu74qN`N%U9YnIzS?@O7@m2rCRb+6$)tQx%DL92NO6FrYOVwE%>%k`P8wI zDiK(PBW&XA=r^ymp({VqOc77SQ9vB6!=96(jI8laOO8;W&5(vtJP{K({vdpYmc@99 zCZ%E3v1$^5RoHV9w-1dk!Ji&42T?z&0JdNP#~*|Tu)Q2#`pN{Ob~{T1R$ORJh^%1;*n$ZhO%OBTP#50xx;r!^Uil zM_K@n?pPDrWhGE-!36HX#ci|}HTi}6wV>6VMiPNl*mDw5&h(l*AvOqZ^mU-vf(hJ% zi-_0l+C1_@5IA4hB}MzON{*xs_YC4uL+ikp;GQbBU_$QOYv(N1N+gVfRqjb-Mw)@m zjW?4&;x@|AO$L@T-%PGPv{GHJ8<=;LnOKQgrnphZyj_d=Ga3r2%_Ufc=~7D#Z0K?` z+4=F`J#kxi)5X6AL8#kS8aUFPiF(xuZ0(_N;)8*1TWDg(JaUL*xiac5p|b3o zLyGMyt%lz+vD~paWYfQUE!{WX%pZBOMsR{j_nwaVL6*55FW3cCjiT(X{g;W=}AndtpVl9KR z$PP<=CcJA+7+Jix5A-=&3^qQnXYc>ZAsYIzV+`KMhyOrjz>b z82D=ed*$69z7H*;lcw6UJVn&i=`!k_{q}6AnEfsuTt+=D{!*-n?re$I@0>KW^U$(B z_k;Z1Z)rqXd)8~9nea)L>ZVrqEMTvhJaD&EM~e4!HPK8Q>ghKxrll3*qZ)d_idYle z%QdoaV>YQU(pnwz(8zw?%_4D$*6OmUMn>OcktJsRcZ^(CjPG4mAKco1q}!v6>`3Qq z61~-0ooO_(9WmMD#&c^mwYZVpJey78Gjt-|?89?+xIyT}2NaL`*9-<$W0RTqcd${P zSR0tq7sBcI?UOY~ue*yaN>L#Zg>wqs|ydzT@>v z+J3d46nn+x$wcxf6OXcfM0<~|A;otw(WJeBO|!@*9k1%OJG-xezq@;lHXmD8BCrZS zt+-_@&7OB|?F_k1%0XFoBfD&$O-|U`sP_E~EIBoste#<`ej8w51wXRMjP80F-hTTv z*Y@3D%#MdNys3%3IFn5-%&=02SeaOdDcK}W+@#y}tC3aQlTE(cobzx3&34+QLTb ze2OiYs2XBqUv_1awqtc7Y|0ny#nmQoqgsK~KClY6O>yt*Z z-bb%jT8r{3bc+5Z5m;5~oROVrkxgp$)Sv3*#M_!%cyoxg{YtR~6S&?KWm5h}ZQt4e zaC&YBxW~agQT!|uQ>$kadQl&7hC~%=|Lv;_OM|TdTQJel&BSclXOmU`?yl(^lBc!U zpu&{Sr6mHZoJX6Oc}O;?ct|h9%KDtvr$I10ucH9AU?Q}ai9KAEO+eh}EN)%czDIkI z*&aR||4A`{Rm0wx*vv24WZfIR-_>S6$m~w~LHz086!+(NWcY38z(#G&As^lKzCGf4 zGp!Zt3}**e0q*rL*f=l`+Z?ieNg1`;3VXJ_s~Fqc>1EVzJXy0^(;7a^umfztM1%Sc ztiv5M3EiTXv3Esrw(?3ZNZ)QDjZt`9lAkJ|>U{R2S}5GCWDVGYi6`A1*v{ftN$o58 zs5YannQeCM3TtD_Nd#7P812Bs?GEHXo=(J^x8j`-n_%i-SE-%jajEYYBg-9@Me6R* zzr%aGqvNH zU7&W!ViJK>vX}9tS(tV^pcf=0eWcieiC0-B7F^LxnqAkw-FbJY*50=txa7T(2&}>$ zj<~sZw>6(T)B@UGtqNs2It$SMbX}Wk;SJ|Ky(9vwOz$1oF5$`k_^Oxj>5e@& zKM-^07BysF6#1XS=G(JzwX(>eaQ&UzW;^oc(;m^-QGpQO+JQB=kVVccwN$YR*Mf+C zd^d9I*q7A%R3KmrCS-qi=6P#wx>^i+WcW!0R^eI@cWs4RiaQia!h|$mz!pqcFcVul zK8qX_GZ{r$-do|V9vflqMQ@3~DqL^++TCC6q_rdLpI#ZT1rrPRn%J)+StR-2UD&w` zpJ_#HDnp$W9uk378}Hh)1`o2y_mTP=OgEp?a^wA=lWk?dZwi-pEm!pI({sp%_xc;$ z9d}V%9uok5B8G)6n2^i(vv7~radbVXx!zSGuuAUR=a%2AjUtWU;!`KU7EBB}CT0_^ zW^$vy{yWY(tk51WYYt9EqeNg89#<5lMaB}Ac&9hGJSqlwRKp_!9=pVedu|VyLxT`# z@k}1oFd>fy7x$FcLLPPoHomMh4q_D^;Y9R&N;9o}wKg!ikpo~0Cj7TLFmbmKIrKz- zAB$Rz)z18A0hRkXN(5HnIuzr_QjI3y_nFOblQJ+^Zv94lv_b9cDntR*GzD+Ze z^oRO*?o)g&RVR-J|5f&q1rsIS8QHSAX0q8vf9H>@_N0y_Cc&V=28qC`k=)3(k1&&v zaGjuYzR+#^`op>Y+to@-O)OK*A!n0HOSA2SXwjld<&gDn|JClA`}DTc5D12B6c4!~xn0yWaWpXJrBYq({b6KXQ_N(; zV!7TFWzdS_G_>aku$a7x;QGNtP$d(abjeKA8hRO-F&bSsA{w5}t{}YwtdgIq&WMLp zvl*{!P0bN^J)KyDQ6%$y6>rlV*gs6RaP-A1ql z6CQ0$%;J-oyv^3j2x|I=rhMrOjr&)TY8R{Un-zB)mbZfR`0kJ$vyWg4CR)b`pSnU0 zDH*MoanN9dqkdhWLs+UrVAaj3Cbrx+hkR?R6O(V|&|%ZV;A3Pc-BH<|wav>R%@@j% zn~Oh8Y>bveZb#|F_z(AKt;9i4%mU(WHTJrReMrtB zA^)DLqwskK%<2s>(YY$NU;@{O$gBypfpJwrps@LFiNGp3e)aW+5jID6hP1PODz;!k zuB%%!UE%K3HgNQ7I>7{1;nV%f}0#=X+Zc=;-fE*L)^>JvALEttS{C^CfdI?}@j#=(S>!4iR09rl^nov&un zcCTJWg;wFTpY<5H5ZjMp3np+KicxKHdz$}fG`vojArV-0NYrkzhB@RylwL;3as8?4 zFcKbpUrezD6Sxi)Wp$etv_tv9@L%jT+WNRXyWH$588x-EIyujtiF@_PyalCIrz!UA z@1qwNWlU^tW-oDy4+ePKKSRTWj!LH?6LnO0;__>ceSiW z4k?(Y6T?dmRv%3q4kZ#UQ*6ORW;c5_#Vv=7*`X7QGE}uit!Q{riAw}lz58xrP+%tA zp6kTekG~t1dKw9H9-O1tf{9iY?OBB@W-`@6ADzEW^UAClG6J4oKQ0ki6?4|a_HQ(k zW6gEq*{SZVLqrrLEIv)K1rtdxOsw<_GnqR;C;Fz&WpVK%Kz(sUBCzUdk~l{r%uEg? z>%?Y8Dt(b$5CBcJWq)8HIZb%ss^pQz0F`sTm}m6iys3jQK8 zXa#Xbteyx@=97_^SkW1V-b^6)+3|1cT-?CyYUPjBq@3TTDIx$aPIjALczm`BSfmQNT?cZCB&ra_HhsPukT#Eym8(7*cGYJT`R&jYE z54q$Q?X)%k8mvo{-UlYk!wszRAv2lju0PdQ?Ui=IF$@Bymy!M!R*f8QV8geWNr#3y z@#FGEt+RV1G>f!Su>})&JyJwDiKZ<~i3VVEq;*bAR7)_h=NrsqSSh^>$H4tsC+|`4 zCQ>G_N?zye=u(q=RI3H?51Lb)Rf=;`4~f;Rsz1%d;;CLnt7c*q8G?Y-u1K*36F6&D z#AMv6YvXFfL;t`sh14GTAu7SpWMpo&H|t(%#|4*%cv+TPcLwe)Y3fX3KLE4i51 z|J=a7id8^zRPW(7T$!Oww~vKk=gLY1R>`$H?z@#1wQ4dP_#{7-hqaMS5r21bd-(|! z#q(PV)4ZpGe~G08KM5uh#OYA|L(Qa5k>0n*dB(GdUQ^+3OM~=lv8r7UBm30FOg#U^ zMLjz<&CGp26+Ty3MzCsROCwtoBIbY}EmfJ=yJ_$bC z&zA_SlA{IfJ}lkWXA9x7V&lnAWCp0k+U)hbC>dQSweGEF59854*6P3*}cF_USf zmr?Gm1AX6V5(Flemk6xF{=A}`VgIRnm3XMo&q?z1F;Tk6$oOzGNlnqq$Qf}+t@bz` zezYnf5m*&+*T`;-6ur+(ofu;`n`Aef3{6`*P;9}3^(iBB>}V!-KXu}y%hN_XUrmN@ zWs6G$Ry`9diZgqN9^<}F%nF;q=A4U%hYw5?TQHG2%gDT_nH=b(_Y7NiY+yC(Oa|{& zibP;l^hhJC+gA9ZK{^ra;H+((F$qq*Gf-^7#Jtubw$#8(I;QBv^pZZBws;b33;d&E z0;@*WF|skO&7|`zoyZO!shwys9vq|WD7Ii?m6eelZ)zsdZ*?MR$~3KC);P%9`BTLN zR^@y*u&JU)J#$SbF4WnobwSAxpHywl-VxBp@4Jc# ztQyV?Y-_ZL6glez?Q&I{`*tYwTw0c53nr}R8`w^fmoa>lPLw`&PkZ%xFnmb(s$v4G zOw)xQv{KY=h)!Gz|D#e#`=d}Rm9_>`@e_+2vCf?L5&zJOT z2Oa;;k^C!6$bLz^2qW)P*a>_)?Ue|u!cQyaYN5sWedq(5oaRZt0~6T$5bNiWU$mf& z{bAXkeG-9HxDG{TW}T~A;@@!ib7#I(yO@y2TA%zg+M70!u+=GDBCra73&IN@o2OyF@|#9q6% z)=YmU!mgr&5`k5?ZHl@o_|7Vgo(y?s7fY=c6L{1X`<;j1Vg*T)A>qnliNGq{$B4*w z%U_uj8cc;{EtX2X4<_&!tSE1_IhiltOo1U^j!Fbp;oenIyzWM+&7V&JpRUVPY{3K` zwM9(-_yTo7=oGm8B10mu3Xc+E|Hn!rt)3naAM=-~*n$Zhtrx4|;7W(Rih~a2PDlh+ z$>ZR#y~F6|Z4=<_jg>04U;@X;MK*4)k@Uf-SeV?BO9WQo=$D8NzFkjWK8t~HmvvGk z4HG!xEp|JZlWFyDqoMoaGZKMSI2tLU=gp7Nt=*zw_Vx=>WD^s34M9YN7pKwcH=?0# zopKcaEv&-PNU=)hoJsdj7!I4)dQ)t{1dc$9`_HSU(c@Xe!PBF&L|_$;Mk>nU0~vHf z+%PC*HJoA#Cgizuc$1xU+st85)Nj5-V3i!@JQRP9Qs+V78!($<3nuVfT|~CGpQimC z27>x)sYGBE&I%QApJg`uSU?Nd?6{rMtp+x`zL~r_X{|omZD4iFo5|lh*6PDv239!H zOrk#NBaYoPBj;8ClN?hiwqW8>UjsYU*Gz_%)pNYYdARaTgB!rjoUJl}RHsY^R_U6^ zhjh^iZDV!*ePmTAUOHLY`-)X~7ppK-b$1Ay zYo^$O2|3$v<$)S}=6Zh!nlxXkD?BU4wV)`y7yI)=k88v9jIk73Fo9>t;uMc#p8Uvv z4I$vkJc+<6{4I!^foxrP|EkU4Ox76bonykHi-FbIEj&w2|E`K}vgPq*T0za%^CbeS z@E58mT^5w)Lt1wNy9eW>Zx<6SmK)ej;q}GM*UPxpqDV95hrrj#Gb945))WYj%+E|p ziCC71CpLMam7U!e66Ou1*n)|qn+6uw+)Q3}(23d8%vzVEfpF{6M2Wzv&3;B!-DoD^ z-a4_coTlxWI22+pgi~z6#4{Ho+ZbRbWvp}};NUJT(I)~b)DgSr(BHx;KFY}4t2+Tg$V)tagf+NQWs;PP@K#THE9T?HZr z5VDVT+BgQ{>#dRqtSTR6V(-N`=$@$0=s$U7W_r8C!tJ&*DYjrj-l33tdoRg&I39va z&z1Wrv=vrS5c6`0L|_%} zmBjfaO;&4j-wcEF7Hg&62NU?KRFvr7J2lJXq41{fVu`>i+*c|}-Ll6u-;V=f{n6D@ zFNz7=y2N@Ey`ueG-5*-~S||}%g+~dITU+~{_GC~msMT_nG#X$6_Y&f%27J_puI>gi z`>m7+tdhq;W8`=3MsP={v~-6ws$l~6V`6QhV+nq5d~0|sd~5u-unPNgVvor_5mk#D z2P?|Wqd10$zgHahQ|EYNIMuwqL|_$; z`-xo61I@HowZ}s@+tw6YFo8#Eu`A_lC#~AJ@!(mau0&uJj{Awa>OW6gH*7Q%e;rJ* z1rylg5Lp)Wmui3fMnki}Ac?>#9QPB^j~NHGO)0}6Kxsj-1rykF5)rSXncC-55wK@u zEs4M?9QRX{=dSr$`SgLX&(Mrw3ns7!s3?AmpJ_?O2f)&;H6#M7aNJLn(YXY-8Wal6 zJ(^H#!36eX#VVP#B_Hx%SBQL6O(L)g$Nd!L={hGKw!IbHj0TD=n7|&n$m^@(#^<&Q zh6^sP5`k56bkIG(zXmV3Sr1aHUzMVRScT8X5qTL0TzEyR z7qsPYA1RZ({%A+`WSE&;`%zjQS=W)>75j=xbl3ATj@NVGeO`W~Qy<8==U9carbWiD zXLEHnQ`nS)@xNeJ0#jv*Qyd=F`FpwERk1`$EKy z+!$MK)AJ*(r&N>ne_#UFh}iRUqAY*?*Am)KsU#6tg?FVX%7Z0#+;>|kIG9~Y+Q)(k zTqDAhschoYr&`1L*7D95tirq9M3l2)d0wkcariji9k2xx@@~M^N8EUyXBO~$hm%BL z6+W9xoNZWK?0v0ymoCbw33$KjuI(l^;rSI3E9M+HXJ4FzP{zc&_q#(aAJzhF!32I! z!bAR9j#oSIo<9CmO(L)g=jF>*f(+Dg|_pGH!P{Y-66bbx2LH zedGw(f(g7ANPN2mnc6x324IMGkO-{8Ir}0z;cL3qdUO-GJfa+63nuVhAmJfzS+DIA z`6XJEjYMFTyceML@fq6O>m6b5o08J*Gfd#UKw>5CKx3^|KnM)$BokOA?;e=2tDMHF z^a1MuKPk3g0`GlRlkcBHp)+^9aR0 zdWRWmMw@|fq2N8m7EIuMeqvwh!5L~q!eHnZRVWcyh4TnSR@j3zWPh75@E-JvVhbkl z4h%&Jtuu>+^d1VGYdw$%tipMOigL9aAgW*u%Q;IE^kn5_!_fl+eZcD7Ih%zZ*sQQ)xFlvu79>cV3qWtipMO;tYsezu0o~U~oBk zk75fZz$%=1C`PrYiCT&L-as;*Qf$El-chG01Lh=Yr@!?C&0HuESS4pPc4)O;JJ&7* zG}CKohcqVeu2#{vA4=Em73%^8u`eV7tK?n37uKKE>_4=Ei&cv#wqOG9wN;cJNw+jZ znWivJoI;BUtin5vMeOzabL~;v`Vi`03a|wec+aqii>7?m4t@-RWphhP1Xjs=s%yk4 z{6-yrNQ$rlY{3NHaVq9&ss+Ej!yg8AE+Y|Gg-haE>@$brSLR`7t!zFccDtGNsieOyGQR;rrN5qFdY}AUbuoL|~Pi zt^Pf`75y7K9O6R`N_zn?f%C=1DK{%ss)a{G|1n|(3+*ewDx4`VPVtB+OJDzphRBbp zQZ^MPaK5;4Hjsov%mWYA7eKt!3R^gbe*f$Ys)bib;q58@LQtTBIIA2^* zQoPz}JuM?3M>{4FScPND;78nri73u)OKw$XDEfmJxxFQVr+nD(`8DE$7ACB^hH zflsUuBTmChT9b?raO`?UBCratSqM)?y`|j@?*tEwSERKGOyE;0#GKRkREsI<0JB$~ zmI$oEu|-kFtB=~BzO7+$$R%lw1rzw38F7}kT`_*>Z7?i&by6a*N{(52JSxS18JobA zofjy!U;>{^BQiORw!BJ$3ihE~BCrat_KLG68`_KWuj;`$*YgxxFd_H5UDvwumdk6v z;11^`0;}+9uNcp(x$!?cszT-E_bIku0{8QxFKOz@=Qj3)&Q5P70;}-pHzNP)S_OWo zjx)qhE(O?v2|Rlhzuc!HzqHc;ZN`>qmFCspUhGUHl1|lIzaet$#>TNM87#(-2P1T+q3mMqs6VzM87w>xq~aa4UfoEaT>Iutj(zg zv;Q`PQg^CJ7EI{(Rf}7wiGF9bqP!Yg9U4Y7gvxJI8)3`;e-AIw?^-$>>BfdUFCahr z<_W?=sSee%8p4l5)1)sEe|`G>(c*?^@_+7-RvOQttLBb_@4wHeudBPWdPfV1#g05O zrlvd7#J|Uie-~fp#-`6NAl@7G_Te!niY6b8g^4fCDz;$a^)Po9cS-!Eqxw^gt<;+K zahnKtr+t+OtZIip21IbJU$Yp>@K`?l_^?DhgO z{=q$xwcVY~7XP1qUN6J#Xl|pjU*aLPg&V~dOtiIiXKZ%?*?w6sWB=hG_08K*?*#p zK_~Sx+6I-QVLT3k`@K`K1rxa5#A@I4y_8%V31*v9D(=Z}4~O5A$UHNyqqz@a;4vJN z-UlZ32fDNMhYLx|?fO%_kDE(>^&bbr8l8~{tioT9ILo`*Lt3lZ5I9sSMSUFU%Ic;+ zB9&^26a6o^F`vPOWKrV(_Pf{N7Cjv{45o~oFZ~Wobi3=udQ2)LKj!IARe0ZbfpdbzWT=KHg{!b@y(US}i8JjdWwNZwtuU z{`yl*Kj8{D>$HKeJUbQtEv%x{m2HiCL@wBg8c_xeaDpa{JHX40b}ClIFK}Z&Jqw9z zbRLn3g1>ffKcfo-Yu+lhVB*GdHx}hvNZyXrpQ=Sv8AvPF0}O8`N(5F(?@1~7Q-R)F z`#`_bk}>x+;+&wD(aG@xJ=J(1Y*?Hi5t0hMe{uGwI7zOS$m^?OpZ0(6 z2mg0kBp!G1E=sYNtc^dM{-wgj?H($&U_u_9Z>LrQi^I*~y1GsxunO;@6uF#TTw%@7 z*6=dsn2If!uo>XQw(*;!>U7-$Xf)IS{wF%Z$`WNMCa?moGz?C81~PeC!H3GiF;3-SaOwHWW-IqjGTwQ z{A;KJm8z7J{1WWdV2?v&8`@OjY`O&)`kMe-Fd_Rsbi6aaQN{>OF55{2R!uxmo+bXd zLDGlm_n*fdwBLc17Hg#OeLJzwC%Zs{PVBKjFSA)$I7t3tDQt()wMb0*$3e> z9vQ5c5mli`o0RMWQIqWfTQITUwiDa`I+t8Nqx*2J-apiirv|~p=H(;;t899gXU%8c zBoY1eGETN!sHJQM=;H1I_|%z>+niWNwLFq=+(MO4pqcKsMT;Mzf>XMabm|Z$-1a&# zm%u!dA-qg+9>B#bn)AJSu;@Pn;3vT<`Kc+!9i zt5!xLu&P?s^6bgMnz6wo~~s)=>(bIEC5?D5%I;DWxT#gI<(Y@oSBvR_|0GG z&6VW=`_b4V$M0WJ{tK(X9ajILWe>UowqQc`+oOH#_~et;@ba2WU=@Dpp&g75Nmj816Nx@9tY?ROGPIaJEApIc1E##Lu=>>piNGq{Ym2ps%@#0W zeGm9!P$;%wqGDGU<}x*(1XS0{@Ob@}9$8 z_?zIuK5Wk?*?sgfD*bno?(Q`dlmi1L0;}ZF;Pw)cCpu&}oQNMlu>})Lj<~Q+XGC4i z)yuf&y@)E0#d#Ti^CSYRj=DIrbG2`g$shF*=W{>|o!)08Shb%`u>}*RH!keW^?XwN zkX}aajykmDoDq;*BSj*x>Ubw-b|B~$Iclx}(=y(_TWck)U4 zUA>HeyGzwuZX@96pbUw?swcCZS#jT6WML(}409_^rU#6IHo55(TQFhSzXDr*EuSp> ztCw-Pvw=-oG8{TJzakM>RfRjVYj(HDyt;ZBEf=M-&AE}Vcfe_iEtqJtx&o`i^2vSo z&!UXbu?DUE`!F~Xoi7nsCHK39FPm$QVS}M<`>PaNFwrol0&BP~pV&0e%gD-!)3y!m z1%_p>Bm%2&pD*%cMz7K)+4X`|eex-`U?QueD@%*cCt7>GjDX|mT3gZq&dm8L5m<%C zE|DR$^`e&V-yXD4Pbs!w!mYk5`&lQSTr7%Oi2!vt1g&p@o7w=B|} z%8Rqr=e?%bf{B=+t}N@zJ<@xqUdBw@QvCRw>M%LFnB+5H74~pM+-H!1=d=uj8|U6p zY{5j^#jfmI>OGPoB03`X{Bn5?_uSx~T3qsdunK!>A`iKr7oX{00iO1FPq76PI0hs# zAUp&4k25xK{KpT8z$!T!wQx>de*KmuM7(-Ju>})2N~I`JyA^->*a;R6YeqW^^kmGf zfPDU)C&hiLH1=d8A`3|Ozj@-9+qgC5tG2qq(5Ag9w%|w+jv$HEzHKTWbk+-go@*`< zSoHxs*-KGI&wpivy{gMyBmJOkw>}hGFwrs5gZ-ZSm^irPi>Ipgt1=&_5pcNKn>Om{ z!Mv_MCik53Nm2z*R(MQAhs58NiB^>Y`2&l(P}9E!#THDcRXkbcodqOHxh~3>A6lF5 zc~%_`Hj)Xf!cQx1+uUlw|0ah(tZQRB;FJfu3x%ZHk30eoJ=g%(LNZ&_bUQx}W-y4j zk5T^}529@Nxx`Lj8{LFr3ns3=_h5O7h~oay-^aT-<#_Sr_HglG4~f7kTq9!T=cOaR z{H_&T>()%FD@<(q;K36A77+MXMu3$&e-zRTf?S$Q1XkgC6EVy4@3a>FeWBtiRr=-l zH;r84!9I^KB)z}rzk{aaYsF3tfKSn#DYjsu*f)3fxMcyEVx`yB*Z$d>bJ`Fn{I9-5 zVAZ!p9<0=aLb01eFXQ*XEN#b&Auv0oKE)PH1TXYpO(qtS`=529=I>+L+;SrC^-&v& zEts%7>CPUEDIi{d^{CpcGP|@xQ=%bxNG*xLDxXjfRx_oL1iseGDDAw2-B=bc&Y5tO zVtv*H?#xca#X8@R<9=dRbp8P=NQ{H{RW20A_b~CXf(J`GSx62&(#x23%%oi&G!Y)W zttk;$HDs1MTfMA+oOrMQj+?Djt+4(CxN7G`u>})T+&$P?UP$Ub*2}QoKT!KqZyZ#c zL?i;Ma4m?h{Y9)cGj%K+d*(;61rve9gH;xBIG^Ww8F%d#YWoZ^kW#vuL|~O%yWh1I zd}6Kxs8i!9j$q?RI__6Qj4T!S-pLi9_S4x?EF2R!sxJK98$o>E!m4nw*i4DQD%{72 zU5)Dkc@-WAr$ZM@y$>eNA9ZK9zC0uyZS|P`lh+lw^$l@PUPfB>3$6W{UXZ+LszhKFZe1dG@WKskwXL}SAS+jurF>b^5G+r^I9+CVD40{ zanUH~Gc#NwunM;uaTcpnsJ3uR478s%UTPnh2+DM0r%C+PQ~B zU=?ov;w+@L=UL@m6Ci7GnAFZO5i{M5m9T$ILeA)Agm=lwyyP7Ru}7Lq1XkhrzBr#D zJAovengmxDw5QmDiPphxY*+cmq|_e0jL~%usmnC31wurGr=-ynkt5(|(N8HtkBRIJ!h5~@hz#ni zmr)dSmCp7L2aB%PBm%4CICbx=c&($cIqdl1Bt^XNDa|+rBwAGY-da*@E7&FO4#yTu z;B%xElzBCrb2WW+WWe}lH7csFs%zZGB$Ch+YD!qZ<+OluCkVRuDE zBCrb2$V3}#y^1-AIZo3v7Jx07z;`x?xxvy(>}J|P@VNS3nyX_{~;BZrN1l0u^H;loS|Uz^NvJd6`moB9V2^RsJ7vQ;ry`&(o7f=I7?SiR>b?$ zz&GI#-s`kPU=^O}i#14(wzSOIA>gy=qBNt&1kOSexdsK(=ngd;%CFul5m<#I7UE2f z2CHb7?7?vN>Ru@_feD-^Co-_>rqPvhDBEZBp)v@@b}vaW zfmJxpB+hQj&!hFH4}~p(B`CIF0{28>ul|@Lw7wb%VJ!kB0;_PGN%-x3Q|N#iBcax! zDim8Vf%`{AX&0G5Tjq?0J!QH{1XkfVljyIadeZU^S8^{8=> ze{q6DU=@xtiM&3qT(#-5SeUsxT%6(d{~}wMz~hy8Dsu&O%H47Btk(jGz$zSP66XQ9 z*_VwAV4SsHBCra_nMAI^#;?p)8v~|Cizv2W0{ahQ zPh6Wu+OBU=khF4_L|_$;Gl_d;E=Ov`FGfM`jkOe8FoFFb5rJ&9Tw8c63>tMgBoSDJ z<4hu_$YQT{DSHr%*u8~f3ns8XC*q=>7qm7Xx`Ws1Oo_lM9A^?|x0QXM<$H)$8@!uh z3ns89EAHElE7Cr1Y7OeZ(-MJIIL;&@MXsg!t%@yyiQWB@1^K&@f33XhV&qPt4IoWB zD-l?Q<4j_OcY-T#A#R=a_>@ku1rvClAljgF72a`{54hbpClOfH2W35pRhbdhxmwx_ zPBh+6u>})&z9X`CPSxi>(;Of-ok;{%$+=N?sy5~&8X2Hu)IN$Wn2 z`)3}Zdp7v7xBCu~+=RDe)-yj=Hu4bpZ`f;+SvYFR_udKC|zU*QT zaiQLra#jtdf6u#L>>Y=%A5b znVv!V{PJZ3zivqozLqC zCa`Ku4S&|gc0W1Y=eZzGKJU)cgDv?|aViV8VB*|;e>Uss0kYz}o^x02L1#W`o{?`~ z7f&#ORUgy**_z%5$f|`pv2b^1zWjla*Vt}B8aoBDJB~-lhGBVR?8g9BXY1jAId^pj z2e9!qMO!JZf4kkq@7TA_$cOcrMDX9jWvr|lz~&x5NaEx4+`$H(J$U6ZmVEBGe1a{Q zklV-o=bgE0f|1uPYAO*}B|lYO*B;#VQW?H{_jZCUn858(>;>@X!Jm3t@>c)NmI$oE zH6ms#9b$Qdot@~O-IeHqc7d$uX9j65;%#5Vzuy;SkQWd0$cfVd?CX-FWJ#W0SESJd zzNKVidSJ6B#THDo>l(=VUd$k!?&=Y*C2uD3y1r%U_|JY4fmLPA0j&M6Bc$~)y^LuO z$8x9Ev2;^=AL*%Zd3Dr4R(a$xVt%WaVV5?FCskfT&(CQ>u>})V_XaR`&kR!Xm0re~ zLDBqG&t3F<!n_s-5)$S;p*Rr1}TFj1yy{xLv(ex@lGr#THDguN%m^Cmkc3{}HV0 zFg_viG__6aNU;SIp0h+Rx+H^C`KCYBj+=w{e<8Q&$E8#vu*xj@;6m%;|5iD~8CxWp z`;1&npQ}@-%_o2MqWKZB|5zcxWh}A^V9SplCgnHi^K_=p)+KWL^m|Mu@-J@L>N>}k6k9MMzw=qc;`qr}mqu=0 zO(X)V%DDuvl=+89P#3+7@Q`@^jn-m+uUDbif{EHW0qkVh5pr{lUb|;o^x~%37wMKy zX%vr^;cfldwc&@!k%ce*XXM=fdjPk6dW2>bY^Hcj#RRT(5fMHY!L^uqbZv$85`k6G zKK^X$h=as8NFSZs-5lRRK!32I!V(;tQG5ocU6&+P+zC=i>y8f)y-2=qU zN-twc?O0xB$qCidaUxZa1rzu^iI{%ziF{}5g%gL?MN0%$jcMS|rnfjil5XpxK~V4{ zp0uVDEAhD##THE9_as)AZ2Iy9-)x#XZym)oI^vQ)84zv|@vbqv3tPqN4O~sJ1rw$IR%P9$?j>y+>cppN zqj*Cf6Kh^ST_Uh*M6wUtv~m~m-J$ze)_$XSsn+SN{?R=YTQK3b(}!7>-bE}Db;7q? z6mOc|hCP{fMk284YQ-w73)@EGUg{p%*2{x=z?W96O@~67G24r=rkly%H>K2})4kaB z8Jo$0;-yuY$O;YPe9pbhrhi^iY{A6sX6SU z1g-@|*)lSOFA=vibv<8N+-3UzW({~YfuB~KzBj8Ack3QNlibQlPlbsF-M!eLZYjjQ zp8l1*JJyB|AJUx;KW&rJl;Rz#Gu&}a!xlQ6r)oaONsZYcNZe1e2TVn*@7qwoS-=ZTex5|fkecM6m*HF~pZ9eSHq@Cnp zFGU^c>&JRnq>)K4^<7&D1EYDpo+GpgUMne9Sp-yJf46TX16Gz$FNl9bjcw%MX}!Oi zcOsmBF0n&foHBzhSmedZ$8I9Kca%~w5kJd|Srywv8pi6gyRn;x^BF%AV6DYjq& zmo4tcu?XiK2OrZ~mG3VRSd}o-i>>{cOj5_{W%R2Y!2|Xl)%qOiOtA$MxJJa;RDTBZ z?iN&- z?n148=4y3AdohEkb(DPAkVl$`e}AZclthYu=cWg+JoPY1>Y{sO#qwhK@J1W8B)0`B zwqRmQlR(zbe1uF-(!FrcoDux%^}|}5U*jbLtL%l}erLlGaw$P4PPK{W)8{j_ccOvf zIfs9bK=wNK3Dzz^eOBeyn(0DlzWV+u()^Q9R{hnr0SvreF&u8DD$(7a zrBvBZx<~51=z-Ov`Ec(Q+WmH(6k9Mcp{73zJs`&UtvX>DHIm!e?ABU*{h?w4tM>l# zXHUZqlIGv^I74iiF?@Q%rP{{8QWRS-am_A(?f!a@l>5SbP#j@jq8~Xa~AqQ89s4 zxD_bM`g&t|pWBPHP8V)SUppo~oef|evJR8lvH#|^@5l1gfeW>k=6w=@Rk&@66_chD zdD6sCZIf4q)M_y?KO~Ulk3CA_cj;eZ(e4O7dX8C(Y12`~Z4E~X<=?S!|6pGBNukz3 zZ6rMvCU9Is%xi~-^MbFrTIST*5`k5?4)t?V!}$B_FSLPUBBk2J1dh*$zWvxRu1&bE z1y|iA5m<%41+n8WZ4giJex<1qi>0pw6F8P7vXCAQ<%XU&HM_qTB?7B(D-b@zkAZyE z+1FbC;k#9A!32)UiF}68f&5{Yx7wk~Od_xfw@tB=)uKE9*2{|Tw{0u6b4QtTD0a1>YUCg0PN9~~b>8$Y)P>_<5Ud$9{EQpkiBrT@nljSX+f57r++ zT^$@Gj|>xkT6i(T$`mqF(4wv~n(?gVNpx=;nZPO>@fN3%bZ^KH{9R9PC~i_L9231= zy;yy_E#z4*y^Q$*!TeR{RC+DB3}CPLcVizm!Ep~+@j_9tC#xt;C%5LmLl4m2A;ke( zFfqP$RhDvW9~u7rmuOMTw9dTPtxc3K{z5Tz7UeLC%-L|_%3`-q$6ws+wr+H17H;hr=r!o-04zAWg>ezN(N zo~?fSST|nA{S-|ccvT{>s?|qdX8g9FWDe1Z8y8}^!@aTW_{WJ-)Bw+Gal}H*&%MX< z)DDT6Yhse5$OI;2&vLTeSbidVn;Lq1xkO+Uj=YGqiLg=p*py$YQ?IR3gas3_FFMOT zlDB!$k1naOOCqoeN07wM`;|j@+Mz@m-!wyt6k$SsAKMc8@;VPw>52O%Bm%4Oije53 zXNK~Z9Zu1l;}@m1B238dquh}QzM$4J&Aa__$=}^2eBap46aLxpJj?P0YxL{Biv1`&_F+#= zw85{Fc<<6a+Pg~yl1GLKJc^1Ka{eTKIMh~~QQtuE-@+<6MmF~B1pc>lQ!VYctrX?N z1oj3*wn&wUyux({ZEQ>(iNGoxpA+jip0V7zZ!1l^TSIDtn803**l%Ep<TQGrVNQz=CJDP8v7^H1~vQ#3l3dgcUB=zJ7KFnIx{<4h}TQGsYP;no9!zlh& zyUg6yYZ8G~a@4?gVFb5LyU%vIUy@<~n2^8SPyWOB?mC%l{QVmefmJx#CQgDjmg06J zn!)I$r)ZTLfow>n5oG+yQtHFtK(_jHGzk)IqU;@iX4o`>tQe-BrrUem1Rip8xB7hC zFnT<*A|tPs5Obl8YIUX}+m^e8*k80!k6o(BoC6n<;*-k?V)gf0{J$N6aCFo#I`4%y zV@={n(kmNv+EZ^96B|cz%r@c<1t0dqH5e9^>HB3?+|YFa z329}fTwZO(ClAjgE#H|by{1_4vT>Q@Un7lp>zJ!9wi?5ZMHwllog8_!eetAgc4g&G zJ4fz6JDz;nQCVsCzB&J9J&LSvqU}69q@JTXYDfwT=$b~_j&H%=Y>O+O&t53z<#%Pr zmCt7vtB!o7TReIGL95{cO9rc(PA9Psk1Hrx!2~W()QLvXYK~PBdl^2RU;?}Hhdc6j zW8#U+5UsZqab#h($$Vh zx98W>#*pJN+UXH@{uZiro{8~l|A`$%dR3Ka5hH7~UoEQ~$MVn4Aowm~ z;_uDo{7Bd+GPQzscTFSLtDQ%TVjX{_O9Xbw*Wut^8LoKsXEB0*bj6N8Y?MfDzpSd@ z-@eqrj#q_o#3xgG+wU#^s~!@0;aTQ02_~lhwBr>nj3rJ-Wm@DXMwF;#>xMCpCo>8D zyO_wBV9$fkk0F=3X!q*r^rvdavti8h;~a^=E_@HQ9pxM#Zx&@0Ms_28F57Z@`xKHn z*i_jQ)QpFRO(5Y$rpnu!w*2UiWYQ=_`=T;!ZQ0M`PhrS z>z*zV*oE)9SY6Y*9Sk(JVH2iwAoX%Z4X|c1sawrVS#_`}KiFk5scm4Uyk6FnU&xwF z?m1~SoY%rOU}ta3#)q~iSiuB5Y|5+rOC_s5X!pweq5`#7JF=xtpCtmj@I4ecEU}(o zxxk$r3v4UhT}%vGV9S4(rHJ!6wK7f?J44NnK1}BsAQ9MwpRAb8xYP-*J2zrKb9zcw zj<0FuM;o3ydTVRd%b@*lwpCic#;;S1(YCHI$W#Nb1HVg2bUtVdzI zL||9X%{IIjnMw|h(TEnSVxW%aaawJ1265YG&8yy>K}O}7DX$J#bM@j3(op<+{2pt5 z{^1M~aZDpBzl#9xz#H_>_&EeCn0VUShA+yPMlNJ)gu$>7IK28DUAMi8^tZ4J|3dLR zY7PcsXu$SYnL@CFi3M|Q__^Gvy2<(!t{GMk#ytuG~hV7Uw zT{*s{$L+0or9rbvNtSjU>qVrfL(USK@zhws3MOK0tofwybYj0$BmVm~4z_zuq5-ES z5lmoLT?cD^d}uleP0|R~It7v^J5s->zhvqiD?Y&>lRURKQy!LB@fKbgqQ)^(FfHnm zqzQ1LK~FkhV;sQ>CW@@Ad31g{897QT<4E-+Xw)o*j*1&E5!faFs+0Ru;r*`K%5=Xk zWcNiYzIW6-;wSnd_!k;qw&LsOW|7db+V>G1l?wfgW+@+%10-VcZ7W`~F_Wx+E7KxV z);JZ;mTgy_UhXJeIVO^ySn(sD=8_Xe+I57xO@fV{UzClDdq@O!;kzJKdN-R0l_%C! zzZy>_yN#^*qT`E*X}F0Jf6s~=Y+pd!OiY!S3f6q*+eKvX46TNn)9=XCui5!fZ)t2$Y!@UVXbzxghRUZU>3LF8rLt-EEc(vsbiJk8GYTT{*s{A^%zP&=1+fp#1E!s>74u z-R)2nb{i{L!NjykYrg*1VzN9`YX@KU8V40`PgQOE&mfqPhU$-HL+$}!`Yg%q3 z#0FeduRWhZ-hZ{`e>0YnyT6PT`q7%7id{+^OsXh*zFYH-u#}9huk{&hXT-qqUB}g7 z88Zo1FwuOLHE+IQ390c_BP{;J!=u+*)UQK~rN4z;_!sJQZaqgsokuIxxq%r3E0{=# zu;%TqEhdu!v@0Jxb}X!Go}~shn3x3jRIy8OkkJA3LDC?x>hc9U2Utmr4pNFDaspw%PEBna3MY3?;dcsNN@ZX|9^Hi$gu}w5L%d>72>n%}FwinQCW)o>22TLJC6gx36O!*E<3$J=E>Z$+S2_%u3VaubFXOyC&- z(Ua-p1DBsnqdivHNCbA_>l68+!&}4Znc=in*GAHHU;@ush&h&Dtzl0|U+Q^JCa?>? zZz8WRuLFEr>Q6_<)|K8XOyFD-F+Ts^8Fme8N}t-+mI&;^UxDb!cm+Yr`bM<+77OY7 zzy!{K5v!dh^#Y!FTY2qnDiPQve}e}5`hoe91H4xTjCDX?@ z-%uQf!4aLMSFHF+5#2dBPm9UC|6vWj+h@`FUOudsvlZ{YbpZ)e&6MvIt@!SX3&`Tf zW{R<)6)$bEkaWJJ_4+nE=nJ0@M^U5iKcq77-<9J&2hMZ`yI&gF!mF9cXjrKVms3@eyuJj;rQPe>=h z?=&KGt_KWWIGL{4-&`WFYe6e39=$A+bV}5S9rG-q?UX5WNIlB7ZL;EBddwm@&KAni zU@Kl{R62QXVxeGKtasjS30DqIr8`e63@ez};cvzDqvwzczqB$2_Gtzq@}|;~|GXpu zyX0RL^zA?B(0Cek-#{2vF!9IKiks$Tl1YoTGR#7oK(j~F>8nz`L||8tc>ZIRd4!0# zpNOR183?IEUFo4GrBbX9Kh5zIt$5<#1!UX^?JcRkqZ@e6??WFQGGSQ31b$9p%vstA zKD6sei!arX2<$59XT|MjE+A3mHENhe6Pa2t)cVo8T6Uh@eThi?80A{*qM8KAY@lQL0`tb zr8wS-Be(Mg*zl=FQ_1KB+VkkPs0ws3V=TP-S&F0CodcZsjUyw=XM5zxc2}JlB+v9^ zAL6c1tYG5&04H7?II=ufRi{fCR~v?1c44(r?nwl88Amzr>}zqPak178UJP#p5$?9^ z{>66`E11|l+JTPo2C#vs2;2Kw?rba>+>6X?(-^vT<@p#06e!ghi|it zne|*Fh80YVDYEB-swI%iQ#FFdbb(vfchk7QGU@K(J1R%Esc~!Y7`#i&8JIDwV4{`3 z4R3XK3Nb!b{yds6$au7#-Zic*5!f}jn>8PtF@yAfqY-Nwd%*qOE2+nB8-^83%(JoK z^*2o+%|2>G@n&a8ZLo;CK5&o-?2_jV9{DwezY}NEaYbGXE0{?CW6hn?rjS{+w3&vE zNtQ5iV;WuAok|3D;W-O2|8dU7#$N0`x08-5{WG6}hDuFM=P@|&klBEyo+m9i2WelsSO zyew}GUWr})ZTgBGRr(Qz6^Urul)pEcL{2Z$%JA>s4sxBZ(bofiO7kCh&I3P9u~T6& z0UM{YbVRf%!wM!|h&6vXreek64lc5`kU#X^Qvids8rflS!}oc`~eE0^fDf(_i!-WV=tJ`eGsx z*oB|J*fsmPJ#0B>#7z5CVfee-k?g>C6~~fVmLjGveS?2Qyq#1kqbb)c7*;UxGtGfV zB*&7+u3F9T<46mrUHcwQ4`?6}*j4h;o;Pk8Pl`5a-}#zrEugaN4ceJDVpzdM#ta9Z zri&$JZM8D?opXW}hk$O_F4__-#jqp6bC%Z|UlJ(^^epM+^-*bL?c&Y~ygdorwGV&9Bre2?2$@@J&h z16XA44zY(H($qQCrCCcnQ|WrwmfLnsBCI@mUgL60=s5Z$eR128VFeSoY*Dw@a)Pt7 zcTp>cW)gv2xK`433$=s#Q*vk7$tP^&j}V(di0Y8$;b?O;~uV5{eZ}tc`Wzr*6gkZ#BoVp4RZX zVqNy_$3Ka{F8p;61IT4*S{wp4Dm1W)B@N5!e;b z&5nn@Pb80iYjtAHLpE@DoEM{EnG`FS7}48~Z{L_m4C`sL0M_@MA^2f)Ht6_biNG#D zvFE@)qh#{6e8yx@b5HoO*^>Dul z>}B!aE_G4cX!hcPLMNYX!5epuBYpZCDJ|c$;E~ni%2#mM&2i)nOU3^iXmQcyNte{? z!$Mf~aln`+X`^s zK8R%m%%NDp#Huz9T>TtRQt~w7RgMMBi)_z28)Qoac3nMh&kcHyCN3q~GrxF7?5BTN zoOW|yBgG0P+TXP2^DB%dF&5f0H#lemMlYOMw|P4x0=t|B*m0*piDZqN_RRa%aeyYb znzDd)$0$}XF<*X@Jgac4vl9<#8e5+IH{^^XZ)7N*W;gA5JfHDYJ@T_ZE7_Gr7yWI) z3ogf!V{?rZOuO%OMbr4mvFn*cJ3p zJi+`?Vpdjrf{_u{FmAssJJszD#R?{#J-6psoko!ee~mD1EF#+;byzOjw>BiZ6BaUWn?zt2evif39A6v50c%&*?lVxV zU;^KDv2$cYJ2<<-mesg&RwA$qzxg6he_0D?T)i%9((gIN3MS;|(fFJ@bTKw((L-NI z1a`?^)XJHjFs)fdmQufjVg(a8vreqk)8(rAhY4)szA6;Ambga6Eu1*{r0YJ_a9}js z+}Dv}1rxY-75j^xyQ2>L8O(~(sYGBGZsA1E-R@#_j`IL!F(#N|1rxY-)#(~!7{lK6 z-I&jbu@Zq@xP=pE4}7TsuM*m^=QlGbRxp8USJA)P^dB?~_hDyN=ST#0;TBG(3sLMK zaC%ENeC;NR6-?mTRi|sT))fv%Sh2bFc1Z+w;Wkmk`i^73&fE11CVf=)MS zIE526s<5<@3lf1{a$9TbufU+8I=1h>R}?Flkl(9n3Ke-7A8E6Y?-GGsIOd?!)ve$S z!^|Jiqy{DoE11BeCDCs$@r2M1=V?RNni7FsIOZVo$bwv;&EW$y>vt1|6->zEsF0yf z&?I{k?VeyS5!i)e4r1?}PqxrV&7yIaJQ!9mAxDaA{H^s*AbbyNgzkcTX!Tcx@kEB`8Kkw|}WW&kbVNs(e#+{B6z~{74}C^;ML! zdG=gwGKS=>tEw!>6>Hpkk0G|Rv|dK16Bgk0s5@)-(Uf8Z6F$t2djyXot50ez&f*!h zq1nVhHsM*R^tZ4pzLgklFC0f6ID!h$zF*EGWL>L}39 z&!z=MWeO&+E3An%FOEqk?e}Sf4<83bHht;zM01K2Oc-3X;IBeD4lEcLl;rB)l z#eQBM%OUVomjc_d-3A>7RsCIR#QmkMC*JC=J^WjK1TK$ar^42E>6WA5F z)rRi~UO`MxYa{x*H-q8k)|cu`+fNEsFd^586J`#EggL*|2M5kc1a{$_-$d`V{{hw2 zHJ`E<%xQwMi|>~T_9z_V*=N%I$hAq_v-6;!R(3cY>B`woG&i2 z?nA0T&9{Bnsyf@G40TN4x>9`S`^1>DX-}5+I$a{L3uk7F(cLI(2;JP4+4SA2U=BwxxT#{{k`wbLW~U|pge`?qhJL|_-r zViv7)%WhEZMlH7c=@u#f8xy#$6whNoZ>W)A%1j>5k_ha=xx?a33>^-+yNl?YS34A} zU;@{bVz-|9BOo&7E~TyJN(6S{>|e2mQ1f{BxpWInvEL=-I%5LYm7->tAXbx~T1W$& zG9&`Ka9*$23E@f-m^yW()?cDAA6{Cs5NwECZApT_2W(6ylz;&gFk^P+r z(NTB!yFIfc0=sa2s#rz$X96S~Yo$hw*d}H6VglEd;u}0X9z6XcREuY`B?7x}R;bv8 z)_x2m9$TmubSqG>f(cw#>U8tQ#>4&I1!}bcvm^q$a9*d_v*w~$ojK{WIwN?ql*Nh( zT)T?Qfm>m)>FXo4d)^F*z%HDnDW1oMp|Cl-ME&t1Pr(W%yT*vj%pFnS2P;$;`zg}yFqoJo%J}TNl5}&` z%GlZ>3Ib}StD#kvQoKSIugH~&DRxm%`&+u|H8huE1rvDp8xgY%jf8e@SE`3^&6Wu4 zlCNX;hiEt${fQ5m!6_B_)Z42qC;zThQK}ub;ogZW$?{Idis3J7p7CHAseVZ70r-^0 zz{uY&s_)>M6rU2`fsgy%XZ7j<9AvaDZb$lU+IG0 z_Q7L`z^=MMVr)=9muzdIm9f)10w%MEh5n|uDONCn-vyBgI4K(5vW9%oozoJ5U3CVE z9QvXqL|<7e!}x3rcw{Z+AD^ofE11AtY8AaJ)$l-F$xkp>ePQ7vLyn$=88Ohmb-+syrz}0Ysx5CpWvYG zX_7&)f(iWgh<#GkG0^3QqnhHJC=uB8JKCC;#4RCT_i1H(%^M9Jd-PMo&xKH|U_ySc z#`cbaO?6Y%*2Qb2x&(h8a+defHqkJ7Qa^R$@XZt}n807KSgY?A1uZtXsy6!%Nd$J` zoOIF4h>n7!H(z-BEhnVhb4=jpFJ{B7B4Fmcwfvfq*x3eJYUehH@4wCh+$t`aYEhgL$^S z(&mtk;lG7lI7?UTr+;@KoGF{7cpA&uxR}5-hR7uU)f-MszpwliCp_T4g;jePM|(erlnCs~6YDAR$EB04MOqn?tz+P7 z?J3GX^W#(}){k|$m`zrsj>~3+;_~9aD=AWGuE11A{M66y; zii4WReku#^kX}Wi_~-y+f2(&*zi0K^m!5VVc|@Q6->zY%5HHa{M(&FuT9O82<)1*%$nCd zH-i{;)5>^h770B_KHdC&62%H8UgV1vd^cy1rgb%<>&T&yQTsf-vNcO0uuINoXv7AC z{inxt>+DGsE0}MJp7#>atoJQ z1N;T!mPn_YDu|`$R`KDl$4e~^Ch*rR@~LZ#g-1uX@GtA;N(6S{7FF!(ICu;M_HyHY zzvoCTCnoUsDCVQG6Tr2L!uuY|lL+j>Jp-}+qg6ayylh^0=FbkP2Y?Cu=8F|>)kngW zI+Y8bxEz%T?7}@9v69sy8m>LOMQjJ2lX^0kz~81$w!UEyu(cHrIg&&8JFSc< zU+uxU^IU53+)W~|3$OVSwdjooVE3y%TQtX&;yDkz%L$&R(CIeycYt08y;;oOHWVwE zz?obk1`zE6am_v0!^LZ>^}gF<1Grp)q7Yl;<2$Th4jTp#Hj#^6-?lIUYsBq5f3pRa%kN* z9uk3Fc%DK;Sj71Tx26xJ21V^CRxp9vc5xm{$vBubqZOSt$4w%z3(r%C+}aCCko4)E z@*=7Y#R?{HUrVQ}zdjj~woXyLk9Ls=?85UDVsDWi$+7T2riG0=Eoe#^ho$ zSib7Yd-%Ib1a{$h3NeqfISC$jf62YP+EA=u0*_?GE(Jy7!LFK>dVH>nL|_-5rw|z_ zE5|~e1%1@Cn*J0kn2<+BoeM_8!N@7<6wYyuIl=aQmkMCkM6}= zGA#x!J=m`H+tNZJunW&qh#4&N2*_A|Or0G}C{{3mck&hMCJqI|n!+dQSc`@dfn9ih zSY)xzXaU!9is-ZBH5krA^~-hQ=lr9~_tutkQlB(%0h89Z>CG{98CEc{bDa~m7NaeKgsVphZ|}4)6rWgNvwjmJP!SCX9DE@eNs#|J$9?;9?KxykQ|-;94f_O@-Iy z;I)L}`|u0^vthY(cy}{~6-?k&HzG2T*apIa=h3~TwIl+&@LEEh?m?+1tm-m zSi!^wX&336d->(wXye>Rs&)J?;9r8jLx=%Ep}#w;T%6P z#<6S$ALiC)1qGidRxp9rn2ELFM;)QMkp-);;ip7k7tSdYEA?`m;9*b&w*Ek6h80ZU z6*1!76)V<9A1|UUR#`{{cHtEfVukb*C%Dn`Ds`>eh+zd2@*0ydjhw(JvycY$wUG$y z!Yd-g^9Xf>&D)mIs;N%W`VUOVYfOF(Xb#0$v*?*ivJdN;hwWN>2FLWIA_p@nJspf`qY@f zdGF#aSyvmXeCWvdmDUo0UATWOa-GFGuODj|Yb$mt#0n;G-n&?-7v%)!Hn_6(ACn{k zyYTu3@wUJ8fTqdKSl*dTX*Wbn;JkOSJIrV%65k5%6(D0_}Hek3?V>j%$gvGWlU}S{*P|`VD@@?M z2t-tEUKET^wxLxU6-oql;rN^w59W;kGpky(_16nh91atB4@$90Xi_AkCY(`%Z=aV4 z$%UeZA`|dlFw|h*l&uFxvRXW4ki!Uw!#RGDyoiDE!6+w3K zTY{+D-c{|{B!!u0RwOm2`tmy+Bg#*7bU*3K?W;wQ(c+{>nV45~s5+-wsnx?@VI)!i^GvUHI4PbbP0~dhc&COPVv8c(wQ9J^x0MmC8G^ zV6-=1Gc=MM&U;SYANS_VnnaQsPqfn`JUh6nCn~0}^?4H|1rudeefTSjNV2cr6G7y( zbXOPYQrNQ86{Oe9R(#XjD02Dv7ZO<8i`S|bMZVO0Pj2`3;%1K{$)IlKC$d#{S4}IV zFgj|vq+kO7S`nwVt*ahtK9P;uH$~c07C(R7`w)Aih%V@cw#lqvXE&)|f(iL8=^Y=e zc78FQ&A75$BCrehQAGRktRA@MJ20<-FDPF1iPw+TG;`r!r$m$MpS4qa)NQrE(c6QS zbi7Kjf{7o`ocYAa7-D!_Oi6E0NYh~1}(h63$uEFlMz9|vdwRMRbZ`U!B z^uMZ=q1)vTCT+^-p#hI5RxpwM(u0TmH-cRKt(B4ZrVYGMp3_eIizEWOGIzW2{;eX& zpm$ms!{7VBiA62grot+8;4wY#KR1kAx^RP>eCo@q>%xienFr+jRz0u%CG3BvC~f=b z0_NjdG4o;7C{{3$SK!O5-47@GH)*HcJlbOqmd=!Y%lNEd0=t&Y)$=OD!~b`RQYNtx ztLWOWoJp@0tYG5i96k3K5l$+WpQ7~r-7t9BB9GP^y^E$j_vU*Whms8ads2CsHy`XD zO6E=fKvOSwt2cpYJ7mE-w{^uhyq{x@&H4Gsz>oH+2dcH*$N@|p8SH5TBV0c*gk#@S~PfN}8 zd|s6>vf%jx(#nGH7DqzL&&8Dqx;+FcH@!m-ta7JV!NjSWgkPN(Lh6*CUpq596vj8X zLB}L}NCbBM6vW=SA^$rgcZk>r@*HfWJ7bnnvx>gFT}~*ub?pUlH1*{nb3#bS;}_&^ zkPnY}9YX50dn>ME(EJY2Zn>o+TscvfJ@;^w2<*c5P~_YV41&3;8T+-RiF9`{@$-|OKU*A1 zHi$El#qKcc`@xTE2Fz2jlL+j>cUqj0+tf{cP&tKtYk5HGA>p=N?kyFZ9i&b_p2W7C zvsJKy3AqQ*zu^+~b=qjQ_~vGbz^>6nt$4jbQKb24tw%Q4?6q1lCxoqtS*y%%>C1K2 z5v0TL2jpf`JwH5UMENOfKJlX8wO|A>n4!Iiy@&l))6WcMH6E^4u!0H0u6q8Y@d)yD zxpuFXeW?OUY#-KU(|(D-uIQ0^{`*S!|4y9xZ}nHzJ!2?q)c&^gt8jT~0Y1E=Qv@lb z+F4s2vdti^RS$M~KsAaLOzfEA!}pIFL8?Y;MB2vMFetwhTTt9eBCzXqO>cg|RrE{0 zYyGQg`|KdW*_XAR6-2Rui8cFtc-E3|(srR%M$r3~u&RYCV*#-efn6c(y}4Vj5oChB zR+n7v#bBI=B{MvmM6rU2!lynwe{~pXwofbL-@Ud_QneN{oi#@yu*){yn`aCNC!2a` zWmK5Z14^g-rA8GpDONCnzh*K1aP0&2*1e&znad>tyKv1XTIX{^;l!yzI_tt3sZPX% zTr&(iH5?oV<dTO|U!aD6Ps&Lj7$bvDH^LyK;T!7X1t$smH<8hL{lndrH`U<4T_ z&I82nv}kMBoK;=#MKK;8ExlKm@HE%+MtLL1o~hcqoAd0d>i0W>J?J%FBCrd;`8wSo zk2&fWeIlC_`-9*S1pbBcXu@;e8g=lxQLOh&y@C}?$k&l^dY4+qvBE5!;X@OLA2*f?7QE-viER`=>J5!lr(#FH0RizJyHv~lf$UQJ=B zkuPhzb^^r;Ch&J7`n$Cqq0$!@7JMy3BCxBY?ZB#>}@(HpL1i z@OLA2wD$3X&1-A22(kVg6WHZg=*ic&8bMa>(#o*U355KWf9U>2`4lUdkiV#z*SkY# z;%jPj?0`gImmC9l9zFo-%;YrJtB_&^6LP;~xy2y3ylNx;TyRz*unWf@bh>lH6IFu_ zg(Eg7a(XK0dscw`A?2@1P?EhM-^Bq&z&SozOj&k8x7Je(mjAEC5>hRY| z?EQdF3RWuWISSNWl+;i5vLpwjR>x=xLg2<*aRADwRE{oe30crD#_|0Ttd&0}9Y_-~VN z@~+M=g2$htZr|DizL~C}y;>DhtYCu2dGMi~!%6*jzs0W#vHrUaZ(a8DSIOmRxuwe=S}z~;bOtn2S!iNG%0lhx_2E$#ygO#jhy^+G6CFo8$NB1`Y|0C4X0 zmQH**Ng}Wd_hiK`&0j;|_Zv=6)|f1fgfW3f_u}2{JOYwp^Qg_8xe|e0cpNQu!2Hw; zWu5!i)WQIP>L;g;HHd>EUtuolG%Ch*e~ zJxlYK>b&hk*|@H4Bm%qS)_FcPgwKt8u;Xfy)KA0&ek(=Pxw{d}59rEjug#DM?83b$ zQJ18fgGIOYZ1|L1skej)9P!raj*T#ZWlrsxUF!`JfnB&aDDKtoI?%n957Y16FZKE` zfg|4HEFt$s&={OqgNf%P0=wi{nGK~5@Tf^67MOTXnq$EPj(CgjJgy~d=~P8@~?-Sa#wLHgyU3gwZw1Y-%;q$3o)Vh6D zY5oHfa-Sgv+Q6ljOX-dW)g=PE@NA7v*XBZB_~2&%J6tIJKG%Awf$@fd$z_4yyY-5V|XG3jb2$TEMS%*d|K4%G7G_lO};ej6$=?L7HL#gLp) z4VAS)p1k$giloOGZRSTUs>Gx2rh>2Dfh^xldDgKK{oCIUNr&T#IA^p(zwYdF5@H0NvBbG@YJr60RJtVlw%eZ~4E^Zz>is3_TALM8FL#X1VY~ zN#UQHsStgB6$u&W&DRNHpzCik_LC=HA^zRSU#BG7dT~cV%n8+cWM{iwD&+T5Vf(+G zJo!t05@$aD}Dyw zyZC)|-RsU@xfzmcW!mmAQ^N+s&Zl40wUt{^{2k!$BYmmuxMEOVwd{jxHrWL zCZ;a+=bt@v#HzfEKl$MhoPJU*Ea@Z>*oE(c$oSni0`lLVR4+NSqFBMi(OiEX*-}Ry zebcU^=dKVi?{`OC73L-p*d^cHX{X1*fwz_En`Hwi{)!sy@#iOE4a-NV_*)TCgEvX= zdfH{Be^6VB6--zi@aK)zRV01?X}>DS593&Cg_41h?zjD3;sog-kyPeFE z;b9dE<&{l4iWN-Qi!yGlsYv>lmvPTE8PW$gB)j$PC|24Z_UAtbA-0`ykc~Doo4)t*o z{P}r}do*ZEv4V+Gai*juIl7h{Uidr@H;K$4Z_AjPIWic@wvbB z?qcGRC?n;Q0r4s?<9T5snB@4W<|AbSyYQDL_B>1W0L!YE)ci@c*~8`TysfE@?0H#P z8OA*M&pSFY<&dEgFx#D<9Q#+l>xTB7@2cz#7lI$DJ-$?BSiyvvDzbNG|J8R5&}yGK z3!P!*jq?Bs8+_q3SFQqzO@SC3?58i*UC1Y zd`gjy9N=0REzbmk&Dl`(m6aL83MQ(o^X3anbtH0#Rz~0X?cv+c9JSIzv8y%uTiAu) zN}cX|Q~eX`H1hrb(21a{%KQtYbI+Y4gf z99Hwn>PlbKq!sSs96fPViP#+-mo46_OFl3ue6!lqvVl|vCgSql`JC4}vf{J$?oMCM zVCDEFYF&}%-SZ~WGsncfUGDtq5d*U2hgQa05&$bZ{o!kK8%qRs;dffB zL>k!^tp9D|FE3h4?=B|z0e7Bsu>yJhM=Rqgbb#0k-3y;yvy=$z!r!LY1#V% z@mmVeF-H`vU}AW@8{hb^M1Spx*3-ZG*;{>6kOZ4rSD=`{uGEQM{7q`9-esj$MwC8K z)#r|b>L322Si!`ZHE#U+tWy0x6YcJnPMWP&-kJaj7HuU0yLRP!@zssK>#YxKW$Yc& z9|nYeQ)~}cWVm08`_Z_5)ak|*4~DuG4=Bxklu@i;0{6(pD7EJxI2d@4g!@#G`qbEk z>ql|EL4{!0pHaE6?#Ry+E0{1oOgJs9K-QLz4HEYZggf=t@jI79t_-Tfu?yFa;&jJV z!yx0!3r_DAQLJEM;y%LnJT)K#!@r4sNukKa+5MHMeO~;N2<*c3qsU>&8w7{e4^hje zy`xycM05e+FDe?4tAn&M!b*F9{pv;P?P@ddIOuYLH*bEImHSlW-k}{ zSIu-p4b;joo8JkT`#H6l(I<((F1e;Y65R#jZ{JgkjP6pbVB+Wu!ePZs&8;9t9z(4~_q5!j_R_2wfRl-(<(NX3B^@C9*dmG*Ogt~sb143yudqieW1-=9wSr?Wh_T6%2<&=u!;24k|6Lz@ zTPveW$R~A3K!4yRDHJQ1u)L(_-k-ng!)I${tT=u_9egzyw)w?N1a`@_Ppg5))rKYE zaLTMJ#R?|cuF~_I|Gw)l4bsYpDPFC9jEsfF(L^G!3)ht*|H?Q=JvuJ|E?jOb)rpws z9jE8x(@OO%oV7A)eTq=Ol_tXa+m$5(yKoIIvJLaPtARF2K*R1ytpO(d#jNG}TBZ7M z1FekQuGQ4^>=bzNXQM=5m)xplkq^Au&55wR#~7)N!UT>Qi4&o3#PEG_sqmv(C5gZ; z9M=*%=^QlT-9$7h=zN+K@xla-mx;)oGF&~PBti9}Bqbo6@}*Ns_13O0h*dp5o*-Jw zqPQC*+MV)-wM+G9s%aTQo-cgVv{}gzpxP=}!9=lzA3tbNs&6E+ti%Y?xPj{PECojO zww4I&l4E@Z%}V&Inv7EG7&m-XqF*{xE2CnADSYqfRG2byl0;w^jx&n= z8CIq6iK(fuuA#FOfy9LQ3&wXmE7AWNtd*fFE-nmwmI`l&U@!mgG3Sb3x{sH;Yd z?7v(!cNz_8?Pe+2;eNb3FV&Z&-yk)D{CHtzseYcw9m98B?2%Gyk$QjX7+5}kiu61% zajlCVpEbQyUr*$%iC?uQO-=9~2SbiUO9Xb|XCvx%*E4G1g(&#dZiUid7vqzyzw48x zKOilq`|-Ih-}N)HZ;+5QKi*FKzt;uP>--QkkCIb5#RRElh4qIs~O zP5G^6H^WR z`I31*^}$EVucJ~EXt<*-d@weX2<$4Y<;P$D{Gs2!SGx}1KJ|f~>jWJQJ}X$kMAx@| z{G8EGebob68Ru)7!L*@0p-+qN5`kU#4HaM105ga$=n2*(_oR0h6TM&g@v@R1dc*x% z87r(SL3X45&~(*hiNG%W9*ZyP+bEdOwGzGad4Uvf$5DA4Nf-UZF=N55^?4LR>rBl32^*%AN5g%DHJQ1kmHFy2gP2K73Zt72c$~`c8yyvuESYJ zdi~N`HLICXQ2Kq1n&^;1v4RO4BiHFx&j^NQ)lR8C&!0iYzOh)1)SY4l6S(FRyFi(@ zf_)}VkZamYBCzYPE#uc6%k)NDv@%ZbaE34&4g0o>s=gnGL}GegOQ;v87nS1g@3DegNaEf?2X?bzWOZ1a@Vfqnv;Ju74G; zl`(H|MHmYGAnLv;#R?|m`fAC7mujtn!SK(_NFuQ7&l1WHS$)?B2We$^pSh)uSr!gn zSuYi=U_x%4t3>Qkr&-5B#h%wB0=wjXiDSlIwR1=;%q%XDdKs9I`wX+X6sRKy$3u3< zg%W{XxKAX;1~grrF(V$XuINi~#Dnj2<5qi1^;z{RD|nP4R_f)gQ^OBL!t}do(r5w` zqg@E>n3*mS*o8++qSJTgq&nv85Ewpjxil)mM8sz|-s07F z{m*V%8ENFcx_xzj=vFKf*o8-ZA}_q^E4AcZ5G>E!D~;|jQPa+ypN{{jk5ARgI69{y zY;4*doMX8}U>6>}>U1y88bZH@evqnOl}4$U2=a30UFw$U)8}esyo;&<^>4L;j9S+u z0=w`iT;yyot^tGWoneFiwKUqs#M-{@e17mR{gQmGj80ySpw*Nnu)X-ZL|_-5vk+^l zT}FVT7%r@CevRU}W;{EM<4mF#o)QE12A@(=cW{aoOyD+Hv})(0!E}6yI1S{KL|_+= zGl`suX7TXlN&Uma2kxX;!31uD#XM){Xo&c^hrx)Y3MOzHEQUB;`a}Kgr`3aepG066jx&kbj5YmX=A}ET zP5adpE11A-u;`JE4uq?}f2kH53M2x%aGXhG=`HO7UtEl!RYnfQ3MOzHELNqQq+oeW zWIMH3EfLs-<4mG2dXzw~NK5zv=@cuNz-_R|7D;u2vCEvmV`i2_U>A-vi82N|!1cKv zFwAKJ#R?{H8!RFdKkGxa+N~i*mnIR|h2u;I zdQUKWJ6IyH3&)wnDM}6gsfPdhLA%4g6f2m(ZLrwa`R;x7=#pSKo#Q1D*oEUvBFgD_ zMLl>b98!$xQLJDBx4}AHuM-7oqmHp~?Wu)CU>A-viRW>5l^QZO0jh0!qhJLSa_juO zI7z+wDiMOcFG~b=;W(4ntw%pZ)zwXcxBFHrSiuC2?ueDeyn(uRUJA5rFi9e?3&)wn zymR<3POnacR>tlMRxlyQeHNvq@KO=+>R;oul*@%(ayC`JA60nStyHjab|qNB1kNcF zxq~ZwVcgT(%4Rz!W_Z+<5AIfh#Cla#Ttr@1>lPKs!K^Au{s1?=VsQoHl&S5$_tvqk zs%DG_C#RZHzXZ?Ytnci`eO*iSJ348t+8dh7t6HQ&`!^2ClxA+c?&A{ulIE4A+%cR} zCi>Lkl$gNde|Y;1(}+Pc7ryh*YkjLk6Q!1|3qL&awf@Nj6Q#JR3pdMut-qVC?Udd$ zY&^_y9;do?oJO+TUHJOlZ}rVOnkdJdUHJ6wZ}s|KCdwmM7e0LJTYd6Kjri?75PDi0 zLi3`Tq(-U>uXCeFUs>$`e?8HKFKAb!-;!HZDIVg&e_DUkU%sxL3y{dgUaU7v;qKTO z1iLWZGtGquoh;Hfnye8ywK~B0m_G@JD^OX{Jh(9nSpN^H=(Bw@sC* zxz4<`!E1fkXKgoK%c}!{G-{-NoKr?y_Hf}LN5AOXUNKQTJBS@5!ix2uUz;fD`^8;& zRI2~jSG$e@2PsVNe@kh+(VjhD?ZzvvuSi~aRZ;M~Bc6{Gd1U4tVdmuDd`#ztY};v9 zeyqhm{jKIzmH95Nym-`a{ptHvl@)ek&zf0(^j|+{*I{$KH56>|S96Oj*(+mrzT<_C z9NS^6j0$(-k(d|8E-wu^T&36k!93I(ueNu`n>OuoGMC z76ZGFfpzRw)MM-HnaA$#Zm>mZ5cT)WKA!LUUZ3B8T-S5IShHu=tXc7do>bgoTfE6h z#?x^0RN=FtAWzEwI@x&E#Z`To=%XLn^-FrY*h%nP!L}`ygKOQXe0pYjKEzeHD)eVT zzZ3QZJX@Z!c{r0R*UrTMg)00_ocCix1uCc(rgP7KDE}1n)i>|?A%$jllIPy^(Q{t> zA>HcbB=3FeqtCDYQ+hkWtVDC3zc}@R^O287s)80IXr7Or{ooI&=P8r8SIdXqgk+;d z@fiYvs@$9%eCY8E=|D~Mc}%}si#k-=YK%GPrs5sNJB>a8Jl~z;N1Hq6pr*IJEBJq( zH1yH$5BwobDwR_f+bD9XHeFkmiSFRpZU8a?cz;ViGr&G@yHHJdD#NN~+lVupf&(vHRSHG^t~v9)6&diWVfq-k#bj zkQUjO>#=pp3k0hE?%|_Pj>%+uG1I&%C9*y_P0pbkIV-AYL1K!VRhQTPlCou(Z`9!Z z0rb!GGg5~+l?4J-;<#IXzm2MeFEV}&E2-j>!Y7FDCg*2Zq|)e7%ZwPksPNVz@uU~W zc~1E)4eVzAj(xrA(Yn@?j0X9O3k0h0uJb6mzX5ITH^pcfUPyQzNTgh{>U-Y(lw6CN zzdUA8BdT_=ondcSL?BRw&xS{aS3$I6S{q|PY<^+9LZZ6ARZs5xLt1{(Y@_((rqps| zRU@uxA%Q>@j&@vw=cYspem|0D-l(eLw+}~D@p;6CC{$_S8hKz*4;3v)h~w_)Z&K*+&E`h!ujPb(g#>yF@rhzt znP&AIW<1zXRv=J?Zvn^ZS8$`>r`%}ld5el)794|d1m{XLkrkF ze?R(Er#tO_8w;#C1p-z0C1RfmYYmz@{ku_VeRkm+g#?b3yb|`4=-{zOM%h_T0)Z;M zi;wPEi+7E})iSGSK|&lwJFIU&&GPDoG%Bk=psEqSwcEC3NFTD8 zZ`8|+O(;|66NX!!UkX}~XfVa9TZX4gjT@Ro=|fFP8NI`(@0nRe0#)^=TJ>Eken=lW zn?%VmEhy^y4r8(B4+Skqe6m^f4|UR{sI?|xzZgvGHbxooZ!Ibks0xv+`k*H1(%6G0 zaj$v^-LA06u$M_y(1OGT-CKXa=e2(anDeV<^}=Y|mmT`x$q$r4JcB%b`l}S1z%|42 z@r=y#v$VL9i)>`~)~7B0EHzinIh>zQKkAZRLBGHDzJeAc)@FF=54wMlO0_VFZ#Vl> zzj)%U%msTG&@9sh8el%&pa4A%NDExB#wc_uvJN2d2ZXB^uTf8bH z9>jX-O((=kVN=a}b#huyTAg#!@kdL(3cmwYcn|qIII;mXN&K!A{9I10o7Y=^n3gDY zs^cO@&-K>dbW4|BZgrNQY~jDxr%Kjo=I`+L@}mb`4Y^+vKlRQUFTK;RILY^di(Klm zm%c4iqSS1bi;VxtVktA+mtOt8F3-37so^WU^meu5B$t~mGSWjdFa1-*S1F65l5+oV zwJDSPI=R@R>MB~05ZkEFzauT7}2TA1ggv25L7Mc- z>?M0ogwp5S3-#r9vZ!c50)L;y(lJ|mqGKoRg|Foj2vp(9lB-Aj>OiZnKeR>d$RVsb zkr40I@o%l@%Z5lf=fZpffht_F@(kddA2oHZK?VEfkq6qn^*J%$q^*fLwojD$x|&Z=-PV;_ja_e)&3aZr z3la}cdFvaiBuOrnO(OH&P|A^s^NZ}dCJ?CV@Y7qLd^1_P_rScW&GUOu&boHvcITDK zPQI$VRliGhD>%z|g&p{+)+|Vno+p^Z>%eZ5vGu6&J9L+V79{X$c^BtaC>?2f#;8-{ zkU*enK?aX-?~BC%SdAql_-lE+{$!D{(9PP>bLHj;Rc@6XK z_VXFfQKp5Ax%=D{vFo+Or#BWxu)_}<^2>ZUE{BexZ|~J$Yin| zx}>kI)m*S3fxpRO`E_U_Rj=S|)SbIWAW)Ud$6GII`6xA=ZC+KOC*!HCR|R9~uXq_P zNZ_4jzYNbYl>1XpW5O|K1qoEm;k~Td-9JkYhMH|0Ju{Lj^crD!j`UK{f&}&ji=}(@ z!PI^CJY({SNX4spr}5m#u|)RZDE)ROR_nqehi_0)Z;LT3)4Y8AF~42la7-M=02THs;~+@%ek{ZgHMJ z2z~eP>yeaE`M&NKG*9S>NW3cNtw#>{Bzf?RlVeQ!kEHaoenxuLQ38P~@t2RCFpNeW zQ;m>L^M&7m#8cH{_W8d ztCCs?1gg3e^wx{NjFE0z%r^SCP9)bu2xRO?<&8CPLk$!t_3>i_vUuZm(7v>-8TqE$EArAe~El$eT9`T96RO_K@SjbgceyBa*A|A%QAfg>fabGHs}5>|vuw z(^m>wkic&VSNdz-j;fXZ+qm@Loj{;UT-~+4-jM>1Mj5BQpDSoV0>9LJww=O3VV!Y(F+x{ zAc6B0o+01pN8`5bF~a0=0)Z+VQMrxC^?I~N1a<4V%Z6t{1$p1N$Al#5f)iJlhchJh zl)e2-w}wxqJE6O5Xh9J?-pP~~>js%KlCB;EO9 z5>uy*GJcOAON+B?v7rTtSG%qHn$L-n`*o98eLk-dTy`SOO};AQ=^I9Ei6?O$`->Wt zZ4>G4`&}|xkidJ$F<4Fe7!!((rDf&s2n4FU+#TZPHA#BY!X*5E>PE>ugX!YPwKlXMv9FU=KOdGTU7BGM-7nlVs%-5? z(I<)v{|i;6hgUQ@;Y0+krc>FHjh^gFz zMt3YMBY~=H4Xt{oYKhWx7jvyvdt!<)E>CyLH+zW*k`k6%b_=5Dd zN=vF;a=r~MNZib1)hq0Ym$HSJ#Ed?r==1x=)G9i!j0CF0Rcen4W$D@ThBUSGLK|9; z`1`rH-t*UY>B<(fjUBdXG^f2x!$TJd1gdbo%XTCNuDQ+&36Y-hccA}0#%2dee_kElO-=tvnRG1rWti322#Y6 zJPKNnz_*!W!y}#xP|55^hs&!kf`bbN%qP?On?&3i&ZatI#DX=VG?!N z;JiB~-Ba4C-B=UG!_1Nr*lHUxIXcFf| z531B8-_3;t0#)w$toqZN2~wYQlSruOLu0=AktSzW(1OGderp?-OORGQGl^Y_je3vq zAU$s;fk0LB``-GBJn>RhUvu{Qs`fl%R`b!6d~>}GzmPa;<2cWmDSS5@X~Tw7(UPTP zv><^aID23hJZ+HcAd2u>FA%80=g+lFe?KuQhV-SfX=`P)Ac5mCdw(wZZnWs#oxa)5 z2n4F|`CBYMPFaYCbf)FQ8w8&9A|n_vei|t-DcRVw8dwB*rc0 zIwtK?q-_q*<(eg*808W|DRISefk0JKgpdBcd8*XdF~3R)d2Ec%*M<6CpQE4!3776Z zx_fwv)X6b>9d;l|rnh;P5uGAUcQ?l?w`Il1eR@4=5Hv+W3lbLHs_(d% zEUn4u7~%3&qGj_qn`foj0)eWJE3Nv85-C#N=_awbkvsip<4>FYCn$mi{%^@yRz189 z=T7Kj68-HyRA{dUO`SbMAW$`-yH)SpFtM5$~M zb8H{dwK4sgQ-I3s3l|7f<@@Zd{}`GeJsoHg+dnlXk4}YYL(d=uEl5;-?X6co7B9^U zHi^%@gGtGjhq}ep5C~NDJM6938Tehww$UWU4QWX`tL3G}3-faBw*Og>IJJjsJ6-)I zWu0LX1zWYJg|D*H(cS4X5~vzIlRX+c#YxL%I8`fvV5ly!HHnUnEzD7t)}#?$rBWg0cSZTryga5Pcv!RP94?PH&CQJ7?IC zKvh^9Z~ajF&(inr=I^L7E(?_|tf_DYRnO zc?B&<9Q~WUEZU?=IjWh&@k>Q0^|cT6iM=WisM<8fN3R{8F5TW{5{*X`p~lvlv^DXR zf)*q~coeM^lqM;2O=9`Ra#WG$K8>4P6bMwcsOh6S`KC*5S6zyV*wSTu-{Km8aBY#}%|7 zQ7Oi%2k%LhmIOM8mo;gsZxJe6;iN#I>iZ$9u9ZoX+%=OZdc~h=NyR8E{;+};BpU3n z>MshUN;}q@#DOXS^s&1O#T>B<1gfr&;@{CIRr*%I?1_>6>(a2;-1Pg(0R=5c3>#$C zKQ>B{?5SoOcg{7Y)XNsy_U5=ipsIc?tDet4MQT34@zyqDU$t|YsA2Q{3R;lJ<73r_ zH%yj79ivYL_m)&=;djGz)n0)>RhKkA3(J`#_1J8-ai&@;dbldx=$^VpK?@QO5_l}B znJB%UWfJ{D+R@7@amIobO9TQ{*G}?z?bUc``$LoPJk_3_FHAHBxJ*{ifl+bC_}UCxWQjcToZ1OioId{wn?BW44i}WEd43dDFNapIbo-5|O>V^*i=2 zQtKinapmVA>JrIksb`X9Bv6%=Pq2C?e3DMES2^!G*BVNl)Ak#oIrhnDLE>oxK3ALn zNjg&7ByMdRNsSKvWi)y*S0GR&daD>T?fj^7|DNSkCfq`37n(ytgo~eomk~g9d>OI z2vp(t$l2a1dsDVwl_^K9)e2gW5ay_s(uL~K+KO&;clkzvKoyRUoUwPfM3r)vq<~>j z3R;lBIVzv_@$=4lDG!aww_YGnh2taFCjZ`mHde_?UX7P4Xh8z!sO+V8zZvaYnVrU8 zUMdi%!ts$aD6eWxz3bwvB=oByiuC zN4Q##jSAhnQ>IpZ1OipKj^>lNdykE7t9wwtr7aY+Ac6b7ycZspZuG6%fj-^tCJ?9+ z*3lgG`@_gtx+8tu-$X$R61eZnp8dC6XxiQubY)MdKnN;WNAnH~&k<9b22(e;1`4jp zk-&XljzoH1f{t+Q*NtD=3IwWf9nJZvo0X(nWdiBs*8l}ANZ`INXMC4EXv9;0I&iv` zK%ffO(Y#xmR+atw{7LO0D`-Ii_kB74)n$M3TL*2!_)Z{v><`IZ9JCr3ZgkPi_w53 zKV>9Ph3jaJOKs7Vn#C8RZX*uLXhA~UxjPusnwDkHOW#r#2n4Ed9nHDI{901;0|lwr zM`sx=NT9DGuhsUpqFvYW)0As7g&0Lti4li`-gwjYpl9;d^qQ*M5-+`%^E>Hss*5~q zq?ex6`<+z2NNzdnC@=l5s_&)8`Ev6-@mW4Ao$dQV9(Jatik2-?y!5tipQZZ=E;9Zn zjwKslrGSC2<>_6;HjqG%X7&&o>Q6Dr59Lh}-ojO(N{oZt=uw+e9-Wb!=l4?4f&}_N z^X_?EAYD$FA?G?&P9RVvddk*15Jbhc?Xq=l=qC8RB7r{87K>|2D>|6*!tUHOzd)c0 z{dzh7Rnb<|;_Y;O*!lc||1J`uKlShWt*LSStNPdrc?1Gg=%38vmEDhq?>i|!`^Q&B zfAij7y>!1S$Ks(I?r%z_K$C2`dS0#$?Z z@Ojj(-%^TW1-WZ+4Z7d_fm~yxkBSx~R$8ojzm68$r2=LfjaStq*KQAG|L#_SK-KNs z9Ah%UV%w6{B=%+xrdHF+7}Y9p^%ICP!)GAIl3h94f*ub^)DONcprQo{e3}+Z`1v66 z_;O0G+^x7kpbBFNdB-cV5e@3?r{A`eQPF|~-gVx^X7z=hcOnI3&d9 zk?Bn>T3`OQe7uC0K%fdE*}2AgNH_(qyJ*`Mw@>g-#ONCIJhWI6pADuq74J$NIVmq% zkia+{(_18*GK#dNtN0u@HFWsv~Za*WUQ+Y+lK^309!13d;@80;oU}PxQjrb3S$>7 zmV8H4O8aMzu_$MLAx04ijAXW0p0|@|`JOX|%c#5pfhsXN^Q50Y-HASB+zT! AUD z<{T(6*GgR;JT!uQ3kd|OFq?qI5}hkAoowStC7#7A7?+A?AsBJWJ6^k7>30bqy5;m< z$RL0Oo{MlLf!D<-hAL70yk7(YRhUhHtBn0FN?E+BQjLkP6|^9M=OR4!X;+@Ej44e~ zC*KJKsxVK0#nRw&IVw4$JlT6a6EX-Of#)K;N7lOI-4#5rk-&2io*~zg zsmt_iRH)8lfj|{{V{=C9yb4XWI#H$(Hx;xXf#)KeNBDIhEq6{aj;^^c5U4_LY|c55 zw;>hp_`~>~=bC~RB=B5>?^Qxm+I;zyv2N`hfj|{{WAoWWSaT})E8382$rncQup>fT5fXSV!d}IdI?$~p_c#`Lk3gUb zuUO zi1R`M&qa8(UA8aH{YXYa>3#x%D$$?%=AeFb?WbWRpRTW<1qnRm;5e^SgUL5}yHP*Z zTOd#+M!u}(Y;Rr8Z89!Cb`c_Ykic^he$PvcqKV^Y8bJ>eW&B^L!ssE+RM>J1jlDI_ z7_&cGh(tmHPdS)qHi14|s%f~qo+A*b5+kbiRhvMkzSlFN-{lbEqmaOSLKchnf{8S0 ze#Gm45Pl$6)qTcX^^%JC{r(bBG}xn+!-!H5|4zv>W7&%Q2| z|FINO{qK0`BYQX-=1Bv+|*Bxj@?%u#0j)>NqN zq34!c^WVwey$_!`o?Bj8(p!%iSMRX$%G?8(yCH%WyY|*{&FL&pX4Q7pN&7HAx4en} z-an_WR<1&Bc`FmOZuHfBdYFWMCW5{UU7@{QU0puTs`$1`w3e?p5}yC=8@@;DJI+Pc zm{_)ZkG57bSCA>!BWPo#xmw$CB?Su-W=!0A^{H0;w7K%yGmGmR&dX6}d7-hw@4#!H z%f!-gWu-ym%&WS6K7x{eE|vW9dN|ssyKRrOk6R~JjTpK|S~~gPD=b!OopkS*c~z5| zc~X<-f6H}xNowJKUb^RtHPY=MS2^22FFp8Vv~(eptGr`AM>78tEuH#mwsBeUq7{$# z$v0cpR?&ilG|WpMzV?pf7G@INs#c}KZGvT=PqJFPhnKE*YAsDV=PIx1>80QE>L(T4 z?J5tR?WMOU*-!eg(v=BmL>0vAK;^r*d(9n9|Y^){f*y`r*$a!m@a4P>M0PY5_j&B8q}ci>vXxLpRceFhlJR7shgD&Ti%mP?hyC- zP=$Mo9Di=FN~=AG$p=(f#U74tm)P4k?Y7dKtFz>aGyPSxAc0rN-zdXI`HqFj-`ZCb z2vq&r>!p|f5+>~%Y(Dd9OW89zFhWk~UqM9+5_qTCb6IOa!5f0)ULy+&1ggH>^wI|% z4U;a*W*eznL+HhZ&T^gSxmC0vfg?D7quO?*EqguWsqZorBv3W}iACuH|6j_V-lv&45^C|6;ab0FZ47@I{`5r6%)DT+T+QBtCe$0M-)bDMpaluD zPxr7zYl9uVy@?k#L&$AfV?)~v1Du7e!VY` zB}kx3yjRMR2wHN!yOw;muJ8@VFSYnRZypdq17^R}Y_V&EFFg|C_xxngBzja$vCq$6 zP{IF&sv;bbdoOR8wrsWeJW5`kKx(78_C*zIDQH1rI1|sF?$J{C)PZ-M{~kk28|}0o zpD|S+P?fY2J6tHj0)WMK>$Gu;b&t1y zNjfSJs50Ndc8kKaPdUwZa2(I!A`(mLGt4>MzwyqR8Sjk5pE;cNZ@lxWmt!bfhh+Pv zT$BHcUUpcJz$@e(;e_!N9rMV(WmaQ>K-Ktva}j7}E&|Rc^VdYW9kbcK{9;7~ElA*< zX0Mm{NpyD2Li@9QpVZx%MPlnx(RK zqibPdOhf`#FPyW#SOi5c4AflL?-s^gRN;z@PZT2~=ysFXvGzZ}f3kkifhR<{sHZ%Dn56twVmRke>kwaqXNQ zJAr1mIATl9UE{w|)RBP#33Gg${a}xjE7APoEaQLqc}9i=s?6~!&E8jP?O-D&M(Z``g+QPR*FOB#Rvku`rjmZY z)GlEThgWDm&Hv34lPyE&WtLj{HxJG6e*9-aLi`;v_rx|5i3yshXA6Xz!h4V*_qi@BTxx2oz<<3x4+&#lx zJe<#QuKTxM*u|GBMa(Yz{JkiZ=a-npCHg-VWT zW~Kk{&Ys*^al&5F6>f=wwYweokl!HoG z_2?l9T5y;dQB`S;jS~Hy=$SrwsCKKbJ|cfs`_Cm#^8HqvhrD4Hd%3@u=;Wg>T$R~A za)C)a2<}S>|J+v|XG@bMj_s)w@KuZ9*q+edoHLQWXtOzLrwK<+9_t*ZJ#<7)E{(9# zkpZ>T(7Q`)8!vk6ZN_}pQaK~#4~|!w>HJ+g6rWR`^}<`f@$kD=ZnN1&oz~%GKl8#q z`o%uw9_R9HRqlhf-_J$HvHj27$Fb7q+*Df+87qJGQq#D`;U7P3&8*1v$KzWw>ubeu z#Nh+aRIQ^UZo5vKgGP-4ebpL;XDMiz!m--Z+NWr1I940~6UWhaT4RJZ8mw+>-cx7; ziD#TCq}JYK&C`)7q)PB~!!!GEbS_x(5`{<7k{m|Z=bdryAJ%wzS zerQX%o&x6(T3(4h?Qv6&mWox-g2Ydb&ips}G2voh|C{yQ< zH0@GVlju|>59RJzSDp5ReZ0Ve#1f99=Z}E4VW3H*tJ&$*geL0ScH0C3Rc=#!^wTX; zHD^b3|E2+%=<3dvYP%PU6|^AX;o+m#?Uka9a75n!DiLS&NNBIFJ2OilQ02|P{A+lM zR>qMJU~o{3v1nfx^=MKr1uaOVadw#BTavXyj`-T0A8r`Ca`je|AGQ<-R2}7CP}k4GyCr5p{@1Bt0UC) zn|i%rlhtC?stJ}qS-Bhpw#{>& zh0paYgD0!)e@EN!f1&E$5362uN0QdRh}p*AikXdh&nBtI$L_VE1qtzY+{ygj7}ukh z`n16s`4?xix!OKSdvnD}p3nKH5-ufbN1~nNfb~|rdEF$fx+DM9%{5tR)y|G;wp}Es zkiO43Yu24j)GAjo$K6b^E>zQ{jhe|Xhk_O)%51ahpEDz?iMXB+dMrx1R^%S%qF`wf<{H`Qx|2Ub%#2Buf`9W2Gwh9pl zRPEzz3x(ul?PPD0a7!vjMV%!z=;1^KEl9lLtPxlDrD!WFnZ&kv9`s_7kJ_ceEP+7P z%vDx>La7w3_%xGvI;a{)&{b2Ds;yDbg2Z`_!Y;8dRohzMBy#8SC7;9P)u^$X1p-x{ zIHvks;Z*IwI+IA;>_g~Upb$qjd4^Axg*!1E8_~NJ+2x8fvSy% zIio}QG|hU#Y$JZGL{D2gb7AmX3R;lJoyAALmyoXQ9cL2ja|O`L?3vXzmmUfPszwp} zh1W~h>fbeqCC>w?SCtgy*zEfXTAU|Y^_d;hw1S-V65F;|o;Ww8qGNw3D}P)S+CZYm zXsbRXC{-)(h$as%A3%ABxv2Ly*aZSrcn|r!wr5?ckdj+neCU91uaL;#`19^TDcaW* z^LKc<)S*)~-BkO;jRJux>S^9Eo3?_v28fWR0GfZA9(&;d*)= z>X<<@1Oipqr#VBDzaQnvS5-aLeYDVbk%;03x|qi}T(+WXaC%`u~uK%ffW zP0kMUp(;&3=&uHpm4$Z@2}?bze(iXo7QNAIBXwIDS{PklUA?i0K%ff881^cD>O#`d zw(9oE3v4)JwfS20fXfM5tJhBdXZCunc`kC5+N-rklG13!TlY>N~Y4 zRk_eio!)zyK%iREfXiQ9xmO8`oTY9;L}> zK?2+3Q8X$$rGM+74h@bH3AlC~=Xuv)#t-Am#jfhD>4k)`9se)h1&+?V_TIRX)Jvs& zf7$SVp{i9dR~ajisJU^SFV5YT>6y{!Wnb0Waj6Y05$!oYSd~OAY?1i&;nnuytHzj( z15~G~D}^?Yh~|8accT)u#Oh`nbrxMTTC^Xi4q8=0_#LPcziMY1Y%?kr7_PPt{@aEY zBywNj5RLlC^0)Z-V&QNk%An#w5Q1zQll^&c2F7NFGErT=rui~6O z&Px-uV`g0d&ek(KJVATz$kwy5X=CcJu7G;)Rk(r{BsOynq5gf6w6cyILT=NWlWS-$ z)%tUaK%nX_XTR83Gf{i%$bRwmTr>K%JG*-I^-={bNVMgg99J9h`lE%JXX03qR@CHd zy7H^ST7f`SDCgw3m@`T1>Bz|uTcjnGJn&s{-oIBt3la-BQ^=HBDO!x9_CRyamQ^e8 zh0<}&5rII}+zihC{XR)^b7bJZ>(`n_PQ9!2TX|7I3lhFuA19(ls&;(3`8%TQAr#*K zw4#-}DG;a%`RT1!xRtCuaMT_cb*n!)S1zkRpL|2X-Ba9qUBR_$PWAer6?D|D>6CjA zeY#Lkw>3DYpaltBM{^$fK!rX??&_My1r#gq8jLBQpm}rdKkPA;IYZN-WAWMoM~;;2 zj~dd^>BZG2HEJnnK>~XZubmgRq+ti0)vNK11p-y+nzvrANWA8$oA;`FP#fBNF^k$d zVz7c1B(V3ecl7r56lNqU3lC2g2vlu7$=;OL;?JN#5hsk2%jP~~;TTaQ|ppyf|Af5$1;4s^(VPgyx^kAfB?u=jA@D6UGit(W1Oip~ zZgQT9mrcnswy^4RJ)iInA`!%yJPYNG*Qz_lcHbKT9-;zn&GZEp=3)IT7B6?yZhe?iSpsV9&_l{lu1^;9t4sCt;yLpbDQR_rweRDDUei{rc$D*}6Q z^`V8*H?6y41`vI|DYbc9TwM^p(1sQy%0zK3x>a#nuV&`he)Uj2x>K=|+I{h2fk0Ih zS5)#${HAqvWH2jne<;;2u|qjNBUz4Vp&K?1LqzXq#E(|DH<xtjigc00~L#VT?H*jh`+<&9Q4onw@_STMhOI}j&gOC&8El3pOjEe(0eAcGLo4v&TWg_*MR9qS7mqY$q!CN1>`<-@`t7KQN z=&hd}@=n`4-dVoRcm3r458A}R=G~oFWFifnU{$KmpKe175|%37dSKi4+RgzcQS0D1 z+V0sy8CzZ?Q03z5t=~QLK`S3*67f?9)53;^@_1@4;TIa58Lj7{Pud;MjD~l_d}~Kg zvp1`i1?QXu3ley>?6Ea{6uDnstfV%M6z(pneEm3%<=F=+k=j+rYaQe&6e^0@+Kl%4FkIHt#Y?F-k5LZ8c><-PUkvG26ej*3$sEtBcu$)&a% z%QIxOAR+o$4qrW)CY_D8P4T=X5U4`mNX~dND}<^Ibyb6Iy9%SsyU9GKy7yIU&Xvt^ zRN^PNvJ3rn=C^XPZEnGW1ok(Jg|zN;%Q;DD95GKA;ZQYzt2+js`>YjwY4*e_S^84_ zH7}J;?`PZ4f`r(2Yh|uUXd)?Eu65E{Raa@Ug`nDh1^qbDI{KHEh zQ9MPP-`MonD)qD>HJdm>t`t#5ea{ulKa9-Kx^e~cRL*hmW$sUH4p%V8|HRSDjq1}0 zmkBm)QbnN+B%Zl(Hr;iqkp@3IwX~3OS3QUmYrXFG8=EP+dg} z5|=rbg@5#KZSKFhEI22}6PNosz3>qTRJlCnyyr|P0cPJ__`VfQ%w10jYLrVol)~PT z$5OR1Ih^H4&Qfu`>krM7Ya##M%g>)uH0L2Eaq~o5`jBgcVrlqGIr4+oucuP9PTz9L zNO$1s@@HNoYvnqaMAls)R6z<*`g>$o(Sn57Mw>zHXk4R8O8(i|1OipIiQalJp90Ku zjP0djgUMPrpEC1(UKOu>%NDLbw;@&Q$FnkV~|5Qqh7$8h_P}_KVjlyf@ppz_X>_ z1>6*`pm+rdR8{2nqjvf4+EqvO)6#c)(w>llO8;@M6to}_$RqXR^Ix^!31%D9UWC!{ z>J^p9?H2_CRUK=4>w6k})#f}liSv~P(&?93l$z~HK?@Q;i+k(tH$G_)sRV_H)prK!~HaOI5rH^UwHyIh`D_ zIbuA{?}NT{-{Ypff0Unk&fp5Pz6n~n6)v)MxtG4Gew>#3mW$j<^U`A?ziPQ0wPmH= zzSM2=b^Z4hKNT%Vlwf*7-8iip(-zCDmxJlXmg4rD?z-UDhyD||AH;PtQU+4lnHG8P zJ8`E7iKu++b7%dm{l!(4IWDzNU)tfGMRs5DT-aMem5r+(8>yeQdR+aO>pOqxLCcGW z%F+ID3R;jT&0lTj8*$p~3MP?Itt03Cs3PwvokK+eRoEB!J2;>@O&jW}d{|si7_ac_ zgCh~g6;*3Ox9`r9efyPE(Sii_7$%AaQNG`v^35}D0)Z+ViTJCwEQpNUS8d~Zxv6MD zLi`;&CbyyUvlqzi-SY?ps&FJ?e};}7C}qoEa^3YgRJ0(0_l^C+yLG3w?e579_k2^3 zKoyQeT*b9O9}2pCRE~>zp`Zl`e3}+Zj>rKd`(Bjil)4}gsKSwmeeP-wrn?Kr%I7VH zf)*sOS8^uk_2JZSc#!P$Wsg9h3P&Q&jT;_n{|p5!NZ5pViQ2R?wOG&!MHV!|jzX{a>#a8f}F68N3x{q_a}NzdO%Nn5l}AW$W)Qm79sKPb1#j@e!Xc`{*L5_YfLRdQ^AQ|{to=HK9PvtUd{k}fBw>6VJVM0zh zf0&P6d7Q<5bx2Nm=uTgK-aCu^?{DU*<*vypWh{B1?+k+a{BiSpe^0D*t_4XED)&DkNN83u4T5r`)RhZ zXI%iLmf9j!URPN~3leHiAHDOtO!kU1&GU0hd;rJSu93f$au*0x9Xa5u-#VGezB|=y zPp(UCq zA$iKHXhA}J9xwaXqRxKNNNbq|_;!n1DEj+?(W5MD$ zBQmPFdi1SbAW+qT>woxrr)d`*r{UFZWEgSP1JyZ$Z!2g);!pN0ZSDfIjgc8yX~q{t zEf{%EAW&6>tCIZgl&&>(R3&*Zz?n+9`l*>eeo)YY#Gm|L+RB|~8^hNXpsZP{s+I44 z69`mk1%35zdwyswvO7E=W)vgKU!~Oc2Q#T?L89_-U%l3w3~j?nvyHvu%TTVgf@;|f zSp@=Bv#R;(-Aew{f=iiglpVFn=utd>$1OZS+1hKs{Q%o!~Wz z1o|X%gxjLC#x3VQ>SyXN5U4`0Q1%3De$&tbx~cB+Ji+@D3G|v~AK@V}#)`2W)W-9d z2?VOpyOlGZRQhgQE8a?-zG#==#fk*>9`>fHotdJ#G*PeCJSY&TLN8tR-;K?|C+-32 z_po2a)V$Q?nZMc~_@+Rh3cZavuiC9bw3>5%>tJq&BNBHW?w*1t5*~=GcUY|#~Q&4(lHDsi#iWVfq@hWY+2W2XfMVMGKr<)RSq60)Z-w3*a`Uc~RQff@+t>uN1T(@qp_tO|Fryb4@|Q{cp4HT#H2fj||;1z0SjR%WIN zE^XDGy}BxBLE<;peT@%G){4zHf5&#u??$Mlv+8-IsX(9#;{w=cyTu1%MC0!2$$DiK zv>>sAD?%%0leC|M%r^2~xMPHd_Ek%|xC#WSFp_{z;@-ER+xr$P^{b`|t5ln8)o0uI zIj-Yu4M02~)T7)8#p{8yuz!WbSspQ>KmF8-IjZm_Wo}0Gsx(v*C+8OkRN-D0@2V|rOq;tj zQ9i~L7EWc5z_kebi#}{b7yikmEcJF12vp$-4fn)W4XE|1?8^5QrB$>bf%9vNMQ#^J zo7+y78%`@P5U9cv8eT!JuSZ`?ww4cEs;Hs`30x;|27%owoqAB&-e_+Xfj||m`nW>( zW`%xdePy3{#6wsQB7y52?(Mhg(56~D^!cYf1p-yL7UgQqo$Aok77z5_;hw@O6$y;N zWAB|d5tQ`wp{;wKx&OaBEdS+R!BsJPtM`Z?x9sEP=@*=YQ%lU&@`le1dc2L*B=)l5 zDC{efDXPy2x!LL*0)eW`e3m-zQ>YVhB+$3PV#&DGi|X8qRV=d>2n4F|1e4we*E8wvDO;Pb&v zL#RadBg*Ah^8^A_c+Sn43h$1je5DpCLyGN{(Sn4yGcmBj81@jFqP&pi3IwX~oSV^us{7n< zRndY3W&z`P=adeVTd-tNMN2a zizRbXS6b>jQ1A6BO(0Mu<~69b!;gYPPU<%<_^Nn{gr`7wPQ`DnR~;(Yb-jLXNp;~o z3JGz4w|jU4YEbWm{pq!G0)Z+#5#W(}Ul6$u-EHsF#7#I?LjvzQXY#xiLZ3X{ZF*f- zfj||W)^Kjz8yzY2bZL9Wr0l{u4ib3RIY;BBp7gwKSnUGE*uxD@kx(U`V67X~i)vbb z*)R6~D4a(jAwG{$cl**s_Nhy5@>C#Dg?`q2Qhl=)Wv;wcDRInA*!RKRA)NJFES)3Ci42+zb-A37AdXY6%hzj;R=AG;-ec-{Fo_9^r?U3a4+Skq;9QG+KP)Y%NIz0`l>00Ys6u~wKL7a8nykTll(v&TC}=?f zy)SsReISIkDEpKWJ6{R}s?bxK{QwTPrvn{UDA!BBQ_zA0o^n_$^^bR?G7qDadxM?} z1gg-_nqw5-bf)hcW-7$RFvSQJ81uaP6DTl@KB6T3O z-!xU()oF!5pb9;6dDl5{2(_FwS!pyWQb7w6=oQE()td&BeQA`E7TH%IP=%hkd~k1(TY65}($z;GP=%hkydylj7j2Aqp=e)R6|^9MGbf8> zs9PtRyV{}#_WB_sfhzROwODTWhtRyR-0G8U2W7M%f&Q=-ORKU?=y3azYR>S*0)Z;@ z%;o*WD3wYssG>IAkXJ?v5~8PUhob%z`P4_P5i4emKow??;MHBkH@(B4NovUXjY4!c z=25`-YCa|FQPucdWP+L{jOOAM%jgIrbjoNo z^zv;XN*xK@_vM_Kp$m;_PNUS#XSNCisxZckSHeEqjB{th)qO{<3DIXrh%4a-oempO z^M|MbQ#J|&sxZ2av%OWiY8)QiUo9VgQHY{L0$1J^i_7k}M$Hqw)QhXn3IwV!vYfN; zHBT|Z$8=GolFG-h*_Aar@wR4p&CG4z zciDH@cOqo_&2fFN>vzxRzpkFo$7{|yXXc)JW@N~{Y_2Q{ohA_2CCqo%m<TpoP1a^rlP5sPw zfb^HL@@v{cVdgz1@XQ`wi*~aB<##8=Zi9(HU>9EHihrGJTSAwLU`7AN9AW({Oo+3D z*14Z%-OtA=zdEjzBBlh;j#l4v-iyk#uG0hPT(@t!+{IoEdYE1{}9iPMCSo z=KlI*;!k}E=Yil14_;q&?*;~U%W0z(jTPC&o4%IyNzBsfQbdp!J;v#uR9`CY?M2&< zt4{iy*5^lcw&6e+-}eJ;wVJ`*Hrn-U^OhC3DeczR5s+|1AiLk=aK=uF9JHfZ*+k3TieSdwjVAL0F z)*&rzFuyu6i~XW~`AAEn2I!NIq=FM2M@PZ?v3l%~{}mZ4m@xY)(IZ3nQB8TziIF_h z>1C1u8$WM>d~!wrHHgtClV&{BTI}RYnvBvX7ppzf);yrl(nZxtam{C(Sa~lQ3Jq$o zukLGPtYE^zK%uoq>Jy{>uQ=h`ZahS!*JP2a$H{*m2hhwl)ye9n_qF~v0_cKRed68V zzV>NJ06ojg{=WDDC&pK%L)FGwEI+D)++uGapXZ}bzWgo|2+IS3w8gsWWZ>U2PLv)> zhi^SD(#ZBhWUSyaaM^rkhZPgx`@uQ1>ST~WU{`Bi#*MYr$>4uwm@P4;Bd=#E1+Cg? zCtTIib^Ph`E_$W4IwsMT{BO52<=XCgGELx5;`5K?{HSK#Fr;=jvlPu8S3$wVubDDk z%4tWX~oIsX-g?qx!Ws zTX;Y4JMp-o&%YyF+E{%O>27zJZ|JFP?`ST+3k;xXu2s5?=k96uGzz3~epR}ir^>W* zVgu;=xj%K|AF6Nd_U}HB;Oe6Mci&XT3MT3*{61yzk=X0%QLVJ90gGDU zt^W0!&UV#3?c4nUbjOEpI{i&$+WyZ2Xw}#6I{p1B(SDgRl<)1U+|8~O2<)nC5I|r2 z_^#W(Pd%!`51YVByRJ&`@DCDJFfmOpkS?3|Ll=HnEn{$vR?uQ+kn*Nh9T^kYg|7(T zn`4(f{9P(5^YrzFYlVrS4Fc%``zqa&lWG}LJ3GOY_WsJgNd^LeUHH23eF0o8`ytgDasy$Vksn2riD}aEE@Nx+WNf%D9NwX&71bWb^G2vJJ^=`$;za$ zvxW1(#Nx;R+KX1|s`AvM3O8Y_+P8QmwCfUqz%Kk<;j4d-oIoE<%2GxiO4s7|1HTjE zJGiADp%d;;R=i3!3hy8$j=fZ<{`0T8!mxjLaIJlAwlZzruu^xr z-cx=aQSF+u%*UC^>s9q6?D}jHKo9Cw>RKd}X+^^OsV|!{bD|Q=Y$dE#KO);y~ zy-!k)YO*wv9hNc_)AtzyfnE4M@hHyPDJ;b&O&NYPPPl`ZxY{j%&YWJUYcf?W<7R_J z?C!L&%8L0@1p>S9-Q-WZ?^#m!ewJd_;6Gt~IQ(tLE5Grqm+ZcD@Axd`%*K{NoB1OmHo%t531p!b)q{><;kn1d2lFyY+WoBrijxAhdYl~Jp^8%x=f zp)9FhM_4%$yYQNjJf`1eFw4?UQ+5xrkgR;0%rK8j`8Y?}(FRfCFpVUCX3MPJZ z^P=Ww^~ky7YCF-cOHbJFAwYfNT%??T%v8Zg zf?eWK4V)hgUw$l+YuvA^UM{P7@XK(e)1B(M; zz~XbV?wh`X6-=-!A6hi)kFH0EN@%Zjf$?L?>CGig72HD9YS7T6$$LZ_n*fA>U9K*l4R}vq1FmkFoCnb`EJdPJHgiM4br9o z76O4?_&)I#+5Qf2^7seoY)32M4q^glfAc-0zXUANuHJZ1kpU6_)Lf-Ilg% z`Z#KplBKjs(ieJ)n80mcjb>nta{BDXB&F}}SptDwxYpKaKFzPsrY*`;#`Rw4VhE?jH#%*>SaZ0N{DW%mX*87r6wTJ2AlwEU*KI8-eoHjT0< z!ze|wd!#^Mm-sa}JMIb#Jrb_yGDpZ*!Gy&{f9mt`n=W#eT888BmuywkU}dIbo7(r5LHQ}*N++gPukV$^+xj1^3jSNT);{9RXVuUf|MxwT-ysZPo&w_<_7 zE@tCH6Pi`&_SaVHlJigM!^F7u%E;dsjRC)!S7YOXK zj`X2`);+NJ!ppc??gwYb*Hrc;+!qM! z66@X1-Ge|g{I}e-`xO~0m^hNFrLgjk&e&HiW83FoxOM%mY`XA`KwuZH^LZW_=?O== zpOKdiy)R=06SG!m=@mN-Vcpd-Y2rS0=w|Hi^s@@4}zr&7RoI7xr`M| z#Fc32)9QNU%22h8S)T_$ng2*RHRz8(U>9x~@Ue-u!(nc|pInspR>le@CY5UG-p6`m zNTgcE+Sj3=x8k)lIYCcoGhi2P;qckZ{YC=0uu{5t@`H>OOw`h8d3JO)Qp}@9dhsme&wr7k)3F(_ zr|ul7(aj+;Rxr`+K>&67s7LNKR?9HGn*phjWs+6nAc4TH2Rss%`9Y6(|0&~yreiu( zuirw3@9kx*VB*p4K)Q0d9+|;oXMC(Ee;gDl0disDAQ>x|D7_Xy^-cB2{`%@sJ-Ia& zvg?kP(_8QsEcz|%TDm2WwydW|`c9@I+aJ%9TXpCwV+9jej|R{f4-J`Yq?S=P zHW46Vt-Pz;Pav?%xhRkp`Dw_IuWA`n;uYv|(pIU~rIC!IPF8_|bmsh@y52YbH-5El zO-ER4YN1SA+DwRFVZtFikQy8R*6n?)mhoTl=^+uj%|wO`rFSi!`@v4Pa6{I|~jrCLUZ^8?{sfS$6`O%@33%H0+~SMBUlP*!B36TwK#t#tJ6#vIFTnJ}1uQty)IG#&Brx{idAZ-bo;^3twqInvoL)b61>{ zw^@71Si!`R<$*NDRYM+pQOg(;90wuEdt{g0J_3PV;vEd)bHmxJnoP>dlyT%2N1*Zh z$X6-I90zRKDYCy8Y7$iBLcQPJ|R2P zaRPx|_?hN;OQpl%#f6*lZvAP(vx|wva}_$c*>5)BNcn2}DAX%Y3>ipJ4-cieN4ekWX3>qmln+y^N?7}f}UNiUw!tX!k z%K7;bLS2H1vhE5UoA*=K|F~L)fx8!2{&H5*N`nLfyTmy4zBpG{-PTjNJh!_Lb;iUW zTZLY8s?r&3Q_J{tz!H)c1u8*DTm=HVaEzSyyuzD8)XNa1!)s3=dX9;gKV+)+{ku+Y zo?1qYUbR7&(pRzD-AEv?ON?yqUQ!JvpBbd|ac?GL1rzyaWlAf)>7FO6Wz_ocobBxw zu9VtU36X8=!cleJvTS&rtu2mJet!QcM4d75dznlRS$@-n_g2d=jNZ#~tP+*#eXj}x zc8Rgq_Wivf@ug1QRMl9>d&M)Eaa@DvUrqD`3!{tjmdOnjtY8Aq+T-~pHGSZG_yf7m zCnJHtF5Eij@8H5VuqykzJo}1~f)z~Q*@t{h^7rmwXsNGkwdC8Bqu2{};a&z`>wdmH z^uKDXv_Gz|U6_3i!UUdW z%yYbEH-@*5T$MUM?+65T;a(pfMZRMU;~cz{(+3|4y*o_c+0uL^ga`vTr{6(|4m~Om z*oAwqd>(zP->mk?V8wpT8KIYo2|VkY*H_)&v8`u%E6tXb2n2TFUO3Ow-*}773LL21 zyHXC#?_&>=I+h+fr*%sVqxbxni;~E{{h^aqNWmol7Rs z<%wC!EQ`~^=shOz*bCngI_L}SbZwGyZF)Zm{}y)P*a@H2IJpHIm!GK&TA3hW1rvDe zMWbnRZ4jH;B16eYjJmddkeFGAe^)A(AtY8AyM11^w>p7NkD^iK*=pqoA;^@Lj<9T+4-7Kjo`83T3Qd0=I)Snx@nH!^5cCvR|LQ0)bsPcEV@H zyAOl0d?l--t?Oj0U;?-2_?iQ$VKCy+I@x9!5eV$Uu@gQX)iDx+niR2^p0tCV5D4tT zu@jBv`-~*G`=>xMuh=PL1rxZRz;{G=5eIVA6#o`CP6`Be;n)e^3!+vs*jLk|x`16W zRxpA4JA6J)W;~o4c9LG(Nd*GC#GE3l1&I(s^qE2Yb{Q*}5Ho}fb_Ifya}j&pr-8C( zTN_$Y6iqf&=}V7$yHU@s(d4LyzO<{G8?7-qhUD0*BUoPTX0r$W<3W+WYxQpU(aCzz z6vFo$Nw;^@}H#jrfW{ zb6n`mdvWBOT}|l=U*p#&GnR}nR?C11uFTUu6R!Vyt_|lq88tOaAa(ct)eeevr_K!$ z_(}RN+fx^s&k@nMQ`TQWCFzb zWJvh8u&dvH&eV275_zQZQM5-fQ>RU4G2e{m#!*f)MZ26gpd=A4)kd_Ztv z`fqkS`ulAx+4B1nC+6r&>sGkX5Uy8Jt zz%JK~-t_Fb7;`LCHNI6_w!B6rY%0ps zVgkFajq{;nhR2Yl`6}_E(4FPC$b>c<^|fnG_|Y>a(PU**nbvHYAHCH%ny5Kmu|>Z0 z#<6H}teX1l_POZ6!VNPadguf#{w-Wav);b+$Lna4IZ@4^^D7Nw!wzJ?ta10XSiyw& zeoXD#md)Vz!~1)Cfxs^Ds7`+y!M^OwfJIw33df5H{66wGYIqo1bUp(@j?EAV?7~-s zk9mD`gAQr!;DX`L z{#42xO_DCCW$bbG1C#E~(BrzHKwy`6=KUTFg5}A2u)4dwaOU`&+L>sn^Wg|`>AhOU z^Xy^p7T&Q_GXrI;V8Y$QpYHt|L2A5Fuhk%31pKbN$=*zDD-hWA!%R!}&5a;!KB;8{ zoErtN+FfI7ay@0NVB$doJ|2}5LDv2w^6a8vgEwU+(|XES!9)}veLYkWPVBy^M|Da{ zfby1`*yjbZKw#H$7cC8&9R4qllxGNC4uz&+uh>gzvfQPnA9YzYitIZ0REx{_{LGim zSv8t8U8%+Z4y_shE@pq(vIXHXRxp9D8}A8U?*!X>HGp~1B7t334*AmLC6T1}1htIq zx7x$wXbUK66e42<6Zq-jb6-6?;QBy!Xkim55ZHAu*Ox9B6Gc4xsAa65;|S&5{ov1a zI~gmOz;7B~N#|D>kQ1BOuIZ(6wv!L_OdmzAO?|IjQtU(5OQXoKsJGgZB|fxO*U@C- zfVaGi$e$y?)@~DJ7lbE=-^9J-bawq z{8#@|#^ob?x0}0!T`XTKlz|C+XL+P3Z~&y1zGQ{XR|o`l%^dGT2M>%S4xZ|HRG-lY zEDQdyQAKlQtY88^3%o!0G6>@8HQ=j3&lU*mqTP6oc&{j8ZlsnGK0<-UJ{HibQHG2a zOyFmM*P`EC;jpVa>?=wT2<-B0=0j(@Mw2iT0VEbV==4(#20D{`9kk{|2~0kk3wmz^>3t586FAmN;xu zTb7fgW)Kj?%hSC{#tJ54 z6J6+nTk&Leb#;ZmusSWEZ(m!uGV+Z;U{^6GPTq(o=l&6!FLr|^gPya)zUSmyPrRs? zbtKW~DzvW0z35u^DDrhdg*N29CvDO^ij+N6uWtDJjxcM*Pqs6F?+%0%Obox`N$WXB zlhwOb;=4~UJTraDOe~)Z1a>9pJZPGGG->ouy}BP7_<+~-O4iXzqfA-jK|?#n5c887 zp$8%MSpL4~0HK`FT0>3A_*-SknMffd5h({HA zPlnS0k6ElePh3a+CG5gS%kyOTmX>`Iez2rwFJ!D>0$&B5d%oWT{tKvNeNWX?aDNH+ zqj1@Lj>&6xxbf{3n`2&AI4Vp8EO()21LKH=xB8ScNoWUsXJ2KpN9zj&cI{f{Lbn`_ zCCh_U;{6K?_|Lr+jJ(Z9N73_xdwTc@Jpgm(}V_^R_vSzfn$E^7g%Kh6mRcHugP@1FhF3ocKs z56{U3p)SFMcn3Wed&0%`=J3mSpFm(2uK6^Yw0&CG7GMT81^a|L5fk|B;_F69PuRvo zVKBR6PkCm!J9VEBPkh`ol4}bOYWOmaJPOrFz1n)w#8WY3!fSQbmQV6eR`IJhq}wc! zv8%GQ4ZUucKt?R7F4cV5hL%UhlRZb(`pVJp8Y@~E2J?$^*vh_faGeDR1a@70>P&TwlgO7;wTxLAYuK?< zN$|7ZVFeS{ZTzWjY806=M{VhY{S~&&J_b7f8ZQvo zb+5KRE#DeN&igo!b9!nsA?W7&RL93_LGk0=w|@#&=BLT)|Gv4uf8&ZwSv7Ch)VscTqa< zl|7mj1|gTW3j}uIw}7|$1{#5_(*Rgwb3k}MFd;ryefI5VwuOn1+NGz2pK2V96whOA z!CL0FZVdF0{Dq^!gb+K??7FabG;4-HU>ClIyiTmUg53{Gh49ok;p$=n$AEa7 z`shyfs&5hmx85QU*oB`3KBCyOkgZEd1u15}@RVQz$IJL=pLPe!9+kxR068NN*oEH$ zJ{Q1Y8GD(X3SqHZC9Gfq$Nl)+jMht-vOE>`SyO?)F8prt9n-H5Vo?t>V3$c(;XTKM z7_;2{#Fd3vWx|HImqL6OyKtnKk0}23g1aY9vcQ)O6x?D7T<^knlZz$k9c%tit1rUb z8yfNvSo4Mrg|-hSI&<2A)6+T4GlZII!8~FYE9oK<*oC9&JPWC#KWv(|jNQ7olny-;Z{N;eS`KYpZK1xW(G(hzA|qB8n`2rIB!(k+;ZlyF=y8RcuKA zY6?~`@i*3!=68=Iu|IzCnxWLCI~*@BWibD%j0x<*?RkwR^-v%9YQL80fBPh~+cEL+ zhbMhfGm^OcP+R)%H}-*>bq=!U*^dMQyKpaq_iOzJ!KVT1*wcphg#HI68h`Vm2TVqj zwYSuq?X2CQP_OfPmNW8-Kwy`BV_xrSMiVkxC2}Hcz@(NR9QvFg^v`h*62}I3Kg!Mt zK3BLw;g~r>3;+{i8_rql4-4O#!+_h11OmHojDtsUx&^@LEoRUtbiEMEz=YW9`?R?` ztl#~cEoi<)Ag~L^gZQ`hWiMzp?**IK{(umZ!Gw4}ipGUPR1xLt2kMJ4} zg?76(vdf3g2=OaSi1*`J;uBV@`(Uu`zDQ_UzUHmW@TrL;V6)iD*a(qmMm_Bxi(Wv=Fbs(r+AK3BRM2J~p0=EYE zJ>S_7Vz+dGv18f^1a{#_7>|+ltqmO<`vAM^CcJ}~z^xjd*LSl%d|lWD&apuPfnE50 ztr*)r8Md7x+V0$ymVzenREgA>+4xANwEO_*_aHJEp4ofD+r_`_W zi$Q$?J5d@Blz zbBXKpy3(X^R#eW;CCd+}1mCm{N|Y+Lv(*c^d8I9#6gq)Kw5ua+TVq3Coy#Jwuj@!A z3;Eyuv&i2TD)Hk~IK2P#Rz4bQAk|oAO}AF9AUzh>lq}X-(>&*uzl8bMWeaWAsTctZ7o^N>ct-t#`NI z9SA+c4VAYKt4UbF1TK%q0QL=rr7I1TXOYvjn7}UgUDmYzkd?%3xcZdzx-tZOY^p2% z(o8K@FoDmH&rmp)1j%c6%bERaNe0Y{?%2PaY#n1LoNY*?6*YRflpKp!*KZ$IGY;yX zIxEXxbG4W#d1po2Bo>l>Mk38?pQADGbKYfn>zQ0FzKWQTK3UN_6AQ_-YUGM z&V3?x`k5yX*d?CFSdR>t`ZG#S;C!i*746V#3Ay>qh_7+*|Bu~NV?~3nEF!-7>eJrW zC=IIV<;n}{&d_4Q(a(ww*tmqa91&@aCZcE@=ClIJi=0#1-n-clm5o{)S6$lq~8VetVLT{b0>-qc}QtYBj8b4%K6_Ck{LZ*SRzNs~dIQYM82=?TAu zUE;N}Kb;AUYgo#LY16b=!NlWgRGrOhV|_3B6-cPwe(%qSzt!I(*i&bK%j`#mJ7O~?0429pqE_{T%_L-XoXWgc<1BO$zSiwZ3 zixrjRJo5VAw>I@bI-Jf)u=jjU513qc>EN$tu)00U6Z|~qE z%zR`^n_rzsMvePdU#$&*u8Uj4tBD~3@%5n%?Nu$CtbZlad<3h!1DKq)frpnm3ulgr zj14w4X?`|2ZlIpWl6swCYPi8^;7)REY z?)I>wHiIV+kJ`r4b5H*Nb!lW+uKN9;nHKO}uQT|*iq~QV6H#65XpM*o+PxQjPXRzNIi3hCpBU3*+Fo4Pb~>6m?&A;ns!JU zOID0hzk>!L8d%CRk?aQNYB7Ob237V{@A5cu8&slTL@6tCN`gz}x!TY79caV;W615F zwWPd@4)jy}7~)vlP>TBOKuem8A*oH(HbaT|ai*6X4!OvP#&l{eWaC&eIYd1V&&)4uaQO)6 zWj9kGuuDAiL&J8knVXZLEB|uhGsowYKgyA=$VnjvP7 z>_ii$CzAmsYCG}KsytRFYCPzN%+O*2yZ&==q93m&6X!W9Vbv~)`8-JnQaDwM6-+ES z>_i=VCzD~1)%NZ&|6y#*)eLz4T2I0XCUAZ#A9p_K$XbVI!skVkwV1#zoDa)a*jU#L z7G>K)&1LW9!uL+}P@6A-7@v)-kj=>?xxE@EaC)(Vc@kFY>J;<3 zBNEt!pC0~oZteyyy>GJA#Kyu?f(e{C!Xqr5T;Njw=j^dW#Y{Tn{mZpGGwmtY89Xr|>y(->l$k zSOajCs|f^l;o6RmG_1`uQ@2stia=Sg+O2zt}A(cl@tPh ze%@mbufLRWR0YRp@;_qS}V5Y1JM!c6z`JzI_+Uz`rX-aeAGT;N1D+%=((Kf)z|e zb+x8L_D>~UK|LyC>I3bgjxs&B1_FUyDcLr3e%WO5t*c5HJamWf(Oa3Zx3z*5Oo-9J z^Q~M!iC@oF?spIf?CKq3Lw9wVOuCF$%Xo3h0={*e#&(^O6dZN5?PpCZQ>Kt=KkNQa z1TtK&733x6um`iX3jSS8B<{ARhbLu|d)L)6z|I!Frq5$*f3y<_>=KWv)s0s0%PyDo zndz@!1rxenHgxQ%No4X;wG1cL3Tis#u;-N`fnBCqHZ@?OS?43ZY5J|#2G_`v5ox7qzewH2&j0^cW|e|6sz&h;;2pD)%I2<-BD zW=n&uGf3>eUTPCFH@Nt!lo_6|RIq{xd`0-zIo}!fo9tk>p4bZncHy^x&o_v+h5uSD zV28Zg3GW9c#A~&ypA~F!%w^?TKY_q5{C4roei#4|LCe_Fq*pSIp5i!cAdiLyqsJcq_zOOa|c1&2|8*u*FeDvCY(&IX!GsM z$)$fg{jF%#3-*6p%M!a+30D_iQ87*(*r5|#30cJK-0CP;!9=e;mNYgrkJLJ<-j9n( zfsj|aoZYU~P$00&d7u^D9GOc7zf_4i>E2MBozL3tu~x8xiC=RpsdwKzV)srZOcuGp z+r9Ic$2~`Zz%FqVAo_?63^1L+(%yS3Si!`=QI_<(Pac`sKpi)Te`XFb$vJFQFIgb4 z3y(l(G_TUEpiR*X7JAoLiF382sdE;PkP~&JeKjrV(M=1;<|lQejz3$`pvDD6_Eyhh zVvAO=w%&BsbC6aU?rljYkIyF~Cf1dnnOM@_S^4BtQC+D=V?GvAFqb_0_cb_uw?B_r zPGv8K{1C<_@OT8iH+(NTT{oEWDuYGE87o-9M6D70jf&!<8NJn`T2aywjE$x<{V@#$ z0=w|N;rR?({NV7bDeS~vD+McxB=L<3 z3+@e}AM{w}RTBj(nAm*Kil$y!K_0rR@A-iCA#m5zljVgp6A0`Q$GkTBc7*9VE$bq; zP_Tjt$4yo=tolk)CrB+rZ@UahF+!$Fo*6SaUS|03HJv4JqzV<0QPX`x^R6S!=idp^|{ zUKl4ZOGi6_z%E?J@EE{TC%E)sD(g_kL#TZ)A)ZIKUe>U8_AIvPh>t*E7p}YbZi1oV zuxoiWX-VOG8Gp$lr`XWzIcxvT&A{)CM)P|A2pAXHOdHwmtBe&)?BK1}_cPc2-%N`S z^M`@Y=fC93_rC&xUHI+NXvXdt3I{J%lHrr|6s%xk|5zIuaAEDgxz-xZh0O!t{*?dd zyTgV8fnE6R;_XD20dTL+UfLkqNWlswbi9RJRlE4#9B#h%z?&YBS7po!=GGSo?85J( zM$G9ELJIBrQZn&y+oE9*#Md>rR;-_+rpPwYGVB$3IO>COGlH@#BiTIYg-6lyeURf*K?sSo{f{7@NHT~{gM4I#QXdbycmkK9uj+2|8 z3=jzHn$AaG%Z4l?7XM<%Zua9~{~KSq-uqE9RxqJI+KRr+Sw@E3QEO`bOXJ~WM{45|3EY+vv!htw=;a7{T zBszh>E}U_}qd5IXgV*tka``<;{xgBU&qr310fP;s%v>94q_^hZ>1L!sIz2vt_Jc;_5FedZMt1WNuQ4_hl)dSFgF;MQ^b{U{{|oD|%zcGUE1C zz30PDCqu)%C#0nZHp*DRL=taP552vN#G9!1e5p+`L~b>ddd}M^5ZG1qgpbiLSWMP> zsP}y9wRrGalR!c`9+k0z3HhcaHQlqA%hKuI}0=o=~ENO841;k#f z-t$f7v0!~5PLA!jRj%NfPC=P#{^cRs@V_e#uKAZQxQgGw(!^E7ucvxHT0e+^yJr{4 zUw0SCd-H7QSMN3C=v)H{(=Bw?G`H<4@}`|ioEZ@Z1^V&wB=dDLRxlx!u||^s+w|S! zF%cyKfnCwxtmxkhMWpi)^$xbLhy(8q@1#}*RK^M>7JuM*S$Zpo?;VwR)H4psH>F5H zLr)0=c13izq8|Fo`G~1{2cPIiLwnj#d$Q*(87r8O0(tAK&2kbQs1i3lBcSAMf0`We zS|G3sXFc)wZg4a-mv_rMBU5DjPT(tzpJSfo?G^{U!WPLXBWKB2!34hQytULV5%yh* zly7Sn3IulH=a~1S<|M*^ zFkf<=#)Ul<2<#HyC^!D)T-3*uO>FvA#tJ5I)*GMGU@;Qz-F+o*EH#wz*AmyL_zTC+ z<546$cz;gbHqc4N3MO#v%Ht(A2~e?Xll(qU76|OZUpPKW)+iY)KhKowjt!Twf(cx^ z@;N3WQ=xI=&a&_EaRPx|_zS1e$kS8d+V#5flk0P2tY8Ayu6$n6pH!$UERasGSt1bF zg}-q8>TXGaTv)FiS-e@s3MO#v%4ZzXBxsuNP4k=V76|OZ-$adOdPW??m+z-GvyaJG z!32I5cm#5G6dXR;h-H60FA&(3ja^*6^FH&)p6?M8-NcQ_1O7~){=&iQP$fk8hQX~F%n>x#g z?M$`Juzzp{47c);gWnm;Siyw!$C9=;SxnZPP`@8jYfXgW&KB~-CzZl)VOI;DpLqMj zBJyC1N}T_e2?r`>Nf+DHk+Fh_lcz0d#i|1GY>(Pzn5sV+EWesakE<#qOkh_A@8jH= zQ9wQ~Rf#fb5*+F@m`3Yr%UHq0W}bzp|7R|FGg@tBM7Em*o({X|`{5N5Ca|kLZ^<0} zFqd5KtP&2}GvNIMH}-R49T_W_Xu~tlF80hLZr4@f*6?&Fsv5v&jTcgbU9k4;Y+HDn_V;&aWo~w=#osMwJpKuq${AZ^OrC zllws`Ve+UwLzy(n%?x3wQj zer2h|sU8}rI1&mcSJalVf{DFN9O>zUDTMV@+oCS}-mqZbk?@Ysp1=fly{zF#AH7Q< zxt=Ov(exTSyg3r=8X3u0!9-a)&#ZAxCa)i>z3rZ6l$lkFho?6_NSMGbarS_N#cH-F zDFx=~eU`9-2|V|i&x#*AlZA(mgVlR43IulHxz;@Px;6&-%(*BRtePR@&EpysXMgjn zJ17N4_->F(txAM^b4=jcm9O|-mP9<+TyRX_ zx{|Ns^=1M*J|N3eU*rh{cHtaojb`-wN#Iv-M6w#VUBU_`a9zoFgZe!gh}~GJcuuZB zV3(MOtob<^#?>>TQMI=SIop`PbtTW4xHcIKe$AtQN^=APyKufRUrm=x1TeN`dme8S zGOaOz>q>sDoF+hb-yY2P;Y@+RE}W&yS3Nz!*Si0DA_<+C{^MS^R$J1n#HZXv4}6S%JAvxIoN-7Vk~3vrnv5ZHw?X!+VZjr&8E zhcQ@v+Ad_>VglEdd=-y~9x!-XBiP<@hCpB!&YI=DZOcG-$7AlzCTDAZ0F`@skZd>AIIUxJCh>z$~kB#8t!RwG3zjgPXs z7LgEKF+w1)3$M?@SL+#akF`BG4BE7wDy+kTiQI!u)MZE#>FKVP;Wz6QTNO0`Mi~~$ zc!n&Vkt-5g%U`m_dj^1a*m4;wn854I@O!@JHhbzl40JbU2?TbD=aI6-6h{5>hvB(Y z&Wm)UPx*KI?^Q$T@OdX1tw|y)y6`yygB|J0{A6N!NNoXlbgTt7w}QcUSc!}kOyHyC zSo=ig4sAX7x_`^o0_J++q3uUZe0$*vqFWFr^FdNhx zE(XpP2<*!7cck~)rI4%B)iQ20e#=~*hJwk9F)~&#fu9(SrjgNS_H%eB3{MCb2<%$p z=txIrrjVDhY8men?ctBq5V9{-$`a51Oud>ymh`GE?VRXHSBEB%Ts^+9G z@m1T2cdlDQWkCxFZT()x3MSsAIMT{fN#x;cwT%96ts!`uCD`73C=l2+@|W!32I5_}rzBU zFoB;QJ}drb186<4J!m>F76|MrJ=>bDpPNctuc~G299##cuILPVTg{QNf(iWe@T1~0 z6rPRi3Yl%j3j}t}X07SrE2*TSR4wCyu>ly*>;sW!BV?>#LVT_kw)?~^&h>%zpVta? z34TAseCiJkHE?82H`q9GtBe&);5V3m&pixalwL=$-hW6SunT8@^KaCMdQi>AA3AP3 zE@XLQ0^ff=(r}_7^qJ}bR}9Jo0=vZg_6$vPa1L;S9!Kv9+3J|U&oO@z=eK~dj<#?< z{k1?~7tTE8Yor`&1&<$_!*_i#!xR(vedOa&)EXjgHh}hrGz$JL?7|te8qI0GE6Mr6 zCg4>|%#_6ht}!$ksniipy{Hae!E|2$E5*5(3Z3dRV^92ICjCf?Ct$Q|ku}m#v{g@z_KpI1S>I4}pm=I^h zU-;4kRy{I;zV~7T0=pU(Skt1O)5!MsY8k2N9*~~V9RAcjCZCDs(Si5l$eJKy315XO ze&!!mO(5pYRieWPFBosq0%rW)C1V8>_=@oR5u-p%LM|v_RX-ST90WY(N4`Z2tLvWUS?_F z9+@Fy1ry@6nlLsLmYsgcu1zZt2<*CBY()=k%q0dr)iTbl83E+Y6}IKgWEm@%sK3jK zzTTZnY#OV?e`iL6VOR;fvb{hcuuIHNXuc{AM$Rr|J7!Imv4RPcW>z%0Umh9pNxiyd zjw!IgG@3nj-;oV{@30GhQTb|CuWZ1l#1sB}TOxcpF@fJl9_t%t1;*}eVc?-n z0)bt)Wx!{11hEM^VJrt?chdB2YBRmL?EyWw{SEX`$|XfO5?4i zA!mh_3?}fq$>(NRIKa?;7SQ|tZGpfp+*0Ft$bl|UIM@s-{=ODkWSCeGXHRPdj3WpC z%`)w}zzM2#F#)r@9|D10xSr=LNAfJau46TD=)YPDRxq)j*D*7vj3qsa)q3~7r3*AT z@s)KmG7$*u62BkSySc!w_)Ba_FLPlI7A7)y-9G3*D#_-vXf>KEYn&l1^az_e#!4Wt z3(sldwa))ylql^_y z;F^fHGR};H42LlGWlURvz%D#a!DmjkPl63G%h;e^Au?7lf$K-!F4+(d9ji*%^Iq)) z0=w`y1>a*NCjxRK%2?FN5E(0&!1X+z6Bil=l|ipqqnDlnfn9i6>z&}jN~YyrP7 z27#A%2N^4vz&#m_X2cvbu$|luj?Q%x2<*b+6nq>9YC_W$eIeT{P{s--#9q;hYtC0Bb^j~NSiuDD-D@;vR#(})xY00Zo3lV*7aphJyV1^P ztmJ7lDIDXzMAehljZ_}U3g@J&ruxI15V^OVo#3MS8!IT??4+G z-mm!ID%N6#>43GJ;O+K6c71GP1uK|19b!W-%`g7H6|K!bw135txg%3;sN8@FJjf+*$V`ArGDh=MlD-S_NJ&27W3S8P<&t+ zvnsGwu!4ypEo`Vyy>~L7&zr&X{CF?5aR-d1OmJ8JU@*lXtXDs+_!?+J+xM^f(bk$hW93-Tw!f$A+ta1 zC=l3%XYlda{im(r=FB{1-P%W(sfP)?LKh#SKW+}Ck8@auL9#$#7hc(nXZ%*hz(&`B zve$uKGR_yoE2iQ6JHE1!XDnFi_?P*~AsH)}!1KTO?6c%pINA22v}@0Cfxs@Df2Ywr zwTgzs&r_u6$m=pzFoEZP@mSxmNLcI}qSg0%C=l3%GxqpBuN@9|o$AurAn}u;_OyHb!KE|R%f$M~ua&eul0)bt444RK~md8W&$p_>CgFguwLYTl=?7YX) zEEQHypD$03tu5ojMrc!G0%x)F9?Q~nc>35()?IEd5ZHy= z*ZkQXm=53j?vpz3RRpnu37o~wv(=?^SeK?~L*8Ww1a{%s3OvJf?Kr-VBA*>_I$v0+ z5ED3yo#)A17z0V#Cv<9)Wdea+czy$KGo=g*?!tn>blX7eXG*8H6zXqKY;tZI;GiP~DQBgSb9ahL}WA_OJcHuaRM$@+MP-xM1 zGc#>_N{E+W0?*Xtdxj+r22cCbtjp4U0)bsP9>m+b&V9ks>?+&a;FJ*e!33VS&sVvb z*8|SPe`bSj>=g*?!f`F0+0WNonvwdAJjdz5kVpAGSYK;F?G{8JunWiM zG@9YRB?wq$2<rGPiMWFkEJ)=p886rjNIyv*>!V;E|qG-piie zsN6`J?fcqW`=cU)^mAy^ zv7sPXC@P%IioN%ailQJYs8~R;V8O1~doS1vHbhN!>>Um$Dk#{%-cV6d^vBKm-uv9i z`=5{V{gB-~+3aL8nb53|0{xX?4Vb;pDSF+iK>zqo0~XNoG(Eu{aH9FP9-#lCl`T`M z=qG(`zykN2{&xnXk%KRDvrnfJ`Pq;nu~gR|>Nhi$!<#M;ESPYs;mZ!Wr2jh!mFJ80 z=npM2O=LaYD-c+Pua@tFEbRftFbZSELUq z@L{i?o}k)i>RAx)i+e!5Ia+zoz8QiA6AR25u&y0X()9k%I8pOS4;YuMl{Y1A)q57z zXLAo8p@yO_`WX+sS*%wY{i1uXfBM&(C2vWigSx3FRQ%5G0S6arWqHCD!GZ~VwHnRT z^If1$ z2ai)9j)u=)%!oI=NpSUpgZ1mO2K7>@(akCn-sj1EhLzFKFzST#twWBm0~8a--0HI6 z)2Z}ciF!UxryC={xkd*mD6Ci@unO-6%6OiM z=e22X>acy+_R`nB>dC!NPj!SfVf~b@x3n_0U;@v)`8m}IJ)wVLfYNbEb%DSt{6zSB zKD7^&@7E}Y*P6=Mf(aZO;F*~r1EJIB{Y>#P5(uoq&y8pAfDFr8?NQ>RY=x_GIbVm_ z`|qQln;S_c{dip*|Gm_|T)p$Y!`s0Pzp+ZGi=FVS@KeC^Xzp1aZUrw7E>&vxwUe<0 z6Ji@%y9L8wr>)BGDy{;7RpR_Sc3K?#Y`sr9pzI;TcYCq@zxPwG6paMG>al}yhw1yi zzxBVr)?>+4j?nY#)pHucevO6mZ)-{MlhOqOtF~|QVu6bf&;cjZk-CjG24gLFWS+D1m)FnIkjR5>^B z3BeXj=&#me2A88W=a1UP*(U>`trD$tJo8B)uH1SrHkHjs5QYBOjI>A zU};0s>6!fn{HkhRn*nS8PLN8MmPnYus=2)FpEu9^JC8}DnKftz%(Xowt)2N=!WK*n z;6&T2XJ{3EY7^gGvvUCWxLs4?o~DzF)qU9Ml9ROMFT9y~_$j)4-Ut1xt==s0 z$VqyPpC+o&oIWxXc6#S3y?4ixwGj>2te^}!<<}Gai(U=bUF!@A3!mys4>n-Nt{GJO zTfL8rL*t>L=Sro+-B7aVVgvR(%7Y1fpj|jX|X=2w+|aJ`!scI^OoO7nfnZISUiqByl*c2=FRyNeI1cO zJMa^M@vq5a`kkjkt9;6~ueBlAf{D((eA(ce8UOFh;`dWwP%R6kD8NS`unIpzo~74% z3fK@?DL>>PJY7tLcJXDWeq_*8eyTFxA^mp}97~z31W8^3fmQfP^Ewl!dcdI!tz7Dt zA^23-8~9)T)$V>UaE+;a=vEyGTQDK|3@3gJgZtSZ$cFm|1p=$8>bzOh*rT-mb=8N< zUN-@5joC)F#O#vx@zd9D1fQnuhZX2|hx)Q1hV*~uon5=qfVH@FnpT>x_Qcf|@!->V z0nruik+205pE~=pHoj-*w=L?kTH`$xM)d7ZTJJw25LmUOk1s2nbmsq_WcD^-5|lk% zPMq656s`)l*V>Z5AN)tfP(L5PGcm=Nz{ zYIHOdmfs`23=0GTt2}=Dur?7V=~FAUmuQm4gX#T!#QX6b30p9M-y6OUvdTm-X}5}4 zE-@yUz^VSJJZ z_7LUFngaw|Fd@EC4U;0F(*C)M@udubz$!5YU>P?UF6AFpHZ`RLTQDK|B~i(JVd#j9 zO3C4y0)bUH{=iqsq6fm6&Q;_)WtW7iDtJDKcYyPn1GBY zFwN_1_lN?EqATR=`d$QEFoCNV@R9n`aH!NVkJRknSRk-UysAqBMnOgYnk2p5C1ECv zD+=N{E}zjCj)LE-nvs?#&Jk?E1YT+4YhDXt;M2V}WV_h`fxxP0J}-H4az9N-RG+S9 zbz3O@6pi9b3Qq?ZG-T8U;@|9 z;IpET(NG+=nV)37P#~}h|2Di0haPZgflfYN_oW_3xo|8C_c5NU_O&luol;$XKd_^O zEttT57e6Z{awvE&DItmS1A)LQ+

      d2H}wq{pb;)JAX*nf(g+htKd~U^d%=q4o<1fz&u_r~ zTbV)oS1aV>)z^1JA=u--vPT&w5Lkt0GJHL1XLne$^}KTQ@k@f^l=ZjPV^PbG(s%ad zdOSDe6|LWPfw|ThO5eb*1Y0l>+qoWdxp;)uc=v~2RqnAKV4k-_(Ov#75LhM7Ia`kF z07?B$DA}Vc%h-a6r6FEyw#gwHTB^Pu2Q_WsQoW`wJ3<8ltFT|n&l$Zk6($*Fv4AD* z2)1BCoOxM3j)y-pY?aP`A_M}fuwTkou-?W&pVslpO~>H`TLeOwJHKrl3ztT%P-eWG zDG+#8jQvu+8g3d1B}q)Vs+}dwYcYZ6>ij*2A+Y~+wo)^1nLuC_o)z=erFQ+{Mfw3H zr3&9GgW~wO=i{$7&zV>@6tvr>D9b%^g|9OvaD0ZZd996t$RFL6R{gFB1Xf}1gMUAK zVxZ}j=geUs6TA#e;5ZY{1nfEW_>v<5LktMBEA>k(gY~Yex~<)yHoI%FoEM` zyv}ycBuF^8T$` zEv&-6wnk%}J`!x_+$XcQ91#3=Oo(d}|Ah{Ra9(@I(=0|HunNyIc>Jnff3PSwk-P1A zBCO+JLR`&g{j&$Oi`B|4+qMx1tir26e5LwZKNufqDtELqlklnqZUaXtG@6LR5ir5; zJ=uC^g@i4bz)wM=sa_BTcO&`RlzdAdunK=g`6{ygSTHF#Oy;e&CD?)q{A==>vR>n0 zX!s_Q(6yC7V3qiFHnyJtmqQ1UE6P;ClfeY;mHZ^L2jgMX(oV#F*HVGND(tE8Y;~hJ z2s-adhRxY1cx0Hs(P$nQJv|n5`ntrcWvW1674|s!Ny=wqq3QaIQpo8uf@g^d9F696 zIWtCsSzNA2JeZh@A zomfO`R}|=d_3o_J>0;{jMvY}WwoXxw*i3+3)%*yyV8W}fJ8QhFnEHNDiD9d1LG;`o z%KWu8p%_U6>p8NPgYMCuH`G;`$p8H0FS)_cEW}$M zvc!dDHhDo`{wdV&f9=dt-#??fZx-oW+qtlO`8j=6qOPURdf_LZc@qpu_u2Y4-)b;- zqe8m6=~w;HCpFli`~rG=|5yDijS~yAFQn~q)tIIIl!kIt-(ZNjyt z?ApR?8ot+9vdz`8J{j4x%XRhCp0D5i)}67jJvG z-g^qc7EG)FcSfH)rw?pYVpT{xsO9GXZ#EAU2(0Ql%!4u4qJLh$MzdjIC|Kuc!E(h; z((9`mJJ|IDMiuBe{=k5~2Kv#SOIds@oyz>$5amrLU_ zsz?hy*I;w{KA>iUD@jR)8m#^P2Q+Y4CH@P3^W%F=j#h@~qG~d>U?TXh6Vr~(qfeUr z$J>a!;sNg(eN{}FxCy--_wZ(M_Uz?I1HJoOtw2+6j}cUC?*j=gEr|TgoegyxOVLqz%C;sjdgBwZDkQ zXzuGpqJ2$YcxDs?jeOb=Y{A4*XAf3TdA7Pb&y;YE7^O6Fa`Rv$+*TRQ^xB^YEjVa3Hx0B)#e{5LktKD4(%RvVvEm zx`KC6sL&HJalgc!I|jWLI7bGw6OtVm!Les6e2N{ujOX+nEAFw;)<*<;5V zv21$kWi_c=ssqdL%cXP98A)B^>{#;qY8j{1c88u{s>|4diBaDjS;mKl zv}-$cWC-`MQPx)O4NG!F0;^v3vt#=!=TQGUY8y9}RZ?2ZVQ|n>BV!9D>VhL*yUnAE zgVZ*@_FK=UTMdN2SBwM#tA*vvw znra(1TWdq5pfcszH3u1gk@5J5$1YxNx=Ky>GQbFWEY-=_f(blU@)+4|JLp@<8epNF zKwy=wiX)q~_a4>%^8mb}wBY3I2+!|W%h-a6sV8c%x&J+&X(QG9X!f)+IKK3R_kV2# z0;`tgJFw#)?$O&DqZ z!30*h9(G_(zPU7mscoF{ysI=QZ4R$IEo5xLgn3vE)_UGUI%v-`a}6lH{n@fLRVtP4h+twzkjH0gcjXW=Jsj? z%SSs41Xkf+mgkq8yQi$#TMyn9c?iEbCT?l$84Jy(hsxA88vOmBv}jWcc5QSO2&}?= zn!mO0e=5`N*MOIqHHE&5i6sH{to?ffef?K$t%4to zy=Bp-=Br`y4;uoJ&Yps|jS11G4(a6~yB})H9J{X^Plo7zUio$B(_ zuwG#E!JS|WCfYgKvdro^G~G;nx*JnU$=O+95NFj|Ah60L-GNzI=Fytx)i&I_HUxhs zBdBw}ii~|u?Bn9`k*}o&_(G*4=1`~XH^CN6U~iePc@?=s>yr);*}Ssg?_w1mA9qF(Hc26TcVGu&7e*m-Ju#S=qZj82T1h2n1H)@saNn?(2vuXB#^RP_Bv!p{4*3ASLO;|6CI$O`EbH?@t#-K&}R(`XnmK1U$1O7u&t zS9fO9Gh?Cr(RqR`m@o}@W*hDn(v%7{_8OgFCAHvlgH9b4fxxPB-5uG9fIND}O#Kf2 zdOl97?H&iWha4c-f{Ar?oLN4frKUYr+n9gZnq2xl77|YG7YM96|v<{TRJKU=aJXY|6~;tNc=mE) zPDzEdK|{5TiiuU_%US(k&%4H8_<#72QRX9q; zGY7u-$(XFaP*63Aq_Q=E4uZERkK1RzbmfnYIreqEV)`;yR_;+uU3ktEKLd1~gS^wMD@^E9 zQy{QPjNIk_b(P(EcYqp}Swc(?6TQc|vV>1XbW^z6Mv-TId8=m&m>oM)Ag~HY4f!sJ zr24X7t_(Y!8w&A6Oq?F$$|B$Jx$|JPjntJ5<x4GMcccwoFhg5_MY%I zYG~x%%?9(iRG9E|@pIGMaAjU2is|xySz$wJY2=IF20^dvMH04P;>8#j7L@j!)@-c) z9)bMVln-_SiO%bNeY>g6$9mMwn}?PxU#0Bis;mN1^T+> zu8gcKrt{b4>H~hdvXLo#w!KCrUfXXb=DQ|9gZ6i%%9~x;>?K9C&b9*mhlXyf>6v0` zv@chW{}T5yhHNGiUrd1615OETVB)y18{5KT$nEy3ZPdDYm~^xp4_%!P2n1H)E9Bq7 z+C7zp_6hL9s;&@qp6TY!u0k;ldXcNg@oT=*qJyLqH=6=E*0qJmHYUD0yR%~#is`B6 z>Q&7=t5a@8Oyws?G!_V~vhC!?EcO=B_@`nRXe)yc|@v4cf)?`^e>R_lz}lkPKMtdTXr7ECxkb7S_rjZOE} zHa?Fi4_UBn26T2dBiJ%+w;N00su$OC_4qIGad+u#=}i9_u)@elXaf@&3*FddPDfl& z+n6`TAT5z_CFH(E+#&VbYs(Q@qThN*295^TW)j@muzYds$B>8A+oY*`Ltysyhw~7*n$ahOso@D zU2!Oghqoc41Olrj%ywl}Y+ukmSJXCcCmGmG zD=k;sXyUISMe7pb*Sb0cTQGq~B_92l)0J$Um;jevdkO?rjlSo?uKwX`kmJ=hd>@Y| zO}fX!=*Q*+TQDJxSCemSCEc6HL4}2}KwwqYRz9zN{G3MgP}`^$dX$7{#zD}^mlC#M zLi{?H1>}$gKG9&*>#jgx74{!^{oPC1WZQ*knE&;#ge{m5eTJV7k4Vh(C|K8FwLoB% z=$D*{`bvCC2g2R0{RobDB-XcOi)!T1l{KnKc$UFy#2X$EJCAUfmp@yWO<=-zoGsJo zbLjW3YJ_F2`8kr(Yy=!%uvj3l3eT2!_Gi#B(l~xN44bhn-Kb#mm$-PKMo(dbmWxQro)%fmL`G&ONeC zJEf&_hC^z|YhkvHiR~tKETK^j-Ecr{!=+VAef#g>aO~?(fxs%fX2Ih=eS%^1Hgnif z|1QDnzzQ#>Hk(HO&r^(ip)OOyF-Ye^y=%;96HtFu#6HAg~I@nfUx8qCU*g zdqYInae^(Fz~5kAxjwK4q%ZM@W-YD>1XkfV6VF20We0y9_}X2|G=eRdz~5kAHR4Sb zC>+xos?5495LkudOnk+}szTWx)fuX}9U<6)3H%M_@vBF9%8Mzzz;}=$5LkudOnlvW zO_uWF_&_+GwT}oE^liuAV17b{%U&hD#ZWlQ(ggymaGZ(P1DLW&>Ag4#YPH=#umuzN z8_cuS*-+)_;L%`}dRQQ^3dfn$UeZn(wqhIvE?q~k1rzuitkEnR_=2S-#X_` zU;=-G`5dSCg>=y+9>!>93j|i-IFm-xV}>OupPm5KPJ|I`!36#W^WA_|hmyGE6T$rL zV1d9Y9B1M);Xl*K&7BjW-T7dGEttUHU`|x*A@@sT;o7>U0)bUH&ct`cd!HmpH)3GA zu_M72OyF-YAFu8{AmOVc;qG%Qfxs#pXX3e0am8eJi{W6k|BZw#n84p)z7I00vK)4G zAPj3}5D2WoaVDN2ly4%tkLd?*(|1VNf(aaR;2v^_gWTpz7ij4;Qy{Pk$C>!Z5b7$& zp6I~qh5Jj`f(bG1(<8pV{QSBM{j}GG%q*-DbEE!d`N^*|A>i4tu^wA6fiuMT8l4NmYaOat||xyen2*s#E3S+rZSxio0EHT$*4KuaH*OMBK@Gv_1&jVw`X zx1PLq4PVLCWzpiMrV?Iv#OslKq(1Rk88y8&Ozz|?uWV(@`gO~q59(K!Og8J-pVCZv z{c&}v^${KOKa)wneNgWs`bU=1rql;EesYuV46|cnwj1cBG!tq2V_VkoSr%P5&Qw}n zZp)nb)gGI!_7d-h%V}xbfw2B)Rk^v19Scd#reSU-682uOSEJF~x-(1JyCD?(cR0!O zo7u5Bj}3IiE)xl_hT}{XKAWg8SEBFsfWpC+vblvF>tLNti&vNkc`LYWzN=9(u$Y>? z;K^7^;i_;x3(h;?_2K-Mux$Z-!IGbAiT@T>;d|mI%kgvn2J9UISD%!V`%i7zsVmuZ zps|T$eZrO{hG)~9;U-cA|NnJ*eznuob7g+9Wh|~~IQV;)5p2Q4iX>b1rcySIxTq4% zOa8LvT?RqQ*FOS*RYSR_e<9gGPXwvI$AB#>ltep;ugbW{_=(~tjdKDt8oT8c%x!2m zbk6xg@ZU{oZ_BKX80ZW)Q%P)N<8wFV-mf8W|G+1LEtrrjY+2bb1KpUYUX_DcFXiO* zfiR<5sX$;==tmuU{XL5=|ELo7_K%et1@+;Qv#X4IAMVFuPaLrJqjLCYZ-X8p71)A{OE4Qgcs{*pB)rgda&!NdioW0~=pwCW%A zjr!T!6n^?tgZ_)^2?SP&v7Z34xc)QFv=H zG3cxE3{NN^mz$*OP@G-Gwu411b0Ha@Nh4Bg#wHD~u^oChLb0|;Szz#y@wX3;sN(Mt+tU_)9sizoOHl-3*RVA;IWc>;p+w~$pdRf zz^YnnZP||A{H^V*zP0aaPF7--USQv#vWzX55J%Blw^k~v)^>%E$wmT!RqM=bS@7_ zPO8MNN7oeB)b>C<$_Tb#!Z}0B{Nl6d))uON^?AK5T$YJJL zE8K?dm${Ep*IcSHjQ`usK)cAQ5107T1(Fhd;K7y$1Y0n1(Z+@)?=Voet|~DqrUA?d zc7wuNPl}N3ngGRsW!MeRai4|{sQh64Y`rBbea?7+={i>kYb{e_NT`ik%ER%)>n@hKUXj$v% zO!_Rr{bMbBi~QP z7EFk3j9qFCTaFup{$@>qz^bQiS~kNji)QK6XZ3x2buizq1IueJGPYnsymObHbzxZ( zM~GSRmEb3OomsQhWd@qJ+*}f$uC0F^&`b7^7x7!@yO?Nk&YF$+XrNOzs#kTRUu{0F z+d^Mcjg0>mR_!`t%{*Tk=(ZgyG1v2*(!nPXN}ig^_^XfSPA>Pg?6WqD-v2irTzTZT z;_T=TRrOV6Y{3M6S9tWJixK4UbE;$en+OC}ZLOhYTiRsN8ULxh}+O{&=?G4IR|#;sW-W)dd2p@XV5D<2G{xX_qZ{9IGbGIWZwVtGxOi5SeZQeb(3r z1Xkf0E0168Z5^ETFbV9Utfbkkv}|FRfu@$4O8@oOGS6NH`rW>|v~ii11rIXNzZcYR z6itq&O+F`q?f%7jOtfsFW!pIY`IkuZDCdJ=Y|pABIKOSF9{*iT_!wzfEC0JGJsb#nLm$U9Dl^8nyrc&eP05F+&f=mn6GS|{9+Eg}^SbHt& zos&gZ4=|HzfmJ(C;slB4P>;BmR-{tXlQL7%RpB+H(ASEK4#G; z-&CSz@mb|p<`AeDc#vQVCh*m2G=ByiQtn&}hv2|d0)bWjFZfm6%c9PT+6G;FRMCco zfmQicf-RU3?;~K%Zlz28FfjdV5D2U)YpG*CSF@-`vf4&YaCLZO+!IzWYeACN*s!>< z2Ksifnbe}Q4Lhe8Xp`M$l6g-XmVVGctrhj@-jB5h_mQ1o@i7;IEtoiKX2Wcqv+3M4 zm3Wcw3J31AhJ*RO0)bUK`PVt2+(3W7REf1q{lTqTAe`iN)$Zh4GrO2`Xs3nhRqYJ3g{LFC!s`FNO4x!4{G>G+r$fdtoS#3Cm|;dRfmLmm*f2ehOgtQ? zwsF9`GAysr9~w+*NU#MHxG(T|?ST)9!C?R-ol7RMpKaJza|3-o*G#HaY{Q;-8)(f@ zW|ByJzgMgbI4~H_HH;Ga6(%h6Y?wnE1FhOsy(&$k_ex3KArMr*r9fa6zFNLVF~A)z zRgqyz>_me5&oP}1KQ-1sbDhlpSKqA_;so#QTR>pPB|=Zc#K(a)Y)qnodUKDHdl^s6 z;o#ptjK`rCh0$+zYliE)xi> z!cU!_W**-N9@p@JD;~?qs4Q!?G9;TCT9`}tK1})hkufBjx*4fo=Y11=VCNry*ql3w zU<)SjGvt-)-#3B{F^yqOrJe$TRULU7JBRWe3L3Qyxu-W2)Cz{KLwpIgU;_7JUSVTU zBS>i!2#ei41Olt@`_Hp?TJp2#?n$t}$7x|?zyy9DdBiKy7j|ZcK%c^Jfxs#}N@z5O z_5+m2_JiSD)LVk%V%IWtY`3R@HoI>s;aM1u$-JDR+bQG)%rYf{uYU|wJ_-a@;aM231Z}=rX<2gsI208TY{7&$w(q&TOKBI;8wQTdjELwM>`bJ%I&QqrH-I>R4-X_?B3G6@c%(M9~ zl*XTWKtbVIfxs&99o!Y3uk2)#@7*&B0+1Elm{&timHI&uHvjSKhv$C4@&D)Z;awMJsh| zO@IEaHK``7A@LbYR}XpNympW~@Sq;AE@6T!)3Gl-vuP(=bvTeSH|+jpZ#D>t$PB2Re2|M>=xfYSpTqkRnJct z%e#;FhmU6aBy7P1ej>c0gU5Sv^~*5O)Xx$Ktb!CBo9&TJ`&y{$AG*r#NQWB{Fx+!D z4>tUN3nuV0~E(aB|JFd$W7Rg6Cp{xp)uLeTuTAyx(Vu>}*!RdlR;tAXB} zrxH__ogmrg$HCEaPQu^9syt^MyLs3^w;WZ8xz`Vov#xP4+vqp1x;tlfY=}743QCA?aYW@iwyU*9_8~Um}vD>U0 zU<)Sj+sscZIK78B@V#UseQF8>R()EiV-rfbf4x*~Blp>EQsehHm^9g( z?{@nC7EFlm`G6`(q{D?taB!5HKw#DTFdgg6=bz-g+D6j2Y2@hj$>0}kO0WeJmLYt^ zILmv<9hKeGT|fd6hgfxxQ7i(1yQ8_#F>trD-c{Rz4Kb_Sf2DidtML=PS>InbZ42^Xrw zwOSq6{?r-3tSbowR@EJ^WfMCYsE@zuy)Jn6i@b>7r^RM(*W)iF9<}i}&odwripZ*( zk>Kd+CSeOE@CdHaEZTU51TEqfTpMl|2&}@tKi}it;2<%ijt9?QTO@431Rjt1?&bNb z$Ryn)DA8XQ2&}@tKR**GbvE&T7Y}QtjS{wC0*}XhCsI}~Qm@xk*z{Bp2&}@tKd)l$ z+>qQ`Fb%#ttdp<>6L@sx+3E)?q#^I7!@>UN1p=$^@6UVtzBH+S_)J*gyGFtmOyKdD z_mXRMrB-w%JdQal5LktK44)O1Y(00TUlN$_TP0x&CUBgQMC z3PxrvBG`fnqOoOPl6h9oKkv1B|9CQIaV*FWR|*7HUE##1U>*aAQOCsBi>DE@7h}Oc zdOpDxOdRCjs3)BG-1#378%S0ji-Wm?_+A-at2-szlr9VCntrcz9BGp+I2OuQ56n%HuxPb5&yO%0TJjy9C(NbQ-}H zOib;hV{aC6?=?~-EIXuAOI-rYT{ur5u&SsD&q(QPpeY3^k#{+VRvtD5A~(kqY{5i- zI~|k44fGVK#L3dL>}Rids1rL^Ah44tJ1ddbsQf9Ef}K`DMnUG!SE@tBcdb07EHt~(6X__ zK$mn=i4D3S<>B=N2>%=?5Lh*+qn4HP7+KYwD&Ycw%Iw}#p?!)q!4^z33(~U84hCv8 zPbGHF9O`&g=3&?hZ_QcRe_$itn?1gFf~%&!Gtd*`lzF^(0wB# z*n)|IUpi({Y@nZBt8L`ytFp5GF_3J0MIf+h*jpXj#v}9*L)A9!mhwuGGsZ&MnzIC3 zFwxH!ap8nU<1Y0n1 zWvPxik1){v+g0LWf>s$Y}p(fmP<-Iz~Ta(JrIaHa6AlqBJm!hIU=j2)1Bigf+i& zO9LJFZ}jP1GeOB-7Y&vhj|v1?+|%cG z{$hbjjQVe$GTtQymabbV5Lk5}j;~ak8R)(|mAKS6S=nJc4#t?zB-nz9;2~NTTE{@k zs7f5KvR*lt6bpTVM+*d2r8;X_178DuVxq=H=Z@N-Tn`%u_hQ=+Y{5h)o&!x<8EA`- zY8#CVN0qS?W5B0p6M?|0Hn(lqV!on$youVz$GDS0hBf4IhMo>8 z@pgEoVjmw36_+myMT7gwg|j1JV6|fswqRmMybb%7%D>Ld zRpN5!S7l1UP-ypbu|Qyzn5}Nee6Q@(4u{G&O@uslOf(#2!-`KDsO+h>VY%anQm^Y! zsGOLr$A1f}aHc%3c{Y45$r&&L(ibTNkG0q@#p5I2;Wlt3N!t_2s}&w0*n$b{qjIlr z`C#(HY7{J3c1j?y3XhL`*YCuUjnDtoDC#kh^xLKwuRfA2pgorH7cjaU!&c zTTieB6WB-P(eq`tis!WPFx6(eKwuRfA9>wcS4ZX3>o{oGel5WkOkf|CSHC#YR+(-z z9ujY@76`1u^Aczo1oI!*{z zQZpyPrz!0SwqOE#oO~4BnyfsoH4*%t`wIkC;qg(U8GUoUvUKny_+xKHumuy?N9ENJ zL$@p6y2inSO=S`$unLclyy6M32e3Ob4)(Q8lduI7*yH5!k|P(ChKpig|BEF8fmL{X z!FXPbdWIZOZ3XiC~>S<~=d3-b+;Qa!E=j1rn zi|5gNZ^o|Yq^>dq=2=A$Y{3MM`|@>XZ+^}MKRe@eqcH-3Rd^oFPl@SujXbJ|ghp3- z5p2N(j{EZJdzE*S-i9$ysYj$hU=^N6^THiom0$}daNL(?)}+oNB@uD( z?ryk1U=^N6^PE(^$Fgn81bCa)fnW^!Md^hQZbY7VPJ3saj2&}^MXdbOieJu5TI~Cwl3xX|}*epbZ*SkAO zg%OEx{8A5rz$!eC=I0v}RFU3JmlJ9z$!eC=GnMA6!wW%(#gA|CD?)q9Bt#7 znE}<6s6*3W%*wwKCa?<6qj_G&7Bgkj*6A>G;zE~~U~5#U_$_E85LhMdgX}|Wp&2Ps zI%^xs*n$b11I@>F2M4IQ_n%VzR84`vDlt>GRSg}iPcef*ZCzw+!355M=5dB(E4V$n z2AFly3ItZ+yj~tXZ(;%u=D5RzYg!?H7ZYMWwf~OFU`y-5lT{G!tUp1TR&`K*< zJCoP!&-WDwtisvxeC;mJ8X7!%t{m>wM8+0OTyWB{N$>8^-zU@=OR&2&q7}&^<;falhIJW$|S{Xi(cm$Rx+Vfw-5ZZ4c_LP!=h<*1Olt@?n6F< z9LVd6)T<0Of9uQGf(iW8`L2{y3)t1KLP@yeEf83R_sa1dBXzZ4N5P4N@<#9>1G zJ<7Y|kZ3wSlV(bO|^^9N( zCN2s)c>FhdK+`S$;ADJ6Ag~JOTyp=amJ4ie?hkoR3c(gk;2lH!Jo;-k@MVn*`E`#9 z1XkfJO&%i)vxF!U0(XZ4!4^!2J9s*7s0_b9cYsmzj|l`;iJ50p!ZmPqcsnqCc0tG^ z!-Tl!=X>&JI zCU1la0+_(-B0RRV$VT!#8v!k?KMDj^;c5ar25_N^WET<%0n=X)Y{3Lx7vX0?STv+J zLPx;*3$FzNt8kqFzM4@tFL+vR6tLliLInX#;B^uH{fLcWJ&YsaasCT|z$#o#fcN&R ztytCVBjNMWJc2El!0RGB;$@k~{EZ@ER-Y#VfmJxqnpgNcb%VvN8wr+Sxk3guCh)ol zua3XMRj~~m0k*-91OltBW&Z#CZ8hJ=QK@<|3Mx&^CfI@rye`7mIcIfKoL5A^navLb z0;_N~Hb3L=LTBa4yAkl!DwALfCh)ol-}QTSmLi!Ag>75z2?SQ*Y;3;kchxMVn|}l} z7jl%vYOyG499)Zl+uXIk2f*XI93j|h;M!UKA zY37Lsl)CaL@Eku)*yn`_ye`7~E-+=rnke|{9xV`9CFWC~Nxi6Oo{fa>ms$~Q!319A z;CsoYZ#eS0 zny^0#6S$rbucqs22ma>W;qv@sJ^ou*h3gmbEY^Vm@L)t;c>8iCS##cul?;DGa~oJl zc;5`(5ySUdKJ$hDHaWtNW{-vawRpd?lxD`#^pEJN2z5rkCp7>%?+Sn(vB{ES#V=Y^ zzl?TZ7SciUUv!|$FM8~(g>=~D7hUc6i?(~N64PA*VA}9NX!LG~H0{O*IxDR*(=4%& zv?q$`oAbs@s%;@%+E+~TsWDqSR3*YI2Y@~;5W>$ilCoPpr41&UvXH0d(wQ}nsB+7U zMNBo9?B+kBhDE}c--n#EsKXI?|D2f*I-0q|?n z6yZMbwf}dx3fpgZN0&@huWJ2~Kp0>a0Ec|Mr43ii*z66D=oM-%y}4+{V)ydrlVmPU zo>QH5uTw~CpH;7FbapkEeIj4UI~O8{XPGjSxdrrVM@y-^Qg!ykrGOp@wUnk$He>fT z=hMn1Y8!8sn1H!OzOpwWM8+0O*o2$0{89PzXJt!H+&^yyWd|N8A!nKk1Xkhrj7GEK z`3EI>&sU`)Qod)m-zN*H)VP4!SX5^v{I}tLi8fzxU1b8J28GDjf(e&?`E+Tt88fS*5=~y! zgU&;F)T`Zp1n(fn`_C8bFk`DN9?`37)!)2UQych^UZAw!?JwhB3dhB8U*M~jk8R=6 z?pI31SYP2c#{`aR@!BG@?IAqot1|Jmmq1|EjiqL6`NMqbepS7yD$AUq`_eMS?1P7l zEtnAZZJY0Nhs$%Tf`g5nKwy=4=VvF^hMF}^!MC%yj4hbJ`^5R_5mo9z`U`%N($7i) zfmQga^L#inBZ%kmtI&>;&=c|di2E4#OIDeJu3?eVc0*GcTQDL19zV8N!OHD&ekIs~ zi2(0Mbk~_h z>VY!0U;@9ve9oErO4(Xq3#PHY0)bU(9X+-8|4%Kwl5t-Zk7RqeSmY&R3npx@=2PuD zGuHXC`bPN{S;9Bof9w6IB;#kL)|F8EuUcCIKLw3u#<}V+C!r23OE#6U1rw(-47|Rt zH7mKM-nmJmYVhNN2izQ>6$q>nuj=S44H%zsgOg@XGPYnsttP0xlWIjlo)^BXOz}@~ zhA!_s1Olt@6XEkHRtru<`op`6JBhk~SM^8KJ-kzTJfipbm(}o3=7ovt5B| z8%_~kaH8BFdipLW*n)|m@sH@n+h%MCUqj$uPTv5?9Ulm~sMdmKf&B;3%ZQcy!Tfw6 z)Lgkm@INpidKsT88bRNHKxpP|OYq;qs?lqT>E8@vrrD(a<|oSipu`~%sci6*fYbZzJd zKW#Du0;`tvET%1X8?z`=^*wL)*B^#G2!!PA)g|?;WwpM5T3f&`A)D&?&giqZ%_Pyk z8h^S8luZhPlS`Kh7EGu$4b<8O|5MlC*{dcH+AIi`#IFzttisPtquD>Y5!A^Dg6_T= zf-M5U>nW)Fs@0kb8cj)=A507if)cQ$~mmO(IRdwYT{m{9kg ztA6$W>_5L9TOZnN3Y*u&w!d9BZiJV^u1 zBZ39r2NT#+;}rz*{wf<1p=#n*Dj{JRvNPaNhLCWYGLsl2WXdXEn^EN5;m66 z@dwK2(F-b3Bh?X%3Orz;p@LuntHi#$&B_g`U-Sfz*PjWtVB+qjGJ5@P8Ev;zZNutX zP4JTI!`=_K1p=$^o2JqH_3(o4AL_$^f^)(fg^Bp0G8*-*jNb39wh?~Q8@`Qi2y5r8 z6$q@tBL?@WD||tD(hzoSnk$S9n8^NJMrrk5bfUA`hWm;}urtgbnsx{g2&}^67+*12 z*902P^M|_$_QD8<2|PpMdwz2L`JD%Vwa;N;6vZk$>(gi?KI`gnDFE6noi5A=F@a~3 z{N$73Kp0l!5Als^NVu{Io_UEiQY2ny@@q~Ls93*NsF8vRJcr{k06vZ!;^WB#KMlcu z3#-KX3~eC@7Vq_g&38QswqOF+hTyx&(}KY4x-Yb;(^#khfeCSb-la|ul-c|7o!)^$ zWeQ9Txn#x;%y~rXe^119il7OzNJw+Y-mKz;EddW5cu{E&D<6+zD3! z!+t4053-{-EZuDf7EeABY{3M+KfZo`rXKWO=?Jf1z7q(n68&B8I=*0<>JDd5-XPe5 z3GrE-_V$C6|HIW;hjsCM@&1FN2m%rUij)WMm4eSoEyO1ytMHEr7u)6~jTd+}Q z_Sj+&Dz|+RP|(kX|Z}w5kI+JZ)1gHT{!+5 z=O(QiFlwO$ea0}Fs#aZyH>nBdgUU+;Rb?D3Es8`D?@;V1dT_EXENNLAO8;J~Pzxnw zf62~Km=CaC9az+hNd#4;IqG=YC&J0J<@!aULl=p84TNeJYea_8ZeigV$?zjdbPNlvCSP4s|CWweHju#RrG6T zFmzl}0p6Uf28;4uN?$cf&{YP;S>oF?;FK41DEmhusEU4r@jg~q!e@IAIP$?t`kqsQ zt}-y@uDUrmIah+NNsbahRdn`&k!QGWzCOzVUL<%)vkXemRTz$m-M(t-&T{Z2GC(4z zN}gY>bt%-!954sZx%H*l5+$ey3F|bB&C}}on}T^`MIxw*dZy4jxbvfS`r&JBPL`@t z?-})S(YY2zy^J)#(;DwI^I?r7KO7~f#{y3xH8sN+WD}@$B1j^riq5rg&Tz^a_Dm=V z=0B^d)ItgBvB2{Nuk2xPiZ$5msUQ(lMdw-=vpvKarmwRB>l!vHwNQfkA8>|z%MDC> zIK#W)28p05I@iJ+TLE5BzJv=bIf6Bd$?T32bOgtfVcZ9rICw$u@oN%6RdlX}tD=Yg z&?(9rHr+nKsD%=A1jlnM(LoS;z#qnxTO|=xMdw<${^(Q_{89tp&9y{EEtH@mIA*{2 zuNIUjRTH#(jU|Gr=v)h{*TvR>K4~=}te*p;7D~_&++c|OPzTKJ)rLKnc1zxVs*=6u zk;Cgkghw4PZP`nq7D~ut`;y;-Vbu0LEYx*7)2mA9@y>c>DZToWeg;IZ02TfStJmWR zW<#oeQmAYF76&75!^Q2;nzGSuuXWr^#-1E z6?n$g7Ei9W#uKbXczSg`o|IjMCuTE>Ps_ge^-#+)FApxpnyUSuYrOwcdod8Bzy4tq z*xuV%_Z(x#T4B`L-mCUvr@6jLU9zt)>|Q&>*!Q@J`u$L$kpVqJHmG=M`^n0QBG5kBrHRSL~n9;xF*)qy-T$$cKSY9j{iZps&&f;I% z7O$Vw%lzCQY}>nQd3)Zn-k39gB<9Ws%$py8*?tm2^aHikL z3sO@}U}dbm8ituoAKtVRl`zZRuLqfY*dseJ8MEZEH<^6-R6DUWTfdKe%NxMxBLNH$i<`^}_4599rPqa4X z72R{jTv>Mh5wIP9dAvA@QdXebi8RNSt#+TYc_9>8A?5h^U!DXnhH-h#f#M0 zwh}>A)9^HI9n2USTYR>!bB%a7p zm}?xlBAc7w>Dwb8EtIVJ*}UgwTao+7LYW(%&1d4t-@nDDeh*9^4;^nT(GIm)V5AmG z(EGzLXZcvL$(pHkLvI!(sOl@;$HC{A+3~o3A2TsBy8YdjTJ?l-3bjyz_6UyDZV}M; z+GTBYw1xC!&?knrjqz7oqoA>(X@-YM(tS|k8RlB5o`^XVOY6_>1FtbKz4}4z(NvkB zD%yuQZ};f~7wej;h4ptEf0xeTiFl%P!&@`uALbbFZi`vPvdon8m|L_i8U&E^Mw;`@jdQP2;UFaeHy zOJWnYmY3dC`UX?lV7NSE9CS+E$h@{KF;WX94C}M`*iUw%CDv)dou9a|;Cpd56SbB} z1XambweY}HFsaX!WzAPe@A)aL#bb)+QN1z85`BYlH)DAM%s!i|;1L2NwNPRR=Bs&w znV{Nr)kg*khXgou?VXZVU@iSEs*=a6bxHAH=j6j?c+N3W3nh}rWb=BM(W+x{Hml^* zlOQvx18dT1zC=)!)Nh9Tomk;0+XrJH^BG;G)WDqZH!!l)AM?U{49A@m%w79ELH8QW zPHF@bTa|{u$pws#$aJLshG&EqVvhO=pY^AG*O;2nx2P;Q?0?Uwg%V+yrLZX7Rv5hX zHs1Qwf|)mLL4A@h5me=(X7gv5`~D{8y~mi;3|rVy+Xq}0{bO{`gYKTl_t8hShppwR z!3xaULoJk$*J=}YI70ouzA)bZwM0-A?L*vAwELu)^{NPE?7h|ReX@8s=27pAIn?Q% z2i*(7bK7rjX!Wygp!TDB>JzLlFyN7m@c)f53}iQp?o;7T-0PRx7xbk1t?`p~muP!3 zv88N*c6f|EG>WMq?O;)2nrRkqirL^hUDtcp`{503eLq|9j;SXRR7I~Aqea?OfSal1 z;bv27^=kPnZiU(1PnEY+k`H9@@>qdt4OX8j{F%kS4aE8bST6u`S#; zTIZf&<~Sn3|Sgyd=oUCbnc zswm0BqAXmu73#rhm7W)s24W!?cIQ}${fPX1z) zpsHC|*J;EXd$GQ_wo?ydf6(US^Z2uW7@ZZ<`SqCXIsA`}gZPNG#Bg3By1>X=&9w^y zEmS&pb}yI1Gb|lM%F;4QO1Eqtg!NLc7uQO$Slb3_H<_Y+m}#R@3ne<<$FDP1APX(d zpSbE;Z`il8gh)#Mb}wJm&!A8Us5W2R@hq!S3ng}yxX$$&VzrC2?`?7E1~cnr zi*>Qq5_okt`jhCrz!7>k zGlR?LT~unJ1byBxF1)@o6tyh@W?`-pK~<-*URy{+mx8;s=*oz1Mm!F0WDx zCFm21yE08`gJbf2?LnNKL{Qbn`B?7-Ye=~k&)XOFGD3CBOl|)4vMRMuf8O&TFsA?oux;cdvZ@v~+yVNtvLfAr@nv!Xd%ZEptt z$<i>gQLzjja4U?bH48;LxIm zw4$f0`0=$e`H1;gp)X8-c7vxCXf|1nFkwuf+At%N$G341=a-o)R7HCM^M1s>)NcQ< z1Mf3|Dz#98wugCfuA9IttOC|E-A^K@iuM9l!rX!9yu!?3Vydr7EtFV?Rpm^vy4>O7 z)m`hycCZ3#PR_mTEfG{j`we3U%Q`|o^`CZddKHygDDnGPCSSDAUL+UiVfo&+3fx@u zOsl)nT_UKeVSX0hg!LhRU~Nc);by!a&HyfIoy%2G=`Tgw8#5gD*9c)EH{{my+!&`;ap&%(yto*GSF`qR$gov0&QLMMT=+h zSB(<#*C6Ck7r4B)q9!I-N#8-LqF*>1OM=?MwS?x{*v1YjwNRpl$l?0AmLpH}-{btx z7O)u4%T(#_C=pae`w+8*E^i7&SEp&qQk?33R!qt4~1IjYMZXx z(Wj5OMTh78V7bN}k`I8Ys6PNtJJlWzn=amDr#{%Sn=v^&4D%Rn#!O}O3e9o6+KoO- zll}Ug-*XxUi`V|gTB=zJwNQdyE$%Mu9{^2~zOah}QY3<^xRS#?m)VO83-mTFx9<%v zI+aofTKXu|LJ8TI@uzxMaJH~hFNGg4Qi7_w`sVQcQ?cG}d%cYj(}%#6J2~uQL?~;A z87OyRCd%MNW(w_vaas<)j2VvaMe0PY8G~WMhyR#KwlAX=O3)s`b46|YL0XruY|~r^ ziJ+qy$w_k2luHb%}wXD|1=uWDB+mqYAw-%dmN7 z871|3HXlFSUep^^Mmh5-n}5a3$L$yDGvr}a$HM88tC@M9%8XhlQ3CVNjXh*9o)%|m z{#ZB$I#pf3syt{X5mfcJAy#n4XF9oq-o~c9C@?c!&D?4ZWz<56@|Y>q9&>h9Mc)}d ziOr*6cF81`Ryao@sOsZf%!-HE@vQM}#^0k>IKY9$Z0vy*j9Mrm?=%#=nFuo)v|yry z8FR!e$!9TJay`tHO#3ZM;GC$hy%=Ad*LmTD3GnjO5Z1ux%BY1Bv=6av#-Z`hB)1cr zc)F!TP}Tjf*}UU^d(m#6ejokIj)O|A!&pXae?~2opnZt-APdIA;wc^2>%^H7K~*N0 zBlQUOZbortRmEX6lo~&P75rGjsD%==4{_hQ;!s%Awgo#EdxKqVex2*tzs5{8Q@ShH zxqj+!-a_gekg1~cZm zvtElbB!a50&O!pSE?zFqxcDP53>v=9Q%Z;DFlwPhYm9Ep!px3Wi?cdfxktbU{~X2Y z#5swes^v9ucuRb)3X3x?7Q}@^c&VXE$;7LSS}2j=n!`C}b{w};{{>srih{-Iit@q} zB!a5cLcOAyz3Bd2CrUq!fS8Ye8YSglWYj{5O4o323Nt%SEzas#Gh`Heo#w@#-#RG~ zRCRC@=F-QkizkXRE_NIl3D3^-5Q$69GHRiO8D?}`fSDcV7H4&w96t*B9hfVW7sn)m zsxA)6=1(!};*sKvi^1O`V2eYZXq%=nYN3P=W^~+wPkXK6td6PGB4CxXy=IljC4#DY zVV1(RQTD>Eygm!x@Mb8)b?>09{_h&27E0X0Y>SPtevNgIPPkhPgap&++QmsXC4#D` zU&~;qIk+XtoUcd3M};FEM>zHLW%vdanHJT0wI3nl(m&EW}VwxV#Q zPGr<>1!sf@9KDffqy$yTS5+mb7Ib#5iPL43I|K7~)9)kh>USLv_3h1B$+pv_ z?;s^6V2q^t-#W0s85Jdhs_5(kciau}a9*5KD)o1g<|UK>tkGbGwHgi-*J%iP z91l68jwnA{my`&qx{G^WA(%OPL~)<VUB{oXs3#vo;QlS}5U&H5$rdtp=N4`hDzr zH3d#PKW+TYs)R&P)vTVl^MfAx7XRr)(#3d~J!GbMlyA?dg%Vy2_aJB6i9?*&PxnUkQULj~>BJ6lFAlvs{gx#zXPx-VOGLc{E3 z(@XhiI|BbIl%T3{n3a2UT|3cbwoaUCF#)o|Mr)3dHjG**ak5!9Uu}Vr5pQ*(f97~t zkT6Zl-StbM1XWGN$bp<6w&MH^o#=6MG-TA>uDvW(j!_FGzG6+8D_3mAy4w01wRYbq z$n1MS>+APJp#)WJ$4WQhn7dY~pc8Z74hPoty4Gu%6{8kP>_R_dS**SoK1L^Ay&ei? zCmw1a62B^xpsFCua%+#-ZaanO#Pvaa;7ZtEEylr;Q41v+Y1!O}^*Up)RwwS)_U{Sn z2bF>ag`X5kP}S&c{4!wO$wf&zVN$;%1YrHzsjEIJ)Ite59%I(ixh-IKcTZ^9v%Nw` zGCIP^#M1ul;Z6OD(CJ^2G*VN7j;Of*QPdggkF*2d&if>Ss_4~XH7K<&gom2IW~X`5 zeNci%z~HIIO#|R}#20P(-~AFnRkRP$xAZRz-qgLW{k=b5>Rn36F%xgvMu1P=d2PE> znnX|)eHILc=;UZP5R}iJn+1;AqJ}UU7;D>4@m@7(PtW?4MXGL#M!=@ zbEn1f(@tVaZz?;G!BKN`)>8+&%js3x>`vp_L z7=BkIUOOrgR7J-ajBjr^6&|s74@CqH>!ISoD4p}=A>juei%wn zFCMmWI||a4q_TQ-tr`7WR7HI!7?V0N94=JgY|A=tMlF<}{xUp^oEZ+m)l!*V9B9$R@x$*Q41yHnf{JhBOt8lF800ue2Jhc*(bv)42C1|7nyIs97Zja zpeqZE9B>!}`%}&`<@Yj)peh=9io1OQEnv%XOW5L=!sax3+6ixRo9=v3Y1i81L=^cXGB% z1XX!r&EGRv`!^r!{$gC;=xU&CstzU0lBLtKR7KC-8VtTWtHbfYs*vKbOFE%I3ECch zojdzN@GL**o|GmLR7FoKV0Qddeo!{v8&+vTI-5ZW8j*xmL%Vvw+UbE%Hu!=>P!&C= zfqv@hZty2I0DdK9GisrP9KDmY!5`KfssYZE=1YA=*CMnRFze9c+R$f-KeSJeVbnqi zx-Kyoj-6`+jZSz#z>|3rK~?lwz$dXh8g~HLOqGrMNbEe3{lz zVskmD`Fg%YP!)Yb(OcW5Gjv^O1~&QQrDvBCcW~C%0&AmBp07Wy()i zK~;_X(8E$_D@x-k9Ct0}^n?3NpJ<8mhBIoR#N=S~6y32EFN?D=1j}h?p}$L z2&$@XhkhSFtWx2vx3M>FI4rW(wAhR=MlF=s6o9Jh_w+gS+VCiNQE#=DWEsJzg%X)wcq+ah)@v-TVDI*M6pZRMQ?t%VkO-<; zfZnLPN9;tYxq2HNlcHhxg+W@vnkYsslvwAFF`gUkgh`Z6ggTFdkGGjtro?oKpsEu1 zdz{C(jM~L(9QJcOe0c7lr521~)Iy0(7;_hftGlbkHIcfEi-qPf7sclf(Go#bG}aw= zUpsY$R%M=RQQimH`IlMTh%1vHo60J!Einu5TU@1}|Keay7SC&CC(?WCzsDWu0ZAL~ zY4$F=8MRPi>ZdHev!R{n*F-0_9q0wu)?U^^E*z2ws_Jz)i*HzICw7(7iC#xBzTNz! zHu&%!MlF73*~K=EgK;7IMST6$5TG!zFn9-Y0UsgVAr%3zZXdaRne~m=Aawg8)nvisMTt)3=)ItgREy3JWnBo75V|_7tXCsNAD(d&c8Cjh;_}>1R7DHPTK95o7`0G>eyQ;{A3p&+FLc&CO4gGIs-k{B zgJJ!Mv0xZ5Pb=}dC8HKf&>072`S%+OO&ToIng`aA2&$rfKU_^>Sg3ics+-=)AP?hW*G{4pu+@t;A*o?A_S|}m!W)$A351Sj*fVk?{ zCGQ|r(X2Y?jk0*5Ek5K7EyI1J$jm2rmaM^8M{(n)neq_h^heio6eWA;yU6`se$-CZ zcYvw+ax5oR(I`ZNp&+qH+v8CYCJvRO4Jq;LaVGB>;UIQJ>OTE}*B@&M51gQ~V}KN& zNL4g85}(9#d0HcHTX@{RwpyiTCQrZ_!HGQ9% zLYrf*@O-C}L{JsYW`?IZYCh0ROO%I2IW<*!3U}i3YkYSKMw{W9gT}z(9!vlGTGKN2 zn1{ZWN-dP2zY~594!zgL{j!F~pMoTUs%Q)>W_A4UySD7872I_TRH=m$@^Ak4rX{=! zF$1#%Z;7BP8a0caq8?7rtg%UKj9{299dBg2PFSMmWE)qdiG@=!Kmcweo zmQA@@xdKO(S|~wd>+$RC-w;X{a?Li%K_aM%#=v6UkFiam_184*>L_cKS|~wd>+!9v z(+XB^+n{NYmJ&f#a%}C~Tb-cI$(h=|H>IT09F(B3_4w=tgh0ljCfbP3GC@^xG_I)H z7bfnu*2)h2#i)f6^h7qEg6J^-Zf(3O3JhN)f~x2VaDyScXb`+U^F(R+=>?+^RP;1C zje5fQRog-Ez+tA6QTU!w3nl2e8C=&U4h8SSGnM|4MG`?(H0lYx&TWUl#Qe2J@4>Ga zwNQdaG~Mm^z~hU}r>e)qR< zKK+nU3nk>U8I|ltKy(RnZFcN+iJ&SP^@RK9Cx$?o+BLKg%ymyKl%QupaMrhcFpRYC ztWA%&EfG{j1?_UR?~Ga~LC>xk47O#O zLC*zuwP~0Ym=aV)Pw?UVs$B!P@#DD`>R(!=7D~`Fcv#coBW6z8`dM2(x0FOsm3&6= zc3pp{G1&kMMp~-WLJ4|;3nR&Q`ok5)6b5xEBN0?ZPXJ?`AA={nb2f+2YUNaFp@clk zs8iq#$xfE=G1*KasEVE$#@uZtm7%Vu9o%y_Q>ld#^0`#25MRtD=LkFMy}WFB5@h3-RTIU8AxbEE8TT67}9KqL)ZDyY{qvk?JiM*Mz^Au(`_U?E;orq9oQog zR3*pO{)-KVA6czge8^!ba+wk|x)ozs!lJ-;mBI#$OOXhwqH(=APy87LgGO4hh>r)P zXevt3=vK_Pw0{h=E&oq>F?_2;P!;uxU{1iPV_+KFqIh52Bl$}xL8Ds@2IJ#sNb{Yh zv|O=CBB+Y`PH^q~V=P#GTw&arpTekx5;VFM_YHoGgHP|RPWqN#FA-EleVI6K?-vcp zBWjBKeYQzHOG?n_Ry_YvG8(=e-yb>Z=Y(zE?`n=vMTF zW0mo(UhTCU?Sw>774~>xvsEY1c;BH1(XPBtm)$;AGNqZBNpr^hu>g9V!C}sClo3jez zsmaa=RZ-s}KD+(ez{FP{wJ9N2q&*f&(7X+JKI&~tXkcRk3tyd<2&$5OmcQ+qf_p(} zNZ6IZsD%8a+BGVV6{jvSYN3QY?zUP{1G=qq zfuS8QN(5EW-Cpdgoz9SemQs9LWoag2pVrD5mZHUT;Lj~n+3F0E5qk3s>Xid zq5TnONeo(b&+U*%pwO#Wr6 zQ2!M@acnSb-SJ%;w9X40H#n*D+U4@L&nk$Kt4k_9OWx$=n^h3MgsIZ3?@ivjS_RQH z!xXQ|_^t#zQ3AnznVGsE^fu3UTTxu-Yoa*ry3HGAR}{8`Oq5Dn@A4~-mBh&7fAFeu z2AV=tXmxNMSyH7IN>u%Immg|gN!+;j8;O9NvhcU40o-qSk4lA)Iy1%yLmk8xT_dB{VfuXWy{0I zWzAvy;$^H%Yyp2g-(5_ZlW*MI>Ji`m(M@EPcw%h7;So=`=_a!8izeEdzz7q$iO+ef5j(@{fg1Vx5!zn-}ekhva~- zd_Y=d=6I`!S9s(m*4@fATBQ{7^6lKjg#3p_v8Rx?E9WLsuIlf{>bc{=&?Jfd_;X&V zf4qpluI?sGcjg*3{P(z;ZXyQ%J$-&5FR|WLcyH2)X~pTI+4M8 zw_7C%oqOVzZLk|)?dAx;x6T_ zq=fvfH9Z;(_YQcfx0Lk~K~?n37e+b_Zv(+yUDTJ+ClqR-#16Q_EeAS@YSZ=ax&Nt7 z(0I75x~ilVqXbpaGhgVlEFS`+nwC)y^>Jg=LWyRt?(nxsPNK#py$!?L9xyPt001?@@*{plhC4#Et=+8wB zhQdnAlkDJ}c~VAFN+egk%O5^<5~J?uZF~(iK+Ypy@T_Vr%`)g5h0Y%g1~J_f`dE5` z?Erg~S|}mUWNw$S12&-oG`(sg5mYtf?`+4VS-mR+|dyxA1;Sq9S4P)!Ueq>;sXNzH5J@l|lXbt6EwrSn8G7>>mPY&PVLDldV?4sX!`jgHu z;_-Bie=}97g%atn@9>ddDu|A)bYjAmuUgKmDsX32MU~Eq>HM1h{`h{Z`Kz59QVFaM zyQ$Pd33(Pi<#bty^09%JH)MjU=p{_s|)l${zuyt z>Lw9XMSmw;53Y2F^}}CkS6X;VzaS-OrXZZ}8iU~6njGzZK_!WxD*9_;e0zx?$g{Yh z{k`L^QVS(^_oF$4_EfJ8|JoeWekHg`1Xan;uAQ+F99U6Z-S&Kgk*>DrjFpbsIEb37 zc!I}I4H|7Kt;r}s=f3D2T+|9aMY^k956zVbs-mMdK8cC#q1?d=>V%MFg<2@lt79IY z;o~fZo9JsC``m8eG1pRE^Xh{{P!%1uah1BECzRP@s{XY#FlwQM^VB?Extp^HsIIqh zv_XGxfBlxNUKA)1R7FQ^^er783?6qLvco%SFlwR1hm<`2FVR_K_0`+h(|b60o;%G9 zhXzRmRmoq2ro+PF-qL;SRQy0jEtKedK94UwhJ7_xZ^Q670v>uVW=VeYB!a3g*1pS+ zJ68}>KI&hb>3v7T=YVKt(P0jw7D~LimB;PhIExZT^fpQ*je?sy>$2n;TP1?34%NBK zPj;>#j+fQPl8>Qd!5Ced4gRx%Q41yR-OuBzyeo;c2YMTKT}MH{gJsI`!RZn~RV94y z@+WgDh((@y8`A^EKz3^|w!N9gsD%=1Zsc+E0hPp}e|j5}mWIRCE|`lm_?kpe)eW1w zyed=>^XlnsY`GZ$tri~;`v#t6)Iy26B9FISQ%U^i_8Hsg@O}t{#@K4dqVgnys^oFk zamY|8dKs*>>u{Y>3ndz@&*P19DhbPmdK){2_lC@z$(rr*R}w*0bj-&)x9JUy#;(>@ z_swI}LW$ICM@85j&s6&Yl-`mU{?_nJ`)B{IJ}n?pVM>&VG-seHI>SLPPOCtO8f*)CxhYXV<%8+w}wR{nls^A$U6@55TF0#N?x2%5rw>J6A#hjUoPJH z>g}#z>Dmm2H|xWwh5CJ{KM2oSUhslLs@ELG=*5ira9B@Pi?*>VZ}F zzKmKZ@n`O1-f4!raB$AUs~WEvA?SA%aJbWld0l_Z8~1V-51sOiMJEdRf=V9Z7yezD z$TzJAtvv&wrhf}YEtIITtB@;IJw&A87PhhXS#_8nS{n{GmIGOmlK6knHpZfkjelNhy7!sJK+|KaZ@y8qI>gXVrCpyT9YT7VcY5mZH=H~iLK z8VS+;w`vDXXGqT#B_bXb@DX2JMb2xzjV9m6z~P%ywZ5~$B!a5wdt)#x+7=CiokFz^ z(Y*32sOlnAP#??2WJ?>!MVw!0)Umkg2Kb4rvf z|CmQlcNHP$^){|}Plm9rIXw1QutZQ5^}`zsiDxFkfviO1^@SZIe>)|1SA5Ldv~(4v z_v&q|FiwWC^^PdPXM!Yxs_5VCKq_Ecj&|Y2Sbnr)(ed=Ve`m$zr{Y3#BH) zOVjqO>LEvopeos?e{#!s2+bPDy4G}N)Iy01zYBQyP27(fqqp%dbu5&-yn&@x{VDnM zsY>?HpNbd-ofA^oukXJke>){I9~AJcjV@wv7rl)+{$cRF&UI$m?S@29mF%bPWETv5 zGUK(KKb<6x7tMM~eLy%1k8KTGD)!NKCpf6oLJ69e71!ryI>V8Y9ks3>EF^-e=t>69 ztCi>u1N?0+Z>qH5fZ5;DVsC^(~p^3JqvOyxKimu4e8-;6}!);cJX6H>+YM}(p zfsQ*3se@qFGEd=t{k^nSqbj(@kJG@LCdVbG*-8mqWwpF~g<^;n?iE^8?CZn&B~xV}&FOi+Tx$zg=)gdwoH zUMd?rWrIXemF#by__z@)coC#-*^nSb3(y^9>Sw~tk+~{(hWV=V+%lw?0!q+bC-jBe zwSmAQSM|oM?h5@|R7L$v2E!$_BaD9KsP^0#rBDkc=sp$Zbea?j8?T$Ii=0nN1XWQ# z6Z!y#^np=lP1LAZO`#S_$Rooe!(fOk_l(8#D8(p2Rn*UfHIb$dhi7@YY+GPSMlF<} zBM}lx1k4$Cj16glIRS|;jH;-g3D5l07!6f2|7L+46Smo;#5Q;+gql) zL{Js=GhrOE!+1Cn*^9xp){I&xLC1NF1Be_Cb>=y-yvq|Mf~u&W2`dmki-lybo64*` zVT@WRLBCf9L&5{Rs_aV2v)&6Of~u&W3B5RRu`t}#lF$5-$f$)9^t+4M_ezh0{}NUT zyV)Bgf~u&W2}d7o9PHopRoE9SX4FCnI)5-2c7Kb6r)?W+3s&ux2&$rfCS0Xnj)cos zBea{h*D-3L1f2)rZ0YV0xY>Ax*0}2tiJ&U#XTq6G)?m0{x=$OmXB(pyO3?WnX6F9T z13r6XXkKf$L{Js=Goi=JJruI6^0h@R_b_Uq1f7@Sd9}@L;OOMBNzZ=`v+@FiAb6q+xPMAx)ItfmPB0ic z&Gv!z6{>>k?TZpYRn*Uf@w;YT(0^2QIMw7JqZUfg^$wm5Pjvv(GY#Nonve*pk|Ui; zHnxTP)tW%5$o-63C?Ur!)$qKic^&Qr2WK5)Z}%VOdpG)tn~86YRuM<|>}P)B+=$o4 z*FO()ZtX8pLSN&IY*nr8+N>KYyzE+Dty?RFPY(4KJAaxg=Ns6+^0uftGq3i(>56 ztzKOq_xDrdiV8dVt$sej`p7?HXNR49WnUlM=lo~Xrtaj+5`4sFQ+*epR+7Ei*{KT* zw|F91C=oe!E5EhETP!cEhQKkuIg*7E>*pu)Or&2R zZ7`T#DXTtv5(423;v|Bq$$svC&sU7~ z{Ae82c`vX0yPELq_YHrK8EJOvqZ3_VdCPQ3Md==!_w$DNzT(WE4@hiYWUlVn*#mYa zcq`OGiNz^t{G^G$SWxp75|5YLsatP$fo7lA8!16mEz2F`V{7<}?7q*DNNZ`Xo_^i~ zR$x{ZYN5pJr-%5(|NO&Oe&msOH)nBY$q!TOh?bJnk zxO09u z{}yc{>EvO)vR;5ln5;(vRw-kyHuUHTbI0cysf7~q`{9ykr~dc63pD!POd_aCzN&Ip z%BZ>Bdcw**DMo6c1brXT7w&DYTDkXxHs|I@1Xa-ETmy((?YN3RiM>?;z zFF=%frT5jVUc0sPgQMVeVr_|_s`NQ0_^$eaqWTBDjo`X>wB^c%bRq|E&j9#LJ7^C31lE7XBALEvv{Kdf&Mbee5IDV8bwg?avH|k!4=^ZC%ZXd?N z>Sco&wa_c1{f1-7g7Vt$#}i<2m`qUB2hXGYu@k=Ylk_&exMqo-@wzpPD^lGPrs*l?bZZI{yf_b`B7Ay6SCwW3`m9ka+lat16=wO3*hAJri>-YZqGd zhHalx8U2Re2tUfh+WCuPi(dTC_q^QGW7@$#10l0;3!`6pO3+@%2#Dx;TK>h6u&&Yu ziJ+?OqYm>ZAAjLnN1roTkBiXS|2GPTtY65eg%b34!gwDa3+?sWaWKYnzC=(}>j#Ip zp`O2Rwb0urv-Ff$T00gz9OD?ZP=fwW=$VMkXlzy@4vwskk_f7r-r^7+*ATx^_w;Yn zg0-EMIxQzb$ly9QacRf+s4Lh%7mJLv7jQ?>a9wM9 zyg$suzM>XNTq&QX0m7Wr=|e9xIG5mZH=eEi~I?ZME+1L4(`Sm_<4 z#1PkXez|9W$Q-G+vAyIitBW9l;}QnA20o{nrPcd zCmQ+KE1!bKKyZUJiJ+>@t9J8I$v(n&r#|Z|-6l;b>o*1(9N){Rg%ajwySd*kA7MH} zCz_?TReY@@;mNe~5^A1SCB)W`+)dW`AEYYN5oRIa~O>X#N6w~l`5_Y2fdOA zs(PEWg&#oTYBAwCdy2NH*cZV6;YujHAg@a8p8MRQN@s|C3%+qQj`H)WZa2uuVxYieJDnFG7s;akd55FDd zBOLSf-W{>ZUvnSb3tD&@)U{rF__Fyv!u6s-n%&E*iD_SUYLD?8*2rXAm99B%3ss==~WCJu!P`_Sj)iyVqlhpep)qVxH8VsiN(zAuzk!6X_kK z1nqT$A@@!vaWOg^Y=2yp2&$rE3|3woktH@^KJVu|QyNPsA^(CK-^>tAiblb2%cBxO zRdnRT3^X%dirI^!z-#GIX-uR9eYH`4;dg0A{3JiPHHW|A9?Z|y>b zS}4&!`xxKWG*C=mpwGg;-a5)Waz;Vh-xDN)s_t(*#>?Zp{R*C4G#F|-Sg_EJ@vtW8 zy7KMvaXtfACfYGvJ7pZ_lknfG@ZTLXkMd6!0z~at{iPS{xPVdjyep~csq3MHuO zY1m=D@3+4Q{-*mGrZ-x~V#|z!O@XBuwNPTu*TejVO@Js_RbLzYy|$D2B#wbYJ+3K~ zpep*j;hDI5i`jC*c_3HiAii+QQP@4>X%irA)uL!qP6Sh^}oP`?I72z|ZDLc+s< zPn{zXR7Lv`>&o1E!AydOz@TvvQtwiN`e$%eH1QUjcVYyzthQSssER%dxHj;9#SW%o z7J-pVq^E=u)R%=hQhMECcODG~n}3%jf~x3SfUAiMui5jTgJ3}T9)(&cL49%t!=tWm z*@4hOaHNWm2&$s*CXQFVE!6dY1$cG7!J3E7``uD`vyrgj(D8}VH7y;2qR;$j`% z36Wa(-d51$d3lx2STa^_<&G`A#Kab6|1;}5++dUz8`cV392}&%4<&3@ZRLMkc!^m^ z;|yTM0_}NvbJ*8bCa8*fyzvy>zYW^s9*y9(!Bz5wQ=);*Hr~g@OFZkXxACgW0d0Oj zOSq9-My2!5iH>{upC&$HN$rnZms-p9G%r9ClU32{10ZhMrkml`_h}dv|H`rQD1pd%x`ngs+ zwbp||;pwzT5WH?4W5?Qo2H+!$WEPL5Vu&5AuQk`HC%f^=S1nZfCT6C%VIo zLDwaMs_ecUWazhl~NI-rFT#1|{TKU)vY`wb^bFu(Z-{iJ&U# zt1%c-kIc~it{MjM&C(^G3?<~>qwXWj5|Y>tPW^XEBB+Y)2w^tej%T#*vqB-~`@UDG=aP`a$ufS z@hp9GU5TJ7>IuWh%zmxe7LQoa9@LQDK}yhB4bFX1Tv?QTEL_!kN(5EW_Yu#Zf9k}# z`HhF~g`F9-P=e0RFb48URpzx5{q0pJO9WL>9}s3}s?e9U^oWL1!EuaQC_&dEcvdE^ z4zsfw3n@>QNd#3=~3`cY+}?x3HrQY%$;^s;f*4}b%Q1mR3)#^%ccIO z_%0d=yWFlwt8Gfi&+eYOT>0cb0w(--TOz26`nB+6*quG1&-jV(eEbMze6^IH(bURf&9v6K04ImKbj zY`!DFQ|z@bhlKf$LM>}&3%Kt0oLN+#!Ap;>A_4|jD`yPT_{No9BIuo!a&W;^eg-{y zrk>VFSfy;%B78&O>y{Uc&6vlhzNsw6_qA3Yo|w%?&hZpMv#b^G9kcn}C{M9AT_;#d zBQ1R607&zA#!PE2GB0zk_E;_mdJm81D`+-28yr#ICa!#`^NqVTmoUhTRR2OYlj)86ElkSvs-?O_~1 zub5Fn@7;DIqQP?HcCF2?c@jZY@_ppg?*;y~ z%^(W-JeLXlzZ@TN=ZS?vuiXM-`8q!z(QuLe?4HCZ@B176YD=x>7%5TW+IT+ehmQz6 zBh&aKZW{=_!@g*B9?db*ze|b1S7Z2sN!3JFd%dq(UmgYpvkJ7jZ{|w`Rnb1g7|0}s z`QiMaL{ukZwQBJ^G}~J&>Sw78A2x{}=~7h;FKwxu`97JyxaBQe;`Q9o50*EFCEnif zV|qU$wNPR}a2#*9qpFyhrQf+3ZwZ0^m7ztjiS)OqO75$!bvwb7R*qmAJHtpVl<@f( z%QM}5ME}ux8%N%BhmKa(@S^iPiJ&Ul>zK>JvI_hOX#rCbTN@8W!VKWS)7BehV%{NGd#d0rycFQ$?JJ(Fw#b>CWjrmFhc}=eP6}UzY0k(QefmZ9DpX78I0GsD%;$D7)3$LC zJ$j-066>eX+l$Xh_EQXHP-;a@{lSD-L zRCqnPl|+0=S;SZ0sVug?kZG*F{4-S~mzfF$*=?jdr^M-Z3;E;xU}d0;p(j8x>&yd|3(o55CdDh@TNgh zn%!Bu5xW(o8xa)|R7Ax9QA`xOFt8PCXO7){?e0z#JASkL?)}^|-~V_#&g;p%cXxL7 z%$YN1s7a);Y_MgvI_#zu^)xn-x4oFF##hkOLD|{}r=R*>p4My}c)f_1umuy#*Unby z4J&%O{7k)r?0{@d$3ae)KLUYO;=S72FIujfKOQc<>?UCgCRQcqt6o>E=&+vJ-96wF zBMtvF9-J4p7YMAv&xzNvSki`P!l%Q54by}x$JZ40dY(G?FFmbLev;XpYvIIrXc`>Y zQANfUOsxK~K%Eq$r;Ee2@8Hj?6Uoz_sbJeLTfziZty(i*4G7fJ8|9~3CAParCM}GC zOOLXp-?@v_S0B0MM-};4;v$v2(Nibms&WTdr0)Eprzs6IpMh>aOzg7bVMy*230pAX zu%t7c2Mcb=;eBX(3$ zs<-VA>Y^+OTQE`fW{LWTf1?IH(EMFGy{ap#Z%hWymYQN2_BIEUX?ji4Xk}WQU z!l;DT1Y2+(0RB&WpVzi5d6Q2#TrYkiw1Ek6t~MuapBz>k361LC5D2W=zJ00sYL_)F z3)P1rvB~$ae#tb0KSgMnh@NL4m+396RCXW<(pXMtyk9@}QaG zad@Fxsg9mbN;j52++VDYqIx>ZshYfX(_+>9oSvSktMy&mR(dvadM9wbS4Y7rOjobX zpZNwo-7RTE>d#h8c5DsTDp@Glf{EX?7O5q#t>~QP+9A0;V;E zUnXt}wmj1>R{J*5Q|F4tGX76|6s0p*6JJ;8SL`CRfeCl}#cB^eCbl)u+L-fU0-N*R z3qDtK6bP&muVaeiELORm8w7N0s$dHyYUV9b=OpXt`cUo4gWJw!j;-9lNp=zDyqvs;gGjb9Ow2~ky(^A0}OyKxFKiT2_B=#5I z572#?wLoAMzCND0JSCFV7}^rdyEGQA0~2@!g3l((`moJET7u6_k-#e4-}s9Aq86-k zQF};9tS9sJcy#5f$oc8)hTQDHMjeK(U-468~Fc;oxu8U69ro^aWr$fI%BgH?F8Dd zidm4#mJHP!(H*(B$)ncj@4SlH* zgXUzi@EKmPWVfS0U{zdUo;ur`U->AFXq}bCw$5zABT_^O>ONK7yv~ZwcQcdg4xg?b z4CV6#V>21kd~UFJB73=|32ZwqE7*bwDJ4hU+QNz&{LtEnDw@a!^tOYtzkCG(tHfW` z!D15Y_USKZwnkF01rsJkdFn3{D>`n0)`tDv$;>p|5}tkz6bP&uCC^m5@#in`xF4St zg?O+%*9XA9`=5naAAXvn2F+GSkF}zyQCctYnbn)s+!_pb_ZchLf(iVbcqT`i9*lhM z2&Lz02?SO-Oqs2g^|hk0<@4Hiy^>gurZQAHYNcQcCh#5M^YdrPEIiK_u0OOF2&}?y z0nYINpjQ zw-b#fsx$jr)0ElT^GNfm2bC?HAUW(M$?rH^efY?MMz=7QD-9m0)*WI`H;pyn8K}e6 zZg(8`>{a`6TGXruiwc{9W#2~xTQH%Rj8bRu{YE*RwK>koCAP4okv-J9a8e+!YF335 zwe1xL8ee`6Z~Bw~=%O=)*GU&hX;6ZCxBcVZ}Pn>QB~y22NKjy?Ogs@ zUFvMAK)1P7A+qL4f-RURIFz8?Z|g$6%GaZQEvgGa6RlwISOcYN&v>=RIG6GrRohDw z)vf7H)VxVG`PkKXb!DQ@>(x{?_eapGb9Cl7oH$~YGU-(yl}xunMno@X_b~WLEIE9{Sz#SJGCERt-+t(soBp<$-3S)egID>AHue za=w0y`oz+f5?}2)l#7$u)&Z8#OD8F3GBQ=8ZPqmGT6Ou?#Bu7BK{j+qdUg3~{CM?y znKgY<{>8EGGl@Or=K=)xl@x5j#4Dq5>i5<*^mw7x#zMDCtVO>z@NB?0VT}c^tKg@} zv(;TrvMQzA>x(l{umuzIO~$K_`7S}jZdx0r>3dnT3%ru~aC3pcD*QD08hw*uX8YO$ zj_%Ye*n$asO*&oM(@WW{I<9cPwv#|$6@Hq07sT^Cw&IHoTx{;6U<)SjUFRcQvq@~z z+`k~OR1yfR!q1;)DUV6UKJ`r^)L3=MMDmzT!B~_oa5L0KxNJVD+BL3Leiff$tm7PdxmVDSTGc zbeWkzU{%NEBh>GF$7#?8?Q3wk$3+%*pVw8Z)>y$7OyK**=Yx4F8`0PWy7jRZ2&{T_ zEk&Ks)1Ky)pPjj3b0Iq&?hMt&yC~R#2@;c}Hsp7q*&*$#b~t_}8(-`S6Yew>p84Y9 zc(odT{@3`q>ca{X)crRdDKXTD3j0^Ecb8qjc#We#U=?nU*Rm+iWwUiI@Tk6<&=WDy z{d|IYXQw00x7FI15Rt>4lsd!8P^QW@!{T<;%Tr&k*&Uz)QGb%XHv&kkh zz9W1cXV6skF3%nct-XbNg^6DdDeB7h_EdhOJ;9klQ<;&W9UPhEBM?}%({rR+l5IzS zC1^g}tkwZoJgz<6Bf3H3KM4%Y{5jZSEg#S z)P|<*)qa(iks;)#1;MVQg#v+9;;(A=IR=tzA7Q(XRwa1#{(;9Zb>j$UI_YU;`N!d8 zHN2)1eb-xy0r;ARLQ0MM%yz2_!4^yuWGAcs)=sn$U-{*=UT*Y(N^f=0_*ip+z^b^% zDeAYK4zx*mw6>LR7g(8Y0yW=;6Kugm?D7<~(m@A0;HEahJ*?XjB0e^R=^>*90;|Gb zjZ)hM+ta&0wZ6MQ)fZ~-vj!58N3aDGTh@+Jqk8duMfJ6Q6?%u)JiqA%0}n3{2(0>J zl&&`C`{+NGuN!>b&;$lL`ap~1^#ofmG3xjjbulOIT4_(vZeexkc$mOab-zGh70zwo zqt9bEFxYDi!85lKgI+1>#nTSdy{wvyJyw^2qg0pv_H>1(b{&>iZJd^R9Gl&a$Ot1wLcm(G=6znR( z(kVWW(V$Equqy0bnwtICmbOaN+8Efgl=(09gnsL*D%gSvJc9GH;`iTSbE`Ll@i{dG z0;_Dhq^TY^Y^hSd&eVH#f<1d3iI6u7xY~OK2Ah4>jVUjxdgfk5Y)?(qF7XsnM-I`#P zPYJeQ;#a{i^?5fZ+Tozq#*Q6rq2K5#Fg&bSAh7Dz;3T!#E@%46TWjNW#deU_w;DvA zUQMtC6YTvkby+JXno*>+VcVq}e2e_UZb)+k0;`I*B&qwCJJSb^v^H)zbb~V63Xt0_ zhhPgP>NZbS4ZWPG(G0DPd#pd4TmG6Ycr{!gu&UALB-K90nf5l&+VF2%1&(#Lhqni+ z3Uf~E!{ON^Uq7$(o&DtbB^j5@6l}o+_MCXVjJ-zi=#c}M^sXupScUtTPWN$Y74X@_ z$KDx63btSZdw_hT9#|g?pW8sq-(>_7ScUr-e}Xd_z>_9+P+a_uU<)R2{DDW$>)S%N zZI)0e;GRHW74BnvHDk9e#6;`iSnzd%EttR&3%>iTmIvrc8bRxU#{~kba3ACQqx2rY zK3YJV_du`(6L_5G=a@8;;Nb5%5I%FWNT7%Z?qfU#us;yao~REC_N*n?g8wi65^;|# zrY$_3Zw8$V<_QE=;a4RFm&ZQf-RW9Uv2KmL|Z}Ql^!so{&s=DD(pY-?|JjO5Prx9Y;q10Y{3Nn zYV-4*YgL7DLkUbMJ0lQSCHf@;Lv&!*zHv{bMK z6XN&Wa^5-?7UBY3lN|&Ct8fH?=gF{qw&9&EB%Sk8umuxh+-JbkiOjl%6>OdzC=ggB zMse!xDF&U)GP4|^o-A^pMXRdGfxSkkvllv0+o_rt?t8Z@bUb1PZQhs=Y{7(AXsYV3@S09X zH80$5Y!EESt^*klKMVg0t6t4XRflsyWf~#3ntDC&r}(o8@`Ir ze9@krt>N3LmhgV?M;Q}X6*e(b{lw>LS2}3KrhYZy8ViPB>81o*FtK^eM0MD7YwCVQ zBPuVe3fq_Wg6kK*$e6&YvPl!w13XLb>mH3LsPu}dvxh+TV>5y+n3%|O@$PNb(?{Pm zVyE9VW^NM+&u{#YF@aU&cD5S6T~8O?)ri^GH?l#Ai9E-v2Ei6gY~kxh=Nswi*h?A_ zIBOm=yf_>-zx^&_0;@{nr>hZ`d^Nm8Bi>o}Vg57~CXcF4umuy>n&hbl7p>^WAsUhK z$B}vFkAbt*KFgTEsLAbf>jOw29qA>*i#@@j501TQJc`%~vO#w4zR%v|jRS ztry*2Iu;x!! zTn-;N7M5q0$(X>Zv?}w|sXUKNw^Aco7Mqhj7x@_3RHGZKz1HYV7DiQjb#)ru9YDGSzoQIqQn z$fgCu;SH3^n82z(FBYk9dGtKnOCz?w-AX*v1hB7LjbIBV@HnQ^9jtkRxb2UDCs*Ie zn82#7p-a@DP1e-pxR!- zoMFzhieL1GGhtO>S>4S-PCF*>Sjl}jn;tNz#0(}pn=TMog>$+2w{}Bom_A$&wtY6q z*n$Z>R`M7?eFb!r9AQ;%wm@K&m`^>#(-mSP10c$Hy^wp32|QNv47ySF{Pc+C@TX*w zKwuTld*)esm(5{=YcTA1uu;eu#{?cLb-G%~CeW>aFEGA0RUohmXB+c1mK|@|jqst6 z^K`3>EttS#CC?m)zrl#$wOj>ZHYEBRi_V{=&8 zm=VyyC08J@3TFcI_uQomtIunn>pyG~vWGE&$4dSktk#72^W87Se@zhxtisv9JVPjV z9$k|(4jQDd7xIEJfyYX|ujt2db#~ZzC}}@QAg~JO!|HU4uMU)B)p2lt-3A$3FoDNP zoh~l+x?KDBSa`K_sz6{B&S>R(cn^7#gkNJIHfpnw3ycXoR`Ohf7SUwT{?TCeaGF41 z70x5&nSh7pkiQ*9Kyh%fj4hbJV^eQGZM-GD;{rPpEtXr(YnV@{VcHD7t{%kB{ zhi(w^UNM13SDvN!@h;hUH3GU8WeWsW;k-_MF4?>?61ye@zCJFJu>}+2xVz|9CBCRx)c<3^czN zBGfOzL@$G-YDa2K+t$+}EX_PslF%m#+I<`%5Lkulv+&GJSVFFDjRg;fETIkyCf)}u zRVVQ_f<3f0+L=!$o0`T#c-2J&?~uhiaz&!fr|BfiJ{EjK77}d11gjR$*1rb z*nf4JKwy=49ed;6$va-h!QgC4w$xax5}twm=TcSKZ`4w?#(rzMxMLML_jaLb_(M-? z?$bPggrDxj|8qP94C3`akOdR?*YdLgFEk}BGZVq@@M?j;D*N??>JXhZZMR%&W7@+g zvPw#X^?q{*wqOF^Y3^BG8bT`FOoH<*as&da?v5%{yHvEMmnLg%>{yaV+B8pu8qbCk zY{3NXF*@Cc;%TJ)&m;&*2o(sdGHzR_Ug2##kJZ`;JRd~EUWf3#$e&4zq=o7oA3dGl z)mUDWwpcB`&3!6^YH~>Hh3c=?dg|t{`H4y4tJMPTH}rFOORxnKu5A{p4PNN!y_Z@W zDV5Ib&j^SF+uQd90;@=ag=)QSdb-(CYa>&+BW?4Gh88B*2)1AX_XVBqh0;hKJT4CA zUOz4nSmpS(K&?AKPXjA!ZFuD`kgM?O+;1K+f-RW9y@yw(SX3l;-<$;IZ#N4BRz)2y zP+x`Wslgk~-<|g3vmEU=4D4^MA=rWm+*|dsBYVX{%hDCXSc2aVF)uuGTwk)NRUE7xx`AK|Ch!}~>qf2dAe}s8 z!Fu;Tfxs%9#m=+Bo_~<*$HhY1jYouRbxh#r&nqs@TqzT)Xt-o_Ss<`V%+p_g#aA}m z9tpvRZVOrWn85v*MIE#Zb(9#RPsI`8R5w z16@;j5VYE-Q}F-7DxBBL>*;@=O7Gqn06ta3{9R1o5rfD2Cf}lSe)NLh{B#HWzpx5t z;Pdafdx>;3C=I^nMUheM=c!+QTG7!r_~?UnllO_4r+R&{qTfGhZ*BFi+tn8GXebFt zBiMooyf2-fH__qT{$n>sLS%8CKwwq=^m%IXJ1g3xhBn*IsBcCOj!cFpcI(Nfjq}uP zPps%3CleW~ScTc@yd755OQ*#EdMkJl+$bcv3M9069p@&p2_ zJ_qEfaL9^2E701I-~6N|Uc7E?${2zzm=Jf~56o-M=1w00y>7<{1Xit2ovs$~9T=P5 zYHeJslSMQ2@$jemVbb~RJXObcoGou{BICPY(r~uAlIQhWG|~u*J9Fu@;3SyxYa789 zOyE1hXOM@!(VJ;WFz4oafxxQ4?ekRgy;gMWPOXj5hGs1HU^46*UO=z~6ZnqsIZmt2 ztk0E1IFqtaAh4?G`046uLp@Ej)3PiAi=x?@M@eu;okFk$6XL!4vtvH9U%+>UP0SYv ztg3e^Tb){{r$)hA8{MV#?1^a%Y ziFp}z@9we2${^S@Z5+WCOt8d>DonAaLq2GCcjp8HaL?-j_sCd*z$%=n!smngzsU0@ zrNVyCNa1UM-(dVD;(Gy3Et4m5V(7Ec!WRb<_-)qd?jGDIo7Nf$A6Cr}2&}?iRKEVv z(^GCfXaxNJGGF*|VgkR9Ji^jhmb2$2L!W&`0)bW7GvIZj&R3Uecn^aUzqSe<048wH z=P{YOl_l?*32@*2pg>?1_HcMU+?}iH0kb%;9dJtUWH5o>O}^6L@JZb`Jqo(rxgii( zg*`RCN|rmDe&A<3fBf@O@W?Px$85f8LisL;^4+rXuVwVcs=-iu`Zs~VDm>2f8jZ;Y zj8*Cl`?ge3umuz0UFNI(7h2ISE46X=dz0$yTGwvSxtf_kV3qj&Sbw24GrHdj=5@6Y z_L5=Z&b0YzS&|jaJgK#D_)>2con>Etn8T2D4dBAjh~h zEd6{ zXX(+rR@iedfxs%fPQlmDCx@_^{3HQ`w`~ZvU;=;Jc_q(mZw6(lFe%4VAg~IrQ*aOY z-A(%LOd33nZAGvJ6WG_{`ye-E(FUv2;Y*6UKwuSKr{M3$>Eyr%-P57qR7-*_n805K zovz8#F7p1f>CmHvhd^KzUZ>!_r0Wyeb3+>V`nDq2f(bm6;qPD#D?;9mhQl-51p=$^ zIt8yxF}pX3SUM6W)NVnr1ry?|Xm3mw=~SEoe|ESE1Xkg73V!N>-$K$nF9|&U5P~h3 zz_WXu?%eGyWagxJ=)1A0KwuSKr{G@3;zOiv^=OzDDiLhK1g@FO>tCt&N$I{&7-`l> zAg~Ir5A(0u{I{%kc2jtGxR#LReX2#A+I*o)c@=A%Va}_IwYLwmMefymy|5-0vW(?&b;Wdo>nvoiTBFXRO*{wM%*3 zNuHB>y@*TEP}ftjUj2t891qr#fY)HFKE3+3qmg zA3Bq5AJqzWeKr>etirnwd9AQ6 zv)Jv=K45>(TEP}f;5{__wC03qZ0j2jush%+5Lkux73y@beliO>Wdqg@e!~7iOyIg< zJoC(c0{bpo@`2c_tWYc7!HVoAzez?hCa>$fmJw%iJx%PIu3UJwVge_EfZ|PL`=;j z)%AJPf2x1~&1>Q;PCLhHrVbSdtim~k{5#k(3@#5p#kNK!3%P>=aXwL<`@1PUG()?N zvP1nLV%sB@GIW|i6eAVRjpV!Hzx9Jh*$-IR_Ix1+5)&`RCaS|4y8Kf)@|{ChsFnDQ zjkQ=M5LktCJb4{@pI~Tw;0sIWxk1R~#6*})qPoe=<)6xtx8Jpf_MMDi^}c-qfmJwH zRi}Hhr5*epSpiI5?iF%UF%h9pRPEed=%@qQy{ehm3ij4Af?=}{3ItY(y8*Wh8x2Fx zC$IwrlZBdaxDp?(%EnJJyEOv#cA3dWd|D^0J7WU(X}(`=M-trMxS6dq-5?NHh1a0@ zejHwdK05CV>(lRpkRgN#yhlK%bNDkDP85D%*|Ek1|1YeC0)bW7zt-u#u28^$@7ik3D-~i3Ch#5s{;Sq_z}8q7X!|Bj zAg~JW)8HA{>2?tO#0!c}c-&Ky%nS; z>>${J37m_^_X526!ICa_g7M9F3ItZ+_yb=B82p?`i9ztI?=d0HfC;>xm(RAl{mt&3 z?+rGwy95HOa2$olEY}`jCtCJ_n$3<2@e)kn{lk1Oz?U_w^~532X~8amz$zRM;0^u4-MAg~I@wfHE?`ZI_15pYL$Oo(4$0#`5K zr^KXNvzs$xp;}{AAg~I@=lJ*B%A5@1tP2%+DWfeynbKb9j8_F9lmLA?}Kwcp;Q!Uk`wz zdA0(9RXBpcYbX4kz~0SvhE7vG6>PzTSZBg+_B8gixh%Fx< z6iv8D7JLs^C+mIbPv4Ky81o1<;f)VH`uU^eVIQd;zv)9y+|=r9H;O1=fgJ+jdqoRn zMq#u%x7dv~`(Y?!ZxVZ%JcewV0gYCBuzM3qq>56!ddaXE&Aa+ta{m&mu1xTz2}-G? zLae%Ovo~!sQ9Ie;d8G_EJER#io7PHtJvmyf@Y0{23%o78I~uJfF7T(v&2CE#Vx!f+ z+XT?F^eQKMSY|-IwjQiTUPbA8hiJ9-#DMbi869dwtIduE&=h`dqeu+6mYj9OOBpI+&E zpA&O+88F|q8CyJliM0MjtlDjgH@)@fgJfPmR_#*9mzLIkC7IrfQLpv$r2~Vt6Dmw9 z@HT2TW9^177A%;+zn1S&bmLF(k_-E_`;p|;BtZ@8<3Stl{v%y~z^e%?_n-^Sbn>(t z3F@4WZgkFl1MZisX`K$Qt`OF+lc!+81gv6PZ53I8vw!u4!<2E=+N zxc9I=_zrk1>_o!5k3MF_skKer>EG|Q({7yoynt;shq4YA3ASKjY)riR^`RRzJgE^S zRqDdfyLK=%?lU^wi>Q14Sp^Wz*R%yKl7!*`j@XQp?gz>NCkvlIP?Ahi5#q+8v*n$bX*P3Vi z4mE}n;t0&%P#~}hUz1L^wo)NGyuJmDiZoX`1VyXGLGJXOzoCpriQK3dHNTxZedeN_ z+?&;68w;v0fo<`+-2t%`#`}H6M?`ge0}^(i@JAMpM}lfW0RV~bzlO| zymh+XW_Ov#h-P5?wuV4p6~5~{ra#Re%)T~)^=vh%;Toq_Xzxkw^K|krvsiU|iWhy= z`@1yTHAWq?lIQs@(9Tc@_jiYpsuheHQ6dmn)uLmpI&*|4?YCV!E$zqc#_;`@J9PeY zm|zPg!ri0Qy(heA=6S7+*3Uqyt}SZ5)}~6o$U?hjnUI z(r-qDI^a+sJ$L4^R8tqJ9(@o%15VtQ>U@Y$Pj3qR=cL%`sot>pjXP8yQiEU%CTiS@ zREvrO=Xn>8T9Kcq#OG>Fi`bW!L!f@jcCyPNT%GX9kLCuxk_NR1S1T9#(V3H9OF>;CR5Htt zwj8OQQW?0Vh#h|$0?GGE2)1Bi@aS;W&)JV|;pcGkiVl1DNgEGipvS6F3{q`=9uHokw^ZDQ< z1L&~2FZjsz0)bWdPV02HD`$YKjVJr$x<~Mk@V8y`mL?xggW{6|*~U}0GPYns^Z=es zNP&Kh3fO`x8w3KY>JN-nQ{H-0$K#quR+bY6gG`^XCGjg|ojzKf__-pw`*0}98;aB1II=Dou6WaMxm6V?j?A;yO&ohPd z{c8|x!Nl$nQR>z#e_Ab0BL=ST2ou)Uf!U?r0)bU$JfhWSwf*SvFPeXq>=pnuO6;NK z)NTY@Fp*ynsjevTr>*B`Z7gf*0o`7?g3>NgAh61_XOtS&){l;H(8iKfuO@K5rvip2 z(+IX;V*T<6Rej)3?Mk#Z%Bq>epPQ}0WNMB;U{!AaNY!?jA6?g7YvXg)Z&qPUcQC4u zN3aDG_-)qd>aTjvdVBPS#Jt4xF0W-NSP zagx!QgHLQm+3lXA1p=#Z&*zz$fumrcR}LGO_*KF) z2>c7h*~Fk#!@+0f3f5~%po}e;5U-=OeG=pz-_ClRpCS-gbxMs^Z7ciJduCcMc@Q1} zM#Jtf=UZoF!Gi7&es8#+I3oni<@c<5juF8GR)xHZR-51SrF9Q!@5gE!ggLsKVcZS;6%0aKgG276xkmZ`lzTf<2f>klywVUb zE?&KS%Y!O`nxFXbSu%{wS-@sItWK~66L>9z@8R8%0@V)BVkh6cmob4=c>c*xOKYDB zr-qJVXTKhju>})2%FXNPKOPOehVe+wg~bAaRd~kAiP8LA+41|>o&`OGE62YOuTyaE zRok(yyTJYo2_@Kq3Dehc>IidBS{6}0H<&RHDn{O69-dPL0;}*k1`qGFo9P#_?lOZ?(ow32g~xGFA!LT?*h*XtJ58vE`4HSy_XYg!317! z;k$n4^n!M&Z`kIg1pn+a%CIro(S<09R0%mjaUDEmIgmN_hm2ocNF>+ zCa`bEW3RhY;6?K}Y>aYMAg~Je7#`ovPl7Yc*E71}v+#akLiGBM6h*+Z=I2=CJ%8aH z#43Cb`3?me#^UT^;MP|^g69As<3iPiE)xCp>+=7ZvG{E(Vz!3yV9R<4vk6S(e+*T( zD1o$ZfX^T(V`w@M2F^ibj0n%Sr5eTe0aV1JEYUM$%*3#lv>wJU3 z*WVnn+MSTG?~LcN*!R`xoc?r#s65h!oDxxv2OB*U0To^PSp=1*n$Z>r{R^gd9-<5KEFT3@wC*)PU zCcGcG=VQ-+zk?f|u+IBCLZ0Pi!2`eqjv8@4(f22N^|Kwc>T^UOunK!Pye4_I+HmA! z06#mE3Z4umaP*5uKSo->*H9nG{7@_qScUyAp1rf&9X4*Y1FIJ+1dj|8IEu&X>7Vxp zU92Tc>Xa`KScN@Kovv_9M|eBjjGu6nE_jxhn0`7&jdu2-B~>-A?^%=X@OgR_h)?V$ z5LkshXC5`k4}pv(uUYV3OTk0NMDO$%HMP)}c9^Dl;iYjA5Y*u&Tf63mjQ-{;C4*U)I>s_y=fG{?NQh21GBE{gS}$UY&&-ms z1rzu#=yXdXlHg6#&1~qTQv!ii_$$gQw~UT}$T3%0_8fD9EttShlkcP75(4e2KVhj| zS_uSJiC^dU7TsYMF@(b`P4HwefqNydXW6a`jO=OzbynsI1Xf{Bjqi{SZVR`jSBIfl z3k8o16F5fB-w&6za45|3r82&@__tjcut_J_!ybs=!qZo#v}1dfsOT`AxO!<#jR zhGS0&1XhXbICm`@!o|vCn;WDp-QnEyYzCtimfP{Oo~a+u1au)}U`&O;|C(gy=Jzb6v#Z zp%rYsT~i>i3a{_*b+x92#AsU!c-h@t`B)e&?bzr>i@qDmUY(+)2i@H1Ax}fOQbdfj zt+P9wWUsCK+zlM1_;}|qMgA)B_=WUuOom57q<>djUr&mbp1<;^HZEE`@kyw$GO(2+ z#9JC_73HLVtC;ikDCytY!G0OB(x+zbbcl)8hL?SY0%Kg+m7hH11-sG#6k?Bg8eF5xA-*#I5)qj@sBx%^@rnIJFB;)_Y zy(RxK%776;Y`4=C(Sis*|CIhcN0sj;uRlgvyto@n@Jka2tP-#Mf>DN25a7uUPuL?B z?2nbElz7wb;iXcu(pafcsy7{`FO{xriIWV>ylC#AFZ_8}aH3BqPnOnpkD$Wz&)2b% z!31x*?AHfQ_#8@8Zap5zmXEWQu>}(cZpBDVhWOH45A7RO$1p>2eB#O6KNU)tz^YTH zVcZ{8(&{WOO5#Y$C&iHoEWqxO$jIoVbez5k+205;`=d$Kab2F z&6w}kmI8rQ;;;I&HBCA3WeA(QVXcHMn85EN&owxcroiA3*7ooefxs$!NBB;pRBy%q zy*qq!tU+qujFe_?4xrZ--j?eAiIBEG3ZNbKmaq0n|E>0^KdUPKhkC%q4SJH27cTYr z5J+1;xGX)G6E4koA4p&Db(IBGBBUo~fi(ZJc6SfXHB}al?gm>|SQ2c(MEw`x(tj&I z^N!Y23^#XxQJt&}x(tzf{!ngm-gA!kQOm-yOL5?`C*-@%}!%8sV| zbcZWd1p=%1+9bO2g~JS#o_G7gvLJim%JDVvwIb=?bv#~c65f!fnS;ai9c@)c!;EE$s~jvqK5C zU;^JaUQed0xpMtVdzcw55?D2Cex!79pFiz3raXEc-9*`Ry(JXZZAY*L6S(*Ax>0>R zl=hyU(AcJhKw#DE;Zf4fJ0x?XDIy2<4~0ecn+digzYUYtwDPAVc`yD?8}cocTsRm4=N_#P+Q0;U zvOHh3gc6ihgJS>QgKRm2rryLumuyiFYtBe8s^Hq z=dB@GpCb@h^|fo1L_7OYi)vaM_57MBp+gj~teZx#1rxY0@OhN0hXP+*VOL>-Kwwpl zYqaFwkY^O!(C%)Qdw`O3z#b}m>PoN$6Syz%Gm$Q@CDS}2VDt1sg72u$v@mHwjR5L+ z?6HLJ0EKsrE)M`fZGs!%};fzw+0^Cg3-;fM5$I z<{QUKEi=4m#{iAk(wm>~*V7tW`)w5ntO{xyEA`Ltq>e?JXW2Z;Ul}Vm1i#%I3ASLO zwo{yRIM|aKPSgl`&rOLdvw$a=M+5?^LNend`&#Za{iWuM{#fs%Tz*;~I(2!h#q_0r z&l2LfW75Cp?ubOta$7}yz^elP=DU8;|H8!V>+w=7KN%>eqE_dwM-N*i#I!M79QsNi zu!`rcN&lTCG{5gtvhG}GIN*Pp_*h3u*B|;&-Tsf#3Xdqs^@tBGoBdI$-zZ9I_tuME zzNg*YX^Vf5(6?=1YxA=NTQE_hX|y!>q8DAZT_c{j0C*a|BveLaZOf{&c;QxgQ@mHN_{($tqO(51@ClFYLe=V;dknoNC3R57d z;WL6Qn80^|_ub~7$gITqdb$@)|sd`ozOE4im!E-Gw6wi5H@Y7_MKwuRf`FLcad2Jhn0swXr9?-=C-J9FLK@ zHuIrlUTPUaAAfdJ{D%EtqiyCBth!>CAbl=zqeJFblpjULOO>Cy(H)1h@v3l1h~iZB zZ#HY?BvOA;qSULt3*As;Bx8cF6-#LM*_05a(VXjS(w|gqE%kpEOyIV89Ih}z@vm}} zb!ZSG5Lnf-ZjzM$q$%AzLfcWb?o@@Fh z_SZ|2E+o}wKw#CQ4cr&yIWwoUoEe?##g0nP0PUQu;TavVUl#6u@&U z=krX-oB2_aes}@ixp8_HtG4UCj4hbJcbcz^E=^LNO6%Aj9|M93toqU?R_guPo7P&V_4cQ8 zBb56yFR}Bc_5@onA-*4vMnx#Tv#zqDX66EcRmP)ZqysB_X`eXF>pMFuM0xG?n%(Ve zNw5VI^`A#ex%YjkZnZ|dj*U=!`rl-2K7W@nfmO@)MN1uxdFI&{EtYXSH$-s_de4@+ z7!hp2gr#$|w7!!+t!SssKU#%HD9&T_NfNTZT1N72PVXRWxFU*>Aq_>OX(Oa<6e!U zk@&sQ>D*ThS61Y&U|r-u;a6b-$4+>3uzixU?d*0&$4?Omtitz@uV96wC{EQEv(S_{ z;qGDr$AEa9yB%ut(v+=N z`m!x%orL!s6JpFVM4zE-f9T3q#XT3|yI6%I#e5&+(PPBz7e9CDxw*E};(s0s-wPo9 zTLVD!mg<~1O2RCB!JKlsmL^7T*$_vhFLW~Y8F}{SwWZ{3b`T8c zRYAcPOymVcN`GR#XzaJ2d}KKCsDzZb1Odz{BbdM{?9cOjANv&~WnXtN{PIEY+cEL5 za-{VBn-_KYrg{3;O!tzvYrDhK%=-d?Rd|-c^DKL>B8vk1!s9x(h4}|2_LxOT^}hJf z71y=Z*BTvGlkwa8!=#}X1p=$;>mnrkdOYeJp%G?P0+dN%Hn6WWO_-nK86=Jk@YUCk z?n;QAGb|dOE5raWA^LE0URx+lr9kL?W3E786^?Q6y|3$QE0LX>L*4$Xg;)kAM6Yl4 z_Fv?~x*(X{XuUvS6^;k#bPZ=dBR8IRh4hwtgqRE_#OD!JNJ-(y{;>bQ|>g?%T5_!TC^=TRl7pYkN}A+rsdD|nWnS&7n1?qxP#CwiGY2IteY}@{AX4YyG$UkO7wRf-vuc?c0X91nHveVV1nnAN&i(4 z&{b%w_%K7*v~r(7U=`25lm0s$*vyS6l}a3-#lZ5NFaL`!WA99i4t74&QJFWQ0gOBU zTE-Sk;IF7o7q+jXa?_+fO!BKK#PqRBj7GKg?yk%#G=zCf$|u z1y$hdqpk#7FoC@@?vah@s65ItgXMPV0)bUH2E=z%S#(z{f(*g1bsE7IOyIc)KaIA3 zM`dbGHCX#(wm@JNjvDdNNA9RBh^h>~=~99%n7}=hpQvNvuiU6y2P_sdfxs$petz<@ zpVB6^Cai06N|x1U(2Nyc{b(eU)S5XR2sI!y8I+G(z)T4AhKKe31olb-cWgA!f?BI9hn^kTmi&3$DedzIu%Ee~7K3+GMbfo}7p z=l@UoSH`uS2%9%u7!<*4ECDUY4mR zW54%+KKzWsN@TW_mtj?Y`l0k`o)oaps{H)(SDy2wvGc9|IluPN+IZqUXdqm4dQK(} zo-S1{wW3W!s>`oPo-}%;6?J`QDlhAqCsmqcMGf^@b;>Tc_mlP6!SH#-3$ncWMCs&c zYdUgZbs6SmOONt+ed5X0Ws;dKjUB0{3-@S5vGScnTPU#A@);T1e~i@Vvn>ttHkDtT z9xrX=XX3cNP zq|ZyFq-Xs3zt(2k!J$=Q)2%-6`d$UWf(hIn-+i{k2&V7q2ah8sOZb0bRm}lQBoBV7 zw)U?oW~M|HZ`g z-3z3uylVEj&f2{iKYk56>dSZ7yvY#=titz@pDVLu5QRnK!5|@6`qDdJvbbbL^9Gs7 z+c(damfW?XkwzwRrR01m^qduKoT1f$%(W?|wQ7xrvI&DEY{5i>oH^2pr&e^*Iqk|D zOt?%F#*Ty5tqp|#g;nCcGOT3998P3F#ng!swqT;crn%Ase$LO}B(06cquaAy71H5F z*XbgGRQRszbSKLW%HuDOgE3j{CF4soq|0}#XuTSyvZa(Kow{m8>lm2IEgsB}JbAU? zn=aaz*risnoKkx{q=vVZumuxm*W^i6`6)`vUTgO%WMzi~T;2-=R^fZdGdbc7 zq~_no0|d1e?k*SLARiX zaOL=#F0Rax-toKZ9im2@#){*2C%umuxu9HvQeUG((KJdGHqQNCXtl8qrtI3nm}Ncc;z#;UnO$}MMKoq zX~LD`YdSt?lC&t;nwI5j*YRx38?td_D9m_JMaC9P1SUaCZ)xS|OsUaY8~Vt>RQ7o~LAq4mhL1R= zGNySH=ajKhn$Q~tu1%7#1rsObiPC_L)-++b)<#B%k)qt`2P2Y33j|h)zsk?cRhgC) z2$PzBkS3iN$K%Dev^n=)@Goq1DP79AZ%f0=Yy7sK=b+SC(Hvf;w-bo26*8r=dp30S z3z6nC;S)B>uSc!m{`n5Vm181lR;HA;#)cj#KiN7nzKK#$qXTSQ&|M&~3f~3(1WyDh z%)dT-sFEo;JxP^@JK0l{NMqTi-x%pu7dz@{Y$7|YN|l~^+0#MU+6edApo79PntFty7cfxs&9UbXr`loQELaPDO{30pAXWSk*= zylG2^_0-ykp5?1J#CU?^!uA4zRropa6Ns~WDpu>N18kTkTsgibw<)8f%d72ag=*TB zZ$H&nad}u7U`G`hTQJcoX@pcf$AK;m*S>@EG6yNu+VK-N`(;a*z$$|aBPFBn_Vh;i z8S9swla%}+CG7m8Y^hGK;Zo@xM|$H&75PK_aB2EEN9tr;RW7bST#71nq$v$FpW#nZ zyt2dM2pf_+MZy+LcwbGC+CFihwLWUZF4rjKP4ipq)8Hz?|H3N#3;Es*|8V8^v1e>f zP_Be6m{8Y_kUC6qpyS$USKjZ@5XCFw6AQMRDiByDUis8@!xT1XGwaO1ocPM|H7%Kx zEaipslaxnkC+ZZ98m?4LSjEhOjAU%VM8ae~f9SwZQZCl~M3bmd%A=*zS*3PUBurq{ z`%A;5EiTTqX|6{2Jshp*y_1-_C`-Z?OgMELCe1(KOb0#C{N3S~(v(AigV@uT1~Rr_ zLdaFsIfP~?M~*qM4|B&!n7}HW1Iu#igJ9+)o3E-faQt9U~>E~AmIw{>)ZZ#}XvYGBgXE{}q*|S9H=tL)arfzxP zO@B&$6gCC7dvz47!n9*qf^;^|iSCv(qSap)NZbA{aIKPsf-M5kV3@R>w>@XMHkSB5 z1Y&Z<1&$Y334|k3C8j1wNAsPiOOV!vb(b76HQyOZkGd5{o*QDq;f{n1*%k$4=T7m5B!#bm+NW)PiesbC8x@EQWI-)_5(1Xl5cZp(O$U(`BQ z;p^ik-i93{UwO8nd6&k*bzlOoa`4$*_;K>V#2tKYiUd~S-ox`OyImu!kvpU$))RUO zCU71IKZUQ?Q?j`|KULSZjzC})?$cUU@mF$rwKLS*XeRV_OyKMk{;PZ{DrKD=;aM{i zfxs&9jk?m#M0w?52S2J+Rj z)FLbg{+>)?XIaB6UwCVBl^p z5Lh+q@;E6u(}sTOq!FPJ8;H?84>0kyRBJo*>!xw5A3>s>_(>xtxiU$Pfcdc#tD0*n)`zV>6}1 z?bh`66|Idoqi2%+cDAtgo3}t)IbGWFfrozSZRM(8#-=*)`pSu zB+`^w!qd+pfmK7UWk|Kh+fa!|@%YH#`IV%e4}g95KZ}t&6s?kODYTTRkjz9zWJdPhqmbP|=RS63 zgKSC4-q~gR&h4Myb-w@g=z2Zh=N{)i=Q`K9&N*FJc z5(9yNszCecsME97bnL%TYRRj7Y-ZSwX@bypH;TY0(@eS9jiuN1p=zz*Tv^p{MX|UHiXrVe}!T66vkmC z9+UOu@si|~%KHeyrt;Q^I2NOS1;hCF(m&gg#AD&R?=_ReSa{h*l{{p_X!dS=8HN@} zP`@3hFoVZl-zk3Lh}?~IOnxjgN_`*@Q03ogGm3d;N3H6VelW+pxTsrPG<$I4HHH>Q zEE>BRy}xHiuc#}1?Mxn3P8%A*^#6Pn2&g(bYy&dzvZJ>`6c4~F<+Rj!K?t*3){H<4 zBrI|_AXj}mS~^c53O??@n{E2DaeeEBrwgB`7^g1pu^Rh!@5$P}lGONH1uoA0wUtuymFZcm^E5}gMwM!%NY z(l+lD;_Zp$Sa)?h=K07)AfQT|1sJTKf#c3Pu&M7m6KH|Nw=Rp(&{4K@p^-9gFlItJ zPIzX;w)V#Y0ab7Yf@g(o%D^wC+Og1w-XwYHN)+#5OM6^wA)VW|66H0wrP)tgNZn1d zP(XtX#hsP=*seDp&#<&%{X!6#H6;^`>}*RTX6Q)2(=z!wA6r_yNk=NkT84s5ZRxXr zy@AcNx%e{Q(cwkdPhoBX&PTv^!*g+7O~>x1`>@gR+5}nzVss`_kKnTz!OB%>YtF}; z4+b!`iADk;0Tp~Vyytv12fxqZd;FfTBhUf~cz-;%_T_xsN%CS(3|#~Qs^Gg(shXTh z#|!xm;7hJ|BG3W}@mcBTq~pv=Yj$a>BoI&q-zJYb`=6BpjtpViLo^8dilVn}Mt!f^ zQ6p zbGvx3*_CbtTJ-tux_9}h^>@c=O07CZ6ssw1$+YS7aLbk*n8qGwfq*J_wJOz{ zM=Nmc7&mtHriXAuNF&6Sl7EryS)N1j=dr%5=B_nS z0ShEx**w;#orulmdNW&>HUa@vu#Mrn^?aC%uhzOU{}!G?>jMe#K8`I}g!}ZjXZy}} z5eTS)ZI?=QbVFl$B{Yhy-S{5Ep6qt|4ir1bfgWqzT!P;X-$5YOyy$g71dHwX6+;Uo z-Y?vN4sq}G+P{?+UF!a#4=YBnFF*bY1XRJVOQkwl@(oQoKAer5*@!?3B)Z+$feI!$ zP+JovQdBwTuyiAP2zz%%Lm;3EeqB6=e!vOI)qMyviqj;}0*QL9o#-_8kiWN4%2-^l zjkmlBVp+=!1Olqy_sDZU;=fA$#!Y30L2($)nNM$-iJ~vq(&{ZOq&lrk6wc>y8s;c9 z@wsCU-2PS)iwn-c&;kkXu*Jwq!;acHD{Z@d@@Xl-aVqnEG+ihI&eublw-shdDRRYll(G@sADTK|h77rgP7+c{2VdhbVJXo1Ab^z}$B#*T(P zP+ICsv6WPSw<-Xx$fE`uLa9if$bmPT$R*%y3L5h89S?o3I95ddock zGo?-Jl9GYOPoBhvpI;{sP<6023(;e?^z*;jjHS=hr2I7ZooyYFipz9nauzt&r z2n19$UAYF;KeeShJe7CeX?r5te=C9Y2snqK1rqwl*C2e?mM-a|5Y6I;*_F&fVWpzt8c^CW~Tdfy9?ao6(vN zJd@*rLe%U_qEGt8Gymbm0s&Q?Y8y~=Upqcys=PseYFzYGEskC4cMn4gB=p;EK$0(? z+xAt6gKq~*cRNJ03DK_w0;*uv6F<`eACsK}HOk5&l;RKa@8_o3h5D!*Dfj>YobLZJl`@Tv1Nk!vJ_r5 zirIwJU}%Aa_&%)G-j;qZk7n`VwE_WE;up1gfIe==d(IgxzhY>C1k8Hlp3K8nvafX{ zQ_fd|y(Mf>VGqamta*P;4u2BM4)F8Upal}Jb>$ua-`jAELn3>>7z+ec!5)sUSg%_s zZ!(#{bS6b%Xn};#x~fb~d&w@5$;|u0WPyMx*u$w*w{Gjmcz!Z_dV48`7D&L>l}9-@ zW>Jqn$?Wp>wE_WEu!mEr7O>q#zBx%Oa%VP%7D&L>m5(_yJ4;>Yc$R5)Ody~N_K7?n zuBJemKRuo~EIE&%1ro3>@bUR26P&SRG@JePx3(94%pV8O*hvf&;kiKTH-6#TgKpF(|R$B_J#rhRWRnj z&tpkW#MQqfw)~e35iDR7CXS=7eVu_@dv;>|lbi$ss$k54?}V^r9xi_5#KxC&5TZDc z5aT{?ix=RiY#Wxl(nlbm3dVrA2XHQ#>?SMZJ+^g{i^l|1G0l~}u5K>DwS91vph`8x zb%A`#c`~ce_#(MJ+K6`6+tC6a4e6fOdh}?F9o@G}Q)=5{Ju=~cw_d1t86)kw$oa#j zvw(Nn7+N6Vr@ID8e{AXYi%O5PvzN6zSA7PX@${SUTTpfX!)j#7Ga4V~C`94sMfCdj zR94cq1%?(#eBPRcE?wpkuj7iBVgFT^&Q+Vms_Q>XkbtTO8ChsL9~ITDQ;1VNhe;LE zOcr-q3quPe)c!0(**tIYO^o7~bZ|Z<#de&@-jDn&K?17IeOQM4xbJhjmqNTxX@{M2 zr?Z9`Eikk|qNLwq)RyO}wY#klo9c()dn2c@yXD^{NI=!7-iwj!U`KxxDnxGFI((;w zpN3hhi=hP)?gb0buRQKE)GNe+p1FAKt#Rz-{RRmVQ00AU0h++0Q5zpC#GTx`ctmIn zn>bz%LklD-!semeRrYk|O@%Po^$w3&6~S`f*GrIqs_@u(sFvrE1?DTn_|_VvpyObc zK1ByZ3naP?n~mIgCi&+Gg$T4UB&WOfW7jmlNsxdl&9SplV2%T=^jC=JKs%!Q#E)Gv z*2d5RiEFcGpeFBHQS$wVfrNSBRCKAABRxx%+Wu>ZFPZY)fo+}rRe}UmeV#fMJtB@&wNoM1?fj4U8kn+@ z4lOXWK%%wIB;<3{iO$@le6=fF2NKn|7A!6Ds{{$CI^Z`6z1ZnQf2AqJ=d+=tI7r1V zZPvoj0*T8flh6q>7b^Etyw^bQNaCLNMt;ZYBuGHjlXpqzWm6Zrpo2o3$&Mw~EpN$f zOf)gHKmxX7ylrosK>8U{x%SQn2@+6cA3gzXjC7^i#mb2O+=e7l9<^1@X#GKg7D$L~ zVxQHM$)WfR`BC9jfe=(+cR9Y##L^OZ$c`~AYiov(X%Aaem@m$=cf9w=#UV*7-|nE0 zp$-Yyy7GP1Hg1sXHzu>ktrrOdRKZ+szRJ`uOm?!G&bFBx60*l30ozJGRx8Bvo;N9M z?u*3&0aY+-nxB1^b(Y4wpULco=1R~43D{Qh(RQ0jbm#9`Z0FJi0s&QG=JI4cULPA~ zvC&#NLY6lqU|Y%OYkw`5gNWiv|@09Kx zg!j0nFzu>^0s&Ppua{@te_w+qUrc6;pC6H+1ro5WU2!VLxu!wEBU(ZZl7=>_w;+XFBJ%=f;qSRsywwxyy;+O_bFG%(}e_V zD|zPGJQI=~9mH~5We5aR!8}_&tADf&xnk?f%xB~X8Mu&uZ6!Yq%C#NY*vOmZ_e>WE zsDhcN{G^Si64^Dvg+0#RFF^|=U|Y%enmiRqwoS8PuTCr!2&jU&qbk+HO~GVQh(3!O zeMrcIXRjLmkLdcGr&6v*9MFIg;Fk_SF`|!-no24J+gZ&Ol&;kkARw^qLVo93U z16eP0p+G**Z7UK;@n2b zEO(`+e>Iojz9xL_>&a*m7)taD^;fkt-6W z$A^&pH817P;TtftKmzVF!`E7N9zlwa-_HZq zX|gWocMAkmO@2NBb@|VQ_SmkJ5tAHD>_7aGv%9Rq&;kkgq`8+75=>@2Y{W`@mk0z@ zJ?fZ*(tTX$&G||h?zN%hj_F%j_r*jkSU}AXYK*F3WGFGwtdmD3MhOH|#iS;o?Jh3# z0dlu^S9zzQxz7>y0?~+_-)oZ1Uzyr2q@LPM<`caiYKvm${i74`g6Fp?3l;L3J zOd1EbV!qmUF|{e{`y<&lYs+12CQKu>=>eE~)qjyCI;-F#9-qy$% zS|9;y504K1*M*GRZ_bS09})1S z+xw6Y#wxZqazBO^NWd?cpXk{rfL!rx#_S7D2?SKZd~ubkv4amui_l{M2QCPC;gEpu zpL^kRJ<0xy#;m+qg+M@+m=W*R&6P}7S+JmUkA(boNWglmQcZGcO&nHOvg^}c3j|cb zTvhHN7{-k3YYkjIP8v((V4*5_}3Dwx*zZ ze&<#e3Nc03l5~&g#4>&##n1u?_(b>~LVkwCm2Z2t`azCBKvfI#+2~WY1D$z7DP!zj zeX<__HS{2)GjC5DyfW(fpTiTMnXOEzMQt?}&8qFESPATeRkVx((sMNWiaI z$-qX$$kLj9+Ot^T|GpMHGDxU*o6L_Haik~ztxIj( zTbKN|(v=x5{wWYp1>1Rk3g09ZvEX@qrw*$VXo1ASIg?NUZ)1XXD($Y(#jm*1)}8gy z)D;M*68n#%38lD6A08L&ZzZhSf<#DRGMdiY_St;hEzhh8J&Vh?yRo?w?F0g<;3_B{ zRok-(Z!dIanhxUnC`c@OH4zOQ=t${nrHuNfOK^2OCu%%}^-)j-*Jg1K`Rq@6*dv9l zTGAfFIS;sJ37n_kdHP# z!?AQ_GW#;oOCX>M&QtIfZp?ao-fuh$>E8oG3nXCss8R*gAH;39;!FdWk z`x;$=SEfg^(U*E)Xn_Q5=lM9w{}o;y8qQ2!b`S`tg7Xyo05hSmXBrJpbzd zXGS0a`*t3U!n$NqLO(WtiKjq76`ZHwI|%f&A_snTXV1oV$It=^=xg!(-6$SaOO@Ey z^p#>6fbkEPIijN_Nb~oja18xEVRdAkyXYbU; zk%=p0d2tlN&;kj#XD;{1_-?wRPw$W?>skl|RKfXSo&%X_fv8U$^2+Tu`8nhF6 z4|Sl{otsPHLMHj!Twgq7M^AQpk|}`}NR+PFi7xkWpd0*^S(#N@A=v7JAFF#|DG*Qv zGt7Alw>TD`4E19XXgFrwP%v|SJHGCf4 z&-Z|MHQ$y%i$JX1iT(sQ(E0z$nCQ0}cT4hQP2M>Qgg#I$UB3+_f3%}{NlJued*OO) zv7jTf&$1`b0*NkqyHJ=VA5DZR_c5^GEROQ)#a6bj7xs;UD{bJ)Kpu4t%*76--C1P+ z76e)#0oTy*vj;Q}BZMBRj1?F3s%f81PcUI!JWP(NJ za(ew3)~WC)h8c!%$26F+$Fq=5x05e)7|W!mr!cfY0gLc|yEqmXdmBRwB;blMzQ>k#kD>=7VwqakDuIA1nB&K@CS7%;aIGkod+-B> z7D&JqV?2j`!A_}e^+?ue&rgAXDwtEIQaw2PMQZ+R2-{uQoIndC;EEW&CN9egdwch1 zZrgMP0;=GO2)@_L`R=&=SAW)C(~>|7B*Zl)r+$vavkW8_Jk(wwpbD;t;QOBUO~->! zJEocDF0B86#7VFp9nX{bkcsDMII+v|UIGDCaP0|?m+WlHGV+J9v+L&zyRX4qcewu< zZ{X^_$PY@w+2k+T!n`viU=}-{A56I`|0bi^&KCOx0;=E~H1}j?70SD764>BjpM(q{ zNWi>zzL(zo74lZ|WHx`S7KXnCRnT+he&U^Ix&6_}ti`&vf=>+znD@@-CaMi(i*?i3 z=`ufofGX%;t5iP*=Fz&L(^z-D?;x~50_MH*ouH?ZqVdu+*5loDfq*KwzJbSmjP0dY zJ0`PzmotUE4Iu&Z-noB;o=RhGOk{J-)(Zqw!4(laa%a~H8zv?2eLs$4Xn_RG#p7%H zq~Z95=NLAt+X;byDj0v@o=jpYUNSbC{R+7x#2Fv~*V^(vYQ#poc2g8!v`kkK4_sti9fGQY4P^o;Hy~iIHda*tsngm)P0oSGTlaxO^ z!*lc7v52nv0s&Ppg23nKqt4@Q=^pIa^;QI0AR(?;Ptz{Mj-B1uh0N9h0aY-9z<0(w zxfb8=;mCR~^d!&%32_ey*TjW*^~~1nvRY?>fGQYs;Qnsgv-o-LAhvH#Ic}+O42Ax5 zroTFWMh{OMMUnTM>BVoKQJD8pbgsdfUVfnLv#qh-kfmt{vp)qjXd&H=rcG%>S3PMY z-TAf`)%16y<^_Mz#N>VG!E{HuL038FX93?&_S}wO_GC^z>b5rrZ4Ysx8F%VY^qgE2 zddrz6kUI4FV=h|o-I)f=Q%-gmkY>P&Uk5XtMcq+a{t0wCwOfRzu>bN@(O{#OF!9f+s+9V&TnYzC^@MDO0m z(R?j8dO73?C&s56FuTXWY!hD{J9~dFvZ-;VcWOSNagImO%)2hM&hQON-+TmB{dS?l z`za?>GdBHnUp6s+uCRM6eE)D?R+Y;6qb}PKH;}db z&r|R+AR*S0OW&Ha+@>KcqinN4Ko#^jcn-@aExF=g9CInUg5iD%Zccm9e&;q+?Mf2~ zt_-F`rqYItW#L6KtL5-Kg#!j zn1ZEr;|LZR{|z^E+lyAIx1r2HO@ga4Av8?UZN=wPz9d|pI6IP;o|9o*}*j$1X>^gV*@;f{2^QF=M&0g zM>Tla~NVwpal|Q86(WM;4S^Svic@g0s&Rx`24&7KAJcq ziRH+XkhW`#FwHnUpUO zP}Om94%)WSkq$eiwA8atM@s<)39QfG^B7tnF@04oGO2c=vrCmSJ{4S$D#wjx5BzQm z1XMYg?MJ5;@G{DkGG4s%#f3?c>{RGu3@wl-wLFB-MJHPRODQ8zj>9J(hqB%U?*#&? z^0w_qU-`Vj@YhNipI(?qi_>PZ>>>?3I=m2#3UQ|;*DH|E&wNyQ!;N;m{0Ql{Dnv8F z-09!*O51*;Z{H%vgqchyLJva=B#uPnqo$>9v>;nKMQP3NiPY}WO!j5zM+p*8_5Df# zn#aqQ`58Y|X3}60|@f@L~ZP#)&5X2v_S%xXX@VEU79V=Y2em&T6_+ zzsYZrcK8W&=cx-_KL0IB$vuu{Z*ifA`Dvm&`r%T6^Kv8Dpj}h&>`sMfO_Up*_VY2i zsaJ@e4s@ezVHIj-RfxXqccTXN%6+u8&BBETCa_*NeQ|YW0a|p{jjpVDgzU$kL>(n} zTKc}?e~3D#9Bex_kri(9!tl2sadg2+RMXj=n*2MB);k~#EFOu5!NoCvC=woPs#E2_}sLw!m+W(>Q z28Y|Xz-n)%vziXB0s&R<8FGIY6P)BfjWryw5uPq2PJAmwzJ1;49)7AaKN~P}GFJON ziFJ}31p=zzljbWe3JqAh6T$3@N1@RAu;N`q*@3IAC1`S1VsM1A@RG}F|LYQ`&s+ec$Lu+?<7vaX{*K-E~EV<@wuD=q%6cw~1P2U9DY!u%En zV`zbdzhxfkW9&x#S1Dy=SX@6{^nDt`J;n(HR5_O)L&l!2G{s3dBiDG;X{p?4Dr& zn#knXc%fcFV&2YtWYEQ(o|vc9#EC|E@{G^p*n>gS1OlpH&F3E3wV!g@pm3Hp?gxTn z4tRy)_@l{-TDj)PC^jU+M}ihei1$(1a7&&Z7sm#cW(WjS1w`~R8n^e! zs7S+S|9 zZ*YEk(M;1REb8V`fq<$bmPe3w8y7ltj#5TY<{nAaXcF`3z6L`JB;a?$XUWhnsekYU z7RT40LjtOj4;?{oja}&0V@erg%SPh1n(?e)bqm-d}8#@C=Smj|*kjf1DHcVS(d8 zxMp0XitJe@Kb;-UuDtsw?A8K_Td((_0V^FT@lpK5^19dZ#~l%D=~EqH{W(;@mF2wk zd6_HA>SNj8h$y^zTsE4&-I0EcQAu#m0Z8-nKWZ+>S;4XFG}M8)7G)8#adJ_c$kvgy9~9aE!|{QdV}6r&o?)e#cH>Xn_QrY2vF) zZw1J)83}BgR*pbG)#KyYD2|Uyrlu%QHw{I~s?qW6nYqM6eWcM%6Mh^g`x>J?PMC&E`q2b{;LCUNZ1k1iPc=e1g= zP$`d#efj;rV}m5GySTf16myUV3Z6bB{$z2VdVw1aX(XnkdAd2S|DM0HWwxK zaiT3>E9WR`-`kEW4hJ*C^Iru5s>Cs8+R$UzZ+tISHnuT=7D&udKY*6{I8xs)%J*^3 z=@8zp3S=|hstW{EbvT)g-VAI*?-(f2D91-_enklcR6)N~r5fx% z1;2Qe#IBe{V`zZ{9Pjd{J7xub)jpBUd^SrUpbGk>D%Hm{io-Qx*hPcc!nhU^aIDVf zg!9U<8ym^&?ky7tsDh(nmFj7J4*uRFgk?6lD|{cY=EGiFr83w$4ZALjV9RYPgx(nv zFh0XqJALbqudIn>-G^Qf2&jVI2j8dYLbVj@n!rp$so-Tm0>+tmKiFuQ^dx8koBipa zKtL7riTI9-WlxH3oSVpOU+oaQB}l+{8P8VVznsREPh#``%Mu8vg5DsHMty4|@7gqp z4K11>czuw_|9%Lqba0{h8j45O(z3r?Vl$Z~jtdqDsDfTCpMCALMxK|I#QLAK5xiGO ztg$?b_L{rWUW*hDd1}l3^5xj^Z10{13H}yTL0_Ba*3P{x>*bGTb2jG)emf+@xruPT zThAZgXlARGAP`UmM;W{oZBS=joI+Ut-H(NN97u?>8G(rgEZ}=E3k(bp2&jUyKq}RQ zjv9Q2|Do(ZV=W2JTEH@3l!E*19&hBRgHdeD^%WAdKmtAmmFi~9U0L%{EQ?IPDiBZw zdr>~dd2~=dZZeL|UuA@$1rqRW@~qkmXLtaXq8IKZUlW@IF^~uyebe-1!q$DSweRlrO&-a zv!E#tgc%b^z-Tm&^&Q+TrC3BUkHv2V0;=Gg1+Q1>?eW@eVXXb0@50OvB%o)YQkC#I z7U$`Mn7^Mmn*mjD4uPMYS+W*SE$_u_1I0NONQgc|+me0Q$7Xg<5wvqnBkh z$#3{A6zXI~2V7QWWjya@pZ=;ud)_=j*)J^Ut}8X@KB-3j z#+LN?M`bRx;AK}b`>6+^{pTPXwMz8zb4$9Sa~(Qx{}DR$xFx-oU5COWYkcB!ao?(YbP2@mll?x&iRHkd~Y*paA6rTsxYK|ib`oA zgcYg6RlzH*O}GGCbJcNwWtaeJ+4M8SSxx* zzY=9gPfinCVxN}5{Y&_b9(SQedxXB~5tHP4TO#Z^pbAE)5-m#?nMt?#5q938*d6v|0 z>=#}}`!gD3$=Xg#ul|`pK-IeM_s~>73%c`y;g61!8y1=#;`H z(%d0;P{xOrRBJ>dsb}^blvdi3c8qMq-^bBIjmc*ZcNSOEoIndC4949nED_UTnyukq15u~p8gKWD_!q5VVFH>sK_^ehm?5pxcH98wX z@Xkv4b7HVSK-JS8HK@^dYdT9)DZ}h=4EYvbBG;bpf}sTx&8F3&@5@_J+ka)$e~KeJ z7o3vmSH8a*_${b{-@HmS>*g3@Dxa21TsmTCfrRh$S`^6Z^y4qeeVmw;NEWE)$lGE( z1p=zXw#3fEl&tdU!Cq_%#qgV;Ry8On(&pbN71n&7-#*fsylK&$g$Da$Xo1AI_!`uv zn++ZMSGlT#5iZ2`YbRDZaJWD~)$c`5QNMYusIj^7bia7IlBIV$v*-2!7+N6lnwRm3 z*wA7B$~f?%Em<vsh+5HB0cTgSvyy;3`o?TtU*gH zY-q#3GA7H2c>JJ11XRH~&G(KT6GXmG(q%3+zCzuFM1`sr-Tv5$cK%n!rFs2H zRf0CtNfZgFf?pax_jPJdvZG~~oHNUqw4-Inb+<7+@vOO2=uv_C?J=cuPpL`iZ^}?m zk}*A2p?tN5XZw>AO@ibBpEL=yK%(&NT{Pya84c>8v?XgA4@XyKy;s zHq@AUU02HRCt>9BvPSZLTNQy8_`5gt?x8l!j4tk^l#!|%O6rELqrWex2?SI%=$E4i z$(U|Gqm&VHIFi^MwxdUHe#FoMiN?v{xQATjUH9W?z|OL}Cqavx^TY)O}@#_Y{+BY}Xbqi=7aW%o_#wF`=uap8zFX_)(4 z{&-oJKno;3`QJr17q+DNqm(kDc6bt-iw|YS&&PoTRGGV1AghC>w2&%gxP9>^Cv0!Z z&uv=}Xn}YQYoY0vM;gMIV3l&)DZ}%g0+&LN;0J!9w@65Xo1AD z<9CsV6Mt60N*RUE`jgR5=g39h)dT{nV6EgQbQ|#6dm~leS8pnOQO8f0p&NUQDdBsa z!?O7vjXMZA(}VA7ZEY@;0f`B7%FxYQ#&pX^rS7K2NMw%7F4^>msX#y#e1`m-hPGbh zPp^ErVV1SFt)p?#*}k*$q3P?n0vHn^Lr- zg9&}{TPdTJpC0+STZ>iSv=#`cg5M^uSMQsXNwN;p8D=kjgWz}H9xX-c{Y>a`zGo4? zs*HN&!)D-0BsTcXy`4AKJ_=AG{NVsNvwsf;B7-f^r>4N z2qZoOZAfj{dVzqdJ&b=*5vJ5>j^el1z3fS9$}I_=bVh;}NVKgiLtWk&(wk2dzkRV3 zOtwGJB{_bLF(jbM@6BEGexWICw^b>lDr_K$x~@s|-?qZg0*M=%<*0|b5zW_9p6P+QjebQ1!-ROl7M_K~;kx!Pnx2Y1%` zM?HoXNI?IZ_ff}9iCoi)#dtRsJY=YX?IWN0>1Rs{`dc%z#E%$SAo2asBlO=2OS$;MV zRUhObwSNTys$l!bz3`~+lISaJNkZ9;wiLAO<((>U-86kze$h2-}<$HQR z1p=yIi^_K$Dh(!qb56>C{cA9^K;m#>CA!hnlFEIRGVT@*A<;9J%Z|-H2n1A#E%n$p zBS_(}1@ebx_c63UqU)wg)V0ilYI`eXJm?rne%N%92VATc2&jVo1JA$?8BMa{ZRH)e zuVH9`L`PbQdat*jkFAw5T&m(o%C1#()P!<@fGW{1NxhLs^j7tu4G&IZXo1A~o0Ui- z+=6EQRbsE*_-G<-s;=~3Z&@Iq>R5++=v03*TA-!$gAT2d$j|EW(zTH}7+N54pO0(T zwzi;09x7#=s~<-eoY%usk7o-6R9*7AhYHNi=*&9ht9{Wei99TH=BGNW#?S(Zceg8% z;X8BM_=Hl1+VDiu>_Q4ou+I_*sM^-%9(wfLl#aWrl(9N+97%1o7}Kw*7+N6F|3W3o z$~UL6ia zlB5ltjFO?`Z*o(z`)+fA zfGXI6^Jr9y!K8IhEh5D{5PAbh3=676^BnoJYNV9W!Kx2wX4aBC`Mp;lpi1o3evar# zY&Thx!viJ>eH0{M42XNkCWOp$bRj?WnhFF|!6=nV)#pK1QvS(<47@f+h+jbhM!$Hr zp-u=1NKhyG@25+hj#Q(k@s`xCeJx6Gu0?lNThaI9E70y4)d*utdRb4&_jz16fYkie zBR%BS60|^~!KN0aF0-PRJZFmMq-q5b?X{+4;$S<0fGRO^XFaGFx&PaWwA3jPVtSC6 z`o0DY8gE56hAU-kvF%1`Y@Nxh#90CXRWNGE*CX#L^} zVSIiaO2P7_r*CLM#R@97Vq47A}?%||agNj6) zix&u}g71d!=~R+Hnxx6NAz+Ktc}xx3JIabqpZ^HqtXkBj!HO(ZPhHK_3>E82SNBhe{@i3LiFOzuKhik)-?EzQii-Il?*=9m|lNnD-cjc z_t&8Rbgk*$Yf2f9`_ClZ*EXZ$)bud4K*EHVVfMtDZoI9Ok+F3q`7o-%r;mjehL%jO znz758KD|_d;4ks9LC8#!w{(uQLQPF50}|&sUAWMiMx9a0@bpO~^W#gUcj_$!0;-Pf zs6pNpRu&|(A#UFV0;*sQ z#f!Oxz1EKChV#ZZok4N)*T%eROIcF*vKR*$--c~9QPzCF;a($csW33j|a(I#G>&x?0mg4N9+eqb2t;9PZ0gT~aZ$Kmta*`Ht2d zV#(9KCuHxMbb)}X_$Sq9^j9ld_Esrl>9w&WBzw2~_{RhcEs%gQa=zcI-UMP@G(*0H zW(WjSol`wU9g3`I>;t8Y_nVW+oGGF5)08L-Eszk~MAJu8Nb4|7`IXNYfq<$eMo-bi zIaYM=1*MEL0n^E~v{Kses6U1lNWhkl*WKt8Qs|vmv{8GIKtNSa%crPUpcQR)Kq=$d zrWvH9M=vBLA`C5%5ZkL)D^f_l%_(VWOOb%8)A~=*OD!wfXt`2G&Ds>=>7~Ly*S5yc z0twhEaW5lzD)FBigwMUO6$q%h_^TR?y~XDsCn#lj_MbxBA5OqyA8KQ0frQvz_4iI9 zlP_<1kJnFKA65PRng*EsT{LpfF(cvB#t zO7u&%o{1xk&z0c?bq5760}`UokWd{p9Q8V7L?@&vWwf*zLo!Do+;$ul2&jUiSDw#M6hl5;a>QwJ zxiCtF#2~30&8#q@i71Y5?D<6)PjrA9Xe0;=FBoVRduqe=9}9nv137s6;85>wli zqiyQObbXFeM$fO|#Im~|I$ZZ%AfO7)S@8V!t=fDf(Uom?zKP+?F`R3LaVEaH{|H}| zdA18nJ3=wEKmzu`d?%eCTk^@#jcFHO5(ub*aVEa!GIAj`QO+zX>?np7NWeZ=rOIF8 zMP7Dn$+~pABoI&q<4k-9GgCw~cN#Mjzato0AOZVeezt79KN;|{32QR@yg)z|j5G0U z!`MEgi|${!xpgjv7D&K8m}eVK8%P2l+>_mh^AQDzg+UdJGjZZ*D8Z{s7K59a$0rX`VOp-*Xlx9tJ}RWQ!P=O9xj6T|ES^dno0 zp#>7K59TN8OqfjU@-};S%*YZ5sDg1Ol?vNWBh42*M-lER7+N3!`(QpwwVXnF);^Wu zRdWOas$iUnuk=oxN`hzV;O57|Ftk7d_Q8DJ-ST9zs%Zq)el{2QaPzB>me6A>d zC{e$!PG042m!Jg_FuKEI;h*}FJReiyXFf|HpbEyB_+H+}dXYe1E7D2bOM(_ih;g6l zVnTwaIFlg;#X@ElREfD!&s9F;cZmnFY12XX^GcwEear zJp3%W$(0fCGk_*vBx&capA}^q`@uLYT8nk zPZ=6hqDM=+X-mmBOVMFNeOh6z5CyL~kw$&mvHEkrgx`hbZJSbt`tx6ky`k)_J}6(E z+;FyGNvrjV&9hRpqd<>t+paDB++B)>@6w}R?rKXN50@a%k@~b>x>CmHFco>W-kdpa zwI@0Qf#gsmm0Ov`}!muX31$tB3w(13n?p(XVT zEJ0n04d}a}%2iq2eu3YVv}Bfi7BDUK(@_!a& zXulGa)!m5Ran_W6eYt_uHyP66hnkXC!42e}Ye+x8Rn9jE_~J_9zLm%u-dmISZKddX zq%l2rL|y9rqy%kyXhau|*O1Kl)h=%^qK8wJTJj|@l(^hoUbOB|Q{uCy40-Dt(=cmw z33@NktKqp(uSbyUB+vXO+Z$Z`7L8a)6tpRN_Mj_^Hm`Oq&Y09s479wbY zM08v!TEy?qXtqN9=J#>HA-U-MR`EXI74GNvG?U-ow;#$I)V`ZWYT9@3jw#lYpal|L zhnJ!a%M9r6GYWC)cpBNWu(Ralxe`GFs!k0nML9_Z^h=IH80OC)N%ftu%~(U}{v!US z-W$+)+8R=e38g4}hXEbkTSK}st`yB?2Gk}_Azsf-C59^;ah}Oi1TBzwkywg~HyhB6 z0~MlFZx$)e`6wM(rziXtRKY9cCp)Z|MTRWDEq%1gM9>0>&!MHrf06+`y;~{6-#d+X z=x>tVxUUijs1olyrg1kZ%94bsY_q(lp>2j zLs}E0oIW%W#gkoUu3(d$n-R1?;@g%|G^>dreLi0yXwi7mZ{acgu-IJqEvUM3uoT_1 zFr=FgDa0u2B(nSb0esbUErJ$EXsjzmN52@*CA$UC4oh?HJ!V(rzH} zkV@&}aXLZ^2Xo_K4jVr|s>2YH;jx73@Kbf+Z$TAoANgKLdq<`weP3x5SJf06BCn%@;M7D0(&ypCyKq=!C$sy*qV3pgkwCL z3iNl75PQxSEzF3gYlHl}tGz%#l~zazdTC}%s}?9%Qmwcjbkc~%hb#9Hj5?8lAt&Vk19O3ZD)`iS47r^*nN(aP_n%-aybnldE-gV5 zos6iCnbNE2{_rG$txDvgKvRK$D)?^r8M*g6kUYBzdF*oo!S{hgYTFWIpJ7PXTvp2P z@$w)qoonO|{}~GeR6);)&#M{K;5PW?M6%kAehjD^;rWVZo$w z?FiX6LtP-CYCHEV?bqi)sd0*UA|B}iwlA?+Ec5QQ85BZXhHWk2`E1QJlC zlUahcpE0DbhARX)*_RAma8S;2Z@|z33ETB0=tHO>UAI{wv=;RwM|PZ&>uOa55>TZV zTY?Ic4C%Dv3SqUUC)xSnl3Zl-149cWJf@T&i$VjsrJFKVJ2%Obd{}415@y}SJHD5o znj`x3`DZODoAB{YxISIcMqA3ZE=5fu^=V(Cj0e+FTuI6^OLk}T9SkjyNZ($H&g$z^ z>mY?l?rKe<65QC@%u)<32IghR?2;ZG6sIknHY!6GF6hx6;}oJ@y%X7EZ^+i}{f;L! zlptMRIvJ`hj5%T1d|lD-_T>39Ew-)Zqi|JllnO_$eBX~D9ZA#WE!f)aPXq$0;1l6> z_p3yPUsq$9qwfpP3KEMhm7qaQxTjyBJl!*~_T-Q3z^?VYC)_!_Tk$^rtg#~f3mn-J zfAOjyQLa{o%FpQ0(Q}k%)ufXR+1<*9-OG9}+y_*_XUJn2o@T^yKpU30qE2|akXZGD zk65T4y|-K`14$;t$g4HG7gaA1P!<2K6m>hLN2hI2h*@8?i9;{G%f?$fGV$;YWYETd zhIQ4J{Nrw*Yu^m$lRa8e>Z2PduiAjNpQ}8pWiFL?GSXvly*d#8w>MCuXnpEctS#A1 zyMY!z)~9_kv?cgUe6JUe`?y(KeYUKq14(IKf{OdeD9w&T;?6 zPfv23tj}8B_aM*$39*dLN1KsxOZ6DKVkZz#HPg5RRaqO*5<}(AwYM3PuM;$x&Lv9% zEszlJyq9Z7GS8OpbW^24U>^>nDjy6=kmYRydOJ~hRu*PnBrCUGZi<=`Xn_Q*`8Ss0MOIHf zhONGopc!2aXlJ4&4Jt1|w5I`GHB3vYxl)35tTmvqI?A0Vln*A0Ew9QpY8NoHK*Din z33|NGfNDD_#JR{JWWiY~kKTVnAfRf=ff5w_oxj1mN=v;-D~kMlcv8MOd_BHoP>RO7 z8c<&cEeT$s<+~CzFWrDX{;Uu`Z;T{%wLA|wbU%g`NWiP*QG-k26a@US01Olp- z+$up{PYtMrtdwC87DkHJ9Flb#E@EgA2;n~ZI){-Ct9Qv7ze@!I-mUA!67<8*klLgx zWgP7FAJH%~XTFOMNSQs2r^)aKD|3$A+G)%PHG$)vAvtpQImV6 zXfiMTzQ2~_QdNo=(WfVSX-PqkOOXfGr!)S2gKuVpk*CL-Ftx?$2wEVK&ev(wbkwKz z1C%mUp+iaAFipN&k4Qk3q+f=LP4(%$c!kKU?Lv;IoPq5vWr+p(_y^_8Fn67bD(Zz-+^*)_w4dA>?VkbtU%o@Jmh%s~3AeQ>S)US8cD?=kLh9 z#oBui$d$fwjGgjQYVk!ah2X1e@GV!8y7ik)_WUXwugjnq`$<#s){+)Q`|i;iyx+AD z_kE#$3@M1%wLZoUshe7aN`-iot~}4}%jA}>HpzoPE^pl6KqAh+jL7Z|=+=jBg#H{+ zKt$9BiVl!Q_WrIKWAVSG`0Cz;+%p&YdJxEkF$=N{^0nYr@kjEj0^cx{34TR5C%V-t zV`IKHB%xclZ!wQ_5rN+$)ieavq_o&oYyVr)@o6NAq5fM$j_XvC3wk4#oglx>Ut2! z<&|!`Z@=d;-!_pi+dp9F9a@<)#y)Z?T$H_-%t2d(I-Xo^#{1qKK(@g>h7?4E(D_kk zVz{_jMD4q+DWbTu%M{sEKJg%s3vCh0`X*NsUOi-%On>_}Lkc3idwZ4E^~qbiLXIXq z3lYeLwg_d)E@;4?yjmyIRlmuQf(SfIC=WSZZQkvzD}Vdrz6XI^UK{84HMRL>c}yNG zevKgo5qMIQ1`t!7kNZAWPB?PKgFvoD>rdP18dChDkNTnpQoZw$%$MXZ$4@Y%AOiIV z%3FH+9lt;Jmb`Lxj|YKVxOY)6y{nD*ik7kRkMnC8QV@aK0NEcSn(}V<{*-CInCC$t z7w&eJHD+f^-v8|hIcpQ$atymAB2ZtUQ*HeZ{851z+0hy3K_D0I7<7J&`-ac2pO3d} zz23$s>)gg??1?id+LttmCn{@MGsaZmf7Qyt-RA3UjMpOKMcp$tn-VT+rBRW%7R77x zuAkEK?Je?q{uXk1V|Ue_)aJ{1S{|I~XB#Pq@O^p4j_w*RCUj9_T<+C~Pb-|9Cp_at zAQ#3B$#Zw3I$ydq1E2WMNe83TSk>r_R9971ZXeE&f(Vp49)nrYa>*D{5RqyRX=J`|apI&x49hZ*H~6OntMnw32Z3D0r^ncf3WbYTRg^!` zpJ@u`wiEWG$!=>;D#`cfNrGK>%7_egt5u6BH7)NOV!dp1v=1R^k2OdZT7bm0>g9Ad+YE%hLf z3*SF!`m1~L!iCqfobP^ekb($|{8D$y@V-3z*qQ9Peb9qIE`0wK^Lp5y$F3g1<~R!+ zq#y!g#dI%ny@9;v>3VG8b?HGM7ruYXIzMhO&ycwod!2r+gA_zyMgg5_4}avR*MD-> zH;(ookPF{G)jPKw%G3P3)tO#owu2NzU`7Gmy5Jwmj~vP8{MmJn2Z3C;VkmE^(JY%23Lu_KOL7r#VPL1m>MkjSu zT%OpC*J<3J@jqsG5Xkkk9C^M55 z%m0{i*O{Juk_UlY+o+dC`{m(cRDQKz70KP7cbt0Psa$P1Lkc3^M#tEBhlYzq$rR$z zi2gjXV>#zqzVRLea#bMv{9TuD5jsjC_CJi`-Di|`R(&;?Aq5eCjgPShRwpf^okFAx zkK!q-?(&ZsKgNSVu2VJ0?^7~dOueEI34a*CFC9GVZ?~vFLkc3CmN9nYwBcfhs}OJM z_2=7P?Gbsqjq)In%SYOIdGe%B&^vYCzEM29%wbU~M<0e1M4Y9V&Q&^ba;8^%d#Z%} z`R%T0WsWU9JqYA_Rw%~ax+F|o>7o!<+6>@R6Q`2PT32I8K}2^(*+Sze7pJyD{Bbmj z&krvnTRto8K_J%$^6oUR7AC$}t`H;Y59C?g((>D>p$sXAI8~Lh>B@wO#A6g<=CUZh zd_)`h>xTCZB9QAJiYN|#pIXd5s}Maa4d8qGb&^LH{^B475txfdF_!%O_|lToGh5o9xnv#*frqQl?EizIa;%OFHKaLkc3c-a2DP4oxF2o>GW!z9wBX zG$DI>_pAqjTy+LezR##MBDkvh&U^Vf@rtWbvU%%|Fr*;j&{(qc8m19R3M<4A>Oq&d z`U0ozy^|gUa*fG$#*V3T(oYb#+WsvJ3sg8s{ifmJq#&`D8Dquu6j6J%&4Rg&&qY> z;U%|=oO$+n5XdzwlCmag-_0Mb5dYTh&d1%_C_22@$&iAG%xz=rLzBbB+NBE7BTpCp zM^u=+yUXuEAlKAz(vZ7_i|66$i%OiS8(+UIwfuBq8$${rCYOq_yVnU9ex1wdCZl&g zuew}wdyfZ!T>i(W?T~`hm$S1Pqi{@TzA#r!S*7Myh7?2$OBrLg4GkAf_3m?KZbx1} zSCmY-V6z8-T$Dp>e{(WS{IF7uF??iKKEc;bwtTyYAq5c+Xy(7{3=_A;>AfUNSKjHr zF>>-Yd@H2r%589lP zpAP=xAOg9>+!*`Y5vj%A`Uh(Ueb5h7$MRBE%QeOm z`9Us>A<;c1P1^DfZAP(O6C}gE7WGoxAITnE)sDAmI)mNow22`F5vZeD)<3B_@%z)h zXXB>q@F0*2_ea_jS9Ipt`gCBqAFpLdK?LfkR6X!lS3dmrT&z!qtsVq&;r>WIvU%P4 zq!k5OmXoU(QV@YUD(SoXd+=jjPB|^#ZSWwF3-?E=9vIP!-~Q>6v-a&Wh7?4gj!M?u z>|VS`w!F?4U#|5akPG)m>J-wb4}aUHq*Jx~Vuln%ppHs86ODTFyM@;Ko2*~uK_D0I zkCyc$WnW%8-wJ%$tFZCdh3-?FzU)}G;UuMl9i+wwXAq5erqf!^a#69`YO_6fY zZ?ilI&0_ZUxS|`w>n5c1Ztdg=j4R0Jo~17a_y~29t3jX{zyH^ zYj@+FD!B6d1IZkuAfo7k&s8w=MQ!fPe{XeCR?I!tMg(%*CkeTKP@#xb zZas+4%bv;k<-m6y1ahGrP4yqW2lKEii5&ie!;pdq^!r-YYwCV+_UE*s{;*me1ahGr zP2P__gZZUy5n{^kBfqq}h$})Kn_pdlA9w+?TgFr5{qiLt6jzD>qNpa~w7()so z(A!2<(T2hNdPH*BWyVJb5y*vhG~M*K_(z`pr(oHt&vpkXi12#u9=#dFi{x?S^S4tx z2;@RLnyl1igZYmYzLwuUNbVp75#H*vJ}U?D<0op%p##Qx>h6#WYw#$7_3<2wUJ~ji zPxuu-(<{b4KRr~ue;eYYB|ZA?uuzdZeF~?0`WSoS+)!~jbqdlGf4qK<)p-``{{CAT z(l9?$CiOdQKYkM`et#L_;9sJSy%)~0s=ZUYkK2{;jDZNubfoUziLSCr*V4GP#})S= zkjq=oS(e>q4OkktMp!Y96hvTdBz4C>{~!A|eR?^wusq;BscVV-P5M0oQo)A;l8Qp*y$ z1CFNhAdm~QDXD5}!c}(YLa2N7mr@+_P@h&kWk3HiOpI&tKXX!3-oDC?MW%K$l%wva zkoSs+r&&+gzx4eO3B2enonY+;^wt966 zH|k_T4+6QcPKSIl`5&_8`NG^}Q;T})aS-8sAC2nXU>|Cwb@ya0=0PAAR^*c>bwplX zxMfjy&9f~G>)J81A2ZU(x(mwBC$}izHn!=OG00Uz1l9=9?L$A6;-wbka5DvM@*t24 zGwUc1;OkO+LGCQ>rA*S3L5B#eR-o?qvpKJPB()oxZ?gx1T$qJO=U`F_$TUmoo@?WJ zG650ctsZ#)tSYZIKcU-c>=q9KxiG7Tx=pvK!Uwdp++;WQd9rs9;jK5=(Z2?NJ^Go< zb9}!Cfn1oKWLb?WSLCy|zm>zMUG`)lAp+|gC_Y%a5|1kKM24Kb?Lipu?yxv;*4V)R9AK0oVaIWut*jub>-Zaqbj zDbMnH=Hv26mZTm8a$(gC-N`!K;ipF&l|?Fsc8-N+fRvuPB1B;IA?2!lU4=&t{Yf_M8R9`87uHQtzlI;T7aTp81YB$R&eXcbxHu9KrHtAoU>SaV=T!dEQ zp4R;Kgw)PAp-(&rUrjC$BXZ)=|uc^iy;LO7#E?c-wJK{hZM#9^Y-2MAdm}d zl&Q=Ah4x(LyHrlJx$3E2Mg+!1sP;9e9bet8tN1hamIr}cSjkMQWN8O}`fx?@Z1W|C z6hvTLgw}52cKmM2OJaC~YaRr0VRkFUisp9UCw3eYDVtsJ#S<06!QRk|%-Ha)9M zQ|__{fn1maOY_*?p7MP%$OL`PFr**?<04dDGrcvRI=r^rz36uj0=X~;maD%B|n|_Adm}lV97Qp)tdi0bGR(r^f!hSL||Nm{Ot!@ z@^(dL$&gXUJP72%Di89W4{OWIMNN_a^xEaA=0F6-MJy|pJlo|rER+?CZ1f)Wc5q097G@&R>W9V^5o5Un%xQA zsI8kk)isFlMoexbsLP{&NbLsSn&3eo7gl!Acm8`Fe&cMoTk&=hPt6Y^yp=B%4^`)z zA7pYv7f`JXR0$!Mw_@Z}+kAXR(+Ib~y&3Fzo6Gj>=wNZ7a0*YqC2!V!>Op1r7PqMT z@m(H9J(W~djbHUuqJB=Q|B_$zbXssC*eTufvcDzS>Xe_@t`t8ea=T#%mXqr>)Jgu$ z8UKpXArAF(QseklPp9*Tf}N=EF8hNDDIY-f6%l;(>Iip2x6#h+0&ndMpWgYaiWE-M zEbr{~A@BTK_M~uTWq4Hd}~5y@Uh2!Yf=j5ujn8r zY}*~blP84}>ko1c{Cvkhx0OPS-x|yEolD{t*z4o$N4intTr!ckT1uyP)+_dR36qPi z6;e897sc9x`vr?c&lO@zNGy9eDXF`!wT~kO5v@AM+BI4Riz5kB5<;x|ogIh{cAM`0 z+JitY^n{Q(>KN<{Z4~QYmq;P(t)+R3gc0tE-Nl{4eUdq6Dqi>7*FzlnTd=cx_GN$T zfgw%|t>v_1FZ=)9tJZG$HKlpGtPyUNk=Z;HMD+e5)aj7@oWK8mWuLE}7r|Q|jc_|I z8sJ&GxL()BJhcDYm`F?-sMb}Z;0Qi%Q)xF{;eyVH`Iqhahl0f+e~8m<&1L(q{lQ|# zun?zC-m7-Mk;z4#J?dAD|1*s5-d)h$Ir1gLx=pO-++tt0ovnm!t;T3sB@O?3Od)rC z^b>{@L||Pq)x_<(!rqrj?M_-*isKqZ-y41fv=Ud|V{a~}alh$N#IxEFfxa`!5bFAZ z)f|z|-FZL12Z3Bu|A@7ZO%4`04y$?OoBWo&oSfM$_&5hg3L>y88+i>zeZl`;lijVC zI;{tRTr*Q#w#P1`uXc_aW7W8;>}5z|cX3t6^L^khfh*s#f{NT`M`k5+#k{XLQV`*l zRpTcAu;`ysxy$<$_8^d}P0$_tY|kKZqq|zW&eMWPDoc z%E3dF$`Iaqf-mg^ey!4uUoxC(h3LsYypW0Rb@NOZm}e8lBQuE1af(Q)jzwk@rCy+_k3_Bjub>tS47nv(XToqT2}6(RyFt0#0b#!~q#&aF z${=S_-8=sF$ViprMZ*YA~d|LH&7gFr5nH2JT5Wq8tb#oZrUq-ID#1j>-I^wO8+ z8$J|uCsi!#K_Hj+4URuwl6PrT$nCvw1VaiUP==OO>+Ap6z*V=)^ADoq)P1c156^iL)iSW0!F| z&7b4xuz(2EYN?vMb8#O2YZ-S zUu`Yp&dFPXAq5d$yY}yNMS1nSW!xdfN_#pFBVygi%XW(c!J^=6bq;nsUw{wT8Q~5n zH`IebF0`pB+ps`7UUNoax96q147F|SA%xmFMadRs;E^|qxJ|$Q)1$W|0=pcM?VL6n zKi{jEJ9fok4+6QozpB)}th~k9;_k|W`#nAYL|~+eGRb$)&XBL9J9hdu4+6O`vPGJH zu4H^=zdUZc8XE7dNTKFesmpw4Jno6?2zn!kVP7R~>bAq5d$S(TiTfm^%3bjRO& z=s_TtR~LP@Dm%}Vw}>0L;}}B7c zuWDI_6hz=UCZA=35`0$4(r$@jX*>wzx+Ct`$9@SCHMIpfEwU89ytlO5>)!9t3jrKSp;4+6Q+ zE}^>A(;4n`(StxPJm)RzOn467Yj%j6 z>O~5V&VUHC8R!jW%*;<0P3HbGKAi`FT&UqtH{CI5`Q#@bWsPBZJemw5(59jo{m-fR zv%3GtCfy2q5Xj}#;c{(G#`kBwEx()al}95(1p1sTt3#p0e09&OGM&%yAdm}vSrnsx z@|d-s`$GE3bBF#m^oyZBXIVXpKVwTfS#Gs<_fN#{?M>-+eV>mb1rg{?AiZQwNTzSRMp&p*}~xz64qLy+V21QahhAq#y!!aLX!?HV+@~&+ne! zebR$KF4X6!&qTMp{L3qa++2U`VMsv)?%@^1?LTzAeye~%<#&VTC{p@kR_+nHe;RWxOYDGyGCr}szgG)^F*n#ICpk0 z)?8sZGdpEBAJ@+tCuVn6b&WBI-0$kKRMn~q_0DHs$>>C!P3TvD_lt!YoLarp>F1o! zvpAXeX7b04;kRqE_UFe6_0F%%N#{)cv$W>=kT$LJHcb`%oaDQVjwNas#O>TwS&_VJ zg?i_*e3;X0X$Q^aUr3ro_x}3%hwW*c4_$^BMBQI2u+eRf3H8ns-VJe<-khYl))xzQ zHe{HopD$-iF<;z4IqC*82a9Ni5X+C^dDPe_W#k`nk!<-Tv4wz7TQmBUgc> zGEL%wQoZvv5z=3B?tA@r8=W}f|90?8{amBZNx#+cy&2=n8EIv7r)*Na^9v)+`FH>J zKyyX7vHk5f?bm0a8Kk$&f66H|02!)A>*c{#BdlO*s4 z#pgFzVQYCg{=`ZB&gcJ;OeC8&Pa~$42o`y>23Cpqyh?Hm{Z=-*u~DdZo_BjHap>VN zjkvHpRJ0xzSc&5EN__OOmJB&QNvLQ zQ185ZvkYSNz$_Y3Yhwm6dtBg)5}&`QZoSeoo@6(RNZpl-JX7s+N7FhTSEhCD%}6|FO~`s-pp@r>zPz2#Qp7O?XF!c{Y>xN{`}61w>Tulu-ZZ) z{^EJXf4v$+E5wtPxy9*y7xXjj4C3?7&?qdSdt+8hn?*I}=?fJQSN^Q#^Y;yR?rbU` ztn$tBtLO2@^9rh9U7`LGb@Fsh%k=e^u(RWv^Ayt)3)bztt++C;Ng`fdJ)xgxO-L** z6+ddnA*T5D%ZVvAv+qVX=kFH2^>15$PjmH4^q;>*vYYz(cCokqTi5?Ih|0m+Wzb$f zt3R|k58r;z|9sh7&Gk0TBYzV2m42SF^{)SV&SwU(aQ{jfQt>x-rGInYW5jv?cZ(7` z>Q@zC_Pf7yk3{;JwfQyI^(8BPMSFdzpVMDk z>Pt5}k3qNtE;&zI{HNz}@liVaPMy4(>*#?bcJlK1^z+=+iS4sJav4OrKf>9VF7Na_ zvOlk4Pfw9cbJ2yy_RaTk&-aIwwXZnY4WfSb@hsEHt4zI*n>k#&aKR9bxU*@U{oRW& z{XG8oYPpd2`*Ums$%V;&euA*(a|({~0D^UuHR z_2Czedgn75Z5ck?&{y5-W(-@MJ?{IWfpL9`iT@i}sZqu%*~-T9rw<$u#_ zxAoxsPFFWpKhw&0XyyCjR$|1zv26G1DN@aRL)s8$eInPdR!L;1R8H>*CZ zuYU0dRy(8BF3oCpXtirDTI~+4cKuAN-J#WP5VYDEt#)ZvyG^TIbJ1$IX|?NTTJ1Ki zc7veR&Sm z%_6;mo<2X{h@kB{cLt6gBb9~Wq-3%30x(szB{W$ zCk-p0xeBbfym#HixaUSoF7D0xb6$g>FG|oC<(e-ln!YHFpf4(#z9{`nUsN=GQ3gR@ zl%Ow4%Zk1zKYdY}i@qp7eNpI^Q3gR@l%y|8%Zk1zKYdY}i@qp7eNpI^ zQ3la?W;wb2#S5uc3C-LeKlA*XdirzyoJ}KW5BAd@Y!I~CC9QV-&S|v^TJ8EB&}tX7 z+VwN7c0sG%yboIKl2*H(2d#ENt6g)^YNz{G8tP|S?SfXjLC|WKwAzJP?SfXj=AzXu zXtnESTJ3^XyFt)ucWJc?H4j?hf>wC6dgr*e(^nwqE71Q=Rdjow$Xv626r+l^R^LZ} zf(Se%EUQkF1a6aKO@&$|h(NAnISYuxeVdvwrX5Y-?)xscxZkZgM+zd$xndAaNB$=Z zRJ81zoAEgU9)rIm=%MTw%^C~Eoag?t}VRyLj1oZ}nBw}$VA z;sy^N%G-5X$e}Zub9~RVKML9(_4}YbQP7@f-UscXl6FzOmmmcZw4(~zQ8n7KB0AiW z(O(UaO{X;Hh(NBG^I>A$#B~Po$L6bYu{%y9kV5;Ffc;8*-mgmj8!O{?INHeq6hzR@ zC*pTL$`)yMPIlZiU;aS93MuA1*T2M^=Vsj29bgY(k1+)OPDc^zZfaMPJUeemydd9!rwwJ zIzRlRWte%8ULr{^(I*aa(TU?Hy+r?AFM`e}8GlA01rc<1`Qy(ns$QH zs{IO296V+4EFn$#=xZ^5!M}RH!cz@TGCZ%Sn&Z%F5nJ7I)qX{~XyD|;(-O}_s%o56 zKqMcPz*YMdp3Zn8k{NcUeMUNSTTXCb|0h|EnKfFqlKGyZuEAo zWgrC+MxQsUy-=ud>M#GKcORq}y|)^$diOz! z(eyQ!(e%w2$~G8nG#R8I!q^OEj4aKHu)D=y%Sp8RAca<+4VsLyCe0Y6`>=T3$Jm*g zf(VZ`XwiPf$d1zc741kLRC%}LpVn#g^%^24cy=FZQ7SUfVQj7(uxr_yA#xORg z{%Vne2xE(yF{)+xz>-`D(qAo7jLoUJjLm7rP*&HF#_(51)f7Y+d)MgHq_=a>+m$7(DWs7*@wz%`Fo~rgUlFxW3aNMu5)vrPXa+zOid;n(Vj?$Kpf(Ro8 zGlr3_qpTuCAeVU`20=CsBOAvtHcr5oVOET-xT~+**Hw;4CbrV6tjP5g!vu~V)1~Rtc-62Q@fAZ z4K&5t}N^m@$;!hb$JR z{60uQggIBt7-X?9vRIh0Sk#H5Ddv>X&*r=`W01wd$YRm{M5G|XoOWgmvRD{dEX-Ie z>KxP*bM`rEEt!+riTi4e2B1BuNI`@-=QWzL)#J1bjWC*prl4orXc-2F*I#8y zXFv)fj5o^sD$?5->FwIfi3kr@oG;6ak-StZMz#S{-?{N}X$m5Y@5~@b(`TgVGo$GT zytPI<)4v4gr!{?tG=2Tm8m&+NEu%APgwf~B7^LYtr0H{`=?A>dMw8VDqh%TdY5ERn z`dodrM#t3@qb=)aqiY*k87-VE&mB?_VKj0xhSBsnX!`nZdAOcyJK;0JPqu+ZSU@3! z@(#xTD&-yg{Hv5dG5%KtD2Sk6sQip(46+Rb*#_L$1_6q(Yc!X!kjxmy1F3!bNI`_L zugn-^8wj!u^mmRFV{K_JW4Di#Ajvk+-#Jo@4XC+{HEG6B zUQV(N^mmRFL>ODtj6t@6B-?-)+d%n6HHFrz@^b2D~sAMdMJP}wz?Uk0r>!ad3=$n^BfV#Wqbo>4C80e z5fkJxeg^$_y$IvW&bp^ljc-YKFeP}YXAWXB8>mi zjA8tu@mfXzfn20m^7r z{$$N%JkVwg6KT+T2~rSY{MTj-vWg^GMS8zNit%P^F5?$BW0=^4-mj2?2;)^ZV~|xO z$tu$O6;h0kU2_?4y%|GAGsr5^u{)$7f@~k<>o;SNRV2wOa*S0Jpcv1;){0G>!szWL z{-L9NNI`^&S$x*pRWw8E?MNZLT}3c77wPjVO8(h4P|=Kd+aN$e1lb9JD7j@7YPD6S ze3IDTwr)>OSvn#M;<3TxO3kWBf3=f}B5UmQ?dV z3L?B2DUo}#u^ZDDYXouG@uSnPvME1J{}P&?%5yMdkhfN8WZGMcaYv(t38jmA5p)_b zIt{d+8YzgN`Kf5Q86)(tk6rJ$IbOPf(UA*(E#0a+^DFlChPnUOJP<)Mw?F6N3^;q3 zUAwrQ@<=IBIk=Tm4LHLFJt|#x{ua!|7Aa z_~G*^8i)lToBWpPWcRgpsrvV_vB`jMgrLtQSo|F8sCn`(X5aF!g;P1rcUd z>N(L(vE>@ctku@Uj}bVx%?j6CgjVqn^Q&l;NLnRYR!Bhvjjg^xGe)YzK1nN4kAVo} zGT*-$gT5$9Uz8pLDTpxNycvVMACi1B+WUd~67D$O9j^Yrhvg(;$FJSM4u=TbyXbDf z+*>8BE4_B{Zy}f2`Si-CY}~&Z$&A-ih;Hcy@ue9ui^wZybxvaTuQQ86=Z?qcCqfod zl8Yndq3%h=%BE2q^OF!^#xNO;#RqJW3)Y1RwRRDKT;|uB?}NTtNnfr0qL6|Jl!Epx zDe1<0yp*i;-$E`U_2@XC4Ee8I@?ZIt{|YIHz|1PTkN)W+8B_Teku_UuPgLKWqJH(= znbXe9-Rv`7*+ErK1OV&q`n`AZpwm1b4&HkjTWY7ZZtqWbDR@ZFZcabK5ZJRPc@_hPIC4NI?WCXVs2CYKy@y=MTXSQ7=$RW! zNY5PSL_O$!Trb7Cs(R)~K?LPGL#AvvTPXKbEu?3T2;{;!QIC`(t!3_6U&toyqc~C! zftk6~le`v_qgPxIhbZG05y*vEy6T-%QNx;X@)c|C$uBV$q@Fp>iMn!~TP}I;wtD7B zK?LP&Lss#b*qJi_)QWoMh(Io!6ICLWZ6x0}NH4E-h~h{=1ZFW)mFepU+4jf_k&yDK z5rJHo(M;V)BKOLyJLbx}c56@8i?O!#%yCY1_dw?PvcEe-&m1X;pxkrFz?LH>%KKBA z>X{<~xo}RF6;-X8{66cKGIOUWjub>-#y9N@JqpUyKPQn%Dfb)^$c5S8)LHfACfPG~ zl^pPOYfmnY@l5EMXX`* zZBBnB!#YQCq#y#b<4I3EnN807BCWhYGe-n+VWvFQhR;|gt0mYbH%3rqOx*xI5)YZB)~HKVIL%QbVC>X{=25k|ij zaaK|Gb&cg}K1t6U5y*veqC4EOWRaaF){}+1L~*1b0;?{_M>Zm{{L5ch9-x^c0=cjP zgR*ym9*bK~%gEb=z-kU0qili2{*RfG>dFqwYBoE$Jk_zKtWCcPDTpvyznS^0sTW1f zQ;s}JD-jXMWh%zZ80&s~Eq12vEPK?8imxTp6hxp0!LoA1RiEjq6#QGrWh&9k7^eD6 zSEZOLGyQu_^_k`}RcQu6ksnEsADt~?yvur(7!R~i`mV8k^s{AA-GrpN3B5{?f(RU& zGM#qQO@cX=>s5jX_xId3L?Do81!MMxc+BlDd~M60=c}hdPa43 z<^6SZJ&vib)3P#kcUnHC9?!_CTA}PR{oq?N8|jJ0E3ai`A_7`IC|9c^FjPq+* zA;p7;tL-!EYUIj?B2$|+T2_d_Ux-qmj-G5R5}w`{xBEcGI3jRt%Q{tehiEusz4pW5-$E{w0^M-be~@_8dbk`!vO)?Xyz@Bv zu)TPhysorJR)|0@TrqT?7u8zMD%V)oV40dqEh|%NspVs8FpaF7yK6k1Lbg;KDrQ5ExvnBgPkNRky& z5aFH2@oPCn4bsREfn2y^=>FQcDpRQ{4ox+wmX)b8)$%dbr$$zjXOa zGEqb=D~hYC2&R@5N`Y=5_>&^R{SNAp*Hj3Urt0^X2}0 z2S&+BBrBvK!aI*|`|kD^6OCmHs_jDra^Z@hJEW<;wsTlhscJ3h@2WalEh|%BtL0maI~p#923b>n3f$Q?x~Sk}2@V|+oON3^VvLeBvNj!k{lZu_HKwcn~` zg$U$ADOl88WKp>bc}B~*BrBvK!aI)(Lw=5a@}`OWnrs|IAQ!F}T32zE#k$Irq^l~3 zwX95Kv6hdiI5x6+@poEh-t*yYE|vDmX)cg*77m6)<#xuhtF}QYf@Xg1>^QB zln)|sZ0hKcy1H|0?&kP!Fz~mK3*|=r$o?qigw-4=x5s^hfp?Aw?>x>;`rEFYx3Mg* z{3Re!0(+-!1NmfWf zgm)hEk1?l6rUtS*dDResT)1LLryjJ>*|xieR92`6duYUDi zGy6mLxM%8@A;Z~=ly|hPhWXT_2L*DdQ3_<&wobq@mWkG~LJA^qY+6@zbIsBUYqhKp zfm|pB@{6Y5;3N+jBrlPykb(&BJhq(~;mluKN46&4DejO%IeW|t=v7jA{4x7Z`xm-yyU3#> zcJF0@I(n$7zSklLJ2vGzsbUjk4+bcRAiE9XgDJkQ&AOhLs%MS}>BMne^Ob`91+NctJ1P2HU5dMDzHmymRN~E z9-Tm?FZnnEmHu>3!`;zr>Ghd$yAMzhLEatcGm&6?J2r*xkXBJL{9DL{E0k(R=ND(s zE>)B&@`DsaU|$Q%x)PLlx_kPE*ws)HQ1o*nzRR_lpaQ9)k3Kvgu(iTqdJ zPG{M7jMFnm3L?lqXMgTYakI%F)_KhUJ#$1L7tV<~F0SWn)V&C)B0oq$1oi--UaWs- zV#_XPlq&Lr2;{XSO8CVPK6k5rK#q#y$OrO+z5n2(KI7a~>U2NB4Hy;I1` z+3p}q(RY%5=UCxF-g+m#dKKqHomGpjV%-;huV;=FM35gIdcAZSHjTBcTvNYuL?9Q= ziEihjwtF)+hD#OsK?)+Uw+!8Dxwr(&oAaZN{2&6ku+NNTW&8IO>pr!=p1H|skB@l; zDs6C1mX%`0Mpm=`H+tqsp_onpL9rL;i!-L$Jod$?(t75IKrWmU{i@XMSgu70bmRvq zh`>HPmQ|^ok44tHt|LE)KrZabL%qVvTw>Q+){-wN@`F`E6qQq*BI09SfjL>$_6yrt zy;S-1%yG7epm-bf5bBd@3HxqV7Cm!BAQ#TbvVPmpoxSUERj9}hQV@YXi>P1t!isD~ z@ID>+K?HJP|023+W6gDT?P(!xv0&{IMPgOQ3q5n36aA_ud)VsPN%hQ;f(VMSLcgUu zw^y=tOB3puBLcZ_PISkJzd!3J||g+?iX}aA1R2SNIdkWDz|totGp&AKDHf@D01PP zD4*f0A?(AmDMCelkb(&8g+(_)_pQTzOYx&nksm}L7xu*>M9+t8Ntt6pMSif(i!v?( zwOu$T%Q`af0J~UsZhSsNKt70|TngypwUljS{dUZc&u0iAkPGKTntsv|Y;d=#LPdU% zf(YyzMr${=KAYD1E1@Dkh(IpvA*TCGu-u>fOa!XWD9c9W#_7BjoReh@ympAS7+f?y zhb15%L{MH1^gIhbu$i%m727IZ?mYWg}VQPLKR5@`DsaV2?G5R9|YuMCfh5 ziu@n~xv<|F)jM}@!U`WPGbz zIS)2rt=nhz#YKKTBaq9CT`q2nUdczZ@WX{{75PC5BFuOuW6SiQv!Mr_{#(dpq~MDi z!}OqYR6jB!EB&|3D$!g$-UM%}EO z|Cwir2ppRb1GX^A3Uidci+>Bba848jC^U+dnq)aD@`Dsac;~VCQe!5QEVotU2NB5S zm6hqf=crC>=8LjbJk#tYwvwp%qV%)Q3S*QN=9sK7C%&7J**|QP6{fxdBP+@ZW0V!9 zWrgxV1ddIlBkPD??StZZ)XK4}%M@4>+f(Y+C+OMj~&VQQbsK^f@kPBA~bvB}2 zlVjQ(b5!KV=x|zAMtjxrF*=-)73Hci%2m^{qFl8=pEILnYFVKabgmksTs18#q#y#v zCZGO_WsGvwnA)!pfm|pB%lf`ScebPN9Y;lekb(&BJT4Wi!m@wyi=!exh(In}F_g~` z*JaaDksqV!Ygri^N6W`(`bJiH_Mc_LhIP`i!a8ANi)dM)6m)hQqwF>B(8E>mb~N_OhtZ>f(Y+CC~(En-#_E1$PXfr3s(%?2u=M(S9MCL zd&(MnP|M0#!dgDY9t^Cj!;JFbn8}9=R4*HgRm%#cp!4Av<-=)NAq5dQHhDQ?XEMr% z)3QPYa-kF~YsQYoZ2Y(BnTq@%1rgqPh=yg@*S(%OD)NH}}OmK91tXV5XqpwqHK3Le`j@8q2-rMMShTi2=6?qq%X{-mJMPm@`DKE!WBcOb6ihZ-ACB?mb9#lS53>u z_?C>UDCdq*&K)y3cY$hh zKzvZI5)&EIf6K&&^s|W}nRzsr`t%+c0S>Z3VtOjxM52hkNNI`^&g_t)uujb#*yxX0biu@n~xlFXiNVnaAb55;u zoI&JAQxIVyG-izS6@%Hwd94^kel!BPaE)13-AB)zQG3fU75PC5B21*ojA3G4dgh2g zE?kwCMR|RU^7@#`>r=hEwA@X6SiffzF*Wa;^7(i?QDISEUt32iPIh5C@S0W-z zd{|2XS14(gOIJ84uMA=;@`DsaU>AF;f|xtQ`8B8(Q;{D;AQygVltI_=l|xy2dgj;{ z!{lY?+2WjZmYzdddU3l?Tn>ZgLWIc=Fsp>J^c>34)760Zw~!0xL>WT$`Z(Fj4reOz zgA_zy$A8OeAKudWB5OUSB0q>gF6{nKwE%b5I+Sy#HDv7XVX{;HuQ}ilE}RqfzNhER5!pR(KHXC6Qx7tV?F-G$Nq_d%nWiu@o25qLuhdCzNi_9yDpgsGYz zL?D;Rpfsle<*EtFRnry=_LHIS(I4Lz9_OTU)dc0L#jo~&d=Nojn*Z}1Bb2KqC|50h zwFeN$g>#}9{jm~a;?faJMShTi2)xaO&cWaWqD!|%OhtYWfn0dA3*G6R|GJ>eGi`rh zmmAuHRX6VV9WEdRop~l|#khLrI9o)}?g}^2Q0AGS%riZ6L?9Q=iFUZ^BSottLz#;F zAO#U7pW3{^Jgf~5ziu@o25qP5#`2e=85mxr9OhtYWfn0dI5=9h$KO!1zsK8X@2XAV^F-)C~ zSyuyFy%pzocVJNSqbZ0mwK?Wg`}56Jv7@DrLCudwAeX5(GGk0@m_oK~(2}Xh4^j|8 zI;y%?#*CqEqNzDNLf<%r2;?%APi72t6HVI01(}NckmaRroYB^{sSMK=wyBRY*0!n) z`{lFE8MvE+Y{S5P9Ar%fx-ifeRjrq#n@{vAK?)*pY|5GVy0)a8JH1K}fm}Ez%X<7N zn_Qp09#fGYq#(jOkDEI`h`;uhU@G#12;}n0O5MS;w^KHK*B065s(Mk&%G3{P`Iss? zBP+@Zlav*vwI%G`L>`2|Z6_!NofRf2D=cm=0f{04$F?lW3X_x-7PprG0=ZBMB`=}aMEh|%Hs^w#9 zEsd-wk4#b?nYJddYZZB>{PB0mpcHf-nWQ{2Ei0rT0>>sTyvZO*d1P8vh(Ios0_E?9 za(VZsGE7B&kb(&BJk}-4C`%^J%v9tD5y*urhE{vry-WIjHS#B_N@y)BQ;V$SV=8iu ztSIwLQs$XnSJCVYv(2-w&f4gE?hBm`zhVEHSxqr9r>a7hw7@JWo7yrX!)4xej}@O zaeWQ6je~vFC_*FR?+-#L=mA4DJ*t{BR68mey@bJQ(k6jxKdH?*uw_X{l_(*wfDit^zk z<-;+P52x-Gv6Y98B7f>GnfNGKKyEr8PEtOcmKDke5jZy0xMx}-DIZSD3K7VKQlMx? ziym@YsvC}q{2&Dp-g#V({YEy-ct}Tn5P@8{V(3oRxck){b-xK6eyRR=4PAS)mkk2A!k~IxQ=tAOgp>EXtshltHIug$U$ADOgsf z4N>w)zh4~{`9TUIyz|)qZ8h07cBP{tKZrmsTrrkqZkBV@&2p3np!)b|S(#2cT0W+q zjFA=P+)2v0)0P+Z>!aKT5ud4mQqVbfl5*~J1_V+Nfn$^Hym+mooV)m_e&8J-7fON3 z?ivi0omNeAROAOKi15y%Rr@+}_K=Z|iu@n~xp2h^a6bcDFa5tXVah*be5i^EWP+_k$^-Ifn!rlm~E7lr5B$q5)JaXttoPd4u1KZ7j={er>DB4=sHuJx%|Hqw%}Iim6A-4387ranX#=2;@S!QCF@(O=WoP+O~>jAO#U-JR@B- z^Tbh8ZJ4=!x5$N(RzA+2Ye=)^>S@q9TdX|rI{K?c5A06Y%ZZ=qdF7fHcFH0p#WZ?O z{>Mt&i$Kck+Z6*`OLlSn{9UaJ{|ln!njizX}mI)0Wl0YF_$}{~x~!x&EiD)Gt&24d=&vmBlx$?)swSQv2uQkz(q*cKTUK zI{x3|c;o(mI7bR1M%1c8t9|WC^_Tv41ag_b6#c&y;W$uib zogY%SNQ%S5@_P4KIp5=D^gOx<*Qh)oNep*I|-G`EkcE4qEXYQ`f zbGVg675UWHW#lq@=k`h>y2CSHp(V@gPM0f*3L(#Zf9_F;9s5#=MyrC{Op}}N=qr`P zlb|QQ!R40Om+0?S81U5hs{b-O``?ws*C(F(-VIU+R(l@xBf0w>(Qu~g7)1gDc**%nBFH~8advMPeePpSfNL?9TGqH~QcTyIhh=;^)DyeT_1%w8z_(ggy1OZ+-@asFMAy{Ax=s z_wkL4{8pFBBEg_nzJ`^S+qoN67FO@qz8fp)c}!(dxA{N5A#;`!V#2LK?t$mS#F+0Z zu)pqA7733ewC9XpW!Ji2SseL2q5Ug8=MIV#)%GN?qqD0qiqG%iR?V1MraQBO&8`wD z244HA$HldaY^UjxOt$ljg5wTSFqn#$W&Q zoeEiDKYCeNgqHZ|vkR=SeP=3*dOiO01yxgHlukL&T{|R%HS{yqVSJ>hm)5esO1RXX zFe_5b4EyB!YyT2^(+v7cssHos`nZG;!_EwF%XA81;Rh?SL7yVU(JC)|?GFBAcg|5o zjCl6gH@3%5_Qwa2V(X`uK3-)pA;QY`aij9zcB1OeVa0Dmib?HW`by7V?BQCNzl!+! zr~AG?Uj9UgV#)ivb!sPNi7rJkq~PDh@u-t$(I~g){ZKY+QA-a3xvKiAh-}+wO*c?u z%-J}=9dtaDsJ7g|=Ay#w5lg;TM`qbf4| zC5Wi;EK&>|{>s)2;S%Tc>;73?2k>J>L>33Y2^7o7_$z z{(V=)y;Oar!^ULeNI^t}Q;{Nnsr$amUn@kH8Wr4QD>FOyrsek_kZZ{FNHO5tBVW~x z3ekH|IX7LN@lN*XMLALs(R?kfx1{%dFQ+NQuueVx4_9X$Rn_vh@q+<2CSs8`pcn|a z_t^u&K~U`O1OpTs6;y1+xF)t3nAg6x%#7WwU^fPhNT?X^Y;>*nncshBt>^ii*)ex@{Dac>fjQsyz8{@=F0G?s? z$T(xz7l}X@zD+TT)5DdwbzhM2bZ-eq(Vkbq{GF zJzXT)kM^VKc3H~Aa(ex7=CzUk_~t-Uf}JD+U6>a{jg#cV+l`(@hZ<^2?;MGkC4SWT zdX}>GhW-ZkM+fp@!S?Z8(yB=Wx-d_RkuDTWG?XWlH1g)-sUPi5VhILWn4{F7DjpGuvPapJ0M>$K%(t5oLW#(Qh1 z;QwNJ2E(h;ethivn*9E?+7f}TyQ59?!ny**ZGfIeR5LF=#Je`XO6@dMkeD;dM6;s{ zlnecJBHd*m-|*uDJK^D~{n%%swYUFLwoHgqs~M;J@HHNc%|R@ z;$A~}{m=wvwrW~q%@GIbX8oHVo>u6)A-P12rnpdmtF4ES0d0Qw;BG~9?YY<#ItfY zLo`&7=<~@$=ae$2$2I-V{fiFeG3$=7r2(rY0$tc%F&H+U8o__3M6*VQjZ#Yn32X<6 zF_}Ii`GE_4ScQNC8YVE5+^3F#mDwdhb-Ab0wEIK)B1K*hFqG83<{qy2fYz<^5iB{&`qUxvldcK<2Zz>;k z@UgK@0}l-qB(P;5`XALJc=IYT#>(4e0$t?2iN0B1R4po6vSLJdP6QuWOfiOKcxb2~ zp@>{E_-7Hd)IyzDb1s6jos;mp^`mM!uE_bYZ_lL_h?O=10zM zV*5Q?Yxr&BQ^4<0#5xxl!x!9Jz&xrC)lfkKpNKf6GItcWA2EZ`a*HGaUHCPNp4Y{3 zyhayKR(i@@={rXPpNObGu8!w6RV>-!)d`Ab~kX1elf> zOU-vH++wN=!M;9@0aV)OOOI>W%IZKpCzg)*7@suJk6&11Pf$Uka)>Xzb|70>RM>7$ zJ2`@Sq_*WJD^-^WbUk0?OC6lQC{1JaG)CDxj$e1EE1%P`96<$%D?NOv{n#%`(s`Xo zY7|7DzwF6tn=B*(UGJueUh%gtietV`wCZ{<-gD|eUiNyfh6)l(ynX47>N(1o8ruZ1 zuV5&xbb2VacS@27boC$ROWk+mC|A4agvstY>$JKt4~wcveCnC#vb{OViGStZ_C{5- zB~E`)x^>jA$|vJ7YennwK6UL0D%d~Ae!Ia?#P2Grx7m(Y?e8oRlB=_ce%_s}WPaCc zgZDu|OtuHr9x-k6?fExmol(#$>i?~SDhDoDh&GEomxo)TX| zzw_j`-`K|goOp+VauR_qd7NR*uVVaZazh?9rvyO-iH2iMw5w;n(*C#ptS+Cd#NSxk zaqlVS5`nISjV4;B(^utVrcSi0RFi)^YtL7d$<1D|jVu36X*yKD533ms`Qp>o ze75gfe!VMIYP0M`gKT&zg!>!xZg;RX#(>Zy{(NcPiGkgDRwqfH$KITT6 z5fvn=^!265W%3lO<@!~Pi3w&~4o~J?_N|o&bUh64rI%~vDW>l_5%$)H)!sdouiLWN zhzb&!zP_|+r95TzSDo12J3T(4ek9Lm*+|2&H+*jLINZTcQ|bF1k-W=wYYi17@EM9V zSjT?R>t&|!kY}wW0$qc{e5ucqT%}(F{i;fQvS%-9PT|q(oitRCz4RFJ@TBVr&Y#xd4Dga-$WkO*}3 zOZ24{U-Oi8zIqzRk|)s*^=I%&UHTa@|6qQ_dlHdnK9mkwKAo4J+eylaNW81!OUr-A zRR(<0(|EkA2)lSal3O=p5`iwfC($c9QIq|Oh~#TJO*f)~#2GR6I>jtcIhU)aF}|t7 zlC2~7*sTjC0$p;xGQamYeu4LR-Zp2mraAdiyGuDr*9qHH9P6Fk$(LSq&Q&6g>Lo+X z%VCt7PvWaPL~E!Zf%#2D{I>o|wR_|E>V(x2fvzjFed+heT;+=xTQ(RbIN7jri^uaj zkqb0bkigtyFboeEz?7e%{Fduxi9pw><04;u%~ht~)zj!uZ6-UM8OmLEEYnay0`r^L z)$!0))_>Aa{;nWSBG5H6*_YaE5&7zgo`zTZ|Jd5-A-r_^H5w{N$T{&~_Xq52?Oyyr z>K=(eSECvxx@}^DPR8NPL2C+^`^N5gAJ0@D_!F8B*#P&oD7B`8_jvJsfB2TXK1J(vAv&(UJ)}}Y?Pjc`>ZPbT}3CpGb>dh(1k50 zkrRvBaLX7cz9r|rh6)l|xQTji|EBbRuBS0!wKMOy)1LQjcu^wIg)Jw8Vbi|m{MU0^ zzNh`a8Y)QOsG-3*Db+dqP5o(Pl(bYW>H&J5d= z$jqz<@-1^FX{aE9C5C9pTuWl*+xFlSn{1Q_bjhXY@;hccsYF}udU2nI3KH`7akE5m zYN%G1AB}BAaCRE!x#gMaB3r}hv8m47J6a{EAb~w(gCTcl4)rYBfWJsEN(8#rX8Tf? zm7kUTVtW5$SyVPP9&OG$Uu{ZIK?3{KqP=^rDvR*);5)avNCdjFpZQX&P1(xNE_xc* z*JsgoSAF@VTswja64<8}HO??`IL^)1eATQP5`nI6mwaiR1z(i+yY)1B9Ll8C>viG# zHk2i(Ac1{qu@l11s_e;@ZhZMG3yDBio|q*c*EvV|RYd=4QzvH8l1B&d(ug&to_8YUJoG^Kl;+Z&S}b}x?5C? zRPeDd(SUL3%10l)@4S-Dq!Vp^uyBw51QjIYcm})Xc{HJU5pMMEEfMH)w-u2p4Ko!I zp{Eh>#+psJUY3_R+=-xqM3s^z+9othnI5kb(H7m<+LxBR-seDxK$o|uork>7QtF=6 zi9@9(FxS`B_$_}Qf(jCY9ZYntWwtVa_L;r8AYr126YcE0wdt?uP0 zo~87BRn==B+x^OyJ2{q?2y|hsEygT;H?hqtI`a4%1yX&EMBf{}bfy@eSstRNQM<_j zb|j-CFIgv3BG83(yO<3>SC)=kV##}4=|V961|xYej~NW>yrSr(-IaOzjSd7AB(SU$ z5kk4S)TXl)|Ckmi5$M7^CfW?At=Y%VcHD2U4?zV9EGxy?1ADr$F=HHf**Tg-pbPVu z7@0WUjrFo?#Fr;EBd8#OWu+)Zt4w5dN;To@!W&5hx-gF!47-foSw<6$554F>P(cFA zN^u5{GKobm^x~zhYDomTFpr7I%oaUZg>8YnQjPKi6(q2%G#IL+hBM#b_PkD`QWAkK z%wwXro!yg#bnC?*zRK57K|(G?gGWwf_H%mk=5tde0$rFZMOm`Vj1SK|uDb2-OE5kS zBX zC=uww*>{7X`yD&39Gyd(&F~|rAn~%VAKf}LUD;PfPh;*$7anl$ApON!N(8!a_Fe4u zR`)1Nb^3Y6H8zZ3L>orB1r!%?QawH?l}74mcz?OVHs2UYueAsvs37q!$3#ymDN52z zov0j<#L9%Mpl}etVXoY>Co| z@sTz8rq=aYPGdibKv$c#esp+5rc%AFPAG>R`P$^x%zL0lP(k9ihaaum{j<_j#1xA8 z!F#Sec2_61b8!=iK$l;DAFY-7MOn2?Cq{g3z_)bnYJBoblVU$!MvJJR_a7Ah^P5%7 zJ)-n^W6PPQ8u!JtmU9UZJ4gD_h_fFQ-*0+6L;oMu_@sK9)X4FH5`ixK3Jiv6pDOZy z7ls{q1I}+x>BC_ht2PNy5p2qon3r=D?8$ZqLDG}(xZ&RELu(=g?D4WY7QeJBd z6HGMhWP!59dz;!x%!aOb`dxX>x2iWTn&|cg-;^Cs^}6=hV1=)okjK`)$M;u@qAGx|5;AC4B|9r_g`NT4g|kciO;7O|0qvr9Q^>hhhni}Hh$EeR?}v=CR- zv1^`Ep{kxnqgmGcpmQl+!`E6O(A9UHh_dLJs~DT;MDEz~+#=AN&u#8VP(fmsh&)~G znxjm4ptrBqA28#IFH7-{|2Rnmx(-E|XoUe^lpiTNQP=7V`+mF_Z&$GeK?RBat4%cD zAzRtCRwpLBd&r7rne(L6Mu|XIt6?H0HT<*EVV_PsI(w0=ZuOJRUfPA^iN3m>uDtQqiRHPS*ve(M*qB*E2`Wfz4G{C(ebSWD z6?Edi>sG9d`4x6GVYoz~YfDWN9auC?Aysr@T;fr6iJTJzpa8zbocW2 z%7qhp$zZW{Al4x~Hv!+V~y5z{^_I*pT!SUYoK+rUT z3KI8cn&{fO9~IY=`c>VIX~iy;u1d$&kB|s-VbruJOGXW44eid-ibE$$@zh8pig~s7 z^OBYEXY@2;=KaGqAA3*7l${_E=yJa%dJ`{`m7Ky-)W2>lJ4WlXX4}FDDoC_HVWNj) zQk5ka^)yl=qV0RqE$MP(fnkZxbDF%vNSw z=y`X~dRty%R19O0o)UpB`?`L#UHLD{!pHhmrT?hQ*LiJYzkFN?Do8vQS7pCDN4eif zPebY6oFBTgg`LTAkO*|eIEXYFcT> zqp#=*r+!j47QT-=;p6D+-w`Z#PdGsZ2{}&R%alyVck9gt51%X%=;}JgL}T5Ol_fXy zJMYt}BFiZ;f!U@`B&Z;

      flAxSyg7E_{O_1#MZGh#+>@V}eAWYg)94-fNtyGbvJVGMSH8{>hceF@XHfHH* z+;`Z{&Q9FNF5eqWP(fnLGBNK=GnCr~vJ@J9HyIq5QbR8rS=)!)2h|6%vW2Zm2W-A`{Ca55R<*^vkuTYY2XKmSG zyUr4UF6<{543oB(=c>;b_A{ytK?Mmcj}3-mW;WdBT?mU@>m?EB!k&d#UmIA5_kKK^ zeKhwVs33vmv8ZeBG~vzxQ`tgy7l}ZZ++&HE@5x7YTFQD3vnQw^A(zxs`}*>EbHiD7 z9czg|SMT9sWlv&`G9y?oeSG5D@a_$x*yv;B2r5X7_4cFf+kaIu3cvF*sToj&<}jl3MlTp$&|z`w9awfPzG1A3vHk>6;RouM=By`txDmbLieu zIT{k^`nA@Nh9AmP>b=%`MIRRp;hWMw(+7LrYN#MFYm8X!wEeqMHeOHT>8cUDr~fkg zHu$zgpld>uAKiJoKuIs`JI{SolCCeamrd$8mf(srW0o&a$Wao3F06eFhJuNs*_dso*{M6h1QjH(4R0_cR$9%zY~U<#=pcze7uG%^M)-Xk zJ7%8922AKhP(cFwB4YIX&3U$J%>wdRUQG{z3KG~iG#ETSmE%!bCVMceu|%K?Yaem) z;$thGxk@ahdKo`cn zi(Lww+Vc(*Ua(h7?nv?NNZ_c5=s_;(#w(3_#=gWKmI!p=Is`FBW;KPkiY=`jJ*sKA zk`dSW;fgvDjTj&|_(1l~NVx`66M*N3UQC4Pvhcxzz1dgPOQ>_|1@KK4ySqD!ai9i>QEsHq) z$~E}M)0b!smp0NEG7>nxFHQkZD$C<6&(J&9yGR7OaEx56V~IBBjqe81u#jHTSU3_m zPa#GP=6z5F7{7Yih1tK$XKUknNd&rZWK#4XZ;WG$ z#YpOzPaUNZNF;EUT+F`SUBga(wcyiS+e!qwaD-Ld$GKhXeX|O@L72BRl8OY*l8X_R zxtG~7Q+Yn_OiPJC7mgGg41TW@*{T^;c|>DZX+#(aXhleA%kima%p?L`IG-SPNgLwII~Xi^VrZH)H-QAk?~7jQ3?sLjUW_lI z&m;m}ShtILwHv;?Wqc9dvd$%G#smqB-xn)c-8%7?V>8*5G5aI}U2>bD*s9L_Wbv=; z`;4{H8bu^9zD&#;7<%!WRWjJwi?bvGT~9c!0F6%Q%A?L1c$4pArL~qw$gyf|6MJ*3 zb$P6Eyh$R^g{x1+-U&H9dGtX8pSQn}v@R71Tz4ya+eNE!yEbk3>m#K!jNeRiG0`WB zz9~=r<5Y~f6lXy!x8o~o`to8QEu{!kB(8XgSpdiHO0N!jG;ZKkN8bJz;g02+NCdht zK2`LiPB`)B^;_~Dy{c%aATd*na(4Iru59b5r(rnWl-oCJ#xojMmk4x?5qouzsRc@z z!Zo~;Ki!Rwts27bsn<1JeS|UM81-Z@%-=GMx@{ZHUs#>cP(cFY#YG#g>lga0{YbvA z$|Z?F7tZjDzOz{kHhX6Xe-L_7Lj?(p7Z)q4w)J6;oQCoZ3vWsUy5z`#p3kST?PrH_ zr>$H=1qqB77qK`#vF!cSKHTcZJ&8b<948aK_>ib;`|yL$FKVbDf$`#Emx9iBnMH$+ ze2ra#M4$^}U=4;3li#q{1?_p58Xumkc<^Q8@k-#Ws zu_o?9BmSvo1Ku+;RwB@aF|Y_nEvg7^f23KBRkB3j{tm$QeL+p}7^ zVG@BZoW~P$!p>XS8mpNs(t9L91qqxN5i#3`8PlrGV_VaPNCdiY9#2Fr&%e#uEZ@jJ zT#Bm!MHk0;8jy_NWfG4bryp_T*{Bye6tw5fgV`IXkk*!&za&&Rm&j9*7szZW$n0$n(sEb8;#Mt=G}W5MGs2`Wh7c#z2LE&O@0 zSG$3-9neQ=WXnFGd8$DLj?)k<3Oybj_S@^ddywj!7$S|4 zA%S}}h%(W83LjPMqj7gm8;L-dy#LkJ*&>aRCABG@?iwmc$a_6t7~vovzR~Mvyqwg8qfE9>md>7x*zC87tGC5tY_(0b$?)b{N8snc<*J~ z6ZUf8GZY7IzKvkwu%Z87d{bMOsub6KR{38>%4sGU12((vwE*YpbOW*iu0+; zS78;KOyf0X+)`0NBHPl7o)YV8YmU;>cy**1TlOh}8xQ461iIw)wa2_XnYuHAR}1>B zqJo6IwHF;LR(fZI>1m9+?#(>a2tH+LaU&Aw!ZqV!#B0+~R;uR|{(DU=X*D?#@;kQ* zpUno>59ekr+#~{Bxb|H{t2f=iu8Vcsk5jryYuu5*JSO5Yt`_IRO7-F)!6&7!7FSW? z_b+0KZWgdokNfe`3-?PU0}{AvrHCAu@SS<9Vg@#DpG2VR$}umx{-f9dbEp1vv*W(8 zu9N%o`(^eSQ9%M%wTf8I8_BH7^TGUgy{!^~u10gc=n~g_W!`E%jdJ~;vY4yEyvp<# zBPvMXx?52@55LB`ogB$mBt%ODx`xd3q9%uY#eJ2Y#tO@;tZlIne)jc3BPvK>DIv}n zIZ4^-7NdC6E3+g5U8{q=Xh)i-e2>=CsQG$8SB2x!NS?pX#hArp0$qM* zyy>^1Mb%J4g1C?GB$7|}pQA2%?4qH9gd*+fl&nSaS#b;F55ATObp1NzO=E8sQ40$1 zqtv~jy!+NitpDj++PQV!bVMVA`ZDLCw69uplsEn7-(QMLn*MYz&l$+yMJ2POGu1Uz za9=ffj4Z1`f9|+0n>DRnO(M|sYJxW{_3o!q?~|U!4Yx>saKpv;Irm(oy{T~5DfvET z*NNnfH=5Hxapo^7NXYvw_1qu9XY5`=yF|(ay7EMRTl2+CCBO8m+WKWG|5p7zo%F?7 zLj{SlZ*do>9Vt_I)a%mhUz1Fr>!nB|GSf_TFHGb5^C|pcR9V)knX`rp61eM>m<4Dv zh40sDvCKp#i9pxuBi?k=Ix}^?_-@3>i$^B&#EQ;rNRX3;3KF<`mROrnGMrC{@4#9F zG?WN*t=Z#EZOfafUBByT3_3rNC-fP{`VMHIp@IbNQzg#rt2K_#NcxAZNvbOm=yKlR zO*gbOsC{zvG*Tyrai7XtnRTf;8Y)QOPFkY1G&huYwL8L+N;*mex@NEUrdiDms(oP^ z^T&tsVRMc!=UfL36(n%CKe3mdS19kk=07(4sZ5{?zchm(u2LwsS$vdL`_Do829d!1 z2*nz#*x_Qd_A=Yv$xb5Bh2Nuy(p%SySC2O1^L|y)@LR)gFm8x9EmP~K(&DZDbf3=Z z#n&D-YUCHdTG6(s^)4F-!e%KTK0zR}ZY)wC;*nN*5jF;>)2 zK?3)n6z{xrAa`19#SOd4NCdhZyuImyWd%y7L_H0*#E%DL)Z&K|OGvv@;=YqIvH5@( z&n9*F*XzYJRFIIz$T})seAl%)+%!uj&?Wa+K0hG5x~VR2)x4O73KBRbCua3yJo)$G zF8uuM-$o?Rg}o(lV)}(JPCISZ7H8Ghh6Z@k%V7i6+|wJ?lf%5J`JMr)zBBVW7nKf} zKDe+(H5mT&AHlkKP9g52VpPlVgswjjr24OpRV(fyG z>E2k-nmw-=L0athlL&P68%^k#!$E4y8a*y!Z9z+xeISC=xoM}Of<&d+E$QQc;p(5$ z3K~zhWIj`-k)iuiTOxt3lKly7b4FZYte%F)>k#fz`It7Vptf}9c(?aeZ|Z!0pjza; zzCU$`!6P}zjMoCsJ8J0qR!ODDmJCrFe}1US#P>%*VlT4$+O=-B8Y)O!7WBP;hNxD8 z7W>1E9?U~-z0nRltsxQU3a{l&cm6X-ecevq<9B1-LHvRFM{Uxl>KZCYxLK;y`Row& zPKKUF{abx_^ojy)^XV!Qfv);xy{X-!L2CbTdK#hcrdLqzu3JjaamDTLj?)l<hpB4 zdLU1~s?s+-_^&OE$mmNM#zz;tXqfd7HPmXe+ULANdo2l4Z{K{V-q^3uDxZVY-xu^W z9u9Qn$s^p!g?6tc0$uq_yy%YjA?m0wJ!*3PFCYFY%AOoZH)wbzQ!XepZGMm%aOXbTI?f6^2^Tst)zV~xO z^842pBPvMX6A|MKTQgXRq(S6D^Et+-3SP8T%22h9wKxl)y+U8t8m4~P_)tx#tG zhN&|b>(A=zr^n2G+%RHD43Y?RmCqw|Zlxe~SQGt=vhCi02RUkFMeai*KG6+J6k2jn zu*!}9N(6lZg9qk3KAis6#COeBG!9pV{NZ^|lyI(xG$12wvL5f!CW5l=CqMSl&?i!{Z6(c(G8{EI-8Y}yK zBq`_6-iQhk=A{*?>>H+r7mnf#<|mo`w9#bJnPw7!u1A#6^23AF=R@^eGCy-CJ9K|6 zxf^0_LE+naP*^Pm1S)GqKU*%Ek#8FU0C~wb$1h^S=0WL$WhNHQoV$P z;aW@jsLXKn{c!!Ae=a+hncIbv#0$o`97!1ziY z>g3_BwDeA{o?oz89ow%tEz;?b+BjN&gVXzbjqiJPoVx$%405QT1-kXk!DXtDgY z>IqS&#`$~DCnwjb5BJBawh!Iuzmqqp&zIF8QiTJ@a7O%C9x{ z5%*Co$AgY86{C(3*SmPP2VI%GMtvmi1MkmZxSH?FZamp$JUVo$bmvHnp6o#l_t&b4 zf;Je;U;DBrBexra{)a#pJ~t6rlk32i^%`ef;2$Ynm7lqh=HH!Jc(?n?deUo-tJT(p zYZPA;wPpiG_cVIniX^BY@$867_ph1x_nj9U+(|F&`JuM4m?079ifiae7ul>*w-m6FP`C~<@l+AIZE3T@yo>*Z^ob~yY7=MvO(P>}09_ipT>ZIn20;Z0IgQjMr{a4I zd8O=0mkD&8eW=mZMT7sQQS?N4Haw!4ac`q(1g{;_kXwDt-uba_=Vltut(!_vK?2{6 zI3MTIG}ilmtTE6nTq4kgEl&L;fjMl?*PX_*Jtq-VkieF+SkHNAGn-lNzOl-;u>=() zE_XB1Wfrqk+EdTF_evgQ@3USQ`+XfP5$KZ3M9-3?czCk2X7162VEuu0Mu}J>eeF3* zEmF9SzSjJr{7~CE+CN8o5LA%BT0%tQj?ZD=7usnxy7rR@bm0|>Z}8`1R{EiZHfcZ* zK?Mmc^Tm3cs0(bhSDtb9nvoKLF8R)TE-%lo%x$iX3TiLiIo=c2+M<2+qB{Q`*j5W4 zZX&24@&1*Oh6d02TefTC9eJa}ftu#4Nd&sE^&#rPLC$<|Zg*|K6gPqj64)jZdkBTQ z^IyxxXp5@XC#WD1Zl%!=i)N{N40?@|mQ1)`yD+WnY#WI{m)uU=F})u@khVaZU+;<3 zH^4T0ZEuab?U|)c4$|AA-4}M}2O7@RoL1&)s33vuU@?nq+ku~3HD7zv(VQTGF1$h! z9X;8fuY5mQ6tO-3$GXN<9TmaTL1Ss_4pb64PJWMkKZ}|MvLzfrlEoa zUZEIO8{UhLF7ZKYZ&)f3=t>*lO3OVtr~ZDSr}4wJ2X`6#PWyFbvxW*1_zVq(@c$Ze z^MChgckCJxY;$5;wDt1l^uX*xe@ljQ#EEay{?oQUuSd|u#k=`&hpS^lH>)yH=Rq?* z>`}aCmr#SCf`r`!@eCu+s<-p?r~6@4E8b1SSTbTR5$M8qBSwUmd-G5JH?(Ok#R)1% zq>p!{mb1>PTfgXO1Q=WMdgtzG)8oEqNT5r8=MFocv4)-cX(Q(kBoAzx(<_w^71npg zr_Jcuy9W#FSC0m+bZbMVT6EXz+DY4z*xZ++H23EH2r4%fSE@{BYL-i^ivJ|q3{&!1 ztjA2P#MJ|KqAnEZ&s{#?qSJi%~-A75PLeI zf<$OfSK7;gtGg5R+MqS5#&3si(GHzbB?4X8lM$=799OXyPbzCe+{O`Xt53*pOux^j z>MYT-z~?5S+t#mQ&8Jq=KIe=js30-*dt+K}F;$C+QA4pyLEG&tb8rLA>CTr8(7&UchA$zk z$Lrj})+_!Oy71kIwXYqzu)wX4mU~`VwPVDF=U{mjVXH>O zZ0Gl21MlrHo*gtr>d|8k$6lD&{i4}=cEbLPQP1tDAb~kl?5E%87;9i@UYOgFKo|CX z#5i?w5<7pTSz&HR1qsZdB5HEtFXnSZ(egxYM*>~gdlBE@q{{sBnc;=G9Tg-nhl-X= z9XoFQD5NmABY`gLi-?^gZJY9putkNr9Tg-nzlr)|fXaU_j4sUWNT3UQ0OB-{Wo>w? z(9MOp9Tg-nhl(Cc*4TgkcBY2yDf3>B3!ZcKnkXzx&|Bd3-17o#`%{oW~y0FzRdfUgtx$}|k z+O$uWT5g~V&H8#$O%`)EOT_Q51t(QsG2<$?mJ*f?;vG`oY7IZu*X~qvp-H7r7tRA> zYZ=?Y;;UWOi+_4x&Z8EsQN60V(5F_%)lFg^5Nl_w=S2%(S{F_|%k$jb4J86y6SAGD zTimg~vwdIYwHJHbRpqu<<}0X31hi2^9NF4He&A&_zNvj`OC+%F!#Yvyhg>0;?>O~} z*D#y zZ;TInA^jH;HsY!OTl4teaq4~d2J(wxIV^ilx{!7`BPvK>k4&s4-x0w*2h?GM-yV?&bjerMii=pa%?|8UxueomE$Ze%Urabr zIM0RYiMefU8ZUS2EzQfnU_=FpsXbk2-qjOoOyNvi>jBgG?kc5ev8T@@0$tc|6Y;x! zr}KX|e8Q!Pa)A-ql zrp7TZvn2vu*f$ihoH^6@frE{W>1DqdQ9;5Y;Nm;~7R)m) z-_+c!>PRIumd+bnxX>PpPpMlAV+~9#LiptYr?f4_>@`%7!0`uBQlARtH*X%+PMxxq z2z2ch<>SfurwXGX#IxEvir-4#r!6>cqoIO?o6&_jhMoEwoeRPY&`dGyhz*Muc}0#3u`!WifjBt9`7?r8xvMZLj?&Ob21nX_Xy`*O7_!=j4v+{ z=)yNE&VAjmhi&aRn!KN0OY>W5OTDKg6-G_g>uyV%Y)ex0NXcY>2YN6%Mb%HK6>G5C zFJ;A3$C0Ats%fYo@w<@&owzAQ)z9Y@yS=DkE0I3ML;5WCC4b%WY}Sq@=&GgJ~P@vY*X^ zNvmRx8Y)Qio$Ek@`=_Y6g(vqOaC*a*y9_1;HgzNdT?5bA(q|;;ZwzGc!7TQ*e1FpO zMO_UQB+QRG(5el@eTXwo#VYK|#rgWh-AR+N4I~0xw2v!ue&~gCmVl8@UK$5DjUCCc;M@v|xsJ?|~>Zu;IFf`#zT{H=G>Jf0*RWbNJma1EXB|syKS$EAoQWj%n609M zM5iHkG&C_;{d2P1@UykZoW%j;=e4~Ofv(6UwP=A|lKN*IOP@W~WLR)JlDhGhiV6~L zGwtY{5-IARljYWTuSfzubs{lu@+AUY^3yF4yK&vv*O`oV{jH*c#L5MBw4i*7`sa+p zxS^J$&8IHp!;<1gB+!L#R_s*RbD`$4ZzA!Sz0YWJw5JC*r>OHA$Ej(JZK(T+BvoHm zR>j_))(|E2pR>=Nq%G7suAN9mxb8Eeg2Z7L8@f@H)PGitEDGG9eXTy8g!^oj2z2ev zw4-CEq^Kb_ddZM=?_bS2WDMC78)HNTiMj=~sJ1*w{j*|ZPaM@&)gMI`osO0Wbe&GI zqi-jss8?(1X%w%?wF$36$*>Cxji?~eJiitlwp5f1g)2tpgkIB{T^~to56qGXbiKN5 zN3RY_QS}ot#oV^*eQkg8aPq$S6eB7~bbVHf_MDoe{#h|nH|wodtV|H;95_fK(1l;K zhL&l)iH$3|DK>dP9>`edU`NFR}WpRf!lxEY}7~1iJ8>7qb9a{`|`> zYf?JUS*z96kxnX+TzCrjlze-7FYtpJoqSp)ZjQ7=M^RoCo&w&3`|uYnY{{rRXAKo3 z_BVB;?YbxbJ<~gGuQ-LKjYissyJ%RdxtDXKAGar~tHsIRatYVBhcoX_Jcy521%V0@ zVHF(dn$5}T$-;BPi!^S;BcfUm&u21$E@NFg>bU#e-&H9!wlwDRYPk{5CoUQ)NPM<- zq|H`{(ys8N@%xc(ypgdn=`L2KAc3yW#Ezzfy!*SlX5uMNzTj*_;(gLZLj?)>S)JB2 z{^NKZvL{L=&{fyVj*b>-{8=SbZHW)xFy5Ag6m!u~K?2{6n0?Lg=L7UouAj3+psW2L zJ4$Q4`x{SPG_^B3d@r1=m|juCR@ihKTY8Bnsd}Wn+#>5)QezdeCzGu+%4?_~kzK=< z9z2_*{)wSK5pTu#`KhGI@-h;EuA+(d^jmz2dZBP1mSdht^on&PiMd)rLj{S_?`&xK zge3J(41HqgDw^pujaY^hlL&NGcwkR|iZuT0_0sF?a_Z7-8rj{pn1%`x)~{`-l}O{y z8r~ttOVZI#rjZ}FejAZM*Ygeb)JR2}x^M@Yae>xKqTO`jRzKf}3KF+=+R*tTjYC)T z@4RNe2F8YBAB(nu=@NmiwK4Y8SETW0C!K-cnj4Rlm`;jrPBWr{M8tL*x>Tg0uVfap zmeI3}j}xYmUNb&Q1iD^E*wY~*4Sla4u~W$4IOC<5Y2>-fJ0mJcoLpc-FNie$ton_0 z|6=@?Mv^K=A4>$fT>98k%OfeOeww71%{W<3v$KmN0}Kz0s34Ix%!Wo>7d4z%EiL*V zl>)Tvgehdftn(6qF03EL-1hen?P{sXq;}hra?J_5MmVB_( z@D1XV9uZ;J3>sUgB3mw4OL?C1=2qd3W^f{i_O zGRst7rEOMoi9M}lm#Lce>9gS}rO&X6_o|b{4c*A&>Gm{dZ@TIvPR_YE$ey0I&QO20 z5$jkM+Ear|hT5~7e&^}mV_14z6EeABeNyD0J*6+x)P>>>W7gVJn^x&+dvV@??In9U zJ}_PFQFseY5t>nD1@mr~Rd0o&CTD;;Q`O)2USP0u9{cT8bh zhfN^2#C~Kr&VVBb{x%MD%vq5WU+To#hwo{wMFff4R$Hn+ux5Dh)}EHWFVc9b6aC)! z^Cx|(l9!^=J^9Ij27F0XPt4w|#^*ZFMKo27Kf77o_QHX-{gkSzKlS&~+1{6%=hh+_ zH9WLl?vB*6d5UTh=ip4}>qyJ~m#n&qbMCQCB)-Ax{yhAtHJRO7ZY?1(YoH@NVMINB+F}Rco@ZlT4rsTWSWw&~5%aTb!noZtJc!wR5D+%cZIb^JCQ}tsQB@wkc|> z!&_9mTJa5D@aL_ptV#U)6}$GdYp{KQh#nas4DsT#z$*7*Pa&dlci?#+Nf?wv!{v8 zGu4!(8&y{i2l~M|L#^3bCsw8U^M{|TNa!IS4HYDU#Q0VJni*=d0zGc2eDwg{c)u07 zwNfU~l^-a^OUh-aYYloDS66glcdkz&@0vMDqfywZk#pkFV>Q^qK9kAqiQXD2NXR+y zayxtGKWidc<}_9!(AA{21Ksvk^f^1}dH0^#KGrHdl)SImOvCXc9KXUZO`M}REQ~Fw zH-^khoTcG^;Wvm^D{{$#g-j)3WK+gy>8g;B)5x=)&tlWZl5Wf-5$M9NSww{$TF1;> z$B<|bSLr)P0`E!e9sR+a#m^2SACKaM<=w~&S3~^&SOO7OW)}Pi;LE;}r2in{}Rdo|5YKeG;do$VYOGAnK8Y&U!>e}0Z zZg5RiZ`Rj|^Bv3b>$^IT4mV61j`iT!Qisb9bjQdP)!tQqgKjH|^XfOclFT{28Y)QO z=$FATY;QKRvg%Dn+7FcobjhXYh}Cb{?p^~)n%Y`J1qmF*6T6YrJnL*w9YF>jlnHcUo)+s^8d!5XSASBfftPkQ z$ALC$oT3i2-L7J95}&$Q>HVlYZ;{fLjBU|ddLQ_t@t+KaCv_@va}iZ@yzUGs4J59l zI?(F}Qq;27^)j(#f*r4YTP4+ZPm>6ArB`yKwi8m+Q#*9x&0US}39L=p?(~rQ&e&Iz zOX{aJTk^v(4aoe@a*cxo_9n%NQ$L#X`#oLA^&*|5vK?LWRb`xQ#FvFOC)>`OG*pnl zUa{C4w^%(snY1J`2lSE%bjeS*PnEjd@1#mB2YO4-3JL7p8w_iVw!HK|t;ol>@;gTt zzJIZ^>XUD@KAA`!yq%+A$%&-|mV6?z#-jn7+j@*>Rc?^VL?p1pFc_*ooWLHf4kb0C z*GdGsuzVDGcgiw$xngrGd^pmU|SU1sA4~vlJ!^#??I&hj3kLbSH)C&I<0G} zTCAJ?tj7KJ=SQ1XC2y~38nz9wt%a=`F~YLZmk;__gN(>*qoIO?{GGo}Qh3kH4kT>G z1c^Xb$+HghUWGLEfKhMhFWl|Mw~+>9=$t7UDoEhhY%rL;cj5;3Mr2yU7>Phvz-9+Z zTBNBn3eQS8^~;gJvT8x*+OE=2K|+3m8!lGmlV2%h!j(M|fv$^j4m4;%s=DvI-YYuy zyDT?*=u2ii-=?901m+kKBmC09EA93t%Nm`Q2y}UeJJ7_vsp|62dK!J-WU!+F9mw#O z$2C-tz%GXq zvri-fU6?DyD(oNgSY6A3WaG9wQqKzsY@>))Ux10#&mBx|^n4@{=#q1LhHVwr{^oG< zXx0@C6(q3bB>Fh70$J?K&Scd+3xZ!Q_9pRr6j3jqX0Rf0fuzRk(gYPGd zcze?OwV6bq3!l1JH{pJa&53MH$_+0@P(fmzg9Dutk*5ArI0i8H%PrQ-q77NJC0%+S z=)&A1;;-tyWAhgIkl{ZwrCfqUy$%jEBP2~Nk*|NX2U``ePH8^mgOVT-=)$i+#Nt?3 zaGR}0(!6Mbl-rS5I@y87bWKxt6t06@|Fsg&>EcNq-#IH0=)$krV7O9zJM+nCK+=f| z!I1(SbC5?3K0SzM?@v0Cs{5S@DoDs96E6zxv#zJ=lc(kEB?4X1nf7#Uhjf(`o@!OO zNeW{J9LN#PmY{-!>3}`$p=792Z|MDV*Q9Uk^_d2wSBDA`fi9n_4s=4>bhT{Zsa79a zTJSfvwMp%{v+8A#2z1?59O!bdboI?Eop_g4 zmDes+n+)mqO+y8Vlj6=R`(>!X?m7_`YtPGMIFk0?UP%PH!b>~Q`>it6#h>(EY8k%( zUUY&LX&B|BVgD6-*w{nXPZKop9z&{;?Sp$reP<-F?lKr|tt5O`gPJ5{;9QA7*LKm5 z@@<)+R$8lH)vRPsez?3nx%PC4h6)l`cZv0C!Oi&9P)?SG~mwe|ncRTSN4)sZy zxI-E$NXWUJPIBNsV;hibyKYDXy6`=TU4cWa`P=tRNXUfS()&OHzb>(JJuSz*dNm;{ zoKhqLU6|iQn_*6Ie%9Wd*jCNZP(cE}d9k|YS01|-*_>EcDlX+jbm4a+PLKHVhDC30 zNjhd0m%a}quByUj)-(1l}}qQ9<4O<8LDwtC*pYva%3+E*cOcMQ-LiaCfPH?s=Y-Qmd8 znzr`T{b-i@=!-tKbT`k$#}~6AjX#EKs30MKgDG6rBPw%ZR*6jiQAr}u)%*X*I?L!P zk}g~~?hqs-5JJvLun-{uf`qOr+}+(hK=2^J-5K0n2A9Fp-30^*4k7s9!D2AD3~+a! zZ`QhR-TPzKV$FV^)amZ(s_LpOU7TjE@VEM`UUnN-S7n!t&U=U*t2_l-kifY_(?WA+ zk{xH|7V%GtD+H?4Q-H$9KUg&$O&X+BZ1MNcizQzu7$<7r0R1KSm&)11ZeK^B= z$zB32NaTrfn5*um=qFsY$>)`d;OQ$r<)5o{RtQv0neH(6jZe{Yj<_}XPUNj);zOo z3r&o?+EF1;HQ|`UY_d32pXjQK-0qa%T2v&z$%cz1{tokY|5SbM+x5!1n)$Df`J+9Z z#J#dt$Yo<|^47QJ^T>yT1)jbkjnAJdfQ>H7bF|&UABRQ?v>>7Na+sSdr|NIr?0ePz zU@$+Pc8U*q*jFJ?h0kBpntJ8t=SMx@+MJ$3vB2MLxzS-3%bKd^sARXX>qQ}6v*8z> zme5flP=(K*s#%;Gkmx5zzQ zpaqHN^ww_eoTjI^PA$)M(#^Yn4&b9Nj#3Ek$`145uT*_1RTsy$DfZQkqFgVQ=cQ8B z>p6O_A)#G?cs z^Hruaz05hgjbeLp>sQ`aW9bg51gh|qoH9q=ZfrF=_>r@_?ZuDx4pY=i)927`4Zib1 z7wOd6H%)J_)ox==abN4&wy*qAfsO(#NZ|WVmCUODYi2w4lowsyLm^P*O}%}=msCCa zjNQhDnj6fhB`t&UGlmu< zux(8X@W>)ouWc)Q_N-7m8qwFa*9wREplp)@T|H7Gg)^^~#mw)#9(!wBwC~g*m3OIO=$yTn7@h>X5(a(Kq_5f%dQJGry!LZ8EXs zjwi>zg{qe$9p>&LNqRR=n>Zg3B<38fD2Cqi=ct-YE2Iq9-sp2mY}QpGwOxSNw?g)8s3fYknXM40Dmu<#t|c#mutPR+GODE5nkQ7` zJ-UXY1&N+*9p+^p%7Zt_CZ5C<71wK(6J6dNQV3Kno9HlSOit2AwXliL-+e{@;(>zI zImJ=csGY;iQ7=g^RCANA64!b<#GFO`z!L)^R>AevN5 zR0veHndC4n@-Mme**?t}nbk{tDpyQoDDe+R3leed9cG8QC3EFw-U&n{4PppC;kbS+8$d(lQ+B}T5#Bi7U^Bu=!+ zC(wdKT5E?{>q(NHgFIE}8|O|Y(QtHO;aj}0LZIsA81gV}nylApXcOHpWEI8l)U_ZE15dlzg)kRRrn;A z5okdot^qy4fyw&yFE(Li`oK4B%_#a8tDq35I!Z*HLCHFI5%vCk%{$%hF5(U!QarHH z>ss|yWBMo{7FIJuo-8m1=cyIdo~$`fyR#7jR)E%?p>m; zxUuCjM+*{RyBy}Z;}n(B%_e$}_?s6zRa@KRtQT%&6S1XF@m!4q#n8LH z0xd{n*h<$iC0XCw!X_4P+sywNT1r%&6RZ%Zs!yvvFD*q6$zT(6*X`uNcO2sBmvRCv zNK9GlFek+)>-#dgepTUBy!k>;5wMIa1gcsuc9_FUr07)*`yK2&a}U23lT*YGt0B;W z1nv#cUU;S*yj03>e)!*p3V|y0rlcJ46JmI=^RKz@y(WsEB@*gB!;JnGf7$O2KXkK& zLZAx0G^tY42scq;Yje?P^DKsI16^{eo^jh zLve6>0LQCrcIfg zQ5={aE-Gz*p%AFT_mR%kUS}1*`;-&Y4*kQ?f&|XNlx=$0SAOnhsHpNji$DTZ_&(D2 zAdR9Ghm{u3_U003K?3Js@?rU!$TR&aDHbmCQV3Mx`$*Ya4<=JZIfuBH%_-1=1kS+} zCw%uRf0ol*j658q5U9fUk?Mb}N#N1N-Nls$Wd&N0z&V)wkd0V=J$o)8UNeP26~2#} zW`2IiZ{N-+Cau<$-9aSO+45?1?Cas;e$acx>mFm* zRR8t|w^#5k-G_)7+=HV93Dv*-<+ml=I6p|_%-LQcP!$yJG&|i%(vut6vvV!SR-V6I ze{pfyNRAdHwq|ge)o6C^T+=45@0-s%Qx5FNs%sPiRei`WykELxed;57Rtw&|mhYp2vl{eO8)JU$$HnUHqm|aG@g;S6i)+x zafKDZ+3wMszT`;XDrRN(>B|)+Mt>dJkR?2V&lJV z0xd`!%jz_<{*kPA*<}+Au7~p4wQGxXN4*pRRcYm&=E3jDdOFv7x6`!Rd_bnEBJQD6 zpaqG=>4~_Ptfy~kw=pVR4jx~iiioWipb)59SK4WouAidsOS0$Mp~JlSrBUU{>n>EF z1qpRWxWcHD?8~=caj8jVg+Nt3Z>QO0eTv?5h22K&q$lk1&yvF7Ed*MSQ1=tRkFUc9 z|8NSgyR{SoRiCMsEcuqAr!}(Mh(9xd&0JMjEbQMvpaluszoe7V->>!Kx$}xm*P1H? zsQzhFZM5D!o2`GHN$eTlPM`$|+*PH>`#gi$=!@_8@B!Tv0#%{&9p;5T zsrti=b{iGDTdY9fU7r3;|53$Pl4eVApvG?5b1EV)q#K$B#*T{-lu#fhvrlp?pgaMJdrW zNT@sXi5{8wfgPcI=9|$9fhvs6p?qYAS6TCOCi0o5+9*4B-rpVO^@nNtuoC~zE}k~) z<2vj6stjs9TJ}lQ}o$@G(EbJYj<$fBrB@7CK{e^p%AFT9Zxz9zd79+6PHEI zuh&>PF+pNyC8v3c_LHYfwA=6;-P}r(-b?gBptG?u8WsRRe}lbk&7qz35V#n6)g~`0d_IjGK{PpaqFV+nuKWon*b3Yft96 z|8@QSqSnGODu+U#>fT7F89OamPy1!J;XOL%iHtYei=~e<3bY_GjC`Z=EK1fVQ&f_s z{aLdWYx%5;*m?gmM?z7JcADkuC+pn@+H-B~2eG>U@gBl!*&D8b1&PN8$UC7`vVNn7 zO~f8p!Cp1!E2^KmsSv2T6Xi5LJd*VZk8NUjfiSl0M1-i*^BhMD66dLn?9OC8>)$r< zxS`3G{uL>r2JTS^RJ9mJJu#JbCR*C-tGcyEu;qt_3jS_AM+*`~=w6MZU4wjWTtuxq z>}ARbQDN&8g+P@WYdQGq0+u{{lo*_007nZFYCLBFZ5QD-P^h=5uiw5{3z|7chA9lP!8BS2eWgG6UE3`{IxXW^sLS&rACRgip7;*g#@mg zHSPA7aGvTjLU=9gsSv2byRKWNZ`s@)7q}^=EX%{v3*#aLMSSD3#i6==_-7{y&huXty@ZO zM*>&Q^bT5?d1Usk;#T)Gg+LX)o0>K{i!Z-lvx8VP{fF|_B7y5*s%zQuHp}s#wOGD1 zt1>d63P&Y6KQEP$haYVwLUQF%Mjs?_rM`w2aJoxWH0xd`=D`zdkf(82Ekd?eemEj73D)nSE`|fZy$q~)V+>H`w zK|)YbWx4I-?M%!d(iA^E!E!?;6`ewDO4OXh8zcMd-w& zCS~hw&`f-*`BouNg}W4#`}6ow-al6Z@ptMEjus^Fl!Hdm#cTMRk%w*m91wi<{v&(5Zy}q3A7-A z=OXmXdqr?-PFZm_Hb@~*g}W5gcXy5D)jJ1>)KTRGT9CkV5sK%$+<{L@?tH-S@5jVa|H}8u^hr zu(c5##SqA=6rs0d>?@pBsPz6m_4HD7rOQt2D|-fE$Xm=pY!dh5UBF`%VB;h z@m3ELb{oG2owuwJ+jwb;&_oLoSIKXQT_m4$S5>P;ov&LFw_^CW60H>iRX%jWyQ%qG zy>d>wjj;Wxp^-q9x;f3@6NrSg4um_ncmJ(}rTEprw* ze$F!K2mamSqwr=6ERts?ft+)9y}o$b9=XF}uB|;z^D~r#w!x zb^CYvyaIL`S^bO21dr@u-=Q1|fhzQS*R*G617!2ES;SO5lj0GN#G62;IdJ+rz4tmh zreR;vQ2EF!hZqv^L5YGu6-GqR`|+xX)x2a;9{y;wK#xy+gV9TqGW@luY^5%1%O^b@ zA<%*ZzRjBEJGG>>?C5M>=FU)sKoxq{(QNRwjaBZ-Dn97zK*fU&34EK$%R6%?>qp5w zoQ?0V5Q>W4g8%C~IAZ!j>+1Fcyu;_7iYFiv_%>6-;nc;}m8`Km=}lLKKo$BeYFhrv zhb-RoJdbxd*EWv>>5IC~P(sSra?Bi(j*O=IoHS~s4-X%+UB(MT(v~AH9iV~D%>Nb3VFT!tO;TD#NIca0xd{j%rMPre5&7?%Rcdt< zt^Iy;v><`m3n&Vra8L8e>u#cG@wWNb_>Y)9W{IOcDR;tCjus>^o||Iat-Pk! z_kQB%$Eyl~D%>NboU%`5nr+(-5ZkR&94$zwvEe-@Y%tpR3=uyL?NSI-;U1}`&3Vz* zY@BVF2wb?1qXh}f&p|nBZf7w*1x1PWfzuQMRk%k=al*sPnJrh15)H!#bF?6V8ARxL zcosH8XO0z_=Y%T+sxXfq`AjrfZhmw|i&>o=N`^lqFgF>Uk~P_8-Y6W;)?FSaoJ-RT ziY;Jv20V((Flg>&c5KGQ)#=TfUkbYZO?8ng6p+S4UF4Pr_|LWPjDxz9Rio%dib*sm z0+HEqiAQ&3F#XC>9cx#N;`ymHwlk|aZ+m_halb=ulm2u4 z`$D7KCjIvx@%}?mS$J<%(XwGzPQS>czwJ`tZ?CfbA0r}z)Aj#pN4UDD41Hcr#Qd7Y z(Siit1*(d;&|PM5t1A+NyD9{#D8|#EJMmu|Hy7uSR%)mi{`oB*I{lrI66j>@X&puJ zq6V#!m>n}3zbu3KZy`_DzbU`Z`drduS9y`R>KR8168M~Gq-I<`x?4oFFlQ;x1D}C< zchBDD^4K1C;qh=YM+*`d8LDYRPV3U)TR_|xc~Buxg>jw~E7QHae0MldOb+PA@u}hS zSD)aHycML6PYKa%;B1Z-B=FbLX1{Ig5UWJQXV|ys?AilwP zO>~;Ex}=O8Q(iP&Hix4H3G55B0~t_E79Seudge%=3a^R24JMS5D^EIHcNZ;4U|*mt zo8|oEj6nrlcNYm%;a#8;-cF@ujS@Ls1X_?#dr7U|fwFm>EF#l_3<3#M;Ww40?bqH| zXPy=i`_=^ty5}a{d)IxZ?^uJrJ6->#Z$X2;-Tr%mL#G_IhNr&a_xd#z)h@m@uJ3iQ zceFb|-{uB=aWnh-{9=Q#bjCvOAQGs0^gfqK|NZw47CoF* z-dvR4)l1NV1l|$KYq0c(b>8O%KT$^rBv3^?#H9Z4UoT0j^xImc$8(c>w$XxwdavGP z{%Ez#E%_emS4f}=_kd_*=)c<9^79u76{nCU5nx zx2z`1_VJCK+6eqxM4I#$Tm-gF(KWL#TlJ$)xCpc$arRs;lm7ef$|GyMvi9bC$n!p` zqg)57@E+1WL!Tt;^sdkU-`zz5-)4HxAN{oUc;poO={?84g(~a|biy0@!}2`i`TzA2 zB-D|iX!;B?XPuIw(B<4pzd{xEY1$*(*TwQ!xPW)98!60d>CMOG=y}k7EA6`)w43Vs zH$EGxgSCIJHSuf$uX(qPGWy`Sf=^b{a(CHj^&4pLy*1Tmj>Mp)xlH=c^)x9LYmxcZ zwQozgTb2GwFF{p~uDMM5&-Dwb(s-*W*2zy}UDtsYBao?VADct@%?Qea z4Sx$&w4OF;UH#vh`e>bd)-type8e5KC*mF{_A&BF{r8;pwcl#)d$_Ye3lg~3OYu10 z_gf*~XY*nodMN~|a0i;swkxl;=6o8@ON@ySXu<2iwkglV{1sM()^l8U7cEHOeWO!= zsYk88+xEGhAQGs;o=^Vm3oJ`N8OJx#TZSf7XCjIwcPaIQjy5audFTL-p34$`C8qM+;lYufZ8jm=~0$FR(0CkV74fo+q|cE%hg-|t|t+f@Qp9n*4} z^xuDN{Jn9Zc_3;vyR>e+KnoJ;bu8fpP5RH(1`?>EYcS~-|JO#gC$p`ud)o33T?Q+? z9Z!C+ACte&mOfUm8WniY(jx>~kiZ>iIx8xoTjduQ=F9#Zr4Xo6M+Pm}!}_O0GW%of zSb-KKaF3i~0Sd>PtjRXEk-q4WK$V(7U|h;%YvirR^$d*6aV=O)(x6bg+i5EdOnX+%~@jPc_@-9xqCVrWqH$`>?x| z9pcijRAcdNAJ(4g4e(Q`M&p-0?8#;OBrfZOzsx@KYMG4uGEjx|(M)N^)dU|FMF(crb~>;=$p|jtWF14c=tqtu8K-EMBCE7L8VmObldVDnWKG$d$Nhd| z^l9l}Qz_DOa>5&9ZW9MCGS)QmWgV!}-_?ytM%K2z ztP)iiAdlbVP?@Q}r+C);D)+0JYJ9BX%St|3r-!yoF?NmeWx0&?`pvKuqwhLjmg>rS zI_X}REI9Ht@31eM$k`y(=;h(dno_pFVog$woo}6NLhto@>9Hxs247#6=E@xTt(J#8 z`A=QZ#^C(I*kof@W4TBpaqN;YC2`m!UgN&@e_J>t^*mKYRP&|$R^>F~ zlAkXNqbz%GTe>gXh8zoqx=j3?y^enx?;lWE((Dvb&qT+FDQ#e z))U1C*5FeHrx z(vKyz-Kg)`oMarR;Kz#l*q-Ep_dR5-)Vku)%!)j=@Ec=udq1`&+ZKKQpf|?zu72#u z-c36GC91*m$wLmmUstRcsJ4Mb&kt`5liFL~(e}W;oyAjbyi!;EZlw~a!e2trVi+2_s`US^VMOG=8n$8!j@Ac1XDzsgD(Nx7F8)SN0vz~4eu&hWR!&@N6k z*Oeu$cIOPT!;ZXS`@~`bEl8->QTcu$S>Z$_k^E(!(%Z2g_pP30tjXca_WUmcX6FL( z$?VGFpHmh`3li$y>%D&p$Tgv%;_}Y>3V|xThvYRGm`lz~E+?KAc*)U%1n%|H8|9rt z7V`-e2N;CeZaelfh7poQNB{!cdDIR4| zpE;_qztQ@taXFbw%PMwe|ESD3IF~GlNHMB6@nr*CS%HhLs3n~d!Tjd+A_C{v_N7yd zBR8mC`R5IK-bpEj^R$ySnQxC*-DWnF*2*sY$tst@*~Lc1jg)^}`@~xO7|K7sPcnwRak6Pt zVJ%}%{xPbkUa>(n zVA%g^7WeBgN?I{qeCV)h94$y-d*tKwV~mVB|C+^LD5emoDq|!W?5>lAb=gACe0HvA z8SB1|T`(OSEl5y3J%i36+5c+lt!~&~ej2cspKI2UA3U36RO{r+GS}a%tf@M8PBOYr z^JSmM*=j?CRBacpjsyE4E=wqIQ6E1OuXwR{s?K$(SpS6{z*p5bG|IfRad6( z_9k*gvs|K5TrGt_6;)9-sLl+_<7%VnfHE>@ZFvz?s4}0k?u{`ruOG9kYEtD(gKB^< zyZWWN_HmE(l-nQF6EGh5KfeKo!*(HK-B_%iyX3`eUiTJm?)R2BlTvXh8z6Nz<;SmXxvO zD~Ma0$SW7t=lIl~4ofn=fg`))toJA>C zCZVp3nfEu(-6v5YP&H>~ve7(>zR2F&YleP*w~!_HY2NA9O^y~MaGs|<nH@OsCvCYb+Oq0D%j7c zTS0nF%^_~?c&4o3@Y&$JLf*I|tIE`Rzq!|&zm*vW3B2p%TU)TY?Aj-z$k+0cLZAv~ zA8La<n-P!z=BP%6ll{)%tb#E^Z?|IKF74FH=f`s}!tcxvW?!}qJk4ZHZ0#)j) zwsmM;X;#c4W9K*p?m!KFl4M+L?O=0gKS14$nmUcVEdI_UkLNEe(1JvlOvy&S2@Y0v zy*(T3@8^&$PA6OEJ~`SiWVgPtekAb?{Kge zuIys{I|jP&M>kvau$;leKc?FRA!9lL4J)TULNKWvKkW79_4OOg7A{ zPIlClRi)*+8nVy1=2qmyA_{@38gw0%$cOETD|3sZg1a2KFTrXaS610i#Ag#8pKQ!s z>tJ788O-h!@s?>xSFLRug9KWTz`IUfldl}ITZ?fC$|90qjR7_play%WaDdjCu{w`oHZ+}%lq-gtPUld0xd|W&m;PD zeYrgPzM1l*kV2s9MO?BmVu+KCb7ey4T&=6@`lbONo%DofubXTvqdm(FRAKSPtYo8_ zw=esfs>U{7oNUy5>1117^}Nz;?jUPNh4EESKXbGo@%(hBZX?o0UKWE)64q_v>>7Go|k>WdFjMobS6arPx>ZKUFOFP-W zu8cr40=#6zy1a5~)7%2bsEeDDjArc}Eb;V49mf?-+dall-mjEL7ORy-paqF}^j+I( zl7snuv9F`n_|h`ON0Yl(=TZn%;kcq{Hy?(|^Ao;W3m<0@XhEX-=Op9VE(iPN%F&qJ zsvrwBzGda}a#ILY;kZH>#?Lajf?c*s1ZNj$L83^BWF!2(gH_IMXN~CjM>To><2K7# zEw4hL3P&PMt5Kw`Wb4;hfqppzT97!^IN3&qIQBdm{a+!O*;_^#0U zYH?GUu1ibn_nPbiEl9i_lx*~({awSAF>A=_X7X^=j8@|xRIdm|OH`@vV5JwW<${T~ z%?VSp3bY`xWLmQEXrz-h{%t?=GCSJIj2Uv8)kbGl2vj}#BiR^3dws85xkbvDU1j;P z6OBbVKXJ4m@uMZ30v&L&vOVqRq0R3pZ)U8=rqq0)5U6TRgh#TI^>k->ede&IV z;@e;0XhC9g(PSeig$SwvOY5ue{pF2*Zagm4R0vdMbxSth7WZZO<7}c@i9zyQ%^-eq z=QfTOBo@%wRQY1QEJt(ubZJVzx^hXU^nCjpFJl&{dxKHl073cTL$HL;}ZrO?$Ptrz~)15&vKuPzY4v8lHTk{KI9_17+m- z&mHujHE)c4!oet;k3N4Xo#W^Zmi^9VJv8mr z(XNhzWf-(sFL?Nk@mFmJ`-?J{xB2|WcskI*qFg!2hkmat|J)xeg95iPv><_P)9KRf z?sELUudRcWM>wuql0miZ+1&hF^s;@Ej49_GEP?9W*R4aRmPZ}zPGz_;xSpQO;5bRN*ygn$#Q1wh0C0vS#BMT9BBUHOUC06~L)ab{pBYHkU6) zxXB?KXDI}#)P6Pla)_K=v7~JHaUDNYl6(r6vf2?O@|wdA3gmw~~i0ey~EeF63xI0{a_fzc|uf zem;HOdj4aJLZIq8eX;h=M*Yf_$+KSluJWfAYvpLXoTCK^wI@!m(Ni|qw${3tyh9;S z)hu1I(OWoKyeq%x#n;1S{Yo<}k23ES{}S{m@uEE$cc+tG3ARVL%bOzQkk-2_|MHI* z`mLZ!^4iU&sv64;)mjf)#3r+-^wJ^$TKAyC!iPLdHA?qsDJ+kJQR z(jk(Ece47`o5<0EME2Aqqxmo=8}G^$_M=^-JW{cYmAlY-g+SHsg5;?ZHA;TyR^6%?R-EH+M*`c{v}2ADvi7HNYxUHg3V|xT zCi34+8zHAvy<=uxJB6bK3H3U9CJd457oIbhjM<%vt)U5LOqJI+u(bKox!`XjJhJ$X`C$ zp!{Sk%TRkwU8zwA*{+bU72W%XLZAx26Uf&&Z&$hNN@mNqRvJeO5^nXAjr60P%yMNa zT)(foto>t{x$RxDLZAx26Ev-;TR%B`P9byS$9RqwB;Gk_pMkzuI=k`?9&J59R_*si z?^ybbLZAx26DS(+(qLI~SOnYAco#Cg+)c zd~5w_94$!TiL$1BlD*}LL3ge5>rX1HSM)r@RSoR{WbP~Hj<{mgjLyQ*f&`A>bRP9r zFS&cx1?%0>h6;fyoPDUeeEa_Lg=4F=aq38p79?;4r-}$Z{p5uM^R1DgYZL-i>Z~@V zLxjBO)x-)pvzwy@33a?0+-JD_{O4#seNV7*s*j$B>fPn3Lu7Q38Qk5d#nFNUo?uhG z)Y(I%|FwZU^!pHnKove&TKlXUDAUiH%}<`0tUPlh)bFTb%LmA?d&Bwn2`dx=RrtM2 z`7)OGmC|b*j~cvN`4UC~zuRd3SlLImx)aW;6hEsFsKW1d@^0JPL+)ZuKHGete4itM zJ9?Tn=1wTvgFBeNXTw07n+q1 zmQwa!kx+LB$9q>%%o5G+PadxjsKN*gS|PU&v{q%(tmaL|h<;a6jsE!^Yz@_~ zM6c`D?Ng0}e|=bER|Uy=`c`Z5otk`B)q&#VoHWCYA}1569$dD#G~-@B2b)FNrABp5 zGu}^ku#YZ(pS$L4ON=YYm)#yJ(1JwxvNU6IO$VF4&GzKz&Oqi zbY%ydNA(UhEmyTh)-cUK#=0^_paluMhvXIZV1RW!eu3G&?p6?)2(cS5dC*4`Fb ztWP_l6d!sd)aTK`t-rNtM!4l4KU^VDg&z2{A}e~yx_#(?Rd{YY;X{6J!6oTSF?@r* zxk!o;UV)z4$PIeB#wo^Rm5bQC>i+5 zs<7p%wdiOAftIlkl8qm<&lIq3gYNq&*?2)c<^k2UrMLFa&(>VO$JSr#s|&Osac5w% z@t^_iQn@NlMTg(FDtou(uS2N*V7)XW?+5C;)#6L45kfmG^IWwWZ-?%-E={`0%5RDkXh8yd zD4j07-e=WaIFNaNQVCQ!FQyuOMmd`mHB<;xp}(-Ey?*lDdiCiNFE^pKKnoIkXQvt4X{Ep0 z-EO03x9l?K%G>;x6|NAdLVsbZ8v4gW%P}vVxc7@IzRnn_hiy|f-KZPZPU}72y{wMX z1`-(WPW2|@Mp%l#A9?wyIem9v?0uaHoqm(T9nV@1A-=dUKU zRR~n!lcnsG?=s5$>xS_Ij^<)Gjp4DCoNR+#V*o~p(8sApzuZpNlBzh9`a#L%?KC%#$wNI*1W4?oZb=BsWG4`mH_fuB$^PNEgElA*qLAmZr$5;VFHkpn44^#+L zb*`LhxbxqA5ch+%{7-tuc#{4?W9Pg@lMv3 z)*|@)Gc8RunznGV=dM~1{iU0%7Z%BXO{_1_f`rl+w47h_Nxv~Qc&%Fv6arNpN2eMG zC`xR%YZSfg$R>;Vd+}pCTMD!wfqj8i;T3bp5epu$srg$e1gc84O*O1Yc5@71m@ znrz=>9(!@Vqd*H1*cZstsabk?VA&~sMh%rfRlc&RhW8Z*>+2dtJ2gtRe7`q0&fVxP z(1HZ^1*%N?@|`tm#bC2x&u$8Vs{2_e{)=YLvaXumqwCzY;z2@t-+IfDg>&U-cK=nq8#k0tAc&M9H*^Lw}Y*?TYUvukWl;8@O)>j>XkcLgOBu5 z2vpVInPOOt9qd&N`*}2+wa@bTIm!AyvyVUv66zc^s@4JP`mW{HyC*#q0#&$DqmkkD zYpdhJ7%TNs6J>pcD<@p3(TQSKO}csQuwJD!RMv1v_?JjAx-X{vc31tuq(#51-J=#+ zIS({b2vqeLpJFVcmA)8jU-{V{IizRtiB`#f8Va-^F|tL9F+@68iDNb)T4$G&{%vN( zyl$!xsM@|O#kh39!AcIdi7fH%^7wOqYkWupffgikN2eI;QXQ5r;#l-cGjNRoiJpcW+rVBBR;Y zsHYI9s{Jj+$ezo|iZ!->RbbYVa^3N|`iXDV1X_?76O&?Sjh!sdIGfn;t(a{0sy|y- zu7*OO>XS#R@uG^8-FHP!{)`Bc%Z4YgLj%JFT97z*J;k_1W91H4U6~x&17x$(9{kFF zl|WU4kW^!DeqAzYpvMQP8k`H!2U+(1_QoW?Q#~jN?q)z5U9eD zPtzinXOZ>ZzBZ=@w^2qoB(R6lm)F-!^5&=6W|!gZ6arN^f|GYb(Y!LcSdua4Omk(V zMgn^%)dsAZM`m9=N3Y`3QXx=oGjD_^fG4jmVWLHWI( zyt>vY4!nJ=_?{zy(TC*q($-%-DPBN)t*AyEq6(uADF=4C;S^h$&R5*QPy zY3+xVmJb%B7q9x|PzY3EL>;ZE7Zj6u&uF6QtNa2jNMLLyJ@fbeGS&St@4U)OAyB18 z>dji;Rg2DUV3dl`Pb+; zp0i6Offgk28ZesA_+NzRwdJtZ`fWI&M)``JAP9^T>#H0xd}34gyu}S#-=g z@M{e(FtwXPplbBjG~)$*dF6NI({I{&gXQM-C+|qv@zH{W`X$_F;1uir<7Hgm5}^>N z!mK(pQtM;oo31&mCsfr6Pr!Sabbd;4?f2_$(ec!pPDaC`rDxs?X2w@}lrwrHY7$NL zwphC+wm-w3&SPcb*R`f!?ofq56`t@@eVp9mzwk2ev#t|IC|OOsWn~sx3bcjSX4eN zc$A|B3G}$3yf`6MWSc-YxySviLZAvytu@UjYjrsyJcmpeaEzk`3G}$3)l%uYa!-~| z*6LZ86#`XwYE7O_8ym}BC*N2B8zn~z66kS5nN=sYkf+a`wF>@wLm^Owr`9xc4s0hI z2OYQe|9ys|1qt-Hq55ifJIags7hB66w-f?ZcxtU_lk#_$E$dCQw%j?-(Sih?P0~Kx zqaJciSQYC~%q@jL6`oqt*j}TrT)M&A`nzKsM+*|_Ip^)T{<3=TRx|a%d4)g~o?2_# zm%f8#(3Y-dnf-e>T980L5SpV(4U_-uouIdQyIvtsg{RgOMHd_;{flJPZx)-TL}4R= zZyHryST#ysm{*R?4jHTvsKVH1^75WJR&EI>%>I}e&e4K|`VJ;Kqh-cc%h^N9>x=}d z)R^ke5A$1Ha!xgyosSlHYK12zc>YBZ>$!?shw@H|nYAri$vT7tp6SrHbJq;k@o8h( z-d^Jr0#)j{+WQ8@tZf$_vLU6YMipe3Mgq^K=-c_Nztwb9Am3t+QV3M3BlYdzp4P2> zb@}C};Q}p4;29fz6$MYW{tX<>L)J$s1gdaep}i%)O;*90L-@rC>imHOo}N(Eo*^+- zlRYzdSSNLkLKV)Blx=$dZR^;lNqnGR7iAtq0(Wl7*STz})%f@#K5=hrg+LX~^Ym4e zlwK~;7x0DYn=11;61eY2GfwZEvf#Ci{9~Eg3V|wIuTTbof*$hi^$omQSFWr}kWg3p zOFVq#vbX#Awz;7Sfht^gQJtS}{?hSn6Q5NvNLgPYfnOGywq{b8TxxCPZTmPC0#%sl zfjl$2RFa>Y&*R2BUnQdh68No788DX!c_hpRYc$GNK_O6uUIa8U>@6*i25&SI zPcVTNByeX+(>%%t$`KoWnL}g36#`YNcf#`@PC00JkmVm)O^I+r0(aOn?Rb7aIqpLT ztH(5^5U9ckKJspR?;#UfPO+}mt)WEfA%Q!En)Y&|r#uyYS8~df zHG8aD-D@Zjhe+U#C)M;Wl1t{j5oCTHZcU*Sf#uG^=IfGyjK&3V|xTBXpWkX`IaX`J$Pl=p*G`ArVVger#q@*8Qa2M!=nM^25qW zW|JMS6arOv-!yGlpFT2w%3W*R)<{;eXQH9Sd9wvm5_I&^!)O)CO*OKIoYMJ?wc}eG zg+SHWE{R6)8E@t}+5S~0%7n|p2g}Iz3pZE67@Qk>o*PD8Z`Q0aJr5-wr&)O+-c!fX}Mk`S6Pq$jKUI#yUXwVcLEl5PA zJvUlLdb3qs>^3satS2j;^On<=?o@@rk!VEE^JYZ` z+HK5AY$n}0=9BvVFA9MwHE!a^{^s&}XkO{r>$i>;BnJ2=8n>5tv$RONjef6N$dNts z$kFpNF(goxtsq7T6+F>a=6ab${#x#>LydH0Zp zm1NyXYNf<3A%T62-t)Yp(dABjeZAKq;GQoD_Uv^pU|k!TD@NDFJCvkV1=HatPrSbJ0{U+`M{ff zpKZ6XVPGG5=lWeM@NOhS3lcagQ6{#to^sT^x?*p~KyG?JHyU>%zpkGNI_47^6!F|B zQI)cj{3L{Qi7yuo4b7K)XfPag|P&BI<{UId_9N zT98ol6#eKECS#hH5qqDg1ga8`KR4!jIoJ=^b==K5NLKLK#XFzy=G8_g8nx&9uty&g zlsu`Sn-YzZt$kQfihXxyHyt7`^jX0ZV+wP$U`{XeVy4rKheKuBmifGFu|f)gDnELo zf^;8N^0nQD=e`Q^_^%)_?M4vC-;Vix)az)?E6I^<14W~AK^!eeUI#ou9IaiuFn>1gaj0M5F5|AJ+1_-A27Vt!2Td8AXRK z{v0hxU``hDj?ULvx^I8SS0t8D2vmI>nP^1*;lnz7vfF4|x4XO+`-FRBFV4||1ZM6b z&*jR!<%U_;d15v{g+Nv2QHjQv1wPE_Y9p>mZ#mTeIuHEh%h7@aW|z~nf9Lj=nSHMD zzV}rERrsc9T1;$j*{{DL=>ZakL?7;1;N;X8ybEpz4Jjcmu!K>Mqiy1jukWhE-B1?^vKbI|KwI-_s zs?;x*jr47hw0I$_Rz4#~3lg|fNLPMuoV*vCjh(vsn<0TJ{8}OpY{zpe`;=~C&bv~4 z@$XZ{sCFUj(}^{D%;3{TT!Ro-^|HhqCyZ-_f?P8yRZ;p$l?tQUiHZZ4={x3_M(yuq zSly-T^#w0Yqg%lcwrbdVy=cKBMn;byHmr|*cN^BoE!?lQ6k&U6D+H=CO*M@XU&^p$ z%k9&p{gm}0GE)mt{IWww3ld>l4jaSY2fDr!=*#P2A<<)HL(y}0aySyG8rsh^wx^b1 ztJd3XM9jKkjV9l#$v=uISB_V^2(1>O4Mc4Vl?jG(7FcQFUy_apTX5 zL9EO_3A##LB46i3kAWhtl@CV?5(lOqH=Yw+kZ7t{^=LMzK#*t?ZqLi*+a56#`YQ0!|sd z2ZgZCL+v(-KN)QmjUFLJ6)M0{b?EakqgtaNw)IJZt`gUl*RYDjjS_*2a&fdE(doi5 zqhX66*7Sk>tLE)2V9m)eRvaFdMIlh-8GX{|Jv4;v{cQiL4h3EsIZBQfgU+V0T+L4! z9fyUm0R`9TeYzYodbSN>S1%{%d3}x<+~-?4TZGIYJ(sNZ-I+vtfxpz7)+X*B2` z!Ujg#8Ljgbi8cSd5H0qmY8-#btM12)%G5@^D+#*#t3raK%_r-|i4A?fGPEFpzmV!1 z93N^H-#t#mbortXsMz|evO-Vs^>99zco78)*M z%THy+4_L;^Iw7pS=X$+X&`~3;VG#SUCPD9f?TE3tS`eEw*S=Q+-tOV++YT1LZ}n0L zRGk`Y8RM&jus(EOsk(gI2==JVc(M3X0>eA{<-$>83f(K~NP@23-KuOq`+jzuD3W@K zp#_QBXO9}~h|WMXRh@41jP0#DPOLu{s}QLAHcT3wdWNv=JM1So@_SC6b8NIY;UB~P z4_#*&T}ASB{l+~w!E=+~4#7gI>JZ%B-GW2#;O@Z&_u%e>b8lbV-DS`L24c9|d%7XX zuK%;%4_PZ~o&CFQ)m^sh6h@G^KVY9Tv~giMe4}*?ul`a!**ugIz2Bq}sFGf8=iR2o zuigd(PDeRIU8ibf&6XOon~4juAL} zrfTUukhoeovc!_`|U&ZDnVzu z+#|EZ2omZ1_B!i03d@`J=ts`BA5`22ja`EcSjLMkWd51IQNYfe|Ee1{}HH~m!Pxr z@OAZvSf6;I%jZ&A6)(duO89A^GsoJpav#^ib6zfRPTNpc-r5=_N+z4{toXjH9Jt#$ zEALuwoV_Q9$!6L0>%cSYC+9iqC-s*;yyq;>D7I|o+WE#)85f5WMv(Y)d5p74Vrd_n zSMZeR=Sq0XM?I~s6R6V9s{Ynlu2)}ksP#;29=ycqb-j%2&*vL8al3Q>3_tsK2jyPs z%(J-6pR@AmIMo%kJ*|qzXN3_YLj1Qohmqf(=aDw?Gv{B=N#Gcv#?4cULn#il5cn3N$vON${T0D;XFUFzWgy~6u%#F5hV0u zWC$+ftiNlM*chb~sB%tsI$JI(`sWyv{HD9YJQAx-MMe;wJ03%C_0=2ia$Ou-P90e^ zlrVw>K7U?6_~?V{$J-vNR;dt;Kozz)*|Yt~Fw?#nqz*S5L>NH=Th2Tamp7A{vDrM8 z@k?LA2oi@cZ+FVOe$r+8uWqNyZwAC$ty+KXtr4iwzlnu2Of+j2GAMD`hJ^J8))}WV z>~LQ5DkS|d<}XUJc;s}0P5 z2AolY+6ECukic&~yNbI@bM}cnYTSbE8i6YP$}_B(W@hkBOud5YXjhKcgta!WSofJ@ z?(dtHLb_Haj35!e{tjo~)+PUZ+c%zGZoWP0Nve|42vlL~gWuZI>rKC>UetC-DZ&U6 z*e2rV(RG{oAg~aHX3a+!L1Npu9nPwMm6RI|>j|d4aM0WouLPwUms2B9rMD9|^|);T^;2^6ldRSaB9jB{M!8sokMv%aEFz2~Tal)L|sRBK& zmza=16`mola2tEfym{E4%+Pd%5hSo3%%dMyj+l)D%hF$8GiU^=^ef-p<-U2bQGH4} z^{95`c!t=A<2?=^+%Nbl`yZP{@3p2o)q=HNDiZ%(-r+3wsN|oW#&f&F&1NfGQ_z^&8i6Y8-Sb{4w@#X~ za(1R$yX&fbsTMmYfAF`@cWS1^&Z0&+`*(+|*yJ2hx%8i7j2O4t+~m=V-h0JKx^9 z-Xl=f?`|EVbKg1UtUbZhd|GXlcw<}V{w{&`x#M-z8qm%eP$N+8J!Cz>hPfA;Rkrpd zXTxBH5hU;odA;+6S!U_fJ*bW`LnBZ%Vt+ellk$P`*L~|4r>D*|{bqEfpQn~9j39yc z&@kkR-erRcJw0AZUG+oI1y$2vnYsXt$aRF68F#|D+9)&JxrR3+Ho(RplUdD*w; za-kFXX7)8*5rO2mk&Q5dgnZD!Irv(6dGV8VcM~s}WOmD6mt2%sBT$9UhUdJDvE~W0 z9*roRh%kago|_$UN00o+ zI+KP;yS|&1WUTXKV>T0T{W`NjkaOU9l1Z9a?W=XZ*~}xyKd3S#TN6eerwMZA{Y3J0 z;V^-}#2I2mUUOxUM3i)46YUsCc--#f^vqsf2Bxr%acXI0^Yhz`RChvkjX)JXS;Kf4 zuYx(DbXGdYYpOAVgnLLQXOGI|<%XM9ZD7u>WA4w8n|2%!8i6Y8$?!_=5tm)f+AUKZ zOZ6jcd5_!~J)&-n{Qi7(rslwjgJ_{v;Ffs3DK4)qmg$ zZLwVye9@aQvU^03bMtzV-TVFTF@}bHbPc?8O!b}6T{{L6zq$rFAG$~$=x7~dPWgCd zmRlFp)cjpF0#*2A4WnG&jn2k@jgxb_k0R_ZHFy@}EbBqC#hx&My%&DwuRUE0dcBk1 z;*He$YDkp69OSH1nxwJaIxCO#U0uGPi>fjwhiL?=@UC+Xx_#4J2d}nPC29}Ro(B>& z4h1=rwV^+woNcd$xn`UgVYgoKw@`)8hIhd@wbm69(NvA>Fodv&g|yydS)J*LtNrCA z>PhK-T8{+@EDKz&I;SwN7TnE!&R!aUs^(=DIZwPT`=`D8vtd4SREGc5k;&}{BS`4) z;I}fB%$#?=tB>BzH3C&D`z>-dD(C;Fy?bnX3-i+1jP$Z{HNprI_@=S5re=tlIE@#z z=e=c+K$X|}Mb4c={QtBQt2P*C9@^kX^L+~tMv%a-E59GJ{xY+q2%zYfIW+=R)vhga z{@UjM=i469f1cT+VlAqgAPHdv3H(;_b(C3cmJO{>nYO=INTBMJRH2$_*VFU@RuQ(HQ#vSIR=j|zJ%QYH-Dr|jlzSpOl&3H4rQHLMFTDt@Zy_J#m z;a+p~h;DSfWF3t_6}D=4ygiT8)u(PlRftPFjv8PI$6gq(^U9IX?2vGwUD`2%1eQ>4 z?*@CD>BeohOFI&%!oCmBJ1?nZF6s4H9p=)G5hSp@aqb=8j^?5oAJr!=?MR>sdoMia z)qIrc>6MONaB0T~5?DgHm62tp**7|?UD}aA74}68<4T=HrYc|5F6|gW0?QlEI|pwt z^A{;?mv$sjg*^by8`XcCS%#`oH7@NKK>|xC@2Y#tX?F3fMH#uYBY`Sx!}ILxP}3~m zrMX?&F@l6%b~EfbXC_J1$}a6lpbFdYoWy+3MN`)7K+i|?RTx1+Z-qOS-Z69CY)>yY z)zt`8VXL2geI=8*CuDC-BVMFdkLPr9PJbOBU-H~d{~4W}P2U8_N<8DLx0X&!U2f(& z7)%BJ%ct6o?BHBfSlIJ`*jmPRFpr)W8RAZqsJj{)xf-z-MSwhOkA*vq^>L57u|-X>a&ABb z32bp#nLPWt3lv*|bmv)rGtaAWd7chkbN)WHtn0wYM^o#xrT=7Zd? z7EV=5*51(wRNYG1)oGk5_h&4;Nv05YXrl>g<>)g4BS_$r<(}}YuI_UsuB&g|+GzI* z?*g_<*$;QPvs)g&r_wL)E-`|{p|M?@H*y91nUBixtDXD%vp4Fm(-SoURq?ZRaTc!| zAbTvc#`IGauIsL~Cj)hSvP)tg2iv$hvEoW2cjcogsZf@65+g`pYnk8LORe0`gh6M$ zXKMti@cIlR`rn4`Gub?-^XLs4an`eob4vozgLpR`*FA}U?6XZO%HQ>(-Z=G!g-BAMqsLzA98i6Y88*+_vv7kF&lK_fL^-f|02{|#y zdG%O;4CdKhUT+|CxFZ@=rHpeDC?rs&e?|ZLnaLdxS(DbCOrkJ?MCO;BoMoN{{Fx0u zcqygZxY2<6Jxrw$sKPHe`{C~FG4mhjK_xTg*1pvEbuKf$qw_%qAy?X7gQ+vmm}&p% zLMsw_D~uq4;}4uu*5isT>bjZ)-NE zKEde~Mv%ZUCoA(;68GWHjVXTrG#Y^_e6qYZN7Pa^{YNkzdy`L{3~nbnRS&eCHC%Iw zm~p08KJCQSiRERrduzE|HT35;Xti$2a@H)~79>)0AK7x&OdSy<(s57Na@OQa(^dF! zjr!YJ^G~{AbZ&B0RhpeONT90E&LGj6`|7`)HE*{KqlMqfDa%=d5hS>N6mfNJ#UUf8 z=*ZN{a@HV$Dy}(2T%Ys&%5^Gj=ib!hMqY(i$n6Ia(|+KxAmU2Ny}f^{Ej~S|Ui{qJ zy+XRsQNC9q@Q)X#=iEbT^7`)d>#VPK4E$Z4`0(7C*-@P2visYM z)8hi~RouIS?ZrU?RqJN97a=(U|9Ek(CH_w>&C}lY;$Q>`F4H2ev`?M=P361L()QvY zfhxzX_99=Zz&~D`p55Zn+#}5?guOVZda|IC`0^^i_TuQo@g}M0+K2{Jn7ud{LBjK8 zClUAc8Clws{7=@jy*Nmqs^Z-aBFWYAf4n$9R}`TX=gZn&oZ!qI#jRuIZ7)vq=|Q69 z(E!_v!(UVp_oaT>tqfgnSIqX}Ac3m2&W_^K^zwhaI1fjA)1;pjZ7&X*M~%)AqD?Wwf%qI2FP>iP34x+g_YUIl731bpmWJ4!3GVT-(RHUl;oP;yC7SHzLAc3m4`#Oo` z`O5$C;)Hv)qk*|UsP62=!3YxgWO+t0M>k4-?TSjkUL1UC+1Gawr9A>{FOL2MQ+@4D zTc@8<9_+=z2oeEXx`@Qw|M>02@gC8eI=J_%LF~mr0##|c28mldF8bSxv*T)Cn)GU& zvb;DLL4tc3BCh|jICLPD%Q#C}UK}J)h4mF@z-%*!77d)LcC!};BS>&BL&Wtz5<5cZ zO{xj%C3|s@Ko!2N5^Jd+m6r^19Q98ttsDI;3td zy4L(XSA_LB*7JtZwBy5oi0KDxKSPb^AW`gxvfUIso-AVgH|)z1aqgY2!~A4|eQ9hz z1J2V{%BF1xrbvquLb0K|R zCp{jHxBU#L;_=;B8e1QnnZo0$+`VJD?PtIU5o!^Z3T@=CJpwx0nBRAE`* zaq5?alz+11wx0ptL45CcZQUaREeg=#nf$xoBe4XM@so4RMjr|Nr zpbF2>Fj8Dkq7whOZTlH8f&{)dJm*#ZqpUdknC)jk0#*8zpPEooHTx@#?PtI%$1}w5 z7+*)NnyTpithS#4BS`QFw21Sn71>!!ss6sUp8*L};rG}uI(%rNCbchQ`x!8T1lAJl zLYmb_%?K%D`x!8T1dmyZxLM08wS!gUOS1h8NT5ouYqv#CR%=JLrb+B)!1fikYIw|A z#LXgaD=Y#DIwow<`#L$A8Fp8*L};TiIL)U&~A@Zf6XWA~p<#>kJs^y$DP3EcDy@PB&14fYGv3C(O z+iw_=yJx9ykGj)G_A?-XD*c<7F!y2=e_K!6&wvpmcrIPUxCq!gcyNwdw?3Ex%-UMt z09E)s<~?7!KUSgd+tU4ab=0I{E|GC#aeG#u$3jJnPl88SMVv3=_|2=T*o=;}X?AUE zBsDgI1kW3Y7&nAr{OI*i9lh0%rm>&lO6U<$m>uJmp8@GF<&KEl?9>14XW0AnrfRjW zA@yTF14fYGkzx_&tf_wPmhvB2%l0!MfvS$hkBCuxjNg8SQI}t-IYnDhhSzlzdptzU z3J$yr`FZ34%1fC(U)JytYb?DmM_A?-XDvvuyL?o}9 z`0ZyX+~HsKy;xJ*&wvpm@E)>rVDlCg@^=Bc#C`^>g|T+#k$Vy6bXukUR!69y?PoyM z_e*Z!=4WI18FZq{EvL$T&Cm8TU<8Rn!w(C`fMS3A42?O9)$?8z$YehQ5~#vw!}*q~ zom1`q3bg$U7(pWS*ux@Eep%#5iX*&maRz}45 z_hy|m#Y0}fWBCj49X!fDt5``?y8VX2t$E2QKzpp{i0A+c|&)s<0Ks zBije0YUZ(5_2D`C=Ks0G4PF^!&E%)^;Im>cxHT`&^Hd_v(fE0HRkeoP_8dJ%kXTv3 z6lL=l`{TgKo#B*_FoOnqUtZ6Yx^=Vf<)eFE-{o> zbN%*Zyy}o&wWzt;_GKV}DtxlMzgpy25i#$bSjQe=_UVckpYHCLPO*kv#g=D+oxmc_ zBYeN!cX9mlK-*=35hU1|E8-m3>_ZkYK4c_N#r|Xw=fGyqwutd;V+09ye~UO@_~xgJ zcRd4oe^Q^9jam3%*zeucM&-Qh8UGrSAh;f*6E~KkHWv)AqZSM!3J3fCr9jH?SpZ+5HSwB71=y04ar zA5~I8|3jb(?=)w0I5I~1{aeNMY-7&^`#adP;AFbJo5=?WGONG~!!4goY%c`~>>F}k zoaX(cgV*m)uBH>H!aKt2)x!P~(WBei{&wtPVUG@vXRqcEu$m*b7l#C|><}?)L3kI8 zoAboY^R*?dve$pa5~#xdF0ZxBAL{Vi0nQ$fVJcW#tfsaAv(j&bkAMv%ak z0q6K#uu`=@P$tH`6HB0qoeCn(z0u3DrZn!idnY!61h&rD0rByua{p)@AJvXx}R= z;rRY@c6{%5a-H8|yR>5j2`q2C{ycSJHLb`VyR;*LD(ttjv;UNzy8iO1UD`2%1eQ?F z9Jwn%Js$Ye_NpO)D(tHp#+yT3)rvtG?9z@AB=oYI`Bo3rA-BUW?MR>sd)_=#9UQ9G zdzG+DJ4TSu%kD4UNw9ufVV8C!P=&o$!>G`6x%xD#hF#h*f`ndnYiC))S@9ZD26pct zfhz2=@`|csoToTlYumkp5hV1oyDs~BRdZ2CyR;*LD(tcHDu^F{s~+*XQn99eEJu87 z9~lX~?EbTPvl=$P2kn_*d+1{cRAC>N_fXi?L?zxEV!L-96Ln)&d)vLkE7nEKDt_!6VjqrsEY}jd-_B}ImV4)JroEy(uj04dJJ{00 z7NB9c{L{Ewj%Y}hdj|Y~uPw#x<(dND5&04yt&q zzKB`fuM?}6{5s^Zz$1%BaP}nevYL-vF<_0rV{>g#uP==cTBs)e z&Z`!CR!G#I6fWk~_K__HTF0oEtT%nizF8&W+->+i~e=QiP@ z)dU~;!9K=ch1u&<@Ui-q)6NwZOQ4GLl!>?uW}nlvq0ZZ1t7iA@d}Of^BskNUNW7b` zW2|+r7EfzJ-7+Mi;(hI$XR!pTINzFx%fvQ$azpBHEE&x%Yv)yqjUd4p(?rBoADMch zb&Q{0b?Ei#v{ZMXox3fTKo#eW6LA^kW|yu-1*&JD)TizIaIq02IP;qr`mc{XZXZKF zs!myYdQxafI|p4Xfhx{_C*m^WrkHT99()?yq%(COQNY1}1D*JlN zNk!KP&I&7HvO;stRFTo!TV5z)5%m@hq&tyQ%x=ZDNQ@xCSzSe3zSqxL`%`Ew-ovfp zN{v8O-yz{*!znoeh6=CxwMv&mFt|Bhq>)d?3XyY1}8G3N4Mxcsw zriz2%4tYAeb<Ids3q8ZnMj=DH0<{a8_3lm+#f@YpbE>IVZ^JUXw9bFR41gc!Y>YI@)Tt} zeC52!YlQywX+veHRntOL@ppdF*zXb&3zokW!D)Tvex`ZeV03AUU$hAM-?Q_J#uBLF ztga$1-|NI2r6}8qqU3+a&fXduL4vcPiZ_{kW%4Q3F^b5dbai+sYVteZYb=2(&Q2@h z^43m1T!021@Tb82b{5*$2ojuMR%|WdD-+n)@qKS@I;a$F9IX?m;w-x&F8}U`ez_?b zJ2Nl$x3lTSMv$mm@1>wpzVhWH>pIF`&q=J(ke&I%kGL4x!BiX4r6|5=1mmvqz@0GGNBG^fTZ0imQ&RQwr@>#l%4yAq0Ose=_DK!FBoZ(RG!@ff;#R^Ccj_!C6PcC=b9A%@E%nw>^-V(I!02zTA2@(%J<32*&iE0ViF(Y!n&Mt z$0=*2MFEeIl)ZI+SIt^c8i6X#jxXZ&+S-+LB(?ie(v@Jjy^}y}1PRV{FJg8T;QYHc zMo{&sV_nTh+1c@92~=?|e-X1A81GOqpL^OJ*0}yD{IA3a5}aFK#AV>$>>5sCW!||m z?!K)NsNx+4MB$d+ax7WT+`&E6)%!inw#GFpi+OAW3Eove#Oz#P7;kS3p}_Rj&BK5Q+{Yyj#qnVZ@4&G+*>|1En?%UU~1fSvw6701Fd$(dUxO4aB+wC zywAPUA`%|%Ok;ZUjtF7Aq6+F%tl`Rb4HpwmIpp6fEn;EcGosJ%_TuZaQM4v7T6{U- zB~!b@#M$=IqO!}&&S2%37cDkF^peNyENQvlCsm!7IbHb|52tw-qC}hY4mtN)m{__w zN_2?ulJ72uiFm)F#Dbe%GTtf62av6SCncYAO(r>8iv~7}5*vA!>`c5%_Ld=0ViE7k zJ(hRnu97)QTnzA*tL@!rOTC(}>RcLT4(ia89&L{lEps|# z6^In;u6WDcA6AI=V~owqF7-nx$YeVWkbMzdAddeJJ$)Cf@~ zhmY*#UMU`3j}YI}`N%;PSBk~QBSh~iKJr}ll}xlu)s?nC*`~hL7^&{83>OKT`N-rC zSBq08!i8$>BllHbEm|%M7qjR1$d1Y?B`doOpzCXgs0&+*DD1`K2tuF3;i6hj9yNGi z5g(H93ZCoFUh7?!B#kD8ivg2KgxYN>;T0gEv54ei1{w_l7f5B%mZn+3` zMF{5yAL%^2T-1CKAy(b@k>ZE-JQ9D%K@GesQFOMl%D-f|XkNxwRvx`lr26}%7|_aB z7JIc)U@gjS+`E~n-Pvk1u4*BL5hV6ieksPb^OZyGE6;j5Go8OxjkeU+2~_E|^V>?9 zsne=z6y;S$mGp=ZB^y86Ed7)@gtgMgBUezM5zsN*$ zBdSr)9TgQukZ6-VS_JW^k>58fhfvY2nJ7)x>U3d_PN1r@N3{4<%SSFWtYcg{JBUut zZm9nCE2xb|VXHQ29O+3muE|_{gPptmi zyaD$pV}oajXDuZ&S;7PvG5RZEIRh(;}Z16uCz$mdXa1g@h+d7aq%eX6j%67}rc5oU%ci%gyLTszK$ZR#-O#)p zb({BCMT)8lBS_$w9PiGRstaw(b67RX(@Y~!h0liT^PJu2X;QaZ`)?`j+l~Z|Epn#x zp53U-BA05nT_;e5Wtv-k#rVsUKQkrIUtakY4Hu{1`^a`)s|EHy@va+2>F}DA;Z_>z zTe^kzJn&BAFY&jX^L^aOosRbA8KoTqiL=|n#iZLm3~&UdX}WV zE}LJqNxwwq%L!4^Y{sF4PEA;rEeysfRjKp&_%>&1xGIMv&0ICDk)_ zqzK2~s*7B#5vanqna4{Ox1uvWPpLhF)@g4o5T*7292Mdf=Yg$t`VrhcZIV$ zes4x=mEbiwKb7}AZiU_VmS;NYEz9w9B7}JEEd%aa$2gw1C4CEOrt*(^qcDPPQEa2~ zD$~IBG&xyb)n?RFjX>3iMiC-igttuC*t%D{OL$VhU)AWz8Ktmoh;1!w)$r~S|7D}8 zODj>gS2YwykkH@rW+#2<(bE759yLHCP<173q)2wyM{bi=yL}bqrzsmsQK#`k6h@H1 zx7jd^GDRrfvw}3Dz!g1jdhIO)$3BL$I+^5xxES_NMJeU>|zP()3-v`)TMtfY6PnEK2F!wO{q_A zQ$7EDN?`;Ed>=WN_u1yOD9du*i{*|+pbASRk29ohN9Om5YU!#=TF(m!Y@_fu@k0kX zRK2n~*X))?ph_?8bJ&iPr)=Xh7{A)>3n?Bq4lju{VkDBRf*o z)S_uGMyYI%QV>Rv(EFV664jxcXO^iJkK$9s}@8QiCSEyP!f>L}||hRaklqV`6AUnv>^W)%C|Kt&|`U-6K-ut?MI`ezM-E z`jHiBdxdZ6dB6>gKo!0P>~&r#>F*>-sAPg0T4_gOexpb+W3Z20Yv&|?-_V~He@;)g zFCEqhRN>pqv*FSC=~SZCDvAmdjuhaSgFb5TY`-tPxaL%zTMH3JkkCga8Xd?-_rG0L zcRjo{0#y_0Mv1AfxIN$5x>x2lAIeZXT33<)g&q03Z4Ip+)3Mo{RpC^rVihzbK3#k)cYo*w0tqxr{}mjP|AAFmI~! z<)KEP>S~2(5t713PJ3bXQWFfwL@BFOrvjrZD(t^v4;y>P)++2Q)bwa&THT?k)^|n% z>n_7spFcbIn~8d~o1hV>s#Gpotmb}H`i0h6?M&lMV_*8ynY+^!Mv%a|i^oNKdeiLA zel+32CXGOqe&uU@@=^8;1u5m49SS2z=%xKfSblO1@}V>9&uIjz@Hz3`vd@asj~s`K-s z%A7utRuWOAy*I|x)#a%9yT_{Dt3=xSfdqcL*!}sW6wR4;K~;X6UL#P2??3OZQe9Ax z=U#PtMSAT$M*_dWyt7xtuM5S7lQzKA?W0^drKZ&Sa`myTO%k0`HClWY*$$q$k zsVGZ?AH~b^T(xWaO4Og{E#IG6CKAqgEq?O&cbcio#Fu5S#SXz^q&2OwyQWS?`dEWo zeQVpQ_~&1XDLe-;vGG!YBU5E|zZMH>ddpkytg)s32{X~|e!>V6Sc~$v8Qn+(<*Pr zvfA7P656bTartkqnFn1p8|<%6y*@;UyWJde*?|?pu`fc*sN|4c_pcDelShi(WgT+x zII9(YJ9xYDdo{*9JhO{7$Aa@Jb2mkb?RD6TQ_&(q-W^w0)3r8(+(Cp9Bo^O|6sbcT z@?fAv#P@%!rswNnehh4*5vbZeGE$72=#VLgS;Rz-uPVdBYUZvT%?Tq&yx$xt4(;T< zbNgGws!GXe=C%6f$B*?i0#!#EMv6{uhx~7!MJzs?kp>>hZ}y>@gb^fK4388uqZ~5z z7K>ON?oCm(3Y(Wl1!@GU8s+2b;F+y8UoE0y#$lj8zuxfsU%xiK0-RvGE=H_QV%&RbMUhP|pDB=3g|W>c z{~2QuX$s#}$qO}8mHgThMv%Ze!WnxL9#x<7mQfG;@F)oU7OM1;xP8S5Wn4?93a#o! z7(oK>h+#Cyy+wJgye1Q^3DyWy;ak8v9^LOH7kmoVN;?wzy*k!@o@!9>KT+d| z{zjn+OFnvOnkHVl&JTt%mB+mA2B(_Xw+{3vS%tBtb~C8+A_J|0?MVgw2F z^75Lv)a5AOoTBcdH8M+#psRT9o|j@?6^Gn9z&gf~WzDFdXA-y9)`gls5nZhJN`#A` zg%0^~mPPb^(2#yD^>F`KIZa{&33SaGMq3Y}$^QA>8|#E=XN6~i*T>f})SnL2DdOJe zxTjq?5~ugQ6qT!T3!s;ERs~#=y3EMyo_i~^!rwyGmh9o;`5=dEpV=Zpca@=21q-|T z-N~;|mEaP)1-OM2nrF4piS2Vs@u);W_xTPT6h@F({p+O|*oa$a$E=a<5i`qD(l);C z@=d2|1ge&?iy-F+hb*<*BG#rZPKQJCy3_7ksxX4Yd9QHMshLCG8edL3 zU+>lkR81NiF6NKsc49+|=$^X}ef;XugTmOVb1Mxufm zfvN>7BE-u64!Qo9)shkCl2TRUyXh5ClrVzCvR)CKxyd0ff3k>GYZH>0=$+X;S80tv zRn^`RVjmOACR*R@K-Is$Fi-EUUtY&Wvusn!0<-2_-6w5LT7V@5hNNm4HqN0uFaF*BGMFYOv6sS zGebGc7!s&D&%VC(HyyI%WvjFoPhOYI%!WIl;&O!%B*u>q7l+q7)##q_!Mw8Oyut_)ClBySi_N@3p}j?9I#Pu?5B$e$ zwKhT{P*o#Ogz&%XkWZ3X#PDB4O_x14Q^)_TFoHzikKy89KE}rQ7Sa2Vq~PM`%}3>v z6B4L8*)>8OyycMLTdcCXX;*2wTmFXGrAQjW2ojI|BgEy64*Ayxi&(qdk7^e>V1CS> zLnBZ%Z)b$)cGV%XHnxaVbqdk30!Pe#w|xjBNc0^SArh>0$ZZWR;!VGNG-usv(?7I` zMxZL25h-eLtFKrBizsr-LDQCRG9Q2PBa9$1=4yl(x6C28C$xwLvoh1Mtc%Tp^OZ)R zYCxVy(PWN8mUmk3;H5(;sm=0T|o0g5rs2NX>b3}X29DdgaoSaedOu${sm|~e?^~cOGOw#0_$LYf-`i}>Kt zf%;dPU=DtDN+VEJx@3eH#GdqReJ$e9)mF4N)f}?}&s1Xsi3Hs0%b(I)-tS`(*{?RI zSthQ>k)L}KKccmWY%I|3iBS<9ui{0Nzy=B|Y7Ez^26{>l; zxEXI>HjO~luCEayx}>*^XSa8ICMr*@CsZ*{-}ferXvCceF(#?=e~G&o)g z^H?DFL*Tb|fvP}_NU^+tx7;3X)wSmam!y9EbC~6*IAH_{eMI=vmm*Yp@L|`vy8ar0 zs=8t9_sQWcJ1w-1asEeMsuKRl<;X#V5hV2S#Ncn<^lfBSSN7YLH3C(0zeI|UTuP#A zTgRBZI4fN}KFT$#driU!5;%UzqqQDsY3i>R&Q+HhXauTSmxvO{E^xafk9CZ&7m29J zmZ`3-BbyUOkibz@-a+#0Yc)D`AJ>4M?KJ{bXSzg*;xiobenRUQ84BH2WjdIy__sO} zMv%bKVV>JgcSt2KwaPU&xR*wts?3ro(Y&5R*5?%}+|oa`LRFgi(3P-nU&06yILghQ zA|4-`mGO{k#+X4Gfht@>!+yB;tyJQQNz6B!L$uX3Na!QIwU&wj20iW zdduOp?Geb%26b6HM%6miP$N))?1DnZ5<gpY~NN z!m4Nls`Rx>Vz&smEASX^3y*BUdd)_q(-3X%%MmT zS=(El8*UL}niZwOW>VF$RT;tv5}B_=io?7@sY7#%$bF_1jT^jF4lL@Y5vV%QiI36B zTjsxJ5!dPm(E6#zWWN)I2qQ?;2#FM%W_rs!yDj49h(Pko$mOR&UX4K2>hzJ~cvoKG zR?PbD?wC`BMjr~1<*zz;HCn(H6vxr|A>(i9^5n{xo^z2!Siy)EzR)me~DVI#QK;$DG;bzf>4O!qGTFJlyFmuXMDC|7v!nV>=hRDjd0{5vcO? zj1ad%yyd8e7BT-|4;q-El&fl|lL{k9B=?RGr}!92|FMX9e+SdUS}s>eudNz^s?1U0 zqG5k;sTx`Bs|CCJQMD=qUFvn1!Uz&0c+?;}->Y;@E#i6PK&n>xmaFvIaTE%W%FWI4dNu<;*J%y#~_FPvy*P zvpQ)6s_?EGM$Nf>$yu(o>D6Ggc6X7$ma}2(X&Ov}N)M1pV!hLm!U_bKqi@{MN;?wRa^{@`lDDG` zW@7V3hiHvJ6~3E>ako-S8j{4voIUZI_SPbS?O>h_zt@CLHoECrFfXb0Wk3~vm3U9@ zef23_zJzA6RH?PE4-(jNHjIPEYthcB^Ic+iW{p4E4NDc)Y6B#&<;?4fQk13??GyP||KX<* zsKVNg*A*QoO5Oo8ovnCH4n~l`mNVCC1M}17e1+uQxug-O!djbqEPH*(+2}53V5+Ru z&PZU(ndc39W}zepf@O{lwKM`%=+R(rRPof@=bR=IQlzSb{FHH}~2x$|}h!Uz)Ba_0G{SC^G*!0Lk!_jc0=RN)LJUq|PCs^`?C zt|I^RCX66~EoYufEw)G{m^stgFkpa2ph}+^9pf0Tl5Z*JDtbGFFoJ~MrtY;_s2#R@B99*}LqZB+^o46}Y9(ci=I4X(42ogBUVHkh!3Zk-8&X{wL*U|`7;V1>K z!J5>LoI`J$-$J@6j39xt9Gs!4T05%y^QhUf^#YAR6^>FEhWG9kRNj5r?Ch~tVFU@B z7vYsi-I~+=ya&v*AC7ATs&JHo$7F^zq(X;Jn2kNJDvTh3^CG-Lp=N!$S80p+rP3>n zKoyQs7)JM0HL2@?eda$=-xNlWz*!D<0;a7-CFd+Px0XslNT3QwDcHX|A&}Pmx6Z8I zC@orxJlKoyQs7{{RksS;JgU8ed7C4x$`Z}=0_R0|+^2pDYLjNPxyY!k5vW2JB42s$pDL{5Z1Zn-ea&r%gg#?3b>hG3 z!{lk^;o2=U0#)dyG>n0NpHu$f%gmuAT5GOJB=lSsCGY*MYBXGIx*|Jh1gbEP2CtBw zP+Q&Y-A2`(Hh`M{WPef~c9<;=6B&J82`}Z4??S_b_vvVHiG8G#IL8Igk|pn>CKQ^e zM)EF47(pUSmsg@~Po8&fWf4&mr>g*0sH*X-hen`k_UCAEk4JIRb+?F8lV_;H&b8{= z$S#BtBsva%C06rn_&a-?VRp+Es!y5?>ZDI6jX>3hJbX=mvuA>=W0(Wish_=1sRF!8 z6C+5-v#-QO_AR~tX}OAf+&H9Wx4EpoCURHCts*5U1|}kZeMyOX71uS+Aqts%q0BX9dJd}G2g093#tTA)JM{ED}w~paAKM|d) z#`|-IX442%p~IZLgF6hmJ=Q@}TX1d;bfv@ZHfix%v`+0Ur)RK^aosaHCC#6Uw(m}% z5vW4nJI~jaNJ39e6r}MYk>-d;qSwUN;$sVcpH~&V)lVZ( zh0Z#D9v2p?x}Te>-k*DE4mu?8Z8nT=dAF(ziCZf#2lO9tE$InsWFWYGZs?fJ+7^>bWmEM21I{l)#HZF<;zRg@mjlZROFW9F_ z*KVv4sKPN)KC2D?D%ItZx-qsEVFU?$n|XvK>Vv8^#;tN^uBj2I!ZA|An4Ks-74 zDo?6R7(qf`Z}6Ft()be_)QlBXH3C&QM#?!eA9>KoPTSP9UF?X5QCTGP6$+zUW~9~5 z+3M$%3L1eb93$mXgR$8t@6bhRMtwmTK|)*MXr#>ML$bv%75E}RBT$87q}-!Fl9zTZ zn4p#p=Gp;9Ws$%&n4F`rRS`P1sG-_$)lVZ(g=3_=57uZudUh*Fy_bavBS`2gsyvgF zqt+9PsMBob$o zI_2gqo438pOc+4|*9>!yKBz8j9dTDSot<7IP=#ZphT)m1A*~8atTH}INf20w6ERho0(Srcz;nNP=#ZphS989Pn!Q|vRrQ-Q5Zo& zUmM=kt1opLwL*N`y;&nrg=3_KQ70K^h<(;f7MitOVFU@x&%txsg+pl5%_O2lp$Qs+ zDjXx_vGB!%sn`HNS*u(hg%Kn$g9tn5CJ&<$nX}5oq2)9JRhY+*cUSQqPT_SI$SG|c zT82L)FgF?RSCsXtTvvCUTz-B8S=sNrISZbZ0nb{OVb#6X+Kg+TGRd<`;@j&qI2Y1= zL4TFbKpyU$Y8TIV|KJsjfxLRrT9at4K(y8+`j*Hn_iaw_XN_XA*O@7>QDrJWxr0jk z!jMzPXSG)~;tEGxyJ#4d^AUxPbI^?@9aYi5%<|Cw1U7-coBDVTIrPvMVXcp3Ct%z1 z)Z}^=sx>xLVFU?0LtgE)tP0I7=1Ixwb<_w{S?e#Yv;2LGr@!)2_a|k^?{r&rx21=) z{;Y^~cGg*1|65mW9rO3<%u0Sfx&uI4l)CUHn901POdj{H30rjdr9WTA4Le zdmi`<@N9Vn=+=yM{HCJJ_g8DzfdsA$cyQjw5Sw06*0g%Kq5>zK*UV$-IQlxW!#jX;&&-kr(6A2=x^4H|G( zd!w-I;*;gk^WlXken@uuu8UXLwqF%VMHoS1`p^Wj?ibHL#GP!3s8OYKlwgLBMxbgz(**MQWzRqTsIe3M zX?6Cz-2uKv{HWRc7CeD2ohKpc#frCA?j2xm;KCzPm`E3hx51oXnGw=Cv+h6Bt24FC`7CCZWo|3Q?k& z2?z;PVV{cg6g|#BJB*iV`|?6$-E-^STm4t7A8YkHt^cjQpw)N#{mchMy;S|i?NfKU z)uYQiG7!ik1h08?!0MY@J#MRi?po<7&lX8w_tgy}Jjr{NI<;GsI#H7_g2a06o1f-B zdNsR$emEYVf0ewH_<{%F`C<n%Y-SYQKX>pz6WfRMPtU zJ(h88c6`dYCn;H_1S3djcf>g5^-N`%_e~wFN*aMGtAtqP!74Gl7Fk?X;bng*7kjob zf`opr8hN%{NXRxVdapbE!;*kAJFq}tGZiMq7A4SnwEDShK{Y3I>1YZT2I^|JoQ zGHn=j=WkcjKHpF)TQ}vrHE|iX34Hh~c&PMl07t-s$_zAfE- z6`bJK^UkU6b(oXVr^Cbg}S{>+i+Juj8C{(g_7 zUivamrO7@+r3vV+l@e5?XqQS_f7TiDY{rLSDsAI&_H|$c3G3RdYy3@oTU}gLI2Nd` z^#~y(P-V5Jt#-B5zUI-WG#k~vs&~}DTY5>vF;XmJhVi-E61DgHN#(Pr4PgWc9P8zk zVPB^z^Xm?k>s^pWpbAHzdG7ARNOjzQiOMsy2Vn%S1CPx!)lEWG@fi#4yNeMd@V@ct z<#pSY|M-3O6GQ@4Sn_$**5T7?!Aw)F;BS_$}c?5EYLoQF4LLOVM6R2txol;tV z*0FhQM#vKR&&pZy-13ox5hV2Mn5!~L>(4p{5~#AS!8+sL$N0RpnM(F(s(RP9k5<}o z<_F8MVFXnytun6ZqB<2ANEkr^N1%D<_c>WrKz5<#Zy2l*sM5a-Z}LP)qll;aYZ%Y! z!#4v793$s!3*4Kp%)R=R+@nVVReA=2K{vwGh{&<_TZ><0{MKTLVQ;P1B-Q#-|NrxC zM*_cmyqY5qsZsq(+GQ7i3sv}R*kv&(ojUc_(=NLhK?1Lj=UBLeSS7_OB}kx3f9AWg z)sah=50y!|>|z87{a#%xK2hAh{kQ1G?*|g7!d(S8%T3N^X31XTRS54Fw~8~7Ea8kK z%Qzd!gQN~wB3G0M{tzbaWpcMgC zJy+NIJm^IQlxucNB-s+Feo8L$1%z*f8k$Z&T zeHoaA^hMTxIKVm(M{F7p6YS%Sy}UOgt=m;$dJ>ttD@Fci;XRmZC@S4&0x-cQ>5(@J877@4hbd#RzGem$Hp?rA>UY zw<(|SeaEMJp9Zm8MC~_vi?XZr+uQ@J!l#QD+D;bxYk8>FO@Fe#yhh$)MbN^m4C;~) zt5;H&N`(ZET_&e^@en)mzGAk`|v0`8|Rtwzxp7-mrLSbY`j2_FXk(F6J@|{gN z^61BU^gW;mwTY8*OO`U?%qVt6$PlBSVHbfM>?ZK?*eX4NT?DSac%$#PISGtAUXMOG z6rq9%e)2yj_DWpBD)k8~^bA&Kk@wJheRB8;y)En94`jW2vT5Dd$?HSmFN)Cc<_qOH zR@l4Y^-gzZl|9VD`7+*nULcU_J}yidZx5FkK?1MG^VA{rD5FbZid^1VAuvmwhbtRi zpC(FsD%a0Xwmr?tzXMpKHvcNUc0_666v^HhP1Ik=d+1qbqRCu)S~-CUxI-jH*DWoo zI=s_+*cA9zWU5aU&e+q%E$82vqwW(&DZ)3-f6v@9gXgM zd8NN@yIS8>o867pzShe*nmfq@-m=1YQW1JE)kCgrS4Jchf2FU;zD|G2z6?A2ztZ<_ zU!&uH;&aihlTTBgIV`dyK3t;|?dO^4_Mx1F5hU>1tVk+LP~B`Nuv13bIIb*V1PS#%Y9IC_ucTu1CT)jO+OZt3VD-yhtb)1Crhxe<+KX~^DnuWT z84@E%sB^C?Sh4QT$3k>|bCN<}7Cu8hyTl5Dm#gsU&qB{7Mv%a{UOv6-Se-ID_>9J8?W@G5d(Uivn<7`0;xBS`FF9oELI$2!NR#cJ+23(I0p`|D*@ z2+YFw#JfeD*)45Z2|7RekMcf{xX1PU&VYCNWSbW2+EW$C2roeoGOF(!v#`AJz9lUi zMK-BPn{#|oS{!Uk>aZg4Y*q&DYf}Yw4y!6lEeW7&ms!se+SmP8oJBkKiQe~Df{uT%1zQl`LKO`>N!{?Fe{in zeg?AFPqfYF=h?v3(z#k2DmCS??9h%qe%SFsue3%V%f3D>+22Pxtk#j{U957O^oVLq zMz?f{5hT=>bHc!Naz_f+y_>TV5}2j_s@GvwiA zwdqs2q6&dog8h)}*%xVnO|n(nBR8Koi;V0cG=u$v z8nW|H2rI+{+1!WTE^Hy!u~W<~c8M{)k4>K<)BhN=OowCB1Lm*Gv2mn??9EOwg9iIb zj39y6<6ZZsUy4!bBkAgyvI>D&;x@Z9v4fp^XVWb$q3|jZoqIH$iFabXu>VDnF#Yt* zb;!S-dZ~T4%jJ#w(5avf(wCi?cC$lMmIiB;K22PfNf&6tj&YRmRkMSw#4(u_41ZJtf zs(e~O`qb8oN*y~Yv8RW<6wc$35k5^7&`+R$=T)UGDA2wR~Lm{p1O z`a833e`#rs4g6e+(zdGg=u~+h`JDZHFS4(%>FIl({Y(n6ugMYiG%>w|O)rzbe!|JO z^HK9x4QZ}hJBbk_TC%51G<(YoxB1E}3Cc~q*p0?BF+d?O%k)GxeP;gpBD=1vMa}y1 z`MzRaau|DXPG>Jp(}&aa$}~MdOutOE@3Zl4Jt~|~l(Mo%mFW^``cauqk=SzzV24Uy zcB*`7bE*7P&7Yn2r+kh!C`*Ocssv`4PMf9^%3rt5-45QAzOWMY zf9EMNf&|_Ze;>7K)1|i+=*F6H68q=)*3#I$%n53p&kQHbx;Z3*RQ6$h9v>UAG3%#m~_aBS_!~iF^9bb5N7MjVM>dB!$2% zeE-}RB}bY(vkr}Uq?Sa}!PRtFFX= z{L(;q=SZkygDQpV)9pe<=*tbM5SWFdK0dvi`c8gr?@g`eY03x^+bFdMFgoCx%yb}t zjs>Jij39xnDC;xKyeH$Y*P}e4$qIp4&DjBCIy+%x|77+Vc#c!{zSn{}-MA((f&{kn z>?>2^qO2a#t8&E7H>Y`!v`68Fh7>76Nh$$t_fNMO6dV;q+g@@VHS zG^_qXg}|&u>TFc{z0B5$lZw-!g2f3VNc3i{ zzRs-KS0l!34O$$3W9;nhM5j`n6aurdv4)o$YkB>$>3Ah&eP#sZtVj!Zrzu8|xXQ|6 z|FOc@Gn=|tamz8IPY2#NaiX+BVAcRu7Hh?-Ct)^qv5l5PM#-%;DTloSVFU?-_0DFo z?wQXv^FB^5o^LeB;6X9=WfTIlR`724L99;F%BEl9(ka^TxF^VPaUhH!5zmS$m*=no zpG{RI^i*@Bb=op*5cBz(=59uw!IM>N(WQZj+qDv z%v#Ax3vX|-LZwY@Ve_;^QDSOy+BqUGVFU@B@#Z?wrL?Fsy)l(wr&S~{>k4a3bY(>e zQQiDiePf^L`-=t8M$_8X5j3Cj96;EgKxVB81c^__$ znl)f-W!kztw?beR)+=0>M1C`_-LFn_9%dzsAn}Ct8SAj(!f%^KW3eVTj2uR7Do`Sy zLSPowE4=qyoHx#&6jZ)y4#Ef$-bqfPq^Ta6!&Hq(`m(|3G1r%zee){>W?@alYj-g# z48M{*Gf^fdVFZbHtV?x_^{MLF`aXW0!i?#g8_<_m`4j@P@LOT;v(7Dz>hqhiUU3e> z2ogPcM(;iAn8w)@v-bI9G6o(Gq9*Bi6aur|wr-Ynkc`ZB`GO;Qve^FssNL-Vet_ADatbQNM+vdqQuz+U|nH2okO-?B~rsuzlDA zmd9$n^GVkqeJJs5yh32sdv=M>6iat^Z%)&lA*Sp^*%g{ny=)ufO z%IqK#Sm(21)~$K+#rz)hIc}FiU>5e_HLcmMYSxHK-gNqFdwmD-dC?WGbm#cB`f{Cn zFAI5Q;?`PyVrTZuxco}r`rLdUSA(ir%a8D)+IjDaU{>Gm&MMp)`>)mau%fssKU<3)gHlI;s4dG_2CA^z;gdbkywbZUWBUo^q zK7l>%Yp~b-b@sWxa=^)^SH3rgIS+S;HG~(kmT>sF6oC;Wy0e1$4OTL@pKIQS8*82~ zW9{=6TbC#VW__FCB(mGT)&qW+gx$(K)Lcu(9K{K;s|KBgr-+Z3!2m^FpyVgX*T67dxez3ga zJ@GqdEq!85{rr=Hl#+-@SZ_`MZg z>n(?@(Q)5FaaNQc&&u+nY^w5SJC(8e&hey$O`|17kihcBI*>;TTc@n^rG+;ZDgNn^@ zIh!n&7(qfUi48ZbG$#A?plfe7DFkMPu(oIrYm8pC>5DdCRn@bsu3DtpCuM&L?kO=9 zR!!a13sub;ZeZ&z#`!hjRH@bjf%{f4OWnf~#5%0=SdVpyrHI4`5_mm!YGNJMF^T=@ z>7QVQz^p2)!`hVfSSvO$%dTXVsfdLGsdxQx5+g`7XPvMdtQR)crWLl|qneQ(98P(P z#V7=3nd)VK?BD2DYzk&0-p`I-Gjs$Q-@;^{FzywxYSx~!+yZRiRrZ^&_0(%?ZOUT( zzrNO6+0@1Q7VT|xq2ctQ$Zvr=c3k;{lc}>6MgMpA&gZUmj3cbf<>6jV;%`R+ugw~! zsousxr=hfbVh@GDEW9VyVez>YpXc3B%Cd5T#0V0mLfZfCBWBL2_#W2>(t?q(3V~Vb zvsziaxb=CvGL+|Rs>CtJGWKQY)bq7Ipu`#-#|gY|X=M@X>LeF(c1e~PL1I2TM|6qe zJySOKh?Q@%SyzU$p3}UK3V~TTPGD{I$(gLdGx_}MlxGqnNYvmF%W77yUuaXVZ?y5b zF(a!F-FTR$5SWGI1Xf!Zd(Wtx7)b7u-bjof@qo4TSF)!5T$`T0f5HLdL}5P3aV}jU zFbl^CeBPk(R^wjtAj-~XMlpg!Mb=?`RFHe&HjUpmTPGPK16$JYoWB$Tvv8ciXJ7LV zGG^QfrhZNzBu0=hHG~V+dZT9@WcI0piiA=3d>PsM_+VP!V3NcL61bwwtH}Lt8>!Y1IvsOV>Am94L+sUP+6-2J3ScED z|It|`Mv%Z7T+_C)0#uVdJ?X=NMhbyh*!pPNGgi#5)UFS$o;XZm1PQFc+5L3aEMvZ7 zZyHv8g+gGK+Nzx`(bO2(K8)N>Y?T;6Land9{udz!gbty}+o~$7`ndB@eY&GdPLcBM zKq?#;ATfdju3&Rt^in_BGkPFZ|1nS@Fbm%-dmK)SmQz;sqoXIHly{DVI*xL`GenkM z+?RetE>Q@~!tt)ASxbzOg%Vg3^doC9P{*=3{SHRt*?a*=~VU>45F zYFgK&bK;}-5_#>esLZ`0q0SCgl;7jW7WJS})!Y;Uvv6*icL-f~J6y81v#51JJ#T=! zmGLA2&odk?aKy9kT5*^C?l6J`?tA8Pm36f6$hc1=MU7Pm%)%2Gd|oZHX2i9tBAYiI zNqq`BiQX69>MPj45_er+XZOgL>>}C3<{%k$%U{ma*UM=>{U{%woIJ`tZprKicZZdw zva`a}G**}T#7=@E*irC{ZNCqVsUUC1N6SSw2N6b)h+=<3Z}vHyyusYb@o>^-(X;3* zIUx5Cg}|(=7ll>0afmo|_B)4y4XxcvHCMEF{Rnt_AdL{aywY&p`rcvRqlzY zLl{BgZbSAxW1lK#o8y$1Lt8o8J4wED>q_}QI|+^b8dvZhb1apaOi{&I(ONL2~U3LW7joY}9jlFh5J(w^tKefUDz!#ad8f&`XO)}|73 z;^z7+mAgDu0<(ItGXBqHZ}o0Ab^MU((eb-8L`%mvLkS~DsAadryzE9VzoqiywSfwO zSz*FSbjp*zs$AuN-?y-`bsUqjX^9)m2@y*kw_O>zjs2sohf?Rj56=4Jk zH$E{E!}|IWtgX*AL(fZc|Bk1!!}vxDfmyg;n6M-OhK5SWF}kbAG2lVy#h!?Klgkn*gMP){$1zql$-ZrLVZ zjAyq>cvF~#Z5rm?|M7J2ohLhu%cX^(lYAsHyNC-gF;}|D0YLc!miLqY>v?T?SG2UvyWxa;_ieI zB(TO{^@{?rV!)8nf)N1+Rj?mcMq3+toi8oxCVp~B(N-KTA7i4GS{~P6mX-VLSWV|J|)(H zy(qTYYSFTlO33q0+3DcsmV^-`uq?1z=fS>RKqi;n3}f-=w)Kb62N2ljg@z`ifNY_(|VAI;-BHhwElUFk*` zK?2Kyrj1xKApX(w53*5@t_p!!J-Ovf%KBEXVe|A(TyMlj)V(baT?!$LAc19pmFp>w zF>TRZIUuTsLSUBTa3|4>UF;v*9PB&ZtZMYmd0Zym=tUSoLM>NyygC{~3Y?S!_V-i> z%rcrdi3Xcf^cQ~S`*8d<-e@#!hx{=$lrVyX+D2X8ve+0AuuFb;)LkJk3wvt3vu4f_ zW5COo^6j~%O8*LbPS{gpwa^lqjL>Wvy+~=K^x=@`Hs489Vh_TxHvhq`Bjy>e=lzzs zb_FQ}X3gWCe)q8{I*l^#ylA;`#>wtEslvxbgb^eLTAjqO7Abo9gC;TlXOKaybI_5O z%@hK&&h26!(=91_g&`(!=xHS*>(#uwoYbJ8iUiJCzE{6d&8ofqKQ& zR|w3?k=t1WvRhNxCg!hNd8nRVC0hkL{N0x@f`rz@nU%j%^t@wCBKSog5&OL?t*Ys# z5SaDM;w(~&yw#IzCnpyTxh{T%xzgT#-lRm}|K8xb^3>%NeUr^sCa7`|nKOqAUD&A- zn6;gqZW^+-;sl%9&3_4XrHfMyn)1bsFoHz!9nK>3L5hCW_N$gA4U$6#R-@m3DuG$M zmhi9geXCEqZMM#LS}!-gyPuK6Jv%8Q7A)cTrSX~Sl{1VDo1RMH+fMnSkiZhEX=%;E zjLq#H%Y@pU6aurb#^7)8Xgy=0+Yh;9U9eI!Ac5tL-(ard#=*X6vf|ke3V~Tz^RX)M z`X=TiA;`ibUBO^pPW zP)*CRe7e5GCofqXTPg%*VN1liAJxJ|pHanVb(=;?8-;{YLbdJ9uL-S75juZVB`^zH zR889$U0C)X??m~Y`zb9a5?Dg{^gybwT;NiQ3UyQo%)*`lYu4=QFT-<`Cu6ji(gQ$3 zExWs;XUO}JW$1YpPldoN?5}8=*X4RtU~m!Iw^vF$o&?B zdL-~PFzdHB71a5aBXt|0p3T54Jaxf)yv}&jrYVlJ!ex%c2oiX5npaHLR3p861&VCF zRv|D8&jPXIRH`c#>tB{EQTvoLKS-#j0UHi2O}p1sq5~_=DFkNWxpY<@Ug=C9K9!+e z?;k3A&ym2>hpZM_t`L=HPp@wt>WM?l!qbPERxB+)?XxRK9z8QCClrvtGm(4(ban=6 z#}243dgoLK%)%3O?4fW%qrll^so9Hygb^h0Y$xxbFZ@t;{#1!N@d-^NFiSnDH?7w_ zIc;`ndgxx3FoJ|S=Ik>dK^8mWNbBcRRS3*_+tpe0Df&(?-q5Vu_e3Ph$}0;{uFjr> z5hQSo%bLqM_shsOIjE_ZpF&_(?h?+znH}tA*i_}ObvP)S2K<&KTpJKZkid~QKdU7h zWx|nH^77dh3V~T0uRDo$``_tJ+S zKJ0Auh+VC41^fY@MK@iplIpF~an+i8efiJC-*X>LnO@{o*65K~vdCGOu3EuO&HW6? z-&V$NV~4IXd8#V}X5k7ye}kcA;zzSXSDWC%5+g`FUhXVRhpsiv%xi4=vh(n2@g^EnpRLq>SNVA^@_ zgv1CExZ{RBEeg&zTyA%u#ZEUA0<&<{nw5v^Pcp_A>_+Quot79u0@o%rZH2qVc=@0^ z?LBfsC1A%6u3EExd#r=8V>yRihg8x@t=d4q8ef-VDKJ@nPX@$TnT(#CT*L7Xu z(|Qe{YCE?{j39ygKzNtM_DH>a#lh6(eT+h27Oq;e`%uYj`q!$%=~~%I$|-Cl@Jr)0 z;h8nXZPs>!ocD~QL&PZUEdZxN_ zu8C}gT~G#{9!{q6<(heel^RQf(9OAvsHQvf`+gmFHW??(eJIVFgvcl^O zG$%tdr9DRi=l%H3FRhlNLvqoVYJm!YS=e9EwD*@|I^Ke!AS4iNS*wsrKPF7cFmhkR;i#UY#@O%2%0u* zQ5o59si4+{R06Y5-Gk2$wtOH4)bXI}^WBuw14!W9347`toFJ0cc+vH!Y6^i_cw&f8 zA{`6ULvB>3)RLa0L|}$RnbFbOB>s$Bd8Q^cE>K$`Fl(!F66rwI)$u2{SEl5{f-r&v z&P;KiA@+BCky=$~&=GHiz$|rlLjNJI##441uN3a9oNz+|XV|#6^trups9+iDK1nD9 zX5o1}UNLDo!I<%>2wkk_r<~M70%r6auq04gR0r8oS+OdtmH-k%@exb>-wF66#9zu5sUt z@LE~vaA)T<8Ao&BOJK?{^|7Y29&=QmvHmIFPJo+IU@02`wc?o#np| zT-R{~z(lpY#>kSRsr&V-0wYLZuV2%Gdgd~o))-As)?5=9L1IE!DRJOjvYz9h`KvxW zI~PB+_82Po`MyG67CsR^QT6p~{1eYHl(W_rYQtwsplpxSI=)v-`Sjs_WYw`1c{pq97Nwr$@;r+^BTi?`T_`ZZMy2lcLeavUx-4YObvUBS;ihPC;CbT5c>X zFqnQrI zRV&Rwgw9IVJr(RO6A z{v+CUAD3?%vHe1+%I$E05hSoy;?>tX^{C9rqO`q371^Y#lZbbCs(<-)T}M5k@;>a2 z5cX7W^T)h~<&hsX&ErT5)2c{}Ac5LKJb%R=RRz7vQSt~^g}|(jyx;3JUnAIdjr)To z?HgH+nh$Z67(oKHg*0u$3op7nvod`!R06XEdtH|K@2TEbyTSJn*1(-E^6Jv`+pZEL zNT@nRN19io^iX%&{zxS-Yeoqtk$i}2QQLjgcHAOwXX{U$4m-%eS&qUtB3Xa%<+`Gi zTA{V0sJr$M={~gQ=NXBzbfrfDWc5&H1u;7i4i1FtxMBle-)wI1MAb40F}V38y_6Sb&bD4 z+chkki_p4V^(m-k6^RifP~VI1V`L$2HXG6Vn=T50S@g(JbSasvPvP%I)1t!j)AfKR z)V-&R#0V0qMv8N4cJd2tK_2xhD+FeBIp!$tQnKFihj|VA$C;@9w${|Xb0vupBv6xu z-Rm}fkdF&=q9w`Y6#}!u=Q@fn!;vf|dIm$_lAc4v~{63~#mLr>g}|(|*^VO1h-BT_c8x)mF3ZHGAyg%`w8RJ!s4k~zSsX9PpEE+JSCUF#7Jg~G zmRjSYJdzMX#rBj|zCk2V^Nu|&?#9VZGy2flASZ>uEc_ldEqj3od12U4n*6)4#BUA1 z!Lg+r#YtE*D0Uo8 z*7rU(uQ6msGg;}&a5^OlNQ@wXnunSe9#lkjj~hvL8*?cHX61ZZO621na?nll8r9D~ z6N?Irrd>C)DQbwQbEp!&RhNq;MaNLu*-R26NT@S+zZNYN;T6YFK$J>gmO5g2J%5f^ z&0_=KTA3t9kieNj-Z_wvU39-QhK^nQBapx>94+zM_Jpp~)#<66{-L5A5$q=B|2d|o z9$uj*Hgpq51{}9Jq+KfJDw1;^wza6NtU5fHO8?4Y_2{=q5ByP0Y?>ag*IO8)ceQsD zv!BQ7%Ld2jnToiIQuh1x!J+2UEqtjZHS)`2b>9}K5STSIt(wR@F>w* zMf%Y>-s_y$%28qjiKk5OntVvNXPQ?UK891{S+R0^QVE5?tVaFZ#FqBQ^hb?NC$sZU z22iHl%jK|_#U)0Na2KwkO!y)F(mV4SIXVrYvZ)j0s>6j90<%K;yNOmV$MjBv%xjby zJ(S8lijX6U6_S|c+t^j?{d!Pe|LD4|5+xHy(1pc*vdX;N5+g`7YT+t6o;j#DyKDZc z=^01SjLn7QzQI`)0<%H}xrw5qkLugMn!hS%g|XDG&~v^2$#-+ zqp3j21hM_CCh?be@iks_JE+&cz;~|vsz(T7 zbDBb6)+WBj<^f0bW`E2(&+>E(<#4GZ{`~$dFoFa=5$*vL8$xt&k&#eqqF7qjO_bYZ z=naa-=5%Ae(H6BPjmu5tF$u*bYuT@U46PgPL3fTu`|Bp+j9aVNCYz-c=CXr zk!e0L;xmSJG=35vb1Fe0Fsow^H}QS2Ro}SDe1o}0jizBgav6s!9T6BoVtOlAaev4G zee@>t8c(*2B*($R$oyrqLSR->8#f^wt@^1u<~8p0kDxo-+89@Y*9eRtflr!y8J@#w ze#1zkQr`s%fmykmx{1|K4Lv5^yheNHq2xPnw$Z!NG=UK$@XfNbb>?uo*La_isc?IN zZ>@l*tC+B6zrL4ebksNauy;RNekR_?Te^wB2oi^DyNa4C_UprKvpAE#^rpINFB-#- z)Kmz}+ELm~w9jMc_j;J6t(+4(q}qSuh2in%l{G;0<*C7 z;oZ1TU1(KkYneISoqi4V5ifJ}&~GkTrMHOm5l>RO>&K_A(w{vPqHjo)UM<>ugKH0y z7_cx}KeauQ63coCz2pM@{oxqho4myMyz^~-Ja>2NV%y^JdXYosv$}aGgIF`GroJsH zk}!hAfpNN!L&w|b|386QN3Tn!d z|7x**Yg>%&_r+7x%DzY+y4U7FVihsZA?T-AiboXds$G-|ANQ|PIVz}3ifA3>%+(?l> z%QL-ySfoN=*3R_W;>53&|DJBCa8H?df2nv^aFp_^GS~AI_+p%X&358&Z2NC|hr~g)l8ASR^qssl`77A*@6OLp4ic?O z-q3%|k0gvBp^XA}x$Q!kRKZ>r{yvZ}f`mw_DUM#=p~u_yUs>$d%G(7h$&TOpD+Fe#bz;LR8o3sl zEVFp>9xrHFu+6yUSWBEPv{TQ(-k=&E^!g&_myVQk_O>C6Ac3s}`xUKtCdXClB}=yK zs1TTizmUD1hMbXWt~Qs$I`<@uAc1v0k3UZClLz|y$bLPW zD0hzcgsnEO(GSc|g-Xwt!+Qk~MvxfTv6jdXwDVux{^@uT+LX9TN`I*kn1#I$Zk>}I z>3HHs**U_UFoFd3iMW5|TZQKL+AgOTuSgg{qVC*UV*7-h`X3 z6aurd#gP%)(JPugVPTNR$6Okq&_alu;@Y#d6mYZGP?f=Vt!E(vfCmPLa3AHc<%7 z!qGjqwHtd2uyz}2R-spX4&XkSv zbU-t?wUZQM;-hTDg5Fa6I1y#bs@YH%=h9~WBizpRpjyjj%9#)L%6e6N#gRH)^|57E z>PVlbDo%csbA%AydMh3`hwP8!W< zp%x{_xMn7dAmMStN0h(WO<(=lyvFYwZOA%kk{q+{vqS>3)OVg^&MSGmbaB~dN*Br& zBg7-GC|i4Xs+ACPvPRk3*P-W0%x>OO&)VATUmZJ zggx)z{v^ik>ZwQZI02s>VG6ausG&2sxOcY^R9xJjSiCz5cyr_)tWo+l^Jm zYDhGxO``VYp1QWf{8eSXRg-xN_7WbaMkxel;ZtY5rK=rf#DN*2M&k(OeISv&6Nv^# zdj6Z`oON=H?0hxG)_cYOg<1G+G;R2sHgfps^*eKgt^E`6r1l_X z#DWCACsspr*(>*l+ePudLe(es3?!IZYD;MP`|-acYexr z4}ba9IanbutEIP>SUqUzzy9u}vxO;PM?3i{pdMia3H;J{9xk6FxilOuyRyFw5}36s z!b>=AT>7t{c;vsDRJZvARxqzj7(oJSS1!9bEmU{TT>0)*DTTnSKij=Ty=zPV)$L(^ zjp)tbg|co&b~1wq5?EJin&)&@C-7J+?RR{UNMP2E+g{>I>e7F0?c~RuNUyb4PP}cE z7(oKtD_)6v-j%8q-YK)SXO}McUzmlx4_-yy-isdJ-y!!E7^L(|kWhOWLs@02{k6k# zePA<%z%1<5u#|ytrWKg5Lrw^H zwv~1yFbl^%>_pS=u{^WfUmoSsju9lVyzxq0gRk;o8TPH=(vAdX;pl~Z+#L(hqTopR zl1n>AkiZhk>mTomlPEUZR@#xkEF6olW~NUyy3%B+t+ZnV2`q1{U{e|$--RPk-#kM!?WUIXfPcaY1m3TMvzd; zZr02lsL;N1w$hFSW?>(mR{^ecrK}-WR!BU1;B|`?6DH6NSJm?Dcb> zp=2u>Tq`?`d6`$v{9qA}=l9TG@!CzBj}|d_RuA2uS6tQJQrW}dbTWFCto)*)TVp|t0|-C>wlH?*puGkOx|AlN?r%Vw!Pp4Z*jYRuYYTIEgP4V zqyLPia;K+QFoJ~IMg@+{D?=j2(5fbHypg~xY~gsfVbXN@vhpxG7J6UT&UlMkxq8`V zez6CDzgE*~yp5Kn8xNy${z=MxAb~v&b_dSfM>V5p2pO1D_ zYEF4aY!w(mVtg};I9nuC|7d$wiGGEt_wgq5D9>Jnz$|=*JU)+irKP{T$Wrs3Sk6y0 zd)E-#3LlQV@JVy~aj-VMeC$Ral3ojpAb}%2cDp&~N_R4PQ>LW53V~U8f81NL)}Sw$ z-D%yNWaU?#+h!4kKlZe(1LO7hWLRqpUBBo;DY-ujj399}!6L-uo_aX1_G;Rj=5?uv zaG=8TGfE^dORYsMDeSuV+nzR@$|^B}gh#SP6n)j>-)gvaqd6VEl#2#E%&icZg*7<0 zoQJ}w=$(DCmVG&;rpDU&K_OjuOzf_&w(T{@e=n4xXP=R=nVcm?kihu|ZU=orD0`kO z^3Wkig}|)u1$D7+W_R0e2>u3Z^dyHHH{{g)r6fj>aL=oYDo4Bj+nsP-bf*v9A4u;N zB_&3XP-j1!+IFN2NvU#M$07=WS=hp9+NXxW6yu$N280)s7(oK(ocL_Uw^nrZYF5fH zIG;jb7QR_cYo4V8osRrr+}m74MvwCqv$y=Vn7bn%4)GN^p8m3!yBHg;4iH1`{<4_v zu6)KMLmTS%CbPA5)j|>@NX(fPAnY^$vi$XZeOjm!ZGZL2$e5>?Lj2qsAj+=&Z86>K z@!Guabz&FFI^mTunRjMl1c@R$0z`$=zb);Cn!jrLWp-9sd&|hoyFZb@tYb@kMenMb zZC5C3o~`Od1zb)U&3We;Mv(A36(AxjX*Ne!P1E!CrPS4XjqV3aD+FduSmrA})YAU# zx%=tbm+XG;G3uNwEir<`p3?#1g1h$5_qE2rzT`f8xA7ufB`~YXa$m9BTl=?nu-CM{ zbUW8>!!J`Ai4i37Ck6;ti>9ZtGcBJCiw>tx>tc-`rOGJ;W-Z?2D;)FL{o4Z>Q)&>s zx;xuwd%wKI2ofGQ1H`NxcK_T2=Uf^}p8Z1%w}F)u0<#|N_7y9a+Wp(h+3(jd^4r+V znCDqpVg!jr4+F&A`F8(YTwBNSxz~a&M$@4#3V~S<_WFv^@9qBWNp<#(pd-~v8F>?3 zBu0=}{Ww6heP#F0jrPKo2x`AKk1@Sg6@|d8uY8TgpY8tbtu62*g04T$Wqhe!MPdYr zTu%bT(;s#=CtTk9@na;7v%4IBN^?~R%=&%ESHzsp@Ncj4wqXDJD;Rl{+?rroZV0KniXj+ z$R}Sgg2bnM{$f58f4yrQJr0WScVn$5)5a(SW+l8Nk?DD=wj0u*~l^#`+Sph?#C_mcJ)PhBZ7RuNZx-(TAfI0<$u1 z_ZK;w(=3T4&1WyJnyOmW(6Mc72h*v{C8sHyU%D^I&egs*Bw`h5hN@x14Or98EkId?5ZnA)4A?5 z^;Udh1PRQlc+gkeT%GaX$(M5ZN7Kw6m4wehSBViM=vjbxye#8CzwH%!M$zvXT-`Q`JXXvUmj=5^j3DtjIY7j2&Zxh#`G&9gIFha}yDHxPsG<;< zRgznr6a6#&+w1(tZY1?^&o19JsvF$=riW&-d6sKh$w@8g*Qe~(d1DJm?6t=gv^|`qe0<$Le z3lN{8(=7>|%r9zs|3D)9Qr1O@*(64gDDCSjrp`&X{M`{BUdD$;Juhd?8v9m{;M4#XOhHS{9!xP;wTs21mY72+T@x4G?#x zf47)=LcHrGu`HFl?Q6Z~`cz;9i3xVTV#)09mcM6smwPx+$J+I*h4$W72+TTPAV7Tn z^vz;={;(f?u42?Ds-d;Bc1>UeiB`{j#E;Z(7W3>gpQ3ZfO^0f=v`&pWt`L}otsT!T zZOcqsO9WfXG(4!ZgGjg?@)5Vbrdft?o5-i)XQj*EuR2;=g>F*_%)&O2_eSljL4|A8 zw7Rjf5tb5s|G8TQh_#+SEEm}yiRS?3I?=h3{??h#^GbY!_@qx%2oNtae7DSEcO{-@ z@W@QH8nw0Noc2q(bG+NiY5pQSJ-yFS2@o6SKC>j)_F0C=k9yqXGDf9kqsgDYoC&XAS{ASxb9#vY z5z_0W<@04$2(BC;o@aSsu{&+9K^|f!of=Db8d=XaqTTUKG-wI)5g_ytA1!NbdX_5}{^De_6icfLv3lO0{^ImVmA1 z+IH(@)u>uWS7SzHcgpS+DCW2PXmMdZli)T+8y_&s~ z9l1@l-uYqa$3Df2(*uOd`R|rteyeql;(@~5A>DGWr0JJ>>~&YF6?NYD(O|4hvIdBP z2Yy>}JY1{$Tn-SK!hc&1)L*N2;s4Yoho*P8IoKzBZcE-fHR}cTmBCRw&LG_8d4?~= zc-G*7S*|``37|~X9jxoulvUafY#FkS4G^~$r(3!wnM9ES5!5e#F8ScFlp|LL3QINq zB@qI z6DS_e%&5Du*DJQ7ysnmSBvoI;u0VCGNQ@wHo}cvhnwj*GwmW~GYa|u@kX3FCQVGmb zTj%c45tQkCHu=ucL+&3OC?db{?7);5y=8+yv2tVvz0R&!9e=Hw75o zfrOiTptzJTqaN4Ee1n@uMbPq+Ib@X{DuG#ePux%3GlG(m^T-CmUw(eerTxqo%Mxv+ z9(yxTq!?+IO+8lXIbQRx{q@;WvaY%7CA4G&eSecfzCEPA4}1roPX&r{ao;T|8%-i9 zX$1YT&ndq>_LHaF>WXR)URmA+uh3uSuPeer-&J!hDs$EWAIi;aG2AP>Jl;(GGg?ekmbxC~SX%yQTrAa*4Ev>XdEOZ%F(Jt)_J8%A=;niA)e zaQ+IvO+Noox+NX{`P-O$GfLwB!mk#8Ex*C@!8E<-M`P8y{>raHLcK<_8||q0imygX zBS0ZA3%`H<&Z~5xe%cEo+S5&`8IZtxVoh0hUwSqnzxBo5jj|)pG}?7Zw@~Y~`q7vG zarpBOOFs5O?w1fC4tD=(*?Zb_Wa~LQfEtHowq9IzSYiZ;1>AmIJCJU1XSa6#Rhyd9 zxwscb?Zxp5fmvTa2Z$bSzbxk~n#8E%!zf^_#b|miK;m2v&Mme05g_J0=Gj3v^9^o! zJ%n-<>|(s1=r1vX1kQf(s-@ikio8D6=;Pc&Auvm=cfEV|r=cfS8gKNv5+g|9EFNpt zGz+DiPYt7G`L+syS@>>vA6eI4)OhJ}WBpTir8PhTXCryPsC_T`kmH2WWrs>&7M5v# zALSyb+pVldj!Hh#B}r1@QreTP`q>OYN^5{w>aWUP zeiR*OGA?e-@c@YtByi-dX}ixwko|(-_^8go3V~Vb)Ae~Wk}~8T7oWF_ukx&rz!?N~ zKdmy7s+~O@|Kf@I&M^z$KWmFb`q8JBMXXn!Oq5u2Vl9C+AG>*6sY^9~<+OG#xLm0d zk-!>*SKQ|{r=6L<86~5aC1JOn${(<8@Z=#HuewOpnSDR9LW_Z-g8f_O)j&(>cVO#`yR|Tmd~G~5SWD}pYMD@ zUn*)0GP3nvs?~jnhW6NmzgcP&1pHCi0Wy;ksYW|$55SWGEil&9^^QQYvJ{VQ+ z|CZ%%2MFJp-z;Z(sD05}CwTUJ%6E$;$-G8CPhXnb_mxpG@}tBE_Fl19%Qf6Zor)f{ zvv!J1RtU`cu`57KZuP^Gsg?Px{BuN5a#Ak&E!%}THhAYWf|iHm65S?7NQ@wXUo-o-#|@#O zc2|##sk}%bFl*AdK#_Pp-4Z#*yvEl9L+Hr~YD+&VY+q6~?Tjrmuy5`MKf{>1N5)9gM9+VJ+2 zQQ}cf!Uz)TD0Tg?`gAUFkJ0XtokCz1K6Oo7;?$VB{#a_{>6M8vf<&Zmpg7j(n`O3b z)?ogYHgvPl3?n-Bt@1uF3ri2rUoB`yoo8NFHn3O^wBbqXA@Y({BQ?axo&>^ z+h9#0Fe~TMKrv+dSIgsvCUGLHGi}S0J-&O#?-CHYy z83}B=cz4N#J187!zM?Lqtof0ERsHJ_()jpJ%eNEiijpq~sv+zA}8#S*t zb$6H(A2#Ho@;;EjuS?UMTX&=I(+TnOTwW^#W?^~b^XJ^_8`d(H;aKFI#0V1j&9g7^ z=hn2Ry0cNNU}mKxVitZkTvOj|LB-oOGn&26tb89xVBMu@R~pu*wtG7p0iOyg1ZLs) z&-0=a18D1{X~yl?g35P}1lGaq=vlye?l#`NDyhti zB7rlWeEKYBciQcCS7a>qTzWqZ6hU@xEnm*8)c<6yD@F`|VaXT0QmIJitkUhp zaETEl)NgS1;6c>lQzp5**&>C&tUcxH3fJW?EKc9dYZNRonC!AW6*uxPk{Ce(zcg0B zbm>oH@1_XvO1l*Tv(!8H+SHf!wAmuQ4>cr4kiaiZ(^f4Hp?r5@#DBYz6ausGscYJf zX+6m0d`{6Lr}{pSz}k*Ikv?>w)hDuxC0XnU{}*O0I~OS8R;5@D7PGYmY3#SuX~5w} zb+Qmfkia^a*SwxKBhh=TW$e#_3V~VwkE^qet76;Y_}B_6w%DE6iJr6f0tK-Zy92>O z#ZFZ0?oO<0U0aOnoO8z3Yj<~o0Z6JCZ_T;f_kR2R=g0N?GG}J?%9rLCRk&xt9rET@q0+AD9A*1>D!Um-;68<>4J?vH-0f4u zXmh*?g+B5T)m&pO8@O+9zTG}zP-KjyKX;SMZTN^`C!#H5rF(>4=F1rGacIpyrzw`pL45Q85&f{Y+S3lfiN`HI6=KU+>Xy9pMyxXbfFagHSK z9twe~#>IR^!3r^!tj-R3S1z@cS8d6TLkBt&T9A0q!dJ}R5MxOgVV+0%qr>H+CmD^T zq}B?7sy3d!qT!oZ%ll&{p`TkN8@xe(lj$D8Eit!DjEp@q*D(;dc@D9!Lqn|C| z&hDqvc7K$7%QwUVy{b$eJ+?6u5x;>%ye}9(udH3g!*P^TW+%y z+7!na-+>B&s+n_r#g!@_E$)xaYt`yNyeu&$#@?t*Px4|<jUJ(E8ZflarVxMR5uiS8OtWj+5Y9*o(V_ge$ z^AT^dCRvgeo5vXbs-Y~tbG-3m^L&98Brs~0`vUwLEv}uKWbA4guADiZE&f`rW_9U@ zwQv7P#$UxBE9ZfPXL3W4dt;*I{b2J~JxU%gI{Xo8thnzk@o%AO2}c!|UYKa*8d~MytmF;G|spj5FpWlM0^3Bkrhd_^gm;I zw%yN%h+P>*8{Qq~Dg>$)`}>H+l@cwrBTQmzu7}pZjU$X4$JR@w_Hy$ zcN(5fyl#E1_cqd&{UXtVM5Wd~qUPavOXue%@p*Efh!I^3En5ac0#z}~eZ&}#c+2yR zCUNBA9c#u?9gP#KTnJTHf_#Mab)4nN(#=+tDA@jy^>B>8aiU``LJJZ_gMCDv1928t zj&0$-WWxrCUeB5tCCe042vn8Z<0D>+IE!C%ld$i8ZSA|LvGFdZD4_+3mEq?g+SHO7e2yqBf;`2i%I;9>LhD6?`*iG{VLId zM5g^dBGx~_vMa4g#6KG&w{~f1yzp`%Bv3Un$ww^Dm|*#^#~iz(Ds+?`S2Q>JR>?tV zL89L|&i|MdZ&|X_B+gVEEmw{AGLkD4Q3zCpWc3vb3dUOswl|4ll{!eRq%?*<^#$WOil{-wlUzx`!^{|x^nTdqzXK33$o0vJl%{Y9!twNv* z<2t#cPECt^>^{M0v2~8XxdF~<@Ok8U`<+6v!{rGEJwLC^GLXRUyry}7C?RVV9%mfd z;UV#Fp$eZz?#X)MmpJD-&d{R$BwCQb?>z5jR4OW8%o$x( z#O{J^jaU1!5n7PIZ!lM_>zH4DvHKZ|Ru)nSRN?c;U$wEZV$N|N<6)K(gcc<58_b#B zd-Ka1RXmN+M=C1>s_=Q_eVmSQ;>PA$#?{9)2rWq9H<)|H*GmxdW6B#8DHH-#_&jo) zev>hxL;p%f*gC7?9YjL?I)84OPBd9o-k25Yr4Xn>-y-J~W%@3+cIa+At{kVt>0|Di z8WF#=S(Myyyq7Uc=9g$eLXC(o+$mCSoYviN&DupJAZ~tVW?ymoTC(M13-jxoe&;=z zK7TLc^2*T?E%IgCeos+M{;2 z<--!4jqJa6Nwgp_FUm)}3s17NcxVzIN4=EMNiB`BF&v!$e+yMxs<8LtOOj>ZFq3d; zbwj2p)!GQ)oociovFN9d_)s*-@^q+4e4p@4&cEto%%fO^K-IwpzG9nClBHK>leoI` zstjxEYrL%VQ=$cldYm!xX>_6`#?>U!J$Wn#rg$0&`&RM{Myh(i|(K5U7gdydt-836?a@`EL52 zf6HahD;gJ{mLRksvB&Bw7X1}(N!!{yM$5tXW%?(DjWgaJ3W2JVVZI`%d%R`;2Xnrg zxbT8(J-m=npQ;mDkWf9sZbRQB^%-IlM8BsmH_@Kp#@UESp?vY(H&M7J=HQ7Fq<`HH?c77uJjXh8z~mt0l; z!D%^V=zYhQ>unSQReKlvio1HW#jC7&jL;|BW0dGOL>8ZR!jbNNUqTBK=pE*rpE|AN!h}tZWg&wV0#(bp z`--TWA1wZy)52@#R(WLQ8fzTshYcgNAc0kZH5B;)YKddioT^+Nd#wi4c!*U18uXD-{2VgxIJwYFDDXL>NFC=etfcowlJ@i&xXv@^Hohp^9yYi0#)eo z7Anc4I;d67x8-=k?lH%W=+?;(AMiT*PLT2moVb(HrF`d3Y`RJd&tdF*+~==jbt{9GkM3lily zDm1fOtieIX1;ebch64~$D}dnR&hcL5ih z_rA%N(oUbuQcriyfR9n1&LF0 zd`0;j-z+!#m_(j4`N(>zy3z2|ZG}M9rKY~3!19ORkP4VSQGRd_H*@b^e&95U5hKGcP5Uq_P97Mo79r5-mum8KAQ+l%nfL$T*mz zxsAs306rI>4rzgE*0#$~0K zd;E>)x@DAKg#^x=Ie*YEE6wQL(kQezP$5u-SDn{UN7IpKw7*fTO_*|Zk-(WV$8!4c zY>zXGdzMr0AgXZm@H*;R8cNF0%s9=p=+J@$&VxC=y?bWLo!86QKH{Q6pbDP?_M~Ri zxW8coBaCZDp#=$?Idc}>nvAqa)G_V^L@NZU@Y&?=;I$ue=7GA#(wQmBQ;P)7gEh@J zB|TkyR?%3sBD3;lKo!1~_>1%Sn{2zo!>E?cO?mqufiq{WEfSiJ1{Wx5SVP?v0#*2S z<(W*mWZ9y2QN#AAsPYy?0%y(~v6U|^T}z+Ch>9z#5U9eh1m^;TC&=ML-Hf)iD=S|E zByi@;Z)!uMiH9|#$ z5U9ehHh1nl6(iSC1^;;$RBZPT-k zbQRhuIn_wu%vsZ#-99P(HtlybYSv95P=$N9T+yM>R#~^x9>>840fZJLaOTWwwI<7C ze6{6{XGaGp1gdZcljm@jV0r800!QU1LkKNM;LKUmvL`f?7up3m+FC{`1gg}X(X5Sg z%0KslO^mf3xbZrxWY z1gg+W!QPMkn`PY*fkwaVe@L_-f%_s{ZF=qj`J#GPBUj>Cg+LX0DKxFSSGasJva8WP z|1F6YByeAZcN8n_lf&P&Hop19C z^g%g9hZdh4j!yv!fhw%L!FygUSIK?;WNk5jB>8g{k9SFLEtS`XTVFo%6^#qLv&7E} zw|;%dUYzWamRVdCgL4|}hh@1^o2-*|gb-Sg_>sGjIN0@_WpOu?*!=3e%y6rO-t=v- zLZGT?hDM@K$4E=AfhN)F`$M_FJDs>asUM*Qi8bs4s63Q^q0`TBtbU|?)~ky3e91tC zKvjpTjYOx-k(SzI9^+lNH1ug^eNl03H$n>%>H0Pj`Sf>|1ZP*PI(f3v>-Le>Z)H0u z1gd6rY$Ps!jI`9tY96DeZvko;x5hgEXLCXe5?GmpcbDu1sKLR?;%2|*gsSZWIiu#} zJB!b^jY=&OUeUiOM%Pw)`1Ay9=8 z&Ak3tT9q!lj}{mItfxdSBhiiXalA6Wx5O_pk5QnMg&N$*Dr$_Wq7bOU$ZYl+EFfx{ zX^m)kvb++3jfA+`NR+Di-txMhd5k&_o6?X+J%m25kV2peBg}a>d{T2NmLWpS?c%OP zk|SY#+DJG!+HgT0^B9N!YESJ)Eff1ATonRU827GegWNh(r^st!x;29m5s$>NG=9Qk z=zB}wjb={6v~@k{Qil6tcyPRu1%WEeh~T&Ag&y)^&wvy4pN%7o_{1j|qcnN7U0|U+ zdjEiJ%F9uN79{X#=Gs)PH^>dc*V(JyAFdFn!pJ(_ySw?9ygP8ZeaP3rN(3De_%w4Z zixn58f7OF_F^M~}K_n@vFhY=HCT_fz#sG`GYf_*R35Wzf&6-xlGfvj%H`D$hs+U5b z3gZ^J7Hidvl=H`Z+l9!^ieD57e44o?d7*6dW=$=7ofhpC0#)cE<&49d1?YpvTie~K z%?T|?;M1&WpLP_avC(VnW!#%71gg+S$}@eR67=#_gxz``tHd4f-9MWR~8A(YUVC656jW4T&_lXnNcB7 zg+5Zg=b5U~q4AlG4yArev><`i3wV8gs{(b{mDeazCPpDpg+5YEbIV(uF7(J{RDJqV zq6G=e=jNyv?hZU8O)=wV!Zn3J75Ydut+r=PdYqwq6G;xH{9l0g`(oi8YvNf zDg>&~N6NdeLu*q{pOQwU#TzABkihyJysy@{8s%(U+2~SfhC-kUeWZLI$LrFT$K{M> z^@mEdAb}M`G;PkGo^&Crhmm1keT6_3R{rBXmYqa-qDmWcdK6b`0wRIc%-9>1H-r45 zkFjmM@=tEY&LwYkvu0lEcUL!aGj0_06T>_9b^e>jZu+s*tbUBBaj~bYcD1qi+M>TR zM-lTCF%wbKsK_|#P-?2sP6o)$@r{N1nKDiS=}vz&7U}EuPt9ulW9>LPdVa1=zxrQ7 zH}fF-v~41|H&H3`-;?N{fB%yQ`J7vv+)RFJ&u$!)wK=Eq-pu#9H|JEQ{u13(r5?li zZ=M018%gy$f3~-^&yi?BBK4e{$L4j^_OY~m`$>CEK64~cm3mI8gfX=jEsc9%ADI** zb)FSf9r|AH!n2~(`HpU8fKFP|SX9i_-}!H@L;to9jeGjU{$}kfi54XA{5YOr@F-dq zX%pso;1$Jtpk7_?i$iJYy-1P&>DGVG!+G72z&uZ0M|lpRJU8Epo1+gY1gbD=lOxIh zxr0{o4&q(I`>)Y2M z@Xnew8vD~Ps%=l)a_8S)E%2qr`gqZ62@E5dJMxbxvr^&q}XS z|IGBSPi#-KVmDf2s$?UyAQ3dAv1s|CU+UVR-+W)n{49@1yRf7}psHZK#$v~oeyOXX z)aTr8KIixxq~1a2GlA#C-;aOpx!t_yXh8zU0%v+>7($ITE;H)wFSq8qm-)E5(~_ zWfTHc>PY+(^PKYE?o7DwXe-^@JZO1gcWUg3~{vX>%8sro7`P2|Gt%qXh}| zTGiumRrB@=vG;%D%K5iYg&rN=eO>!q=AJa#em$ZGwK~FIPM3bV=?hEsUpfDcW14&9 zp2$L5OLP{SyLTk~TdB0ulZL;R;{eEo@-@9;H3_sJu_(;Exy@XqpRKk`%l^1EW&>!aRtBrewf=YIU-7cDa9 zn!NP0x-ExgpfXBOU_uL?hx)5Z^t~oKE?8lOtLr=l5_sJ> zd->~6IqY|J>%RZpK_`JK9QnLI*x7~NE$wUD!p|UDkih%TyGv(_k;whaW*?xzl>jU$JRG&{J%a+ z=XwdB4|N^&;LKFckiKm*#}!(TNWId|r;D%E#WwOmP#xznkU-VT@P9_Txo+cnGP#~v z=aiVD_kTZ`Qmdou|5iu;ccr)E??z(bw;<>LbDr?{&Em_I6g^{&$%Ga&=lov+kInly zpW2FQl}71jcBllZrnLO$SDDA=Sc95(#AYTgZ=6JEK|(!`mgC!ry+hhnFpq%*s#1Tg zv-&$ni(K0$-|Lk`e9xiEXvcjV9LHS$s>4$0vx}?4R2=p18_xL#Kmz^Ayzkt4xD*j~ z>&l&D6#`YM=al+pNXa6l%rH}m=&{}!s$dH^R^ zUzIeslszZE6Y-6V?^+x&{L~spWbyecZ2$jmM*`oKn%1=UG+DDwoNkU?{9CBPd&6_M z>}}}6kJ@@0W+v#$OCG-Eru5&aXp%reIg&K&gT8@lizH~iqRzq(dPripRm5^-nnNG; z=FTer*>*=-vlUDfow84&{9NndqVIeC0oQui!;uvOGqFE_`wh4h=UC3{k@|}(=JT&}V}UH4v;LqRwD5}oBfNbhST>w~xt zQVY%=$z3K{_j7h#ST-$1&Un|2_ScO6H;+X(J2l;X=OYTIB`gG3Qte?q8?3j?KcPy~gI-9e}tqT+N)y{14wh!`A zeC=;CG=CYY!||=H+a>8a^KZ5mJF^=MUUoO-KZHpV*92qdfU>Qt+_c*_^6E2S2**8tE~>9CIt$~d^fhpPBMBfh4`$i;dQ)TmiA^*6(^Y zTex*3*D&3FEk*zAtYO;pd>g92rk?D&KMQGG`|r}}M7=fF{_DcE2FKk?&?ol|w+`bv zkS$w&)uWwtAZuqIM>{8Gb#$;v*>83u(KfGUtD835I%ioUu{76jJ@V8>>t608uqWp) z{iw5(z~mcTeQ!WkNA5EX<@n!?#09@NJ?PAO>%iiEVoJ;>eP+md>(3~zZTLH0Cuep1 zT%IFnOu5(gF>O}JYFsmKUQoPVn``Ew3cX+K7j+p;ty^VwqS9j+1rm5X-X*It zhK9b+;h4Ox=fBm(oCK=SU&ir?e~zWd=Q$kpgB!|nhj^DY#}7SA&W+Ym_xY|F$+}xl z^%rWIEn+PD$lM&AMm3bETK=e!c-SdfpVIRGiQp4sX=)`m$A)PQCH{6Knsd$mNnr_k zAa@wx`PG@R*m}AVN=0$ zwhx^)TNAoB66dd_v6U%iMv~tdF^+Ctb#XkKU006!-%LS1NyEt-W}*v{Z-d+^tFbSx@3RcesLB z#Z}Vc!$0XK3YhDtH3f|OFiRI6 zME=cg*}t4}NVFiKdTV=a=u0kF!|j)MKT-%(;WgwP_pE*BT&2hMmwDbvv><`rVfMYQ z?@7^V?%OB#i&qF#;gvSCGpkXvx=U@lX4E6R&nvjEOx=MW^|#ztM!i=1Gu5Qa^ZSar z!F32NNVMd>GM|gb>Z6=}W%L(vNr*fv#EosdagWEIR9@{K(xda#a7RTPtj_R^)C#orq$M>iu~XUuQY2cCP`|bDbsAHK=R0Jj-I)jpRH?tJ!M3K|=iRAI%5d3q! z9wQmK<50?~6n#E-9JhFOl(aYGdH-(Ga>G}&4f&;KY`RsMh2_4;Gct>2OLF!T zp5Hl;$`86L?{Fs?oVTTR@UV4Yl{$xe%KblTaTe&geYGW8kT`t7*%#S%*LjSo0sX1s ziqoD<#KwU3GIEdM{h6W5QX^ls(kqH6!`W8$eK`>q6XS37pNy&zV{X9@1?aJpS{hR+W*7mGH2WW&3$rlSF74t zGCMMHSF6*W|gqt-4Z5oMvr$bjOTFW z4y3U)+-|-_b4(vi!Mz??O9jo5Xh8z+Kj%$Y$IwrYjbg#ti3))#yqlU<^x_CAn%7NU zi=Qjef&{LqIC9|Za4OWcp3FLKhC-kU??2D_xVuV@qZdTz3w0!>c2}{j;46y9X0IA| za5)(}S$~{LyT^r0uKaTz$l+BTNS1JUmaGl6k zw?QWwR6)oNOEqQ9iQg!72GBOF1J(DODo^<)OSB+?Ur|k){i7=t%@HQu`n^#IR4wB! z7*i(j8ZOS9GyFZF3sv^nB75GwEzyDme&;o<;OCyyz2|z_Zud!rK-B^6E3@bLFa4^s zugtLRJ!rb8P0m}rQ=$b4{I2loE?pq4Tysb+Y_dWjP}P;Y2~Ky>Y)73v^%iaIOJQwo zGTW74i54W(uR(^sL+J3y4RT*SKZQV5YELYVlQiEY@8|WQ4WGY=+q+&Vb2z*=_+8Po zmz@J>Z-=_FaMTm!i-QDSb?zGav@aDKQ$^-#cUd7&g;<^{eJO;l1_Es77>VUI{{L2ZU&%`GdW~@NYw-8lSkdyL51mUat`Mk- zd+a0fZHUuJq?@rK^0F^_va^EOv{PKu$;*?w2~;MuAc0q1 z)0Q7?FFO^lLQCG%R0vcBa9y<-ZgKiJXI-^Rc}K}IF4bub=Nq5}3B2mOU&|e{`q|1* z+P*avLQ!!o?=L&!^cZI??}e>-4jNsK)*h%#8d#9PtIoY38eNp-HWsJ+Jt`>#s$KCOfq6LWp?6dY<_*JhKWRBg*J*v>Vi1gH|dwN0wRY4rro6S~S8}03KJE&Es%~6o;!LMRT~s%JRpPK5l&N_}no+A1p#=%m z-@bNV8oKw)h2AgnPzY2V;EF&wd&cWOoE3ov7kyw|!`0rWx6V%Zj=Ip%N0b;AufI9X z{&wYk^`=UYc=D_hmG;d>saD@QiCnV{EmF{?)C2iD1>?;27G@0<#ODtr_1PMp^sx%0UXd6aS`v>;KDYg3IL zlc+a#&VAknU6!sNJSj0MheDtVpA}78`s%U#l(8QDUhhI^L1G(M%<}Y2(rwO)Sy8XP z$@QF7)hZ>sLZC{023P$`PmiK1QrPs&gcc+!as`og^^*0Lzs-Ao{&;SB>0X??$7NIq zRNdv;B4zx)>hGPkMOx%8Oz%&Ypru(8C0dX;#+5?0<@l!82sH0UzR4A7{t0)Q=JQq| zP!)U7SLEvOT_5P|!k1@a4WfeXbgRo%i54V|hx>~B2~2PgSoZ1fBg(WXD_#6-R|r%E zai`dlfj{)z7fs@AMn4*GHVd8Fyf#%T<-L;LmA652rXl+X7gXkavt9m zKO7SHMrF_TgXZ))?xvjQ{z4&8g>!h0XYgoAtwuhT&lg-*yn{&KJD>NX=C!BXgCEOy z+d+ju70%)L8GQT6y6@R!I-k_l>K@rpc%4erOW3zsQ)`mzF88-uQ|pE6d)}G%Be}^B z>*@ZJsIJ>%QIacgZwXJ-(+$~beae-~$8AZ}4|C=6tz4ga-i1VcjI$>B@qpVh%b)(OV(zpck(aBOM`caY^DQyYV<^`>-*j*+wcYdIy5~*;Rd=gM+f-li)g-od`D~p~K9r*CSCP1LjMq)wMcyAdUcCJyl-gc$ zmuNu(uc4;ZI`T_g$~umMANwf;ssgyWal?m+dUt1amB2NZ-TjmFYM$nqzgsX(K725oF69#vElA+K;W{i_rNGfLnED0{ zPzY3Y=cH+Bj|eQ zY>5^maJ+F3=_Wm;<>w%}T5Y33pz5!qJg&Yb>XV#xwp(#!?t?LdsM;TkC0dZc@y0bw z4{Vk_MhDXClx+%uswrH_v*;!sSI$bFUM&yH)pPrhE9cXr1qpQ|?(cA0el6XZZhzdR z5U8rcH9@zGO4e^V>xzy|5jFYMx$Enwc5&v zSUUO|?N0-mgh{j@ae`}w9lP^YpX96+cFos?4tX}F>;=LV0#&EDg4y~pU-g^L3TF9} zOVZQ+R&sm|mS=dy`y=f){qQC3P2S#D7@ptt#M@h~8@amJv5epK_Ri{JZ^JWC<1C#h zCjT#iF+Qm^w)Cm=|M5P>yM9m5S2!!zABpQEgWGqeJI|990#&$9;91|m@v_A9E>vsA zM~N0Bx^X@IDZH9k;;g5i!DoZqxU@CdFQ+I3s&Jj4X{D?0lZT>PQx?t{MGF#BxnggV zVo7=pXN}*C`>x8z-F#_`>raJ16|NIFmNV>`jNlme!Np@GT98=Db%alTNzyY7H{b1L z@BEN!{;Er%eNz+yRk%*znojF8QeWRXyh@FhXhC8tS1P>lIazl&D;3tAnwMVZ@}TXp z9~A;sxK7|VL%O2mw$g((CESu|K|*rfLGP{K^d8Q-gCkc|qSo6>P`8R_6#`YbPSCUs zduq|IC&g%2%RePrkigw#t~(g*O;<s zRXe*!q6G={eN{D~6V2VP(agP7WHa9HANlyFb65Yz9_~`O^_MeNQN6m&?scJjYm#JM zo3BI*5)YM##yNM}(UemfRsB9pAy9>PmNOKz&U86%v^;rss&dbfP}foEm$#wg8NSNz zlUFMQs&Ku_oyKeX(~Ds-a?H>@%1RgsT(@!eh|4}y-Dn2Pa z&9gsN*5^o|M~|}y`c$Kqnj764^hqI5h5iT5T?#8t>$tb`cs&iF1qt*4YT6}PknSzd zM;G$DC~e%n$|gcI&u#vK;u^yQ3zC_PnP$i<|oPq z9r959L**6UD-x=Au+fWqa{1)^G@)uWg-}%BTjuq7o)^}vZ{J&MT~#v_Fuoac54g|I z=3ZjYn!)06YQMXGvl5WNNNMiJQsAKoTDZ>oXzCRvViR+`2GeWq2Y1}^L4U*j;F7qy zRBN|LeGXTbs>?NCW;~116P)orE!%96*%z)8EAI^_v>*}B(b3;7zSn1NHzPS#&Rirn z9(gNK+O8esmt5QCvQ}TvoU>QXx=@y~$eai;t*xIa>cV-rUBnKPt6p#=#XpoWu_kvGq`ltmI%0#y^|`ih%XKk5~ny&AQ@`pM(5QU)3$2`xzA z2<5s_Da~Zo2|@Cpr%Iq|4$u1D-TI&hIIH7#_0J^}GLMwSK8_-^Afb-kWwFtsP`VBB z%k5zbfvQb~eMPTypLB9&j7UeQ*jeeYJl-^f(1L`TW0KRBT^y}+Mb=u)^$p-}p(@vV zAJM$cC;gnWTfw9)X{dk9QCsc3-IOdLvkKJ9&5^oUMQ$cnd+YisQulOLdn==7CBHPQ ztlKWPC$u23i!(4Trv0dojV{RWFoA+y9 z79)qW+V`yVQ;z|e@R%X5X+3@vpwZzla80KO&C{O}dmeWLYt z+{Kx9Oe!bIzrOg%C3m_IT9Cju26ro{6eVpH2FuPlx+w&zKHTsX4~~7-b!SKDL!MXU zxN3c+|EfNO79{YE!S%=vIwTdCDK~#o2~-7a^A&&8`K+&Zc7$G1X|r6FZ;A}{9!O|G z0^b;#X0%!+hc#U;UmYBv5U9$-Yqg-$pY*TJ-W*qagXPNy3uN+ru9X57B=C*F{`Ll~ z18j7)zC+d_~ph7=4fPEn5HYud-yWdGfE_?FcRScX2Feyg2wMcjeqDr{`|35UASD z6+Z8_h|wvld97;Cx+a@0SufvS=tgKk0>=XPX?T26ZgT9Gvl^-dsx~d=-9CG?-rxBa zy;X9nJT+>MJbyEQ(1HYx1?~ZwdxeZ&XUOJ(y%hpge+T%Anj%`S;q2-Cebf*+bju0( z*Y&=H79?;iXxfrQf4OY&RXKEOphBSPGIy|le(kgV(%HfO@TGjRX~qlk;@$p)79`Yh z6*(_KI2J#Y!;S_i1gaWl@)b>nf7ahOH19{;?JyCS<$?S@yC0zi3H2M5`(_T2xH?kC zzUZS6sKS{V_gMD|6X$m3q0g6FDf26wIpIu=XJmoQPzY03W2J+#dyt7kw@YL^UUXFYA;tmbE9%!niE=(@Me#2pSQ7k z+2baW;qq`fKQ<%jk*yU1RTo?MiW3`S^l~FjqV$bb^7z+GG_hJULJJZN`f>K@m@j&( zJtnatc)Q#^>-^&xGGIRFx>pxiUH8^*ImBuk$j;6fvsk4>`uOhq7Y9ag0wI*A}UjB<|KqOTxR0 z@koFT)mAwM(~zF0>>LawJAg8l;F3r z+@)>`fhv6Sah=p^ZWtLZAxY;QZ9SJS~?m zyD#URZKJ%Yk-!nkb!$)Gkb{EHN=vbJ3V|y85^=5j8qu=phcj|Z$L7j63JDycn)YKz ziu62wKwdei5~#v2D#tTKb1YHOeKH3}BB2Ed9HG3cUm_Q6D7;SQ>8=u}!kGbALRedj zG7nzK3m2}S46_L&)Ulh?ybN`HFipP8=&2B>!ubk&=<|)E2H~!bhzKb$D;jf#)u?;d zCSz$@njiKI9Xcv8^hjVfu%=y(8BGtHZ?^}GRdX{?g;^I|HR9Ds+E8PyeZ9wGi54U< z*ILu|FBncC>rdDwci5^BsKQ(zUJ3h!(DI%4ZPuwrl$;+V)NH`ZcLvh!~9-xdxr9AAPM> zM)q7=NFh+AX6hY%?nM>z<&n>8mnO6zp{_Z@T5>^T;(fBUQc8T!aL7CbS@d z9t7^SHS>#f)e4Ke(|aofs+w>;{Wl#W_1w;S`hBdCvS-06w(eXVA1z3zE8#pFFUTY5 zpV+M1f)xT)Sciw#QRxa$@up4b1$VW=9q`l+SNfyI+pM^2&AG2jiqo>fK9v5wo3clb zL~5@sy>lxwo}u~0Qq=MYQK{_J6#`Yb!_Vu%V;=ORe0}QJIj=+u5>wcJ-NF02zNNK! z4DDzQDp9j0MOQ7T5U5J6DXVAgVG?5_Z&<_g2h&aKCGJ}Azddt|vcX+zO`El;pQycM z2tCbrOriw|jJV-T%rXDjJV-l{ViSP zeUCs|H|L5%pbB@bIS%>BM7i~3AbD&yBwCQbh#UUaHVl_<$9JWCKW-`ns&LnuXBqPk z$d`4x(*7rBC0dZch#QXVZ*xOts?eHN6~C(xsKQ-qjyxOtQocxON!#vUkZ3^y_a-&% zMP`jk)oVZz`dx)U74BMd7w{gL>2v`vdeZHpL<_}yVhK_u1PgY+qg2_Eyf2u6W++I!AnK$ z?&>!RRrr16z3qs2d2oA-7+k8S@*PA1{jmIMw`HQpcfUp0z77h3D*Vp#oVt!1l{{8X zE>7E8`JN+zem{=P3@uC>{L0IOs*Mx^RXAVaiq;29(dsBa>D@~z^AaS~nSR90Y81Z1 zUv8gYT_I3~^Df>Qy1gfyQ2Y1x5=A}hXAIm$-swvq6NT4T#s~bmVr^zx#-k!?UbU6>|-`ZWM z!i*tJE7e7#G)h)K0*#UDum zEl6Z1Z*g{VioW*l9iH#TRn10U%C)1%+fIv5$GpV8m}EWujyu-&@4UqK#IJh#V|T2$ z0$?9mqB}({Z$^Q4ZV9v?fwO+DQZTIm4J+G>UTwK8(1JwEC@*m-<2T*qxcRG&W-LMZ zbNN#4_@@eiD!d|G5vWKBTK&t1T#G(at`!o~(s+y2i@xarC(UDoWhqZ9IZ3GXuJ;Oo zD!gvoE9Kc<>Ct8=h5ivDa`}4++rlJ$(X=~OjMA&U%t!d!lAQ5=>?7N?UZ&|hf_8oD zs1T^S)!a+Wo{^-xPc?tltzMt4yI)VHE{nHXFb8MjQ4))|uAYC(JO7uDGkMWq(SPA& z%55*DSdhs6hQxtaiF!(R^BB7a9~aj?Pog}vCn*G~Fk69V$bUM-t4EV4V#qWrT97ys zNg_SxO|0!{9^>oGWZ|825=~#RTOm+|`3+q6BS&7Dt2+1QoP5=a79`@_yu@E=lJvrZ z&0{=2R8uaFoWQ4+tPrSD^CpgX)sxok6R1GYZ!21mDBscqz zxP=)65~#vlAWe(h5GY+bjicYIiYQq^NT~Nb-22l8T-)|21gb6^@e*s_b6w8u=GBec_D!}M+k1SEm@zr!aPRy9*^Y8i+w5Yq?H0KNMJq%*Zt`Kw`_lWAT7N+ zS0PZU2Yy@soO=_EPXJYd@)C$1qpmhXxjJVcDbU?V5)IpszRV@MPDz` z+Mc9;pKBhY@b|qkviVT*cn~7cf&{*m_!zF^$?`LkV_&yQvTy{y^@pUlCH%Z&#d<;| zj(dy3ThrM({x**>1>0vyL=wsDU>EP zo^G4>pt3{@5*E&o5BQnZS$m0lfXYysx^0ei{|l8s)vv$2MfjDpwiM@ixZDh+4x8`G z9w&;(Q)|4%fGV2pS;8Hqvg+J0Z?WjlUwY+F=G8qvy%)U>i;{2jf)XuQ(+i`RdFQ7> z4=S~Wd)}2Upb)5fKGIvby#A?|i!_gMxppY+Uw76z{bpr}za8uQsOK@QOej@dpHVbF zUs<9B39LZGo}#@IX!6blqHU;3pel*S+p739Hu`1$s?G7^>07~DVsv~Zj&uK?1qrOy z#Z?_YjH9p@uJTV`l|a=q{!5`TX>4_!$GG%l9Nh`aCjDzxl4wCft^Adt={VXei^!OJ z9twe~7l*vXhBawyv-r8;-UEj?PBd2~*(bPdY>Lecf0nJ-FjA#Xh8yNvS?bCBExC&n?-Wfo3aXls!Hp;#k%^Mt!tur zjE`eOs9~PX(%q$uL<m%yS;J>=TOV(cwa8Ds&MWikKAPH@Rv%15{_pcj zv><`G4jch7y&X9cve1l)xfB9b6$1DeS%2ygFU?~#sL_sAj&`97B9}x95^6QXkFL$h zV}3r;c4SouRF(Ah7PA+p=>GT2V>lKxq9)Nr=-|D~O8rEvbEpy<_jyqqm7%Yf(o3`; zp?dCGTfDdyc^UGZsuHMDS1ey{bCCkyveckfdWjY!&{N2JcPs1B_x_dX^tImt2~^=~ zNz?vpJV3UsH_oU#c%{{C1c|l#f^3afgj;j%ATf7hkZtXVaBIzT^+ov{{cR)qnb+#_ zY(M!V*94=^-bM<6s_sKb3_TcRTe-^ID_WgWU&ig5V3fI1+=>;B zx5&7wr_Jmvx2CdH^qdsnoEfn9<3%u4&U3^uHKnvdpz4;@TU0vT%a-=-dOk+0fPq9Y zHb?W*r6j7p<+h3=3;Niqez{{+iSPG=xPr$m$KUOXNwgqwp6Q#5`q=U@&0VdA1W@qR zmyUgp3MmAt#uV`u+ZXk=y=Y-pv|eAfH{H(o-Z46|phOE2wcV_u(#bxy>(S;h%3tkD zbC;$#HlE0<5U47j&07?|-`mz>xOt4_r#jQ10cnge1@cH#eT%V(SE~YTf4sP3Rf*dZ z+tAq#*^J6dvq`idQTL5SgG@Pg_Li1wpoJSMFFZ@3n}$UxIAE&zQ%!)2kXq z4XA6JY4JiKP?fyEOZ;K$V;dY|R>)Y>t+h-}E-l)S52Ba(amd9|CPn-NUWvTUx}6BK>Uf>+e|ambM6eYCqeQ z`R29y8u>t$7~ap&?gc3Xs&XWen2|fk)~~wx3>NE9fr3g&V`<_Yfmd|h0*lDfyRXf0 z^o~`%x~|VkaV}Xyqu}Su0xd|~oo5lX`t`M?W14?eu42?IkDsye{27Hn)$xH|B5(OX z+m2o49gJRAfbNWFW}K*?3$!2+JlG*OUwxk zw4Hxw9%B!8oH`cP!MNFZi$Dt!c%`|HFjr_Q|D~%@VbF4gK-I?bULx*Tpe;PbJjSRp ziSk4KUdF%*a|BwDz&p!%^tW%yJVgc=>GF0Jc-QJ=w}`?!`q?7bqodxzy$k-9*}e}n zvX^Wr(1JupSBtRh>1P|`^x^~<$7P9$LyXaSO@%WfKf`rGa~y&v`SE|zQOjWVlQQkyFGt0w9%G;H@) zZ?ul>Uro4fH*BY8Z?q2UUQ49)KVYjm*Sv$1x_-5GyExpo_t9iJkWxpS{kg$rcFuX| zR#QZ}?05cq0@V~_xC3PVzszfe1X_^jx~8hIEwDLhO`AE^Q~vp8jeSV&2~^|{Pmw-( zwe1*xg|{{K6c3O8hpe-Xs_KdQ{g`<#ir4KbWXJH8>fi%L z8S~YVq+rfhYX3g+RbhF)E2@xTKC4vgVS`BDQ;=G_%+#`68_m#y#F05cByH**N7*9V z%?}USWY;`xOQcMoO1`Q*53ADk1(s=T#eEe2RF(A4vqT*ru6Nefs$^lxQuUs=54=B- zr{QZDz5HOkcA)D>>CTbpKfEe2B`#C%3fg4K`7De+=)FPf_P+>J;d2vymSTiIuk|2p zdcROSZ#ALdAr2+B0yI5uG$1$`ZQH_O?3HcXh){<-c z_K{Ivo~e1?jb*5+?7~R1SKZXdhZ2;EzbUDg-c7ybIB|IQXjZa*PLQMS;%^~+c)UXB z&qmwa}wsOzZZ@ZedGUFkdVu;&pxWO>hkpXwltYQ)rs4bEY8+Fvy5zq3(%gU zg0$`B$1uEhEJGeA2ED99zn`3-om@VWp#=$iHzH2z*)gy zJbHcsc795*-mhCj>CW+<@T)DxSC31uA5r!7xSrt*El9k2N=V=C6EpjEI@p_)-xsCR zFe(wK!qJEL4t6TXI)84d$BYPJXh8zUL?+XmxGL<=ya9TAi82f=NW>MRhNyHShVGgmTY&~ zDZ2l{&lD|4;5gW1YUb65om@0cf8IDJLjqNJg~C^Dcm!McYPinh3o*1Hf#YD4$>&BL zHq1FrU+|-dM4(E(^F~pfS4(w*ZK;v7z_h4=5qVp}fOpICNCb2TJ(cA#X8 zHc>6388gVA&w8`e1M~DRk#i*iRXBSUyRWKVyGD@-pIbq!$30ay-*IPXLBc#lJj2l^)N5ajr~A5JE!LvwSzTv2B?49WZp4c4 z{F>}-#ASU>~B>5+vP}hAl%7`R&S?QBE^|2d2QY26%zjN#6hqP>y_ImGW z9oa3fU~<05UdQ*2Bn6QZH}*KbuT}jjl67TuHCIbxd^K!+GM)0IpI#-nJwwZt>J>@# zvAX&$AVI-j5@UuDU+LPa6ZBlmT1sUg@l@2edFOPsW?rL=6<_kP8G&>3MpGgs0#*2C zg_mBd{A|*=#rkD&rW!3s^o_1aT3flg^{(+XsLO;mO5e5m-lK{{pbBR)!jH^*5qWK?2b z?Pr#;3@u31yi}NbduQ zEol|Vpk7+$x~S=6AKL2KXUFIje+yOkZiFvRqh>V9SJldO9>H)Tkm%7+R3PmL{T}RxHU{PoAN7 zN~98js(m9uiPx6pnd8K@aRKa3m38_O@3IUnNMP?O`b6P}Tzu&|Jw3%!B2e{rcPNRt zwLG(LpIIlIbqYMJ*UgrTp#=%-D}_hOvj*&D+5x@To=+4BRPDJRN^X8$p82h9(4Z9? zaOJ!{={~1uK?1*5;^h7B_U!nVQ@T^zjS_*X>7PT%VdoW@ql_wFy0Bj_&g*m9#!|E( zA&)YKF73(M-8!aks?%5^P!&{PA(y|-&K#G7e{DrO-rS^}=rlr_(PItAS(wSRIcNnv zZ271ewH+-;U=0;8R~UpbBRIB1-eTdaPF8HICYj79_BSiWy6hW~@Q+m3k3T+mS#O zj^V}0$wKYfr_($2$)dKS1qrO7B2&}yE^KqjEsolb1gdZhFYD=F z3AygtmA-7=v@QDi@Wv8>DjfBT+4iA0R&IYweazeZ^m9}IdH3yznj-dYW{bbS{XC+E zi5*vYv~*`)C)UXRLNEKK482}FfF$QV=GZ^O(K3#Mg{RZJ*6hu#oNRLZQl*A#07)u# zNL?*<4)N=Z-+3_t7}Jbtp#|8Ftz{(wRYN|MBOx0PX6_GuoZ3+2PjF@a=ciRii$uT} zMMPp-7R7cyDb7|mv{yp{zkT>k6nkC;yR(f)pHk}uH`34?KnevNa;!%esUq%a^&$0= zSpUZHgIKMt8^eN&{h(#SlBB!Eryvu~lVX@ykD{k~JeGb72~Y9Vca%JoxlXB&u1Z>e_^V0 zA4t?}5J28nIIQ+rZLI0fx-pD>woRm$Eej+9RXFw)QJS-lWTu<-X+ZJK1T9F&BjnF_ zM~W;oq10vgPO@5*{;twt^}Q$^XGKVxO#d|)&1!EgL=XNvLePQ)&d9`>(M_XRJ=xoBRJJ?WuDpbF=0BD+evv26C40;Ib3kf3Uk_}#A;4?Fe;Wg@8i zShi;6-|CM`CKI$EF{*6qdK zi$^kd!^1a=c>Ve6=!2d*O9ZO02N&)9dv}(8?us5#%tz{}v3FioIe@g9byQvF@HGe* zr<~5k9M#umw@|bof$I;Vr#{-3UAeMPKYG+lB2cwe^p8iT9d&p^h-bCEAG?~iQ=fjw zlcEKQ5E4MVV~=KfCoE|c%W8RS)I(R5q-a4xUj3L6JD5dQh}UW9i6n_`XvnN`~V{U}n4o`Bu=yrW+Wbl}mCeI)`_ z?WR~s_YOAovm=Y^ZvW?Wen4mb)6<8d1&P@CUgXoT)w{?!!^Wheg-v`GMW}ixewG3leqac#)bTk{$lAA{J|Xlfa$| z{CHqBel2A~bv43++}!ojG4fien8}>QDXNhx0$_1{U0g!bONtV=k*+iH@679^T< zF_XS`Q`CPsEqb2t;FD)X^4}M?O9ZM$&-Nfc&B^M&lNN2ax$z#|8*uxos|s3>2$^6e zlbvkpznm5;S{CAwZ=3KX&%a6ps_@NyvnVH!7yv+2vA9^&DO+QhV*E|wH(SpRT zO5UVF%aqJqzsD$LzYh8EZR2GERlYUMq`xTR-|2ze!pCdOARm5XZ~#RM5-h}C%N@yHPj%zzQROIFknm{kO@=w8IPxV6 zAIMfIdQw~$?w2!~n4mplJ8%BbgG7%^R{x!}@O}3}&z`RvZyME!paqGi*UaQXC!1j+wqC~C0~_tiG_UmlYO zsWbG(%ZBn^6?aMms!}U>k}8LjRpTV0IK3P_Ll4+FlvkM~&J}?LiEwWV*|Wx`{yT}( z?Mq*M=dU>KW;!Afs7meONk&}~Wr!1w;*5LYNd3c|5q$bYaSjqJNCdRCko@~?s*ycJ ztezin(aq-3JjNtWH3EUEBhx*}={w2lzY~WERX%Dvw9&lif%^n4NIV&3Azd_^YD8EO z@fkXA)Xpv$!yg5_ln7Lf+Tcm%h%$`Rpkn7|=0xrOoiV)ixHkkXNGw}oAz`A7e{onk zeh=36JB{Vp)}%@Vs;+MKB-2D0d(RtXxVQJy%DRl@^`p`VT9A0O(n5$RW33|&%kU_- z<9E$td6hC>B?47$&pb&nQO3V>sa+1`CjB3b;XkhaC1^pS;4KUJt=iOoky~1ym`?(N z#_+B6vr{BcmG`A5DIm)D=ih!;co}B+kKy_IWT$9BBHLXH`7X*h?T8L@AT*hrcN@)@ zTyT;IRDE#wB706GtN;A;52?i{KQ)pE&d*2Dg2Yu9D|xilruy_Y-g#Zpgnmki<2hOu zk_c1pehKe@0e1K6#O{b}}iO&%JaJ#ES zpsI9BFA}&uS^al*DY)Srn!`SbXLBh|(Sk%ugq7@>Dc<=Iql}3wx6yTt`}0?0JtP8E zI06*8uupEMTT1lj!5cj&T98=Wz)BiSv#D){8f6rHpwip3dh=%DGzSu>l1G-d<^LVK zP-G0RC?W#kd&YWoeY1s>ziU&kiM&E$H>2=H?Ow=eKKpfkiZvWtRIff3l6=Lc&JkIO zM9i9Bz4cr^aXjyg-vrw>_9dqRE#&wio0_Z}M2l8C^lj^7`H4zT2=;2&i$3^aCWjY^ zTC&d|CiK6rXFt)Mj}bXWus_G|$CUGCQnjZ|{ZC}e6FXR=J1NTsUQ~a)8ppn$^&%T< zrmOjRf)cKIkxQM@9lm2bo_Z1U;&k=2!=thLYE|?3+D(MTs-dW->H7O)Vzk(=PY5kewsa z)QKVyIp&tG{;ns^f6TBDQ$V^J?PA<{+K(kP zZDSxGUbYO&y2nDaC#mWTafeHmS%_z?G_~P<;bD5#LIy{rsjVCt5mJ}O(iY?D@W-W# zvCTIvWPRCG^}y$~O1@JT(rH4f`fc`FrPfCaIX5v?tgt45TJ$Sl%Roc3WHwg{4so^5i@Q`-i#QDDz zwW7$8iX%YL1}{ahxFk0|sct!n79=Ki^d^VHQ`C`;JHK)-f|a=7#&Cc3XIg?1Sl64Bt#4Cn?OUth)rvNFI)c?I=EnUZt4Q~O#O0=f z{w6llI~Z?p^sNY%`>!i6*HtD^h4&;peh);j>`PsF+EMxG;uCGZPV}N*Q`OWhhPOzr zIT0*>Cs+RMd2L#DiiPB8`%X=7y-Hb`Y9V)nGgRB0RZ7LGR`R-Bx>~ZXK`gXKu-k8o z@xFU&Q?ww_O?(YHluTEHej4681xiG+3cHH&s|#fURbQjTT82xyy3AyhabZC-di~Nc z{xZm)V(r5^CfCFR2i@t6w!`_gp*1O5kdSNQxds**F>xrL=RZ&)P!(9pO4h%ysVAEl zb@yhLowQb3U;e6O5XCPGesQp+iM+@?V(IMC1NhXt6Dj@{wn4mFQA?)JpbCrStJC{S zSA~RJ#uv9~G$CyuZ=r`v1gfw#3*V@{%W0O11Nh9U6{U8L1m2U#U;8>IRVT&rHwU)R zfhiV}{i97~EjK9sqLy$^yIMeG1h)HFiEjbBdf>c~mn?Um5V|>cZ+?BnF^U!>=6YL6 zaD-hA5jo4nuKvvlbnDr!yvkBdB2d-5jg_pdXjiY4F^E%*o!O-=jd-KW;nG?kuHrR1 zXC<3@+f++M;|+!^$iYfnZq73%hf%a3f$MW7Q;+Q*Xt82#cyCKri9nUyi}qUloNjI1 zk*6wkDO!-g^*Irf!}kQ8<=lfe_l=eaRN=cZnO-_^y3Df|-}Ev>>f4dP)i#mQbGb&X zeS7hadt?GtSf|Bl4nH?$t{B1d_|>2nK3Pdn1)JK@YlDJoC%D2YB7fa0z$)A7^MRGy zNbdumH2#vw^uVVO%NZWQ5BZLh%0S}0-AXR)wyDmSj6Sj29WyI+P2nZBj*$pdr4{xj zUPEl^(M<;N{03#)qDt}lo2yD+16-Mqd+MZ;)!4ozetg<{`HO=DuAP`n*M0@F#OMHi zDQgp{Z%37URp}?nvw3}k`TA4g6fH>L8jx5Q%`W^BSv5W(rnN+%N`AU+i~6!UM--mF zV@>Hl#q!Rr#oxS;-#M!A{flgA55AK!Y$(6=Vlu^^6MG5l`9!3`s(y4z z-2uEq;gwRKhy?Z+Vs3DI2)(zsFE2TBnM9xp`$tiCN6e$=k9X&HBeqhsAR+f9cJqHU zvS=6HgRGDURAFlt-U)rr(@`th@q@!QORW}(A#<#xuNWD$a%8YC(&{z6_&S=eTsTi6 zP=z($Wb!-ljjpTIlsolWF7-Z0l;T!$NPMFvr5d$;^6b2J;^BJXSZm2rnESzH|{+}3ywu`j4Gn4 zXV!BllOF-H0`wuZ3v%#U}SJc6PH32ehK`nPs^h#>YKcPtk$|))=ue@x;UmZ;jyd${&*mRMm{L zlDpgO>iqXc8SS2@(*u!>c+YBwC|Z!fdMxTyxm&buwkG`g%WD#WDtV4Gz(=P&H?-of zzn!OOK?2*OI0spL4V{0fHQ#gMfkdDRYo$1g{A()p&EJu)T7O-dc_D#g6fx?H45wv2 zcjlL)?@0uz+&|Ji0D->6x9O1&OIvE15hh zRh{ct1DNvhDhnClJTARPFen%oug{?q%q~yxQJl7E(ob8TO+mV)=u~1X)J)@N&&7p$g2i#Z>jXv5pV9gs~kfM67tH#FUVK#{9fu@^|{|xF2ub zsGvlks(XhCBB4GY;`J6#h2=~4<_*6; zl?YVD<+YN;TIuSnx5g|rZ=Fb%ZAdX*c6@D$^H-c<;|$rzn-R`hbt%p_bZ#ZhosqzA zm&l5^kg+X(C3&BYQzQaa8^k;+tXjHSc$slk6H`Ljz5*70F=;kM3ljM45~sGh2eAu% zEquz=?Gk}1`OZsj^=F%`Wq7`gdnsCwkZZd(%*uWz`0zf!eOwPehSgLR@*K~>&B(TkkGbVq&(2Jvk zxm)2JQcXk^wj1FA@$osGxuF_woRLFnA4p)|C3?8US82$L5FY-autcB=+rP=w&Gis{ z6shq0YYR*590}}$g=bCLN?Ni)D0g1(DG{i`wM_BFDLj#Wn8tWUN=a#z6A4_uG?|Lq zgV=6=XP%|_YuaS7g>;O`P(NK!K#Qfho)%?vUv1{42QHFY?xY3IyeJ;-K)hofD)ym1xf&})#Vx_28 z5yr9<=3{?}%v11NsA>~qA>q|B)EV83GOn%2!y24-<=a-cF|;6o-x85A-6aQWH^YS| zKJ$?XRLQ#lC60ciwVxE`_0RY*v><`sM3G5(_j7vUO+G$%a)?Br3U?q(rZy8U(9Vks z@zPzYN_!JX;I4y64LB@Ozww_CG|3sexL2?YLPv6PMDdP58KtABB$Dcs%8?H zCsiFj$ryzPWlYfT$L`Tj%9-T#;oF`c#)6`u@GG8CsAy zzRyfP?MPKW4L0s$?yV;J`mj9w%a_IyfvT?DOingSRo@&oh+)V5^c5$H@&Qc5D+UV^ zbJNVE&FEA$zavjvT2z3(!Dit%#?_PvR80~)Tg}U)svCb8Wn8N5PHPv<%|GmI&YHSd z$f&1jY88=B6!*Nky)=`-$J5jVv3n*~SS~#zm&@km4@$IPXh8yZ&qVgR8M8^pW+p!D zT04nA)wm;O(r96tI^K~3wDn1*o8n^iTVx1Z1j&CZ(Lx)Vx)VGIqQwu7^c^)zfdc zlL%Dd`xnvJ*T2>?4U@({Is?$EMJubYrM4+nGa5HIlDNS{IXgsSPKPS+Zo9^m$ zd}7#=+h#K3P`X-I#9P6qVA^da>GA36qX`C)r(85G5RjyY1$AO*K?0wM7-f{MLPN8k z(w`3KDG{iWYoh5^Zn|gfS-sr)UJNZr;1dy%*w)=5O?`IiIX1>h1gfwVh`8sE`;h?; z_UKE$#>%xF-huqAn$~`!obI$(uXj>zQK-V2FX9d^tiZMW)%dA;ZUlXH(MNc39r1NO zC_Ea67&}-=TReDJg-Bk%SvP{-vFMGP+|Nv6zNDzF#u-Gmy578l8phAWHz8<20?Rg; z{9SYLm8+w<*REv*{T|Vuw%al@d05G&ewk;K@pqLAANZsh|GjP&K?@S-nJZR=L;ZM+ zi%4VIFhRO=yj#3lu`b%MJl95s^26qb(tRKiURQW#9!^o;^fRui$DGo)TKn@oi$eI7&YdY* zkQmxrdcG- zkmwq1CRe;{>b(gD@$7;pzY!k9W8NK*2vjW@Zzj_w+SK9A4C2cVEAQ=7j+444DXJQ@ zHj})OHnn)zdPOF#cQy0)1%A9tWFkci5^n{)x~omSTf!(~|0-90>y|%nR5Mv3P}ORJ zndrj5}OYRd^HF?$47nrrtG|Tsmc<8s>6b)+uyEI2NC(}t=|4_XMW+}0g;9KfBdGgUy*&) zi1J5YQLP=nmzYY>f&}(4VvnWQ4}DR!HvE(~p-7-A{)U+pjJK&@s~GKk#h+|^$mr&L zncAA71&J}DpKsR6ruzCB#HjNh^#TDcc>IBR5`n5McSRc%etp3=jM}cdnRsBHM!b6M zH54sKoY*4HO-#0_I~+a3@?$A__SFq}!ci^}sCxFmOitKrD(z#G@zC^H_wbG2H#c6P zXh9-mhnbu^D$dPxGKlU&AL+$T*5U0o*(Cy1p-E;^&)2TL$ZZgLn?%c2(A9UZ!(1Jv^ zP2xT#+11_63}WHt4f^{*Wq4?Od5J((Ju&KYH>Ii-vl+y!HQV*__ssnH*C2)#Bqpsk zlL?7-bx(H3Rh3wwH=XCk{g;TGVenh1YPrx%hWMtcH5^&lJ51lDUq7CYCl0R7(1HZ6 z4T!by9NY9Vseko@zoH}pRp?DABBhTzu9rIhR<}NAB>7n)A+Iw`>#ggrd)?Cy+-fEf zs6sDIk*{cI0q(o0DQ~c02Enlbj%u(ynoO(572{i%HsI{(Icb!E1b*j5?1ZU>dC=J? zzJH59#os~|wnvkx#**SZ$C^6)Z(3c779{XHFY-;$0=$QR1pgR6T_RA0?NRI^>qWV~ zz9!%JW-&zz68N1L9$QuN^7!nvcsunH#?uOQjt~%k&wU6-!H$=S7!O4Pa9oBB2a~Ei^Ai#>U90=+aWwD-~&OQ zcJy4A{o5bjU8cu$9>}LrSBe%SWdHWp-xulX`Tjg#zBUqps(@-1(*B-JwKp)n&f(@w zdg0c+`K2YpC|Z!%l+8kFim!8rFoU?UXO7-MM1qd3u}UIP)kFA&_sU{dCqFU1YUMYq z)_2tC%3c0!qi8{*S8fY=D@J_{9vH;nuqpaym(F~6#(9ZA)iB|cUO8BNaRwU1Cg+9v z@x*q#v)HLd3le_$EF_y4^*tV75Nk|>^pc6Kc|3b35vb}^L-@DH+SQIu2GM!L6g@j_ z&Yze2P0@lxYF-OTZ)jID@*2dUy3KWMdSm`^cOHfWsshD6&M5J%owC9Bs`U@+qvubk z$JhNTz|exk5hn|Anr~NQb{Itc8-aSAI(2xK!|oD+s`OwB+5f|?W^s&n+fS*Z_svm* zUwCX`XhC9ORzWA4+ z8Vh7-K|)>;t~~sN_Vs&tez{SoM4&3t!$KM*q^ez)8D&J+o@rNpm*!><#?XR<`&mttr1?_2e#OF_Q= zdQ*u&Rqm^1(!NrfTEo{Uqvg(-TEg2LeAn343@u3Ds;Y?HmVbaY;?g^PNZ(EpfvUhc zW^%Ddn)*1qQAU-{x>lszeLd^F?hGwR;CixHjS5+>T_|*1UliLfnkAG_JdeN1bmb5valyPq7<* zYbqUiAs3$$*-+XsL1KGV3ppv)lP8Tg%5WRel%`I1;XQN91gdcNM2t)F#L)F4it>XY z5ezLzR2Ff0S}jgfkBDgVqLy3`nT@KK6lY)SNCc|nvr8jaRHDiOD}Oh=215%Hi+fv0 zLd7%@x7?_^kIH6{jnRHQdLxktRHZhskc-Dt)yty|B0zVd6QV2dF72u?v>yBcgrBQ%sfqQHL1=Aoh`@Eg2eW@7E&)R zRrNh!5J5%Fi6WePTrCTRNafS5LZ{bI_{}K3@s9(EjiYQ*X??aq6LZbqKrHi zyXy4FAf85P+T#CWd0f9;5`n5_gGEhD6Dt$Vjqz1PouS&&1A{nymq5{iL`m_i#)wse zLaiJ`_&x1)>QG*J(E>a~Z=sM;Db&fFgnCN5$%S=e&9sWfZTwKM%!oq5;C6<^P``$Ey`zoUXO> z32AXWy^4=?RY>5-S>!kPT1`*$8p_@0b(IKI;Zrx6)N1YZ`ill~ucqUrr;7xRoW0&3TXFwJ9N@D-KOm@B6;U>JIbAGA!K>|n4BHq%>CEBqwQCu1A zCK0H@-c_8Emn z77`$R4UoW*v+$bilq1xfw=$3XExu9kEkYH3?Zj$S^|@;0qZN2NaV`ffNZ`m>_yLqD zM{W)E<4KE{M4$@4+M<0lPg3$9vhsFQ!lkb>5;$@eCnt}_lGS~SbC1qZ5`il8(JocfT`33lcbT z7OMtBHXIw1aYKK4sFy^b3U@HYX~3CI+P&_F_41GUGqfNfjhs!{=FU|IR9vn%t3E^` zP$ln-=Gj?In_wQTSGXU?(1L_KrrsNPOYOHq(UYc$JU`%(fGYF}5Tm7PQQCvh?7DS^ zh>!dk(*M|4`Pg`_&tVEy+y$D1;dRI-4AJ~`g=#)tCL_eO}$5jfkGdlFD zUM6QxK6P9!iWVermqX<3n{iS9Z+|zw=uDJEpbA$hL~S2=U!O9qBmWuKi=qVy+!qni z5dWOgBO^NUw(XZn1gdbALae0n8@lB{8{XYz6GaOWxGy4B)k+`L3-)Tw3w}N$5vamd z3USWs#94jEsAjx{Ya&Gp61XoSc1*%V%-Z@*`1i03i9i*uQiuqcM-S`0o$K>QX+J4i zkicCI(TgrzrJpDm!FPq^Wk{e3S1CknsyCbUM^kF@$mRtZT9Ckf5fPBI;Y|I)HNqP) z4~ak(u2P8n&eIm^A3s*+oyvMMv><`|BI2EQ>!a)OmH64y0TO{KT%{0ocgHBbRtJBc zHav)-1qs~c5a&6swACkM_2zk&idD|<|KnSSD)inH-s&|b>9?P`^53m%OI~_N;J%2- z)Sq{Wr42u|D*rMn@HYopJ>oVB2b0i zlp?#MZM8o1zsvf_O6?`DNhIW07WJB~(1RcTr)#O5B?46#M?>tZ_3uD0O=+Mvm^Fk2 z_?k)UKf=Rog@{H$&7`O`L;V<^pj;Pzq?QZm>NFAKLe!FSQ>k;F0s7c2u?#Ip#Pl_j z;yp6ddF>3Mx)x8kI=5Y^4j@uGP<3yGjJAy#6zj&%POI2s6s~)Bilxhi=x(u4u>5g2c7mW)(A_N(8FB#18NJrWtBzKBJ6LbDz?}pKj{2en&C1Ac1j4Or~Au z-qIR{F6lRWh%p0{K6k&F+`pcohJ9ZnMJ5sF4fGE*a>z}6`_j4$e+!9?SIp$hmkhPx zDZ@MZM8j{iK#Mee&pjd$s6vlsF;~l(i;azcp zFV6b2rj>H>$x05%BOZyAau(8W>N~aj8skjE9?wAb#62$`*yp2k3IbJlB0{u}HzjG) z(w=&?CnFeod}0emFHI49(A5=s|8M;y4>}~UHH))kIos2prFZFMY;TE>RH7C9kMH2nsq^TyE&KGgU%E=3 zfJk6#7AFoTFQiwUPV2UmjuL??^jkEU3Wpw`wDEcU!rRu;x+oIZn#FF$(!+GZJM z1}$U)dIMY|6j9L>4`KsX|3@u3D8BE~`xV#xH+O9m`niwPzsKPZ;vEzQP8+|-Jh<_ph3@u2=C#u>{ zEl*u@RpS>rl$8in;ToyPqEw+aUABYr8wb1@T9A;>U_Fe^M-}IA-ei@RM4$@SNJXAF zk+67NNF?8#;>OT|1fCfdU$rqw#N4eBZ?&MXM4$@SNKK~o2|1~2v1YvJvwRFKNZ_ev zu`_ykJ;{};HP23SN(8EKjZ_eYlSuXOcD$wcUy2qaFnWQ>RH;N)^6YIV?&*^u5vam7 zQgQy{_%7mmxT}br@SLIr2|Uj&&baFZiTjUU{P(A85`ijQBNY)apG_yx(S7+A{Uk*T z67t#buH)7!t-J>Ep9gkG1gdb2RP6S>iY5(n59a0Ot)XZ^0^@UteS^EXl+OWiyiK_& z5`ijQBNhASLxM>26~lQ{wE@C2{(qwEA%PJ@#QSh7K?0|b;yL51Nd&4ej-T+EXtb1k zvW(_4I+&#he@I|#GOvv! zO`FyC*?^I*%cW$g^^Kf2cdS@!mKq}(59jbzFO=RZe5{|#c z8AwHxlSw?D?auZ(Grq1wJVgr zp~-Y>VP2-E1@a+ZGU%YG@08SX7OjmKM~U;I#<@|=I5V2KBpdlv+|BW~i0_l&%v^T_ z^W+sTC|Zz^@53Xe25Wh{IFFhbFTFv0Yk0L{mGdrThj$g_ZjU!e_kjeS3^kbso>G|E zT7=&mwqGJph37m?roGJq8NFPA55L=qV$HxOE!UFvg@f3tFhAbw%1nwDB;@Syf zC}ZXwJyeN6m3Xp5JjcwZTRtv?eV0KDKWUW^)sqd5+aDBm!0Pc(>-X zqHJzl2p=}&62&)#H4)#eh_fA6l2sdBj(=W%TYBe61XXb%;$P-{m?&wyDOPJGFv9mJgg9V;GTnLn`4y-RK338 zN|v_Dru~~og#}rew_WQ8zi!1YH+6;;oB(N@s6-fV5%x6$J z$2&&?Rd`QgZZNJ4TYkdqc)Dmo0_%c^vKi#fru8r4c)CcS3ZH`5;cZ`*)%MNjAkcz@ zTuZ|LmSaup=HfZ#W@AX83g=X!MVV6Qnde3Lo;Br|c;-Yrd&hGZ^H@d9I~{+Exu7EE zZkcaz(4@n3NLq^ipjTs7^HPR#W4Bp*Csqf<+*}beZq1mVUn-xCXzN@Ze~bLi`8l=a z`lN@PtbYR|D zvXO6nMQs2^mXl9G5jq-67dTT0?QVsYi3@d^+q3a z5NJW->^Wy5{$<{IZ0$F6ccI66!6$X4`#=>wL$S`#!$wc-`0{_AE)v+9MLU1;o9=SW z$M=eMj=zN}tP5g?H}EHQJLC3$Y6%i@&)}Ig8_QR>G%tR|MXFb*!a6P1$o9lg*LidG zjuEj;yPlOi4HEA|thb7FS7ZIv@i)F3kqv6^ZaV(#Z9VLME2;Oveg)sG$>b8Vo%ZUd z>bt|_caB8=#m+?hbG%Ivi?!q&dj0!iy+HNeQY}GM-j2>h{BvBP$yBh#BzofWD93%E z1qpF)MBHO0QR{R~`g22|eydL$LjqM|JWa&7I&(~Yxb6eGq`)?P=sme6;um2>oYo%^I*ny!130&(H=W%}Qr4@h7)JuKrCK0H@6=*T)3tdU$KabUYNA_W8!TZ3n zMVyH_%V_16@s6j979{YwiCuunhiT8vdmL{N2~=Ut7yj*Yb*h}WpsyFL7A;8N`!|{H z9KK6mmrHZBK_pOxHD8>rA&E38^smlDe}xt#o_!=OAD*Wz>=&g}i z=%UBIdiU`o8P2w_eaJJf@`1ke`u6&cdW9Awu%(H0xL^6`0Cx{Z8Azb&b!lfJ{$G_EGms!T6b@Rx+xRu)FHDeiCkdW_V5iLf9<|c`p1|7QfdL&RKM-Uj3I*|^$li+Bz z*dt?Ki#0|>F~2^T&heV|fBJSLu;&wf`=DTY!- z;r%Al&YsaUuJJ&&vUi%Y-p{P97STv5l}b~dIGMHB&k4%=`>D#qVrDJM5#>L6;9c^) z{A3dCGM1GMOjj=c@Y3#!=n$9xq$vyUdTDJ$z5#kNO=V zmw_sz59df%uHE+1jyqyN92nS_O)93*ubmT(JUfc;uF#BJJA+5qlpPsnt*^+5vu}}2 zx&Ong)pcZD*zYxzt(`rU?hg8BWSddM=@-q&II}Oorj+-!XzeO)R1O`oDJR7$g%dYC z8cTEuVJ!mvSs3q5FZ@kWdNem{lf_BTiMLafS&htEtKu7!6(w!T^I>LfndAKVgR`}m zOY9^NB*d^e1RnOu0W8|!J&>2~Gb zMyuw3T4Y^#A?|})wZ9^c?7ZDJ<)+=L&2z+DZdG9bn{{Bheni9z7dbu@5lvh(@_a;0 zvni_@ShcnyAIG(IHpMC0s#O&k28742J&@(-?Z#hpzec@lq$!`OTeZ^9)+m9^QcReG+mYH5zBrxPB8uwujB>TUPrX8G!;DcxMHT4NC{uvDWoWqXE28`nKS zDLX1vS!=aw>5j;e-@{$miT4q_l}hQwQFdiVPH(MB)&wPwW>+qLwrX!ru2B--*p<_d zt=b_+CV>wgu5A3N2wwPfZMu9}y0X=5)w-QtrQ|=Fp=9M^g)MfKGO%2_5?$4*F-NTX z*f*}MR{k11uIXZWCp2BT>}}OTM3g;L;cA;WQ~kUsTVJRS&vrjfT2(^=%Mc z-6Qz8l`#^5DqI5;(Zy&nRw_1<`}C_#Ck;qdqR(5k+y&Pt=5c9CM~47s<_nf?A#hFhGo zGILCZ(r2+n`y%4p;e4P>qYUNmD2sN?5hbni>l`e7QE7hvXkLaEB(Q8zubf0gQtHn8 zH+7Q;ROPFdp$v+#XtNwq(&}``#@cQx$hV9y#n6I;d>^4n#aZQJRk{7^9;vot4ewbi zU0Idas_k+_z|7a72zxd&l)pbI;_!k630%<=5#QezVXFcI`IYTS5`ijwhQe#IoHLtl z58}^@yryVD0@r#)i}J|JN_hqHu{}OY1gh{!i+#1!4>aF{zxuW*p$y;iH&ce<>uJ$m zrLIxrXBB?IiRHQeR>c|q)KhBwT_4=dRy8BB6s_;FTOmp%U zV-LUo*1MYIH;BZaYUxV1-4<<`BNpq#-i6rs2QIu>YH{hEqYCSrSSgxXoGqx6pSKYt zT99Z^J6-wjhDDp_h{f6`XE7$c&iJ8-ToQpQd`~8m_X>Bm*5b*pjQ%UV4SVXO91O9q-a4x{&Ma~jbM`oZq&mPjFBmz~%qS6#{)}k$PL>C)=VHlf# z{j=8W=OFs&gH0KnV$r6E93$BhZOYvjqE{37gSwxvDfKk>dW+@~ib~JDlmq-St6(Yf`izf#nGwub(5?vGZ@W#EYdQ z0#y}Mn+S|%(L!Q2ig!NKc{Dp+bd7dVGgGu6A+pLTVjoibmsxIQRB!gV?{58ElXi6f zS({R`y;aLuZ-X?Z>d?Wabe>|>zBuymPEGC09_QGp-xir@a1ES3-9`%iSQJuw}apnBjHi{M`tDyCqn;&;NTS*bBM*i}A) z)%JJe=X`6>Yso3f>(^E-W$H$yNClg6<®^?ZP?9+AThJIO=*74s>M0-%JkgQh%Ia4%&T4qmk3mejMIw9Go$5ql+n0v1s1S6m{Il#8{6_Qg69%BszioUMdYK>c8TA@kyFja zDN1;VxAxYNVfEE>5B8x#829z7O3{LZT*irdrPz@~%8PE02~>$Jv5LrqqGc0TEBqN2 z`?38V)p-B(suV3q;60g4*V9U~)4`Sbo%Q1>j?eL}Js)gSz83b@YHv1r(KzoQc5}2J z_wF`>q6G}79?C8G1cx z#(e21y~CYb6fH>LcV4U^uWi9bxnI+pZ$BXssH)~-SH{e-YF8b3WiI}VVI3|U)MqZ+ zO3{J@epiH#a7;(m)BlV{KIW0SIo2ufG_P_!T+e+^zn zcVrcpKi7AM)|CiUx%$}@krzw5GtuZvrbSd{?vwNKTiaepV>o;__+1g+xWj6&w8+1@ zd&(o}i-QC{b>UlEtQPCoBRenD{IW!#3co(03=+jWzr5G0?&8vV2@?3!#oolcD3*Bq zw_Y%Ew?v={dkHZU?%a}XZ}?U(Z(2psf&@Nwks+^F3)V37i>|xGO9ZOq-e*(MHtgW8 z4|>%ST`5|Skl%-XsX235n1lbE5GE0*lD}%31{Gvlm0av}yoKQk)SzcJXbo6Op8 zM;xyvdCRb*T(9V&iS7(7NNf$YD~a38+ABwNvEJ>07*!iUkX+kk?i9pq$2Xx2c0^TazNR+oajq$i9bZx+P*q#pM^)kD^~@2u z#ay{48@A^*ZF-@Sw4R9Xrdpz1nYG%ieRV`IyI0bKrQ5F2&FcafT9Ck}F1#k+m|44h z+eNbSAc;WLoxgUa`6aV9!Vy>P<-{^9;m8KMT%0#R3ljL$g#ZF(QNVs8LL3ljL$O{SHdsmzK>Xr2hWvP7&|t`!*;Z_cnQH9f4_Bat<>=|Z~__S&Lta^&;MvY{=j6BnYdc>aZ= z1&NnQcICoji&n9lQFk|6TeCB}>{_Gt*%=b3O1o=UR&Nn&Qp#Yx!KdAkwD|B4iyh)eb>HHrv`g7v>+j`o>zKB z*zdR3mA7;KB?471B2$%}Wi8q-M?|1${_d>Lnu2U{V;6>f)TQ+{rAZsJmV9cRg8hog zv~#34ORAcml?u;LIi%og4!>s*r#AwW;S7yZ<-l2uu3rGa2uwM}o#?KPAj9j6<aXyORF@=sN4D ztd_QoKX!LuQx+>|X#ZVc@14zQ1{=NPDa_87^~&_*s3QnOht2I$iqEsp+{D0#*21q5jpv<~&W;*6i1+tQ;dq zyzU>T1=9SkZe`3Gc&r8AS1Ud9|3>E(L2ZdD^*31KSzA7L{7w6~NtroDkXST1PJ1xS zS@{1lzq!Yj0G>WwcDwJ$j0%CO2lL~!Q8d^0!pbe;A-eIZqsMCtvL`W&An~m=tpe?F z7L|LM-@`Vi7r&Oip_o|rnL?ndEfEfJ&LY%0g|FxF-n>wq#o}s*3k)MjtS=F#xyKVh zXTVbb>T4*!(mS_tIzcD|sxs$}(_WWy5&2G=gm3Bo{A68s)hlfmcM{HG zy*6htt>b7;BI~X7TCU5lG|Cw+wm&z&N9hqY`PCK`dG%cP>^%>>(gGSdiFEzfYX$ec z(*CLMB>thya-R!}~et*gSraZ!@ zyT@vjOIXaxw?V5M601!-+xhUhWq7Nzg&0PVz;{Tlmo@eIsHKH@ z-+K)d0#$X|#cCthI*HC!cH?>{n(&I0IcfTe@(d$L;4@K1>+sfm*{^i`*_Hr>KvmkA zvD(zjPQtT>`Q-1tJ8-wquk2hwJHrSP_-!ax@w9Hd$e7zKD6qFepsEV3xUWy=ES6hY z9Xqt;JYb?5AJ(d~9m@}vS9~U$jq7!}X9HKBXL1XrBqGu8<|~b|<%_N_&F9E|ry(D* zxhQw2VkiWv@R@8jsrmEv*9-C`Eymh0g2bfEv063i0US*-uaRYAOa6RlZa#4BbcH~b zTCQfC_vACY%J3$X!)eEMB-}}iwzA6m&a1)Cc5&s4o6TSt zK?2Jgjn6mua&e>pUwmV+LZB*iQmm$LCU>Ki(RxP(KYq4WZhmRZG=>o*u)Nu9{jxXX zSBu#A1hQc;ij0*|oSW3W2H?Y2vgX?kuia z`9;sZ9Ksvbn8qAD-YNbP^pq5(Ihg{^&f-EvvxYmrE{qRsyN$V3ePBo53aV5O%Yq&Q zd5fFN*fJjnh7lz2dNy15>Hd7mmqqO9uK>)miX z!w3>t6JoWNgPp}#D_7XJfH1z_%Y)@C9H|hf`c;seD#M+{6)S_;x}hWZh}U!N#^*ll z!TDG%w2!m+=j?i|>`iI`HaUx=YwNZCA7eGz%O=`b*~Pl?;k<95-t3LTPdhqxC?l6f zdA39Z|6ljc;e_G*efQeTt6C|B_l^W!+h&V)8p`V@d9#(1dMN~|@R`WJn>dtDu64_v zarH!o5hT>-=yiP{kDPbXzGzgGLZC{0SI;}R^3_F(@SJCp7>+r*1jcGB0-VHvqU$sq zCs3~9yXASC)ehXbdV(Yv;DWabfhrs)P#(zH-u&&9 z^t|)bXAC1qtUVa3Ri+WkVk>j~tW33dlg-cBjfbBU0#!Ipu-VF;uFq?Y{f||f9LF$% z#Ol~s?ZF)Oq~0s5U9d&0%dh<*@BO2x}9aAJ);;w;!(aht!#Gc zgPw~C_kCVG|22z*J#?2 z2NZT;V}iaZ1gdbHKwjrO-T1Z(8JSDHM1~P0ayN?8(vEZ%hLx!>a#s&t|Jz{urZ;g4 zfhrs)*lZ_;b18w{ATD?E%oyz^I5U9d&0__Go zH-MKJ+(&Hj-^MV41gQI2<4k2p^l?UF73;!-5Fwh9k)y&P=(`N%9pV;gv+Ag#_$2# zm60$KIBui%V|g%dbIaTCDRn|2P=(`ma<}d5$+y{^jTz#eGCoHFXY_2gQMbDDBLC^) zR^NDqKo!nE(A!Pu$hUo3AVwWd!!d#c&H>WO=*)IJ-KA3cNr$WofhwFwq2KxGW_)6v zD4%B23Mlg>NZ=eG&3-sH_}bF$>**vonM<@4+{|1PV{y&|E`4vsD4 z#mllU_R$`m3V|w|TP8z>|KFR1$s(5;L+38-%GyWW2ENM4_Nblx3CkU-xv zIfT;fv&&3l#NCLo3V|xzfk8dw4i(sn3^vxX*(l!oLV^~W&q=JJ^DEJH{jx)XcKy4f z@V8EooULtS5x43Z(`)tPM`k8!xoPKQ44ns;<#eKUr?-=sPT8eKbV=0SO>q(*EWgif zF@y2&GRBgdgE&Tz@LrOrMbvc?Q#P4Sj=(~5*u%;1#ef_`6arP1JrcF6G&3>SI^!_M z;6PTn(qWO8PDR8B5{G&wY5|TkO0`a2j5^epH7>7-`DauDRcpwHUaqE-m`&#$+H5&| zo3g<+Hy`7|D2@>%@EwvX>|S4X`RZJIkB|`xfhu&$lRF_tXSTCdCYH2ixZ6i#WFNf^p4Wj7mL@ttJ7B-7Nw=} zkJlD;b`oDknQPm{XWn9oqYc)cvVUU)iN#sswfyw1`b3ySnF=ph^$i!O@ z)4tI>Q~5PfnoClg_KZr*Jv!HxezkvnWV2i!vVS6LbBrKyt6!XUuQAP1Stm}7@xIGy z7H@C7^rZ6#8zyRb-c#8nk2#jgJI;xkFRd1r7;^ukiZg3t4l9;F~52JMDZk* zK$Y{^1TA=klW?=nYAhJGn7RG)T<;}^aEu^_j3A+w-H`sDP`#(NrUd(Fj zZ_c6{g>j4^q3#%||6>)qeRLwLx-3*7P_<)Myf(FjlQ?0WR#1%ZV#7kEQEf*jj(dLo zEB#t4|BsU}v&c6}qzTz!raBzDe7)HYL3e|rJ*8YQ}C<=L0tG=3W1 z3V|y03)^f_^Y1gK*=gjRpG@&O<4!%iHf7TteuZr{-Wl7MG*GUA1nzgI^CqrdWtaCq zGR6#Uq7bOUcSyNj?jB;>x5gN4oLeaG3JG=h@`-IbSlElJ#)}E<6#`ZGWhp!5oAiA5 zn!&~%rX#hp5MFfZUxF0#y|bCupOeI*G&9iO|7kAG7@hzl#=2dvc5*fi;HBHeky$Rx@vu zSR1brsLHaC_DV%l&1anmU4&m?O(s+mV|+t7Mv%Z7gL(iNuCQNq_jo_q(_0}>H7Phj zt24(*e74T!m^%6Z%afGZ{_$3Sju9lV#-LpH{KU? z5hSoIkkhF}TE1t=QGIG1l|WVA$_ZNW3r-@$szp0DO<*oxTWTk-^xzml0?PuOO#1u{ z8?kJFy-Ba`3W2J-nP~qPwVai$GrdPPxXn&)H0%d21(Ayk?^-w5FtK|(E8L-L+rwQF`}1NH|h1gaWsjn@o+ zC-I_=`8}FU-^Cn%OkiK91#^rbp|(*Y>g{2dw=HFF9`#fRRAEnzYKE6DS*Ll2S;Dzy zO8*LbPS{hU6~)Xpp1bH4_9DKC(uYIBt#rKBVvodd+aEu@^tW~@=P&$dy(I&y$X5|yUw_t}~HdhE#ZQd5I zo!jFi$_z1yOjir=gHPSqSkJ~BBS_>N6R)jFa1zb7o5X9#M{!=FPkMWZ-cTV>RsT!8 zmNkd7DCuwBRfWuD`09gx`k^nr93x1KIvlUr{GCOvaFdAoQj!O}2o-Cp)KLgjB{?K$ z&wQN4U2Es$k3Q~v$&l+}Z$EF25hPAtj@NEbUAe_NS0-E5^1MYk2jjwSl|WTv&jf8} zsI!=8opw{+sWSiTcmreV2TzU>B!VBrYeja^`iFH_LkD{B<#z`eKkKLjs!sY+ExOEE zOuucm&R?pXVRzcDWW#H8QAR9S!ts|zzNIZs*{#*HnBBL7@{2+OOQ_AZwZmifsd*oE zym}XfKo!;)wC?Qrm32De$ChmfP-+Gwu)NW_LEld-AbSy3_G~AGKo!<}Hd~*inRvt3 zFYS{mwo__2B(Q|i$m??kel2N+z3Y$wg+LY7;N(syk%x~d8LQ3wx1~~3BY`E9&IYWN zi)URqQ}=Oftq`cfmdIuc9bK3&@dy)Z+cie`1gfxSK>H1{mgdLy^f!z#HI*I!5^CAK zKhBl^J!6*fJYx-oKo#~^=){o04!q`NKe><6*Ww;$+ySh*?yEK`%y-|cCo{Bdr+Da* zz}>*~&0jh4+Rf~;#|U+A2C8t^h0V5Qsw2O9##^o`KaXJq3EVkN=WX{a!^f@jkmK5} zR|r($ULeZ1)W0PEndB~gBK9eJevnXi1OC0ijW-_ZA`h%Orx2*Zed&}z`JF4jxY}9n zdHqoFo+E*~56Sh?-i<#hm0y1LQgoB++ zzc)9ne9=3bLZAwF)KQ;$Zb_c!Uz=?HA|J;H61caMzWF;ho>1VS(S>$tB7rJ(r{46r zE_`~(f5yXVB{@crP{*8w4?FVE0mqGv^C~I?szM7TY6;z)MUlp4-Ck~WUjEO>(?<5L zH8@6)z%efE0Bx6*U&yxKXjZe1LZHgIZ=#l?DD5S*vdTBB_mf@g6m1lBZ^SWz1dhDv ztgXYZSi-W+#^tlE6arNp_S5+Mx|8s4Z$8Hj$||3|+;$_ZPXNaV5;%iEr}iv}W_y0F zGV)LAt`Mji`8iR0MkB9$RzCgaU7}d-+v<-a}0#%q* zhiYnVG=J4C8+$~jTHy+KPeJRaw6FcH-v$j=t!ZVn+8ACa&l!9A7rB%*dL-%+P3LWi zfM%wjVMmwIJm&LiyKBx$3V|wI;ivO)a)$Fq!LIgp0RzbR_IGR74 zZ~3s>JJEyMTW|}Y>Id!4q`a~sdl!>Pd$$}9U*pWLXlEI&fTPO>SFP#Ezf|VN_!9hn z!2=8{5&)LSa&$9H5( zVk@VgR|r($sx>*C*820nBd=KbwUS{333S|04(#!*__32GSi$dC6arPaYE3O?zX0y< zevs|{?_Y)yB+zj~=d0cB#Lwni$d)?YPzY4vsm=PH*~Xm?B2mJf&}_NsEsN+n7`dQPH*=*QXx=xda(Pc1%{P=UBIZx?W*9+2{SC%AkKyUtEEV@DuQL*; zQukDUyq}MC%|6NA;?x+9t5&#Tg6m(jV?9SHwl~j2pXr;%C|QS)z%?BjJ9kUR4o)5| zb_Rwk1gg|^wReq6vQ201i-Be7j4H@5jRdYu(b)O58*4tIg0Vr2PzY41HTBJkz1WRi ze#ZIXLpVl|z%@1+6;+I2-z$tXJR`#t0#(?q(A<*iI##gmK;vw6wf#T>S5N5Fo`Hv1 zvmH~7YMs?K3RT!X()okCZ?fp52}VEHu1Y(I1kT)&*ST^6^FO%27{9ZvLZAxUc^VbP zrsa#YxyHP-&6V~X37q$%7AGh>FL-IK@xi0MLZAx!E0jT?paXw>Im+ zk%J3g@_LuCX;vkLKo$18=$xM~Zrth1I%B$*yVAcx0!J1$+o}n45`wYTXdmpX5U9dT z59G|Gp4i8hvkm=?i;~d+2^_0a2247AZ-0geqx1b@3V|xjqe1&vu6gqgKFy3170M_X zHjuy>1iGu`c0O#0tI;;UN}vj}d(a$NZ7<%c^#gHzp{KHY012E4p|`uPCT|-(QCyGk zPzY4vjv;a`->Ag<9_^zi6|2E9f&|X!*lerMRN?JTf7hDkt*#KLLKgwm3_Hv50~OcW zV-DFlMv%anDVxoqY6U(t>Zg6sVQ+;%mFiA-`pud5AL7p3!hDq-Zb;w^o6UAGpDPc4 z-;wp4Y*z?W;eI@Fx4m=V*IQ3y7yareJN1yjnL?ZG`PxGKNW~Q_$0Vi@sKT9y)C<3m zoyV`*!Rqy>qwF|D0%ttwOz&bjc%CcA+5H=Kg+LYNTca~ZUZm&WGCyFxGc;xABogXM zby(F*e9!pL>`+&AuO+H*7cJ!-%sQ4|yHd%%_1}0q_HpOjh|xx`FCm_syslwS)@JMI zGL|oVHrHp-#*cQ4AW@L$LXS#_6*sO^fA`Csk^JT%KX!M+F}v4+7%kqTgh;>nx;FYO z{T)nyAGogJ2!PfmijCnnJ#w+0*RPr<+@|^d%pMg6#`ZGMrbvoMmSIZ@vJ>ti3iHNLgF|*dGxdrqQ?>Q z8s%?=^Y_aq*qd#6p%AFT_hz#V4i4t|;%~F?jbZjOy<#-m>EdGU#OoTm^l-Nd<)#|e zlTYmOif#GQP9acrqHBy+@!#U2P=t9`hdjJ_k-t57hk5ILa1YLv9ZxmguefO8Pv1k? zkJF+m=dY`l<9UUv59HfDBlQLLYNjp;Ehcw@3gRxIf`{7k9M3cHpG%7?yM&NXzj;;OnGb7d<7ui_ zQwUVyo+ioTV)Ggsdkx^XK5b(K#xAjA1PRZjtuYms@4^s#-p-*bZkRW6QT>AXt;@Grh1+3vj39xv5@ljLQHYPY<0p4^s=!3?r<#9v z@^$^Vu3l*t;mE!jYGue`Q8W=$Wa|=;Uz}e;arWZBk8$%^f<@(oC&0d-^x!P{f zb6lj=r9O?S$(gs^8Agy$^AvpxuEr0y^pHCrsRXKG4nEap6?GEdtmn9$xj(P&xXtKt zs5tW-8Kc#o<0u|{xUS?$t+XyiE7R6dxW}7scLwFeJrlglh&fz@VFYt}p^KSTGwu)K zi5un^l}i>@2voV!FUnnW6lGqT*C@2BIzRZ+T~5B@&hXwbzmNJHZCMRItbGO9^rSn( z2ojiq$Ywh;n(;gXDJ$0)l|a?RUr)8Dw~m7UH1CRMsLMY+Dj|oyufQ;Z1ZL}^d4_=v zdDIUFxvic`pz69UM!WIGQFvL`*s!M|_u1+oTU4pQFoFc;_oBPX+l1#Cm0!NTSzaMf z)vZ{J#veI~sr0*{6A|k9^N6rKvS(m*=j8N{QeUp8X0xGDsyGLDGRKFxI$&ekBjmN zP6~l4{5{%i7lsYxS@O~jg`Wi&{?_m}ctXZ#V@o)S>QBtKdoE%qU*2Pc(c(n`h7lw% zgCXtBxH_DFdD7CD5}sEfP_^qwjP|amquBe{yoTF{;e5!f=Eg~TUWO4QFz2Do)>9wF z!&*2PX*Oq92vp^!9&)y)B}9vx<~5e&9m6Y~e?? zT2|XpUm;MHVUo~>e)14YmYS6Mtm!&JUKq?mdi)AQe8bo+GneXXz=g^ z8#paQHaX_XP!&D(p!S!SyYP5>T~mp3EaVgQfM#-c} zENhn`a?POv3W2IN<&SDX{XIpOLFP3|JsQbMj2S9N6wc33wfAGR=G)X=Yp z>#$;{N5~2baxjb_(fLfY)})oYXnxPUt65v~vzh5e%YB10DFmttjX9zP4e}H_Kbm*d zA^&qNTbZ%4|A|C-{HbVqmb>$rK1qm?4{ zroG3?<4qqa1gb8clUn0YPth;TJV`lkvE%mdXU52#2{wjz@}ftyR+FyL@WORXy(`a( zW9*OCgv+Rq&vuL;fpvCzow%*rW zOqgZ9tG=&y7?JG<$X_=C6#`X9M;qE$A5Rfn$^1n{w(lbzc#M?`ldjwGjea_FK$}SK z%GiHhQ{Qea`)={|M7S)LaL$eqB_+y{W8@*X!*+}yaev4GZDt#HF=mT-4adQDEyx9N6_Ac0?&)@z&YGpb|=lj#d|wBuKsxNg6ew}!jeOEWs^7hHKp7!P~* zlet{{?HEC#%Bua^q3Z5pxHXH@VEsj7%7@-^_~9xFfvS!<4Q-c;r}(dzSxWZ4duY5) z7bGwDDP+e85_zla*ZiH_#Z7DWqeRyvBVc|vX)7G7A%QAveQdVah_6Nix2|$u%{xlF zgv7RD`?V6(syz!azj;XTFT>?bXZiB4(+YtqY<+CDHNkD!zNh77hHusQ%dEY$A46-2 zo6FW{PvU!Ot;W?7$EK~(`UXX4&mP)^#|-le4p=-xTYrd)lRL+8t=J;%bjh0H^`S^@ zLav3HH?L`(SF>a31nu76ns7L1zN>X}s%SS4rWHHxj^h|Xf(@OZ9T>0uIql~EBT%(C zU66L($HOD1c~7_cacM+%AfC%C*w11zCKFy?=wyzQ1$PR)!OcF z)&IQR)AyI#ON7-h67!8#?rQwu68saX!U3}}b2dnFP`^hVHjcS3Tl<$GWmn+M( zpb<61ZKCPKsT=F;FW=QQe)LiaRN>dO*?t}?Z@(D2QDl2FmgBwed8KRXbq{fWf220} zqON)V?IEsNI}SUY9;A)!_*pkgB0eF~FSG8_?&PZS=gHd?yP=(*(n9=LIF5cFsSza9 zYvd2}(pvnzRo{}J5~$K=>srU<9)GSewaRRJWX_Dn){5aA?;Wq9_WGJn684J`-p0}8 zqc}#8!0%7{2OlNbf4u8sG^sXRAy9=qPV#I&vavjGhZ#rO591g?0(;K15?7`mE6{$i zQQ*r!ju9k|T;8SG?^Y4Q@?YJ~>&AT2tT#G;?ynH2QtL$b{8L!t3O1RsMk|i(2euif z^6%EJIaU>E>1Mv%Z(g3ibB2w}mio*BhjcUA~g;T=*9ceN$^ zZ^#*ASl2*~5hSqACs%Q(oh>-A&zQJ0R3T8MK6(DASuDS6M%gdWUwLwTCTz87$GXcx z7CkVJ93E1SV+4t`Ep}@IJ6HWvw{JPUhP^xHAX#0e5U9f52mNYKZ)R0u9A(#$bP_T2 zSdhRz5q*!4o$P^c1v#@wS&k7Tc23-_HJD#jY_XYNFwccUY-^gzGRMRc3V|xMpSZQp zZFV(NQ#q~79c65QefZ|vc57D-Ruv-x&A#Xn?Fw@`U0;@8n8YxG1ond|&t0|?Y*w$@ z@^SNw90^q69nucBh~w<$k($z&nU`Y(3G4^c?8lX(tc`CCIsa>Zg+P`1kfvx}`; z$jmd2DNl}fh+{Z9waexT%mc`ysiKH-{sw!_oJ$Rt`XXFB}*9GUpk#?%6jDL zu7x!AwIW~tjnEeLX4c=~B0}5Vh5dQ*``fm$(M$Ts{d4>oMv!pXx>TDx^!N2>?QX?v z=6SZ4oc&-gJ6yZF=2yX2jCEbDAw5KN*Ushf6_LLg>2)x?sDK6$uNRMwJi}^ zNniG-?2cbKjctnQBr~49rx2)0bH2N_Ij65^5o%t;A} z`HEln&1;;VF_%@D6C!_}TEj4c1inL?%^uaCwK!5uUUn+Sv6qUy*XJ`MwBZHWpSmQ+ zqab#CSPi-UzcL(E>7sjT$LH1(1N*MgRHE$MflS2tN~aq|IYyAMKj@*2xK>MC{A9k} zj4P+I-fqpL;29MHRrqaamCP2wP8iK)xO)bU5hP0A?4fzxs3q3EH?JWFO=dr{wv*u- z-ZLanrGE2cE=5?@d9RGnsonUanh{#&NW0ZS&dU^`oor*bTI9Jc1GS;&xyaPk?2&D9 zEy|Amn`C%Z?aVRqICr2{<`Wlh+#@yoPc(C2lfgl{(U z8YfoOW1rs@kj*AHR0vezm$lhmrK!y(S1%&Z(JpL^AR$Ng()!e^CH}f;wjagkM^OLjvE6f zhbq@V;#WwZ_E2zfu%~&Ag|*VK!nZCMGu%QH0#*2BZ8qF^oX}|a4Tbi-T=njeMmjgBb>Ri}%nRk^lUx?lHvxnhzaH$FNCCKF zO23bJ^I73+J~HuD357tF-?io1ubnmj)a`MD7qdQfn#cy}GI5L`fpsN4hu3;mV`d9k zaMuTh1gfqiE!TG4uKA~})vB&%QyzDblWt3f5hSp^qPDicZg%N;cbU2428BQs_E)Gc z`r{wgCrya-Y&SsZ$snQjGD2S(Z0vu*a!R=a!F$c%I@+Fmaj39v}lzJJ3=dyu`MXb_}1gdcKVzXWG zU(Q%95396e1PLr}v{D`R7jvsv-74)!pbEzflxb@4PUgiMNIxp=7(oI{D4oN5OJ~6j zO=JNo?MR>sd;PRtJIY|Sf&;A5ju9l(vYUV3IhH9yC#$q0fhz3v(>z1a6;|p>cR9Ob z7{dq>YQOzt=wmkXLsxnKy}v@B3dafL1gx5cPcGI*hQG|k9xv>r&3@w}UeRjL;5ogt zc5i(|U0S16drL)bY-E+D^_P=AmtkI$dTI~yYho>}ZFL>nLtE~yS*wVzUAk#kr_>UD z_cl_i)@JHx-lrBbKK@lsJCiF!i#p*gR@2HMw(YkYhG_XFdjDDN8}n-nZ{4(*;d*MS z4@Qts+o+(C;k^E+T*eyzIBz6Sg)JQIl_@uj7r8srkiqx0TiHW2+Zk_bt{8g&c(=4N z+H@GNoG`;ERrjv)97te~gH{?Uj^r6Kgc=bumnsCR@R`U-KBFH$Hdq)NGx*rCZ-{-7 zr(1)y|FZdrv(^l~)A0d(+>PzV^j6Mxj39w`Xyz9k$jg=AY&e}Rq!6eYn{oQ*Cfhv4Hns3igjTe@c z<%W4N%3T$B8>pSz;bW~F1PS|;K<(;r9}!0D!?Z)eUYy6Z zY#<9POvjKwm0F9=|5=dx#5b0kPG({lL88#BUYb{o&!6@4Lzl91+l`iT(8C-Gfhw%Q z$+KN%HH-WZCI`GMtITEKEQMNAum18kbEwx>9xYjlVFU@Bf1vMi;~-n}Jyf=LEU6Hv z!d8Ov*5NW6mcMHpAP0oyV;DgK zXQ|BWVww1n&uwJd!MPOzRah3txmUn7-YcH8i}PRJ(em8121a%A;vj*l0eb@V&NNp4?ZtVwbF^Ic&D$`&I2b{KT2wu? zb*?iqTzZVnWtd(ZBv3_dt)4pO6fM>mWsZl*S>!@G8P-kj)zH^+A<+z*o;<@w{Rcg{ z|3K$W1?j8PGH=6YbwcIeOkhn6pr+$)3;&1m(p9_zTe*Jq`?j0mhwP|j5eRy%-Kkl7t8DAKyN_V&1I~YNN zN~oS%c4sX3W|Y0q(Q@w~fhwn4-Sx6LeE+z2`u0vE7aa|d!^ypaswYc(>0e&^SneH_ z__u8ic`dx9bSL)?Mv!oL)k{yUea2RIkTp*>w%j{NpsLQ@9(ty$wf?wwenwT4+0NIn z+&f`~dg`~1*RtF@0kZ@3j>mi~_YT#ldU731^H;sSYrxU`s3bt zINn)K{aMFy@8F%pPYu*ZQtfQIchtLbtyEUF8O>xQxpy#v1l}R#XV_R)8ikqV-a!IY z<>PwjAU9;~PL z_p#hN)T_}``##Qtg5~Fzw+-9PK!rfnf4RZP)BBa;3|uddj}&(R1FT&Z_M=hWns&`gApXCm!T*3i6|4aXesX<%VoKDkU-V+F}?KII<@||cMgniE4TBkmU{;y zNZ^~c*~-4{C`au~W4U*bK-Iegz4SF@YyENW#5#17LrWzYq2%7d2om^ZX$`V?Z<+Pl z6(b$Fckrtf+Z?P{&*@{ichoPK<7=qgG5d^>liWKPLBeNyu%3~|2EW}q&f)!K4;gI? zBlivxsLCA@sNbS_(ckW!-B$<7sjoK~rh5k?NYDsCPaPYqm^oB>7no<5?j0mhh3ysP z%*h}smj37ay2|am4M(YMn!{yr?lZ{v8-a!IY*j`ay9KX#*g+Y#%d&hf@ z)ZK$UE%#2gO;R5b;%T{eXf{DlUEw7Mgboe}J=x{ zw?$W6FCsD3^^y`ng65p`WY3JvM$Q^KOY*m~2LBhT)Vo@jdzr|3uZGc)o}+)(C3<1< z4h+WQ(XNH`_A7}Na5D0fA(&U&)*=#1-PeS40YqCvDd-`=%*Gn zXii^Gb!;8q@?HP7Ym;b{X`Di!YG#Q=`i62fMU-w{qr}a{`pxrA1z$IgV+0BEd+Esz zG1__m@sWOU&mPOYgQ`}~0;y);mV2jBVxaE%gZ**ukSk12_L1TLLYf?6da93XPUL(& zaeP|YJPR3JMWj2B+j8&Vy(`yH`iWnTP7qa| z*0m@zYTeWuSSa5e^xV)Ko#~;Y5n~3CXw^uB+I>n5hSqZOnF#xUKM+Hud&=a z7(s$o9rWb2Ldqxe=DxU+WtZjNK>}4+kI@>-s|rTVELko04z?fIX3(mGp83z(Bzfo? zmokb^O(*A)dj}&(V4ZKXeVy)P7$m8tv!jw%j}T54hFJifOFoFcFp6IF0%!+%O z7;Lbs<=#O8RoIuX*?J_kHKum2V7YfNf&}(($a6PufH7ydm*w8U2okj3qNlF7*KZnT z#J}Q}dj|`>Kxaq2ol(zWX}va`v)#Gs_qYyK@*xP1gdaUY_k=8xZhYG-dkR)YOP@D z;NH=b-8)n3P13J9{r2V9Y)-507$t9Zm#?-qGgkrhWPcK^0_e#epOH~p_3(Pt|M-1= z^m}L=yVXk0A}`LBnMZYZ+8<$haghGveN-<+yHb98arVdDG&*f+B?plg2O~((DumQizT6U&Q(1gd&gI;xMOYy9@&d=s%o`n8>9z^tZ>98G%iekFX4vcHb%|8?;E z`e23I~-L~Br{!cl1iM%-2=fu7!tvczczP@$rALA%5Z+UT0_5G66C4C#yi=z_3 zw{)Y_wJMeu2O~%v9&wt^L;HZ4n~m3 z6>&sQpnW>Oy*Oo#UNIWl8_2Qb#X$m9>NhXfqO;+$>7M1qp%q0v*{w<|n0m51c5OLB zui@tT$BQ%hK|f>Ix){rggAt#xhJK#*u9#jN{7*D^x|LyiFqdt{UPm- z`|ZV|=J>oV++lpbEb%IRVElHvHS=vb;DLK_b9K>V4aL{_)~m>>Fh?pqXmZ zi-QEJa3o{1-M^FH=;^x1^5S4${p&=b523wwrWXg_o6S~jRAHmVibcjd^5S3wi88Z< zK8p7I{r2L#?%`$xG+u9caWE3_Lg+VWH=yao!T&_gfrECVea`)s7Y8Fq75XS@*3ACyYZ&vl4LJV%E$`|eCw3c$-9^lwQF~> z7bk^475NVIR4-106U~eUuO1|OaZ(~k;O~ZZpWWzS6fF1Iawp*bLKXQA^i(fSo5@p* zSX#j{-3b^$0)IE;?4LBy+-awO_RMiDFmv>cc73z^T=e~=Ey>SouJba+( ztVxL=q4qL9-#Tf`D-k4b?QNzIs3I>;O0R~JW?$JT>V0Zw9O*t%8PQ`2$59w%$9H}& zHdR?+m3E9Ef#r?%pXbVG%&NH0D(y(13P&>J>_1h-xc(}}D(x6S0!t`mj{Mulcs%r{ zC_!I(F*z2b=6#i~&WZXa8^5VSt9IYqOzFpIc^Z8q}KAZkFy*O%b zsaf0;ngrWXg>cG^>~ zr|!HjTGxTUpW-hIlNSdgNT_Yp&Ig70*=0@SYVzVBfhug_Y&Jjkg=L@ERqEu$p&gle z^1e;%0pQ(IPp05kHnu@m=}cZ6j39wM4q9EhmXW`k7a+%x7Y7Mc;WJSdkI!eA?R}^; zy*Su6#JhH|zu3ex;jyO8aDIWIi1H)G-QBe`B^AGMymKl|h9 z1Ntc14{o|%aP&girn{D6u^UIr9^~G^Q4#iv)oWzD(wK#$A7#0BFoFd3uPIk?Yy_Ki zd6+yy?j0mhh0jNI`(Jt4KTXHTedNW#yFyxhj)CKAvZR}%WKQzpU<8Rbl@I8v>0SNy z;w)I>!fMOWmKO&JRN*_c*{UqfYH!zNtmVa_-S&F&{(KyH;hQG+XW>bDfd*qOFAheK zz>yx!q!!3#Z_stD%t&4wBv6HSOBomQUi4`YI96^XFAm-nWfRbovpC@OY_^@dJVc=n z;WB}|I2b|VN6%=zJe8Q=UYvA!6U70iF_sqx2~?@IsJ6F&@!;bq%Zq~%Bq%q8o|?;| zRrdNuy-g!5FAfr@!Wx{~+LPyvQD1^&wSuLTni^~8cC!xZt7zxF>87;VPIf(L)T`b{ zMx}RV7(oK(A8fYs=l2*L5B9a3HAtX}GLz`ZxlAY{P{MZOz}9}2vj!tbP(BbnHMdCZ z;v0-5&BA0&a@Jr333c|v&ts-BJ#4V$tU&@**uqg?w9YW&zCP4))?fq)oIxU=OqR~Z zo_516XAKgl!tX?DUZsXe-^^2tds`jMd}MlZZZpb@q$lSfqYOm)uZk{W`2aJY{>MYZ zv^@I7JWzeZ5b=iFUn(5^Q|`}%EmR$jG~ z2ojVrO^>_kB63YJukq8-U%pwNM>ZR3Ce6`+(vcl@gd1NWS ztiDon5?ODp*C>;#o|+-HWmPT{DW_~c$|;KxBq$55KB=pd*#3Myz1&nXCT=|Jl z;R=B&%H*o2W{549v!0CX?8}+dTLhS@%!7$ zCvlm0+}PrFj3AM@V66UWmXoOa)x1Vw-dS#>oU&onswo7jD5tD`<$#meo7Mb%xNjdS zm$aYGYE0a2r~IpWJy&Nj)nkK3Sz-0$tk9G*RWIP|EG|?uiRR0O$~*DXS#Qtnc8nlF zSzYzie6OF243;yS&>3!Z)+z+529Au?|9VYlNS83LQK-)V`R2+t78SX~ju9j%tE--x z?{!hxesaqO!Db$sp%AE|oT>VuSSNA1n0bvM5Btgt#Uu+pKHZKHBq*z^o|^Bq%Gppk zsqY!)xHCc_P(}H7^@kUo#H@VgHFmrTkykvgvS(FC+A)FzWp&k4^S!3e9w8=o{QorEc;XP%UcCVOQ#`b1b;FNER1Z9ZTlk-+nUgy!>WmLhpEZ4Fo3V|vtZ#G++ zMoezlT1xs4cV}4RP$o~^E2pbiJZ*!f);?W$4cVz(1zG2Je$kYA35lg^Ug=?ZTtzg| zH0wORx=ia)QP#X?&A%HysFch?KFiC4t!%m}5hR*5f2H$kuHw~H^Eql=FCkrX)s^vI zt&F`X1ga?aub!Oym-6XPDI}L=X($t$SXqHnB1llaU%hy1SFyutarRspF4M)eG!~4_ zYi7Vq>FH5!OFcR3rP_zf^KOJ}pM@D~$K^INN2c`dkf5xUdTKsPd2EzCpcgbM&Cjk7 zsGPH$xjuc(PPaRvE+1Sh7lwv2c@2x&+>KoaCx)uB9W_4dWAq0<%HBz zPlIx=5-tOd%ol$(PR}rc1Z9-eQ}gNfzY{Kd?$08=U-)H50#%f2QvZ+6sEV@AsJiJi zRt{=X$fsJ_PiD^kln4@2=^7U{l@Pm6nPZ%CImgOko!#t>ni5=e<4LAmbrFaLJz$)b9Y2LY73K2RlTQPqo%c&`zD1C3JT>W7xYaP5pAy9>FB3&bYxQt!?kGChCONONczkkJ>vHGP=&f?-Vvpv66 zjh;N;8T;(#xfp(1eA6-KWA)yBoW-28CXuPsaM|s9D9bkehw|k3w1@Y{>c=WMix|Ts zwyX=2ZQ5;PM=C#1T4!u`4=jq+@6eg|rS_Oa`XfPdLVr3DA@YdQ4q^*eBP3Rze9B4u zv(_Y*4LqX{7}H(<`fMEE;G3v_IpHXB$w=*N_e8y(aI`X5IW11qw>@+e$E_@Br9Naf zf>!Hxw-saf;tL6SmwZlQ5uK&JYFmQdBhFF0zZ|Kh`IVqAz3C{@oHD(GMO!+^tP8J+ zOlO<$q3sj&Ep$qDK{_RS`^W@+Ii1QKL8o%pFO;BP^l=vJtnv6k zh}6obd9CLu;Vd4;uhEJ-z1EYsv#7V-%rlYqN)Z{G?XWScTs8h-Yl428PUtO9rOVQ_gdmPoA)$l1%uz#28VoEEf;r^|W-}?sR&>615ZbC3KRm z|82@()+9l9JmD$Q%nWAz0KT|`f2 zmXfu>L*(_1BaI6?Dl#0!;|#)pBeA+)37R!{U=m50Xg|*NXJW&;l1lr5Ekm}evHG`;u~%HDPHfq)h2&j&GD0;AJ<_SI=<1%O?DQE z0jso|RbT5XUB4Hr?Yfk|9{Sx_#D^OJpd*I^hzqD!$vJ&O$aS_XG<~1&z9VSmNXk|RDQeK&j!d{J95~p_@A@}Yp zYFr%Z%P@k3S`z&thRTyoosD_r2Py=r);*!GS<*!uZDE$(+6jH-l{DLpXT_>8oE^g1 zDEy__Y_rP@kcWfAj43xG82&H(4dUHWeg;l^Ag4_?RwwpX?g|O@8j%SD<;Ox(jW$L- zg+LYlnrSrQIY18Iz1)~l!&CX4BZ1Fkv*{DVWZ&l*jTd`2v-Iy{^?|RP1#i1vlO^Kx z@>EK4Utgz{&K;-6m2we#PpzYOwJA%e%+jZtacRXNh7lyH`o-yUU0p;qUz7OjL@(L> z$^^q}sZa=1t@Mo3TX%2~=gXSJ+0D)5vF15svvc(r&fMTk(ZsKLVFU@B%d*)D7VIE{x4tt%oqH(+s?=KauYhi{_u|J!yw-qW1PPpzqioYT zg5}oIM~v2`+baaB@Y_&(UZS^rnpqkfpH@@qb|i3ak@5lb?Jd2Q3!~dEl|U7iY3lWP zQqAL5NM?1b#j1G3>Zd=rh;EMSH5`B9TesP&$2OMvZ{?N)t9MYo2fk_iPgJ+p^OJW< z<(2zOk5jIJ#Mzy(`l&bjjcCziaZN$(p@vdCZI3V|xeA+dTwK38#Yqe*OOQc^y? z%w*$DHI&u>M|WyXy=RG=yj#p$PJOGkI7s05lXlCtcb6BxSCwbewovMJRH=70uWwbE zc%-6ScdQ=62ogAsw%JB-Z|Rf1jGWLlKp{}2zTNuKn(SDhw9M7bS9w=R;Cuji=;zj! zODW0Zizn(gM-_g5+I_}{${}~Yh-*(KF|0YUmcW|NW}Dn#fUH-;&FGSErBWv%fi(v8 z!WZ|IMXnDqip^N25U9fXkw&S9gJgw~^NgE*e=&?8q1Gi03-pw6PX8Fe_7w_&D*QFm ze94MV@=V`T#=c>jlwU0peW_703!l5@HU2HrQGN?-Z@7(n%P@j{QS77Ao>AZKa$1%$Mwf9h z3W2Kd)^U2?IA@W*jrp$jR(6nse)-8KXBfl2A@;SfS3{>qyeKMXtg0(}ziz}Zf`s}z zZ-3H7K8o>?VdI7<1gfs&iPy6naS=Q1X1{$McaziqswR6)8p$w%1pbHltU5!;WMqlq-v>&m0Qa>#N2tz#HL0!s{?IQ5sGZ1BJ)=T$tU5U9GjHBR>(?jq*D zHLtO^VKdq3aiS68y`NzO2`tCt-eyecJxb*a*LZC_=xmhpbASR%`@ccCXMe?j8*F{DI+f=u#ZA@Vp0!zxM4lxT>D!J zfhx7M`=1YyiH-$~TM?%iMv%as6Zyg)w3OW*HZc}m$;9zji=#>WJ<=KL8=A;jFUJ{0 zA7$ehK|&pKrpe$hOPpD4ba<3TAy9>Hoz{xRG?3}N_8B=t(sPU;F==$XKE=gF%(dnK zs$^;;C%?a7%#2Dy%~ z_BZ3X&kcn@75)my9lh2r|H+g|R!w(9DeXusX&tZ68Q~%}S~TQ$b47EP8XTKQmpYebL2_{W<1*Y(5%r;XEExWIX-`M*iCxId@%x= zK^LN@gu7pT;}Lo}Irij3AM}exe>tPafoD64?`7Wmu%M^#Afu zAy9R-cA`E!n~RwB(j29x8&XhauisFX8()Xv_!URkI6}7B+Vw0f+a0SX*Y{|rjGd9d zwu?M>ZpCQa%w?Z$lNAD0b-fey^)!ykx6Hh&J-MA_#H*U}%-z`xBS>J|Mf0M4o#ld{ zDsu9LtqOrE^~pE7l$FK)DlfBd*v&A4gj(8vM7l{a%tfBrd`=-yh2M$JmVH)9{^(Ok z_8D?f`5s8%uZvb?0xHQSBBxwXK2{-6h2@QMG&+098Iv+dM~6g)5hU<8Pkp#CRi*#W zk4B+<8I+QUD&==$o3Y+o2E2c4G=H5z`F$XPbr<yz00Q%sKVbrovzYQ zlYtKVjoVTAl;1fLSO?R|avnA1zX>ai9P3Ib#Q)Lt*1=UQQM>ox5FltskdPfbga{5{ z?;b3;1rHV^5FkMCAi+K8!9BS9!I|j=1a}GU5G)1Abo?m9q zOixcwcduum3g^w)>*lN2Qnz_-JMm*}<7$(wRdT-3&HHfKgR@!l9 zs_Opt#*)U~=ADn$+|rPY1?bwBUUFj>g=bgq2NKxZ@p!j*0s7XW7%k15PRGB6 zs_^FTj8~(*&BFz)Ui40*LUjLgL3&y{vyKrYun*>HQ0ekfwm$i3?7#UG0#(65?~D#% zJgeT*I!4p8?sR3j3vFHQp<@IIe3xiirx~tP-Zc~5cv?~+P^GQ{)Onnb3LW_<8=vyg zF@glXMY%6|orA)5J(F`MS5^pA;R*!jZ7<489VVQUrF&FU)+UfpRvol!fAgDp_zltW za6`TS=Var4ADg-A$QrxtP_i+nuFdRyc#XZhONz0-n#~+B$r^>*!Q%%im|B7OB|a(08jAMJbcJ2_1SXbAD=H3huU%s?Z z2vnVDm12aG&3t{xB9PXrN*z*m?NTEi+~9PBUu97#&wxJ>%1inBQLJ$-Qy*8$HsD z5HFkQ=k$8{9b7{Gb^VdKpv-6;BS^GboMw#VXMXY~>kcON>?tqRK4z{7AE6Ma>JpG< zoZ`KMkx1Ga&Iuoq^jqEM4j?!#>pRE=Is;KdE_1b#@w9bYqlvmRyhw;;WgxH zX<_Tl!4>k<_~k!Nxw=Ta&Xi_6PVh1V&REB|{GpavVyCM;-F}ro6|R!=8)x4qnS8sM zblmNr>kZS4pC4@IOrEX5XTCtOG{f%#uR(9Lj&XI~OQ5U85_m9I3n_Lx)FF`^f~lxym)F+2X#L&pdbYR|C9_p)?*UfGNe?yC@} z>U1I1Xg9)UdOWa>(RSl)8S!(1tXDEjpK&nFSe#%p>$i`y<5ftTnPzCaZ05rW7LnWU zzH}+qUe>MHO~(ilctzNMH{(h9t#noSWMFTFK$Y4Ocdt1uwVT;wxpjSXj39wmMAKT9 z+#$Wz-ZV39h*Aht;ZwjB^6u@HPapL+mwb&EuZ_V zfQEE`v!~v;RZj=*T*aNTVPD=FiT$}&{5Wd`tBX;WGSn}wpPCuszz7n!msiuwTtQT3 zL4ba;k%t2#xT|>Kfw#t@dNy(9;2$$k!Jq-A=?Ax%#k>E z=&cc4pGN@wtzT8vbWp^c()z+X9s>Uss&*7fGF}b0ncX}rV&=Z8bk^5TAAHY8pen;v z-Yvi*q?x7G+f`!s!pb}=;j3Tj-d$h>iS>Wp8pB%i=q%ov*&Z{u8fEQLT(8+KRv}Qe zigytd9b+>q@3)AJxysY==+b(gLn{SFkhtWPWQ4c3nRg~w#I@jx^z>X&J?#B{g+SG` ziAl!d@jOm!Wf6T#mZL8}is_E}Cj_dpH%u~`hT6=6b=TQdV&;4wx*BfN%QURHZ$~zMFd8cpoD6!S$ zd)slZHh-;MB~}I(q~US7^rP+a>KH*H_-T@n)|SU5yirg6KPSJxu`JjhKQBfknQldnRcYRQ^p zW9<-|x%rPZlCfXRO7*pWg;#Qbju9kQ^-pFm8=HCUt3|Ban2}_rkD_mhDhh$B`U8@U zLre%K(fM|FYWVLPaqhr=Wj{6UlvekuEf4BM4*PF$=SGSHBS>H$qiG9+I#9YkKg7x6 z4uJ%!^2|&!W?r+IU#nWr`OuiwwETAleW?*DFoHy@c1gw6+Er%eyou>7nU0>Z}$RL1OacB;)vIo4MWDGh|%VjFugJE8>oj zLZIq+Qj+oX9$(!^>lmJ;8qfpnv$($DlE4TOXO3{D#dgk6=w=ZGPSm4b!ybxG8M*k$40YOZxheHR@5c}b; zTGEtOjVqw*PtGW#3?%S9&zZ%in^4HqeEPo4z5@Ris_=Q_Jjm7csOI8=`k&PL0wYM^ zd!FkF`!=8-BDel==5&QX6+Vx=#jCi5HaVP|;@Ojj<+qW~4`Q?$Au)?m)4kDqxomZs$A-`XIE~drQ zR0vez+#=^2yctSMt4$a8{XQtW?hEry;{QKKP2Jxf)_o8?xV=BaDfpdYVq57V+L=tOI?fT;@O9; z?Vcl|YOYiWRP{-hY(((B@X3#@x7zla;pD%5m2myNRbT{(H$3X=lg-;~de0(0yLP7` zb*G3C@6IX&s;X2^dcWrrI$C)T>vI8ec0f z(j6+S5UASsBiTr+iz6!0;31wONH4Er1POIU`0ICnsxsoZ<6`sb3W2KT zalGHh)7uPRY8~U!uhP^Y>8Zo!sp}X)LY+^H`sq#oj;-$~ayM8ZP_^)Tit&Y8Nm^6u z7}J**q8q2iIp+0ktYZWToWJDRTGu=j`{#{)-PM)~fvV0GQjKhvd0bM;I!4@^Ow@Kq ztYhccP#q&k;H)awgS_xwj?XpFF|=Pdg+SH$h*YEe9Gm$lqjik@oy_ zJU=$i?U-ZEgy9N-D$Jqb{cxW;$;@@Kh<~<6E7>(js5A6?x0aWQ?wQ2&w<8q-RhXN@ zo@Y4{<)#D6<@6Knl$pD0kJ1cJ&LtXBN}a`Huj1t&<&00O<%k_Em03#2QP8x3=BW1cP zd5ml+duLM#RN?9gf2EFequnlH@<8PVI!2Iaw8cJG1=;heDw0{IL`xrKz`h zF~%Y$v=1OZnN{}aR8_|a5+2u6jN_c4)IHQ9N}jJwlSZsGhXqtr2vi*j=VNs8Hhped z#LbWzv^h539DKT*ju9jpMW-0s=6ai@_FKg7F}0|o8@Hd9r4<5I>+_`;r+RaSTcFkN z?paWe#vh9|Yu>Qw7(wD}asG~4#aU1VETZXvCba0=#$zws3MmAtik?q4`VI0ni!QQ= zKW-s3V{x)EW?DWSBS`q%NjBzh_BKm6=VU(2Z%Z$HuGwuPvMU6t;-@4V_l9#X`rA52 z#_Ju(b7YRAi=JfEF@i*{`N_r*-WxTMvywEe_46>=Qn!s`+x;&B2~<^Tlx%1t`40BC z-nBkQdQiOw@%F-t-wKQ%VQZ6YJlX4QUhiQMuN(KK_`ORVwNKns2voVdCmVO7z0Gk? zEMoD|NE(*EvZH?Z8G#WbT)dNwvwV!K4=rNR-%<3WiRp;$zf&Pl<&m0Xv>M`Viq_Wn zYRUe=)S%ulhje-{ow|jO` zf1iuMJWUYVe8>avF#(t&Aqued25H#N|3;jGxt|| zZ)(5PQ*0h`P9ac*PXT+e-s?eeWowA>TxSgE#Z=iY zeTaSU-R?R@kid~MuSdPRCe5MigPt7hqY$XV6-+*lUWa7A*sKo!hXZtsAb}%iUP}#J zCNs>PYj0I!s6wDhT^XHVi;*rnf*b*NqjiiRp^mBhZ@0@mWa|K@{P=$K}I2XBk zMmZ^{iKEzzF*-(&P;=ZzME-3a4i9!LJTz7zP=&h)c;;?UKMHp@#rAGD6ki;4yun!t zo~_N?o2C!DET)djA~1pku5xJF-}`z}wHfEd!c$EY0#!Im!8usdx{@*KuJ{?dA zTo+-7rUqT9`R|jWW9KCbfhwG(&@}J;9jGQ<Jv(jN*@tmrH=Es?FcJFg(##P=&I*mOpc$Lg$pqx@}svNsHO2-Hi1tZ=WVf}dB zxsyetPMs}lm@{RgmyrsAs`=m2j0Zf6lee!$RGvOZ`WYML&9M|VzGPNSyle&e(9tW;Q!%ok#9A zsq%QUZ*un?heDtVcQk9-*qP5|gUngz-1h3q&SfM96nbyOCi4B5YaL@vrGMqzSuRvD z+Fv11g*&skhr9bx9{8T0njJ5r?7&7stN-5U&9k*Hs$0jXxHuDCY{1nvXBJinRN)SD z-aEKQqq`Gr6x+c=*-4H>+YaxI&bhqJ+4-$wB)Gd!R-Y2Idw+I?Ko#zL=k?kOS?Kv` zUz%*sr0j@CqW{$Q#@lk7SG3y7X?R>XJMAu7o(4sJRI(sYg&7fijM7D=-|HeW=i&pd9ve|aAhYT68JRpUe2uX zGUMb0GU;tsg+LYVTV!|q7H4I?>igxnH=)YBC=&QI^E+zt9XVjhAz7tq8-+j>&XMx3 z+VVn*h^z9}#3njMkie&zXIN4{%O(>@mh@<>5U9dAQcatmDLn9l|Icp#9h=*BOB-9Lr@g3c0y)j?@o>5yNP=#}( zJZmtqFqIy)OwI|h>li^o$#B$i6fQ=N4x?qQH#HOjRX9h=U-TzR)4nBBli^o&B3zg45kO|bI6dDUJ8LKoFnBL(v=%h$)3gKuD2dK zMv%aqVg91;*_?Kcxo@_cpHCrBg>$5u=3bx`t&7Vn-Ja&qF@gkUHS<3GETOdV;yN>< z$gB{k!Z}iQ;1A}t)O`2Nw#EMlj39yT1)RzHrW;i#6mAwR`A#8Fg>$65hviT>T{yPW z40!ZRU<3)w=Vq6*AARVj%wzugbVVUhg>$5u*1ml|TKsgnxmlhN7(qhK4R7Z)h{DIM zF@Emft`MlgIZ{n)mTd^dzHD!no3~nE1PS!#;I(bPXxe-`i_xLn6oo()&XMw5`0^3t zKeVFRBxs<(2omTZ!aL}ukERM9h0M$|gA@W)=;O!LRlH*;sreFfMi-mn@P`C?lX1PG zLO0A!%{Q5=FOAVH_d9QP!LuCjth@~C-D~A$-27U=ys#p@Gf#teK+JQa47nRnqJLLW zWAi^oB=0G(auhLN5i=3FzVm>RbmDaoS|j5{>y_j9@*)yD*4Hk z_KJPH4*!euDr<30rIjgZ{TfSU{e9~={}BnUwP{O14{Bx35Ewzi%D=SE%Q~Jl_ga&( zT`Wo!&xI)js;u*|&g(y-Yj`0V(4j6(YN}o^o^CG4PD8)E6Dd4~8q8y< z4m^&s@pwpXHOaXBe*`E!90B=Cyxi0p0=dg&0(GsmOj zuTt;Fp`C7Y>b4+{N9zSfkig7P?h}jUr$Hy}bba_fg+LYNdGd(N-=CJAtw14TdI-GF z*kaUszGX#eiW*gknk=3vFoFdBT3%NxW24P}fz;L0PzY36SJt|Y)|J+@?^E5#Ke{q) z9DYGy1PS##=JLJRwyhFnTJ>BZP^FG{=knjLHI1|NhF(zGF1AX%vpjnqQ;yO{7opGV z5|n$6M8&GEruFZ?^H_Avi)?v4$oF|V9sd@pHhH+3*1!M04So*JM}E9-`<;JI9V1B0 z9+kmt{@wk5hW5hT=B(z1RQ3jR}$GR@7PBY`UXredF>XZdN5 z_Ezp*T~4>IxpnQW?^o+P*81+W{%?H?THkK}-SeTTZ{^@ghvdCJE%a+VGf<0X2;TGT zfc0%|eQ{gg=jK{>^MZc{=eN41C1v>}bLApg`E+9)BS>uKZ}W5fjo!fdeSSP$2AW;3 zG-bZ*s^jm)FGxH;emgh*DZ>ie=uN}I%9$g9-?+R6>G4f|+gE@RHk*Ra^+iH>oMl8{E?829xV@22vp$=0#_yZ%ZL2gn`+OT3_AAh_&hqF zCVr~^yB`ZH6{U0ob5R;UgBU>qpG_XUHqS-f8fJAqgGiw2@rRtI_3yvAjGOb*Q_%xi z$!aASK|;AA+F7rcvf!eh@@RcsAy8$t5UV{{ErxTE?KfmnwLjA2J=+*TLcLb4T}i&r z{7LTQc7+70a1My~m;5>-xAa{hukP=nf9vON7Ei~mooCOiSu|_b%lbdIX-#Xsc(k&LSITIP9NUpWs{ z;Z^5~h1>Z!~TE z=>$1$&n{W_Zaby-!F~nrtfuwpZ%Eg$ZE{y#^`0X!U{Oxf`uE>V>ecUyWbPt!WbPV$ zl~#hP>|Jx3)<5eP@@mHC(K1h)NzU`Y2ol!0S?Bm4@pFB7Sv$U#ycrp-BY`SwJZ+7u zt?@OFeR6M=hw9&x!|tdp5$8y;jcMAqJ}czGf6vHb2fFAOK?3J`IWz1>tdu|Y$PyoW zDg>%<2AbFIK97~Bs;`ixMn&ov!Sldl^GbEwnX>$xrOvC15hU=sarW}2-Lm@RL(V&h z1gfy*bJo`Jb8^XCDcA8+ixDL7{`1b7a;fsxq1(=95D8Ra%jfx$>VITY#|^1-e}xew z)VEsyTiGb**t@bVzYUN;6~1>lYwJ-dd9queu>Uk^_1x)Lobqpj>Wu1fdi~l>ux1H@}wx_Z3W7t5Ywd2YUwqs4} zS*MD0+Ylkc%MQ~qf&|V$Yg(lRg=CE)cDZ=V2!%kE+B5u9D%sTh-Q{1Sc~u|!3?y)l zoZS}qYd)C2>euoYJrbx=9R!Boij!kfCOV&5?2)mr#TLVRYrUq)&R2*0Uwu0g*z<8V zM=4#78(hiRcJXha3hxc?vY3`vp8eqNY`Yji0?&`vSh$5)EyZdjNT5o+=lcpbGgq!2 zWoG5JixDK$YjvgkRO9a5zl}cpd?0};tSZ1RH$~fvO8qCx=oW+Yb?ij4f*na#u^Y+b ztTwYkiBu!%bDaG_0h{^H-4vsV)8+rW|71t|LATjmf2@9Zp$_JKI&^nh41d#c#SyXbaR z{OGW1E?M;%th!77T&ZAhT$0f#aD)8>&p90AtdXo_?N4k|-d8WwqcYW{ULu0CZqIR6 z_hio7oYmZBPE2@fv@5vY{%p9-T+SKgOP$%|u2Bokd#7ttjC)Bvl=rqyKYc6b={Dzl-89bCeG$U7AF3o9 ztxBx5-{tXKInEVcu)PcBc-dtDKq*kP|YJMEQzy4t>--4DyN3t~lJ5T!yb@j*$Xnw=>vKEp9b_j*qz!LLTt}m z+&n*;YaFDHv!Cah04`h`;LVBE_IR!daN~8danM;8VEoAj^ug1e^2OH?TWnnUa4CDv z$MZZKd7HV8yfdaot+cnVR?Hm4?)AFUxxRL;niTcgouXSV5*OJo?^g9RqcVHup$cce zcqe(@dQ|@z&-dMp78pSSkH@ply&6ykUpE@JB1|Drh4W>cYZ=v$CW``8vVR@X{w(|W z4rIsKJgeK8NpJ=2VEr=R}Hj18&u z`2uuhg-W0buOaUpJko$#l<=TY)vJmgTyf!R#U$ev@0(u1^@;9%dTS)LUu)l6g=-b9 zPclk+S^L6+Q`s;4zB@ghURA8`P~40!^wwCJZG-&?0YuL>3P<1YaXiCB?E09UqZ(S z66$$WIa-aX-!DkXUw1359oz9r_Ok5Fo|ZeEewI&Tt5c3H`RSh%QeXrLbtZKs`_J9` zCqG@Khq+E-O`utfFHCi4d;$vV;4QVa}Q_;aUSoGkc)uRJ?rnD93Oo6~tg(A@Wt}`+VW;^VtG|-V z!eqDUP3Y<1TslUOaLHH9T%C|?yx{6O>{)YvvV799A@v-h5~vF0iamq4a!;(YYR}6- zYo&KUJ1RQundroIEBbT&3cJrb`&h2h)0(UG2+y^4q*Q4T!A-A~_PzJ6DG>fYNHRd`(z1Z(1#92!y zbx|w1f$P59;hHa2C1b1VkX6kXRaU)XtD?()HH+o3!mVko zj>yulFy-aQK6GkVWq}bSta`;(b&vmQ7U#-I@&xBRcjAg6NT5pnRi(b>qYv$?Q_&O0 z1&;J^l&OyTqS%9e^z#}-N4E-$Afb*$XACPz9_cDltH_lKfhr$%-w$IK{$j!!>DTe~ zpq>5==uD}a;uTlty~0&`tqQ%DxH?IGu2OQ0E0kE3fvw6U|5XQ0yqlX^zHLl@1$Gb^ zL83KRh>7J&G11N{F-t>oQg5y;Q|(-^LZHg3aBNkL`LD{c->OQ~q914L6|63Xb4AUW zTv^kqs%cfev?_X7)i2et&*ldW$SvN3vT(&ItLCFsUCOHah$E+9t~XhW>rTFL)|~th zP?ugl^Q2Nf)dWV6P>*r=hM?n(N|4)nl|YqMH`A(X@?Y)DeV#$|bCC}XNUJ6=f&`uu zKOdE<(ACt^bZgysf#Y+$YhSq*%d;U#Mx9MoFM2)3hoXyDq~bki2#g?s_n+q(*i|L! zvYloxAEOYc!n?`&wFUA~w;jQB~=4buXGa zyEct^s^>Z263gB%g!n>UCtel=YNJ#?9wd)BS_$Tg}-rpPs!t9U1?6kMGAqc z#a!jD4!=<*h1L|5cYS zJUKf}Yfy!5Zhfwd;qczzdxdwgHvA)>53fmu-#%2{I7r}CXK&nyjO16KHsx)7Q6W%; zZy)~h`tpx_?r1{Qc9Jq*f&^Z5&K@}SOCFrpgz_}pr4XpXUV`1Mn!SF z$Jr$dM5FXoDXu_qg+SFx-rGKyy++zN-AH`9#EPm99VC4{b&MckvOmhTdF-d>^hk*~ z(^9lvU5BE^7f}dQRpY&1b@)7nPqMF0KeDu> zE8o_wix(5i&@#>* zzz7m})!Bjn+Gw$9fG?%*#d$^Ww@@|ryUonW?%eO3&fH1UBgL>46=?Y$KOG}T;8o`x zjk$frif+}&y-PWTK-D*PpBc<9G;N&@H1}_m5S^FRrjDh&b&MdP-j5|Q_Z=}O8&S&B zf(n7EVS~KQm*?2Y!0Bty^=)I>rB+uOne;(oFb*wbper*xt` zzpCGwm&U<@!8El}aUCN_sI%w4-dwd;cDw1gfxK;l5s8XN7x#Mp;s=aJW<0fa-F@nTnb_rR?ZXwP7 zSob_*h8&K7t)WzFWM+jx)hM3pd(0kKuboaIl}3-Z2bf)HevZ!qBS^g1>uvsQ&2P?d z>wetK*wEDGgwv$DFBJk+?#aBnjfuX_ntC2}7MVTb`_PRJmjy$oDse^Kxx6-&y`{Cf zw6Jq}IjK(r+WfY#GINK|InK%Piu+%=<-7gONw1nm#|RSG6KUGK3r(cU+m_TRK8r%2 z3g^x^^QBN%S+`nyD&zY@nTJCHdsKFtcFdMx`8v`pkEaTODjdUezx#cvjL6@W9?!n2 z%nl-feLnkN-I*_6F9@fP#$JU$6^`LGt;OB|eWXtio&D0$zFX()&y{ZtzQgtvb{@Sf z;+cs%>+O@dCV=G(zT=g3KW>Eh>!n6irz*J~I6~P=y9aw}XBe>F{x|!B7hs?8zu6=F zndL{$zU0wPPx38${Pn>m_5Unt(oOmFx_Ta{-2A!t+#)h zWizuCNHT(dthe`Ickx^7GG5>>>sJM`ANg|jC2zH3sRJWOTt8$pEtlZ^F4oN55%v&X z#9qQt7gH1hRg=#08g%a@BVny|jL=CwdWW_;4R6)ifxj2851t?YDt2Pm*^xcZln~|2 zkqGHwGyC6uYlOYAjxls|VLivahU8vRDg>(V{5bz3p@2^IX0$kDta2VmROUC1<$`+R zvvrJD?5diL-BkyzouLq@!mF-n2df5%pP^CYS};zuWDg$~_VO9aK0cOb(4PXy#&z}$ zD#vb%&DnLaOf%~k7YjERqdP`Yz^NSqBS`dO@5B)HP`u&vPdvYOj#%K;hoZ}`R0ve9 z=Uj@4yyCvh>CxDD(<(8wPB`62-YPJHL@#z*yvE-m%bbpj|7!7~VWY0((rk%JfNC1M zK&NLn=)h{$d3-r}jXfqi(2JiN1V-@hZs3gHef+D&I(?n@U-&4F`?sOMjq?-&RU_Bh z%sT8J-P!3KeZ7#T_s`LsE(NX@7(v2d7wEq12K~|L1bv}qZhdFD26Q!Mx4)I3%pP=)&(G%dDjX+8E*AT|E9 zTG;`C#54Aw-(Nb(Xg$<=8{Ba9)BR>urL-V_f%_z|U%_9?eoJ#p>xqVgT3zr^ew9Kf zz0as61$Du$z5O24R|tGk@v5^+Gkb&uvor9F<-W?*MM8ZBm;TA1XB*R+UTzIl2vlL~ z;W@ItKg37&CBIm}p|lbt)ZV91%w5rIdROYzvyVcc3ZDW^+rge6&HnC5?+-OmT00VV zf7r~u3zLlcd#%>~l08y=I`pNrlZPt=s_<#%N=@v;I`-TEO8gV5Jhe!u`(y;WOpRPL zi25`fuMnuhK87n>znkk=H*5sSZ;_&JB#(;N1MBY#>+RP!@hbc6B;)hV^>)iAY`~W! zqm9!mte;08(N&M8_wK(PxMRnU^OY>utcm*n-o5j&TWxWSeYUDrE-CPrAc4nbN7Bzh z;;?NPt(Y9H5U5hmV@l0C4%f6{lzG)8r58m)J&(9~XB^=PgJ|KXH41?$>`~cus8AvO zRfpo_df~IcZ;s`mHnU65Bx7LVb$0wt;C)N0-1W8heaYK5QD6j#1zZQB>qM@j;H(9) zDmAOVDykwKng5SMpbEbe*eQK#Mm=;kXR}UwDKLUW1^!}L%U<-0oIdnTHop?Hvecwo zPrfPys_;93y%WYh6lKrVqsmi~1xAo~e2?p)u|xh}PIvse@rT4Ix5i{%{HYMA!tVsm z9%#BlJZu?4**F6fBS@5CSJkKacogn*>`mS=MU1M~nxeD+QV3MxcLHa!<{2zz-3z7u zw)X-fNLY@*`6?wFSq59ZXlTJ=qFU3A6w~XcLZAx26WAB$a%OQVPgg1yoF*`WM0)ld z%+20|(&;-`@8=Ll-0tqQ>3y<7pbEbecqB8kprdH+KD74J4S^9P&hZz^dt0*6#pxng zv(H!KP}_dgsq86*Kox!`Xj<0D18Hls?E)i6;Oa8_I`_{YvqcP|Z;n+8fhzU; zW42jb_BlC(Ha40fFoFcGD6?M%*RyEBbuIRBO$!`NKDolX0=x0rcD@aE?1S06ZNOde znR?OLxZ@6tAaOK_D=rM|%tk({VAmQfiZCc*m zm;J3{G-R*vi|iTh7VtqKP=)(1c|^8lq#PJAl&0?VSM~wmUPbkO#1xq(Md~1OGlB(1 zkia!>emh_7FMGxgqVhimDFmvpEpUy)8L@KO>i%^6)I_C~AfbMFRlYY=mRQn{evDhH z5U9d0WKE;OV`Tm%y(xO&4&~b!3H;LIzWq*+bX^ufHA>NTZIW(=mbs&Khzh<*Ox)sWaQr z8Fv?jKo!osaBI)ArpB{#&8hixH)Vze37j?L+}GtX4$ZqEjauxf5U9dgTutk?Y@Q=_ zzfRTnl~HDEkx=Io%ZTreu^v@vbU>g&pbBTBc~4P7U{H}N-e#rCYQ6#PR>n*Mo|!nF zw??&o>&*vT?+znK;J#;WS6O1rsu>QL_a}~32vlJP2Is3~(gdgW%a+YY>3#Fr%s!V> zjg?%#5_erEaP`PHTt%{(vx4NrJ9Xu3`$jpVW`8|5XHFjHnsA9+5AGg2OJ!q+sTu4p z^?@r1j^K)dpPV~{^f9I7T{BiLzCBpS2oe*yzF`p8Ih?x5+WYZj%15)O#~e8@=TL<} z)eWA@sK9j&hd65-Rw#eW%sHf|%xhIega{I$UR=kNt1kvRD=#+owVP{>_LF~|R|!;= ztG;LLpFvJLS2Oa;q$& zTh7k%^VVo(4?Pm<{a80GNOa8ISNhx-st~Bc9r#>5V*g$dTJ)kUG%Hm1FKsiuc&FUx zpf&cODmHU{krd<8@HO^@oo!~iW+}$^QPygB+Gr^}XWo(R+5Hr=O1dUW8|l9GeZDAV_*7M>6JW8#|RQ?+bujlo9JCwvzPbhi}KCWAF|@OdOAjs*v#JsyJFLf z9d6b!axA+oi*|FN-!e!cP=z~;*_mQ?I$HDBBYE$)P+Q2vp%U6h;prvP_vh#Uf+bdw2{%|iNR8B?pTju9lV$6#OQx_g6+ zOxNY}y?qn{Rdwd@tTWf=_~xw5k>_(($F$LhCq_gL--Ue~wGl>z^cgV9R2k00<0(%VJf0c8Vyuwb+F-vRepSVuK>TRh; zdmfA6{cpi_ATn`1h!@UW%Z8PsWM9fnzsEPyF@glP1x+hHs*cR@EiVP%YOD~b+RJ%m zokpe_JDj~}37^99k}Vq@-qu>j2ol&9*e!JK19Mc>>@+!F8-+lX{BASLwC7$lhjpzw zG@os557X%7*-kn}kifRUS*D9m7|%n})3iD&fhtd~_mY?EzVvqXqQ!o+w0CZrD$iW+ zu44oVYzsWsw{)Q6>8tm$Nq9GfKvhqEbKcLAYE*F6^gg#yI!4yNE00|5rDFsMYzypM zue*vFiyz2=6T=k(RbJ6HvjtbNf99-U-}$z`=#%}VJa?J_ew$9w6jT>li^|b*jyDjp6){9TqXD@E6CSf%)kp zSE4}zRhPKx`)miYS8*H(e1eG1euf<&R+-e$z(6yt{TS1r3gSPmN$K)>s# z1giEf!N(IU<=15jdQA3%@UiozL1Vu9h4^u32dR7 z_O(T%*w*2hjIYu~Ay9=q20w$x8;C`LKjhL4p-Rty1hzN6gEG8Z~21gfy- z<5{(LZyb?Jve0Dzc1jP21h!D#E%G_mQTkgZ3L6@#5U9c)oGTWVNV10&%|kO!wN!d) zB(Q~Qn#+or#?qR(sD@W-g+LX)iP-leAj<4Jx*)A>*FBMt$pI5=l>1d3<;{r%wosns{9H>e^esyHJF5h$aAd%qHG2ohD3?+sW2!47 z03_75yDxT@d^D~&y~)s%nlRsxV(s(+YmgLkH58q^dpBD>)5FU=}6kjLuC@ z9k>GO>ps~P0#%rU$2AmAX;g1+32N~=pN`%kshsfhsk(Z$|Hj za>m?Z^rUhL9V1An-<*91#>;}oylCS*e}zC*YBz7QuSc3usIk?z|2^`YEW0W%<8tzb}rPsdL4y8RnEfRrZ-oxo8@$szuD=qY##hu7WQkTV+0BO^5$!` zbhC^<_EuiI&`KdtwK>6Nb~u=3G;8ntJ}_S&dsB~Jm(z`E5}gA*SVBceI%AH_BO40TcORZ zwW7pts~kJILRWFu@(O_}+!MghU_^083|HuC7wRT3g2b~G-lkQdYh4TL7+XK>2|AH~ z45bAWQV3M#xyk+kG_75^+)f3A;&((u^$(>z z4^IhSf&}g<)3lY9Ylt_G zd(i%4w^RalwBb58`?s(06bI_`riY!*35?+1Rd;gK_TT8ZeXcL1J~*oosKRw_P4nB( z)$z6WKnmEiQ(y!M+&RMgGIotKN|hNx?cT*H1gdbIo2w5M$!dJ@kEWX?rYL#aNZ^yE zY3FBGH1D#vb8O&1g+LW%OS4mE-yt7 z)iHtuuCZy_zvV{CP5u*QU|f_!pbFnBnpU9hAi2HxI(ear`u;!yS5Me$a_2NTf6y^m zxwHC?LKVIrd6)O+33B+J+p>T0Fy%dn1kS^9Uvh+ZM^{Ld<9D@H2vp&Fp7);H=gQJa z>1kg27Rvh^37q%iGrzi4#`MZTp91PB1gdbnqG|80t&yV(xKpjJLK&AJp^o$yzuPSr zx)-BOv&t(3s&L%JbNb)c$@|}ZXhu~(WqgGMepzsTCD+Q86Dm{t2ycZz6?#MPzKoW$ zW&f~hWV|n?ct9Y5-|D=pIMYNqccD(59~DsuRH5?*&so-JE^popqSNI{E1n!k;0%JM z4PRVb_Fv|pw)s^8Rpv9eX z?p{a9QA7e~Jo!87dc2rdBqu$($S|XvYRPP=C zO+;17LPx{Y>`YW)-Yw7KTrcnF>@t?Nol0@w77fLvl!kr?WcaKnKSByiNPX(2sxh!+)N==r*v4vZi%DYB?}=whPba@hJ+ z?_XYY468DR@_l@y5U9c{!Z}!9E;yc78$;QPK31+35{IW3HRJiryC1iX@p0J%hwq&+ z)O_n}g+LWvH?9Dda#swAh@deWqa4~fPqTD*qA_<;f*tqV;T}KUx76jW$S}MIZT;R( zAyDOi%F{d@mS}iPw0>2geF6H>fFSBHZ+#8S+A$h zYZg}`NF0dtG<&{zVf^fD9V6{?alO*Ky5v@QtU{m)^G$dLvSV@GEq5^OA27*|5hPki zd79B_FO213)-kG{@zgU;Z%9)XZBqzTVTKCVINar-_w3F&qvI~yF@i+QY)|v2Ezu~_ z-#SL_PI>hii6La)^Hm{GrDncdE1yUIxu+$0^!#JT2okp!dYb)w5{lnksbLoBF zw4#x7GAX%BsKTrycC&hwMK5r)J^fzd>A(mQ>OCLcP}3{voheo;Ms`| zY~e^$`s!&$%txH9xY8ZMP2{?wBS~(10zV3`srzk zzY>k9i>zbZ{kmOj3?E1Z#x7O}RN-z@-kmUUg;mX-)`1Zu_WBhyR~|?->Tj}+ z(aa-OET2D&ZsgdZ5U5gju|5f$Av*6JMiCo!DE^{IVDHNA-@B)YR*AzX$Bdl{fhx>( z;HnETk>Y!v5!AQWVI>O!3G9zKgD0&4g>Chqh|c9ishV5`A@YUM?oWcfSvQ+$dcH6| z{YtQp{K}Q(o4hh&-yY>NKPm+Md$1&J9q%Xp;ayruOoTFlG&%+GEa&Vxv|@-CMP~F< zJcN)?kJ0*g9ok&ki&}gsrx2(@$0J@JWVg`$n>^@M<8q1@5)$aDq-mR8SEp;U%hG$P zo(KMR2Uo`|zU76{PrJou9@(feUE%epnRopJMvzdwkdCzspq~+yY1dPgK-H|mHZ$=E z_q%)zc|V-jc6m4J0P1qoQ`DQ|W!4&*XgvOupm?#CZtG>1Uzce3rC7xIh@~>N#UM&N zR!Cq3eZz3yGxzNq=Ewn$22+I+1r-8Ses(XjIJfrFZ>(b+`Rzv@ySZBIb-q^MV1*t+ z>Uj)rUyj;}YSi?MpTGzb=yJs4t3f5{{AjMh6QdHSTJw*WIqA;}L;r34s;^IrlAft9 z4f|M5U<3(t1k%EtmpmBfYJVuRe?zCZVLkg)_PGAHH^bq6o z7?q#&yiMrcZC`~zmHyPr>{=wzn8r_+rcI2>LkYpns7Fsj^LO0cXy&{$U-Xz_X0haA#ZU80I4|f&}`$aJ{?D@8z?+U1(`yDTP2))L&la zr{Rf4$IsR=uEsx=?HhC_cbAd^BS@e-5Z{j(*JP3Ey(lqTafLwD*STJ1<`Id8xAPc- zeXhxK&3jR~&&32rkU$4JP0Q?cRsK7x7xlic5~#u_jaOeQT#?7(dr`r^iz&|_66mYP zRWKeHvdgT#v_8b95U9fEQPZ;J9VsslA4XGuy9s>O@EIIi)XO|giAI&@*416seT2L? zaTtZXb`uyu0$mchQq%L6yxTXLrjE(05UBc4*vs5~Jki+y%sR%|ulo!Py)+l+jiJ4_vnq~@=%uI1r8cR zBCMAk7`lhd-v$>IW4TdMk*ho>De0{%&`t3;xEf4a!KqtCVR5*R_^1=D+{ z9x)0q&1)0?L{ZZ@Yviu`g%tu-P5K9#+dG~xo;I~=pIv%BkTT|6A&0*yBrt+RWrv?x zJnD#XHO)GPOP8Tk;`3y=`ly>ipsLq^K(meS38Twk>lj62hEd6rSye41cai6ZAl(A6b%WV!h{1xAo)(#p^5eEzV};(_(6W@Z>ov$y4!2Zm%(2vqeN z9B6vP95;4-v3^zd(qpMZ{#V9;(`k-QLjuj5Esq=h3aqw=xA!w6!VVi(E+yDUcl0y! zcpWzW#9PN`+Gi{sFVFibn?6+tR5k7!XkNKUM*k?wHT&Q5F_gDRytyk?6ZlK2^D$m` zKWsF-%xA9rs;8^RP@sQ|xu*9w2S$*R~n5x;_PWn{LEm#L&nFI z3HJ51{LC&_4;m9@S=TDA{XpvXZm0NjtEWPsYHW=_^TcRrMDR7`efj}oDXx8_W5MSH z2VT)he67BoKV-;*33m1B{y05`YC85filkn2U<8R!rt6(PWMp8Pb4+TEq1{cNJL1m7 zD+H=KhXln|sk0P%j4w328 zHibad{dR$-!;6eF_pD>w8!(dY?QAEmhpuyA1PQ#-Jj$pRO$!>26F&VGDg>%>HV-t{ zzK}-TPwN;Ry@ye)`Ex}dpBWB}Ac1$5Yhh=KqK8cnh>UI>9eCIBR`W9_tvhJ!=Q$wt z4nFDApH`eVMXqAa92i03Xca%R;>v?Yv~%8P>Zd+bfBh8^eXOEFplWxqK(nK(G#-Xq zt>j&XUbO$i6LBrl!+{Ybn%Vr!ycG``x1IAPp?`IyqG6wfRxrtq1gh}uqiOYh!YFCt z4{@OSJ>|WGL{WaLZ7*`rc-h;!=f%!<7%4EQ+gODr?0lZeBvP<1>(n2R#>`X8d$)oOBc=A~x3{G)Zxjn&MIUzZw(_$@qZOEq)B+a<=GopJU$ zpQ@RavMn}-?YDl_fa!6jcawkqKenzqzKWx3Zy;!JLV`nrh5!i=EZLb!2rfm7lu{%( zgy8P(ZY|apiWF-p+U(Ba*5bw8id(Vb-#K&VUe5OY{^+l1&v|xa=kCm$InOgz^SthM z&>A*OTiNc-=2@X|OD$xJJPVecS~j z>gBH0lehU~!}T-mRe&h)S4Dg6z(rOcsPFda&3r{jQ?jzsO=;t4ABN%Fu+# zwjb1rS}0l~mV;`L8ex%>2w z_J{Uv1ofhC6Y|Kq{$zjL9c~9a9WH3yms=6`ulFqL^44W$zfjMhI%52zMC`H~nk{CRMc7JaQwbSIciB zY-^gO%UG5vwVY6Hn*DR>VS?73mf>FY9UUDl8;rH>UEdBC)It&T{Ts%If4a#Q*IwFn z%MWlNs25#v!d&~Tzf5z@kUN|A7t}%#bma^yVrGVQ+4WNd- zkaI#u$eEj)32LDTI!nL}M~iREkrAC`-X^VF2_7Hxk=wg6Ic7mu7lL}ZTOL>_wG;ULRGHY}3s=i&o9L_!r~19JI)R~crGmLy`n>m%QT##2n*1Gm;6mjKrlx^+*#VT&&4)R~#!Wn(;wtQV{h6_Qx=q}ta zA}+RavTnaF&(}G&`D{`2NPv~r3#_hpAs^;`(*MR)g*HThejle5h- z*|%JMJ~CO@kN@hco;9}%x8Lp^t^Qv34Y!BcqjfuO_wMFA+p$iron4Pp3q?d2(e~t^ z?{uvq54U%szMCeeUD?cQmW;ELtF*O-7g}Oc^dDK{?7nte>sUJ+S3mvO)|uUEj_h^F z;nYGAh2ywge$8k-5?9{(+8McMqD+1Gq62qTSWC+#g z+dIYCsn@ht^`*TKQ#;PC+qaFiH5uPvlfsEk%)dk z(_IMa)igHF9=5%W_31K}QEqx?=iuZS^5cP}oLVS?_92{9?=0`I?|aDO1xpCJ=A>)U z0YTjUd&+42W!Tfdl9TaTN4fk`F+sid%!sv9Zcng!bzf?_5%z;Pr}&Isvf$}Ff?6nI z;Hg-fU1?_>eT}`_C9J-adeH=Fi_|Uz^`h^_F!sp?&OBqZ99Alopcaa#cskZDdZwNA z!*eX-WBO)}(|ep8w&FRb2`rcnngO;cQ7?b`cNt}K*CR*Y&TsHNCzVPDVE!FpP1nMt1nw=R@U{-5eT%Ef`r~T35Y&slS;H7tA-8kSuZsKwSlHA;5#6fA z+RmW%*6K4j8*C3O;>g)w$X|AtE(G2WvF! z6KKByTejIUSvvj?``L?Lf?6n|O&?(o+R(xBho~XMeZJZ#Yc#xKhu`fXsAcUcVQ(JR z!Rp%kzh(40wnq+J_R8)xuB)pIinwYE`%~u*){X=$BiGp@a!#zDoE+BKg`i&a&BFXK zYm6P;YmGIh>j**jOO-MSyV30q)>m8LK1kPIZ9(F5yZzH(`<>r#*ItbxzNjGV3dcKG z#zw4Fp?@P}rtF>Viu;GS5Y&tII-GN!Y$XS6n`)P>H^}uqC?efA!mgd%K}R{K?;9pt zpIoL^uk=~ei@qDsHhj=b4mj|WJ-po@L3dab?cTApJ-$dT54vIBsL<^ ze6!rzF+lnSCb|&RYu`VW>=qTj)$836fp_G`#>M5XiERY6P=xz8nE(8H`L1GB`6{G^ z3qie_L|3+d=>4r;?;bmx!`ZX(D|xS4O+hUbL4Rowhs#pH39mCiwmk_sUgTNS>(@b* z?E3PL=FSC4bQClAiS&%X&pEyCjTu8a1FJobJNlejNXW(#+>C zakNtlMbHsy7}>^blw*=Y)M%#&>P7cHaNAAdb$Mt}Rk;&JJGD>*9dB?FSNoN`S|~xj zhS5$D)Qj$3;O6%N*_`<;M##G`+Np&i=m>@LkH@(kmTQI@?G!=1=w1ZwkdBRTPJHpL z8tv3V5p=wP=2__q&RP2?|kg+9dIFMmx1o1RbHEpP1@vCveLjYP3@X^`dKd!}zCUf^)z*Ec34K z#i@lN++#P(?siV8Urx()H|x6))QhhAVa<^DOQ%m%I%nA3%zWC@82kF1_SQW(yJ_|; z#_lt{y;T)XT-~ds!oMdu`z9}yCGHgG-$e{T-*%Wz#qmZJ*81Sw(*73V_zuFv>ofEJN${cM4a%;A#g& z&=m*VK%A zPOp;%_w;loH4b6aLJ_ovp!goXN|rbXdCCWKx)9XM?@Y8k+^@5axA)97OAct?&v`!f zkx4BSLHiJNw#)t{E6?ogyzTOhs~xn4bX^L!F6_N1zuVc-$-cBJqZW!dT{y;09^FZw zN4>xOOy>L4#+i9=ybD3S%G8gsQ{?Gnbz6cl{kmHMos6aGI|(;7F}la0Yg{*?+U^X_ z_a~Y-C3CH0)It$-wG2B*({QFA``S4iGTViqUbKC1>s#sq&eeQ1oR_cnux^Pl_WR=< z)wxsjv>5xVb{(zxaLz^dREBYRa874$le*64ciUaP2e{`*XXLv+zS@C%W7vwg~E;u5Cwk!bf*r zv`sL7Y_H(ly&ma2y>OpV3q{bK9^9z2y_9o4Wwhge;i3ycy=ePjwd9m_UZg7TteAPr zRjWVN$JjZZbx`NPv^?OFHH~rpIvVag%=ny93q_pV6JxXS9jqic?KO-CjcPc-ET5BO zPD)M@)XV)9jd=(+JAMpuR_;&3sf8jc-ionv-fOQo@0ZTW zlWCk3eX_U^)Qi4ZxVt7*d*}4tsr+@b9X!pVN_MNb_U4Rn56w|GE7@D}wKu26JTU$0 zSF-bWPB8zP_87+1tZ_x1R+W#jO`Bsyuf7qsf8?E*LctkXOfSe=S$rxcZ>NmxXugv6 zhe^j``h1av!Hz!jmrmsx8e>K5pMe6so&@Wg$I-Sk@v7PX?^0IU!QA#BHtZV9 z*UjnSTsk<4?+#8dtG|l2k94_e_Q;)JUVa*Fhrn|IVSYw5oZ3u`TxvKUYt-V`HWguq z4xd!3jOGy~m^o&z`a7)#$~kFFK;u7KW^x_24$uBCgILGN0+cNz4qsQJddlzL%zOf9`-B55CN?=vGw>jwA#eh z`+8SG?+V?!7W6LDy=y`5GTpoQJ~SeGlXrY&pLzUt;YOl*m&~kCn=Pi*H#<9aDjQof zd5!vejUB{BX5L_WTK*taO7UXROBZXa zzwgX0#s1CTKqH_X4zxq+cG%Dk3(J6Z*w7C3H?+fsc37U4LpvO3ht%z`p&iN#+F?UG z)Zfq!8`_}}&<+RMVe59-(2iu?4jbB`{?@-*J+7b~4z$D8?XaO8$_v_ILp#*p&<-2g zp%F8OXLVZb?rJ*)RLgw`>IMDgD-Ukle3;oOo$shU4BjC0uCG?KCbUhUvppuG^YBqZn^n#L&xF`2$0jRdt&#IwKh*&7cI(6xG9EVFZQcYRst zKs^_NdYx-r)Sg|bp03sY>gkkg7%C@O?4SJx&=6`Cq&92`P~TW zY^6pU8!=t7WSqjRf_g z=sYXa*e@>sp%FoUypUzqZjos=)DzS~5vhXG+J`cn*Daq}|8IGu@@Cb$6hXZ*&h)o= z;wfE5y_wf#%51;OkMJ#_7K-SX@}pHZ-F1!lzSQ6H`o#mX4%CWTDB^tNC#%81hq_h` zFP)WNe6>&YE=5qUH{bnhZTk6dT}IcRPs(XW4$H$Z+Np&i{tbki3Y-@jkzC=7?0xN= z+z7Rz7K*?c;eUI+4DE{?lrNgVZX3RE6hXbRgSPF{@Bh_hl$!*RsIM-_T`+d3g(4!q zKVy|oN@?R4!!SC2+$$R_yDKYftS6|2BJk~D-+5|vFK(MOvfYyS^`Qvrl{D&<)o_u& zE@Md5U**;x?#i1mcBzFTvL4uJZCnwc5!04#lBbN<@(R?7S||d?GmbM)t(@9F$!SBL zN&Lc51ogUJ(6LIE$e_!(ANZ3j8E7~~w$&5VLJ=@OSujuOG8V@#lwo_`$cQ|RTnOrQ zYyBFl;Xm1Q8RtgNl4T#Ha#sIRPf!a*;7owuGEY02mKrA$E2VHEp$v+kUiHe)vF@GC zsmoXzpD2qo%HS-w>IwYr;WrDPHU8oNtI^GT%8Q~6qi0x8Ii+bTXD58ysf8kpA+xM^ zb#m!4F1;Qqw>(SfVDC}{^>Wwh#e*O@Z(4R|`QCa0zkB$V!&>1ihTnJm`}Bh#>sEsz zx{L?c^T^~o862Dqs0C=Q*7dic%8Nb;GPYWV$qkN4f{bk1=2ol^@%6kFfZ3SE_7w`0k^#`5GhX&wB1Pz3dI z^|Wz4Q$PFqs9* za{tT@&T7;`5eIgsvC_vD)n)8^^v?ctG?Rm~8bweqIu;D$^t#{8!1_6z+w0*g3ac(} z|AhT`A$rYZPyckNFud5v%%xSofnwG_Ph;LiW^-^YN-Y#&EF4wLi-z0GZw|HgRL<#y z9;)X;P%rv!4CCgy->rR_vN`!nz?Yi5HHv`pe*av?%gj0KTlca$3t?PQ1ofhC7E}t7 zr?6gKgB_e};eEt-M+v;a81Fl$Jp%2>+mOv#0_!-KqXpp2N$t5dQW}HV5Zg_%fK@uMd0~Oz*dZ*48i*zs-Bf|gSYMZicj zKYy{B+;U4$igkWiY*8YWOmk-tPykE!=p!rXnwSD!sE4 zeznv>5%484KY!s;wG89y;hVVL^G)=%oO;nVK`u_YLA+hg00-w<__mwAxoF5N(>nvu z+JZXFnznq`{nQT5=PnCDz!%Q+&OU|#-$YKniN2OoFWM%^jt-y7`+-VxX_yCbm*|~^ zVNNu?^DE3a=I42E+smaq-}IMic7{3J^sWtHZa2NNK1Bl?@b_&zJo9sjGbgMpOz#>8 z)+nZT^+KNn=QwwN=7*X*k~nix3q`={!~DFGfprP@u1hF_deIs}Htw18y!V~IB+i_$ z3NyXyLHM_ct1_GoV8v;EUW+cwafFZTbX@JDs0G%Hrg!~GpJW)YvgF>CCAClltRKzK zE6cd%hj_;&wPGXUX{2Xq!x;R^`rTDEeb13?p;|@1ofgl4Y_K$ zU-OW3o78>~-W~&#>K}Ob40>Dr4Lcd;-S2=Nz<~Sw;`bZWevn#VFT%Y08u}!-Be(wF z+`D6;7K(s<3H!WbnU?<^@1An6+7D6$^`dVR^j^DN;zP3Ul!IXAq!x;ReTn&bj{`dv z?%lCa1ofh00eHeEQj4BZ)8*eVbHZ;NBPptXbhJh7AaqPd{eQ@m4gSO%Jf1Fb=A;&i z&=DQI|44JuPn^uUOybN*5!8#m8&D7^@|t%ITP$(rq!x}xsM*ZSTw^`dXq zFy3AY5bYcHR=ZUA<}zHB;jajG^voLrpgjWla4Y;pj+gz^PMBIKLPw@_t#tfK?Y1d` zdeMG^aWy1^SRELuc91%LrJe=5c;=0Gz`Vt9Ws9{1mQc3P36RFv`D5E3z!Dt9IMeLJ<(9V4tHO5HArVUgGOr>P7p_FnUAe?ifV8 zaE^lYg4z>c3w7j9^#bh?;N3-J7Q-SQ*}GvLq+S%QBYG;91qw88bBNAi=WU#8sf8k7 z1w~@7Eg?EM^>b7Wql4Z^n$Jr|3UwLFGh`Lv$L88MU>>9v`dl3~)QGsn!D9M|K{n2{ z)It%kqE#z@&pU4l5y&SHxtsAh0;!%wy>v8Em$57|r}&}NW2-RiYpI1IV0FwE9U4~5 zQ%38G*+jm9tu5TwQUvw7wLXjuDKU11Cu#uEK>^W0rlW(txTr2e#X@ORRYeB{Lm5=1EPZhqJvyV2YvBf{RT~}yB_%(0ntGL(Lt`GgT7d?{tYTGJ*E{J zv<+iY3y2PK9Ub&Vn)P`7e-L`Ka~&PT(XO6F5qjk7T0wMBKy;An=%5clz4UKW*9xM8 z0-}RlM+fnDt}GOxe~-Eh{bk@fI_N`CFLz(*uc(T*>+h~ALw`Bdb7|xrzCMMYaEK0a z9Ua6uRe4dgo)dMgAUen)I>>c&5a-wbLFoBWw_MM)s(0zLsF$7-br}#H0dY3+ndg-}VmjTg14$(obql36sQx=NQ zYb}j{=pcvaAlK1BT(|uXLa)1Yt@IjBoqy10Q7^sL(q%w&kVABk>*ye^?v#Zh^jeGg zqJtcwgIq@kajm8-6ropY%=0bLYdEf>gFXcH(rY+f21ExrLM|fY$RRo?baW8+waP*fdS9!{&^uwFqk}#K^`h^_z~~@@ z=%CQiL5zN=GIV@K{jK9Ox(tX8GKdZe9Ua8@jc=%5AB zL7}6A7(G>G=%|`{?(%{vI;dL?(ZOVh4hr1kPzyyEPgQhK*9xM8CPW7X?r|uBdeL{I zqJt(x2ZfFfV$9N0I(e>+s_8NyI>;b8D0FnthoD~WcMj1(8=`|kM+cL=qXga{MugRK zp;o>gQPDvgqJu(52YnWbfHE-ZtZN0)K^vljLPrOE2~po(Lu}m&fyJW z6j(hMMxw8_DmrLGbWrH%pwB`PFk&!Ht!t$t+upJ3Lr^c;CKVl&5FHdcI%s*nKJaD0 zlLqx%7`wjOs_3AE=%CQiL7#;pU?k#chOQMv2Qjkk9lJgR^`dQ3(Lo8(L7}6AmiJo% zUj{r~P|wA^ptrUvIw&DJD0FntXQ2rA65;uWt`$TFB}4~>jt=?|)Qh%BMF%BB2ZfFf z;z^Zf?0U|J)N^q^?X9hf4oZj)3LPE%Y#|8v!r|GJu9ZG9@qQD12e3spsnRC|w3b2PH%Y)$ELsAzZcMibbFNDKCmv(Lo8(L9U~Ncmk>ruzJC> zO@*LOQqe&P(Lt`GgT68-LZ40QTIo|uwJxF0qF%IyDmo}3I>>c&5KoKMdJz7N=h^CS zSc~FGwO;i>bWlQcQ0=3r1=fssI_+Hn`kthsgLv+&R+jKgpM@e|Wr^p`x(tX8N{9|} z9Ub%`s29fOynU#mgA$^HTt^3e7K+fP%et@hxwBeX(q~aG+S4jJC?Pti_JdF|W+ABl zfp?GD5bAH(?_f5BZU;mMB}50+evn#VFM?SQ%8NcpMF%mTLG4(mg(6_bg82-(42TX& zhz_d#AVp9w`ZiT`P(pN&>*%2GJyQhiOE3dMm!b0+)Q*Kdi+a(qprV5gLK}+%VGfgeF8s=DT$_4U`VbwI5FJ!GUerPn5XG~-`Ch zu>lnw#0(*C48Uih2#5z@PLZw^LP$8 z*;L+miLZC57wtC{9dsZ%$aQoO^WM~m)45~nxwJ=AbkKq5Ak)!7%$iePu-fpUbw*l@ zXI~4^K?kCPOh*SXS4~+c0#;Bqu97{Y9ioE{LP%nrM+D2^4VxHcul3~9L>5@g1+!-yFBpi&u3?cvInTBy>|{ajQfxG$wyT(i??fH@LbI|b5ca#`+r(Hb7yC7 zHw8c}y#2hra?1XUBD^pY)bcpr5$kYLHuj`chX0gN@X{W+8WBQvgtY}_nDP)pT^M=ZaD ztgPID|JI7X*ez343J{xm3sU9G(yQRsa;yrt5jDZtDQH zKSd@eV&CXW9mP5#f+=wvxuI&0-aj|@OE>YP3lvN}?Cp#$p*;MDGHM3w&#@_q0U6YPm zRi5Nznf+5i84YXRl3O1Y5%tsM7t}%#w>urPD)kCtC*P(4M1h$X<=(`C!k%5!g`i&U zmXGatMpnz6R}89J($x-%Sd;yzHE%BLO)I8@GG-L`OBU~wTR6Q-yAafi_B!lXvc8q^ zzeb7XEmDeXJIJjulZTKTb@-A`K;$L3|8{Pr$K|B)Y0M2gkB z0tB^C1nm(RS5c3p>{?PZ&yd~Ka*B9X{4dKnlauw|o)X&8sL*{mZFiVBvMJbwpkDMn z!F}|-QaiC<#EHF+5Ax<0E?WuP^RY~$ADcaMU$TBZlb5aP^uo03owpu-U4VJG0CyqZ zZpn2a&V--f)It$o2VJt3|CN_@==TCx5a}PKaDIs3BCx<^7lL}x9)Ww@PZ-X3^D2u% zr=N0ap@;>q&shViP6oZtf}pc&ZYOYMTYp%9N8Pd z;$X<&xZC@>b!%b)cI?lqCNepYbKqeQ6bj1d>@QJUT>5tsrxuF%z2-Hm@jv<54=I4% zW{fYL-r4uwFOV_*liXyV-zG{tZk)QRhdmqXuADz}I zJU?Cp9{t^gpkDONLSF%g1-L8%c`UT$v`xru0gekpehb_zcQd2YbTOQS|JIsQ3q=4& z!$PhGvMvn6ew*3Zn&t~JtYQ@xf_kAIJ?PSF#NkmNhoK3 zYM}^PHk|f3kLBPwEktOoAua^<8d+hxHLqPsHt@|AC?nn8TXJZ+MuIQd$}_ayY@NAL zf+4%6{irQgg(l%FXSI9gx@$YFzUhkTUzDBpj?A{QvAFEFj#CRoB(B+N{c<3jA$thQ z=>J&GsnA4pnYq-3pkB0w@TI=~P^PcfTr^Cau+MGS{LN{8?{8^i#Is6P(-eDo2;+igt7M(pF^$MBwv@=Z`Bg-5-++C)Qk2Z?9VS< zlQ(PD7Xxb^aP<{M3|{}6HF8M_wh_L3pglW1W;6DTR$@tfm#dL^UQVT_l zO1l=gSjAY}3j@CGlX@MO!!E~&ofQIH2@>7#n!Pr zp^U@IBI}4H*4gf%>}=Qc(2m>_ewMw<6%pA!MF?t{x^S7*=V>V0(kmUKPlD{7%o}CR zZpB6CgW;|+D56r9CGe`sry z@-4RFfQZKG!Ol?_4esbTC>_3q?R2!xuF)jOkYv$fh#`MXRtXE(G<0h{)&Y zr_s3X6#4DAGy?Zg)It&N2;@ai4!!r3%=avp7m1OA9zf+JS>|T25K+~{&S4|19-9iW zOQ$ojr@cm5#hMgie(y42Hi0i*Y8YMLCCT+k!J_u?YTn#)6|sZB>)OR^MVHv=+5 zUlnTHOHO(mBp&Q{BdFK&%44k~qe9vI2t@Sk)a}gwH0z7t5O&+a-9(8g6XeQ9 zImF(1RRy(t7%|X+)%jxNM*s4YWXC%>M2!pau3Aw=EuDe_J_A{`Mf3$XQ&t5Y+3tMhmSYJww=$ zUWnN6X^u=&H;)LM&jhvXsQjIEeOCx8w>#iJwffL+zPxxmuXubm##IJIRC>6`ib@~K zW*5QVd9!^BK754>&J-Kzb9Hf&xEn?lmTqa)E-v* zT45~v&;ZPx@tupn&2s*&<=FVbVo_C7P_M&vlB{mei?d6={}&Nc;~Tjzd#ET=o_kp- z>NiLc)9&@Q8aFNm*DqsV{kWi&e0C_m*qtKIg`i$@Y7Vdt-7LatAH{e6bbc#2t!zFK zUcZWwd(mLmEd7-l6mD9na0z%uSM?IB05$tkj|b0er1 z{qlhp>&9O4@ubS4-PR)F`J&F&Z)+pis<-~^r&(RBw3|w)nQT_^CRW_@a5baC-k^4( zeDJ!QI9sr!pcaa-hIF%jY!S|?ZNq)->Lp!e$pVq0daXzof_fcT(cSuGRtdJI9nQ|( zE{~G0_SO|Acz{3_Jh0&za{Mq+ZFKsy9+bCD#SP&Tmtm{^NdaZFD>PiDoKsC?yPm^^pk7gRI$PHpMzY;yajxAxZh{<~)LdK| z`iLV>ANcwV+2qL02adj4O>WQJ!3us|f&Fj}*NIUBC(25BTMECwVP#1y6p_>DU=<6l z$gB>C_=b;`)pB(f)tjy36(%KE3$jGBu>H5pUXK&3pW-XCt<&$Bt=ETJo6?(l-TvX{ zQL_7hj$#Ms#8V4J>;*o3mz$MXqbd)ej9Z^Z%9ddrM5lPmg`i%@x(96oT}Jc$Q)ROZ z?Zx8qJ2QotDYf2BelS+P zPm?5O_a2Ix13p%~Rwhup-`}6NvpR_wR`m5HC?l}#1i3nUZ}ClgYmHFDN_NTQ=MP7TML#F?X<7TeB9{%4ea79wRrfc4CdCdajL%H72|yePlijr1Z?Z*LQpUIW?{FzbpiXW&S3FnsOnwcJEsWfg_zI1TXjwi zwq(;_5e(ysK8t$M_pg*fI4Fe(trTK{Qi$5?gHnhIN+D`b4&xYgKlHc?J2aL*Sk*(k z2p`3%g(9A1PA~&g$LPq!^vyGPzbie(xPn#qtmo~_jqrQMxCs1$P46%G*^e#FSwDDw z&4!U_btS%Odw+4DiTi!fo`zqV>G}(DBc+kvPG(m=Y7(DDb5sn%c+GT-UoCvcR!0#kr$W; zhfm-$S~M4*jz4lCsMp}Y4rbz`3MxJWch?-9!W&g;EB418;0xZiH^+rmRI!(D2DUdV z!JL6H5_dbE44BGe3nYlZCu+v=wU8oE!3UIlR3r?zub}ONDm1S^--kYndeJ^KjJWHA z_}ntFVrG$i0@gdGcZD=JkBJ)`&V)44}X8K7bbi8EtiLN|* zQlxnMBEp5BURLpLX2^g~C%(=+(5$tsh}x5FF5A!CI=(3T06Q;tPHL*FEqTz2V6os2 zwG;N0L7(eJbRYZ;-%>P>XnaGh+f8rw7e&kp9cSmZC^m-9TO{P-9HrXWBypPnA!uw+RnDd8%EB927$GN+{| zuJ?nHeZJu-_l1hK-!T`0dhsqvX70Pi)!q>9KaX0#Z`R5uD%Xt>cS0AN&GQ2<3ifKv zvMw@LT?IuW*sEcd%IDoSzc-Js>zh{`k2P^W=(A8np(fv%>-K_@A?({A*C22X-?~4y zSQ^O%wIuAEZ|12IqV{L>Nf5bPJDs;^oKu{BulCNqGAQD8$vI|P{}8=bOXxP0&nz1( z2GmqLdLM#%{dQ!w`8s8Y+PA?i7)g`)Aw=)I3TzqAU**psc3gKOsF&Giiup@ih>9~oKJ|mK{L5bhMWxZz z1hoY9o^0-F7oy@x?pifT9>bf>2^8P`p&~54mQzH%Mib2qt3z~bY0dj#ynak}QG8Yn zS39T|=I3~Sn~<5Atv~PwgGAF$Dt_g&P(H_+zGdx-h&_dDyO(|%l-ACUi3=@G0Qv4c+>BTh~wGIipXM%&Bg^nS#`ev zHmB%f^F!WHmH@w%tkaj6b9#m9U20YT)x6)NLL#(qSwSrn0Wnh38;yn=3yc5EPdzIv zdNz)9A*k1dtjo;aheP$=IsfW?{9LYR(Xee+ar)|NGi^dqwSR@UvFVND4-8sseuyom zcEyHKXV`Im{C14UTP#3O3q?R2-u!(2u_DWEo;RtYSaUartBk#sSDD-FB5L`HS;(;_OG04LQqBrjO0l!%%dig9Wmf_l+jfV&6YZssB9 zONxb3MbCY`ND&YhH$TVQKdjuq*M=4s1xl2}c)Jflz1+QfrPx_s<)<2A{rE>bYVWUR zn=4^z=iY7c2D8$S#ntZK-B-QiPw}-UtBQ|#)Y*iu7b)V$9qY~hwTi2Vg<(_+I?hi_ zs3PiISLYu-1ofit3Gy=D{>{S{Hx^r~t>Y)VZZSL830M1mI8ida=XHI4*=qJU9Ij#m za0)Q=F^`XFBEl1wa%!OnIEf<~bQ|wJDWM_-w1$T9DF019 z<7NZV{10{Jjk3 zUY*_f-Umfwd;P0f^B>65S23BsRWI<_S89okkJb604?(@?=z%=TpC9w@$F&eYHy_Gr zpU}RVJZrmI5YB`>v5e$mFZuCbTZr}DT61cl2sj`1DGK6z{txe0?Q2oyahwZ5z2H3B z^qxl>M*N!$V(!NJB0t13;LIFVBGoPqPQ#VHA)c921w-Jxkj?2fGl|D|YR5 zv);-A?B98Kwmt1?M&VbYj>s@;B&QaNNIT%V`EW`BHf#c(B9EK}`SbnbM9~ii_?X6* z%(>6=vZvN_v-G*k=Fx5WSeH?cF~7w8oL{n`U0RXtk9hHN;10}Z@L4FLPxGth@j>}n z`Y-Q68LMZd6S-lY9rpVQ7lL}x8X89OjS$7oW)jo_88AKsWC)p`v#I9Qz0Y4>3KKQQ1-lT`t9i;(W?+?^ z?46B~)H-AC@>-CwwHh+EsD&a<$&=>%0y)_bbRGNr2>d44=+9uCUG zx@`Mk(i(!cVbc%%{vVKwGyenT;`r)L5k=pfGdIQOVJG*i?43|QasFnEXma(g3qif; zSb#gdm!}l>w=!`zgUTuLjS`9&nB$UJ8?umQx5q4`dV^Dmj+tY{iQ>myql9|V5emQa z!6$jqkX)ib?nulEGrifL{mLFOJ532>n>(jxl@A^=rR(~Mz{Ge#Efi5W z-zD>!UwT$J9%~i!U^oA(QF?JTcdV-&w-+8YTVKnGa!)s(?V{0Pf>8PW;Yp)z)VEZWX=*gcZf02#-d^~^+y!)rQW@UCZAU5DXqdlP0 zF`m>WNPN?>oS0iyhBjo2yg)YaWWr%+_vwY|7;Z zdzUjaqdalg4Li z)QgTv$i+!_ia#IthTqFk&8s@3eg_mWcKA*6@0zJuk2N@UOJ6+3^R@oOKc=hdLQpUF zXn)rA25)xb4zCm8ZaHo3-Kc-fTDxDH_o`q!djE8T+oNvqVry#%YM}^Za^Zh__y#M& zAMk_~S9xK->MjKJvZ0sPL2u{Hg=IuX`iV2ukMfBSy?Y10%qw{>nd{;A-1=xbmUhe~ z^Pk$87=9J7zdU8|!k>8Q=g0WrpsIpeD8gZ>S^v2=%_8ftuU`H2f-nE}1pnfGbr*tq z(Ha^?il#64@b~9<&A@72Wg}HOMfA*)lD)rn&)k?7v%vK54UlU9oCA)0 z18PC80Wb(m|P62>x0GtDkd;@Bs2%H;nj`Z*ikZS;( z1CD$HilAO}OvBZ(z%`gu`wt#HJ``tvo0dft1L0}@^fR0eeLISPP z0dNi!-+)>u0=WjjCNMpG1LPV2=YS*MfFh_DeNT|Z3S0x=94Nj4at$E!-bB6uat(k% zU?ShZeZK*64S;i?_y*KM5y&+FZh-0G8z9#JI0uSvKoQi7_6WRl;2HquK=BQzg(8q^ z0Bi!&!#6;#0dNi!-+&^h7k#tp-V6bp1I0I>EvGd^t^qI$Ob_1xxdy;FP<#Vwp$K{} zgkd1p05}JVZ$J^$3u7o4OYtxikU0Ph0*>qfjMQMn1}*yD4D~lM2Y@GFde{TV8~_FZ zNA>`_kP%n4OkvRYi0*>qfWDY={xryunWDWoyz(n={M$R#& z==s7Sa{w3w9N7cZLJ`OufJ}eW!yZ8905AwRvIi)FdeI(%^Fd$^0E2)ddw^Of0+|DY zAvWq^4fFpYVnFEkDZX$aCnFGKFFp)igCk`0B_snX@ z8~_FZNA>`B z>0u8ba{w3w9N7aDLA~gkh1(s0IRFd-j_d(EtHHAaT<;=t05arFWDg*70C)nXhds~- zm;-qx{LHfedw^PyIWT?UGIKMq2k4UwqZTj+E@$4zI{|xuS||cfGVrY8j$#iWa{w3w z9N7aDLA_`n!VSd08~_FZNA>`aFA<^bf; zn#dj~0?dI|y+)ZSfIWccsCaVesnuFw4s?H)#F0HfEfj&w0pJFh9`*n-2Y^Aqkv%{W z)C-vdFDj2UJ?sHw4giCIBYS{akU0Q+02A2*^huDt1Iz(n5O8D0u8bbKvNWA!p zj+y!{5B zDUj9wcz!Eh3Nrht1+)4gSKq|Ue)=TCcn?|q-Sd6JV$>oixylM^ zp$KGn0Mo<7%pusHZz?Kg$2Q{^H%7Y<)Qk3rVIW&19I~&s0Aqw&C?WxvBV(ubFfk*^ zFpw<*tPzfk5sIK*bo3a;%82@6XX8=4=gu?&vlcN&5!Y(SBJke&h8cR8kLOv*AlCpm z2ORkZ)It%+I{-F;iQEIoXaueSa1J=~4Jg9p1zZDQ6PO;pfj@8!5(*9H$TvV1g4crl z0^k{#$T6T#g4+a#$BU+uhVm&+PFEQefqV_%ZJ5Z}fE&OTnxfUT9{lZ?P#1!F(KidM z6ySc$-Pnt_0saTIPy}WyI=fDH#ICv^YE&wtFfCFG6 zO8|5KfdgRTNj~PIVh*NfH?g}!Tj76r3a>Tl0H+p;K+XhkCrr;7{m2_%i=wwD@-r(g zx)9Whjs>_e9e5e#22SM2&7c;FKqd$9HcStj1Gyi-0pZC1pa|-PoDlCVgNA{({NY`S zc+(%=@`raR;!S^e%OBpQh&TOVE;Z&1d)WOCrzeWDeaG_h%_nhcp$O!J05`-$UI?7m zKJ6x=7bWo-!&lnv}F0;_lB7kMpLtuRL$bG31gJNzMIi?Y_#JK>k>dy9#cM)G}iYH@18 zoN&wyM+EH=!{{%2ikzdz@rR>YyUL&lWQzd1!}MfXyaRrT1$lRKfn!3SMZM^If=JQB z{-WlM7~ZE^6`pr<9NXK&U)6-RBj!vjo88sl^khIB7}Hl|-CCEo+tZp;3q{bfVFhr$ zkBHb(nKx`Z*oB~8x7Nk7!(IGMPXThBOMD~}A?P}?7Vg>|#v!H&_w5u4fsvI9Wc8BYoQ$+sMf(5ko zH`A*Oh|CoeMfN;3c!hl{TnOq#YX~f%GCjqRtsG3gCg?(BG`=f{-!4bVrseG z;?>hiJl9J1?}K`|TOPiF_ z7gPqscZchXF$*I3AD1!-YN3c5eWTdaorU%M@ps?aVn?0={QTr#7lL{vRIR}F#Q2+@ z42VHSEfL&2KMx(7OHd0%?8{z(@9^#6`2SwW02i0YPgB zc>s045>?lP@fAOQ;M779&d6x?xQ@T+$$(g#zO|UL)#Oza0T< zhRd#ZP7&ufn{36G{-!4bLM-nf{2G?wC!&tK5Y&r~P{<26D~N2JvhW8Xks{ZeGOX4^ zKl5z2^z2N-vMgiulx8SoJzVY)!Frb{s8=#KW>pe1`()$U=av%GLJ?M(a;#4_fAhmE z%x9R`feHI?2+z^2mtC_dp|LIm^%^uZf|W1xAf_VZ9T>*c--?Rs@(tU# zTL@~&GcSS-iF*=L60!x{wHoxOsA$yu9lJ9@xXPf2GJyUz{z*(mm22>U7ZYt$d|)pt zx)IcCpNwED%RP??ov$(nZWa?2{0-i30T2W6*(?k^tzjhPtF$OD#L|HQ3ihVhM7JamQk{HxX7G6D{s6f z+J&e`yy&k0?)08ePPA;1kxvgO=Nj!4Q8rT<7Mf_732JX}sCAT>(l!%M54q0tS=5XE zHeo+lDp-tcGM}N|E4{k{)tbGEdvsJ9MvVpqMaH->Y{$Lof?6nIZMz6oGPZL}f0b)c zaY`Yv!<^5iWUT5!P_Jp7BiQC2mc|@Wxj09@E-cQnHEcheK~hWFZV{~Qf%P$cAS;NL zZ5Y3{DMcHjI#QMaA4o$5`-|SQmnN(O(zjGgJ!| z{&CmMcUP;4e_KSb4^vtB&5-*swp9fC;b6X)Dv-TFdjVM37ed7s=gYF15RIZ1iYV4L zf_>krQB0A&m}_vpdLfY~xi(v|r>YARso^JNa9KLb&KZr%} zt34gjIXQ4Gma(d8A+cmrZF@M(QS@2Vi@qDfcwQr190|%QBlbmmzdjbmEEXDNSmzdo zg&8UOD{6TnMGtP35W@pf$>SS*Ur}YDh-CvJS=fyC$)1dqJl}+gKb#b@Q<(4Dt`OAg zNtQ^~zrw%Cn4JP&(f-9n%@TfcVmdCUrTyaw78Uj?8M9E_wd(Vxm^c|}$O@xwFfq#)lss1Vfa)S?L1^5c_a%uazb$oEA>gB9=W%!7oW zmY(w?SkuZ+k}(U#U8{yWi;5IE-`ab&xXYl36(b|qmw6v1doohGeHkK_kH2r%U*KD1 zs9I4k{T0=tuSs35h9$0~0F#Rpe%g}2r%d;X&9#KJT|0# z^0&(<2WRxnwdz^ai;hZAfy%|jkCj5@(gj7m>qONKT6cG?W?7ZR)N0vfky<5PwW5fd z-+Qj=-ld4{)he)+%-_PS9>{cpz1r30`DH%XtI=msFFM8yBl3?{V#mO6IpX?LPWy+} zu=5s^ef_1s<;fPg_@u4KT8PVT;g>nJP=wxjS)M4)fi4}y#&Tuk`HCl82uBh&buVh@OnkL z`}c*eGAN?rdCso1^0z#>A8+4v7ui2nm-7m)bRno0?FCR=4D2dijwvUXpa0#v=TyB& z5wWirYyOqLg?T`RQ6Z|6c$B-W{ORpM7lL}Zdlyv@iXR#)UxE?>Y9)XIf`wTKsC)nn ze+x4!+%2!1D@k;DI#xbxH^kKria>P)&;+nNxgX^q8g=bPjJ)wV8f9TzjJ{1BXHx&) zFt$T9YW3E-@;F4JsD&cjwbGG0$QZ5VLQpRqpVMVj9??rQ`gMftva_`}a;Gd5;cmyd zLA^xADN|&4`6@01_0my1T?VRBRPH-gqA~^TU0Q}xtC*5tdGbpNJm@AyEJ%{4zF*3z zg(BReq;8SUqDhs}vP1TDE(G;L1qM)JurLD#6njC_0JIGx>KdTh0q7Z6m@R@j2B2qP zVYY~l6zebC<$^86*ufL!>XW{xv$9acc+ffk%>&DmEt2%?YccHpMA@#xMQ_wuA*h#* zk?Su5>L!4Gg4_q%3DiOnsG$JL2$m;X1a%WYKS82)0!2_S)J*_o1PfI}4FeSlK&e2Y zN&#vYfI5MN*&?V)0O|x5W{c?44E@~=m|auE@{w}ZeBX(QvQPwSPk;u6<;fPQlB%9) zJ8q;*5$QXXQ3&eg?p@Te7+GVSL@f(yp$OEp0Hq4clP!We7NBP#QOklNs26>+pgII9 z2y;$!m8gV(`Us$aU}07WDj$FXf`z#s`dmb>89FwI5@*IF$_h@n_rye5C_ov=K)AE-(J>J$={DJX(^(Kl-t zsOA8w4iXg|^ckdD^`V->>Fy&eJeNl`2hdWm@bn#cETGK*8VwTl8C(eBrO))#lMDm3 z89<{!qCNw)(C4By1E?=po-=yXW&n)_iTVr_LA_8(0yG*d&lx>xOn}yeM4bt0L5&H} zYq0Q)o<7MiP|aZhAW+ePS||dQ9YC+a@|@A5nggghNK|y72phr7hd$8rK(<}2-E@rO%Tg-MxPBL6DNb4$;6A% zu3Awq_t-^U5zrTre}c9MwNM0VjDT{8g?Unjfx04~FCtM}gd(UH{oO!z8>mu%I)y}K z3RI;4bqWj5mr<1hv?eS(2i6${dX%6l1*lU%pcaZiRf<<7=UARx15~8|bqa~f6cj%pcaZiRSM9Zusq5X zs7e9q6cUvwD1v&?FREdnDg~%hNK~dkRSHn2uuz!-RVhGg!a`*VRHXn73d^IPh^iEz zP9ag5f?6m-=ili$3RNjUokF5A1w~LVRHXp@1k0o9h^iEzP9ag50#zwMox;LQ2c1W# zW@=QW0Br-ylQV&;6rfHaQJI2TC_-m!>eUjeQh+*zL}dzE2C7nk)`W#Q6BG^cL{Oyw zbqa~f6x2cys7e7U5|$@t0#zwMokF5A1w~LV+6xfh1yu@Ar;w;jK`j)ab1wCKj;a)( zP9ag5f+DDwyLVBQ0@NuaDpQ~;1?US{n1z6<6reR>q3)!+uTYf&)F~t?Q&0;J$={DNvOH)F~{?5YQRMYW<0-6re$2d9o8w zl>*c$Bq~!-3q|P6Y`y11RSHn2kf=;S5!4G+DL{k5!u$!y0{~SDP^XZnOhGLafvOas z#9(3eg<+s71*lUJ$={DX4`aP?Z8yBrK0I1*%ej zI)y}K3W}g!wAVpR7gQ-gokF5A1+`EFs#1XNgyqS4K~)M+r;w;jK@rr8jvmO^0#yo7 zr;w;jLHmUE6{=Ez28HFxnLt$vP^XZnOhGLap}7ZouZF4=piUuCnSvsym*zTXMA=&n z#GUW}Co#Sj*X#;48Z>W0d0pF7gdIA3QX^260@NuSRHo333T2@PRHXn73d@t1fvOas zPT`<31+`EFEgSB<2UQACr*Kf2f+DCFs#1Ukh2_c1KvfD*r*Kf2f?6m7RVhHD!Sdu~ zpehBZQ#hzhfvOb1{kJeL163(NYr?|349#!RyE{~+0Cfrnl_{u&B2bkAR3xnQDlY?7 zDL|dVL1hYxpkB0wz)J;H3Q(tTP?>^SC<0X}KzG9O@Ts7e9q6c*-XXdaWA0Z^3!G$<@jUIwaCfI5XlWeRGc2+jY}drnlP0Cft9$`lkq zy-<|`G$<@jUIwaCfI5XlWeRGc2vns2-2uy!mw~DjpiUuCnS!mEz*tqn1aR;t8lyfI5Xl zWeSR*Ui59k?;KPqK%GKX24xCrp$N^Q)aM4MN&)H=5|t?^f_k|}2?JG%;t%%9dZ0|9 z8L}3hT4=7V+Si-|Rf^%w&Rc7gGR5tceqwIm9@!FtPpk+zDlfE;7t}%#E#UUAv2Y96Om%*asuZA3AyJuv zwgXiuKx@K6WeQqD!^jD$6rfHaQJI2TC<0X}KzG9OC{v&+1*lUV>Klph01I zlqpb^0@NuaDpODks#1W~goVl!^hpqz096W5r;w;jK`j)4suZ9*VR@7(P?ZAIDI_XW zPz3ctRSHn2usq5Xs7e9q6cUvwP?ZAIDXg`S6@sc1pgUoqG6fx>z?%S7iu9e1$=0Au zLA_9w0<ha0&2whuP|7_ZI7*{piEITI3>$=`kr;m4|iT0`9FL_`ctw?;~HL-0)?Pn zbc{hPW7ZpPzCS6qWv%ArhW`(uOs&)`X2eY^i^~1z-R=`VdHI-(O6yZwPzdVf9=k2J zUF9EhKajtJ!iH9gP>B57ApdxUVGo0LEO__Ygnz6j>WqHcoEv=loEx$f=uA)q_0swb z>PevL`1}sP)$E462wE1@LJ^BV*<;c3*VbWG#v#!BD759O91pdk2&)>|Vq+cvs!{+)-_|!_qRxzNIjT~C zI)$Te!t_}v0#zwMgTnURgvmjj!qGQj`YfnQ0a_Ebz6sO!B*Q>e3Q(tT^i7yP3q_zR z1?W!L9%Twtr2usbN8g0`89}^Il>#&8ls#1VDg`;o6^jT1q0<1U7V!=WY6tN@d zos$8%_hLZ>M6o?ZM8txiB2@u)vKHj*$6+$p@0Fr$LA z_&yFKOapfcuO!R_t_N1WVT&sTye6!YFvUsBRw`e_l>+V*UYse^l`BM8p?+I7k}wV2 zDZG*}<8N`6x+jIci3%RLQox zox&>#GlA=YRT8GSQ&=To%1qo=>bAv|0`3%ENtiJrJ{DC4pOHYqG;pWzO2Ujs&I)m* zfbWEjBuoQ$3a=#0sNgJd52;?KK*CJnPT`e=nZU!qDhX5EDXfw(<(<%0_5p}11>7mT zk}zXLd@QO8aixHZgpDN36z&vWNtjW=S?ZXl=So~D;7;L{gc;8jE5wxoz7sZ*Fb&)( zypk}Zg0sXuqzz?i5~0nBrRzBI09F zRfsDETqJBHVWx1W@Jhmr3eHl8KRvtRN&$BYuO!TPu2>#Gb%Vs z{6?x*Hjpq=kTAWHFyoQ)(TXbt93^bUnL=DC;7;L{gc&2OP{&Ox`vU?AGle^aR}yAa zaF#lJs^ZVl4bxrEImR#T7D$-l9UIQB`iq7vbqiI6_*lTt!Yc_=oJT{172;z74+-UstWP3fbWEjBuoQ83$G;1sNgLA3j+z$z|X>qmjy>yAwCvx zs<4rSY2at!m4q3u2WJ(JTzo9xXW^BEnZWhHDhX5kEUc0+WgS`jx%gPX&%!GSGe*Su zqN)%d3;0gh%I*a5v4Ee2R}yAaaF+V=>e&?^3;0=hC1J*M#R~DUfK!EyBuoQ83$G;1 zsNgJdD5+lAK*BWev+zp7OyFT)m4unVox;lQ1a+a-aZr3L;Ai2Lgem^iAtKHfRfRZI zz<0t%5~hKlg;x@0RB)C$59`?#9}DfQ0Flgc;9|dWVPeCO#G*VcJN-G$3JmC1J)0D?qGF;5(u3AL3&H zKMSuU%&6cjb@^8XNSNlX%Qx^!!W5VP5Mc!vm&yFkTiASfGrVnsglV4rqmiGud7rAw ze^3;%#@>{yIcytMfP`t_XW^BEnV@pqDhV?I3DYVGQ@s53uL23vfQ0Flgc&0sVMc}c zSiq^mMiQohpM_TvW>jz%c$W!WD{LfT8u(dwC1J*h_*lT5!YTj!i@p_1l1xT1)Ntp3^umX(B1Wpw;k}wVYEWDC1qk^-* zyG-C(VIv9Cz|X=f2{T5-#{%vYR!Nxgm+;LCJ{It^@Jhmr5mtb4nZT*SMiQohpM_Tv zW>j#N_*lTT!bTFNfuDs}5@w8mYni~E!YTRnJaILVBglXVs;gy6LBjRHLcM7W{%=k;C5=fW^BuxK%g@hR+tN`OO zfm4NzBuoPmrdJYXRB%@D$p8|jfwzHI5@rHF11o!2z_?66!n8`l6nc#IDDgCaw}Dp@ zX3P>74EPyXC1H|6yfWaK;gy6LBdieL47g#~NWwJm%F^72=fvHw+s|m6e$TqbZsu#tpmK*ID&!i);e5^oMTZrDh|G;pWzO2QNm z3#%l|1YQ$XNtnWw(wU67Qox&QWwGEIk4M>$fVYLM>>N-Q zofj6J(&WP1k23DUJCzdW^vx@SrvccRUfG!mJPfStbYQi(Ai(FqR=(M z-*|3ugcZd$zIygXbN2Vc{0qyw6%?GM3_ty=-ubzgNiMy>C*VQy-_C6)Ur`memphy5 zI$YrIe`ipYyci;^P==qr51v+GHF{z-1_fs+g;Cp3R-@kstVWKoLYa!HP*$TCRwGAP zp?pRCtCZE~h1JLk&Qc1aw(-QxJ<9uRH`)u)lOwFyv>b?@+QyBe-%e&N9OGNyE@1^{ z-7?2y+sM$D>r-)}S`w80Tp;2a8>RNLsjRY&*D z^b5jqu!6I2-h_UtZ78496Q46gSfQ*=ZR3ZFezn&g-{LHsH{p+J8{gHx zWcx1|?GIWRNKJyu+{6qzr|U6roje0a|3(g*JJ#?M;&4~!U`p!Y8%RA z^}=Lj1!onn;Oi$}>7Lr+Jiqrok$4+^OIfzz-%>4tItpE3>ECmtyJzF`{D;q+EVRuS zVFh0&xJIBN1(hjYs!~|NSyIn}DivK}0Rz;b`o#+alq0N=Y8cdQ=voH2mJVD?uUyL< zRTW_!2G8@n`qTz_F$dSuMy{m;*U~H3GDcW|Cw0E=Ne!;0Lp^|3u4RrIfbixnd;hV! zKfGaMBocD7j!{wvfO-J0T+0|?g;aQ;9w4lv1g@n+4Tx8+WmIsM)PbP7BdoTRglp+g zpW&5jnS*N?R#K!E1JxE`#iMu}QkQ}H3@^1A9ASmjWuQJItZN0Xr32T}E7vlf6V580 zU8x*E1%X$trI5eF>_w^tP!AB^u$8KTu4Rrr=T`Qy%U*NrCJ$>Fn33hxc~_|<`_8fd+$+~I zMpz;B8rXlXs~_N6I&dw$axJ5Rv!tp6wHje1BycSqDj~dbE%WL-GH7x+_U(o@I;ns_ z#X@**gMSGs2T*h1m1~)!<{-RbNv#1Y2&{4~^L6hAQZs?t39nqs*arVDT=7UDH4~_v z@XED}5mrde1gawReNbv9P&?t3YZ(=sB{dV(zcz3!9V#KbaxLTEE>#bxYY1<2#lK1_ zAW#Y6m1`N>UVyT+7%7E2MG&wE_AbC6xoHAn?kyj0(;Iy)s9gKv*>jTuX-v0?|C@XED}ZLk9T$s9ZVb)`ru2T(!am1`LloP{^Y*lz;Y(xHOD zE7vkcSRs`Is0|3~Oo40ZP(k38YZ(=sC6xoH6VSCKsT@EBfmg0&j7a4G>H)&)Q1P#l z$^ldmc;#BgHdrB*1E>wKk!$HtLEx2Z85NwxPoluJbf_Tk%C*c!l*$2A5P0QU#)#A!R25k9%&Tk5fothdLEx2Z85Nu*l>^x0u5ZFpIe-cRFVzE5 zIe^{$;cXPFz+SivuNhJ~fC>VyT+7&oR1TmX zAiT@6I&du=DhRxCE#qIp3aK2xPXDkr5V)2O6$D)N(xHODE7vlfMOI*y zJ4bDRuAWQf04fN)axJ5Rvx;X|DhE(O;FW8cV-I+ECzr|r)B}V!?BcnS$^ldmc;#Bg zv&agm96)VASbqpyONR;quUyNh;H=^ml*$2A5P0QU=Gb{3-s16nD6f8flga_?`VVjV zfothdLEx2Z86&K~*R#C(Z89(?9d`G7WlqL6WLH1->W6o7RtM&!!|r~s%*ptdutIkA zV;8=@pUbX(?C$r>r2%GcKV0)fa1B5nhDfSc&VG<2rHz@0yP!3Qfcud z>M~HD;eSGH1}iwLcm+R39l(gX6a7A@1pwP1uYMEezYt%0bJPatTTzZ$1JoRNsW;#V zE4Xd=WnBE1yZpgp{iFNijh=psvvxk z0V)Wrk}%_67)Y27H3wcvm@&c%sWm`tfQ=+fkD7x}Z@@>(S$t&!3DcwIAk-UhgcVY2 zfNBC8Nthlr2ch186`aL)Xdq!a)EsyvVdmA{pHgdp9m`fpm^ms7Y$Rbi)EsyvVaABm z8lZx}DhV_GQXpYEkTAWHFk^%jAXet64X}}f=|IBtO2Ui^&f=>XNSF>JOs^!&c>k~h zd*gCc6X>2hsWm{&fmae{RB%@DE&&PCfrROmgqdTne%Mb5W?Np}9Sh!N4ict~Buobq zrdJYXjIaXxEc5Da%0R+&AYpnXVMYaKfp?jMglQuQ(}9HPm4q21tN%p4?4t0c@EyXAG)JxG`i zBuu9y%oqU)Gb%u=%t6Amk%Z|$!gNZ)j0(=;yE2e49Y~l?Ntm%8umX(B93)H|Ntg~K zOs6EwsNk&P-3}6_0}0b92{Rr!cG}0k5WLGAB+NXLFdaykPDz+C!U{Q0^52zO0FW>p zNSIDZm{Gx5;6YlDF!M;l^dMn6C1F~SFmokgT97dFB^45;mGf0;10+lb5~foUW{iM@ z85JN_T97dFNWyd=VLByYMg?c_Ul>T34kS#cB+Ph(tN`QEf`pkz5~c$Q(fm@&c%sWm_~K^{q%9wbbsB+RJbEU7g> z%|RYXm>widrzFf6ky-;(5ade2jK35}m>x9;PDz+C!U`E1Q5z8I@!;KtS_69K02KtmsZi!a)jKqhFg-|^PDz+C!V0N1KsA9n6-uoENSIDZm{Gx5d>;oArUwbr zDGAeJFMIIJlUf5*5Cq3XnH|ggr&4bqwFam;a8hr;5mv~&M`kvWgy})TbV|aEzr|U_ zBbQnO)Eqb^VaDTNh143Lnn2wUrPcr>Os6EwsNgKAHK?BTK*IDOVLByYTI^-dm4snBn%AS)lTQc2-)t5HtV85RDing&uljHqsKQ48B?>gCVgcZd$PMdV1zxwyZ zZuYhZ6%?E$>rJxmR5=c*0|3|3Dc90s*Ld)=lU@DT-5*^2WF=Bo2rGBH)B&I#z$w=< zMpz+r0NA&$zJpQ+0IsD|u4Pnk79UgKTKY9VEO1f_z!6qR9RPOv2S-VK%|IOhxRy@2 zmhlR57GIlEN$LPl58#w*X|ZcOI2FpSe(dfKPKB~^F6)++=atj}pdP>}*D^*}A$0)Q zx35lxQU`!~0H<8bsNk&P*_Ao~)B`x>TE=t53aJAagZ0Hts=;FN0_&lM}A4gfp-)u~YG0Km0$%C(FN&XPKS>Xi*#OAoH4 zQ?8|z?-0thw5SINer-|*0Ip?lFoe@B>HxsCbjr1i5vcMh13CH z-@dxNNgV*VmQJ~rQNdY!4g=THqaMI1*D_uYR!AKHxR${y4t)@H0N`3WIz zxRxGVOQ&4RsNk&PlR@_AW3RqbuBFBP{NO?<`|`2#K6p*aULV;jQ|VE%M;}~Er(DYz zVFl=w7F6B|36`Un|^s7&$z_s+? zS~}%gT5v6cBcbe>$KLtifG9h{WM^39T6%CTopLQ>gcVY+0j^~(H5-9z>A|&h%C(FN z&MKZ=sr>-g(ka(6o-0;>SZTqv%p=#*qXxt&*D@+NOX@(XcTeD2dT=eBaxJawUX;0- z)C7QQ8C?BjAD-;gtITAiasXUQr(DYzVTIHLpf*4~8l`do6$DPXmQhj2LgfHz1A^Nl z_WPi609;F_T+0}dY5`OY1dqnzUj?qE2iMXm*D|)j3aP#T*HS$i!L{_@S~}%gMg?aT zuQ|Au9$ZVOT+4U`Ss}X|QLCZz5~<`sMTb+aWmIsMRB}}Bx4^aZ;95H6T3YPr56*$I zlOH?!gAbtWN0nWhmA46SEj_rFPPvvb!V0OSKuv`@{DEuf!L@YCwTueRk{ztodm(Tw zJ-C)mxt1})3aQaRP@fTeCj)cRgE{GxIca65ue?D@ zjRwe+!TVA6@yhPp%8^SY2bhyinUgWX3aQaRtwwN^49rQ7iVmmD$*ABgspLTAMP8}q zkO~M?LO7{{kV*&CH3SbssfGY~Gk8DB-uCKW8~B_ad`>5PPL8kwS&*N(*|Wz6l>^&htC$b%ooz;XwvY`xccOA;RZP zY64`Zf92izh)(DEW9JWdvn~lFff!*0w~hUxn_l2w?0=klc+Wr*hzid7=FqP8;(RA< zA|&h%C)rMS_c0_P%16Bmcc)A|&h%C(I5 z6)V7>wBTB*e6B|3?-EvkSZTqvRR2V9Ej_rFPPvxr z6qLnxPpJg1r3cs2Dc911YZ?3#K@73rT85FqbnI-wwN(E^a4kK!mQJ~rF~SP)O)R*U zI(~p_>A|&h%C(FN&H}yCf@`V%iQrm#a4ns3En|cgU>sU-E!95}TuTqGrBkkDJPuGQ zEx4A!Kau~!z_s+?S~}%g#-n8g_>&e~OZ86#*V2P)>6B|36`WPPOTe}C;96qN5V)4{ znzI7LN(-)~`X_>G>A|&h%C(FN&H~pm-l5nRp6u_zwRFn0wBTCi%C)rMTIR~NwBTCm zOa@#_53Z$Cu4RmXYZ(>bPg-y-^T@UI;95H6T1EwD@wEwDOAoH4Q?6ya8(0CZkOkLL zSLngD^x#@L@!L_u?wTueR0=?3LYner^r3cs2Dc3SaK&iCgT4u_% zjK5SWfoti(wRFn0j1g9VSZTqv%p%v)gKO!OYZ(=s1$w0g*D{M-OAoH4Q?6xe(t~U1lxrCkoCU6B?3;mW>A|(M%C)qOyS|gj+6zc_7F^44@A6$) zDjnQwCl9Wr6)!!Guma>o3$A5$LGU)*=i1i(u;g|-vBI^CeS)(R8Gi{*Yy;Z*;h+hQsBkS~gcYC+T5v713fHpL z<-7RXx_n@pSGbl@!CBn9uwGKv%5R_kkpErbTG~F>m7i6vrJeTQmRW6uYZ=cQ=ykJO z`IElb#~xbYTE+;tmQm6Els)bAfA`7S1g_=m`qqB?>`*(s!nKSF&f@bHxRxGV%Y4u6 z`lMTT*wudh)uG`Ef>LQqT~BEDf3IfXT6%CTbLCpbHdq0Mqb-%jwX3|*gKO!*wak@k z85Nubx??;efothEe(db$lxrCy|5wrBm3NG;aXa7Eo-(1Nfnezd*sVAYm{p# z_ggr=z_s)b_I{{5w8FKF5mq!u|LFMLJvAQ%u4TiIck<_Tomf_`WmIsM_D5}F%x|sz z5wD$9eyGB=jOU6KAXZv%Eo&-V%Li&(`$BXwTux^DlNE{HL|BfM`!)3z_s+?S{mhA#x__1VxA|%u zE7vkAI7^@4dY6D}>A|%uE7vmKSF8ZB(t>MQ6SA|%$%C)rMS|-Z1wBTAM%C(I5Ti{xHa4n5;En@^+ z%cuac(t>N5M6RU=*U~80GAcNW@5;cn^x#?=AXZv%EtAN#^x#?={x*V2P)X_RYe!L>}3YiYr? zOq6RW@6<_UCkMEe9$ZVKT+0{%*D@+Vue9J=CXs9D!L>BXwTux^DlNE{iE=IDFQHy- z%}@`nrBSYBjIaXyNeixJ61kQhTuY-|%c$TiJ_~_s>A|%$%C(et&Ttl40b->E*D{G* zOAoH4QLbfFa8~i`N@YK|mPWaj7M1*oaxE>Y{S)O{#=o{y688YO2pHvB#)vouR2AY- z0C$0;;sg28ek1*_?{+fR_dLkx`c5LNPM}oAtEuZj;s2LP+kHITH@m;y)P8Vsb*1S4 zQ|OwEUUOZIGO`-Qzr|U);-zgg!J5nobBCMLXT}w;5Mf2}I0h!?`FHoY!Zhx9kgzjl z#VaT{OIO>p4R9?zxRyq_mhtRz8=zO(Q?ETWiCjw$uBB0~WsI<*c$a`{>A|%$%C(FN z&JqU(a4nO_we;Xx8s%DA_!%V1wY2avNR(?SE5)JDmrCGTdT=d`axG&-oDZrB@Fy*} zmPy4q5?o6UuBB0~WmIsMuAb|YL3|V7pJ0@0DQn>&!V2+FfHOi8xt1RO2}Ze=QNdZ_ zn*e8oByuf1xRyq_mKN>=iE=G1+zArpTFMs)eeQy5>A|%$%C(FU@iC|>#Crl<%Or9w zJ-C)ext3AES-PgLXIFeIz_m2WwT$PA72;_Dr-~$UEj|1!jB+ibg0sZOqIzWm*V2P) zX_RYe;ee1R*V4iPAyKZSd>7Ht8C**buBB0~WsHbdLRFz(Pm;*B^x#?=h zJ-gyc0e1?cT+4W_SRoD-@SR8^*V4nC!YJ1=DmY7ADXLdCa4kK!mPWaj@(nV~YsJk0 zT+2kcmKI(LN#t63cr+O0TCP*T^P!rh-v@PuEZz+8XfVpPl&^i2Hb^1f3~*maBG=Nx zqroWGGAcMrycyupkVLMfhu4Hru4Rmf#{|4466IRPUkY4H53Z$Au4Rm{LYy7o*N{Z6 zrH8A7QLbfFa8_`0*zepVaxFbv9gK1wI8%N9iE=IDF9oiphdYH)u4Rm{LR=}pwM-({(!-s?DAzJ7I7?h9;7*Z5uB8Xp z(kRz5M#Pl@T+2kcmhqPY*V4nC!YJ1=Mpz-P6!4u$BG=Nxox&*BGAcMrTq(e{Od{9P zgKKG&YZ)WrN&&BlM7fsnmjc()!=1t?*D^*}A+8kQS|*We>ETXclxrCkoTYmv^qPw+ z1-O<*xt8%+!U}PvfbT>Sxt1PWOQT%NsNgJdrGPs{61kQh?i5D3mN6o(6!4lzlxrD( zDR3=4+$oH5En|cg;z|MEi6n9@J-C)ext3AES^Pu|TuTqGrBSY>1=liBuBC<7M50_v z3$A4nxt1R86h^t0F(R%MRfX=q(|#_l6yRDK0_hPYC|Ya&suWo$2S zEj_rFM!A+T!U}PvfQv*Dxt1PWOQT%NsNgI<3xR9t!L>BXwUnKi;ViO3_gw0DF0K@C zr!dO3j0(;wo?UUJfIEdzuBC;CL84qs3$KYpxt6lKRnL{UQoxA|%$%C(FN&MIC(aixGeg;B1h1=liBuBGfS4zo;grGU3V61kQhTuY-|%NWu9 z%|W4ix%K@+d=tR6G|IJ%3eFOz1$ZeWk!$JU(O{Ho86&I^X9xH-B#~?B!L>BXwT#Ch z&KK~rNR(?Ck1231J-C)ext1})3UR)GQ$-TFmL3imM!A+z!CA$-U7RoAfMJwt8LtN` z#Q6f=7D?nj#NxKhA_B8enS4|j@GNtiLh3UQ@?M?(@xm>wj|R7sc?wf~8d zFfF_$5+z|uC6c}miYo=&DN-e2#)!C5R2AY%0T+p+NtJ}@;ZBh%2{S4wUptw@N zog#@OOb-&KQ4(g1XsuLGXf2t(M~N#1+$oHbFr$LA#FYZ>6iFmudXO-Uk}zY072-+( z-+`p!Od+lmaHlXz!i>iut`zW^NR)&bk13EaJxG{FNtiLh3UQ@?i$oGhm>wj|R7sdo z!C6`brFV(AQh2(A694;rG9A;R|>dO7$spw1!ooS5|A)GNSH=R zm{NJ0C<#+)ZNsb>^hyg7W)ex59wbboB+MAm%Il!eid>yjFW9i5zxJ;8u!<8%m{Gx5 zvpP1h1K#{9`7#j_=6feL@DJ|%zWE9yOpdSuG(igzW)ex59wbboB+Pgm;z|Lpi9|`5 z@t6V$(}RR*l!O^0tPocU_)a8|gy})TG)lsZ3eFN&3b<1wk%Z|%!Zb?4j1h6AfY(H# zB+U3rfrRPdPGOXU86&I^R|@z}B$0&aLBcdj!i);e5?2biQzVgu=|RFYO2V`tVJ1q# zv>;(7O2UkHD0U9Ol>#J8qa@6jC9V|knn;v{NeXeLfIEdz5@w9BLR=}}JCQ^ZrUwbr zC_EaaFH}gF;vf+2IPe)QNSKL`Fxzb1$ZqxN{G>v{e9SCyAYmFM zVMYaK@jVtun6A9`BcmitsSOWpumX%r3le4$Ntg~KOrs>ssNk&Py$cei0}0b82~)f! zLK~nh<{)8~m4ulKwK9@09Y~l)NtjWAjF_eV4B7`l!gL^E8YN-IBWDE|mpMq7NhD!9 zkT8vsFr$LA_)G^9rUMBxRT5?n5@uORm^nz8WhG&X^G3Py{Tw7r2NI@H5@w8mgc%iJ zT;?EQmLmz%frM$4gc%i_rEVK~jFK>; zg0uMAluFoxY-BI;{>NTzusb=C{m1gwfZf;8DPO*K$yb5OH!tkhHXkfL%gdf^j<7<$ zAIVpN%9pt9F6(Cg@k9MN``%Gda29)@mrA3yZ)e({JH#Ko=c9%rtaxJ8&ov!iG}^{i zlb4j|KY5-Xf;L#eS?qz1BR|@ght3`9`=Skwu;Pu$gKF+MrmMD*JlU=M?}LZ?v(W}C zIE($a;iY$}O%7^&ZfJuetf)`MwR`mYY8z|6`ES0>#g#T#!CCAhj;h}$y4j819#%b$ z=vK}Ow3n?rj&~-!X5T#F{OWN;1!on#)%U+*vE8au)u6*zC%y6dsc0lT@)W)G`g zkLaz=S+akA-F>y;IjQ^4p=XEV;0P;l{iCmUsf4drZpYuw@*hnNcVhf4&cgSuJbd^1 z?kBJy@b${cS1kF0#SvEE>s9m-5B5fz-J z_m#GR{$bHSQtcmdmxKr_^!jTX=pPpSBh~&96`VD_O<)gb8|WW7`bTJkBdpjB3iJu+GWtho zgCnfKd6Varwt@a(&_Alzqo#TVIZL0e+6MZELH`JCaD)}O{_@<_HstFr`bVn$BdOkr zoF(6b(Lc(SZ^H6*7yTpE{t+XrkgvP=%3H2{;YAgak!mEVL}K~~(_G~H>N-DtR3RCu zMv_V-j<7<$2e0$fpZMZfv-$S@{cp`aEhsok|3X{oQTJWd-~7J#M8C(HUkpcBA^US= z_ejO1;K>cTm|ON77}{V3XX%;NHlF&rrFrPG{-F(yuwvV9f2i5Aca663+@!hX)7B0O zZLor~^p4RsCfxf>dD&+Jd`BDyM_5swFra3Kd5O01n(th`a@^q11}iv=M}|_V_1Y(s zi+(!Q?~XP&!is%s#d>s3y6LC6jWR&W;fOGHKlNXlcbaTosrK`z;4D4s+6MZ$ zLqAWopUc?|5mxAV(>Bo09r}4_gMW*&^j^?5(9a$Ed1!+ptkCPPZJ?i9^z+aLD>zI0 zhqi%!Zqd(E?dNj0hX^b5KGrtS&n^0SXoG)?vv`CH{X9oMPo5i?eVq(8!5?ZqU!ead3ncxc)MJXdCF~2K~HxU&Y_zEc6c< z2lZT`pBwb^&<00Xf%{m-L2U#5+@PPQ+Rx)}ahB|h0t=>G*&8K0snE|;?dLJV3fWbK z-Bo4Ti-kRRJ+3e>Y<9GNW%JdBIclg2kIXn#+e)uRCAoQE&m+B5lXHX>vdgJTcERe$ zU1yqa8ua!JpDZdkOV5I~G49DDP4}yM`o|V+o^pg0vYT0UvQ{eAhmY)F>fi6{8=wtV zaF$+8ZKHP87H03ykMuLq21i)&IRt92{XqeeZwQoPBE-ZR0=LZsn6cJT@E$D>#csQCz{XGm>7*`-J1*2rIrgU|hQe zEe_B&Zd(0heni9L!f~*Iv(Pq;&YQlpn{D!PpXzbM2rJNDw(dC2-0m?uac#fqaYO}Y z;T+QF{J;($+l~KSIaeHE1TosrGX@!VqDFwpXt7LG*L@o%K$&pGO5}={eLk(9a$Ed8++fu1AQlLeHDFfqw4L z&r|K^QNdYy_h=jF=MMcm)qXB_NrqMwK3;0P=9 zKGrtS&n^0SI1W~D7LTH#pXcc3;W#+Lif3Deey(kxpC{<&;W${qS!kO^XY}(j`g!#@ zVuTfFPo7uW2Ksp!{k(b{QNdX_hcr5)pO?|kLmM1n1W8FWX2`7IEG7(qwRPW*?uvE?gb{}$tSC}@POSOat+&VC;YrO3&MG?a z54-w(*ZP6>zRAt4QjV~qNbTvf#s%XTX$I7_^Dt4spyZoB$IBThHsa>Mjo zxY|UvuwH*#dG5mD#)#96xZH4r6-5H^Y1bcZPCNtdsyGf-aF*W3+Q!eP)R;$~>EaK> zad3ncQiUjWSQYoAYd6~7oc(P#zY*GC1!rl0)Hcq%zma+1iJH&`M_AGHhRiT6uV(#o_tiGG{ASzo*vsm|xnc!p z@jR$h+9*PJ7)NV<$`_vs(iHYSapkstI#r43ea7TTuy)kR-zYu`D-RF5M@ zSb_Gkb;t4X;>ou0E0uG_zr|TNhcv%BZLPB?rwzx!5mw;5W$UiT?9H0EtzS4OoGVsv z7VZU_Uwx2o?M|=pRKIxq1 z>-nF-EdKtfw&l0q`6!qDSJ)L+t~%>tPf=N(u$3`E3gN)EKk+S6An-5RG!u{hhqh2VMj`NonJVf(y2VHsD03eLh)y1dRQ-Tk(Hy4@SS)2*{XX6F;XO5SPEx-3@^S1(*exoWt2 ziJbY$6~xsuauwwYa)cGQdWoFv%Jsn2OT$&HjJ5H%I15)VkuzUW;OZHmDwg2m1C2n#UYf~L-<;f5ttk6EMZD6c*7;D3E@NaRJKF72TjI|D9ZK`9f zJS{_n75ePbHZayYjJ2tbwNb%Y`aIS)FxEPZwV@4;utJ}~+6Km2i?KGe!3xgOaYfs} zSZguXhBi3D3LQ(d4UDxGV{JHBtl%tu7YSo+jm z)*6hp;W${qS-7w09S38r!B`vG;0P;l{bdfPZD6c57;8fttl%u%)AWvmvDRR$4Q+6Q z6}XQRR8?sk7;6p2+EmBd_*SQ{g(kUB!t6PBMncO$$NHT<%# zuV1fWx;5U4co#J9z{XQL?zx4ZKHiArX{}>zjIaVv>9~u%R0?lIcv|aN8x@>|r*zyE z3QjfNh~#OlV{MGE0#E6^rGhRPDJ#Ryhnt$&RoWI!ZtLUtH?yQ}C`H$AF&GrYS9ASmJM&y;z;GXI2eW%5V z+vBAJ3kuFEx`oOc(Of*O)eSJl}O3#9Nn)2y(7i!C6|#stQ>Lmvu5(BjX4w zW|kB_cirvoIFcd!CCs0P{qW%yZdaw+HgHM!U}yd z=rup%)`R>DS1b(kc2;nfJ|$GK&(Qt-?4G}cc{@i~p-%?Acbm4^&)@p~SK;1e1!w6~ zLKU4m@8b73__NSIIKm2jGH9>e_Q_U$_cPxJ^LAEnmOfWhF``Q|zt7_~^mC4|qDbeO ze#NH#if3nrX9+7fi@o(rrHN}x{-rafySXzDPdUPh`ZG4Ot@}T#e)?PVUE>}+|2Fq? zn?3~vXR#Z9skG}iliiTTZG5{W`=qFWjD&8~3rCtgv$wH^-1tuS-6t)5vzZ5`9AQO~ zvHsC6Q{6^xJHHgqL{@MXuVs}=iyBOIdyd`Gx5jgqBdid%ft;1f-rCM9(CtT`J;SZjOpSRR->m0>aMjUvBo2gIj z;>9nVBdm~$e;L0j=W74OiIH(i&J`;-OXphJ2F5@mW1(CRj<7;}!em^mv@x*M#9Z}c zhtLKqI7{b@+Qzlzx#j0iZxh@;0?Ti(z*w80Tp;QHt5 z?yK$Z@94gLXxGpND>w`HG_Av3FsYL}Z_-ZTdT@jlxR3L7{R3_eZcF%0ilYN7I1By{ zx%f3yJRmw8bg~=pTpNGKS2Za|SOLF@TwEl?bD~uGXrC$O@s$m{xH|qc^WmiTk}a)x zKjP_=RG(^6ktEN0y-S{*X{KQek>?dhSfQ&FdbeYIGBQp{KW7DJ=~{*=Fa{bK3uR8t z5mxBhiLJ~<_d579Bjc^C8nA-1bWKJT7|V@}=`t7P2rG0A$X4c}U-$gY?1g!Q%tcwj zS-Kvi3d~82%uVDSha;@ewJcj%@p@^%S|jrxnTxW5vveg)6$jR@F*3)J`4vZ4p=)xs zvT}#{TPpK7+3U;-&e9b&Kau{TZD90IWfmZJJ1aN~vol(I z#ps{PEI@h`M_7UWSC-MbavT`_Q<(+G41g7!1@duO#(JqSgJbW=O;VW!$P9oZtU$e5 zS!My1dNn(uS=zYWw(jxA4o@HPZOWsDvzG5CD*;z%9n82`68q}OPBKHcOEAMouf$A4 z?h=l$LZ7aB%`wABWu_r_2`e~DpOvb>3?r49hRiZJ!V0{F%eOnd=9pomGSiS*1}iuV zZ};-;P8FD8q%zZxyM!aGz-oeggVbw|8Ad8I4Y^BL!C6?PkZ+KxzzidmnT9+|IKm37 zipaNAz2=xffesE_^iR*qf{E%t8aSykL#sPjt)*C@wYfjzelSAGYlg$ z4P9qQWTqjr4DltCd4tR{FvCb>c2JpRV1{92rlIQ$F~SPWFcO&&RK`KfFpSJJbe$n8 zI7?@;<;oKdGYlg$4P9r5-vL>n^J{GbGYlg$4Y}L-w>V4Z!P*997)E9q(xW)S3Z0#6 z8<=4jnQ7=cL;TjrSyII=^NB~oECVwPBQp(MXNVD2NJYHNG%B+UtTQ;QGo-rCkYk;p ztm_Op))~U}(03m_4q=jEogvkA26@8@5h0gV75cuT$ANVQhjoTba39M$oVFpZkyvL)b)6yp7H5giB-RkLuBSs49u8M!M8 z`DP%q09|K@5msRI&tkLk20lLl*6`Y09KbMiaqL6PNG7Hdkh8ST5M*mz!>$uL~ zWEP<73{k;Z82xh@xho2c{!V5Ay3P%V-_f8NAE_be$n8I18hHE@OQ~u_$fi z&u-o~o%niKXNVD2?0mpG`DO##huulwV4b*;|8}cB>A)UgogpeXOZN_|LcTJ{EI`*8 zqT?b)|L9JN(LZ`AhIIxnvjAOZh!Iv`^p8H5*vWyf3^EJQb%vkM9I0lLl*BdjR;;$WS@W1Ye1I)lYJLwGm9^C^1R;&~W36nKNg zDk|0)!f|kf6_^!RdHPkJ46;&-b%t=RSixBs<0B~nd(W}QQucr7Izx=G0`G&i`ql?} z1om;t9ur+>hzicayI~{@fPIF_8rgZT>kKi%3cL?S-)is;P`!h7hOh&Ie~Yv5ZWu`k zrIJ+RO0}M@GsFlh@IDw_!Qo<#ieIcVgm(k}EzZKbVRX$0*`}_UUG_2eX|a4n4@~{Wcatbzfot$?^?=_x#+%x+b)&vYj(EZ z;kswcHcz)I{8g-Y`pr7~UZ+z2Db%IXX8q3gV_H6K=FBfDIBWNNy4iaUEafLGmvzy> zSD)>_X!?}t-ng~l2rIUDtIl?;Ddo#U8_!)c)GxVjs#(25+k%3#?s&MH-Es2^=Nw(x$Q@$ z!#Z^;bA%OFkFK?|FI$m4(?rhhcBkL!_MbUC-Tcm;1qEkq*}JRFZ&;Dtc&W6pyIYvw zI%jVdN1J!E3%~4j)vlu<z<5F=U%^F;V$7UzW$}sS5J-gdmVCZ`G}Dn4c~FU%&oHx z-)NZMcGZ0eKgUX?5p6H@J)c>>e9#*m3r{#!96qnkPW!B3{sPpc(yIM0^b@+|NtdsR z3eKv}y4h8Y8s%q~u)b7U)%8Mu*SVvT1HSBNIKqmWU+V0DzZ&LEu9h|in+yG{Q?JjD z{=TT-toAQ-v!6|ClplxZajDdHiwphr19!DuU+8E!!ix0gI{U-jjq*m}I3_(k)?fSD zHTK~NMFnT=j5fBP(J1d1+W2VZSl@Zl_4b4FI~tC#V(CwHcIqRI^7&WFaZLYXjQ`~B zkL<$LyB8FkRpjvg(_oAr*l8p8d(Yjg1edU5ixvIx^ttx*#`(B;^V40| zKeo*Mnfv)|gSy&Yc15=O8aY@0Ie&(0yw7=QpPr|bIl_ugx76C+`HJkiW^x?gzWR)7 z)Np7zcfZjE1!tXlaaUW{YGu~>R%v6vz1HpGP~k7X=B7;Z@UlOndvnzT~p==D_(i3)_%Ls%IvHi zq>WV<&vxDqN~cb_y`bQ%H=pfl@1D0Z>+yiJapqt1-KXylNJn*_R^|vRdi_{y@A!FT z_TC=S#w)W{xzdo6(lhsZw4mUu1XuG~}Fa3j|9ZOn0Li_!}P1!o;Sx2s*f{LifM^U}tsmYet&_v@Qpb;+w`jX|Rf z9AU+Rj&=6SYgc8n50*B*eyfdd`$f0(>yC2@3eGz5U)}7@?N(<$z9DV&TH4P4w0@c% zH-283BdmC{Yn|=idUbZ(knO;r`Dv6CNC%`IP2-=-RxNhuFjr#Q`(r-es{m= z&Nb;_Jr|Za!itM(>+AvDR%cUtNgKoJ_w^sP+%N6ieq}+yS(~QdhL2y9-TkSwG4r+q z{9R{sOjp16PnjdE7oO+)&-yyyItqltb&f0ZAH`}!7U)eK1 zNE+ zUs=0fq>YOj_VYu2TQ5CkkAE4Cu;Q?3b$0kye`R+KlQ#OSf1-b5{A%;{BU={~oW-+# zFh>4$l7DRe64PkYZ45_PvG&nA+h)e!+0^0EMh(2LHn?=Yxgy)Ppx`Wi11OcYdUhYb z)qeY?d+oWc;cLLxe3PT=?2Im}v-dxi8NfC-?c`@|Uz=V(cQeCxAK&e-x2v=B8m`K2 zct;e^cV5r$*YntP?bFR&h|_9pY;c&exGm4{KP3d;a;z` z8?{}TwS7_)tqz^(PI-K2deM}Z%lxe6XZs-&YwcANR%B046UC3aew(-Zadpk=pU0;+ z?_Xz!EciLw%uh+)s;RRF_5V2=>82zH4XU#b-t=?!+VfMO7-as)^DA1LUGKgytwmqE z^w(dqTR)zXtl6&44jTMRw)B5flGk>tvvb#+OIKf6M9~oeae>ckk)<{C7ul-EN)IjSi@{xAgrZ>u}waL|_gkH9FnDG5%<`$p@&DA>Gq+ul z{dxV=THOgmfW$X&UScrRW_pg zw50R4^|n*XHQB7~r$O<`uc!F^E_v6iK6IR!?dxo_=l{-{d^aQM`oB8cc!>k+_~PS=QPagCQM6iYh7=@yS`Dr*P>|&&(1LS z*?f%O`}Pgor9E~x9AU+~IMb{4ZJdt@M?Sad7~f*?2JX?`MFnRSXMLw$Guk(PcSHC4 zj-AbO=hxfue`0mu$|*_TL+kCmV;bfMJvlYuzZP?b38VexGdFVW59wSu4p!{dsos9D zd80f(Nv_}{V@LaYwr}EgA6Qgy79Ufobo%zA{i@%ZxP>nk&n}Rw)v`T!Grgr zjoGtD`G1;k?Eb{6*Bg8FuzP+xKl}Z-Ny#r;^sr~0z9{?khDk}2UvYeYEzP#?A&NC` zj`CB_-^88$1lGwY!ionM)!QXkF3a{^GYN{BZj}FI%BJqUTZ#(KTDlN@^X+BXoh51G z$6t=}=WVx9`qRE04Bvfxj}`C4)@=^+bDRGw{osObh9j&f-ib3>9_pJn-y)sZ;oO3P zvsyk?XCI%vHhZPF+`H3{9q5}5`_%lj{l11*hj^6Xo>nS-*{ZL9Y3<+Uiq9@F{9D`y z`LD$leD^qiZHqt5gIpGbc=M}GY^`7V>Z#C|C%g4W=8Vzlsfy;($(4KpG;4NyjEvlICX9I z%$w73u1>qL&L4i(dg=RjzhpSVid!)neEj^HtW!5pEPeP$KP#VS_P@gx6r8nUX`LOo z*I(JY?L{&6)e*jKMvXagR-NIs9$qOrYIU8x`G-=z^ImcV|MTl`-?UkOv*@x~!x2{S zS{7Cf8VvK}Ke@`Bx%0q+g0qTG(F0FA$6xUJz2>*1hv5h-cufv7X>#cm&v1)M72>)dBcIMpuk1t#gKGXb5rBe50!~F^W+QvM$ z%lJYYteC%hz1{7%QohMM@=UC)8R@$wlgryZbWuUUSvT%iZ=ZU+LH^?XVI16ctY7)h zZMNqFT?(TCuNoAe)E`|o*1xmlKzrpM#Sw=Uysm-o2G@`AD}Q`6f2U#Z!n2*TihtEc zyNvbEA2A`B{%W1!2rGDfrc`=r)@a}S*5k^ToP1nC!CA$#+x5pWzTqYl%A57?RybFz z;B_WcXYM}6@A=M~<#|6AuQ_M&x)%JY$9MNj`fira2l{W0SZwzA=5Mph7j?GV^?zn>4=m0sKYtzHSgu@^)y$SQhIHxXZ#sLv zX+QoC!x5f~@*EXUxc3v^;^hYEN#lPiC^&2NlXdorqgQ8*kCt;)+hnx=X?9chqy5JgWi!qjt1kQ$N=ZUUaD82rG*H{IlgF{cSC7u*1d=FDN)`!nK&gFIk&CR+f4D z?>mk1_Y7)k2V6GVaD)}yn@go}`EWn7!ACV0?RI-X!C9A2sJCyuyCxfdk+iYm`Qbi) zu4no39d9)pVMXx@-m>d3e@Xe>^6)nwE+{x_dXIX$>o4qb$;5(*NI+P?L+$C$O*O@D+pmJLt$H;o!)1|RsG;Rq}E zJ_fsH_(}fL?l+qc=Dc4}a8~gh=Z$Ah@ZB$d#LWHkO~VmZaDOb78qMwPpYQa#dHm%s z3kuHSyAsdc_DA@)&iuyQJN<*gn-?p1j#4TuKcTx{z5g0B>)6i=3eGCt?KiD5zF*fS z>F1ZcX*j|Po;hK3?sI@|_|^~RmJc^bx!3aBB=^Tsslgv*|G>gG%y!>zoN|N}#dps8 zM;zj3z4f#?{`&?61!wVDFO}}x>2QC_>buOQgBzzDVa51v_4bvXe`Ys^HGo_G)6akQ zuj|Y;Qx_Jl2WRo!gSXUMkM}2iak?4&*P_B*!isB8z@2!(s%*oR(xdvHe5xPyVZE7K z^JziBS=i;>?EXyJxMk*9{^C9#m%sSn<${8< zxHsb){j9zH<;};Kg=xo>R|&c)h5sr2wm zC;EHuyQRGFxKcsESsUL~Z-+m&BKzSxQM`WE$^NlTH!7d{?^T8)ta#ej+vB%ik`3xC zioW{}@;CqQe>F#}`mUhhtld7Ux0k%SB)jexc}qR^*-?I>-OTMep}XPtSAN6hH{??3 zoSvh6=h7NGV?e*cyE7|z?83YAoD2N-N55sy?0#>*FI*2+aPPue_%Q?g&^KQz-`wHXf`YU7 zeuEDrW_=_2HZ?nL{k!1^E4a_Yxn=1w{^`AUHrq5?uW%=F7WW%GslPhPZ+m<%(`(Us zh5o?`es+~gA0BpyKlYiEP2G}a1qEku|HmpP`~V-l{A%;X)MkZ#&I*18mrBdFJkUQd z?GCfa^c@Nc&f>L9%ze)4rJskFS`Q9dVf4yC?29(qGkSbNA!@C!0fRde|MF zo|j#5^rVDWrtWUn!yYhcUiSG?Sz8*g*$Ch2-VNMd^F|tuu%g%pZ#@4zf7Fu3?w($^ z7ZjZJ^e#PY$9v{wJN+qbG~4cc-(bTz_R}qHHymLF_q0-JlMd(jabGR42k!b*LBUzY zBR}Bbv;EWk{$p2N;0#At!9A^1ntab7zxkI_>_bn^E+{yQ&w8o!_|*e_hj%x&12-;S z4_5Hg4rB-TuuOY>BYWri4O0Fs&boV6z0D^t$X?hcj0P)@^QWCO?7;62T0i9oEBG0V zZ;*3(`SKa#vTpqd58vG)-_sN9Hot#vUcT}4!Z#NFu5#1{_^x*D!t9mqqL_N- zGFu+WSl0j^&zvbN|`XMcWh zNp|0AQ5^m1pKj2f*O;YG^i4NjTW7~~|2^yc*p!67c`d{DmRp}&m`%agvr_5OM}Bj4 z%kMQ`ZhLgf5mxZmvr?($g!kQ~3nrNn@1IyuaMqCf>g>6l7G@I`OB+M~Sl`}u!JX#g z^6+%Cy%8DzYj)kDDTVK9Zex7sd~AL;W1c9kx?rrmc;X{w=r_Ys{`$shzW(rte_^qG zHF?y0xA)MLBdmDrkUDFRUyv=@T+Y>9S##Ip=Qqr`-wZA&IE$}8++lw1?f!Gld!}^l zz?37b_HdDcut+YcfAGKVfRZL zlXjW!{`=S2=G%Xrm~w;_-2d@x-}hbDVuL|uhkH&fC^+kw=dru(w%@V~UzawH{Eu@N zH@L!_@W-hsM_5sOG91-znk!?M_sF_43kuG<;+i`9?jFBoExrnEJh9a6JaSRFzU|3r zSFAMNGwIi?$FWlqJ`3}f)!Eqx{+fM#u_)}*bKU1pY-eisJtgG`EBK7SuW!lQ?y+w- zH{T5#Tu^XU@lO0|RPGvYxWCzb`WY!lSixtcR9e|;id#6fy;<+Rp#=qJaW8;>`$;#s zhh`jM?pQgraJRFfc&_F?b-HWyp)rTPQtVNj#dm(GWDZ%F@BaMw^wmRKlzBfb@84av zyt^GTb$K>(xO~BSBw1lMvKOU2k2_hEq?G&-#rQ#j;v!kGpAH`uerK z%N$_^w+%Yi?StICPmW4=oOx%N_ayRO*KJO$wLdjok*%00ZJhUGcem3+W74(Lt}And z6})Q}-xsEw%6s$ zvuk&mk^CRU$a(pdH;ztc4H#fJ!iuHaU`Ez*c{cbpS=ny!#!&n4dLz zT03#~!{APcE2;0W!uzFPl}4mp7yv!_ z*8S3#?r4&7*1M?CYDSB}K)yN6*fmUer5%sULi0=(kw0!&$ZVUr#K_HpWgB zIJca8hVB3DVQH(j+ZGg@)$Y++JEy!P>(Nsb_K`XHpc@ZP=PueI<(c4zNoGcsMUjr zS8-2VhE1gPT5NSYID{SExkJbOX*jMV*{imZPFgG;&MuyPsG|f49Ah-C(u@gKg^NSj z{^GiU1Zurq5ol_W&s{HSh<;vjT{mmp+@Wl~yN!VoB>D{sG|OFj<|X~c3Ju-Z8X|&~b zb!W?djD8}G`Ageb?@DxMXI7msP=Z9>1%c-FSBb8`E`qq%HP-qt zvMuZI(*uP-tzFjwP3v@`>juT^H0|BJ)>c4h8|IVxrGXM8GHebspF}3Q)}|IjLR^%! zvTZoKMk^Xfpw_VGf##g_iLUz_MB5!+rj^xdZYb+n!Iz-~iCzck{KupO*X%Wd_^s>+ zYkq7U_M%Kdg+Q%AS%b{!`4U|DS_qbng+Q%g#e&SQsSj34BZ$f?T3AoLDzFbON89J4Bqb@OTwc6Mleh7u$&Hb5(iN1vG+^;~S{+fao- zE!<5>Ju3S+^Uk~+toWq}WuGMyYMh~2Z!dG=NFTQSTr-70E!?H4X$=D$)?ax>vapqt zb+ir8s=@w9cKaXst(M0}GWPc&#mYbe=XpAbbib%owLlEpw%XsoccB*cM@_rA=e>C_ zOAON@%|V{M$@h1FbrOCeAT`y<(+ zJ)f9m)^}nPcRV#vf&|XNWG61lZH=7Uf;rRPFM;e*rlJfbNZ=f-X%9B$woX^5$wurfuMnt( z{gKvjTE&~Emse#c|Ej`Jf&|XNnl`UiqB-qxX~t+yM*_95KhhbKhEZnA-sRZ1MNTC; zh=e*j|Jx{y+3@?)Y|^MY3V~V}Tci^_8D3i}TXtZ7m5-?f%b=)kgMZL1QXwI*Ybx&PD)*Ml%IJEvXqrYf z-tM$7{NESPT^$1jG3xM5>r{hQY*3xW3V~WRXs>&Z;V)cY$B9|(a`SW6rJ`+^_xrU5 zN|2a(FVMWb?71uKk{})ozivHx9?qg4)9wU#7iz7jK+%t<&t03o6h!8T(^jhDO;}f2 zsYVGBGv5W8_X|CDT^%fl*CXSsX(t2ORQ5z6P-|uWOV-d8{w&q*{0f0u@pK-?CnnLA%C>jYb~Lg#;7Z+tiAu7H#UxG!%%_*MpbF$C(B&xz({Tk>)%Bo zP^(B(kg4x`=(?I#q*1ijK&!}vJw}=fJsC=n!00fo{8W#yW+eV-d_QP_LZH_79fHhz zXYRWq>4XaT&Jj7R@>LcXX}|oEp#%wxa?|eUb`Q+0FJg=t<3}h2YT+3gifnfpVxGP} z(s;T)N;zGFgc_m$zVKW3HFrDX+j}tzfm(PrhrVF541CC--}P_zwNfH?8)zrk=~NF~ zLrbbrJX-l_=FLL}Jl112G*zOUNSvr1Y<~Inp=(r_sH?yw8F{B00Y>QIW(t8?81dA! zZkv2~k1lnMnGM606%!;fmk2gzUVh}7FixZ~>U}0Yqv;re@yS^*VX;KK*YQ!z%_T1ZwS~b%Wj&6J2G_2_lD?lk--$jUfliF_a)t zns$XI%>NOr!USpilgI*US}R*f%%%pEmfxE{S1Xmr)>#VVBS3g zB}nX>9AuXEedRjSO%OSL%f+4hDzp0g&M5?H9cvV1wv2k|8vC~(PHZZ~%WkQ_g1a9w zP=Z7-jk`}*&a!@K_O5}J!^UFSutL+kCP2b)89Y|66$%*Nr#K` z-*+;$)wi-jpcbCX?V>?k*sjjaZ2qX zftEAvl!mKMy^k z5U7Q{fFh~sH69sIkBvKjUTN(}pyf<=ax6&CXX@42A6*|Q1ZrX5q_oUoNDKqDY|SOgpx6rRJy7`m%fRB^3g-aF(F60Lv1s zA#}fJvufp)*#HT&oN1)y8Xvt~V-4R0C6};G zduz?0YsTd{Od(JUXKlJ4Zr@{T;qWU)`)`7j*%=A6oauL}%RI7b9{tTI*fmrkPz(2H zXxffnPg~6z9Wc_AX|9}*MglEoO>2B^uNCs+W+S+9dxbzPT)U+kd-JcfYP8;9Y`xf( zp#%xEoXJ;f_`Q`-X^s)MtB*pU7Or5D4d>`*o!vX#D1T)jLkSXSIn&(wbYf-tPQeR>qD9u6)#3Hlpvwn)MZB9GFN2JV_cpzQXxjjMH7P-$FC_w_(MQBB_+$L+t?I!G1;A4eAEsRo7ESxQ|9Fv={EC0SR zP=W-ma?sARS{tmF=K|TrYFQW(sD)7qTFqFy$ol6}eb%UXHii-;a9xCA;mg-qg$mYS z5v-s>pcY0csIK}hv@TDq#=4d*&QO8`u8YtY3|?zxy;_PL{H?q~pcY0cXt!af1(va{ z1p7BSfT08lTo=)_^k;vt{w$P_WuC7q1Zv^#J=#t6Y^XKnL|*o;O?_pT9ul}NLi=~) zn_IJw`LG3Am_ncy?n0zhvg3IyW0x1(&LfrGhDfL@CO5M@r@NF=v%O($6#}(zHznOv zIBvWdyZwU^Tcv}tYZ3|dE(=$GU$bS{L&JL5RUuFd@6n(&ukiWSrby-vn>LI^(w!W) zpWkwoU%1S9{c@1mAn$Eg!qjEXmzOAt<9*jPiSD@2w0Lv7RjT-p?lG$eF_a+jHhZwS zwcTyktoDLfe&djp?rc#6weMPSoh!Hx73;1LsMWG!u-SU~T~{?G(zx9|6@M_Xwpn&zdxjDu()0{A zbGdH265oqm#np3U<^Qy}>wZ|92oJ)Os?lktu#VWvnU zZ*d2&cRH(CC8~l#pcd}Trl`Sm#v5f=V21B4t?a-?LO&U777w`N`lputJuWrk121

      Q}H^1|tMm{Z#3QFf9e;k+7bTD046dJd7s_Fr4@7Q??cH}A-z z5U7Rw-ZibiPaEF)?kV$YXF6p^JQBN8g_!<>@3?v{6=xbIEb7FMrMqAb>6f6KfRCTqp?Jlop~&ck=xC~;9Fus3U( zp5Ke#Tu@c79@au3Pzz(EbmH(#UVh*Imh=2qp$sKRU~ks6hpY4P=tm3m5_uXc1ZrW7 zlq~(gqWt=e9eU8DAchho)bj?BX$tTaTm6g~KZYm-YGI6&)+RO=zgsp5xvZY;wmU$_;-=;N4^tjmnwMdg_XDE<0z7TUrtDg2V?aLSy#kc&K%33v`n=!j+1GDa!pX@V=cwP}tB7PzaK}ao! zIMpa=`&kkW&#A_#_lEI;J&jst~AE zjm}#BIq{C8u6@?>+{74uA_Fr6j&w4*HEU>U+O=XLSCvjSFkgoCw#y`GmnT1S9lrtQmUe|58O&$@dDqNyb)`}cB=DRk`B60o z@*HPwnP*09QwY?;Q=8;FyJL9E!~310c4ht8-x+Iq4D-~wr*=z^8Nr<)E_X9?vVjsL z)N+KJ8^Fiat!8#E=vD~Sl67dGwWYo1S^M%I*Y7ZY9&zkr?b;F~)N<^;*^OVna>Y!y zWYFD%|ifm7A&!5%W?DW5pis8FZt4(49 z>IHj?d3=N4N4MaUo-B1guHeN`f`lxe^d@>u3*s5$a+s-S6jKP)%2%s_xq3w}=|_nk z6}N4b{)BoI_HAr2SSIpogGTVZ>6tEC2}+Q_)zmI$Yi}cg#RjiPW!no`JAN!?l>;nKIf2m+4+X~ zGxSS+ny~Z~9mwap?RY}b0qJc!gnxebb%?pGZ7=&-)BZS@m)|}&SFd)kF+&Lwapa#T z+`8>(VEgAc?>FTK%bqmTpY&#!U-TfcM(E}ipGLgO@LLpE~ZHey^YVzhec9=_MeyS_GjUs`*I_>_{D)3buSDSGQYk#a=n?Nm$AZXfq zy18ZR?`!ofGtw{|0kA*HlG~#MMOYfQpj?&GA5kAf2@=>h=@$`p1o1um6V8o+YAZqF zNNvv-^h9e5PCjKFdso@%>*%YrE7S^k9AeM4qD+)V{7&n9jd)k*27?$%kdWnbd5C!t z6RZQk#jr-^ zv7BFz9QiSlYI||myHxLPcjOQ&dZ+39W=%9h2@6RP6IQQhD;~l;4jAil$cE`sX*gyK8tB(eoGhX$u|4yfuW0#vxPrPxYuQHaQ zM4W{GNMLShb?IRlrt1Zv6L+BeM89+p#^tUIo9W&({@*xGS*3EMH<%0**h;99z~hQ>scAc0YCS`BY9 z#L{<|?s@bDkw7h3COI;^$z)hYZp%HJS_w*!z&O07JlDFQ=#h5~!u#Qt(Rj z^JfM0mofd6*%`-LY%$bp`A)0Iw7E_(CZYrh94j@gQI`o;K=pWs7!#2|E&MiQCwe!t z#+M)N5^WbHNMQLswGx+TB}kx_`prYA?Y2Jt#+C7N+qGK*5^7y7^oesnDm>oRhx!M; z3$^f<3+Q*^KK&cVkMzu?|Mk6}emd}?BXPqQdd`-q?PonSpMLg>_fGNmPwMnAj(e@~ zHp>^uXKNMB|JI%Jbt(IqwB3SAP83d4(o9$#=N6J`V~dzs8a=X~x0m%d!#gF|&uSXI z(=;`kPRux65MSL8{f;ahdiFXRVjgOGY)|qu#vQC~7P)cCepl1M^jl;BYwYLe*Q=TJ zfBz|kG%$6{RUcl^%&;o6nLLfM-rL-(su^|(N8j7+J{w!ve$H6?qPuj~swtElB}kN< zebn7!X}J^#nJcGAUFO8rTGv0nd8f-8`|oO9$qSqt`as?n9rtk-v^Kw#}+jSjor z#Pr#_!Iiw^Sc_C@Q5djI7V(m(>W zu!X8=$QEvj{K}SZKW}WC&K!6{o*>ap9_7M?0(jkP7~0Z zR6_PUTO#|T{Y>xIMLNle4VNAIcgI}zw-v3BzK8u>r)p*0G2puWtfqkyBt$Eu?~ww5 zBf#OU+4V2Bq}N4GaKup4KnW79wq@0yzV@=||0Yl?=G*joT>YXc5U53Uql-Ecx%zJc zB}j||o|JeJ^`bLEmh_=q9&K6VZ*^+#{4m!_vs%1Zm{zv^V1!ByVD(?6* z9^%p8ZQOI4*0HrJCe(4K?irc_f#WNE3scmvC^?SDYVD!~3HlbMsK?~(3JKK0kw{Gg zB}j+X`loN>ryTH73c3$NCOGf z!Vz3e1Lr>K^QLHLqU7>BnaS%4B}h<N9v{6(7 zB}j;GLFGsx4J1(Ozil6B<2XcVJH!Q>3;dVc&u9~=xk3pN!Hj8B3oTid zKr8G{^$@dQ`U$ob_TLs6N|5-Oeg|u0xpOwHrhx=%;rOT$C_%zGEzq1jDq9Ne3JKK0 z(N#@D&X#to7IuiR1CCCQk!% zg<3dbs3k`U62j{eqiXUrkU%XQSJX7ndJ%n`dae#7x1Uu4Z5$*-AE(;=9|UTl9i*m# z5+p<)7h_iPk|Tjy|7~BP9fkIlw8B$JLwF^^8WyPw@8M%<(T7vZff6KyuS;z#g*1>r zE%c++G*E(s@S&+CrjP~_sD<{Ung))R&Rf;Yw|jrG$6E9(RRSeQNQ)zdks1lqk~UEa z1WJ$?OTN`_xJ^NYsg*1NI&uYoha~I_hvz$mzmM;YY zB}j;|O3ZS}OO6C;$?v2mCs2Zf7^}oA_kR3XQiR1$z2}j>&PS^n+Rx+> zIccOwAy+6t0{wP14J1%YjEywnrH}?nkofO83dg16!|R!SGt{!{M_N%S)D=pQkha$U zAW#eKV725ZLEjWi<^Pm#BW+Vg?c|13fa8KnW65>uxavC2v||o9PQLJP=bW$f1)Omr-1}&{r4#9`|AZ)_uwYFc-Qbu8~4n88fibT zjXbs|Pps|{rtk4yP6FPwx3mE&)V@0pKg)1rj?=wT8X1s4EgV|~8{~oWfcTyTI%DXA*4SREnxw5s8p!D`ouI#`6H-TERMp7V9f&`VLHjTUg zgFr1DCDdHum_e~5r?51j#iWo1jy_0GJl`qeOUc_V5~zjqu9_>9AR#Pp5#vvu1`?=+ zBcGZESw%WU9qkC6^bPE1vYd3Xuk2@)KnW7k%Wx;p75W(zxzi~kXxnY*m#Ar=1PS^s zx~T2sX&`}G=)I_Epaco}db+6XYFZ_&r`@1 z5~zjIHZ={DAR*$%q75W3ITENvE#%XRshS4HFQ|6i^wmu9-v5qepaco3X*Ycjn^x06 z0=3ZAQVEnGL0`~K^I!^TAc0yqOQ>m}?M&XJPOG8zXdwGd3L^tbkRWeTC;#(*5UBOv zqYp}ukbORdG>||o9Qo9e<0wjNEIO^kBpXpx0!L0HXjMih&Em;hA`+-2|89?{DW+jd zkf8M)o%Su&{?9aQ0<~}i*EIh*8Lc$Fv8?zcf5RDZ-_<&@o}T#b59bg2j=FXq@;qbT zq~B^Rw@{D$X(Y@4jlVJQMPJA4=k;x3@3J9|-|l*z(I(QgBW1WTYHlAMOvIF23!N3U z+Vl(4i=D;R&3Dcm?s-OAoAxLEI)b}rG`BWQ^f&&U%gojHD!4_it~RP;j&~QapK(Qq zcCk*HVLUA`ghf#rkBfD7o}E}nZ}8Vo&ZjHdIcG0-+BxhrrmJ&7dC#+^y}2`-`4s79 zWZdX);A}AFp{_5=*1##!>wG;(pV}*}bK}HSv@AM zua|a4v9;Ce8o9Qq1ZvSQkn5LyKRDcb#R-ML_AzY8;rvD}`sP3W8LU6FUO3ivU*bgj zfqv0dFX4XWc(_`eJ{uJm#k$_rjWfIa4U{0E*6z`hQEXZeGcNB?3Dk;R60AEazIW`l ze0{`x4}2xl`0&>t*8bgMBPX>h zlpukgCH?kth5>A2hmA%sl>-UX3TW)qkH45M({LT{!JL~<8zZQ$&>yUQt*UCMs}I%xd-lfQuyBxrom#W>@stM4oIW916&rkfB{0=3j!{g$Ua8~y&d(RaPS zfpO|1jVtM{!Tas^Vs7cSo@$+$!@6T!n5LEkiM(D_^;Yk;%UspU)sdS$>Jv|78b8hoWk*hBXKm>VB7s_1 zKKkvN!r`p(ifpXOQhx)rQuCs^&##Z269+AJs>HP~!`Z`f*_h8_wXTp@Q>2)_;D<-f z9>0mU8?Z5)O}^;MVi&3eYK;mhrdKHV$k|;Jy;eIP&h{?zWzh@#4U|-mDW(@0`>%6+ z_>v^Kn(Q0FzHj8q(o$>3{36l%a4~(t;D^pk*~C~fJuHH~i1%Sr=BWf~9eq|z&ul($ z-rXk%zkv~~qkdEaMnn@EJ?1KeHXzl&Gca}X*R%IA+fc3aed>; z`_2-D#T~y-_D8TO4Sm?n?^Ob|7Bw%fUrM~^yx&@k)Wt4Fu(M@-*Z?9>Vv<((gnQ0q z?UyIX)v4PNY;sN?RwzjtNc_{exV~lJJ?E}X;uhMOZzI@~XWnehcWSOsYh~Nw`fvH} zITvRVGv~pd+Oy7Co*A*!c7M-XUcZ@Tk3GU+|7cyYtnQp}K+b~&=C)zCe*0joqFkW_ z39Lg+n;6%UjqRS6ot~}|sC8{y3H|7?voejoUpHlbbT{01DhEoCP|LA7eI$D|$cqKf zR0-5NM!#rSvgcKqM)T3(%)d}J=Ae-pB}f#cZ!;p}J!xfRT^G(`<9yjevVD+1t?({I zbhF?;GL2jtYqK?fmSKZ-`y04Zc2!|ty~c>Fx)=ws|7#l443@88Nmh(TIFuk!v2GsS z^-CI?re6m7p*~9(Qp%SQtBN5$Y(WVS*SJ=TSkOd(3m)Jg;c&DI5t}wTnw&GR= zRy&~@d%r?02NIXtdF$f8XKbJOHh_Kmuo8=-Q54^WT399;;ZFLp3cJGDC2EPggYG%M zqLwXeDzEMLoWt4|*M)_IJ5}hW!d<>>$H8#6ISGMU;_Hd;a-akW(WXRu5O31712uhE!QUfTI?5Fi zsHNsgv?5~59sw&h7%um~wCP@h)Y;h6 zS>dcc5hy{TY~%aR$|1#dVKdTi4^+ve&h=p|oGbv8^z?q@d=Xkq|AA&QOk2~MjrU`##)q++M4$wT zjs5IxV@@4AqwI)?EojKQ5mTAoB_|}*)t1TNqvjIwwP|GnV z+g)RHk)wji_C7U#A<&7B}ibs(H+0BJB_O2`?1aR&G8#x zO$*;c_zj*kc$J?FBX%IWN9_tFNMMAO#&*{n!zlkHJ4&q`3DoN9)5Y1laovw~HK)F@ zY(W%jO0ycqMg7lZb?&NC*Z!Kqn-~7NXH0Y-o@R9HIE3Y)c7^Z4G=!ffyfRNYwiJps z3a=Q(rjyT!5+pEfP5U{2v=K?f061c8Tzb2ULck6nYo@^Jj5+qP7=ErsJ(LvQ^8ZrsV{>-Np!3ovc@sAVEH@TX?M=zxIZ&4_|gSf@P+t z8WN~QKCN4LupYm5-vw{}%%=%kxxwE+3Hh{c;i(G07T-iZ=U3kRSfeKF2O1Mmf&}@r zZsE0h{Mtulym_ukP1sj!R06fgr*#Vt*5lV+eC@?+u5Q8xP(Mcr`Lu4~sS3Xq)23e~ zIpoDNA8*3y{;Z~f1o^aX;kA1F+OcE3c#bzs*w$4lfm-C#x`hYp@oPuM`SOp}D_N=T zk5(#KukMdlF3kzu8p;)>PJXl7q?`!f zSuJ_x#$NoJLXm71&F3gVg8XK;@Qgja^PQrkrd5_sm1e&4xm8D64@gY_pX0}0fcw=SbOeRXy@ismgki zN)v$+B*;%Qg}>(U)y|X;O0*gjo5h48Ls zKDLGCC?rq|dm6>t+t=e)-xXo|e)Km`f&`5UrtrQzY0OP!@HB-=vW`@{NT3$>M@{QH zr6c#s{m3{83X8h;JZ+3LMngr%B+1d4exyI`7rH;v4#kgAc5bB?t%Q!p1(VsU>v2ABY|3E z_nIH$zI2~{`T=}$yNyOBT2aLFIOIK;!gmwj8NUtP@%wdOZhW)H*iCB_C_zH3EDOKW z(@K82+l!Ykb=bH>xk3W9)NkH!+)zGi=hsGRS~rmE&UT&9s+{?8RgU}~Q}}V7G~`OP zAy%s8>a@kO-S*PO-@Bv1=$n(h(47tObvE@@Pz6_dV2Ld@}x zA3B7!jXA_yb~UZ!xEP-Kb#9{>^;(o5fjj;+ZOz(P-njk)y%P0WBv1?Q>(sP1p(A;8 z;vRi2c||Be0`KUgUr{;}%{yl(W3;7J87xQahhXz?NW4Q>_n1S9U+s zN^PUxfAD?l5Y|1uiGEdgRy5!CZw2E4ML$r2#N_XT&F}m^I6RjAfQiw(>ZyuGL=pnE zdVL#gHp{8mt6B7m2qWp{;UkrdE#wKKB(X!VdFWIsd({flre8SfAI*p7tzulJFNhK( zLaPOvKjup#SFjHCi00ikR58XRAyDgD)nL=NU>bWhOVg@$iRS)(0Y-fyP%_P%ZVr8u z#$L6;wCNWS+D7vVYXgkCWc8s0iQx}}%tD>h$`z~yyQBEiDs_z$NeI-!{!hPB*(#b} zxE^2}Ap#{x&<+pt^Zt@&4WoIf9MueAiz0zqv|GgdyjvtBek9MirJo+Rf%av1?u)i> zH^$a3?k!%DY4u9ac=f2(DE{Tl%(_@BLJ1OhE?v_)g^%LFb@#iEFHs59l4;v_RnuMG zo?MxbD_equOwZm~^{LmIqSxZPPz&#r*0ejVqj~#d0oI>XSG3c`q`fh2VLQvOY3~G+ z_2%}h%7oJwd|tDzb$|$zAR%kr?U`%k_prqGKmxVo_mITS4$=H#rvNJlwM5Jn?W{3r z|BYMN>X@FUZSEG$UtO+Zb^YAh?YtvFJ8n$ci{tj}#qsYG%@=pBVr@u5pcd`2F==0p z+hez{9vaQh53g+1rCy5?+F4`L{u{Tj)zw@T{wkVpu2{*+{&{4ubA<%$VKHehj?1$b z$1ydU=kHR{`XLE{TC^L+qTdf5}rCzbTKR(>9L?Q)>jY8t8ICndT(cKfnJ(foDV zvetAO+fi~iTZq}O*JGEk)iG`Q{lU0s&X1I`I#Y}cB}g2qMEAYM-E#>Wo^0xoF+A_U zJXTej2a!N6Z24rv)rjS#Z>O=M>6@bj2{}K?J}75SQ_P%5pqARBq_t#$wPe?ow2<6l z{E(KD{Y>|yR_Mpe7u;>_-~7qGvI*3ZwuJq6`qc%GePs#zO4?L*&ylu|{VZ)1nTE8M zEMYC71PQD|irkU4q!0eu64nwDs3ol$nZ~JmL->e$-&zA{OhgG1YB{8}WC?2t3DlC- zl1!uBoB_Oj_&V$UGJ9{7uyJh(5?F6^XQsyrw}cfgEpNLPrG0JJm9(#A8qx~4gcXhw zB%~EC$E)I1J9FB%WG&jJrh&AyoaGmc9n+ORSr=#3p!gL^kdXeB%$4-KEa7<}fm+zc zG%fAeX8hKUOnfc1E9uwRsY?&Z&O6o!-IKbf6)*HAHBU#mLJ1Pm_mL%+UXdldA|y}? z>y1|X4u$Z8HS_TR^3|mGYnKpnD1BVhGuJMiSD&vPQ<&c-UkxQlNDo==*_OUD7rrwR zs3m=8nMREt8uP@GIe9~BiI^*jeVZayEi7_OPt!g;Y|K+_&%xJGD?teo6xB9G+}ab_ z-ccr$ZtTs$SrP)ZD5`CW7`DgW9o#gOPbrmyXCMM46xB9GtXkN(n6{>MoEgfypUcko zQOQw)1Vyz?5x4e4w$GmoDM7C1}hwD26=bK_$M7W@nTjAtS}I z*UA_&7j_~Ns3l{_G7Y(!!Np!2xgKE(n^UfA*v~RTZ+fiP{$F@;SItQ7rkFlTC}!*y zQDI^G$`uHitBbY0`1fTZd9}|g4YmXciXXd0wAd3vKGo8TugMk3PbMKyi(<)c5h3>2 zqEiNY@mlF3d3#zhK?%i--6AS1>`ygUx0ZWx^PeVs=ue+kOzd1CLGfd^h!%Td$X#!H z@lrdR@E1R;1Zq(%*)1Z(9$R!zHgCRoeiQz5wZDN9iW$2_R9M)bYOZ#Md-KErO?a2J zY8psT{Map`#hw`Q*S~sm^NS|@A+-{G7iv)~*)1Z(9$U0aqBpPiHi9=Jy96Z^Gj@xp zu&_VzO=MqH^5L`2M)0ejR}}5KLW1JQZV@f^#E=&~@!{*kBKQZIaqwNJC0A%rar)eRf3-&Tc!d(V`f9gud=stedscY4Sm8wp5^~i^ z_K#;x3h~4#fn0d0NT3$>E}GTO72~(g*5P733MEL$RVSH-T#w>nJqiibQhRO4?Wb1w zR~`6zvf<UvW*XmxlGoM7O$S6TVu9C~|A=l5jSU*PswdDG_Ohc}7 zazuMZ|0aWIGUn|hwz2^@AO*aT|HeFriPxjTW2 z-3cf`0_)J;O(phBaIu>T3DlDNCuACD4o$QEXg`Esrqyt{d&90pJW(fis>r&^TOits zUpb5)C7%-|NOT@o)!nBClW8Q}{>EC}awxw;{vZ;lMUi2*@Mb(wgG<{MTfOfM;>*cP zMMCapv2%jC{j}?ai(M}$K|=0rk>!||dzV$OOFu3=79>y$Ta2cSpCCK zwJ3KU+0Sx!k||De(ORl!-x7y?OSS|Fxra%9k0Z_r#?b9Ud1~^{@m;7z-%0G)k|p1E zrMuDg)NsCoW&@NUA$L~Eax9`fUPV_7<1;?**s|Y+T5`9TOyl0JXruoR!|X4J5+u~R zlDpfu*xiN%YKfH-;dgrckB78_u6pc14m;><2@?2i$miU5)cCbkFW#O`T8MQN;gO1W z;nx(aaKd-$(M$Z; zKrL~GMfg7+uc%eLFH5~RoEIkoCE^T=@NaMM*ceu+BhOE>GqzD|yV%AwZ4vF?-T$-=hyA;D z8$|+ht7#k8rDp|(wBR{tR>OCpmfCik(=V94%+rLgp>m)E3AG$0YWuLVry_W!Bm`=S zb#39hd1f_nhK0_uaB+?WB}j=S)P6Ot~!6P_0#zen?NnOUtIRu^;1i;vX>k@<|o@%`}8ice?dfC z#Q32Sa_>2Zz32A3kdXV(Wv(tf%*V3S4&j4ocE)$17JeH|OB0%#E&kAuU!!l15+uYf z4iVw;jBpuxW@kID(ykPm4Uj-B9LF@xs8o~9pHhw=pm`8$6mNy58W3lGWE!36l+d#R zC3z9D8Bl_RJUt|9SDq5$;*<~)s3lJc$>?CKR883XN8WrUMd+#Rh;vZ3uP@H!2v1e` zwemccj6jNAfWm)<^HFwWLY|4TpYcs}dO1TR+cD6K*Q2_k7A;O^CDW4UzwEzjTK#XD zvSR^Rcr@h-CHP)7SMu~3KSQ$t5~xM9kT~Hc)A;Z-f;CL%!>>~sSXyxkNqF4CCr6r2 zNXJF697TP21F}U?f`mAiBRp}Be;#l$f~~LZ!`CDsP)nS}5#G0FttfJR1l!Zkhxeh? zaFmGiH^So3kovpB;0_N*0MpBK)WzVzieX>9@}Y- z2WI1uw3dnzB*eKK;a7XS?bFLc+527Dxi3WxkU%Z$UG)2XcN(x9`||KYG;^W^2^vSl zIbqocyVA+xT~pqAQe<(X;=&Q#mAE6-8e?p9+C2w*5m|iVM7B&ro*A{onNgG=fpw^9$LXYZ*Z0q@ zel)@%fm-rJwoK!s*?}#|@YG%_LJ1OTIpj%iOPusZ0=3AV7U$h%8c)`BXE6)UTlMIK zG)j=bdi!)AfFysNHvIP=ts~SwP=W+`E8@-pnJamNfF*7aKmxU}jnN5(f1+5% z(YpOT@UEBQ7lQR4_zRa$rzIb6rjYGw_{Au;y{BOnB3}*5fduWD(P@{B%VSe_J{ZNO zBr@yjc9lRa+B2im&Kj4;rk=SciVgdtjPK@F zN|2x(9^$SSxzZqSZn4D8El8l2ytzfD5&2aNEBP?D#i*atJ~Ey5!?}b9NxQ;y+DGOR z9wfFS3ZhI#MEX^luipcbvy>xH)8k*oSmhsLrxxnG(4m)rZ{K1qSyMsu>=X!TAt8A&+}UenX5fRV%Y5oc`dOX zg{7t4Z946Na|!Pk)6=vPy<^ymx%n)yj)M{;XxE!g`{7)k{cz2?#IWr_`K=sD2-LzJ ztZAbiqu7NNnay<+hr|40IcNuz{?(<^#XUClSDi;OaqH5bWQC&y3HdBO-p^x*HAo~-i*~2zw4cS{SvTl6BZlqSkjrRK1WIUsiB9`g9KsgC zH)+~~B{6KKPfp{jBxxWa+paA6i`B7gRf7lmGa3`|U8tqj?uU*eS?w=&=yz%52PH_z z7An(_ZC4j<7YWo-zlXg4ii`WN@Rl@r|CQ~T%6qY-mpcATS!;tknuk)4LISlgo=pD7 zh(?xwohUw<;_WCwLX1^nPm9Of_KxadB^(;gTT<;Jfm#@Wrqdh&f14A}$MS#3o4~wd z4(YZo7v0t+)41lp(ENMlNPdM{J4%pHZwp=gq>S0U^e8@>qUT7U*74t#?>XHxP^OVO zRaxCCIf~b(xpoiS3M}spv$c?>Uxa=$!TD#aQT#qxWGF%6;iR#poD)8#k#pG;cU0?9 zycSunNT8OQtC^ltzg(R9#h9)<^=sz} - + @@ -106,7 +106,7 @@ - + @@ -135,7 +135,7 @@ - + @@ -164,7 +164,7 @@ - + @@ -193,7 +193,7 @@ - + @@ -222,7 +222,7 @@ - + @@ -251,7 +251,7 @@ - + @@ -280,7 +280,7 @@ - + diff --git a/examples/CommonInterfaces/CommonExampleInterface.h b/examples/CommonInterfaces/CommonExampleInterface.h index f3fb20047..14d19ec3d 100644 --- a/examples/CommonInterfaces/CommonExampleInterface.h +++ b/examples/CommonInterfaces/CommonExampleInterface.h @@ -46,6 +46,8 @@ public: virtual bool mouseButtonCallback(int button, int state, float x, float y)=0; virtual bool keyboardCallback(int key, int state)=0; + virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4]) {} + virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]){} }; class ExampleEntries diff --git a/examples/OpenGLWindow/GLInstancingRenderer.cpp b/examples/OpenGLWindow/GLInstancingRenderer.cpp index 64503dcc3..e9c5e38fa 100644 --- a/examples/OpenGLWindow/GLInstancingRenderer.cpp +++ b/examples/OpenGLWindow/GLInstancingRenderer.cpp @@ -16,9 +16,9 @@ subject to the following restrictions: ///todo: make this configurable in the gui -bool useShadowMap=true;//false;//true; +bool useShadowMap = true;// true;//false;//true; int shadowMapWidth=4096;//8192; -int shadowMapHeight=4096; +int shadowMapHeight= 4096; float shadowMapWorldSize=25; #define MAX_POINTS_IN_BATCH 1024 @@ -363,7 +363,7 @@ void GLInstancingRenderer::writeSingleInstanceScaleToCPU(double* scale, int srcI void GLInstancingRenderer::writeSingleInstanceTransformToGPU(float* position, float* orientation, int objectIndex) { glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo); - glFlush(); + //glFlush(); char* orgBase = (char*)glMapBuffer( GL_ARRAY_BUFFER,GL_READ_WRITE); //b3GraphicsInstance* gfxObj = m_graphicsInstances[k]; @@ -393,7 +393,7 @@ void GLInstancingRenderer::writeSingleInstanceTransformToGPU(float* position, fl orientations [objectIndex*4+3] = orientation[3]; glUnmapBuffer( GL_ARRAY_BUFFER); - glFlush(); + //glFlush(); } @@ -500,7 +500,7 @@ void GLInstancingRenderer::writeTransforms() glUnmapBuffer( GL_ARRAY_BUFFER); //if this glFinish is removed, the animation is not always working/blocks //@todo: figure out why - glFlush(); + //glFlush(); #endif @@ -1037,7 +1037,7 @@ void GLInstancingRenderer::renderScene() //avoid some Intel driver on a Macbook Pro to lock-up //todo: figure out what is going on on that machine - glFlush(); + //glFlush(); if (useShadowMap) { @@ -1539,7 +1539,7 @@ b3Assert(glGetError() ==GL_NO_ERROR); B3_PROFILE("glFlush2"); glBindBuffer(GL_ARRAY_BUFFER, m_data->m_vbo); - glFlush(); + //glFlush(); } b3Assert(glGetError() ==GL_NO_ERROR); @@ -1730,7 +1730,7 @@ b3Assert(glGetError() ==GL_NO_ERROR); { B3_PROFILE("glFlush"); - glFlush(); + //glFlush(); } if (renderMode==B3_CREATE_SHADOWMAP_RENDERMODE) { diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 5a728b0cb..1ff24b66c 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -115,6 +115,15 @@ int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, doub return 0; } +int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); + command->m_physSimParamArgs.m_allowRealTimeSimulation = enableRealTimeSimulation; + command->m_updateFlags |= SIM_PARAM_UPDATE_REAL_TIME_SIMULATION; + return 0; +} + int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index dcbe9c30c..a3b6dbd5c 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -81,6 +81,7 @@ void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImage b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient); int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz); int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep); +int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation); b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 5c82e3381..420fe37b6 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -374,6 +374,8 @@ struct PhysicsServerCommandProcessorInternalData ///end handle management + bool m_allowRealTimeSimulation; + bool m_hasGround; CommandLogger* m_commandLogger; CommandLogPlayback* m_logPlayback; @@ -417,7 +419,8 @@ struct PhysicsServerCommandProcessorInternalData TinyRendererVisualShapeConverter m_visualConverter; PhysicsServerCommandProcessorInternalData() - : + :m_hasGround(false), + m_allowRealTimeSimulation(false), m_commandLogger(0), m_logPlayback(0), m_physicsDeltaTime(1./240.), @@ -496,6 +499,9 @@ void PhysicsServerCommandProcessor::setGuiHelper(struct GUIHelperInterface* guiH } } m_data->m_guiHelper = guiHelper; + + + } @@ -504,6 +510,7 @@ PhysicsServerCommandProcessor::PhysicsServerCommandProcessor() m_data = new PhysicsServerCommandProcessorInternalData(); createEmptyDynamicsWorld(); + } PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor() @@ -983,7 +990,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char* bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes ) { - + bool hasStatus = false; { @@ -1768,6 +1775,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { m_data->m_physicsDeltaTime = clientCmd.m_physSimParamArgs.m_deltaTime; } + if (clientCmd.m_updateFlags & SIM_PARAM_UPDATE_REAL_TIME_SIMULATION) + { + m_data->m_allowRealTimeSimulation = clientCmd.m_physSimParamArgs.m_allowRealTimeSimulation; + } if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_GRAVITY) { btVector3 grav(clientCmd.m_physSimParamArgs.m_gravityAcceleration[0], @@ -1873,7 +1884,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm SharedMemoryStatus& serverCmd =serverStatusOut; serverCmd.m_type = CMD_RESET_SIMULATION_COMPLETED; hasStatus = true; - + m_data->m_hasGround = false; break; } case CMD_CREATE_RIGID_BODY: @@ -2307,6 +2318,26 @@ void PhysicsServerCommandProcessor::replayFromLogFile(const char* fileName) m_data->m_logPlayback = pb; } +void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec) +{ + if (m_data->m_allowRealTimeSimulation) + { + if (!m_data->m_hasGround) + { + m_data->m_hasGround = true; + + int bodyId = 0; + btAlignedObjectArray bufferServerToClient; + bufferServerToClient.resize(32768); + + + loadUrdf("plane.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, true, &bodyId, &bufferServerToClient[0], bufferServerToClient.size()); + } + + m_data->m_dynamicsWorld->stepSimulation(dtInSec); + } +} + void PhysicsServerCommandProcessor::applyJointDamping(int bodyUniqueId) { InteralBodyData* body = m_data->getHandle(bodyUniqueId); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.h b/examples/SharedMemory/PhysicsServerCommandProcessor.h index bc74a0a27..7cbc87ab4 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.h +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.h @@ -53,7 +53,8 @@ public: void enableCommandLogging(bool enable, const char* fileName); void replayFromLogFile(const char* fileName); - void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes ); + void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes ); + void stepSimulationRealTime(double dtInSec); void applyJointDamping(int bodyUniqueId); }; diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index a4ac05f67..6ae9a654d 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -9,11 +9,12 @@ #include "PhysicsServerSharedMemory.h" #include "SharedMemoryCommon.h" - +#include "Bullet3Common/b3Matrix3x3.h" #include "../Utils/b3Clock.h" #include "../MultiThreading/b3ThreadSupportInterface.h" + void MotionThreadFunc(void* userPtr,void* lsMemory); void* MotionlsMemoryFunc(); #define MAX_MOTION_NUM_THREADS 1 @@ -80,13 +81,23 @@ b3ThreadSupportInterface* createMotionThreadSupport(int numThreads) struct MotionArgs { MotionArgs() - :m_physicsServerPtr(0) + :m_physicsServerPtr(0), + m_isPicking(false), + m_isDragging(false), + m_isReleasing(false) { } b3CriticalSection* m_cs; PhysicsServerSharedMemory* m_physicsServerPtr; b3AlignedObjectArray m_positions; + + btVector3 m_pos; + btQuaternion m_orn; + bool m_isPicking; + bool m_isDragging; + bool m_isReleasing; + }; struct MotionThreadLocalStorage @@ -113,23 +124,58 @@ void MotionThreadFunc(void* userPtr,void* lsMemory) args->m_cs->setSharedParam(0,eMotionIsInitialized); args->m_cs->unlock(); + do { //todo(erwincoumans): do we want some sleep to reduce CPU resources in this thread? -#if 0 + double deltaTimeInSeconds = double(clock.getTimeMicroseconds())/1000000.; - if (deltaTimeInSeconds<(1./260.)) + if (deltaTimeInSeconds<(1./5000.)) { skip++; - if (deltaTimeInSeconds<.001) - continue; + } else + { + //process special controller commands, such as + //VR controller button press/release and controller motion + + btVector3 from = args->m_pos; + btMatrix3x3 mat(args->m_orn); + + btVector3 toX = args->m_pos+mat.getColumn(0); + btVector3 toY = args->m_pos+mat.getColumn(1); + btVector3 toZ = args->m_pos+mat.getColumn(2)*50.; + + + if (args->m_isPicking) + { + args->m_isPicking = false; + args->m_isDragging = true; + args->m_physicsServerPtr->pickBody(from,-toZ); + //printf("PICK!\n"); + } + + if (args->m_isDragging) + { + args->m_physicsServerPtr->movePickedBody(from,-toZ); + // printf("."); + } + + if (args->m_isReleasing) + { + args->m_isDragging = false; + args->m_isReleasing = false; + args->m_physicsServerPtr->removePickingConstraint(); + //printf("Release pick\n"); + } + + //don't simulate over a huge timestep if we had some interruption (debugger breakpoint etc) + btClamp(deltaTimeInSeconds,0.,0.1); + args->m_physicsServerPtr->stepSimulationRealTime(deltaTimeInSeconds); + clock.reset(); } - clock.reset(); -#endif args->m_physicsServerPtr->processClientCommands(); - } while (args->m_cs->getSharedParam(0)!=eRequestTerminateMotion); } else { @@ -375,7 +421,7 @@ class PhysicsServerExample : public SharedMemoryCommon btClock m_clock; bool m_replay; int m_options; - + public: PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, SharedMemoryInterface* sharedMem=0, int options=0); @@ -417,6 +463,9 @@ public: btVector3 getRayTo(int x,int y); + virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]); + virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4]); + virtual bool mouseMoveCallback(float x,float y) { if (m_replay) @@ -720,6 +769,28 @@ void PhysicsServerExample::renderScene() //m_args[0].m_cs->lock(); m_physicsServer.renderScene(); + + if (m_args[0].m_isPicking || m_args[0].m_isDragging) + { + btVector3 from = m_args[0].m_pos; + btMatrix3x3 mat(m_args[0].m_orn); + + btVector3 toX = m_args[0].m_pos+mat.getColumn(0); + btVector3 toY = m_args[0].m_pos+mat.getColumn(1); + btVector3 toZ = m_args[0].m_pos+mat.getColumn(2); + + int width = 2; + + + btVector4 color; + color=btVector4(1,0,0,1); + m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toX,color,width); + color=btVector4(0,1,0,1); + m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toY,color,width); + color=btVector4(0,0,1,1); + m_guiHelper->getAppInterface()->m_renderer->drawLine(from,toZ,color,width); + + } if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera()) { @@ -856,4 +927,17 @@ class CommonExampleInterface* PhysicsServerCreateFunc(struct CommonExampleOpt } -B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc) \ No newline at end of file +void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orn[4]) +{ + m_args[0].m_isPicking = (state!=0); + m_args[0].m_isReleasing = (state==0); + m_args[0].m_pos.setValue(pos[0],pos[1],pos[2]); + m_args[0].m_orn.setValue(orn[0],orn[1],orn[2],orn[3]); +} + +void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4]) +{ + m_args[0].m_pos.setValue(pos[0],pos[1],pos[2]); + m_args[0].m_orn.setValue(orn[0],orn[1],orn[2],orn[3]); +} +B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc) diff --git a/examples/SharedMemory/PhysicsServerSharedMemory.cpp b/examples/SharedMemory/PhysicsServerSharedMemory.cpp index d0b583969..111ac07f5 100644 --- a/examples/SharedMemory/PhysicsServerSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsServerSharedMemory.cpp @@ -236,8 +236,10 @@ void PhysicsServerSharedMemory::releaseSharedMemory() } - - +void PhysicsServerSharedMemory::stepSimulationRealTime(double dtInSec) +{ + m_data->m_commandProcessor->stepSimulationRealTime(dtInSec); +} void PhysicsServerSharedMemory::processClientCommands() diff --git a/examples/SharedMemory/PhysicsServerSharedMemory.h b/examples/SharedMemory/PhysicsServerSharedMemory.h index 2c08124d0..f96e7ca4b 100644 --- a/examples/SharedMemory/PhysicsServerSharedMemory.h +++ b/examples/SharedMemory/PhysicsServerSharedMemory.h @@ -26,6 +26,8 @@ public: virtual void processClientCommands(); + virtual void stepSimulationRealTime(double dtInSec); + //bool supportsJointMotor(class btMultiBody* body, int linkIndex); //@todo(erwincoumans) Should we have shared memory commands for picking objects? diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index d5b50d2ba..64ae61991 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -215,6 +215,7 @@ enum EnumSimParamUpdateFlags SIM_PARAM_UPDATE_GRAVITY=2, SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS=4, SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS=8, + SIM_PARAM_UPDATE_REAL_TIME_SIMULATION = 16, }; ///Controlling a robot involves sending the desired state to its joint motor controllers. @@ -225,6 +226,7 @@ struct SendPhysicsSimulationParameters double m_gravityAcceleration[3]; int m_numSimulationSubSteps; int m_numSolverIterations; + bool m_allowRealTimeSimulation; }; struct RequestActualStateArgs diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index dcb7aa22f..630c2d3e8 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -4,6 +4,8 @@ #include "../OpenGLWindow/SimpleOpenGL3App.h" #include "../OpenGLWindow/OpenGLInclude.h" #include "Bullet3Common/b3Quaternion.h" +#include "Bullet3Common/b3Transform.h" + #include "../ExampleBrowser/OpenGLGuiHelper.h" #include "../CommonInterfaces/CommonExampleInterface.h" #include "../CommonInterfaces/CommonGUIHelperInterface.h" @@ -28,6 +30,8 @@ int gSharedMemoryKey = -1; #include "pathtools.h" CommonExampleInterface* sExample; +int sIsPressed=-1; +int sPrevPacketNum=0; GUIHelperInterface* sGuiPtr = 0; @@ -82,7 +86,7 @@ public: bool BInit(); bool BInitGL(); bool BInitCompositor(); - + void getControllerTransform(int unDevice, b3Transform& tr); void SetupRenderModels(); void Shutdown(); @@ -619,6 +623,26 @@ void CMainApplication::Shutdown() } + +void CMainApplication::getControllerTransform(int unDevice, b3Transform& tr) +{ + const Matrix4 & matOrg = m_rmat4DevicePose[unDevice]; + tr.setIdentity(); + tr.setOrigin(b3MakeVector3(matOrg[12],matOrg[13],matOrg[14]));//pos[1])); + b3Matrix3x3 bmat; + for (int i=0;i<3;i++) + { + for (int j=0;j<3;j++) + { + bmat[i][j] = matOrg[i+4*j]; + } + } + tr.setBasis(bmat); + b3Transform y2z; + y2z.setIdentity(); + y2z.setRotation(b3Quaternion(0,B3_HALF_PI,0)); + tr = y2z*tr; +} //----------------------------------------------------------------------------- // Purpose: //----------------------------------------------------------------------------- @@ -639,14 +663,61 @@ bool CMainApplication::HandleInput() vr::VRControllerState_t state; if( m_pHMD->GetControllerState( unDevice, &state ) ) { - if (state.ulButtonPressed) + uint64_t trigger = vr::ButtonMaskFromId(vr::k_EButton_SteamVR_Trigger); + + if (sPrevPacketNum != state.unPacketNum) { - b3Printf("state.ulButtonPressed=%d\n",state.ulButtonPressed); - sExample->exitPhysics(); - m_app->m_instancingRenderer->removeAllInstances(); - sExample->initPhysics(); + + static int counter=0; + sPrevPacketNum = state.unPacketNum; + //b3Printf("."); + bool isTrigger = (state.ulButtonPressed&trigger)!=0; + if (isTrigger) + { + //printf("unDevice=%d\n",unDevice); + b3Transform tr; + getControllerTransform(unDevice,tr); + float pos[3] = {tr.getOrigin()[0],tr.getOrigin()[1],tr.getOrigin()[2]}; + b3Quaternion born = tr.getRotation(); + float orn[4] = {born[0],born[1],born[2],born[3]}; + + + if (sIsPressed!=unDevice) + { + b3Printf("trigger pressed %d, %d\n",counter++, unDevice); + sIsPressed=unDevice; + + sExample->vrControllerButtonCallback(unDevice,1,1,pos, orn); + + // + //virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4]) {} + //virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]){} + + //sExample->start + } else + { + sExample->vrControllerMoveCallback(unDevice,pos,orn); + } + //sExample->exitPhysics(); + //m_app->m_instancingRenderer->removeAllInstances(); + ///sExample->initPhysics(); + } else + { + if (unDevice==sIsPressed) + { + b3Transform tr; + getControllerTransform(unDevice,tr); + float pos[3] = {tr.getOrigin()[0],tr.getOrigin()[1],tr.getOrigin()[2]}; + b3Quaternion born = tr.getRotation(); + float orn[4] = {born[0],born[1],born[2],born[3]}; + + sIsPressed=-1; + printf("device released: %d",unDevice); + sExample->vrControllerButtonCallback(unDevice,1,0,pos, orn); + } + } + } - } m_rbShowTrackedDevice[ unDevice ] = state.ulButtonPressed == 0; } } @@ -1480,7 +1551,7 @@ void CMainApplication::RenderStereoTargets() rotYtoZ.rotateX(-90); } - RenderScene( vr::Eye_Left ); + // Left Eye { @@ -1527,7 +1598,7 @@ void CMainApplication::RenderStereoTargets() m_app->m_window->startRendering(); - + RenderScene( vr::Eye_Left ); @@ -1560,7 +1631,7 @@ void CMainApplication::RenderStereoTargets() // Right Eye - RenderScene( vr::Eye_Right ); + { Matrix4 viewMatRight = m_mat4eyePosRight * m_mat4HMDPose * rotYtoZ; @@ -1573,7 +1644,7 @@ void CMainApplication::RenderStereoTargets() m_app->m_window->startRendering(); - + RenderScene( vr::Eye_Right ); m_app->m_instancingRenderer->setRenderFrameBuffer((unsigned int)rightEyeDesc.m_nRenderFramebufferId); //m_app->m_renderer->renderScene(); diff --git a/examples/Utils/b3ResourcePath.cpp b/examples/Utils/b3ResourcePath.cpp index 44952d61a..bc50ef5cb 100644 --- a/examples/Utils/b3ResourcePath.cpp +++ b/examples/Utils/b3ResourcePath.cpp @@ -33,8 +33,10 @@ int b3ResourcePath::getExePath(char* path, int maxPathLenInBytes) #else #ifdef _WIN32 //https://msdn.microsoft.com/en-us/library/windows/desktop/ms683197(v=vs.85).aspx + HMODULE hModule = GetModuleHandle(NULL); - numBytes = GetModuleFileName(hModule, path, maxPathLenInBytes); + numBytes = GetModuleFileNameA(hModule, path, maxPathLenInBytes); + #else ///http://stackoverflow.com/questions/933850/how-to-find-the-location-of-the-executable-in-c numBytes = (int)readlink("/proc/self/exe", path, maxPathLenInBytes-1); diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 2a2d9b2d1..be5994c16 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -410,6 +410,41 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) } + +static PyObject * +pybullet_setRealTimeSimulation(PyObject* self, PyObject* args) +{ + if (0 == sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + int enableRealTimeSimulation = 0; + int ret; + + b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); + b3SharedMemoryStatusHandle statusHandle; + + if (!PyArg_ParseTuple(args, "i", &enableRealTimeSimulation)) + { + PyErr_SetString(SpamError, "setRealTimeSimulation expected a single value (integer)."); + return NULL; + } + ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation); + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + //ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); + } + + Py_INCREF(Py_None); + return Py_None; +} + + + + // Set the gravity of the world with (x, y, z) arguments static PyObject * pybullet_setGravity(PyObject* self, PyObject* args) @@ -1453,6 +1488,9 @@ static PyMethodDef SpamMethods[] = { {"setTimeStep", pybullet_setTimeStep, METH_VARARGS, "Set the amount of time to proceed at each call to stepSimulation. (unit is seconds, typically range is 0.01 or 0.001)"}, + { "setRealTimeSimulation", pybullet_setRealTimeSimulation, METH_VARARGS, + "Enable or disable real time simulation (using the real time clock, RTC) in the physics server. Expects one integer argument, 0 or 1" }, + {"loadURDF", pybullet_loadURDF, METH_VARARGS, "Create a multibody by loading a URDF file."}, diff --git a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp index 264c7b9f0..369f1d750 100644 --- a/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp +++ b/src/Bullet3OpenCL/Initialize/b3OpenCLUtils.cpp @@ -636,10 +636,10 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev FILETIME modtimeBinary; - CreateDirectory(sCachedBinaryPath,0); + CreateDirectoryA(sCachedBinaryPath,0); { - HANDLE binaryFileHandle = CreateFile(binaryFileName,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0); + HANDLE binaryFileHandle = CreateFileA(binaryFileName,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0); if (binaryFileHandle ==INVALID_HANDLE_VALUE) { DWORD errorCode; @@ -677,7 +677,7 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev if (binaryFileValid) { - HANDLE srcFileHandle = CreateFile(clFileNameForCaching,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0); + HANDLE srcFileHandle = CreateFileA(clFileNameForCaching,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0); if (srcFileHandle==INVALID_HANDLE_VALUE) { @@ -686,7 +686,7 @@ cl_program b3OpenCLUtils_compileCLProgramFromString(cl_context clContext, cl_dev { char relativeFileName[1024]; sprintf(relativeFileName,"%s%s",prefix[i],clFileNameForCaching); - srcFileHandle = CreateFile(relativeFileName,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0); + srcFileHandle = CreateFileA(relativeFileName,GENERIC_READ,0,0,OPEN_EXISTING,FILE_ATTRIBUTE_NORMAL,0); } } From c9c837cc6754274db1a532737c584756eee7e054 Mon Sep 17 00:00:00 2001 From: hujiajie Date: Mon, 18 Jul 2016 23:07:26 +0800 Subject: [PATCH 095/115] [WIP] Suppress compiler warnings. Fix Visual Studio warning C4373: previous versions of the compiler did not override when parameters only differed by const/volatile qualifiers. --- Extras/InverseDynamics/DillCreator.cpp | 2 +- Extras/InverseDynamics/DillCreator.hpp | 2 +- Extras/InverseDynamics/btMultiBodyTreeCreator.cpp | 2 +- Extras/InverseDynamics/btMultiBodyTreeCreator.hpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Extras/InverseDynamics/DillCreator.cpp b/Extras/InverseDynamics/DillCreator.cpp index a1ddf00c2..46f68e698 100644 --- a/Extras/InverseDynamics/DillCreator.cpp +++ b/Extras/InverseDynamics/DillCreator.cpp @@ -44,7 +44,7 @@ int DillCreator::getNumBodies(int* num_bodies) const { return 0; } -int DillCreator::getBody(int body_index, int* parent_index, JointType* joint_type, +int DillCreator::getBody(const int body_index, int* parent_index, JointType* joint_type, vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, vec3* body_axis_of_motion, idScalar* mass, vec3* body_r_body_com, mat33* body_I_body, int* user_int, void** user_ptr) const { diff --git a/Extras/InverseDynamics/DillCreator.hpp b/Extras/InverseDynamics/DillCreator.hpp index d52e0d06d..fbe0e8e22 100644 --- a/Extras/InverseDynamics/DillCreator.hpp +++ b/Extras/InverseDynamics/DillCreator.hpp @@ -22,7 +22,7 @@ public: ///\copydoc MultiBodyTreeCreator::getNumBodies int getNumBodies(int* num_bodies) const; ///\copydoc MultiBodyTreeCreator::getBody - int getBody(int body_index, int* parent_index, JointType* joint_type, + int getBody(const int body_index, int* parent_index, JointType* joint_type, vec3* parent_r_parent_body_ref, mat33* body_T_parent_ref, vec3* body_axis_of_motion, idScalar* mass, vec3* body_r_body_com, mat33* body_I_body, int* user_int, void** user_ptr) const; diff --git a/Extras/InverseDynamics/btMultiBodyTreeCreator.cpp b/Extras/InverseDynamics/btMultiBodyTreeCreator.cpp index b91a10cce..ef3ebf6b8 100644 --- a/Extras/InverseDynamics/btMultiBodyTreeCreator.cpp +++ b/Extras/InverseDynamics/btMultiBodyTreeCreator.cpp @@ -237,7 +237,7 @@ int btMultiBodyTreeCreator::getNumBodies(int *num_bodies) const { return 0; } -int btMultiBodyTreeCreator::getBody(int body_index, int *parent_index, JointType *joint_type, +int btMultiBodyTreeCreator::getBody(const int body_index, int *parent_index, JointType *joint_type, vec3 *parent_r_parent_body_ref, mat33 *body_T_parent_ref, vec3 *body_axis_of_motion, idScalar *mass, vec3 *body_r_body_com, mat33 *body_I_body, int *user_int, diff --git a/Extras/InverseDynamics/btMultiBodyTreeCreator.hpp b/Extras/InverseDynamics/btMultiBodyTreeCreator.hpp index 0e2d614f2..3844cf3d3 100644 --- a/Extras/InverseDynamics/btMultiBodyTreeCreator.hpp +++ b/Extras/InverseDynamics/btMultiBodyTreeCreator.hpp @@ -25,7 +25,7 @@ public: /// \copydoc MultiBodyTreeCreator::getNumBodies int getNumBodies(int *num_bodies) const; ///\copydoc MultiBodyTreeCreator::getBody - int getBody(int body_index, int *parent_index, JointType *joint_type, + int getBody(const int body_index, int *parent_index, JointType *joint_type, vec3 *parent_r_parent_body_ref, mat33 *body_T_parent_ref, vec3 *body_axis_of_motion, idScalar *mass, vec3 *body_r_body_com, mat33 *body_I_body, int *user_int, void **user_ptr) const; From 2302709e2da56ad50ed1ce1141a4349fc71fd77c Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Mon, 18 Jul 2016 23:13:46 -0700 Subject: [PATCH 096/115] OpenVR support: track multiple controllers and buttons --- .../SharedMemory/PhysicsServerExample.cpp | 6 +- .../StandaloneMain/hellovr_opengl_main.cpp | 85 +++++++++---------- 2 files changed, 44 insertions(+), 47 deletions(-) diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 6ae9a654d..75e475738 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -140,11 +140,11 @@ void MotionThreadFunc(void* userPtr,void* lsMemory) btVector3 from = args->m_pos; btMatrix3x3 mat(args->m_orn); - + btScalar pickDistance = 100.; btVector3 toX = args->m_pos+mat.getColumn(0); btVector3 toY = args->m_pos+mat.getColumn(1); - btVector3 toZ = args->m_pos+mat.getColumn(2)*50.; - + btVector3 toZ = args->m_pos+mat.getColumn(2)*pickDistance; + if (args->m_isPicking) { diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index 630c2d3e8..e85b8af0e 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -30,11 +30,14 @@ int gSharedMemoryKey = -1; #include "pathtools.h" CommonExampleInterface* sExample; -int sIsPressed=-1; + int sPrevPacketNum=0; GUIHelperInterface* sGuiPtr = 0; +static vr::VRControllerState_t sPrevStates[vr::k_unMaxTrackedDeviceCount] = { 0 }; + + #if defined(POSIX) #include "unistd.h" #endif @@ -663,63 +666,57 @@ bool CMainApplication::HandleInput() vr::VRControllerState_t state; if( m_pHMD->GetControllerState( unDevice, &state ) ) { - uint64_t trigger = vr::ButtonMaskFromId(vr::k_EButton_SteamVR_Trigger); - - if (sPrevPacketNum != state.unPacketNum) + //we need to have the 'move' events, so no early out here + //if (sPrevStates[unDevice].unPacketNum != state.unPacketNum) { - - static int counter=0; - sPrevPacketNum = state.unPacketNum; - //b3Printf("."); - bool isTrigger = (state.ulButtonPressed&trigger)!=0; - if (isTrigger) + sPrevStates[unDevice].unPacketNum = state.unPacketNum; + + for (int button = 0; button < vr::k_EButton_Max; button++) { - //printf("unDevice=%d\n",unDevice); - b3Transform tr; - getControllerTransform(unDevice,tr); - float pos[3] = {tr.getOrigin()[0],tr.getOrigin()[1],tr.getOrigin()[2]}; - b3Quaternion born = tr.getRotation(); - float orn[4] = {born[0],born[1],born[2],born[3]}; - + uint64_t trigger = vr::ButtonMaskFromId((vr::EVRButtonId)button); - if (sIsPressed!=unDevice) + bool isTrigger = (state.ulButtonPressed&trigger) != 0; + if (isTrigger) { - b3Printf("trigger pressed %d, %d\n",counter++, unDevice); - sIsPressed=unDevice; - sExample->vrControllerButtonCallback(unDevice,1,1,pos, orn); - - // - //virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4]) {} - //virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]){} - - //sExample->start - } else - { - sExample->vrControllerMoveCallback(unDevice,pos,orn); - } - //sExample->exitPhysics(); - //m_app->m_instancingRenderer->removeAllInstances(); - ///sExample->initPhysics(); - } else - { - if (unDevice==sIsPressed) - { b3Transform tr; - getControllerTransform(unDevice,tr); - float pos[3] = {tr.getOrigin()[0],tr.getOrigin()[1],tr.getOrigin()[2]}; + getControllerTransform(unDevice, tr); + float pos[3] = { tr.getOrigin()[0], tr.getOrigin()[1], tr.getOrigin()[2] }; b3Quaternion born = tr.getRotation(); - float orn[4] = {born[0],born[1],born[2],born[3]}; + float orn[4] = { born[0], born[1], born[2], born[3] }; - sIsPressed=-1; - printf("device released: %d",unDevice); - sExample->vrControllerButtonCallback(unDevice,1,0,pos, orn); + //pressed now, not pressed before -> raise a button down event + if ((sPrevStates[unDevice].ulButtonPressed&trigger)==0) + { +// printf("Device PRESSED: %d, button %d\n", unDevice, button); + sExample->vrControllerButtonCallback(unDevice, button, 1, pos, orn); + } + else + { +// printf("Device MOVED: %d\n", unDevice); + sExample->vrControllerMoveCallback(unDevice, pos, orn); + } + } + else + { + //not pressed now, but pressed before -> raise a button up event + if ((sPrevStates[unDevice].ulButtonPressed&trigger) != 0) + { + b3Transform tr; + getControllerTransform(unDevice, tr); + float pos[3] = { tr.getOrigin()[0], tr.getOrigin()[1], tr.getOrigin()[2] }; + b3Quaternion born = tr.getRotation(); + float orn[4] = { born[0], born[1], born[2], born[3] }; +// printf("Device RELEASED: %d, button %d\n", unDevice,button); + sExample->vrControllerButtonCallback(unDevice, button, 0, pos, orn); + } } } } m_rbShowTrackedDevice[ unDevice ] = state.ulButtonPressed == 0; } + sPrevStates[unDevice] = state; } return bRet; From 0ae252fa35fde063a9480a338ca9c2f1ca6179f5 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 19 Jul 2016 15:53:16 -0700 Subject: [PATCH 097/115] fix issue, use bodyUniqueId/b3JointControlCommandInit2 --- examples/RoboticsLearning/b3RobotSimAPI.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/RoboticsLearning/b3RobotSimAPI.cpp b/examples/RoboticsLearning/b3RobotSimAPI.cpp index 235861913..b29e0e429 100644 --- a/examples/RoboticsLearning/b3RobotSimAPI.cpp +++ b/examples/RoboticsLearning/b3RobotSimAPI.cpp @@ -556,7 +556,7 @@ void b3RobotSimAPI::setJointMotorControl(int bodyUniqueId, int jointIndex, const { case CONTROL_MODE_VELOCITY: { - b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_data->m_physicsClient, CONTROL_MODE_VELOCITY); + b3SharedMemoryCommandHandle command = b3JointControlCommandInit2( m_data->m_physicsClient, bodyUniqueId, CONTROL_MODE_VELOCITY); b3JointInfo jointInfo; b3GetJointInfo(m_data->m_physicsClient, bodyUniqueId, jointIndex, &jointInfo); int uIndex = jointInfo.m_uIndex; @@ -567,7 +567,7 @@ void b3RobotSimAPI::setJointMotorControl(int bodyUniqueId, int jointIndex, const } case CONTROL_MODE_POSITION_VELOCITY_PD: { - b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_data->m_physicsClient, CONTROL_MODE_POSITION_VELOCITY_PD); + b3SharedMemoryCommandHandle command = b3JointControlCommandInit2( m_data->m_physicsClient, bodyUniqueId, CONTROL_MODE_POSITION_VELOCITY_PD); b3JointInfo jointInfo; b3GetJointInfo(m_data->m_physicsClient, bodyUniqueId, jointIndex, &jointInfo); int uIndex = jointInfo.m_uIndex; @@ -583,7 +583,7 @@ void b3RobotSimAPI::setJointMotorControl(int bodyUniqueId, int jointIndex, const } case CONTROL_MODE_TORQUE: { - b3SharedMemoryCommandHandle command = b3JointControlCommandInit( m_data->m_physicsClient, CONTROL_MODE_TORQUE); + b3SharedMemoryCommandHandle command = b3JointControlCommandInit2( m_data->m_physicsClient, bodyUniqueId, CONTROL_MODE_TORQUE); b3JointInfo jointInfo; b3GetJointInfo(m_data->m_physicsClient, bodyUniqueId, jointIndex, &jointInfo); int uIndex = jointInfo.m_uIndex; From 25a1714754572ce07b458e0cbaa6b84932619140 Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Tue, 19 Jul 2016 15:55:52 -0700 Subject: [PATCH 098/115] disable CProfileManager, might reduce some multi-threading conflicts --- .../Collision/CollisionTutorialBullet2.cpp | 5 +++- .../GwenGUISupport/GwenProfileWindow.cpp | 7 ++++-- src/LinearMath/btQuickprof.cpp | 8 +++--- src/LinearMath/btQuickprof.h | 25 +++++++++++-------- 4 files changed, 27 insertions(+), 18 deletions(-) diff --git a/examples/Collision/CollisionTutorialBullet2.cpp b/examples/Collision/CollisionTutorialBullet2.cpp index 1198f9e5d..0479a73e8 100644 --- a/examples/Collision/CollisionTutorialBullet2.cpp +++ b/examples/Collision/CollisionTutorialBullet2.cpp @@ -265,8 +265,9 @@ public: virtual void stepSimulation(float deltaTime) { +#ifndef BT_NO_PROFILE CProfileManager::Reset(); - +#endif @@ -314,7 +315,9 @@ public: m_app->m_renderer->writeTransforms(); +#ifndef BT_NO_PROFILE CProfileManager::Increment_Frame_Counter(); +#endif } virtual void renderScene() { diff --git a/examples/ExampleBrowser/GwenGUISupport/GwenProfileWindow.cpp b/examples/ExampleBrowser/GwenGUISupport/GwenProfileWindow.cpp index 597ff834d..4991ee04e 100644 --- a/examples/ExampleBrowser/GwenGUISupport/GwenProfileWindow.cpp +++ b/examples/ExampleBrowser/GwenGUISupport/GwenProfileWindow.cpp @@ -4,7 +4,7 @@ #include "LinearMath/btQuickprof.h" - +#ifndef BT_NO_PROFILE class MyProfileWindow : public Gwen::Controls::WindowControl @@ -42,8 +42,9 @@ protected: } public: - + CProfileIterator* profIter; + class MyMenuItems* m_menuItems; MyProfileWindow ( Gwen::Controls::Base* pParent) : Gwen::Controls::WindowControl( pParent ), @@ -304,3 +305,5 @@ void destroyProfileWindow(MyProfileWindow* window) CProfileManager::Release_Iterator(window->profIter); delete window; } + +#endif //BT_NO_PROFILE \ No newline at end of file diff --git a/src/LinearMath/btQuickprof.cpp b/src/LinearMath/btQuickprof.cpp index d88d965a4..cfbda3628 100644 --- a/src/LinearMath/btQuickprof.cpp +++ b/src/LinearMath/btQuickprof.cpp @@ -15,11 +15,8 @@ #include "btQuickprof.h" -#ifndef BT_NO_PROFILE -static btClock gProfileClock; - #ifdef __CELLOS_LV2__ #include @@ -250,6 +247,10 @@ btScalar btClock::getTimeSeconds() return btScalar(getTimeMicroseconds()) * microseconds_to_seconds; } +#ifndef BT_NO_PROFILE + + +static btClock gProfileClock; inline void Profile_Get_Ticks(unsigned long int * ticks) @@ -265,7 +266,6 @@ inline float Profile_Get_Tick_Rate(void) } - /*************************************************************************************************** ** ** CProfileNode diff --git a/src/LinearMath/btQuickprof.h b/src/LinearMath/btQuickprof.h index 362f62d6d..49545713b 100644 --- a/src/LinearMath/btQuickprof.h +++ b/src/LinearMath/btQuickprof.h @@ -15,18 +15,7 @@ #ifndef BT_QUICK_PROF_H #define BT_QUICK_PROF_H -//To disable built-in profiling, please comment out next line -//#define BT_NO_PROFILE 1 -#ifndef BT_NO_PROFILE -#include //@todo remove this, backwards compatibility #include "btScalar.h" -#include "btAlignedAllocator.h" -#include - - - - - #define USE_BT_CLOCK 1 #ifdef USE_BT_CLOCK @@ -64,6 +53,20 @@ private: #endif //USE_BT_CLOCK +//To disable built-in profiling, please comment out next line +#define BT_NO_PROFILE 1 +#ifndef BT_NO_PROFILE +#include //@todo remove this, backwards compatibility + +#include "btAlignedAllocator.h" +#include + + + + + + + ///A node in the Profile Hierarchy Tree From 9369f9b764534bdd289106a59f77b1f827305ef8 Mon Sep 17 00:00:00 2001 From: Mat Kelcey Date: Wed, 20 Jul 2016 10:24:34 -0700 Subject: [PATCH 099/115] fix error msg when loading sdfs --- examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp index f081325b3..425620c1a 100644 --- a/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp +++ b/examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp @@ -175,7 +175,7 @@ bool BulletURDFImporter::loadSDF(const char* fileName, bool forceFixedBase) m_data->m_pathPrefix[0] = 0; if (!fileFound){ - std::cerr << "URDF file not found" << std::endl; + std::cerr << "SDF file not found" << std::endl; return false; } else { From 51ec707230e5763b3cfb71d215f9eca4718cc87a Mon Sep 17 00:00:00 2001 From: Mat Kelcey Date: Wed, 20 Jul 2016 11:01:02 -0700 Subject: [PATCH 100/115] fix GetJointInfo to use a param called jointIndex (not linkIndex) for naming consistency --- examples/SharedMemory/PhysicsClientC_API.cpp | 4 ++-- examples/SharedMemory/PhysicsClientC_API.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 1ff24b66c..4197544b2 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -702,10 +702,10 @@ int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyId) } -int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, struct b3JointInfo* info) +int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointIndex, struct b3JointInfo* info) { PhysicsClient* cl = (PhysicsClient* ) physClient; - return cl->getJointInfo(bodyIndex, linkIndex,*info); + return cl->getJointInfo(bodyIndex, jointIndex, *info); } b3SharedMemoryCommandHandle b3PickBody(b3PhysicsClientHandle physClient, double rayFromWorldX, diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index a3b6dbd5c..2e2f126e2 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -56,8 +56,8 @@ int b3GetStatusActualState(b3SharedMemoryStatusHandle statusHandle, ///give a unique body index (after loading the body) return the number of joints. int b3GetNumJoints(b3PhysicsClientHandle physClient, int bodyIndex); -///given a body and link index, return the joint information. See b3JointInfo in SharedMemoryPublic.h -int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int linkIndex, struct b3JointInfo* info); +///given a body and joint index, return the joint information. See b3JointInfo in SharedMemoryPublic.h +int b3GetJointInfo(b3PhysicsClientHandle physClient, int bodyIndex, int jointIndex, struct b3JointInfo* info); ///Request debug lines for debug visualization. The flags in debugMode are the same as used in Bullet ///See btIDebugDraw::DebugDrawModes in Bullet/src/LinearMath/btIDebugDraw.h From d3a94248d484615dc4dd4d5c29819bf3efb125a0 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Wed, 20 Jul 2016 12:48:01 -0700 Subject: [PATCH 101/115] fix one more multi-threading issue --- .../MultiThreading/b3PosixThreadSupport.cpp | 24 +++++++++---------- .../MultiThreading/b3PosixThreadSupport.h | 12 ++++++++-- 2 files changed, 22 insertions(+), 14 deletions(-) diff --git a/examples/MultiThreading/b3PosixThreadSupport.cpp b/examples/MultiThreading/b3PosixThreadSupport.cpp index c19ab1b48..9a00d48aa 100644 --- a/examples/MultiThreading/b3PosixThreadSupport.cpp +++ b/examples/MultiThreading/b3PosixThreadSupport.cpp @@ -44,8 +44,6 @@ b3PosixThreadSupport::~b3PosixThreadSupport() #define NAMED_SEMAPHORES #endif -// this semaphore will signal, if and how many threads are finished with their work -static sem_t* mainSemaphore=0; static sem_t* createSem(const char* baseName) { @@ -100,12 +98,12 @@ static void *threadFunction(void *argument) b3Assert(status->m_status); status->m_userThreadFunc(userPtr,status->m_lsMemory); status->m_status = 2; - checkPThreadFunction(sem_post(mainSemaphore)); + checkPThreadFunction(sem_post(status->m_mainSemaphore)); status->threadUsed++; } else { //exit Thread status->m_status = 3; - checkPThreadFunction(sem_post(mainSemaphore)); + checkPThreadFunction(sem_post(status->m_mainSemaphore)); printf("Thread with taskId %i exiting\n",status->m_taskId); break; } @@ -160,13 +158,14 @@ bool b3PosixThreadSupport::isTaskCompleted(int *puiArgument0, int *puiArgument1, b3Assert(m_activeThreadStatus.size()); // wait for any of the threads to finish - int result = sem_trywait(mainSemaphore); + int result = sem_trywait(m_mainSemaphore); if (result==0) { // get at least one thread which has finished - size_t last = -1; - - for(size_t t=0; t < size_t(m_activeThreadStatus.size()); ++t) { + int last = -1; + int status = -1; + for(int t=0; t < int (m_activeThreadStatus.size()); ++t) { + status = m_activeThreadStatus[t].m_status; if(2 == m_activeThreadStatus[t].m_status) { last = t; break; @@ -200,7 +199,7 @@ void b3PosixThreadSupport::waitForResponse( int *puiArgument0, int *puiArgument b3Assert(m_activeThreadStatus.size()); // wait for any of the threads to finish - checkPThreadFunction(sem_wait(mainSemaphore)); + checkPThreadFunction(sem_wait(m_mainSemaphore)); // get at least one thread which has finished size_t last = -1; @@ -231,7 +230,7 @@ void b3PosixThreadSupport::startThreads(ThreadConstructionInfo& threadConstructi printf("%s creating %i threads.\n", __FUNCTION__, threadConstructionInfo.m_numThreads); m_activeThreadStatus.resize(threadConstructionInfo.m_numThreads); - mainSemaphore = createSem("main"); + m_mainSemaphore = createSem("main"); //checkPThreadFunction(sem_wait(mainSemaphore)); for (int i=0;i < threadConstructionInfo.m_numThreads;i++) @@ -249,6 +248,7 @@ void b3PosixThreadSupport::startThreads(ThreadConstructionInfo& threadConstructi spuStatus.m_taskId = i; spuStatus.m_commandId = 0; spuStatus.m_status = 0; + spuStatus.m_mainSemaphore = m_mainSemaphore; spuStatus.m_lsMemory = threadConstructionInfo.m_lsMemoryFunc(); spuStatus.m_userThreadFunc = threadConstructionInfo.m_userThreadFunc; spuStatus.threadUsed = 0; @@ -271,7 +271,7 @@ void b3PosixThreadSupport::stopThreads() spuStatus.m_userPtr = 0; checkPThreadFunction(sem_post(spuStatus.startSemaphore)); - checkPThreadFunction(sem_wait(mainSemaphore)); + checkPThreadFunction(sem_wait(m_mainSemaphore)); printf("destroy semaphore\n"); destroySem(spuStatus.startSemaphore); @@ -280,7 +280,7 @@ void b3PosixThreadSupport::stopThreads() } printf("destroy main semaphore\n"); - destroySem(mainSemaphore); + destroySem(m_mainSemaphore); printf("main semaphore destroyed\n"); m_activeThreadStatus.clear(); } diff --git a/examples/MultiThreading/b3PosixThreadSupport.h b/examples/MultiThreading/b3PosixThreadSupport.h index ae23dd610..3f54d4ab5 100644 --- a/examples/MultiThreading/b3PosixThreadSupport.h +++ b/examples/MultiThreading/b3PosixThreadSupport.h @@ -57,14 +57,22 @@ public: void* m_userPtr; //for taskDesc etc void* m_lsMemory; //initialized using PosixLocalStoreMemorySetupFunc - pthread_t thread; - sem_t* startSemaphore; + pthread_t thread; + //each tread will wait until this signal to start its work + sem_t* startSemaphore; + // this is a copy of m_mainSemaphore, + //each tread will signal once it is finished with its work + sem_t* m_mainSemaphore; unsigned long threadUsed; }; private: b3AlignedObjectArray m_activeThreadStatus; + + // m_mainSemaphoresemaphore will signal, if and how many threads are finished with their work + sem_t* m_mainSemaphore; + public: ///Setup and initialize SPU/CELL/Libspe2 From e88de13cc669b77acbe12c3efe303c1c37a60dbb Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Wed, 20 Jul 2016 15:41:58 -0700 Subject: [PATCH 102/115] fix Parse joint dynamics in SDF --- examples/Importers/ImportURDFDemo/UrdfParser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 6ed9ac2c8..a6a5e256e 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -960,7 +960,7 @@ bool UrdfParser::parseJoint(UrdfJoint& joint, TiXmlElement *config, ErrorLogger* return false; } - TiXmlElement *prop_xml = config->FirstChildElement("dynamics"); + TiXmlElement *prop_xml = axis_xml->FirstChildElement("dynamics"); if (prop_xml) { if (!parseJointDynamics(joint, prop_xml,logger)) From 75e86051c2724f159cecf12bd6b683ab8b83b82b Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Sun, 24 Jul 2016 22:22:42 -0700 Subject: [PATCH 103/115] Add inverse kinematics example with implementations by Sam Buss. Uses Kuka IIWA model description and 4 methods: Selectively Damped Least Squares,Damped Least Squares, Jacobi Transpose, Jacobi Pseudo Inverse Tweak some PD values in Inverse Dynamics example and Robot example. --- examples/ExampleBrowser/CMakeLists.txt | 13 + examples/ExampleBrowser/ExampleEntries.cpp | 19 +- .../ExampleBrowser/OpenGLExampleBrowser.cpp | 1 + examples/ExampleBrowser/premake4.lua | 4 +- .../InverseDynamicsExample.cpp | 21 +- .../InverseKinematicsExample.cpp | 382 ++++ .../InverseKinematicsExample.h | 8 + .../SharedMemory/PhysicsClientExample.cpp | 6 +- examples/ThirdPartyLibs/BussIK/Jacobian.cpp | 640 ++++++ examples/ThirdPartyLibs/BussIK/Jacobian.h | 132 ++ examples/ThirdPartyLibs/BussIK/LinearR2.cpp | 101 + examples/ThirdPartyLibs/BussIK/LinearR2.h | 981 ++++++++ examples/ThirdPartyLibs/BussIK/LinearR3.cpp | 822 +++++++ examples/ThirdPartyLibs/BussIK/LinearR3.h | 2027 +++++++++++++++++ examples/ThirdPartyLibs/BussIK/LinearR4.cpp | 467 ++++ examples/ThirdPartyLibs/BussIK/LinearR4.h | 1099 +++++++++ examples/ThirdPartyLibs/BussIK/MathMisc.h | 384 ++++ examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp | 984 ++++++++ examples/ThirdPartyLibs/BussIK/MatrixRmn.h | 402 ++++ examples/ThirdPartyLibs/BussIK/Misc.cpp | 346 +++ examples/ThirdPartyLibs/BussIK/Node.cpp | 90 + examples/ThirdPartyLibs/BussIK/Node.h | 101 + examples/ThirdPartyLibs/BussIK/Spherical.h | 298 +++ examples/ThirdPartyLibs/BussIK/Tree.cpp | 217 ++ examples/ThirdPartyLibs/BussIK/Tree.h | 92 + examples/ThirdPartyLibs/BussIK/VectorRn.cpp | 46 + examples/ThirdPartyLibs/BussIK/VectorRn.h | 238 ++ examples/TinyRenderer/tgaimage.h | 6 +- .../Featherstone/btMultiBodyJointMotor.cpp | 28 +- 29 files changed, 9926 insertions(+), 29 deletions(-) create mode 100644 examples/InverseKinematics/InverseKinematicsExample.cpp create mode 100644 examples/InverseKinematics/InverseKinematicsExample.h create mode 100644 examples/ThirdPartyLibs/BussIK/Jacobian.cpp create mode 100644 examples/ThirdPartyLibs/BussIK/Jacobian.h create mode 100644 examples/ThirdPartyLibs/BussIK/LinearR2.cpp create mode 100644 examples/ThirdPartyLibs/BussIK/LinearR2.h create mode 100644 examples/ThirdPartyLibs/BussIK/LinearR3.cpp create mode 100644 examples/ThirdPartyLibs/BussIK/LinearR3.h create mode 100644 examples/ThirdPartyLibs/BussIK/LinearR4.cpp create mode 100644 examples/ThirdPartyLibs/BussIK/LinearR4.h create mode 100644 examples/ThirdPartyLibs/BussIK/MathMisc.h create mode 100644 examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp create mode 100644 examples/ThirdPartyLibs/BussIK/MatrixRmn.h create mode 100644 examples/ThirdPartyLibs/BussIK/Misc.cpp create mode 100644 examples/ThirdPartyLibs/BussIK/Node.cpp create mode 100644 examples/ThirdPartyLibs/BussIK/Node.h create mode 100644 examples/ThirdPartyLibs/BussIK/Spherical.h create mode 100644 examples/ThirdPartyLibs/BussIK/Tree.cpp create mode 100644 examples/ThirdPartyLibs/BussIK/Tree.h create mode 100644 examples/ThirdPartyLibs/BussIK/VectorRn.cpp create mode 100644 examples/ThirdPartyLibs/BussIK/VectorRn.h diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index da15ba32b..0678eaf4a 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -155,6 +155,8 @@ SET(BulletExampleBrowser_SRCS ../BasicDemo/BasicExample.h ../InverseDynamics/InverseDynamicsExample.cpp ../InverseDynamics/InverseDynamicsExample.h + ../InverseKinematics/InverseKinematicsExample.cpp + ../InverseKinematics/InverseKinematicsExample.h ../ForkLift/ForkLiftDemo.cpp ../ForkLift/ForkLiftDemo.h ../Tutorial/Tutorial.cpp @@ -298,6 +300,17 @@ SET(BulletExampleBrowser_SRCS ../ThirdPartyLibs/stb_image/stb_image.cpp ../ThirdPartyLibs/stb_image/stb_image.h + + ../ThirdPartyLibs/BussIK/Jacobian.cpp + ../ThirdPartyLibs/BussIK/Tree.cpp + ../ThirdPartyLibs/BussIK/Node.cpp + ../ThirdPartyLibs/BussIK/LinearR2.cpp + ../ThirdPartyLibs/BussIK/LinearR3.cpp + ../ThirdPartyLibs/BussIK/LinearR4.cpp + ../ThirdPartyLibs/BussIK/MatrixRmn.cpp + ../ThirdPartyLibs/BussIK/VectorRn.cpp + ../ThirdPartyLibs/BussIK/Misc.cpp + ../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp ../ThirdPartyLibs/tinyxml/tinystr.cpp diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index c5901ca34..a6abd4fd7 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -46,6 +46,7 @@ #include "../MultiThreading/MultiThreadingExample.h" #include "../InverseDynamics/InverseDynamicsExample.h" #include "../RoboticsLearning/R2D2GraspExample.h" +#include "../InverseKinematics/InverseKinematicsExample.h" #ifdef ENABLE_LUA #include "../LuaDemo/LuaPhysicsSetup.h" @@ -95,7 +96,6 @@ struct ExampleEntry static ExampleEntry gDefaultExamples[]= { - ExampleEntry(0,"API"), ExampleEntry(1,"Basic Example","Create some rigid bodies using box collision shapes. This is a good example to familiarize with the basic initialization of Bullet. The Basic Example can also be compiled without graphical user interface, as a console application. Press W for wireframe, A to show AABBs, I to suspend/restart physics simulation. Press D to toggle auto-deactivation of the simulation. ", BasicExampleCreateFunc), @@ -124,14 +124,21 @@ static ExampleEntry gDefaultExamples[]= ExampleEntry(1,"TestJointTorque","Apply a torque to a btMultiBody with 1-DOF joints (mobilizers). This setup is similar to API/TestHingeTorque.", TestJointTorqueCreateFunc), ExampleEntry(1,"TestPendulum","Simulate a pendulum using btMultiBody with a constant joint torque applied. The same code is also used as a unit test comparing Bullet with the numerical solution of second-order non-linear differential equation stored in pendulum_gold.h", TestPendulumCreateFunc), - ExampleEntry(1,"Constraint Feedback", "The example shows how to receive joint reaction forces in a btMultiBody. Also the applied impulse is available for a btMultiBodyJointMotor", MultiBodyConstraintFeedbackCreateFunc), + ExampleEntry(1,"Constraint Feedback", "The example shows how to receive joint reaction forces in a btMultiBody. Also the applied impulse is available for a btMultiBodyJointMotor", MultiBodyConstraintFeedbackCreateFunc), ExampleEntry(1,"Inverted Pendulum PD","Keep an inverted pendulum up using open loop PD control", InvertedPendulumPDControlCreateFunc), - ExampleEntry(1,"MultiBody Soft Contact", "Using the error correction parameter (ERP) and constraint force mixing (CFM) values for contacts to simulate compliant contact.",MultiBodySoftContactCreateFunc,0), + ExampleEntry(1,"MultiBody Soft Contact", "Using the error correction parameter (ERP) and constraint force mixing (CFM) values for contacts to simulate compliant contact.",MultiBodySoftContactCreateFunc,0), - ExampleEntry(0,"Inverse Dynamics"), - ExampleEntry(1,"Inverse Dynamics URDF", "Create a btMultiBody from URDF. Create an inverse MultiBodyTree model from that. Use either decoupled PD control or computed torque control using the inverse model to track joint position targets", InverseDynamicsExampleCreateFunc,BT_ID_LOAD_URDF), - ExampleEntry(1,"Inverse Dynamics Prog", "Create a btMultiBody programatically. Create an inverse MultiBodyTree model from that. Use either decoupled PD control or computed torque control using the inverse model to track joint position targets", InverseDynamicsExampleCreateFunc,BT_ID_PROGRAMMATICALLY), + ExampleEntry(0,"Inverse Dynamics"), + ExampleEntry(1,"Inverse Dynamics URDF", "Create a btMultiBody from URDF. Create an inverse MultiBodyTree model from that. Use either decoupled PD control or computed torque control using the inverse model to track joint position targets", InverseDynamicsExampleCreateFunc,BT_ID_LOAD_URDF), + ExampleEntry(1,"Inverse Dynamics Prog", "Create a btMultiBody programatically. Create an inverse MultiBodyTree model from that. Use either decoupled PD control or computed torque control using the inverse model to track joint position targets", InverseDynamicsExampleCreateFunc,BT_ID_PROGRAMMATICALLY), + + ExampleEntry(0, "Inverse Kinematics"), + ExampleEntry(1, "SDLS", "Selectively Damped Least Squares by Sam Buss. Example configures the IK tree of a Kuka IIWA", InverseKinematicsExampleCreateFunc, IK_SDLS), + ExampleEntry(1, "DLS", "Damped Least Squares by Sam Buss. Example configures the IK tree of a Kuka IIWA", InverseKinematicsExampleCreateFunc, IK_DLS), + ExampleEntry(1, "Jacobi Transpose", "Jacobi Transpose by Sam Buss. Example configures the IK tree of a Kuka IIWA", InverseKinematicsExampleCreateFunc, IK_JACOB_TRANS), + ExampleEntry(1, "Jacobi Pseudo Inv", "Jacobi Pseudo Inverse Method by Sam Buss. Example configures the IK tree of a Kuka IIWA", InverseKinematicsExampleCreateFunc, IK_PURE_PSEUDO), + ExampleEntry(0,"Tutorial"), ExampleEntry(1,"Constant Velocity","Free moving rigid body, without external or constraint forces", TutorialCreateFunc,TUT_VELOCITY), diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index e06d5f205..44d0baf53 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -800,6 +800,7 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[]) s_app = new SimpleOpenGL2App(title,width,height); s_app->m_renderer = new SimpleOpenGL2Renderer(width,height); } + #ifndef NO_OPENGL3 else { diff --git a/examples/ExampleBrowser/premake4.lua b/examples/ExampleBrowser/premake4.lua index 7d11eaed9..2010c744e 100644 --- a/examples/ExampleBrowser/premake4.lua +++ b/examples/ExampleBrowser/premake4.lua @@ -45,9 +45,10 @@ project "App_BulletExampleBrowser" defines {"INCLUDE_CLOTH_DEMOS"} files { + "main.cpp", "ExampleEntries.cpp", - + "../InverseKinematics/*", "../TinyRenderer/geometry.cpp", "../TinyRenderer/model.cpp", "../TinyRenderer/tgaimage.cpp", @@ -116,6 +117,7 @@ project "App_BulletExampleBrowser" "../ThirdPartyLibs/stb_image/*", "../ThirdPartyLibs/Wavefront/tiny_obj_loader.*", "../ThirdPartyLibs/tinyxml/*", + "../ThirdPartyLibs/BussIK/*", "../GyroscopicDemo/GyroscopicSetup.cpp", "../GyroscopicDemo/GyroscopicSetup.h", "../ThirdPartyLibs/tinyxml/tinystr.cpp", diff --git a/examples/InverseDynamics/InverseDynamicsExample.cpp b/examples/InverseDynamics/InverseDynamicsExample.cpp index ebf7efb0d..9eb9287f4 100644 --- a/examples/InverseDynamics/InverseDynamicsExample.cpp +++ b/examples/InverseDynamics/InverseDynamicsExample.cpp @@ -157,7 +157,7 @@ void InverseDynamicsExample::initPhysics() BulletURDFImporter u2b(m_guiHelper,0); - bool loadOk = u2b.loadURDF("kuka_lwr/kuka.urdf"); + bool loadOk = u2b.loadURDF("kuka_iiwa/model.urdf");// lwr / kuka.urdf"); if (loadOk) { int rootLinkIndex = u2b.getRootLinkIndex(); @@ -225,13 +225,13 @@ void InverseDynamicsExample::initPhysics() { qd[dof] = 0; char tmp[25]; - sprintf(tmp,"q_desired[%zu]",dof); + sprintf(tmp,"q_desired[%u]",dof); qd_name[dof] = tmp; SliderParams slider(qd_name[dof].c_str(),&qd[dof]); slider.m_minVal=-3.14; slider.m_maxVal=3.14; - sprintf(tmp,"q[%zu]",dof); + sprintf(tmp,"q[%u]",dof); q_name[dof] = tmp; m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); btVector4 color = sJointCurveColors[dof&7]; @@ -340,6 +340,21 @@ void InverseDynamicsExample::stepSimulation(float deltaTime) // todo(thomas) check that this is correct: // want to advance by 10ms, with 1ms timesteps m_dynamicsWorld->stepSimulation(1e-3,0);//,1e-3); + btAlignedObjectArray scratch_q; + btAlignedObjectArray scratch_m; + m_multiBody->forwardKinematics(scratch_q, scratch_m); + for (int i = 0; i < m_multiBody->getNumLinks(); i++) + { + //btVector3 pos = m_multiBody->getLink(i).m_cachedWorldTransform.getOrigin(); + btTransform tr = m_multiBody->getLink(i).m_cachedWorldTransform; + btVector3 pos = tr.getOrigin() - quatRotate(tr.getRotation(), m_multiBody->getLink(i).m_dVector); + btVector3 localAxis = m_multiBody->getLink(i).m_axes[0].m_topVec; + //printf("link %d: %f,%f,%f, local axis:%f,%f,%f\n", i, pos.x(), pos.y(), pos.z(), localAxis.x(), localAxis.y(), localAxis.z()); + + + + + } } } diff --git a/examples/InverseKinematics/InverseKinematicsExample.cpp b/examples/InverseKinematics/InverseKinematicsExample.cpp new file mode 100644 index 000000000..ae1ed8f17 --- /dev/null +++ b/examples/InverseKinematics/InverseKinematicsExample.cpp @@ -0,0 +1,382 @@ +#include "InverseKinematicsExample.h" + +#include "../CommonInterfaces/CommonGraphicsAppInterface.h" +#include "Bullet3Common/b3Quaternion.h" +#include "Bullet3Common/b3Transform.h" +#include "Bullet3Common/b3AlignedObjectArray.h" +#include "../CommonInterfaces/CommonRenderInterface.h" +#include "../CommonInterfaces/CommonExampleInterface.h" +#include "../CommonInterfaces/CommonGUIHelperInterface.h" +#include "../OpenGLWindow/OpenGLInclude.h" + +#include "BussIK/Node.h" +#include "BussIK/Tree.h" +#include "BussIK/Jacobian.h" +#include "BussIK/VectorRn.h" + +#define RADIAN(X) ((X)*RadiansToDegrees) + +#define MAX_NUM_NODE 1000 +#define MAX_NUM_THETA 1000 +#define MAX_NUM_EFFECT 100 + +double T = 0; +VectorR3 target1[MAX_NUM_EFFECT]; + + + +// Make slowdown factor larger to make the simulation take larger, less frequent steps +// Make the constant factor in Tstep larger to make time pass more quickly +//const int SlowdownFactor = 40; +const int SlowdownFactor = 0; // Make higher to take larger steps less frequently +const int SleepsPerStep=SlowdownFactor; +int SleepCounter=0; +//const double Tstep = 0.0005*(double)SlowdownFactor; // Time step + + +int AxesList; /* list to hold the axes */ +int AxesOn; /* ON or OFF */ + +float Scale, Scale2; /* scaling factors */ + + + +int JointLimitsOn; +int RestPositionOn; +int UseJacobianTargets1; + + +int numIteration = 1; +double error = 0.0; +double errorDLS = 0.0; +double errorSDLS = 0.0; +double sumError = 0.0; +double sumErrorDLS = 0.0; +double sumErrorSDLS = 0.0; + +#ifdef _DYNAMIC +bool initMaxDist = true; +extern double Excess[]; +extern double dsnorm[]; +#endif + + + + +void Reset(Tree &tree, Jacobian* m_ikJacobian) +{ + AxesOn = false; + + Scale = 1.0; + Scale2 = 0.0; /* because add 1. to it in Display() */ + + JointLimitsOn = true; + RestPositionOn = false; + UseJacobianTargets1 = false; + + + tree.Init(); + tree.Compute(); + m_ikJacobian->Reset(); + +} + +// Update target positions + +void UpdateTargets( double T2, Tree & treeY) { + double T = T2 / 20.; + target1[0].Set(0.6*b3Sin(0), 0.6*b3Cos(0), 0.5+0.4*b3Sin(3 * T)); +} + + +// Does a single update (on one kind of tree) +void DoUpdateStep(double Tstep, Tree & treeY, Jacobian *jacob, int ikMethod) { + + if ( SleepCounter==0 ) { + T += Tstep; + UpdateTargets( T , treeY); + } + + if ( UseJacobianTargets1 ) { + jacob->SetJtargetActive(); + } + else { + jacob->SetJendActive(); + } + jacob->ComputeJacobian(); // Set up Jacobian and deltaS vectors + + // Calculate the change in theta values + switch (ikMethod) { + case IK_JACOB_TRANS: + jacob->CalcDeltaThetasTranspose(); // Jacobian transpose method + break; + case IK_DLS: + jacob->CalcDeltaThetasDLS(); // Damped least squares method + break; + case IK_PURE_PSEUDO: + jacob->CalcDeltaThetasPseudoinverse(); // Pure pseudoinverse method + break; + case IK_SDLS: + jacob->CalcDeltaThetasSDLS(); // Selectively damped least squares method + break; + default: + jacob->ZeroDeltaThetas(); + break; + } + + if ( SleepCounter==0 ) { + jacob->UpdateThetas(); // Apply the change in the theta values + jacob->UpdatedSClampValue(); + SleepCounter = SleepsPerStep; + } + else { + SleepCounter--; + } + + +} + + + + + + + + +///quick demo showing the right-handed coordinate system and positive rotations around each axis +class InverseKinematicsExample : public CommonExampleInterface +{ + CommonGraphicsApp* m_app; + int m_ikMethod; + Tree m_ikTree; + b3AlignedObjectArray m_ikNodes; + Jacobian* m_ikJacobian; + + float m_x; + float m_y; + float m_z; + b3AlignedObjectArray m_movingInstances; + int m_targetInstance; + enum + { + numCubesX = 20, + numCubesY = 20 + }; +public: + + InverseKinematicsExample(CommonGraphicsApp* app, int option) + :m_app(app), + m_x(0), + m_y(0), + m_z(0), + m_targetInstance(-1), + m_ikMethod(option) + { + m_app->setUpAxis(2); + + { + b3Vector3 extents=b3MakeVector3(100,100,100); + extents[m_app->getUpAxis()]=1; + + int xres = 20; + int yres = 20; + + b3Vector4 color0=b3MakeVector4(0.4, 0.4, 0.4,1); + b3Vector4 color1=b3MakeVector4(0.6, 0.6, 0.6,1); + m_app->registerGrid(xres, yres, color0, color1); + } + + ///create some graphics proxy for the tracking target + ///the endeffector tries to track it using Inverse Kinematics + { + int sphereId = m_app->registerGraphicsUnitSphereShape(SPHERE_LOD_MEDIUM); + b3Vector3 pos = b3MakeVector3(1,1,1); + pos[app->getUpAxis()] = 1; + b3Quaternion orn(0, 0, 0, 1); + b3Vector4 color = b3MakeVector4(1., 0.3, 0.3, 1); + b3Vector3 scaling = b3MakeVector3(.02, .02, .02); + m_targetInstance = m_app->m_renderer->registerGraphicsInstance(sphereId, pos, orn, color, scaling); + } + m_app->m_renderer->writeTransforms(); + } + virtual ~InverseKinematicsExample() + { + m_app->m_renderer->enableBlend(false); + } + + + virtual void physicsDebugDraw(int debugDrawMode) + { + + } + virtual void initPhysics() + { + BuildKukaIIWAShape(); + m_ikJacobian = new Jacobian(&m_ikTree); + Reset(m_ikTree,m_ikJacobian); + } + virtual void exitPhysics() + { + delete m_ikJacobian; + m_ikJacobian = 0; + } + + void BuildKukaIIWAShape(); + + void getLocalTransform(const Node* node, b3Transform& act) + { + b3Vector3 axis = b3MakeVector3(node->v.x, node->v.y, node->v.z); + b3Quaternion rot(0, 0, 0, 1); + if (axis.length()) + { + rot = b3Quaternion (axis, node->theta); + } + act.setIdentity(); + act.setRotation(rot); + act.setOrigin(b3MakeVector3(node->r.x, node->r.y, node->r.z)); + } + void MyDrawTree(Node* node, const b3Transform& tr) + { + b3Vector3 lineColor = b3MakeVector3(0, 0, 0); + int lineWidth = 2; + if (node != 0) { + // glPushMatrix(); + b3Vector3 pos = b3MakeVector3(tr.getOrigin().x, tr.getOrigin().y, tr.getOrigin().z); + b3Vector3 color = b3MakeVector3(0, 1, 0); + int pointSize = 10; + m_app->m_renderer->drawPoint(pos, color, pointSize); + + m_app->m_renderer->drawLine(pos, pos+ 0.05*tr.getBasis().getColumn(0), b3MakeVector3(1,0,0), lineWidth); + m_app->m_renderer->drawLine(pos, pos + 0.05*tr.getBasis().getColumn(1), b3MakeVector3(0, 1, 0), lineWidth); + m_app->m_renderer->drawLine(pos, pos + 0.05*tr.getBasis().getColumn(2), b3MakeVector3(0, 0, 1), lineWidth); + + b3Vector3 axisLocal = b3MakeVector3(node->v.x, node->v.y, node->v.z); + b3Vector3 axisWorld = tr.getBasis()*axisLocal; + + m_app->m_renderer->drawLine(pos, pos + 0.1*axisWorld, b3MakeVector3(.2, 0.2, 0.7), 5); + + //node->DrawNode(node == root); // Recursively draw node and update ModelView matrix + if (node->left) { + b3Transform act; + getLocalTransform(node->left, act); + + b3Transform trl = tr*act; + m_app->m_renderer->drawLine(tr.getOrigin(), trl.getOrigin(), lineColor, lineWidth); + MyDrawTree(node->left, trl); // Draw tree of children recursively + } + // glPopMatrix(); + if (node->right) { + b3Transform act; + getLocalTransform(node->right, act); + b3Transform trr = tr*act; + m_app->m_renderer->drawLine(tr.getOrigin(), trr.getOrigin(), lineColor, lineWidth); + MyDrawTree(node->right,trr); // Draw right siblings recursively + } + } + + } + virtual void stepSimulation(float deltaTime) + { + DoUpdateStep(deltaTime, m_ikTree, m_ikJacobian, m_ikMethod); + } + virtual void renderScene() + { + + + b3Transform act; + getLocalTransform(m_ikTree.GetRoot(), act); + MyDrawTree(m_ikTree.GetRoot(), act); + + b3Vector3 pos = b3MakeVector3(target1[0].x, target1[0].y, target1[0].z); + b3Quaternion orn(0, 0, 0, 1); + + m_app->m_renderer->writeSingleInstanceTransformToCPU(pos, orn, m_targetInstance); + m_app->m_renderer->writeTransforms(); + m_app->m_renderer->renderScene(); + } + + + virtual void physicsDebugDraw() + { + + } + virtual bool mouseMoveCallback(float x,float y) + { + return false; + } + virtual bool mouseButtonCallback(int button, int state, float x, float y) + { + return false; + } + virtual bool keyboardCallback(int key, int state) + { + return false; + } + + virtual void resetCamera() + { + float dist = 1.3; + float pitch = 120; + float yaw = 13; + float targetPos[3]={-0.35,0.14,0.25}; + if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) + { + + m_app->m_renderer->getActiveCamera()->setCameraDistance(dist); + m_app->m_renderer->getActiveCamera()->setCameraPitch(pitch); + m_app->m_renderer->getActiveCamera()->setCameraYaw(yaw); + m_app->m_renderer->getActiveCamera()->setCameraTargetPosition(targetPos[0],targetPos[1],targetPos[2]); + } + } + +}; + +void InverseKinematicsExample::BuildKukaIIWAShape() +{ + const VectorR3& unitx = VectorR3::UnitX; + const VectorR3& unity = VectorR3::UnitY; + const VectorR3& unitz = VectorR3::UnitZ; + const VectorR3 unit1(sqrt(14.0) / 8.0, 1.0 / 8.0, 7.0 / 8.0); + const VectorR3& zero = VectorR3::Zero; + + float minTheta = -4 * PI; + float maxTheta = 4 * PI; + + m_ikNodes.resize(8);//7DOF+additional endeffector + + m_ikNodes[0] = new Node(VectorR3(0.100000, 0.000000, 0.087500), unitz, 0.08, JOINT, -1e30, 1e30, RADIAN(0.)); + m_ikTree.InsertRoot(m_ikNodes[0]); + + m_ikNodes[1] = new Node(VectorR3(0.100000, -0.000000, 0.290000), unity, 0.08, JOINT, -0.5, 0.4, RADIAN(0.)); + m_ikTree.InsertLeftChild(m_ikNodes[0], m_ikNodes[1]); + + m_ikNodes[2] = new Node(VectorR3(0.100000, -0.000000, 0.494500), unitz, 0.08, JOINT, minTheta, maxTheta, RADIAN(0.)); + m_ikTree.InsertLeftChild(m_ikNodes[1], m_ikNodes[2]); + + m_ikNodes[3] = new Node(VectorR3(0.100000, 0.000000, 0.710000), -unity, 0.08, JOINT, minTheta, maxTheta, RADIAN(0.)); + m_ikTree.InsertLeftChild(m_ikNodes[2], m_ikNodes[3]); + + m_ikNodes[4] = new Node(VectorR3(0.100000, 0.000000, 0.894500), unitz, 0.08, JOINT, minTheta, maxTheta, RADIAN(0.)); + m_ikTree.InsertLeftChild(m_ikNodes[3], m_ikNodes[4]); + + m_ikNodes[5] = new Node(VectorR3(0.100000, 0.000000, 1.110000), unity, 0.08, JOINT, minTheta, maxTheta, RADIAN(0.)); + m_ikTree.InsertLeftChild(m_ikNodes[4], m_ikNodes[5]); + + m_ikNodes[6] = new Node(VectorR3(0.100000, 0.000000, 1.191000), unitz, 0.08, JOINT, minTheta, maxTheta, RADIAN(0.)); + m_ikTree.InsertLeftChild(m_ikNodes[5], m_ikNodes[6]); + + m_ikNodes[7] = new Node(VectorR3(0.100000, 0.000000, 1.20000), zero, 0.08, EFFECTOR); + m_ikTree.InsertLeftChild(m_ikNodes[6], m_ikNodes[7]); + +} + + +class CommonExampleInterface* InverseKinematicsExampleCreateFunc(struct CommonExampleOptions& options) +{ + return new InverseKinematicsExample(options.m_guiHelper->getAppInterface(), options.m_option); +} + + + + + diff --git a/examples/InverseKinematics/InverseKinematicsExample.h b/examples/InverseKinematics/InverseKinematicsExample.h new file mode 100644 index 000000000..ca0d1e3b5 --- /dev/null +++ b/examples/InverseKinematics/InverseKinematicsExample.h @@ -0,0 +1,8 @@ +#ifndef INVERSE_KINEMATICSEXAMPLE_H +#define INVERSE_KINEMATICSEXAMPLE_H + +enum Method {IK_JACOB_TRANS=0, IK_PURE_PSEUDO, IK_DLS, IK_SDLS }; + +class CommonExampleInterface* InverseKinematicsExampleCreateFunc(struct CommonExampleOptions& options); + +#endif //INVERSE_KINEMATICSEXAMPLE_H diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index 9faa782a9..b5788bd09 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -171,10 +171,10 @@ protected: b3JointControlSetDesiredPosition(commandHandle, qIndex, targetPos); b3JointControlSetDesiredVelocity(commandHandle,uIndex,0); - b3JointControlSetKp(commandHandle, qIndex, 0.01); - b3JointControlSetKd(commandHandle, uIndex, 0.1); + b3JointControlSetKp(commandHandle, qIndex, 0.2); + b3JointControlSetKd(commandHandle, uIndex, 1.); - b3JointControlSetMaximumForce(commandHandle,uIndex,1000); + b3JointControlSetMaximumForce(commandHandle,uIndex,5000); } } virtual void physicsDebugDraw(int debugFlags) diff --git a/examples/ThirdPartyLibs/BussIK/Jacobian.cpp b/examples/ThirdPartyLibs/BussIK/Jacobian.cpp new file mode 100644 index 000000000..646513b86 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/Jacobian.cpp @@ -0,0 +1,640 @@ +/* +* +* Inverse Kinematics software, with several solvers including +* Selectively Damped Least Squares Method +* Damped Least Squares Method +* Pure Pseudoinverse Method +* Jacobian Transpose Method +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + +#include +#include +#include +#include +using namespace std; + +#include "../OpenGLWindow/OpenGLInclude.h" + +#include "Jacobian.h" + +void Arrow(const VectorR3& tail, const VectorR3& head); + +//extern RestPositionOn; +extern VectorR3 target1[]; + +// Optimal damping values have to be determined in an ad hoc manner (Yuck!) +const double Jacobian::DefaultDampingLambda = 0.6; // Optimal for the "Y" shape (any lower gives jitter) +//const double Jacobian::DefaultDampingLambda = 1.1; // Optimal for the DLS "double Y" shape (any lower gives jitter) +// const double Jacobian::DefaultDampingLambda = 0.7; // Optimal for the DLS "double Y" shape with distance clamping (lower gives jitter) + +const double Jacobian::PseudoInverseThresholdFactor = 0.01; +const double Jacobian::MaxAngleJtranspose = 30.0*DegreesToRadians; +const double Jacobian::MaxAnglePseudoinverse = 5.0*DegreesToRadians; +const double Jacobian::MaxAngleDLS = 45.0*DegreesToRadians; +const double Jacobian::MaxAngleSDLS = 45.0*DegreesToRadians; +const double Jacobian::BaseMaxTargetDist = 0.4; + +Jacobian::Jacobian(Tree* tree) +{ + Jacobian::tree = tree; + nEffector = tree->GetNumEffector(); + nJoint = tree->GetNumJoint(); + nRow = 3 * nEffector; + nCol = nJoint; + + Jend.SetSize(nRow, nCol); // The Jocobian matrix + Jend.SetZero(); + Jtarget.SetSize(nRow, nCol); // The Jacobian matrix based on target positions + Jtarget.SetZero(); + SetJendActive(); + + U.SetSize(nRow, nRow); // The U matrix for SVD calculations + w .SetLength(Min(nRow, nCol)); + V.SetSize(nCol, nCol); // The V matrix for SVD calculations + + dS.SetLength(nRow); // (Target positions) - (End effector positions) + dTheta.SetLength(nCol); // Changes in joint angles + dPreTheta.SetLength(nCol); + + // Used by Jacobian transpose method & DLS & SDLS + dT1.SetLength(nRow); // Linearized change in end effector positions based on dTheta + + // Used by the Selectively Damped Least Squares Method + //dT.SetLength(nRow); + dSclamp.SetLength(nEffector); + errorArray.SetLength(nEffector); + Jnorms.SetSize(nEffector, nCol); // Holds the norms of the active J matrix + + Reset(); +} + +void Jacobian::Reset() +{ + // Used by Damped Least Squares Method + DampingLambda = DefaultDampingLambda; + DampingLambdaSq = Square(DampingLambda); + // DampingLambdaSDLS = 1.5*DefaultDampingLambda; + + dSclamp.Fill(HUGE_VAL); +} + +// Compute the deltaS vector, dS, (the error in end effector positions +// Compute the J and K matrices (the Jacobians) +void Jacobian::ComputeJacobian() +{ + // Traverse tree to find all end effectors + VectorR3 temp; + Node* n = tree->GetRoot(); + while ( n ) { + if ( n->IsEffector() ) { + int i = n->GetEffectorNum(); + const VectorR3& targetPos = target1[i]; + + // Compute the delta S value (differences from end effectors to target positions. + temp = targetPos; + temp -= n->GetS(); + dS.SetTriple(i, temp); + + // Find all ancestors (they will usually all be joints) + // Set the corresponding entries in the Jacobians J, K. + Node* m = tree->GetParent(n); + while ( m ) { + int j = m->GetJointNum(); + assert ( 0 <=i && iIsFrozen() ) { + Jend.SetTriple(i, j, VectorR3::Zero); + Jtarget.SetTriple(i, j, VectorR3::Zero); + } + else { + temp = m->GetS(); // joint pos. + temp -= n->GetS(); // -(end effector pos. - joint pos.) + temp *= m->GetW(); // cross product with joint rotation axis + Jend.SetTriple(i, j, temp); + temp = m->GetS(); // joint pos. + temp -= targetPos; // -(target pos. - joint pos.) + temp *= m->GetW(); // cross product with joint rotation axis + Jtarget.SetTriple(i, j, temp); + } + m = tree->GetParent( m ); + } + } + n = tree->GetSuccessor( n ); + } +} + +// The delta theta values have been computed in dTheta array +// Apply the delta theta values to the joints +// Nothing is done about joint limits for now. +void Jacobian::UpdateThetas() +{ + // Traverse the tree to find all joints + // Update the joint angles + Node* n = tree->GetRoot(); + while ( n ) { + if ( n->IsJoint() ) { + int i = n->GetJointNum(); + n->AddToTheta( dTheta[i] ); + + } + n = tree->GetSuccessor( n ); + } + + // Update the positions and rotation axes of all joints/effectors + tree->Compute(); +} + +void Jacobian::CalcDeltaThetas() +{ + switch (CurrentUpdateMode) { + case JACOB_Undefined: + ZeroDeltaThetas(); + break; + case JACOB_JacobianTranspose: + CalcDeltaThetasTranspose(); + break; + case JACOB_PseudoInverse: + CalcDeltaThetasPseudoinverse(); + break; + case JACOB_DLS: + CalcDeltaThetasDLS(); + break; + case JACOB_SDLS: + CalcDeltaThetasSDLS(); + break; + } +} + +void Jacobian::ZeroDeltaThetas() +{ + dTheta.SetZero(); +} + +// Find the delta theta values using inverse Jacobian method +// Uses a greedy method to decide scaling factor +void Jacobian::CalcDeltaThetasTranspose() +{ + const MatrixRmn& J = ActiveJacobian(); + + J.MultiplyTranspose( dS, dTheta ); + + // Scale back the dTheta values greedily + J.Multiply ( dTheta, dT1 ); // dT = J * dTheta + double alpha = Dot(dS,dT1) / dT1.NormSq(); + assert ( alpha>0.0 ); + // Also scale back to be have max angle change less than MaxAngleJtranspose + double maxChange = dTheta.MaxAbs(); + double beta = MaxAngleJtranspose/maxChange; + dTheta *= Min(alpha, beta); + +} + +void Jacobian::CalcDeltaThetasPseudoinverse() +{ + MatrixRmn& J = const_cast(ActiveJacobian()); + + // Compute Singular Value Decomposition + // This an inefficient way to do Pseudoinverse, but it is convenient since we need SVD anyway + + J.ComputeSVD( U, w, V ); + + // Next line for debugging only + assert(J.DebugCheckSVD(U, w , V)); + + // Calculate response vector dTheta that is the DLS solution. + // Delta target values are the dS values + // We multiply by Moore-Penrose pseudo-inverse of the J matrix + double pseudoInverseThreshold = PseudoInverseThresholdFactor*w.MaxAbs(); + + long diagLength = w.GetLength(); + double* wPtr = w.GetPtr(); + dTheta.SetZero(); + for ( long i=0; ipseudoInverseThreshold ) { + alpha = 1.0/alpha; + MatrixRmn::AddArrayScale(V.GetNumRows(), V.GetColumnPtr(i), 1, dTheta.GetPtr(), 1, dotProdCol*alpha ); + } + } + + // Scale back to not exceed maximum angle changes + double maxChange = dTheta.MaxAbs(); + if ( maxChange>MaxAnglePseudoinverse ) { + dTheta *= MaxAnglePseudoinverse/maxChange; + } + +} + +void Jacobian::CalcDeltaThetasDLS() +{ + const MatrixRmn& J = ActiveJacobian(); + + MatrixRmn::MultiplyTranspose(J, J, U); // U = J * (J^T) + U.AddToDiagonal( DampingLambdaSq ); + + // Use the next four lines instead of the succeeding two lines for the DLS method with clamped error vector e. + // CalcdTClampedFromdS(); + // VectorRn dTextra(3*nEffector); + // U.Solve( dT, &dTextra ); + // J.MultiplyTranspose( dTextra, dTheta ); + + // Use these two lines for the traditional DLS method + U.Solve( dS, &dT1 ); + J.MultiplyTranspose( dT1, dTheta ); + + // Scale back to not exceed maximum angle changes + double maxChange = dTheta.MaxAbs(); + if ( maxChange>MaxAngleDLS ) { + dTheta *= MaxAngleDLS/maxChange; + } +} + +void Jacobian::CalcDeltaThetasDLSwithSVD() +{ + const MatrixRmn& J = ActiveJacobian(); + + // Compute Singular Value Decomposition + // This an inefficient way to do DLS, but it is convenient since we need SVD anyway + + J.ComputeSVD( U, w, V ); + + // Next line for debugging only + assert(J.DebugCheckSVD(U, w , V)); + + // Calculate response vector dTheta that is the DLS solution. + // Delta target values are the dS values + // We multiply by DLS inverse of the J matrix + long diagLength = w.GetLength(); + double* wPtr = w.GetPtr(); + dTheta.SetZero(); + for ( long i=0; iMaxAngleDLS ) { + dTheta *= MaxAngleDLS/maxChange; + } +} + + +void Jacobian::CalcDeltaThetasSDLS() +{ + const MatrixRmn& J = ActiveJacobian(); + + // Compute Singular Value Decomposition + + J.ComputeSVD( U, w, V ); + + // Next line for debugging only + assert(J.DebugCheckSVD(U, w , V)); + + // Calculate response vector dTheta that is the SDLS solution. + // Delta target values are the dS values + int nRows = J.GetNumRows(); + int numEndEffectors = tree->GetNumEffector(); // Equals the number of rows of J divided by three + int nCols = J.GetNumColumns(); + dTheta.SetZero(); + + // Calculate the norms of the 3-vectors in the Jacobian + long i; + const double *jx = J.GetPtr(); + double *jnx = Jnorms.GetPtr(); + for ( i=nCols*numEndEffectors; i>0; i-- ) { + double accumSq = Square(*(jx++)); + accumSq += Square(*(jx++)); + accumSq += Square(*(jx++)); + *(jnx++) = sqrt(accumSq); + } + + // Clamp the dS values + CalcdTClampedFromdS(); + + // Loop over each singular vector + for ( i=0; i0; j-- ) { + double tmp; + alpha += (*ux)*(*(dTx++)); + tmp = Square( *(ux++) ); + alpha += (*ux)*(*(dTx++)); + tmp += Square(*(ux++)); + alpha += (*ux)*(*(dTx++)); + tmp += Square(*(ux++)); + N += sqrt(tmp); + } + + // M is the quasi-1-norm of the response to angles changing according to the i-th column of V + // Then is multiplied by the wiInv value. + double M = 0.0; + double *vx = V.GetColumnPtr(i); + jnx = Jnorms.GetPtr(); + for ( j=nCols; j>0; j-- ) { + double accum=0.0; + for ( long k=numEndEffectors; k>0; k-- ) { + accum += *(jnx++); + } + M += fabs((*(vx++)))*accum; + } + M *= fabs(wiInv); + + double gamma = MaxAngleSDLS; + if ( NMaxAngleSDLS ) { + dTheta *= MaxAngleSDLS/(MaxAngleSDLS+maxChange); + //dTheta *= MaxAngleSDLS/maxChange; + } +} + +void Jacobian::CalcdTClampedFromdS() +{ + long len = dS.GetLength(); + long j = 0; + for ( long i=0; iSquare(dSclamp[j]) ) { + double factor = dSclamp[j]/sqrt(normSq); + dT1[i] = dS[i]*factor; + dT1[i+1] = dS[i+1]*factor; + dT1[i+2] = dS[i+2]*factor; + } + else { + dT1[i] = dS[i]; + dT1[i+1] = dS[i+1]; + dT1[i+2] = dS[i+2]; + } + } +} + +double Jacobian::UpdateErrorArray() +{ + double totalError = 0.0; + + // Traverse tree to find all end effectors + VectorR3 temp; + Node* n = tree->GetRoot(); + while ( n ) { + if ( n->IsEffector() ) { + int i = n->GetEffectorNum(); + const VectorR3& targetPos = target1[i]; + temp = targetPos; + temp -= n->GetS(); + double err = temp.Norm(); + errorArray[i] = err; + totalError += err; + } + n = tree->GetSuccessor( n ); + } + return totalError; +} + +void Jacobian::UpdatedSClampValue() +{ + // Traverse tree to find all end effectors + VectorR3 temp; + Node* n = tree->GetRoot(); + while ( n ) { + if ( n->IsEffector() ) { + int i = n->GetEffectorNum(); + const VectorR3& targetPos = target1[i]; + + // Compute the delta S value (differences from end effectors to target positions. + // While we are at it, also update the clamping values in dSclamp; + temp = targetPos; + temp -= n->GetS(); + double normSi = sqrt(Square(dS[i])+Square(dS[i+1])+Square(dS[i+2])); + double changedDist = temp.Norm()-normSi; + if ( changedDist>0.0 ) { + dSclamp[i] = BaseMaxTargetDist + changedDist; + } + else { + dSclamp[i] = BaseMaxTargetDist; + } + } + n = tree->GetSuccessor( n ); + } +} + +void Jacobian::DrawEigenVectors() const +{ + int i, j; + VectorR3 tail; + VectorR3 head; + Node *node; + + for (i=0; iGetEffector(j); + tail = node->GetS(); + U.GetTriple( j, i, &head ); + head += tail; + glDisable(GL_LIGHTING); + glColor3f(1.0f, 0.2f, 0.0f); + glLineWidth(2.0); + glBegin(GL_LINES); + glVertex3f(tail.x, tail.y, tail.z); + glVertex3f(head.x, head.y, tail.z); + glEnd(); + Arrow(tail, head); + glLineWidth(1.0); + glEnable(GL_LIGHTING); + } + } +} + +void Jacobian::CompareErrors( const Jacobian& j1, const Jacobian& j2, double* weightedDist1, double* weightedDist2 ) +{ + const VectorRn& e1 = j1.errorArray; + const VectorRn& e2 = j2.errorArray; + double ret1 = 0.0; + double ret2 = 0.0; + int len = e1.GetLength(); + for ( long i=0; iGetNumEffector(); // Equals the number of rows of J divided by three + int nCols = J.GetNumColumns(); + dTheta.SetZero(); + + // Calculate the norms of the 3-vectors in the Jacobian + long i; + const double *jx = J.GetPtr(); + double *jnx = Jnorms.GetPtr(); + for ( i=nCols*numEndEffectors; i>0; i-- ) { + double accumSq = Square(*(jx++)); + accumSq += Square(*(jx++)); + accumSq += Square(*(jx++)); + *(jnx++) = sqrt(accumSq); + } + + // Loop over each singular vector + for ( i=0; i0; j-- ) { + double tmp; + alpha += (*ux)*(*(dSx++)); + tmp = Square( *(ux++) ); + alpha += (*ux)*(*(dSx++)); + tmp += Square(*(ux++)); + alpha += (*ux)*(*(dSx++)); + tmp += Square(*(ux++)); + N += sqrt(tmp); + } + + // P is the quasi-1-norm of the response to angles changing according to the i-th column of V + double P = 0.0; + double *vx = V.GetColumnPtr(i); + jnx = Jnorms.GetPtr(); + for ( j=nCols; j>0; j-- ) { + double accum=0.0; + for ( long k=numEndEffectors; k>0; k-- ) { + accum += *(jnx++); + } + P += fabs((*(vx++)))*accum; + } + + double lambda = 1.0; + if ( N

      MaxAngleSDLS ) { + dTheta *= MaxAngleSDLS/maxChange; + } +} */ + + + + diff --git a/examples/ThirdPartyLibs/BussIK/Jacobian.h b/examples/ThirdPartyLibs/BussIK/Jacobian.h new file mode 100644 index 000000000..1c0bc4572 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/Jacobian.h @@ -0,0 +1,132 @@ + +/* +* +* Inverse Kinematics software, with several solvers including +* Selectively Damped Least Squares Method +* Damped Least Squares Method +* Pure Pseudoinverse Method +* Jacobian Transpose Method +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + +#include "Node.h" +#include "Tree.h" +#include "MathMisc.h" +#include "LinearR3.h" +#include "VectorRn.h" +#include "MatrixRmn.h" + +#ifndef _CLASS_JACOBIAN +#define _CLASS_JACOBIAN + +#ifdef _DYNAMIC +const double BASEMAXDIST = 0.02; +#else +const double MAXDIST = 0.08; // optimal value for double Y shape : 0.08 +#endif +const double DELTA = 0.4; +const long double LAMBDA = 2.0; // only for DLS. optimal : 0.24 +const double NEARZERO = 0.0000000001; + +enum UpdateMode { + JACOB_Undefined = 0, + JACOB_JacobianTranspose = 1, + JACOB_PseudoInverse = 2, + JACOB_DLS = 3, + JACOB_SDLS = 4 }; + +class Jacobian { +public: + Jacobian(Tree*); + + void ComputeJacobian(); + const MatrixRmn& ActiveJacobian() const { return *Jactive; } + void SetJendActive() { Jactive = &Jend; } // The default setting is Jend. + void SetJtargetActive() { Jactive = &Jtarget; } + + void CalcDeltaThetas(); // Use this only if the Current Mode has been set. + void ZeroDeltaThetas(); + void CalcDeltaThetasTranspose(); + void CalcDeltaThetasPseudoinverse(); + void CalcDeltaThetasDLS(); + void CalcDeltaThetasDLSwithSVD(); + void CalcDeltaThetasSDLS(); + + void UpdateThetas(); + double UpdateErrorArray(); // Returns sum of errors + const VectorRn& GetErrorArray() const { return errorArray; } + void UpdatedSClampValue(); + void DrawEigenVectors() const; + + void SetCurrentMode( UpdateMode mode ) { CurrentUpdateMode = mode; } + UpdateMode GetCurrentMode() const { return CurrentUpdateMode; } + void SetDampingDLS( double lambda ) { DampingLambda = lambda; DampingLambdaSq = Square(lambda); } + + void Reset(); + + static void CompareErrors( const Jacobian& j1, const Jacobian& j2, double* weightedDist1, double* weightedDist2 ); + static void CountErrors( const Jacobian& j1, const Jacobian& j2, int* numBetter1, int* numBetter2, int* numTies ); + +private: + Tree* tree; // tree associated with this Jacobian matrix + int nEffector; // Number of end effectors + int nJoint; // Number of joints + int nRow; // Total number of rows the real J (= 3*number of end effectors for now) + int nCol; // Total number of columns in the real J (= number of joints for now) + + MatrixRmn Jend; // Jacobian matrix based on end effector positions + MatrixRmn Jtarget; // Jacobian matrix based on target positions + MatrixRmn Jnorms; // Norms of 3-vectors in active Jacobian (SDLS only) + + MatrixRmn U; // J = U * Diag(w) * V^T (Singular Value Decomposition) + VectorRn w; + MatrixRmn V; + + UpdateMode CurrentUpdateMode; + + VectorRn dS; // delta s + VectorRn dT1; // delta t -- these are delta S values clamped to smaller magnitude + VectorRn dSclamp; // Value to clamp magnitude of dT at. + VectorRn dTheta; // delta theta + VectorRn dPreTheta; // delta theta for single eigenvalue (SDLS only) + + VectorRn errorArray; // Distance of end effectors from target after updating + + // Parameters for pseudoinverses + static const double PseudoInverseThresholdFactor; // Threshold for treating eigenvalue as zero (fraction of largest eigenvalue) + + // Parameters for damped least squares + static const double DefaultDampingLambda; + double DampingLambda; + double DampingLambdaSq; + //double DampingLambdaSDLS; + + // Cap on max. value of changes in angles in single update step + static const double MaxAngleJtranspose; + static const double MaxAnglePseudoinverse; + static const double MaxAngleDLS; + static const double MaxAngleSDLS; + MatrixRmn* Jactive; + + void CalcdTClampedFromdS(); + static const double BaseMaxTargetDist; + +}; + +#endif \ No newline at end of file diff --git a/examples/ThirdPartyLibs/BussIK/LinearR2.cpp b/examples/ThirdPartyLibs/BussIK/LinearR2.cpp new file mode 100644 index 000000000..9e3398f65 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/LinearR2.cpp @@ -0,0 +1,101 @@ + /* + * + * Mathematics Subpackage (VrMath) + * + * + * Author: Samuel R. Buss, sbuss@ucsd.edu. + * Web page: http://math.ucsd.edu/~sbuss/MathCG + * + * + This software is provided 'as-is', without any express or implied warranty. + In no event will the authors be held liable for any damages arising from the use of this software. + Permission is granted to anyone to use this software for any purpose, + including commercial applications, and to alter it and redistribute it freely, + subject to the following restrictions: + + 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. + 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. + 3. This notice may not be removed or altered from any source distribution. + * + * + */ + +#include "LinearR2.h" + + +#include + +// ****************************************************** +// * VectorR2 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +const VectorR2 VectorR2::Zero(0.0, 0.0); +const VectorR2 VectorR2::UnitX( 1.0, 0.0); +const VectorR2 VectorR2::UnitY( 0.0, 1.0); +const VectorR2 VectorR2::NegUnitX(-1.0, 0.0); +const VectorR2 VectorR2::NegUnitY( 0.0,-1.0); + +const Matrix2x2 Matrix2x2::Identity(1.0, 0.0, 0.0, 1.0); + +// ****************************************************** +// * Matrix2x2 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + + +// ****************************************************** +// * LinearMapR2 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + + +LinearMapR2 LinearMapR2::Inverse() const // Returns inverse +{ + + + register double detInv = 1.0/(m11*m22 - m12*m21) ; + + return( LinearMapR2( m22*detInv, -m21*detInv, -m12*detInv, m11*detInv ) ); +} + +LinearMapR2& LinearMapR2::Invert() // Converts into inverse. +{ + register double detInv = 1.0/(m11*m22 - m12*m21) ; + + double temp; + temp = m11*detInv; + m11= m22*detInv; + m22=temp; + m12 = -m12*detInv; + m21 = -m22*detInv; + + return ( *this ); +} + +VectorR2 LinearMapR2::Solve(const VectorR2& u) const // Returns solution +{ + // Just uses Inverse() for now. + return ( Inverse()*u ); +} + +// ****************************************************** +// * RotationMapR2 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + + + +// *************************************************************** +// * 2-space vector and matrix utilities * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + + + + +// *************************************************************** +// Stream Output Routines * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +ostream& operator<< ( ostream& os, const VectorR2& u ) +{ + return (os << "<" << u.x << "," << u.y << ">"); +} + + diff --git a/examples/ThirdPartyLibs/BussIK/LinearR2.h b/examples/ThirdPartyLibs/BussIK/LinearR2.h new file mode 100644 index 000000000..4c4140c71 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/LinearR2.h @@ -0,0 +1,981 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + + +// +// Linear Algebra Classes over R2 +// +// +// A. Vector and Position classes +// +// A.1. VectorR2: a column vector of length 2 +// +// A.2. VectorHgR2 - homogenous vector for R2 (a 3-Vector) +// +// B. Matrix Classes +// +// B.1 LinearMapR2 - arbitrary linear map; 2x2 real matrix +// +// B.2 RotationMapR2 - orthonormal 2x2 matrix +// + +#ifndef LINEAR_R2_H +#define LINEAR_R2_H + +#include +#include +#include +#include "MathMisc.h" +using namespace std; + +class VectorR2; // R2 Vector +class VectorHgR2; +class Matrix2x2; +class LinearMapR2; // 2x2 real matrix +class AffineMapR3; // Affine Map (3x4 Matrix) +class RotationMapR2; // 2x2 rotation map + +// ************************************** +// VectorR2 class * +// * * * * * * * * * * * * * * * * * * ** + +class VectorR2 { + +public: + double x, y; // The x & y coordinates. + +public: + VectorR2( ) : x(0.0), y(0.0) {} + VectorR2( double xVal, double yVal ) + : x(xVal), y(yVal) {} + VectorR2( const VectorHgR2& uH ); + + VectorR2& SetZero() { x=0.0; y=0.0; return *this;} + VectorR2& Set( double xx, double yy ) + { x=xx; y=yy; return *this;} + VectorR2& Load( const double* v ); + VectorR2& Load( const float* v ); + void Dump( double* v ) const; + void Dump( float* v ) const; + + static const VectorR2 Zero; + static const VectorR2 UnitX; + static const VectorR2 UnitY; + static const VectorR2 NegUnitX; + static const VectorR2 NegUnitY; + + VectorR2& operator+= ( const VectorR2& v ) + { x+=v.x; y+=v.y; return(*this); } + VectorR2& operator-= ( const VectorR2& v ) + { x-=v.x; y-=v.y; return(*this); } + VectorR2& operator*= ( double m ) + { x*=m; y*=m; return(*this); } + VectorR2& operator/= ( double m ) + { register double mInv = 1.0/m; + x*=mInv; y*=mInv; + return(*this); } + VectorR2 operator- () const { return ( VectorR2(-x, -y) ); } + VectorR2& ArrayProd(const VectorR2&); // Component-wise product + + VectorR2& AddScaled( const VectorR2& u, double s ); + + double Norm() const { return ( sqrt( x*x + y*y ) ); } + double L1Norm() const { return (Max(fabs(x),fabs(y))); } + double Dist( const VectorR2& u ) const; // Distance from u + double DistSq( const VectorR2& u ) const; // Distance from u + double NormSq() const { return ( x*x + y*y ); } + double MaxAbs() const; + VectorR2& Normalize () { *this /= Norm(); return *this;} // No error checking + VectorR2& MakeUnit(); // Normalize() with error checking + VectorR2& ReNormalize(); + bool IsUnit( double tolerance = 1.0e-15 ) const + { register double norm = Norm(); + return ( 1.0+tolerance>=norm && norm>=1.0-tolerance ); } + bool IsZero() const { return ( x==0.0 && y==0.0 ); } + bool NearZero(double tolerance) const { return( MaxAbs()<=tolerance );} + // tolerance should be non-negative + + VectorR2& Rotate( double theta ); // rotate through angle theta + VectorR2& Rotate( double costheta, double sintheta ); + +}; + +inline VectorR2 operator+( const VectorR2& u, const VectorR2& v ); +inline VectorR2 operator-( const VectorR2& u, const VectorR2& v ); +inline VectorR2 operator*( const VectorR2& u, double m); +inline VectorR2 operator*( double m, const VectorR2& u); +inline VectorR2 operator/( const VectorR2& u, double m); +inline int operator==( const VectorR2& u, const VectorR2& v ); + +inline double operator^ (const VectorR2& u, const VectorR2& v ); // Dot Product +inline VectorR2 ArrayProd ( const VectorR2& u, const VectorR2& v ); + +inline double Mag(const VectorR2& u) { return u.Norm(); } +inline double Dist(const VectorR2& u, const VectorR2& v) { return u.Dist(v); } +inline double DistSq(const VectorR2& u, const VectorR2& v) { return u.DistSq(v); } +inline double NormalizeError (const VectorR2&); + +// **************************************** +// VectorHgR2 class * +// * * * * * * * * * * * * * * * * * * * ** + +class VectorHgR2 { + +public: + double x, y, w; // The x & y & w coordinates. + +public: + VectorHgR2( ) : x(0.0), y(0.0), w(1.0) {} + VectorHgR2( double xVal, double yVal ) + : x(xVal), y(yVal), w(1.0) {} + VectorHgR2( double xVal, double yVal, double wVal ) + : x(xVal), y(yVal), w(wVal) {} + VectorHgR2 ( const VectorR2& u ) : x(u.x), y(u.y), w(1.0) {} +}; + +// ******************************************************************** +// Matrix2x2 - base class for 2x2 matrices * +// * * * * * * * * * * * * * * * * * * * * * ************************** + +class Matrix2x2 { + +public: + double m11, m12, m21, m22; + + // Implements a 2x2 matrix: m_i_j - row-i and column-j entry + + static const Matrix2x2 Identity; + +public: + + inline Matrix2x2(); + inline Matrix2x2( const VectorR2&, const VectorR2& ); // Sets by columns! + inline Matrix2x2( double, double, double, double ); // Sets by columns + + inline void SetIdentity (); // Set to the identity map + inline void SetZero (); // Set to the zero map + inline void Set( const VectorR2&, const VectorR2& ); + inline void Set( double, double, double, double ); + inline void SetByRows( const VectorR2&, const VectorR2& ); + inline void SetByRows( double, double, double, double ); + inline void SetColumn1 ( double, double ); + inline void SetColumn2 ( double, double ); + inline void SetColumn1 ( const VectorR2& ); + inline void SetColumn2 ( const VectorR2& ); + inline VectorR2 Column1() const; + inline VectorR2 Column2() const; + + inline void SetRow1 ( double, double ); + inline void SetRow2 ( double, double ); + inline void SetRow1 ( const VectorR2& ); + inline void SetRow2 ( const VectorR2& ); + inline VectorR2 Row1() const; + inline VectorR2 Row2() const; + + inline void SetDiagonal( double, double ); + inline void SetDiagonal( const VectorR2& ); + inline double Diagonal( int ); + + inline void MakeTranspose(); // Transposes it. + inline void operator*= (const Matrix2x2& B); // Matrix product + inline Matrix2x2& ReNormalize(); + + inline void Transform( VectorR2* ) const; + inline void Transform( const VectorR2& src, VectorR2* dest) const; + +}; + +inline double NormalizeError( const Matrix2x2& ); +inline VectorR2 operator* ( const Matrix2x2&, const VectorR2& ); + +ostream& operator<< ( ostream& os, const Matrix2x2& A ); + + +// ***************************************** +// LinearMapR2 class * +// * * * * * * * * * * * * * * * * * * * * * + +class LinearMapR2 : public Matrix2x2 { + +public: + + LinearMapR2(); + LinearMapR2( const VectorR2&, const VectorR2& ); // Sets by columns! + LinearMapR2( double, double, double, double ); // Sets by columns + LinearMapR2 ( const Matrix2x2& ); + + inline void Negate(); + inline LinearMapR2& operator+= (const Matrix2x2& ); + inline LinearMapR2& operator-= (const Matrix2x2& ); + inline LinearMapR2& operator*= (double); + inline LinearMapR2& operator/= (double); + inline LinearMapR2& operator*= (const Matrix2x2& ); // Matrix product + + inline LinearMapR2 Transpose() const; + inline double Determinant () const; // Returns the determinant + LinearMapR2 Inverse() const; // Returns inverse + LinearMapR2& Invert(); // Converts into inverse. + VectorR2 Solve(const VectorR2&) const; // Returns solution + LinearMapR2 PseudoInverse() const; // Returns pseudo-inverse TO DO + VectorR2 PseudoSolve(const VectorR2&); // Finds least squares solution TO DO +}; + +inline LinearMapR2 operator+ ( const LinearMapR2&, const LinearMapR2&); +inline LinearMapR2 operator- ( const Matrix2x2& ); +inline LinearMapR2 operator- ( const LinearMapR2&, const LinearMapR2&); +inline LinearMapR2 operator* ( const LinearMapR2&, double); +inline LinearMapR2 operator* ( double, const LinearMapR2& ); +inline LinearMapR2 operator/ ( const LinearMapR2&, double ); +inline LinearMapR2 operator* ( const Matrix2x2&, const LinearMapR2& ); +inline LinearMapR2 operator* ( const LinearMapR2&, const Matrix2x2& ); +inline LinearMapR2 operator* ( const LinearMapR2&, const LinearMapR2& ); + // Matrix product (composition) + + +// ******************************************* +// RotationMapR2class * +// * * * * * * * * * * * * * * * * * * * * * * + +class RotationMapR2 : public Matrix2x2 { + +public: + + RotationMapR2(); + RotationMapR2( const VectorR2&, const VectorR2& ); // Sets by columns! + RotationMapR2( double, double, double, double ); // Sets by columns! + + RotationMapR2& SetZero(); // IT IS AN ERROR TO USE THIS FUNCTION! + + inline RotationMapR2& operator*= (const RotationMapR2& ); // Matrix product + + inline RotationMapR2 Transpose() const; + inline RotationMapR2 Inverse() const { return Transpose(); }; // Returns the transpose + inline RotationMapR2& Invert() { MakeTranspose(); return *this; }; // Transposes it. + inline VectorR2 Invert(const VectorR2&) const; // Returns solution +}; + +inline RotationMapR2 operator* ( const RotationMapR2&, const RotationMapR2& ); + // Matrix product (composition) + + + +// *************************************************************** +// * 2-space vector and matrix utilities (prototypes) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +// Returns the angle between vectors u and v. +// Use AngleUnit if both vectors are unit vectors +inline double Angle( const VectorR2& u, const VectorR2& v); +inline double AngleUnit( const VectorR2& u, const VectorR2& v ); + +// Returns a righthanded orthonormal basis to complement vector u +// The vector u must be unit. +inline VectorR2 GetOrtho( const VectorR2& u ); + +// Projections + +inline VectorR2 ProjectToUnit ( const VectorR2& u, const VectorR2& v); + // Project u onto v +inline VectorR2 ProjectPerpUnit ( const VectorR2& u, const VectorR2 & v); + // Project perp to v +// v must be a unit vector. + +// Projection maps (LinearMapR2's) + +inline LinearMapR2 VectorProjectMap( const VectorR2& u ); + +inline LinearMapR2 PerpProjectMap ( const VectorR2& u ); +// u - must be unit vector. + +// Rotation Maps + +inline RotationMapR2 RotateToMap( const VectorR2& fromVec, const VectorR2& toVec); +// fromVec and toVec should be unit vectors + + + +// *************************************************************** +// * Stream Output Routines (Prototypes) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +ostream& operator<< ( ostream& os, const VectorR2& u ); + + +// ***************************************************** +// * VectorR2 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * + +inline VectorR2& VectorR2::Load( const double* v ) +{ + x = *v; + y = *(v+1); + return *this; +} + +inline VectorR2& VectorR2::Load( const float* v ) +{ + x = *v; + y = *(v+1); + return *this; +} + +inline void VectorR2::Dump( double* v ) const +{ + *v = x; + *(v+1) = y; +} + +inline void VectorR2::Dump( float* v ) const +{ + *v = (float)x; + *(v+1) = (float)y; +} + +inline VectorR2& VectorR2::ArrayProd (const VectorR2& v) // Component-wise Product +{ + x *= v.x; + y *= v.y; + return ( *this ); +} + +inline VectorR2& VectorR2::MakeUnit () // Convert to unit vector (or leave zero). +{ + double nSq = NormSq(); + if (nSq != 0.0) { + *this /= sqrt(nSq); + } + return *this; +} + +inline VectorR2& VectorR2::ReNormalize() // Convert near unit back to unit +{ + double nSq = NormSq(); + register double mFact = 1.0-0.5*(nSq-1.0); // Multiplicative factor + *this *= mFact; + return *this; +} + +// Rotate through angle theta +inline VectorR2& VectorR2::Rotate( double theta ) +{ + double costheta = cos(theta); + double sintheta = sin(theta); + double tempx = x*costheta - y*sintheta; + y = y*costheta + x*sintheta; + x = tempx; + return *this; +} + +inline VectorR2& VectorR2::Rotate( double costheta, double sintheta ) +{ + double tempx = x*costheta + y*sintheta; + y = y*costheta - x*sintheta; + x = tempx; + return *this; +} + +inline double VectorR2::MaxAbs() const +{ + register double m; + m = (x>=0.0) ? x : -x; + if ( y>m ) m=y; + else if ( -y >m ) m = -y; + return m; +} + +inline VectorR2 operator+( const VectorR2& u, const VectorR2& v ) +{ + return VectorR2(u.x+v.x, u.y+v.y ); +} +inline VectorR2 operator-( const VectorR2& u, const VectorR2& v ) +{ + return VectorR2(u.x-v.x, u.y-v.y ); +} +inline VectorR2 operator*( const VectorR2& u, register double m) +{ + return VectorR2( u.x*m, u.y*m ); +} +inline VectorR2 operator*( register double m, const VectorR2& u) +{ + return VectorR2( u.x*m, u.y*m ); +} +inline VectorR2 operator/( const VectorR2& u, double m) +{ + register double mInv = 1.0/m; + return VectorR2( u.x*mInv, u.y*mInv ); +} + +inline int operator==( const VectorR2& u, const VectorR2& v ) +{ + return ( u.x==v.x && u.y==v.y ); +} + +inline double operator^ ( const VectorR2& u, const VectorR2& v ) // Dot Product +{ + return ( u.x*v.x + u.y*v.y ); +} + +inline VectorR2 ArrayProd ( const VectorR2& u, const VectorR2& v ) +{ + return ( VectorR2( u.x*v.x, u.y*v.y ) ); +} + +inline VectorR2& VectorR2::AddScaled( const VectorR2& u, double s ) +{ + x += s*u.x; + y += s*u.y; + return(*this); +} + +inline VectorR2::VectorR2( const VectorHgR2& uH ) +: x(uH.x), y(uH.y) +{ + *this /= uH.w; +} + +inline double NormalizeError (const VectorR2& u) +{ + register double discrepancy; + discrepancy = u.x*u.x + u.y*u.y - 1.0; + if ( discrepancy < 0.0 ) { + discrepancy = -discrepancy; + } + return discrepancy; +} + +inline double VectorR2::Dist( const VectorR2& u ) const // Distance from u +{ + return sqrt( DistSq(u) ); +} + +inline double VectorR2::DistSq( const VectorR2& u ) const // Distance from u +{ + return ( (x-u.x)*(x-u.x) + (y-u.y)*(y-u.y) ); +} + + +// ********************************************************* +// * Matrix2x2 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ***** + +inline Matrix2x2::Matrix2x2() {} + +inline Matrix2x2::Matrix2x2( const VectorR2& u, const VectorR2& v ) +{ + m11 = u.x; // Column 1 + m21 = u.y; + m12 = v.x; // Column 2 + m22 = v.y; +} + +inline Matrix2x2::Matrix2x2( double a11, double a21, double a12, double a22 ) + // Values specified in column order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m21 = a21; // Row 2 + m22 = a22; +} + +inline void Matrix2x2::SetIdentity ( ) +{ + m11 = m22 = 1.0; + m12 = m21 = 0.0; +} + +inline void Matrix2x2::Set( const VectorR2& u, const VectorR2& v ) +{ + m11 = u.x; // Column 1 + m21 = u.y; + m12 = v.x; // Column 2 + m22 = v.y; +} + +inline void Matrix2x2::Set( double a11, double a21, double a12, double a22 ) + // Values specified in column order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m21 = a21; // Row 2 + m22 = a22; +} + +inline void Matrix2x2::SetZero( ) +{ + m11 = m12 = m21 = m22 = 0.0; +} + +inline void Matrix2x2::SetByRows( const VectorR2& u, const VectorR2& v ) +{ + m11 = u.x; // Row 1 + m12 = u.y; + m21 = v.x; // Row 2 + m22 = v.y; +} + +inline void Matrix2x2::SetByRows( double a11, double a12, double a21, double a22 ) + // Values specified in row order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m21 = a21; // Row 2 + m22 = a22; +} + +inline void Matrix2x2::SetColumn1 ( double x, double y ) +{ + m11 = x; m21 = y; +} + +inline void Matrix2x2::SetColumn2 ( double x, double y ) +{ + m12 = x; m22 = y; +} + +inline void Matrix2x2::SetColumn1 ( const VectorR2& u ) +{ + m11 = u.x; m21 = u.y; +} + +inline void Matrix2x2::SetColumn2 ( const VectorR2& u ) +{ + m12 = u.x; m22 = u.y; +} + +VectorR2 Matrix2x2::Column1() const +{ + return ( VectorR2(m11, m21) ); +} + +VectorR2 Matrix2x2::Column2() const +{ + return ( VectorR2(m12, m22) ); +} + +inline void Matrix2x2::SetRow1 ( double x, double y ) +{ + m11 = x; m12 = y; +} + +inline void Matrix2x2::SetRow2 ( double x, double y ) +{ + m21 = x; m22 = y; +} + +inline void Matrix2x2::SetRow1 ( const VectorR2& u ) +{ + m11 = u.x; m12 = u.y; +} + +inline void Matrix2x2::SetRow2 ( const VectorR2& u ) +{ + m21 = u.x; m22 = u.y; +} + +VectorR2 Matrix2x2::Row1() const +{ + return ( VectorR2(m11, m12) ); +} + +VectorR2 Matrix2x2::Row2() const +{ + return ( VectorR2(m21, m22) ); +} + +inline void Matrix2x2::SetDiagonal( double x, double y ) +{ + m11 = x; + m22 = y; +} + +inline void Matrix2x2::SetDiagonal( const VectorR2& u ) +{ + SetDiagonal ( u.x, u.y ); +} + +inline double Matrix2x2::Diagonal( int i ) +{ + switch (i) { + case 0: + return m11; + case 1: + return m22; + default: + assert(0); + return 0.0; + } +} +inline void Matrix2x2::MakeTranspose() // Transposes it. +{ + register double temp; + temp = m12; + m12 = m21; + m21=temp; +} + +inline void Matrix2x2::operator*= (const Matrix2x2& B) // Matrix product +{ + double t1; // temporary value + + t1 = m11*B.m11 + m12*B.m21; + m12 = m11*B.m12 + m12*B.m22; + m11 = t1; + + t1 = m21*B.m11 + m22*B.m21; + m22 = m21*B.m12 + m22*B.m22; + m21 = t1; +} + +inline Matrix2x2& Matrix2x2::ReNormalize() // Re-normalizes nearly orthonormal matrix +{ + register double alpha = m11*m11+m21*m21; // First column's norm squared + register double beta = m12*m12+m22*m22; // Second column's norm squared + alpha = 1.0 - 0.5*(alpha-1.0); // Get mult. factor + beta = 1.0 - 0.5*(beta-1.0); + m11 *= alpha; // Renormalize first column + m21 *= alpha; + m12 *= beta; // Renormalize second column + m22 *= beta; + alpha = m11*m12+m21*m22; // Columns' inner product + alpha *= 0.5; // times 1/2 + register double temp; + temp = m11-alpha*m12; // Subtract alpha times other column + m12 -= alpha*m11; + m11 = temp; + temp = m21-alpha*m22; + m22 -= alpha*m21; + m11 = temp; + return *this; +} + +// Gives a measure of how far the matrix is from being normalized. +// Mostly intended for diagnostic purposes. +inline double NormalizeError( const Matrix2x2& A) +{ + register double discrepancy; + register double newdisc; + discrepancy = A.m11*A.m11 + A.m21*A.m21 -1.0; // First column - inner product - 1 + if (discrepancy<0.0) { + discrepancy = -discrepancy; + } + newdisc = A.m12*A.m12 + A.m22*A.m22 - 1.0; // Second column inner product - 1 + if ( newdisc<0.0 ) { + newdisc = -newdisc; + } + if ( newdisc>discrepancy ) { + discrepancy = newdisc; + } + newdisc = A.m11*A.m12 + A.m21*A.m22; // Inner product of two columns + if ( newdisc<0.0 ) { + newdisc = -newdisc; + } + if ( newdisc>discrepancy ) { + discrepancy = newdisc; + } + return discrepancy; +} + +inline VectorR2 operator* ( const Matrix2x2& A, const VectorR2& u) +{ + return(VectorR2 ( A.m11*u.x + A.m12*u.y, + A.m21*u.x + A.m22*u.y ) ); +} + +inline void Matrix2x2::Transform( VectorR2* u ) const { + double newX; + newX = m11*u->x + m12*u->y; + u->y = m21*u->x + m22*u->y; + u->x = newX; +} + +inline void Matrix2x2::Transform( const VectorR2& src, VectorR2* dest ) const { + dest->x = m11*src.x + m12*src.y; + dest->y = m21*src.x + m22*src.y; +} + + + +// ****************************************************** +// * LinearMapR2 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +inline LinearMapR2::LinearMapR2() +{ + SetZero(); + return; +} + +inline LinearMapR2::LinearMapR2( const VectorR2& u, const VectorR2& v ) +:Matrix2x2 ( u, v ) +{ } + +inline LinearMapR2::LinearMapR2(double a11, double a21, double a12, double a22) + // Values specified in column order!!! +:Matrix2x2 ( a11, a21, a12, a22 ) +{ } + +inline LinearMapR2::LinearMapR2 ( const Matrix2x2& A ) +: Matrix2x2 (A) +{} + +inline void LinearMapR2::Negate () +{ + m11 = -m11; + m12 = -m12; + m21 = -m21; + m22 = -m22; +} + +inline LinearMapR2& LinearMapR2::operator+= (const Matrix2x2& B) +{ + m11 += B.m11; + m12 += B.m12; + m21 += B.m21; + m22 += B.m22; + return ( *this ); +} + +inline LinearMapR2& LinearMapR2::operator-= (const Matrix2x2& B) +{ + m11 -= B.m11; + m12 -= B.m12; + m21 -= B.m21; + m22 -= B.m22; + return( *this ); +} + +inline LinearMapR2 operator+ (const LinearMapR2& A, const LinearMapR2& B) +{ + return( LinearMapR2( A.m11+B.m11, A.m21+B.m21, + A.m12+B.m12, A.m22+B.m22 ) ); +} + +inline LinearMapR2 operator- (const Matrix2x2& A) +{ + return( LinearMapR2( -A.m11, -A.m21, -A.m12, -A.m22 ) ); +} + +inline LinearMapR2 operator- (const LinearMapR2& A, const LinearMapR2& B) +{ + return( LinearMapR2( A.m11-B.m11, A.m21-B.m21, + A.m12-B.m12, A.m22-B.m22 ) ); +} + +inline LinearMapR2& LinearMapR2::operator*= (register double b) +{ + m11 *= b; + m12 *= b; + m21 *= b; + m22 *= b; + return ( *this); +} + +inline LinearMapR2 operator* ( const LinearMapR2& A, register double b) +{ + return( LinearMapR2( A.m11*b, A.m21*b, + A.m12*b, A.m22*b ) ); +} + +inline LinearMapR2 operator* ( register double b, const LinearMapR2& A) +{ + return( LinearMapR2( A.m11*b, A.m21*b, + A.m12*b, A.m22*b ) ); +} + +inline LinearMapR2 operator/ ( const LinearMapR2& A, double b) +{ + register double bInv = 1.0/b; + return ( A*bInv ); +} + +inline LinearMapR2& LinearMapR2::operator/= (register double b) +{ + register double bInv = 1.0/b; + return ( *this *= bInv ); +} + +inline LinearMapR2 LinearMapR2::Transpose() const // Returns the transpose +{ + return (LinearMapR2( m11, m12, m21, m22 ) ); +} + +inline LinearMapR2& LinearMapR2::operator*= (const Matrix2x2& B) // Matrix product +{ + (*this).Matrix2x2::operator*=(B); + + return( *this ); +} + +inline LinearMapR2 operator* ( const LinearMapR2& A, const Matrix2x2& B) +{ + LinearMapR2 AA(A); + AA.Matrix2x2::operator*=(B); + return AA; +} + +inline LinearMapR2 operator* ( const Matrix2x2& A, const LinearMapR2& B) +{ + LinearMapR2 AA(A); + AA.Matrix2x2::operator*=(B); + return AA; +} + +inline LinearMapR2 operator* ( const LinearMapR2& A, const LinearMapR2& B) +{ + LinearMapR2 AA(A); + AA.Matrix2x2::operator*=(B); + return AA; +} + +inline double LinearMapR2::Determinant () const // Returns the determinant +{ + return ( m11*m22 - m12*m21 ); +} + +// ****************************************************** +// * RotationMapR2 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +inline RotationMapR2::RotationMapR2() +{ + SetIdentity(); + return; +} + +inline RotationMapR2::RotationMapR2( const VectorR2& u, const VectorR2& v ) +:Matrix2x2 ( u, v ) +{ } + +inline RotationMapR2::RotationMapR2( + double a11, double a21, double a12, double a22 ) + // Values specified in column order!!! +:Matrix2x2 ( a11, a21, a12, a22 ) +{ } + +inline RotationMapR2 RotationMapR2::Transpose() const // Returns the transpose +{ + return ( RotationMapR2( m11, m12, + m21, m22 ) ); +} + +inline VectorR2 RotationMapR2::Invert(const VectorR2& u) const // Returns solution +{ + return (VectorR2( m11*u.x + m21*u.y, // Multiply with Transpose + m12*u.x + m22*u.y ) ); +} + +inline RotationMapR2& RotationMapR2::operator*= (const RotationMapR2& B) // Matrix product +{ + (*this).Matrix2x2::operator*=(B); + + return( *this ); +} + +inline RotationMapR2 operator* ( const RotationMapR2& A, const RotationMapR2& B) +{ + RotationMapR2 AA(A); + AA.Matrix2x2::operator*=(B); + return AA; +} + + +// *************************************************************** +// * 2-space vector and matrix utilities (inlined functions) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +// Returns a righthanded orthonormal basis to complement vector u +// The vector u must be unit. +inline VectorR2 GetOrtho( const VectorR2& u ) +{ + return VectorR2 ( -u.y, u.x ); +} + +// Returns the projection of u onto unit v +inline VectorR2 ProjectToUnit ( const VectorR2& u, const VectorR2& v) +{ + return (u^v)*v; +} + +// Returns the projection of u onto the plane perpindicular to the unit vector v +inline VectorR2 ProjectPerpUnit ( const VectorR2& u, const VectorR2& v) +{ + return ( u - ((u^v)*v) ); +} + +// Returns the projection of u onto the plane perpindicular to the unit vector v +// This one is more stable when u and v are nearly equal. +inline VectorR2 ProjectPerpUnitDiff ( const VectorR2& u, const VectorR2& v) +{ + VectorR2 ans = u; + ans -= v; + ans -= ((ans^v)*v); + return ans; // ans = (u-v) - ((u-v)^v)*v +} + +// Returns the solid angle between vectors u and v. +inline double Angle( const VectorR2& u, const VectorR2& v) +{ + double nSqU = u.NormSq(); + double nSqV = v.NormSq(); + if ( nSqU==0.0 && nSqV==0.0 ) { + return (0.0); + } + else { + return ( AngleUnit( u/sqrt(nSqU), v/sqrt(nSqV) ) ); + } +} + +inline double AngleUnit( const VectorR2& u, const VectorR2& v ) +{ + return ( atan2 ( (ProjectPerpUnit(v,u)).Norm(), u^v ) ); +} + +// Projection maps (LinearMapR2's) + +// VectorProjectMap returns map projecting onto a given vector u. +// u should be a unit vector (otherwise the returned map is +// scaled according to the magnitude of u. +inline LinearMapR2 VectorProjectMap( const VectorR2& u ) +{ + double xy = u.x*u.y; + return( LinearMapR2( u.x*u.x, xy, xy, u.y*u.y ) ) ; +} + +// PlaneProjectMap returns map projecting onto a given plane. +// The plane is the plane orthognal to u. +// u must be a unit vector (otherwise the returned map is +// garbage). +inline LinearMapR2 PerpProjectMap ( const VectorR2& u ) +{ + double nxy = -u.x*u.y; + return ( LinearMapR2 ( 1.0-u.x*u.x, nxy, nxy, 1.0-u.y*u.y ) ); +} + +// fromVec and toVec should be unit vectors +inline RotationMapR2 RotateToMap( const VectorR2& fromVec, const VectorR2& toVec) +{ + double costheta = fromVec.x*toVec.x + fromVec.y*toVec.y; + double sintheta = fromVec.x*toVec.y - fromVec.y*toVec.x; + return( RotationMapR2( costheta, sintheta, -sintheta, costheta ) ); +} + +#endif // LINEAR_R2_H diff --git a/examples/ThirdPartyLibs/BussIK/LinearR3.cpp b/examples/ThirdPartyLibs/BussIK/LinearR3.cpp new file mode 100644 index 000000000..c74d2b2b5 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/LinearR3.cpp @@ -0,0 +1,822 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + + + +#include "MathMisc.h" +#include "LinearR3.h" +#include "Spherical.h" + +// ****************************************************** +// * VectorR3 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +const VectorR3 UnitVecIR3(1.0, 0.0, 0.0); +const VectorR3 UnitVecJR3(0.0, 1.0, 0.0); +const VectorR3 UnitVecKR3(0.0, 0.0, 1.0); + +const VectorR3 VectorR3::Zero(0.0, 0.0, 0.0); +const VectorR3 VectorR3::UnitX( 1.0, 0.0, 0.0); +const VectorR3 VectorR3::UnitY( 0.0, 1.0, 0.0); +const VectorR3 VectorR3::UnitZ( 0.0, 0.0, 1.0); +const VectorR3 VectorR3::NegUnitX(-1.0, 0.0, 0.0); +const VectorR3 VectorR3::NegUnitY( 0.0,-1.0, 0.0); +const VectorR3 VectorR3::NegUnitZ( 0.0, 0.0,-1.0); + +const Matrix3x3 Matrix3x3::Identity(1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0); +const Matrix3x4 Matrix3x4::Identity(1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0); + +double VectorR3::MaxAbs() const +{ + register double m; + m = (x>0.0) ? x : -x; + if ( y>m ) m=y; + else if ( -y >m ) m = -y; + if ( z>m ) m=z; + else if ( -z>m ) m = -z; + return m; +} + +VectorR3& VectorR3::Set( const Quaternion& q ) +{ + double sinhalf = sqrt( Square(q.x)+Square(q.y)+Square(q.z) ); + if (sinhalf>0.0) { + double theta = atan2( sinhalf, q.w ); + theta += theta; + this->Set( q.x, q.y, q.z ); + (*this) *= (theta/sinhalf); + } + else { + this->SetZero(); + } + return *this; +} + + +// ********************************************************************* +// Rotation routines * +// ********************************************************************* + +// s.Rotate(theta, u) rotates s and returns s +// rotated theta degrees around unit vector w. +VectorR3& VectorR3::Rotate( double theta, const VectorR3& w) +{ + double c = cos(theta); + double s = sin(theta); + double dotw = (x*w.x + y*w.y + z*w.z); + double v0x = dotw*w.x; + double v0y = dotw*w.y; // v0 = provjection onto w + double v0z = dotw*w.z; + double v1x = x-v0x; + double v1y = y-v0y; // v1 = projection onto plane normal to w + double v1z = z-v0z; + double v2x = w.y*v1z - w.z*v1y; + double v2y = w.z*v1x - w.x*v1z; // v2 = w * v1 (cross product) + double v2z = w.x*v1y - w.y*v1x; + + x = v0x + c*v1x + s*v2x; + y = v0y + c*v1y + s*v2y; + z = v0z + c*v1z + s*v2z; + + return ( *this ); +} + +// Rotate unit vector x in the direction of "dir": length of dir is rotation angle. +// x must be a unit vector. dir must be perpindicular to x. +VectorR3& VectorR3::RotateUnitInDirection ( const VectorR3& dir) +{ + double theta = dir.NormSq(); + if ( theta==0.0 ) { + return *this; + } + else { + theta = sqrt(theta); + double costheta = cos(theta); + double sintheta = sin(theta); + VectorR3 dirUnit = dir/theta; + *this = costheta*(*this) + sintheta*dirUnit; + return ( *this ); + } +} + +// ****************************************************** +// * Matrix3x3 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +Matrix3x3& Matrix3x3::ReNormalize() // Re-normalizes nearly orthonormal matrix +{ + register double alpha = m11*m11+m21*m21+m31*m31; // First column's norm squared + register double beta = m12*m12+m22*m22+m32*m32; // Second column's norm squared + register double gamma = m13*m13+m23*m23+m33*m33; // Third column's norm squared + alpha = 1.0 - 0.5*(alpha-1.0); // Get mult. factor + beta = 1.0 - 0.5*(beta-1.0); + gamma = 1.0 - 0.5*(gamma-1.0); + m11 *= alpha; // Renormalize first column + m21 *= alpha; + m31 *= alpha; + m12 *= beta; // Renormalize second column + m22 *= beta; + m32 *= beta; + m13 *= gamma; + m23 *= gamma; + m33 *= gamma; + alpha = m11*m12+m21*m22+m31*m32; // First and second column dot product + beta = m11*m13+m21*m23+m31*m33; // First and third column dot product + gamma = m12*m13+m22*m23+m32*m33; // Second and third column dot product + alpha *= 0.5; + beta *= 0.5; + gamma *= 0.5; + register double temp1, temp2; + temp1 = m11-alpha*m12-beta*m13; // Update row1 + temp2 = m12-alpha*m11-gamma*m13; + m13 -= beta*m11+gamma*m12; + m11 = temp1; + m12 = temp2; + temp1 = m21-alpha*m22-beta*m23; // Update row2 + temp2 = m22-alpha*m21-gamma*m23; + m23 -= beta*m21+gamma*m22; + m21 = temp1; + m22 = temp2; + temp1 = m31-alpha*m32-beta*m33; // Update row3 + temp2 = m32-alpha*m31-gamma*m33; + m33 -= beta*m31+gamma*m32; + m31 = temp1; + m32 = temp2; + return *this; +} + +void Matrix3x3::OperatorTimesEquals(const Matrix3x3& B) // Matrix product +{ + double t1, t2; // temporary values + t1 = m11*B.m11 + m12*B.m21 + m13*B.m31; + t2 = m11*B.m12 + m12*B.m22 + m13*B.m32; + m13 = m11*B.m13 + m12*B.m23 + m13*B.m33; + m11 = t1; + m12 = t2; + + t1 = m21*B.m11 + m22*B.m21 + m23*B.m31; + t2 = m21*B.m12 + m22*B.m22 + m23*B.m32; + m23 = m21*B.m13 + m22*B.m23 + m23*B.m33; + m21 = t1; + m22 = t2; + + t1 = m31*B.m11 + m32*B.m21 + m33*B.m31; + t2 = m31*B.m12 + m32*B.m22 + m33*B.m32; + m33 = m31*B.m13 + m32*B.m23 + m33*B.m33; + m31 = t1; + m32 = t2; + return; +} + +VectorR3 Matrix3x3::Solve(const VectorR3& u) const // Returns solution +{ // based on Cramer's rule + double sd11 = m22*m33-m23*m32; + double sd21 = m32*m13-m12*m33; + double sd31 = m12*m23-m22*m13; + double sd12 = m31*m23-m21*m33; + double sd22 = m11*m33-m31*m13; + double sd32 = m21*m13-m11*m23; + double sd13 = m21*m32-m31*m22; + double sd23 = m31*m12-m11*m32; + double sd33 = m11*m22-m21*m12; + + register double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13); + + double rx = (u.x*sd11 + u.y*sd21 + u.z*sd31)*detInv; + double ry = (u.x*sd12 + u.y*sd22 + u.z*sd32)*detInv; + double rz = (u.x*sd13 + u.y*sd23 + u.z*sd33)*detInv; + + return ( VectorR3( rx, ry, rz ) ); +} + + +// ****************************************************** +// * Matrix3x4 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +Matrix3x4& Matrix3x4::ReNormalize() // Re-normalizes nearly orthonormal matrix +{ + register double alpha = m11*m11+m21*m21+m31*m31; // First column's norm squared + register double beta = m12*m12+m22*m22+m32*m32; // Second column's norm squared + register double gamma = m13*m13+m23*m23+m33*m33; // Third column's norm squared + alpha = 1.0 - 0.5*(alpha-1.0); // Get mult. factor + beta = 1.0 - 0.5*(beta-1.0); + gamma = 1.0 - 0.5*(gamma-1.0); + m11 *= alpha; // Renormalize first column + m21 *= alpha; + m31 *= alpha; + m12 *= beta; // Renormalize second column + m22 *= beta; + m32 *= beta; + m13 *= gamma; + m23 *= gamma; + m33 *= gamma; + alpha = m11*m12+m21*m22+m31*m32; // First and second column dot product + beta = m11*m13+m21*m23+m31*m33; // First and third column dot product + gamma = m12*m13+m22*m23+m32*m33; // Second and third column dot product + alpha *= 0.5; + beta *= 0.5; + gamma *= 0.5; + register double temp1, temp2; + temp1 = m11-alpha*m12-beta*m13; // Update row1 + temp2 = m12-alpha*m11-gamma*m13; + m13 -= beta*m11+gamma*m12; + m11 = temp1; + m12 = temp2; + temp1 = m21-alpha*m22-beta*m23; // Update row2 + temp2 = m22-alpha*m21-gamma*m23; + m23 -= beta*m21+gamma*m22; + m21 = temp1; + m22 = temp2; + temp1 = m31-alpha*m32-beta*m33; // Update row3 + temp2 = m32-alpha*m31-gamma*m33; + m33 -= beta*m31+gamma*m32; + m31 = temp1; + m32 = temp2; + return *this; +} + +void Matrix3x4::OperatorTimesEquals (const Matrix3x4& B) // Composition +{ + m14 += m11*B.m14 + m12*B.m24 + m13*B.m34; + m24 += m21*B.m14 + m22*B.m24 + m23*B.m34; + m34 += m31*B.m14 + m32*B.m24 + m33*B.m34; + + double t1, t2; // temporary values + t1 = m11*B.m11 + m12*B.m21 + m13*B.m31; + t2 = m11*B.m12 + m12*B.m22 + m13*B.m32; + m13 = m11*B.m13 + m12*B.m23 + m13*B.m33; + m11 = t1; + m12 = t2; + + t1 = m21*B.m11 + m22*B.m21 + m23*B.m31; + t2 = m21*B.m12 + m22*B.m22 + m23*B.m32; + m23 = m21*B.m13 + m22*B.m23 + m23*B.m33; + m21 = t1; + m22 = t2; + + t1 = m31*B.m11 + m32*B.m21 + m33*B.m31; + t2 = m31*B.m12 + m32*B.m22 + m33*B.m32; + m33 = m31*B.m13 + m32*B.m23 + m33*B.m33; + m31 = t1; + m32 = t2; +} + +void Matrix3x4::OperatorTimesEquals (const Matrix3x3& B) // Composition +{ + double t1, t2; // temporary values + t1 = m11*B.m11 + m12*B.m21 + m13*B.m31; + t2 = m11*B.m12 + m12*B.m22 + m13*B.m32; + m13 = m11*B.m13 + m12*B.m23 + m13*B.m33; + m11 = t1; + m12 = t2; + + t1 = m21*B.m11 + m22*B.m21 + m23*B.m31; + t2 = m21*B.m12 + m22*B.m22 + m23*B.m32; + m23 = m21*B.m13 + m22*B.m23 + m23*B.m33; + m21 = t1; + m22 = t2; + + t1 = m31*B.m11 + m32*B.m21 + m33*B.m31; + t2 = m31*B.m12 + m32*B.m22 + m33*B.m32; + m33 = m31*B.m13 + m32*B.m23 + m33*B.m33; + m31 = t1; + m32 = t2; +} + +// ****************************************************** +// * LinearMapR3 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + + +LinearMapR3 operator* ( const LinearMapR3& A, const LinearMapR3& B) +{ + return( LinearMapR3( A.m11*B.m11 + A.m12*B.m21 + A.m13*B.m31, + A.m21*B.m11 + A.m22*B.m21 + A.m23*B.m31, + A.m31*B.m11 + A.m32*B.m21 + A.m33*B.m31, + A.m11*B.m12 + A.m12*B.m22 + A.m13*B.m32, + A.m21*B.m12 + A.m22*B.m22 + A.m23*B.m32, + A.m31*B.m12 + A.m32*B.m22 + A.m33*B.m32, + A.m11*B.m13 + A.m12*B.m23 + A.m13*B.m33, + A.m21*B.m13 + A.m22*B.m23 + A.m23*B.m33, + A.m31*B.m13 + A.m32*B.m23 + A.m33*B.m33 ) ); +} + +double LinearMapR3::Determinant () const // Returns the determinant +{ + return ( m11*(m22*m33-m23*m32) + - m12*(m21*m33-m31*m23) + + m13*(m21*m23-m31*m22) ); +} + +LinearMapR3 LinearMapR3::Inverse() const // Returns inverse +{ + double sd11 = m22*m33-m23*m32; + double sd21 = m32*m13-m12*m33; + double sd31 = m12*m23-m22*m13; + double sd12 = m31*m23-m21*m33; + double sd22 = m11*m33-m31*m13; + double sd32 = m21*m13-m11*m23; + double sd13 = m21*m32-m31*m22; + double sd23 = m31*m12-m11*m32; + double sd33 = m11*m22-m21*m12; + + register double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13); + + return( LinearMapR3( sd11*detInv, sd12*detInv, sd13*detInv, + sd21*detInv, sd22*detInv, sd23*detInv, + sd31*detInv, sd32*detInv, sd33*detInv ) ); +} + +LinearMapR3& LinearMapR3::Invert() // Converts into inverse. +{ + double sd11 = m22*m33-m23*m32; + double sd21 = m32*m13-m12*m33; + double sd31 = m12*m23-m22*m13; + double sd12 = m31*m23-m21*m33; + double sd22 = m11*m33-m31*m13; + double sd32 = m21*m13-m11*m23; + double sd13 = m21*m32-m31*m22; + double sd23 = m31*m12-m11*m32; + double sd33 = m11*m22-m21*m12; + + register double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13); + + m11 = sd11*detInv; + m12 = sd21*detInv; + m13 = sd31*detInv; + m21 = sd12*detInv; + m22 = sd22*detInv; + m23 = sd32*detInv; + m31 = sd13*detInv; + m32 = sd23*detInv; + m33 = sd33*detInv; + + return ( *this ); +} + + +// ****************************************************** +// * AffineMapR3 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +AffineMapR3 operator* ( const AffineMapR3& A, const AffineMapR3& B ) +{ + return( AffineMapR3( A.m11*B.m11 + A.m12*B.m21 + A.m13*B.m31, + A.m21*B.m11 + A.m22*B.m21 + A.m23*B.m31, + A.m31*B.m11 + A.m32*B.m21 + A.m33*B.m31, + A.m11*B.m12 + A.m12*B.m22 + A.m13*B.m32, + A.m21*B.m12 + A.m22*B.m22 + A.m23*B.m32, + A.m31*B.m12 + A.m32*B.m22 + A.m33*B.m32, + A.m11*B.m13 + A.m12*B.m23 + A.m13*B.m33, + A.m21*B.m13 + A.m22*B.m23 + A.m23*B.m33, + A.m31*B.m13 + A.m32*B.m23 + A.m33*B.m33, + A.m11*B.m14 + A.m12*B.m24 + A.m13*B.m34 + A.m14, + A.m21*B.m14 + A.m22*B.m24 + A.m23*B.m34 + A.m24, + A.m31*B.m14 + A.m32*B.m24 + A.m33*B.m34 + A.m34)); +} + +AffineMapR3 operator* ( const LinearMapR3& A, const AffineMapR3& B ) +{ + return( AffineMapR3( A.m11*B.m11 + A.m12*B.m21 + A.m13*B.m31, + A.m21*B.m11 + A.m22*B.m21 + A.m23*B.m31, + A.m31*B.m11 + A.m32*B.m21 + A.m33*B.m31, + A.m11*B.m12 + A.m12*B.m22 + A.m13*B.m32, + A.m21*B.m12 + A.m22*B.m22 + A.m23*B.m32, + A.m31*B.m12 + A.m32*B.m22 + A.m33*B.m32, + A.m11*B.m13 + A.m12*B.m23 + A.m13*B.m33, + A.m21*B.m13 + A.m22*B.m23 + A.m23*B.m33, + A.m31*B.m13 + A.m32*B.m23 + A.m33*B.m33, + A.m11*B.m14 + A.m12*B.m24 + A.m13*B.m34, + A.m21*B.m14 + A.m22*B.m24 + A.m23*B.m34, + A.m31*B.m14 + A.m32*B.m24 + A.m33*B.m34 )); + +} + +AffineMapR3 operator* ( const AffineMapR3& A, const LinearMapR3& B ) +{ + return( AffineMapR3( A.m11*B.m11 + A.m12*B.m21 + A.m13*B.m31, + A.m21*B.m11 + A.m22*B.m21 + A.m23*B.m31, + A.m31*B.m11 + A.m32*B.m21 + A.m33*B.m31, + A.m11*B.m12 + A.m12*B.m22 + A.m13*B.m32, + A.m21*B.m12 + A.m22*B.m22 + A.m23*B.m32, + A.m31*B.m12 + A.m32*B.m22 + A.m33*B.m32, + A.m11*B.m13 + A.m12*B.m23 + A.m13*B.m33, + A.m21*B.m13 + A.m22*B.m23 + A.m23*B.m33, + A.m31*B.m13 + A.m32*B.m23 + A.m33*B.m33, + A.m14, + A.m24, + A.m34 ) ); +} + + +AffineMapR3 AffineMapR3::Inverse() const // Returns inverse +{ + double sd11 = m22*m33-m23*m32; + double sd21 = m32*m13-m12*m33; + double sd31 = m12*m23-m22*m13; + double sd12 = m31*m23-m21*m33; + double sd22 = m11*m33-m31*m13; + double sd32 = m21*m13-m11*m23; + double sd13 = m21*m32-m31*m22; + double sd23 = m31*m12-m11*m32; + double sd33 = m11*m22-m21*m12; + + register double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13); + + // Make sd's hold the (transpose of) the inverse of the 3x3 part + sd11 *= detInv; + sd12 *= detInv; + sd13 *= detInv; + sd21 *= detInv; + sd22 *= detInv; + sd23 *= detInv; + sd31 *= detInv; + sd32 *= detInv; + sd33 *= detInv; + double sd41 = -(m14*sd11 + m24*sd21 + m34*sd31); + double sd42 = -(m14*sd12 + m24*sd22 + m34*sd32); + double sd43 = -(m14*sd12 + m24*sd23 + m34*sd33); + + return( AffineMapR3( sd11, sd12, sd13, + sd21, sd22, sd23, + sd31, sd32, sd33, + sd41, sd42, sd43 ) ); +} + +AffineMapR3& AffineMapR3::Invert() // Converts into inverse. +{ + double sd11 = m22*m33-m23*m32; + double sd21 = m32*m13-m12*m33; + double sd31 = m12*m23-m22*m13; + double sd12 = m31*m23-m21*m33; + double sd22 = m11*m33-m31*m13; + double sd32 = m21*m13-m11*m23; + double sd13 = m21*m32-m31*m22; + double sd23 = m31*m12-m11*m32; + double sd33 = m11*m22-m21*m12; + + register double detInv = 1.0/(m11*sd11 + m12*sd12 + m13*sd13); + + m11 = sd11*detInv; + m12 = sd21*detInv; + m13 = sd31*detInv; + m21 = sd12*detInv; + m22 = sd22*detInv; + m23 = sd32*detInv; + m31 = sd13*detInv; + m32 = sd23*detInv; + m33 = sd33*detInv; + double sd41 = -(m14*m11 + m24*m12 + m34*m13); // Compare to ::Inverse. + double sd42 = -(m14*m21 + m24*m22 + m34*m23); + double sd43 = -(m14*m31 + m24*m32 + m34*m33); + m14 = sd41; + m24 = sd42; + m34 = sd43; + + return ( *this ); +} + +// ************************************************************** +// * RotationMapR3 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +RotationMapR3 operator*(const RotationMapR3& A, const RotationMapR3& B) + // Matrix product (composition) +{ + return(RotationMapR3(A.m11*B.m11 + A.m12*B.m21 + A.m13*B.m31, + A.m21*B.m11 + A.m22*B.m21 + A.m23*B.m31, + A.m31*B.m11 + A.m32*B.m21 + A.m33*B.m31, + A.m11*B.m12 + A.m12*B.m22 + A.m13*B.m32, + A.m21*B.m12 + A.m22*B.m22 + A.m23*B.m32, + A.m31*B.m12 + A.m32*B.m22 + A.m33*B.m32, + A.m11*B.m13 + A.m12*B.m23 + A.m13*B.m33, + A.m21*B.m13 + A.m22*B.m23 + A.m23*B.m33, + A.m31*B.m13 + A.m32*B.m23 + A.m33*B.m33 ) ); +} + +RotationMapR3& RotationMapR3::Set( const Quaternion& quat ) +{ + double wSq = quat.w*quat.w; + double xSq = quat.x*quat.x; + double ySq = quat.y*quat.y; + double zSq = quat.z*quat.z; + double Dqwx = 2.0*quat.w*quat.x; + double Dqwy = 2.0*quat.w*quat.y; + double Dqwz = 2.0*quat.w*quat.z; + double Dqxy = 2.0*quat.x*quat.y; + double Dqyz = 2.0*quat.y*quat.z; + double Dqxz = 2.0*quat.x*quat.z; + m11 = wSq+xSq-ySq-zSq; + m22 = wSq-xSq+ySq-zSq; + m33 = wSq-xSq-ySq+zSq; + m12 = Dqxy-Dqwz; + m21 = Dqxy+Dqwz; + m13 = Dqxz+Dqwy; + m31 = Dqxz-Dqwy; + m23 = Dqyz-Dqwx; + m32 = Dqyz+Dqwx; + return *this; +} + +RotationMapR3& RotationMapR3::Set( const VectorR3& u, double theta ) +{ + assert ( fabs(u.NormSq()-1.0)<2.0e-6 ); + register double c = cos(theta); + register double s = sin(theta); + register double mc = 1.0-c; + double xmc = u.x*mc; + double xymc = xmc*u.y; + double xzmc = xmc*u.z; + double yzmc = u.y*u.z*mc; + double xs = u.x*s; + double ys = u.y*s; + double zs = u.z*s; + Matrix3x3::Set( u.x*u.x*mc+c, xymc+zs, xzmc-ys, + xymc-zs, u.y*u.y*mc+c, yzmc+xs, + xzmc+ys, yzmc-xs, u.z*u.z*mc+c ); + return *this; +} + +// The rotation axis vector u MUST be a UNIT vector!!! +RotationMapR3& RotationMapR3::Set( const VectorR3& u, double s, double c ) +{ + assert ( fabs(u.NormSq()-1.0)<2.0e-6 ); + double mc = 1.0-c; + double xmc = u.x*mc; + double xymc = xmc*u.y; + double xzmc = xmc*u.z; + double yzmc = u.y*u.z*mc; + double xs = u.x*s; + double ys = u.y*s; + double zs = u.z*s; + Matrix3x3::Set( u.x*u.x*mc+c, xymc+zs, xzmc-ys, + xymc-zs, u.y*u.y*mc+c, yzmc+xs, + xzmc+ys, yzmc-xs, u.z*u.z*mc+c ); + return *this; +} + + +// ToAxisAndAngle - find a unit vector in the direction of the rotation axis, +// and the angle theta of rotation. Returns true if the rotation angle is non-zero, +// and false if it is zero. +bool RotationMapR3::ToAxisAndAngle( VectorR3* u, double *theta ) const +{ + double alpha = m11+m22+m33-1.0; + double beta = sqrt(Square(m32-m23)+Square(m13-m31)+Square(m21-m12)); + if ( beta==0.0 ) { + *u = VectorR3::UnitY; + *theta = 0.0; + return false; + } + else { + u->Set(m32-m23, m13-m31, m21-m12); + *u /= beta; + *theta = atan2( beta, alpha ); + return true; + } +} + +// VrRotate is similar to glRotate. Returns a matrix (LinearMapR3) +// that will perform the rotation when multiplied on the left. +// u is supposed to be a *unit* vector. Otherwise, the LinearMapR3 +// returned will be garbage! +RotationMapR3 VrRotate( double theta, const VectorR3& u ) +{ + RotationMapR3 ret; + ret.Set( u, theta ); + return ret; +} + +// This version of rotate takes the cosine and sine of theta +// instead of theta. u must still be a unit vector. + +RotationMapR3 VrRotate( double c, double s, const VectorR3& u ) +{ + RotationMapR3 ret; + ret.Set( u, s, c ); + return ret; +} + +// Returns a RotationMapR3 which rotates the fromVec to be colinear +// with toVec. + +RotationMapR3 VrRotateAlign( const VectorR3& fromVec, const VectorR3& toVec) +{ + VectorR3 crossVec = fromVec; + crossVec *= toVec; + double sinetheta = crossVec.Norm(); // Not yet normalized! + if ( sinetheta < 1.0e-40 ) { + return ( RotationMapR3( + 1.0, 0.0, 0.0, + 0.0, 1.0, 0.0, + 0.0, 0.0, 1.0) ); + } + crossVec /= sinetheta; // Normalize the vector + double scale = 1.0/sqrt(fromVec.NormSq()*toVec.NormSq()); + sinetheta *= scale; + double cosinetheta = (fromVec^toVec)*scale; + return ( VrRotate( cosinetheta, sinetheta, crossVec) ); +} + +// RotateToMap returns a rotation map which rotates fromVec to have the +// same direction as toVec. +// fromVec and toVec should be unit vectors +RotationMapR3 RotateToMap( const VectorR3& fromVec, const VectorR3& toVec) +{ + VectorR3 crossVec = fromVec; + crossVec *= toVec; + double sintheta = crossVec.Norm(); + double costheta = fromVec^toVec; + if ( sintheta <= 1.0e-40 ) { + if ( costheta>0.0 ) { + return ( RotationMapR3( + 1.0, 0.0, 0.0, + 0.0, 1.0, 0.0, + 0.0, 0.0, 1.0) ); + } + else { + GetOrtho ( toVec, crossVec ); // Get arbitrary orthonormal vector + return( VrRotate(costheta, sintheta, crossVec ) ); + } + } + else { + crossVec /= sintheta; // Normalize the vector + return ( VrRotate( costheta, sintheta, crossVec) ); + } +} + +// ************************************************************** +// * RigidMapR3 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +// The rotation axis vector u MUST be a UNIT vector!!! +RigidMapR3& RigidMapR3::SetRotationPart( const VectorR3& u, double theta ) +{ + assert ( fabs(u.NormSq()-1.0)<2.0e-6 ); + register double c = cos(theta); + register double s = sin(theta); + register double mc = 1.0-c; + double xmc = u.x*mc; + double xymc = xmc*u.y; + double xzmc = xmc*u.z; + double yzmc = u.y*u.z*mc; + double xs = u.x*s; + double ys = u.y*s; + double zs = u.z*s; + Matrix3x4::Set3x3( u.x*u.x*mc+c, xymc+zs, xzmc-ys, + xymc-zs, u.y*u.y*mc+c, yzmc+xs, + xzmc+ys, yzmc-xs, u.z*u.z*mc+c ); + return *this; +} + +// The rotation axis vector u MUST be a UNIT vector!!! +RigidMapR3& RigidMapR3::SetRotationPart( const VectorR3& u, double s, double c ) +{ + assert ( fabs(u.NormSq()-1.0)<2.0e-6 ); + double mc = 1.0-c; + double xmc = u.x*mc; + double xymc = xmc*u.y; + double xzmc = xmc*u.z; + double yzmc = u.y*u.z*mc; + double xs = u.x*s; + double ys = u.y*s; + double zs = u.z*s; + Matrix3x4::Set3x3( u.x*u.x*mc+c, xymc+zs, xzmc-ys, + xymc-zs, u.y*u.y*mc+c, yzmc+xs, + xzmc+ys, yzmc-xs, u.z*u.z*mc+c ); + return *this; +} + + +// CalcGlideRotation - converts a rigid map into an equivalent +// glide rotation (screw motion). It returns the rotation axis +// as base point u, and a rotation axis v. The vectors u and v are +// always orthonormal. v will be a unit vector. +// It also returns the glide distance, which is the translation parallel +// to v. Further, it returns the signed rotation angle theta (right hand rule +// specifies the direction. +// The glide rotation means a rotation around the point u with axis direction v. +// Return code "true" if the rotation amount is non-zero. "false" if pure translation. +bool RigidMapR3::CalcGlideRotation( VectorR3* u, VectorR3* v, + double *glideDist, double *rotation ) const +{ + // Compare to the code for ToAxisAndAngle. + double alpha = m11+m22+m33-1.0; + double beta = sqrt(Square(m32-m23)+Square(m13-m31)+Square(m21-m12)); + if ( beta==0.0 ) { + double vN = m14*m14 + m24*m24 + m34*m34; + if ( vN>0.0 ) { + vN = sqrt(vN); + v->Set( m14, m24, m34 ); + *v /= vN; + *glideDist = vN; + } + else { + *v = VectorR3::UnitX; + *glideDist = 0.0; + } + u->SetZero(); + *rotation = 0; + return false; + } + else { + v->Set(m32-m23, m13-m31, m21-m12); + *v /= beta; // v - unit vector, rotation axis + *rotation = atan2( beta, alpha ); + u->Set( m14, m24, m34 ); + *glideDist = ((*u)^(*v)); + VectorR3 temp = *v; + temp *= *glideDist; + *u -= temp; // Subtract component in direction of rot. axis v + temp = *v; + temp *= *u; + temp /= tan((*rotation)/2); // temp = (v \times u) / tan(rotation/2) + *u += temp; + *u *= 0.5; + return true; + } + +} + +// *************************************************************** +// Linear Algebra Utilities * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +// Returns a righthanded orthonormal basis to complement vector u +void GetOrtho( const VectorR3& u, VectorR3& v, VectorR3& w) +{ + if ( u.x > 0.5 || u.x<-0.5 || u.y > 0.5 || u.y<-0.5 ) { + v.Set ( u.y, -u.x, 0.0 ); + } + else { + v.Set ( 0.0, u.z, -u.y); + } + v.Normalize(); + w = u; + w *= v; + w.Normalize(); + // w.NormalizeFast(); + return; +} + +// Returns a vector v orthonormal to unit vector u +void GetOrtho( const VectorR3& u, VectorR3& v ) +{ + if ( u.x > 0.5 || u.x<-0.5 || u.y > 0.5 || u.y<-0.5 ) { + v.Set ( u.y, -u.x, 0.0 ); + } + else { + v.Set ( 0.0, u.z, -u.y); + } + v.Normalize(); + return; +} + +// *************************************************************** +// Stream Output Routines * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +ostream& operator<< ( ostream& os, const VectorR3& u ) +{ + return (os << "<" << u.x << "," << u.y << "," << u.z << ">"); +} + +ostream& operator<< ( ostream& os, const Matrix3x3& A ) +{ + os << " <" << A.m11 << ", " << A.m12 << ", " << A.m13 << ">\n" + << " <" << A.m21 << ", " << A.m22 << ", " << A.m23 << ">\n" + << " <" << A.m31 << ", " << A.m32 << ", " << A.m33 << ">\n" ; + return (os); +} + +ostream& operator<< ( ostream& os, const Matrix3x4& A ) +{ + os << " <" << A.m11 << ", " << A.m12 << ", " << A.m13 + << "; " << A.m14 << ">\n" + << " <" << A.m21 << ", " << A.m22 << ", " << A.m23 + << "; " << A.m24 << ">\n" + << " <" << A.m31 << ", " << A.m32 << ", " << A.m33 + << "; " << A.m34 << ">\n" ; + return (os); +} + diff --git a/examples/ThirdPartyLibs/BussIK/LinearR3.h b/examples/ThirdPartyLibs/BussIK/LinearR3.h new file mode 100644 index 000000000..4b79d4eed --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/LinearR3.h @@ -0,0 +1,2027 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + +// +// Linear Algebra Classes over R3 +// +// +// A. Vector and Position classes +// +// A.1. VectorR3: a real column vector of length 3. +// +// A.2. VectorHgR3: a column vector of length 4 which is +// the homogenous representation of a vector in 3-space +// +// B. Matrix Classes +// +// B.1 LinearMapR3 - arbitrary linear map; 3x3 real matrix +// +// B.2 AffineMapR3 - arbitrary affine map; a 3x4 real matrix +// +// B.3 RotationMapR3 - orthonormal 3x3 matrix +// +// B.4 RigidMapR3 - RotationMapR3 plus displacement +// + +#ifndef LINEAR_R3_H +#define LINEAR_R3_H + +#include +#include +#include +#include "MathMisc.h" +using namespace std; + +class VectorR3; // Space Vector (length 3) +class VectorHgR3; // Homogenous Space Vector +class VectorR4; // Space Vector (length 4) + +class LinearMapR3; // Linear Map (3x3 Matrix) +class AffineMapR3; // Affine Map (3x4 Matrix) +class RotationMapR3; // Rotation (3x3 orthonormal matrix) +class RigidMapR3; // 3x4 matrix, first 3 columns orthonormal + +// Most for internal use: +class Matrix3x3; +class Matrix3x4; + +class Quaternion; + +// ************************************** +// VectorR3 class * +// * * * * * * * * * * * * * * * * * * ** + +class VectorR3 { + +public: + double x, y, z; // The x & y & z coordinates. + + static const VectorR3 Zero; + static const VectorR3 UnitX; + static const VectorR3 UnitY; + static const VectorR3 UnitZ; + static const VectorR3 NegUnitX; + static const VectorR3 NegUnitY; + static const VectorR3 NegUnitZ; + +public: + VectorR3( ) : x(0.0), y(0.0), z(0.0) {} + VectorR3( double xVal, double yVal, double zVal ) + : x(xVal), y(yVal), z(zVal) {} + VectorR3( const VectorHgR3& uH ); + + VectorR3& Set( const Quaternion& ); // Convert quat to rotation vector + VectorR3& Set( double xx, double yy, double zz ) + { x=xx; y=yy; z=zz; return *this; } + VectorR3& SetFromHg( const VectorR4& ); // Convert homogeneous VectorR4 to VectorR3 + VectorR3& SetZero() { x=0.0; y=0.0; z=0.0; return *this;} + VectorR3& Load( const double* v ); + VectorR3& Load( const float* v ); + void Dump( double* v ) const; + void Dump( float* v ) const; + + inline double operator[]( int i ); + + VectorR3& operator= ( const VectorR3& v ) + { x=v.x; y=v.y; z=v.z; return(*this);} + VectorR3& operator+= ( const VectorR3& v ) + { x+=v.x; y+=v.y; z+=v.z; return(*this); } + VectorR3& operator-= ( const VectorR3& v ) + { x-=v.x; y-=v.y; z-=v.z; return(*this); } + VectorR3& operator*= ( double m ) + { x*=m; y*=m; z*=m; return(*this); } + VectorR3& operator/= ( double m ) + { register double mInv = 1.0/m; + x*=mInv; y*=mInv; z*=mInv; + return(*this); } + VectorR3 operator- () const { return ( VectorR3(-x, -y, -z) ); } + VectorR3& operator*= (const VectorR3& v); // Cross Product + VectorR3& ArrayProd(const VectorR3&); // Component-wise product + + VectorR3& AddScaled( const VectorR3& u, double s ); + + bool IsZero() const { return ( x==0.0 && y==0.0 && z==0.0 ); } + double Norm() const { return ( (double)sqrt( x*x + y*y + z*z ) ); } + double NormSq() const { return ( x*x + y*y + z*z ); } + double MaxAbs() const; + double Dist( const VectorR3& u ) const; // Distance from u + double DistSq( const VectorR3& u ) const; // Distance from u squared + VectorR3& Negate() { x = -x; y = -y; z = -z; return *this;} + VectorR3& Normalize () { *this /= Norm(); return *this;} // No error checking + inline VectorR3& MakeUnit(); // Normalize() with error checking + inline VectorR3& ReNormalize(); + bool IsUnit( ) const + { register double norm = Norm(); + return ( 1.000001>=norm && norm>=0.999999 ); } + bool IsUnit( double tolerance ) const + { register double norm = Norm(); + return ( 1.0+tolerance>=norm && norm>=1.0-tolerance ); } + bool NearZero(double tolerance) const { return( MaxAbs()<=tolerance );} + // tolerance should be non-negative + + double YaxisDistSq() const { return (x*x+z*z); } + double YaxisDist() const { return sqrt(x*x+z*z); } + + VectorR3& Rotate( double theta, const VectorR3& u); // rotate around u. + VectorR3& RotateUnitInDirection ( const VectorR3& dir); // rotate in direction dir + VectorR3& Rotate( const Quaternion& ); // Rotate according to quaternion + + friend ostream& operator<< ( ostream& os, const VectorR3& u ); + +}; + +inline VectorR3 operator+( const VectorR3& u, const VectorR3& v ); +inline VectorR3 operator-( const VectorR3& u, const VectorR3& v ); +inline VectorR3 operator*( const VectorR3& u, double m); +inline VectorR3 operator*( double m, const VectorR3& u); +inline VectorR3 operator/( const VectorR3& u, double m); +inline int operator==( const VectorR3& u, const VectorR3& v ); + +inline double operator^ (const VectorR3& u, const VectorR3& v ); // Dot Product +inline VectorR3 operator* (const VectorR3& u, const VectorR3& v); // Cross Product +inline VectorR3 ArrayProd ( const VectorR3& u, const VectorR3& v ); + +inline double Mag(const VectorR3& u) { return u.Norm(); } +inline double Dist(const VectorR3& u, const VectorR3& v) { return u.Dist(v); } +inline double DistSq(const VectorR3& u, const VectorR3& v) { return u.DistSq(v); } +inline double NormalizeError (const VectorR3& u); + +extern const VectorR3 UnitVecIR3; +extern const VectorR3 UnitVecJR3; +extern const VectorR3 UnitVecKR3; + +inline VectorR3 ToVectorR3( const Quaternion& q ) + {return VectorR3().Set(q);} + + +// **************************************** +// VectorHgR3 class * +// * * * * * * * * * * * * * * * * * * * ** + +class VectorHgR3 { + +public: + double x, y, z, w; // The x & y & z & w coordinates. + +public: + VectorHgR3( ) : x(0.0), y(0.0), z(0.0), w(1.0) {} + VectorHgR3( double xVal, double yVal, double zVal ) + : x(xVal), y(yVal), z(zVal), w(1.0) {} + VectorHgR3( double xVal, double yVal, double zVal, double wVal ) + : x(xVal), y(yVal), z(zVal), w(wVal) {} + VectorHgR3 ( const VectorR3& u ) : x(u.x), y(u.y), z(u.z), w(1.0) {} +}; + +// +// Advanced vector and position functions (prototypes) +// + +VectorR3 Interpolate( const VectorR3& start, const VectorR3& end, double a); + +// ***************************************** +// Matrix3x3 class * +// * * * * * * * * * * * * * * * * * * * * * + +class Matrix3x3 { +public: + + double m11, m12, m13, m21, m22, m23, m31, m32, m33; + + // Implements a 3x3 matrix: m_i_j - row-i and column-j entry + + static const Matrix3x3 Identity; + +public: + inline Matrix3x3(); + inline Matrix3x3(const VectorR3&, const VectorR3&, const VectorR3&); // Sets by columns! + inline Matrix3x3(double, double, double, double, double, double, + double, double, double ); // Sets by columns + + inline void SetIdentity (); // Set to the identity map + inline void Set ( const Matrix3x3& ); // Set to the matrix. + inline void Set3x3 ( const Matrix3x4& ); // Set to the 3x3 part of the matrix. + inline void Set( const VectorR3&, const VectorR3&, const VectorR3& ); + inline void Set( double, double, double, + double, double, double, + double, double, double ); + inline void SetByRows( double, double, double, double, double, double, + double, double, double ); + inline void SetByRows( const VectorR3&, const VectorR3&, const VectorR3& ); + + inline void SetColumn1 ( double, double, double ); + inline void SetColumn2 ( double, double, double ); + inline void SetColumn3 ( double, double, double ); + inline void SetColumn1 ( const VectorR3& ); + inline void SetColumn2 ( const VectorR3& ); + inline void SetColumn3 ( const VectorR3& ); + inline VectorR3 Column1() const; + inline VectorR3 Column2() const; + inline VectorR3 Column3() const; + + inline void SetRow1 ( double, double, double ); + inline void SetRow2 ( double, double, double ); + inline void SetRow3 ( double, double, double ); + inline void SetRow1 ( const VectorR3& ); + inline void SetRow2 ( const VectorR3& ); + inline void SetRow3 ( const VectorR3& ); + inline VectorR3 Row1() const; + inline VectorR3 Row2() const; + inline VectorR3 Row3() const; + + inline void SetDiagonal( double, double, double ); + inline void SetDiagonal( const VectorR3& ); + inline double Diagonal( int ); + + inline void MakeTranspose(); // Transposes it. + Matrix3x3& ReNormalize(); + VectorR3 Solve(const VectorR3&) const; // Returns solution + + inline void Transform( VectorR3* ) const; + inline void Transform( const VectorR3& src, VectorR3* dest) const; + +protected: + void OperatorTimesEquals( const Matrix3x3& ); // Internal use only + void SetZero (); // Set to the zero map + +}; + +inline VectorR3 operator* ( const Matrix3x3&, const VectorR3& ); + +ostream& operator<< ( ostream& os, const Matrix3x3& A ); + + +// ***************************************** +// Matrix3x4 class * +// * * * * * * * * * * * * * * * * * * * * * + +class Matrix3x4 +{ +public: + double m11, m12, m13, m21, m22, m23, m31, m32, m33; + double m14; + double m24; + double m34; + + static const Matrix3x4 Identity; + +public: + // Constructors set by columns! + Matrix3x4() {} + Matrix3x4(const VectorR3&, const VectorR3&, const VectorR3&, const VectorR3& ); + Matrix3x4(double, double, double, double, double, double, + double, double, double, double, double, double ); // Sets by columns + Matrix3x4( const Matrix3x3&, const VectorR3& ); + + void SetIdentity (); // Set to the identity map + void Set ( const Matrix3x4& ); // Set to the matrix. + void Set3x3 ( const Matrix3x3& ); // Set linear part to the matrix. + void Set ( const Matrix3x3&, const VectorR3& ); // Set to the matrix plus 4th column + void Set( const VectorR3&, const VectorR3&, const VectorR3&, const VectorR3& ); + void Set( double, double, double, + double, double, double, + double, double, double, + double, double, double ); // Sets by columns + void Set3x3( double, double, double, + double, double, double, + double, double, double ); // Sets by columns + void SetByRows( double, double, double, double, double, double, + double, double, double, double, double, double ); + + void SetColumn1 ( double, double, double ); + void SetColumn2 ( double, double, double ); + void SetColumn3 ( double, double, double ); + void SetColumn4 ( double, double, double ); + void SetColumn1 ( const VectorR3& ); + void SetColumn2 ( const VectorR3& ); + void SetColumn3 ( const VectorR3& ); + void SetColumn4 ( const VectorR3& ); + VectorR3 Column1() const; + VectorR3 Column2() const; + VectorR3 Column3() const; + VectorR3 Column4() const; + void SetRow1 ( double x, double y, double z, double w ); + void SetRow2 ( double x, double y, double z, double w ); + void SetRow3 ( double x, double y, double z, double w ); + void SetRow4 ( double x, double y, double z, double w ); + + Matrix3x4& ApplyTranslationLeft( const VectorR3& u ); + Matrix3x4& ApplyTranslationRight( const VectorR3& u ); + Matrix3x4& ApplyYRotationLeft( double theta ); + Matrix3x4& ApplyYRotationLeft( double costheta, double sintheta ); + + Matrix3x4& ReNormalize(); + VectorR3 Solve(const VectorR3&) const; // Returns solution + + inline void Transform( VectorR3* ) const; + inline void Transform3x3( VectorR3* ) const; + inline void Transform( const VectorR3& src, VectorR3* dest ) const; + inline void Transform3x3( const VectorR3& src, VectorR3* dest ) const; + inline void Transform3x3Transpose( VectorR3* dest ) const; + inline void Transform3x3Transpose( const VectorR3& src, VectorR3* dest ) const; + +protected: + void SetZero (); // Set to the zero map + void OperatorTimesEquals( const Matrix3x3& ); // Internal use only + void OperatorTimesEquals( const Matrix3x4& ); // Internal use only +}; + +inline VectorR3 operator* ( const Matrix3x4&, const VectorR3& ); + +ostream& operator<< ( ostream& os, const Matrix3x4& A ); + +// ***************************************** +// LinearMapR3 class * +// * * * * * * * * * * * * * * * * * * * * * + +class LinearMapR3 : public Matrix3x3 { + +public: + + LinearMapR3(); + LinearMapR3( const VectorR3&, const VectorR3&, const VectorR3& ); + LinearMapR3( double, double, double, double, double, double, + double, double, double ); // Sets by columns + LinearMapR3 ( const Matrix3x3& ); + + void SetZero (); // Set to the zero map + inline void Negate(); + + inline LinearMapR3& operator+= (const Matrix3x3& ); + inline LinearMapR3& operator-= (const Matrix3x3& ); + inline LinearMapR3& operator*= (double); + inline LinearMapR3& operator/= (double); + LinearMapR3& operator*= (const Matrix3x3& ); // Matrix product + + inline LinearMapR3 Transpose() const; // Returns the transpose + double Determinant () const; // Returns the determinant + LinearMapR3 Inverse() const; // Returns inverse + LinearMapR3& Invert(); // Converts into inverse. + VectorR3 Solve(const VectorR3&) const; // Returns solution + LinearMapR3 PseudoInverse() const; // Returns pseudo-inverse TO DO + VectorR3 PseudoSolve(const VectorR3&); // Finds least squares solution TO DO + +}; + +inline LinearMapR3 operator+ (const LinearMapR3&, const Matrix3x3&); +inline LinearMapR3 operator+ (const Matrix3x3&, const LinearMapR3&); +inline LinearMapR3 operator- (const LinearMapR3&); +inline LinearMapR3 operator- (const LinearMapR3&, const Matrix3x3&); +inline LinearMapR3 operator- (const Matrix3x3&, const LinearMapR3&); +inline LinearMapR3 operator* ( const LinearMapR3&, double); +inline LinearMapR3 operator* ( double, const LinearMapR3& ); +inline LinearMapR3 operator/ ( const LinearMapR3&, double ); +LinearMapR3 operator* ( const LinearMapR3&, const LinearMapR3& ); + // Matrix product (composition) + + +// ***************************************************** +// * AffineMapR3 class * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * + +class AffineMapR3 : public Matrix3x4 { + +public: + AffineMapR3(); + AffineMapR3( double, double, double, double, double, double, + double, double, double, double, double, double ); // Sets by columns + AffineMapR3 ( const VectorR3&, const VectorR3&, const VectorR3&, const VectorR3&); + AffineMapR3 ( const LinearMapR3&, const VectorR3& ); + + void SetIdentity (); // Set to the identity map + void SetZero (); // Set to the zero map + + AffineMapR3& operator+= (const Matrix3x4& ); + AffineMapR3& operator-= (const Matrix3x4& ); + AffineMapR3& operator*= (double); + AffineMapR3& operator/= (double); + AffineMapR3& operator*= (const Matrix3x3& ); // Composition + AffineMapR3& operator*= (const Matrix3x4& ); // Composition + + AffineMapR3& ApplyTranslationLeft( const VectorR3& u ) + { Matrix3x4::ApplyTranslationLeft( u ); return *this; } + AffineMapR3& ApplyTranslationRight( const VectorR3& u ) + { Matrix3x4::ApplyTranslationRight( u ); return *this; } + AffineMapR3& ApplyYRotationLeft( double theta ) + { Matrix3x4::ApplyYRotationLeft( theta ); return *this; } + AffineMapR3& ApplyYRotationLeft( double costheta, double sintheta ) + { Matrix3x4::ApplyYRotationLeft( costheta, sintheta ); return *this; } + + AffineMapR3 Inverse() const; // Returns inverse + AffineMapR3& Invert(); // Converts into inverse. + VectorR3 Solve(const VectorR3&) const; // Returns solution + AffineMapR3 PseudoInverse() const; // Returns pseudo-inverse // TO DO + VectorR3 PseudoSolve(const VectorR3&); // Least squares solution // TO DO +}; + +inline AffineMapR3 operator+ (const AffineMapR3&, const Matrix3x4&); +inline AffineMapR3 operator+ (const Matrix3x4&, const AffineMapR3&); +inline AffineMapR3 operator+ (const AffineMapR3&, const Matrix3x3&); +inline AffineMapR3 operator+ (const Matrix3x3&, const AffineMapR3&); +inline AffineMapR3 operator- (const AffineMapR3&, const Matrix3x4&); +inline AffineMapR3 operator- (const Matrix3x4&, const AffineMapR3&); +inline AffineMapR3 operator- (const AffineMapR3&, const Matrix3x3&); +inline AffineMapR3 operator- (const Matrix3x3&, const AffineMapR3&); +inline AffineMapR3 operator* (const AffineMapR3&, double); +inline AffineMapR3 operator* (double, const AffineMapR3& ); +inline AffineMapR3 operator/ (const AffineMapR3&, double ); + +// Composition operators +AffineMapR3 operator* ( const AffineMapR3&, const AffineMapR3& ); +AffineMapR3 operator* ( const LinearMapR3&, const AffineMapR3& ); +AffineMapR3 operator* ( const AffineMapR3&, const LinearMapR3& ); + + +// ******************************************* +// RotationMapR3 class * +// * * * * * * * * * * * * * * * * * * * * * * + +class RotationMapR3 : public Matrix3x3 { + +public: + + RotationMapR3(); + RotationMapR3( const VectorR3&, const VectorR3&, const VectorR3& ); + RotationMapR3( double, double, double, double, double, double, + double, double, double ); + + RotationMapR3& Set( const Quaternion& ); + RotationMapR3& Set( const VectorR3&, double theta ); // Set rotation axis and angle + RotationMapR3& Set( const VectorR3&, double sintheta, double costheta ); + + RotationMapR3& operator*= (const RotationMapR3& ); // Matrix product + + RotationMapR3 Transpose() const { return Inverse(); }; // Returns the transpose + RotationMapR3 Inverse() const; // Returns inverse + RotationMapR3& Invert(); // Converts into inverse. + VectorR3 Solve(const VectorR3&) const; // Returns solution // Was named Invert + + bool ToAxisAndAngle( VectorR3* u, double* theta ) const; // returns unit vector u and angle + +}; + +RotationMapR3 operator* ( const RotationMapR3&, const RotationMapR3& ); + // Matrix product (composition) + +inline RotationMapR3 ToRotationMapR3( const Quaternion& q ) + { return( RotationMapR3().Set(q) ); } + +ostream& operator<< ( ostream& os, const RotationMapR3& A ); + + + +// *************************************************************** +// * RigidMapR3 class - prototypes. * * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +class RigidMapR3 : public Matrix3x4 +{ + +public: + RigidMapR3(); + RigidMapR3( const VectorR3&, const VectorR3&, const VectorR3&, const VectorR3& ); + RigidMapR3( double, double, double, double, double, double, + double, double, double, double, double, double ); + RigidMapR3( const Matrix3x3&, const VectorR3& ); + + RigidMapR3& Set( const Matrix3x3&, const VectorR3& ); // Set to RotationMap & Vector + RigidMapR3& SetTranslationPart( const VectorR3& ); // Set the translation part + RigidMapR3& SetTranslationPart( double, double, double ); // Set the translation part + RigidMapR3& SetRotationPart( const Matrix3x3& ); // Set the rotation part + RigidMapR3& SetRotationPart( const Quaternion& ); + RigidMapR3& SetRotationPart( const VectorR3&, double theta ); // Set rotation axis and angle + RigidMapR3& SetRotationPart( const VectorR3&, double sintheta, double costheta ); + + RigidMapR3& ApplyTranslationLeft( const VectorR3& u ) + {Matrix3x4::ApplyTranslationLeft( u ); return *this;} + RigidMapR3& ApplyTranslationRight( const VectorR3& u ) + {Matrix3x4::ApplyTranslationRight( u ); return *this;} + RigidMapR3& ApplyYRotationLeft( double theta ) + { Matrix3x4::ApplyYRotationLeft( theta ); return *this; } + RigidMapR3& ApplyYRotationLeft( double costheta, double sintheta ) + { Matrix3x4::ApplyYRotationLeft( costheta, sintheta ); return *this; } + + RigidMapR3& operator*=(const RotationMapR3& ); // Composition + RigidMapR3& operator*=(const RigidMapR3& ); // Composition + + RigidMapR3 Inverse() const; // Returns inverse + RigidMapR3& Invert(); // Converts into inverse. + + bool CalcGlideRotation( VectorR3* u, VectorR3* v, + double *glideDist, double *rotation ) const; + + void Transform3x3Inverse( VectorR3* dest ) const + { Matrix3x4::Transform3x3Transpose( dest ); } + void Transform3x3Inverse( const VectorR3& src, VectorR3* dest ) const + { Matrix3x4::Transform3x3Transpose( src, dest ); } + +}; + + +// *************************************************************** +// * 3-space vector and matrix utilities (prototypes) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +// Returns the solid angle between vectors v and w. +inline double SolidAngle( const VectorR3& v, const VectorR3& w); + +// Returns a righthanded orthonormal basis to complement unit vector x +void GetOrtho( const VectorR3& x, VectorR3& y, VectorR3& z); +// Returns a vector v orthonormal to unit vector x +void GetOrtho( const VectorR3& x, VectorR3& y ); + +// Projections + +// The next three functions are templated below. +//inline VectorR3 ProjectToUnit ( const VectorR3& u, const VectorR3& v); // Project u onto v +//inline VectorR3 ProjectPerpUnit ( const VectorR3& u, const VectorR3 & v); // Project perp to v +//inline VectorR3 ProjectPerpUnitDiff ( const VectorR3& u, const VectorR3& v) +// v must be a unit vector. + +// Projection maps (LinearMapR3s) + +inline LinearMapR3 VectorProjectMap( const VectorR3& u ); +inline LinearMapR3 PlaneProjectMap ( const VectorR3& w ); +inline LinearMapR3 PlaneProjectMap ( const VectorR3& u, const VectorR3 &v ); +// u,v,w - must be unit vector. u and v must be orthonormal and +// specify the plane they are parallel to. w specifies the plane +// it is orthogonal to. + +// VrRotate is similar to glRotate. Returns a matrix (RotationMapR3) +// that will perform the rotation. u should be a unit vector. +RotationMapR3 VrRotate( double theta, const VectorR3& u ); +RotationMapR3 VrRotate( double costheta, double sintheta, const VectorR3& u ); +RotationMapR3 VrRotateAlign( const VectorR3& fromVec, const VectorR3& toVec); +RotationMapR3 RotateToMap( const VectorR3& fromVec, const VectorR3& toVec); +// fromVec and toVec should be unit vectors for RotateToMap + +// *************************************************************** +// * Stream Output Routines (Prototypes) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +ostream& operator<< ( ostream& os, const VectorR3& u ); + + +// ***************************************************** +// * VectorR3 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * + +inline VectorR3& VectorR3::Load( const double* v ) +{ + x = *v; + y = *(v+1); + z = *(v+2); + return *this; +} + +inline VectorR3& VectorR3::Load( const float* v ) +{ + x = *v; + y = *(v+1); + z = *(v+2); + return *this; +} + +inline void VectorR3::Dump( double* v ) const +{ + *v = x; + *(v+1) = y; + *(v+2) = z; +} + +inline void VectorR3::Dump( float* v ) const +{ + *v = (float)x; + *(v+1) = (float)y; + *(v+2) = (float)z; +} + +inline double VectorR3::operator[]( int i ) +{ + switch (i) { + case 0: + return x; + case 1: + return y; + case 2: + return z; + default: + assert(0); + return 0.0; + } +} + +inline VectorR3& VectorR3::MakeUnit () // Convert to unit vector (or leave zero). +{ + double nSq = NormSq(); + if (nSq != 0.0) { + *this /= sqrt(nSq); + } + return *this; +} + +inline VectorR3 operator+( const VectorR3& u, const VectorR3& v ) +{ + return VectorR3(u.x+v.x, u.y+v.y, u.z+v.z); +} +inline VectorR3 operator-( const VectorR3& u, const VectorR3& v ) +{ + return VectorR3(u.x-v.x, u.y-v.y, u.z-v.z); +} +inline VectorR3 operator*( const VectorR3& u, register double m) +{ + return VectorR3( u.x*m, u.y*m, u.z*m); +} +inline VectorR3 operator*( register double m, const VectorR3& u) +{ + return VectorR3( u.x*m, u.y*m, u.z*m); +} +inline VectorR3 operator/( const VectorR3& u, double m) +{ + register double mInv = 1.0/m; + return VectorR3( u.x*mInv, u.y*mInv, u.z*mInv); +} + +inline int operator==( const VectorR3& u, const VectorR3& v ) +{ + return ( u.x==v.x && u.y==v.y && u.z==v.z ); +} + +inline double operator^ ( const VectorR3& u, const VectorR3& v ) // Dot Product +{ + return ( u.x*v.x + u.y*v.y + u.z*v.z ); +} + +inline VectorR3 operator* (const VectorR3& u, const VectorR3& v) // Cross Product +{ + return (VectorR3( u.y*v.z - u.z*v.y, + u.z*v.x - u.x*v.z, + u.x*v.y - u.y*v.x ) ); +} + +inline VectorR3 ArrayProd ( const VectorR3& u, const VectorR3& v ) +{ + return ( VectorR3( u.x*v.x, u.y*v.y, u.z*v.z ) ); +} + +inline VectorR3& VectorR3::operator*= (const VectorR3& v) // Cross Product +{ + double tx=x, ty=y; + x = y*v.z - z*v.y; + y = z*v.x - tx*v.z; + z = tx*v.y - ty*v.x; + return ( *this ); +} + +inline VectorR3& VectorR3::ArrayProd (const VectorR3& v) // Component-wise Product +{ + x *= v.x; + y *= v.y; + z *= v.z; + return ( *this ); +} + +inline VectorR3& VectorR3::AddScaled( const VectorR3& u, double s ) +{ + x += s*u.x; + y += s*u.y; + z += s*u.z; + return(*this); +} + +inline VectorR3::VectorR3( const VectorHgR3& uH ) +: x(uH.x), y(uH.y), z(uH.z) +{ + *this /= uH.w; +} + +inline VectorR3& VectorR3::ReNormalize() // Convert near unit back to unit +{ + double nSq = NormSq(); + register double mFact = 1.0-0.5*(nSq-1.0); // Multiplicative factor + *this *= mFact; + return *this; +} + +inline double NormalizeError (const VectorR3& u) +{ + register double discrepancy; + discrepancy = u.x*u.x + u.y*u.y + u.z*u.z - 1.0; + if ( discrepancy < 0.0 ) { + discrepancy = -discrepancy; + } + return discrepancy; +} + +inline double VectorR3::Dist( const VectorR3& u ) const // Distance from u +{ + return sqrt( DistSq(u) ); +} + +inline double VectorR3::DistSq( const VectorR3& u ) const // Distance from u +{ + return ( (x-u.x)*(x-u.x) + (y-u.y)*(y-u.y) + (z-u.z)*(z-u.z) ); +} + +// +// Interpolation routines (not just Spherical Interpolation) +// + +// Interpolate(start,end,frac) - linear interpolation +// - allows overshooting the end points +inline VectorR3 Interpolate( const VectorR3& start, const VectorR3& end, double a) +{ + VectorR3 ret; + Lerp( start, end, a, ret ); + return ret; +} + + +// ****************************************************** +// * Matrix3x3 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +inline Matrix3x3::Matrix3x3() {} + +inline Matrix3x3::Matrix3x3( const VectorR3& u, const VectorR3& v, + const VectorR3& s ) +{ + m11 = u.x; // Column 1 + m21 = u.y; + m31 = u.z; + m12 = v.x; // Column 2 + m22 = v.y; + m32 = v.z; + m13 = s.x; // Column 3 + m23 = s.y; + m33 = s.z; +} + +inline Matrix3x3::Matrix3x3( double a11, double a21, double a31, + double a12, double a22, double a32, + double a13, double a23, double a33) + // Values specified in column order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m13 = a13; + m21 = a21; // Row 2 + m22 = a22; + m23 = a23; + m31 = a31; // Row 3 + m32 = a32; + m33 = a33; +} + +inline void Matrix3x3::SetIdentity ( ) +{ + m11 = m22 = m33 = 1.0; + m12 = m13 = m21 = m23 = m31 = m32 = 0.0; +} + +inline void Matrix3x3::SetZero( ) +{ + m11 = m12 = m13 = m21 = m22 = m23 = m31 = m32 = m33 = 0.0; +} + +inline void Matrix3x3::Set ( const Matrix3x3& A ) // Set to the matrix. +{ + m11 = A.m11; + m21 = A.m21; + m31 = A.m31; + m12 = A.m12; + m22 = A.m22; + m32 = A.m32; + m13 = A.m13; + m23 = A.m23; + m33 = A.m33; +} + +inline void Matrix3x3::Set3x3 ( const Matrix3x4& A ) // Set to the 3x3 part of the matrix. +{ + m11 = A.m11; + m21 = A.m21; + m31 = A.m31; + m12 = A.m12; + m22 = A.m22; + m32 = A.m32; + m13 = A.m13; + m23 = A.m23; + m33 = A.m33; +} + +inline void Matrix3x3::Set( const VectorR3& u, const VectorR3& v, + const VectorR3& w) +{ + m11 = u.x; // Column 1 + m21 = u.y; + m31 = u.z; + m12 = v.x; // Column 2 + m22 = v.y; + m32 = v.z; + m13 = w.x; // Column 3 + m23 = w.y; + m33 = w.z; +} + +inline void Matrix3x3::Set( double a11, double a21, double a31, + double a12, double a22, double a32, + double a13, double a23, double a33) + // Values specified in column order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m13 = a13; + m21 = a21; // Row 2 + m22 = a22; + m23 = a23; + m31 = a31; // Row 3 + m32 = a32; + m33 = a33; +} + +inline void Matrix3x3::SetByRows( double a11, double a12, double a13, + double a21, double a22, double a23, + double a31, double a32, double a33) + // Values specified in row order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m13 = a13; + m21 = a21; // Row 2 + m22 = a22; + m23 = a23; + m31 = a31; // Row 3 + m32 = a32; + m33 = a33; +} + +inline void Matrix3x3::SetByRows( const VectorR3& u, const VectorR3& v, + const VectorR3& s ) +{ + m11 = u.x; // Row 1 + m12 = u.y; + m13 = u.z; + m21 = v.x; // Row 2 + m22 = v.y; + m23 = v.z; + m31 = s.x; // Row 3 + m32 = s.y; + m33 = s.z; +} + +inline void Matrix3x3::SetColumn1 ( double x, double y, double z) +{ + m11 = x; m21 = y; m31= z; +} + +inline void Matrix3x3::SetColumn2 ( double x, double y, double z) +{ + m12 = x; m22 = y; m32= z; +} + +inline void Matrix3x3::SetColumn3 ( double x, double y, double z) +{ + m13 = x; m23 = y; m33= z; +} + +inline void Matrix3x3::SetColumn1 ( const VectorR3& u ) +{ + m11 = u.x; m21 = u.y; m31 = u.z; +} + +inline void Matrix3x3::SetColumn2 ( const VectorR3& u ) +{ + m12 = u.x; m22 = u.y; m32 = u.z; +} + +inline void Matrix3x3::SetColumn3 ( const VectorR3& u ) +{ + m13 = u.x; m23 = u.y; m33 = u.z; +} + +inline void Matrix3x3::SetRow1 ( double x, double y, double z ) +{ + m11 = x; + m12 = y; + m13 = z; +} + +inline void Matrix3x3::SetRow2 ( double x, double y, double z ) +{ + m21 = x; + m22 = y; + m23 = z; +} + +inline void Matrix3x3::SetRow3 ( double x, double y, double z ) +{ + m31 = x; + m32 = y; + m33 = z; +} + + + +inline VectorR3 Matrix3x3::Column1() const +{ + return ( VectorR3(m11, m21, m31) ); +} + +inline VectorR3 Matrix3x3::Column2() const +{ + return ( VectorR3(m12, m22, m32) ); +} + +inline VectorR3 Matrix3x3::Column3() const +{ + return ( VectorR3(m13, m23, m33) ); +} + +inline VectorR3 Matrix3x3::Row1() const +{ + return ( VectorR3(m11, m12, m13) ); +} + +inline VectorR3 Matrix3x3::Row2() const +{ + return ( VectorR3(m21, m22, m23) ); +} + +inline VectorR3 Matrix3x3::Row3() const +{ + return ( VectorR3(m31, m32, m33) ); +} + +inline void Matrix3x3::SetDiagonal( double x, double y, double z ) +{ + m11 = x; + m22 = y; + m33 = z; +} + +inline void Matrix3x3::SetDiagonal( const VectorR3& u ) +{ + SetDiagonal ( u.x, u.y, u.z ); +} + +inline double Matrix3x3::Diagonal( int i ) +{ + switch (i) { + case 0: + return m11; + case 1: + return m22; + case 2: + return m33; + default: + assert(0); + return 0.0; + } +} + +inline void Matrix3x3::MakeTranspose() // Transposes it. +{ + register double temp; + temp = m12; + m12 = m21; + m21=temp; + temp = m13; + m13 = m31; + m31 = temp; + temp = m23; + m23 = m32; + m32 = temp; +} + +inline VectorR3 operator* ( const Matrix3x3& A, const VectorR3& u) +{ + return( VectorR3( A.m11*u.x + A.m12*u.y + A.m13*u.z, + A.m21*u.x + A.m22*u.y + A.m23*u.z, + A.m31*u.x + A.m32*u.y + A.m33*u.z ) ); +} + +inline void Matrix3x3::Transform( VectorR3* u ) const { + double newX, newY; + newX = m11*u->x + m12*u->y + m13*u->z; + newY = m21*u->x + m22*u->y + m23*u->z; + u->z = m31*u->x + m32*u->y + m33*u->z; + u->x = newX; + u->y = newY; +} + +inline void Matrix3x3::Transform( const VectorR3& src, VectorR3* dest ) const { + dest->x = m11*src.x + m12*src.y + m13*src.z; + dest->y = m21*src.x + m22*src.y + m23*src.z; + dest->z = m31*src.x + m32*src.y + m33*src.z; +} + + +// ****************************************************** +// * Matrix3x4 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +inline Matrix3x4::Matrix3x4(const VectorR3& u, const VectorR3& v, + const VectorR3& s, const VectorR3& t) +{ + m11 = u.x; // Column 1 + m21 = u.y; + m31 = u.z; + m12 = v.x; // Column 2 + m22 = v.y; + m32 = v.z; + m13 = s.x; // Column 3 + m23 = s.y; + m33 = s.z; + m14 = t.x; + m24 = t.y; + m34 = t.z; +} + +inline Matrix3x4::Matrix3x4(double a11, double a21, double a31, + double a12, double a22, double a32, + double a13, double a23, double a33, + double a14, double a24, double a34) +{ // Values in COLUMN order! + m11 = a11; // Row 1 + m12 = a12; + m13 = a13; + m14 = a14; + m21 = a21; // Row 2 + m22 = a22; + m23 = a23; + m24 = a24; + m31 = a31; // Row 3 + m32 = a32; + m33 = a33; + m34 = a34; +} + +inline Matrix3x4::Matrix3x4( const Matrix3x3& A, const VectorR3& u ) +{ + Set(A, u); +} + +inline void Matrix3x4::SetIdentity () // Set to the identity map +{ + m11 = m22 = m33 = 1.0; + m12 = m13 = m21 = m23 = m31 = m32 = 0.0; + m14 = m24 = m34 = 0.0; +} + +inline void Matrix3x4::SetZero () // Set to the zero map +{ + m11 = m22 = m33 = 0.0; + m12 = m13 = m21 = m23 = m31 = m32 = 0.0; + m14 = m24 = m34 = 0.0; +} + +inline void Matrix3x4::Set ( const Matrix3x4& A ) // Set to the matrix. +{ + m11 = A.m11; + m21 = A.m21; + m31 = A.m31; + m12 = A.m12; + m22 = A.m22; + m32 = A.m32; + m13 = A.m13; + m23 = A.m23; + m33 = A.m33; + m14 = A.m14; + m24 = A.m24; + m34 = A.m34; +} + +inline void Matrix3x4::Set ( const Matrix3x3& A, const VectorR3& t ) // Set to the matrix plus 4th column +{ + m11 = A.m11; + m21 = A.m21; + m31 = A.m31; + m12 = A.m12; + m22 = A.m22; + m32 = A.m32; + m13 = A.m13; + m23 = A.m23; + m33 = A.m33; + m14 = t.x; // Column 4 + m24 = t.y; + m34 = t.z; +} + +// Set linear part to the matrix +inline void Matrix3x4::Set3x3 ( const Matrix3x3& A ) +{ + m11 = A.m11; + m21 = A.m21; + m31 = A.m31; + m12 = A.m12; + m22 = A.m22; + m32 = A.m32; + m13 = A.m13; + m23 = A.m23; + m33 = A.m33; +} + +inline void Matrix3x4::Set( const VectorR3& u, const VectorR3& v, + const VectorR3& w, const VectorR3& t ) +{ + m11 = u.x; // Column 1 + m21 = u.y; + m31 = u.z; + m12 = v.x; // Column 2 + m22 = v.y; + m32 = v.z; + m13 = w.x; // Column 3 + m23 = w.y; + m33 = w.z; + m14 = t.x; // Column 4 + m24 = t.y; + m34 = t.z; +} + +inline void Matrix3x4::Set( double a11, double a21, double a31, + double a12, double a22, double a32, + double a13, double a23, double a33, + double a14, double a24, double a34 ) + // Values specified in column order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m13 = a13; + m14 = a14; + m21 = a21; // Row 2 + m22 = a22; + m23 = a23; + m24 = a24; + m31 = a31; // Row 3 + m32 = a32; + m33 = a33; + m34 = a34; +} + +inline void Matrix3x4::Set3x3( double a11, double a21, double a31, + double a12, double a22, double a32, + double a13, double a23, double a33 ) + // Values specified in column order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m13 = a13; + m21 = a21; // Row 2 + m22 = a22; + m23 = a23; + m31 = a31; // Row 3 + m32 = a32; + m33 = a33; +} + +inline void Matrix3x4::SetByRows( double a11, double a12, double a13, double a14, + double a21, double a22, double a23, double a24, + double a31, double a32, double a33, double a34 ) + // Values specified in row order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m13 = a13; + m14 = a14; + m21 = a21; // Row 2 + m22 = a22; + m23 = a23; + m24 = a24; + m31 = a31; // Row 3 + m32 = a32; + m33 = a33; + m34 = a34; +} + +inline void Matrix3x4::SetColumn1 ( double x, double y, double z) +{ + m11 = x; m21 = y; m31= z; +} + +inline void Matrix3x4::SetColumn2 ( double x, double y, double z) +{ + m12 = x; m22 = y; m32= z; +} + +inline void Matrix3x4::SetColumn3 ( double x, double y, double z) +{ + m13 = x; m23 = y; m33= z; +} + +inline void Matrix3x4::SetColumn4 ( double x, double y, double z ) +{ + m14 = x; m24 = y; m34= z; +} + +inline void Matrix3x4::SetColumn1 ( const VectorR3& u ) +{ + m11 = u.x; m21 = u.y; m31 = u.z; +} + +inline void Matrix3x4::SetColumn2 ( const VectorR3& u ) +{ + m12 = u.x; m22 = u.y; m32 = u.z; +} + +inline void Matrix3x4::SetColumn3 ( const VectorR3& u ) +{ + m13 = u.x; m23 = u.y; m33 = u.z; +} + +inline void Matrix3x4::SetColumn4 ( const VectorR3& u ) +{ + m14 = u.x; m24 = u.y; m34 = u.z; +} + +inline VectorR3 Matrix3x4::Column1() const +{ + return ( VectorR3(m11, m21, m31) ); +} + +inline VectorR3 Matrix3x4::Column2() const +{ + return ( VectorR3(m12, m22, m32) ); +} + +inline VectorR3 Matrix3x4::Column3() const +{ + return ( VectorR3(m13, m23, m33) ); +} + +inline VectorR3 Matrix3x4::Column4() const +{ + return ( VectorR3(m14, m24, m34) ); +} + +inline void Matrix3x4::SetRow1 ( double x, double y, double z, double w ) +{ + m11 = x; + m12 = y; + m13 = z; + m14 = w; +} + +inline void Matrix3x4::SetRow2 ( double x, double y, double z, double w ) +{ + m21 = x; + m22 = y; + m23 = z; + m24 = w; +} + +inline void Matrix3x4::SetRow3 ( double x, double y, double z, double w ) +{ + m31 = x; + m32 = y; + m33 = z; + m34 = w; +} + +// Left multiply with a translation (so the translation is applied afterwards). +inline Matrix3x4& Matrix3x4::ApplyTranslationLeft( const VectorR3& u ) +{ + m14 += u.x; + m24 += u.y; + m34 += u.z; + return *this; +} + +// Right multiply with a translation (so the translation is applied first). +inline Matrix3x4& Matrix3x4::ApplyTranslationRight( const VectorR3& u ) +{ + double new14 = m14 + m11*u.x + m12*u.y + m13*u.z; + double new24 = m24 + m21*u.x + m22*u.y + m23*u.z; + m34 = m34 + m31*u.x + m32*u.y + m33*u.z; + m14 = new14; + m24 = new24; + return *this; +} + +// Left-multiply with a rotation around the y-axis. +inline Matrix3x4& Matrix3x4::ApplyYRotationLeft( double theta ) +{ + double costheta = cos(theta); + double sintheta = sin(theta); + return ApplyYRotationLeft( costheta, sintheta ); +} + +inline Matrix3x4& Matrix3x4::ApplyYRotationLeft( double costheta, double sintheta ) +{ + double tmp; + tmp = costheta*m11+sintheta*m31; + m31 = costheta*m31-sintheta*m11; + m11 = tmp; + + tmp = costheta*m12+sintheta*m32; + m32 = costheta*m32-sintheta*m12; + m12 = tmp; + + tmp = costheta*m13+sintheta*m33; + m33 = costheta*m33-sintheta*m13; + m13 = tmp; + + tmp = costheta*m14+sintheta*m34; + m34 = costheta*m34-sintheta*m14; + m14 = tmp; + + return *this; +} + +inline VectorR3 Matrix3x4::Solve(const VectorR3& u) const // Returns solution +{ + Matrix3x3 A; + A.Set3x3(*this); + return ( A.Solve( VectorR3(m14-u.x, m24-u.y, m34-u.z) ) ); +} + +inline void Matrix3x4::Transform( VectorR3* u ) const { + double newX, newY; + newX = m11*u->x + m12*u->y + m13*u->z + m14; + newY = m21*u->x + m22*u->y + m23*u->z + m24; + u->z = m31*u->x + m32*u->y + m33*u->z + m34; + u->x = newX; + u->y = newY; +} + +inline void Matrix3x4::Transform3x3( VectorR3* u ) const { + double newX, newY; + newX = m11*u->x + m12*u->y + m13*u->z; + newY = m21*u->x + m22*u->y + m23*u->z; + u->z = m31*u->x + m32*u->y + m33*u->z; + u->x = newX; + u->y = newY; +} + +inline void Matrix3x4::Transform( const VectorR3& src, VectorR3* dest ) const { + dest->x = m11*src.x + m12*src.y + m13*src.z + m14; + dest->y = m21*src.x + m22*src.y + m23*src.z + m24; + dest->z = m31*src.x + m32*src.y + m33*src.z + m34; +} + +inline void Matrix3x4::Transform3x3( const VectorR3& src, VectorR3* dest ) const { + dest->x = m11*src.x + m12*src.y + m13*src.z; + dest->y = m21*src.x + m22*src.y + m23*src.z; + dest->z = m31*src.x + m32*src.y + m33*src.z; +} + +inline void Matrix3x4::Transform3x3Transpose( VectorR3* u ) const { + double newX, newY; + newX = m11*u->x + m21*u->y + m31*u->z; + newY = m12*u->x + m22*u->y + m32*u->z; + u->z = m13*u->x + m23*u->y + m33*u->z; + u->x = newX; + u->y = newY; +} + +inline void Matrix3x4::Transform3x3Transpose( const VectorR3& src, VectorR3* dest ) const { + dest->x = m11*src.x + m21*src.y + m31*src.z; + dest->y = m12*src.x + m22*src.y + m32*src.z; + dest->z = m13*src.x + m23*src.y + m33*src.z; +} + +inline VectorR3 operator* ( const Matrix3x4& A, const VectorR3& u ) +{ + return( VectorR3( A.m11*u.x + A.m12*u.y + A.m13*u.z + A.m14, + A.m21*u.x + A.m22*u.y + A.m23*u.z + A.m24, + A.m31*u.x + A.m32*u.y + A.m33*u.z + A.m34) ); +} + + +// ****************************************************** +// * LinearMapR3 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +inline LinearMapR3::LinearMapR3() +{ + SetZero(); + return; +} + +inline LinearMapR3::LinearMapR3( const VectorR3& u, const VectorR3& v, + const VectorR3& s ) +:Matrix3x3 ( u, v, s ) +{ } + +inline LinearMapR3::LinearMapR3( + double a11, double a21, double a31, + double a12, double a22, double a32, + double a13, double a23, double a33) + // Values specified in column order!!! +:Matrix3x3 ( a11, a21, a31, a12, a22, a32, a13, a23, a33) +{ } + +inline LinearMapR3::LinearMapR3 ( const Matrix3x3& A ) +: Matrix3x3 (A) +{} + +inline void LinearMapR3::SetZero( ) +{ + Matrix3x3::SetZero(); +} + +inline void LinearMapR3::Negate() +{ + m11 = -m11; // Row 1 + m12 = -m12; + m13 = -m13; + m21 = -m21; // Row 2 + m22 = -m22; + m23 = -m23; + m31 = -m31; // Row 3 + m32 = -m32; + m33 = -m33; +} + + +inline LinearMapR3& LinearMapR3::operator+= (const Matrix3x3& B) +{ + m11 += B.m11; + m12 += B.m12; + m13 += B.m13; + m21 += B.m21; + m22 += B.m22; + m23 += B.m23; + m31 += B.m31; + m32 += B.m32; + m33 += B.m33; + return ( *this ); +} + +inline LinearMapR3& LinearMapR3::operator-= (const Matrix3x3& B) +{ + m11 -= B.m11; + m12 -= B.m12; + m13 -= B.m13; + m21 -= B.m21; + m22 -= B.m22; + m23 -= B.m23; + m31 -= B.m31; + m32 -= B.m32; + m33 -= B.m33; + return( *this ); +} + +inline LinearMapR3 operator+ (const LinearMapR3& A, const Matrix3x3& B) +{ + return (LinearMapR3( A.m11+B.m11, A.m21+B.m21, A.m31+B.m31, + A.m12+B.m12, A.m22+B.m22, A.m32+B.m32, + A.m13+B.m13, A.m23+B.m23, A.m33+B.m33 ) ); +} + +inline LinearMapR3 operator+ (const Matrix3x3& A, const LinearMapR3& B) +{ + return (LinearMapR3( A.m11+B.m11, A.m21+B.m21, A.m31+B.m31, + A.m12+B.m12, A.m22+B.m22, A.m32+B.m32, + A.m13+B.m13, A.m23+B.m23, A.m33+B.m33 ) ); +} + +inline LinearMapR3 operator- (const LinearMapR3& A) +{ + return( LinearMapR3( -A.m11, -A.m21, -A.m31, + -A.m12, -A.m22, -A.m32, + -A.m13, -A.m23, -A.m33 ) ); +} + +inline LinearMapR3 operator- (const Matrix3x3& A, const LinearMapR3& B) +{ + return( LinearMapR3( A.m11-B.m11, A.m21-B.m21, A.m31-B.m31, + A.m12-B.m12, A.m22-B.m22, A.m32-B.m32, + A.m13-B.m13, A.m23-B.m23, A.m33-B.m33 ) ); +} + +inline LinearMapR3 operator- (const LinearMapR3& A, const Matrix3x3& B) +{ + return( LinearMapR3( A.m11-B.m11, A.m21-B.m21, A.m31-B.m31, + A.m12-B.m12, A.m22-B.m22, A.m32-B.m32, + A.m13-B.m13, A.m23-B.m23, A.m33-B.m33 ) ); +} + +inline LinearMapR3& LinearMapR3::operator*= (register double b) +{ + m11 *= b; + m12 *= b; + m13 *= b; + m21 *= b; + m22 *= b; + m23 *= b; + m31 *= b; + m32 *= b; + m33 *= b; + return ( *this); +} + +inline LinearMapR3 operator* ( const LinearMapR3& A, register double b) +{ + return( LinearMapR3( A.m11*b, A.m21*b, A.m31*b, + A.m12*b, A.m22*b, A.m32*b, + A.m13*b, A.m23*b, A.m33*b ) ); +} + +inline LinearMapR3 operator* ( register double b, const LinearMapR3& A) +{ + return( LinearMapR3( A.m11*b, A.m21*b, A.m31*b, + A.m12*b, A.m22*b, A.m32*b, + A.m13*b, A.m23*b, A.m33*b ) ); +} + +inline LinearMapR3 operator/ ( const LinearMapR3& A, double b) +{ + register double bInv = 1.0/b; + return( LinearMapR3( A.m11*bInv, A.m21*bInv, A.m31*bInv, + A.m12*bInv, A.m22*bInv, A.m32*bInv, + A.m13*bInv, A.m23*bInv, A.m33*bInv ) ); +} + +inline LinearMapR3& LinearMapR3::operator/= (register double b) +{ + register double bInv = 1.0/b; + return ( *this *= bInv ); +} + +inline LinearMapR3& LinearMapR3::operator*= (const Matrix3x3& B) // Matrix product +{ + OperatorTimesEquals( B ); + return( *this ); +} + +inline VectorR3 LinearMapR3::Solve(const VectorR3& u) const // Returns solution +{ + return ( Matrix3x3::Solve( u ) ); +} + +inline LinearMapR3 LinearMapR3::Transpose() const // Returns the transpose +{ + return ( LinearMapR3 ( m11, m12, m13, m21, m22, m23, m31, m32, m33) ); +} + +// ****************************************************** +// * AffineMapR3 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +inline AffineMapR3::AffineMapR3( double a11, double a21, double a31, + double a12, double a22, double a32, + double a13, double a23, double a33, + double a14, double a24, double a34) +{ // Values in COLUMN order! + m11 = a11; // Row 1 + m12 = a12; + m13 = a13; + m14 = a14; + m21 = a21; // Row 2 + m22 = a22; + m23 = a23; + m24 = a24; + m31 = a31; // Row 3 + m32 = a32; + m33 = a33; + m34 = a34; +} + +inline AffineMapR3::AffineMapR3 (const VectorR3& u, const VectorR3& v, + const VectorR3& w, const VectorR3& t) +{ + m11 = u.x; // Column 1 + m21 = u.y; + m31 = u.z; + m12 = v.x; // Column 2 + m22 = v.y; + m32 = v.z; + m13 = w.x; // Column 3 + m23 = w.y; + m33 = w.z; + m14 = t.x; // Column 4 + m24 = t.y; + m34 = t.z; +} + +inline AffineMapR3::AffineMapR3 (const LinearMapR3& A, const VectorR3& t) +{ + m11 = A.m11; + m12 = A.m12; + m13 = A.m13; + m14 = t.x; + m21 = A.m21; + m22 = A.m22; + m23 = A.m23; + m24 = t.y; + m31 = A.m31; + m32 = A.m32; + m33 = A.m33; + m34 = t.z; + +} + +inline void AffineMapR3::SetIdentity ( ) +{ + Matrix3x4::SetIdentity(); +} + +inline void AffineMapR3::SetZero( ) +{ + Matrix3x4::SetZero(); +} + +inline VectorR3 AffineMapR3::Solve(const VectorR3& u) const // Returns solution +{ + return ( Matrix3x4::Solve( u ) ); +} + + +inline AffineMapR3& AffineMapR3::operator+= (const Matrix3x4& B) +{ + m11 += B.m11; + m21 += B.m21; + m31 += B.m31; + m12 += B.m12; + m22 += B.m22; + m32 += B.m32; + m13 += B.m13; + m23 += B.m23; + m33 += B.m33; + m14 += B.m14; + m24 += B.m24; + m34 += B.m34; + return (*this); +} + +inline AffineMapR3& AffineMapR3::operator-= (const Matrix3x4& B) +{ + m11 -= B.m11; + m21 -= B.m21; + m31 -= B.m31; + m12 -= B.m12; + m22 -= B.m22; + m32 -= B.m32; + m13 -= B.m13; + m23 -= B.m23; + m33 -= B.m33; + m14 -= B.m14; + m24 -= B.m24; + m34 -= B.m34; + return (*this); + +} + +inline AffineMapR3 operator+ (const AffineMapR3& A, const AffineMapR3& B) +{ + return( AffineMapR3( A.m11+B.m11, A.m21+B.m21, A.m31+B.m31, + A.m12+B.m12, A.m22+B.m22, A.m32+B.m32, + A.m13+B.m13, A.m23+B.m23, A.m33+B.m33, + A.m14+B.m14, A.m23+B.m24, A.m34+B.m34) ); +} + +inline AffineMapR3 operator+ (const AffineMapR3& A, const Matrix3x3& B) +{ + return( AffineMapR3( A.m11+B.m11, A.m21+B.m21, A.m31+B.m31, + A.m12+B.m12, A.m22+B.m22, A.m32+B.m32, + A.m13+B.m13, A.m23+B.m23, A.m33+B.m33, + A.m14, A.m23, A.m34 ) ); +} + +inline AffineMapR3 operator+ (const Matrix3x3& B, const AffineMapR3& A) +{ + return( AffineMapR3( A.m11+B.m11, A.m21+B.m21, A.m31+B.m31, + A.m12+B.m12, A.m22+B.m22, A.m32+B.m32, + A.m13+B.m13, A.m23+B.m23, A.m33+B.m33, + A.m14, A.m23, A.m34 ) ); +} + +inline AffineMapR3 operator- (const AffineMapR3& A, const AffineMapR3& B) +{ + return( AffineMapR3( A.m11-B.m11, A.m21-B.m21, A.m31-B.m31, + A.m12-B.m12, A.m22-B.m22, A.m32-B.m32, + A.m13-B.m13, A.m23-B.m23, A.m33-B.m33, + A.m14-B.m14, A.m23-B.m24, A.m34-B.m34) ); +} + +inline AffineMapR3 operator- (const AffineMapR3& A, const LinearMapR3& B) +{ + return ( AffineMapR3( A.m11-B.m11, A.m21-B.m21, A.m31-B.m31, + A.m12-B.m12, A.m22-B.m22, A.m32-B.m32, + A.m13-B.m13, A.m23-B.m23, A.m33-B.m33, + A.m14, A.m23, A.m34 ) ); +} + +inline AffineMapR3 operator- (const LinearMapR3& B, const AffineMapR3& A) +{ + return( AffineMapR3( A.m11-B.m11, A.m21-B.m21, A.m31-B.m31, + A.m12-B.m12, A.m22-B.m22, A.m32-B.m32, + A.m13-B.m13, A.m23-B.m23, A.m33-B.m33, + A.m14, A.m23, A.m34 ) ); +} + + +inline AffineMapR3& AffineMapR3::operator*= (register double b) +{ + m11 *= b; + m12 *= b; + m13 *= b; + m21 *= b; + m22 *= b; + m23 *= b; + m31 *= b; + m32 *= b; + m33 *= b; + m14 *= b; + m24 *= b; + m34 *= b; + return (*this); +} + +inline AffineMapR3 operator* (const AffineMapR3& A, register double b) +{ + return(AffineMapR3( A.m11*b, A.m21*b, A.m31*b, + A.m12*b, A.m22*b, A.m32*b, + A.m13*b, A.m23*b, A.m33*b, + A.m14*b, A.m24*b, A.m34*b ) ); +} + +inline AffineMapR3 operator* (register double b, const AffineMapR3& A) +{ + return(AffineMapR3( A.m11*b, A.m21*b, A.m31*b, + A.m12*b, A.m22*b, A.m32*b, + A.m13*b, A.m23*b, A.m33*b, + A.m14*b, A.m24*b, A.m34*b ) ); +} + +inline AffineMapR3& AffineMapR3::operator/= (double b) +{ + register double bInv = 1.0/b; + *this *= bInv; + return( *this ); +} + +inline AffineMapR3 operator/ (const AffineMapR3& A, double b) +{ + register double bInv = 1.0/b; + return(AffineMapR3( A.m11*bInv, A.m21*bInv, A.m31*bInv, + A.m12*bInv, A.m22*bInv, A.m32*bInv, + A.m13*bInv, A.m23*bInv, A.m33*bInv, + A.m14*bInv, A.m24*bInv, A.m34*bInv ) ); +} + +inline AffineMapR3& AffineMapR3::operator*= (const Matrix3x3& B) // Composition +{ + OperatorTimesEquals( B ); + return( *this ); +} + +inline AffineMapR3& AffineMapR3::operator*= (const Matrix3x4& B) // Composition +{ + OperatorTimesEquals( B ); + return( *this ); +} + +// ************************************************************** +// RotationMapR3 class (inlined functions) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +inline RotationMapR3::RotationMapR3() +{ + SetIdentity(); + return; +} + +inline RotationMapR3::RotationMapR3( const VectorR3& u, const VectorR3& v, + const VectorR3& s ) +:Matrix3x3 ( u, v, s ) +{ } + +inline RotationMapR3::RotationMapR3( + double a11, double a21, double a31, + double a12, double a22, double a32, + double a13, double a23, double a33) + // Values specified in column order!!! +:Matrix3x3 ( a11, a21, a31, a12, a22, a32, a13, a23, a33) +{ } + +inline RotationMapR3 RotationMapR3::Inverse() const // Returns inverse +{ + return ( RotationMapR3 ( m11, m12, m13, // In column order! + m21, m22, m23, + m31, m32, m33 ) ); +} + +inline RotationMapR3& RotationMapR3::Invert() // Converts into inverse. +{ + register double temp; + temp = m12; + m12 = m21; + m21 = temp; + temp = m13; + m13 = m31; + m31 = temp; + temp = m23; + m23 = m32; + m32 = temp; + return ( *this ); +} + +inline VectorR3 RotationMapR3::Solve(const VectorR3& u) const // Returns solution +{ + return( VectorR3( m11*u.x + m21*u.y + m31*u.z, + m12*u.x + m22*u.y + m32*u.z, + m13*u.x + m23*u.y + m33*u.z ) ); +} + +inline RotationMapR3& RotationMapR3::operator*= (const RotationMapR3& B) // Matrix product +{ + OperatorTimesEquals( B ); + return( *this ); +} + + +// ************************************************************** +// RigidMapR3 class (inlined functions) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +inline RigidMapR3::RigidMapR3() +{ + SetIdentity(); + return; +} + +inline RigidMapR3::RigidMapR3( const VectorR3& u, const VectorR3& v, + const VectorR3& s, const VectorR3& t ) +:Matrix3x4 ( u, v, s, t ) +{} + +inline RigidMapR3::RigidMapR3( + double a11, double a21, double a31, + double a12, double a22, double a32, + double a13, double a23, double a33, + double a14, double a24, double a34) + // Values specified in column order!!! +:Matrix3x4 ( a11, a21, a31, a12, a22, a32, a13, a23, a33, a14, a24, a34 ) +{} + +inline RigidMapR3::RigidMapR3( const Matrix3x3& A, const VectorR3& u ) // Set to RotationMap & Vector +: Matrix3x4( A, u ) +{} + + +inline RigidMapR3& RigidMapR3::Set( const Matrix3x3& A, const VectorR3& u ) // Set to RotationMap & Vector +{ + Matrix3x4::Set( A, u ); + return *this; +} + +inline RigidMapR3& RigidMapR3::SetTranslationPart( const VectorR3& u) // Set the translation part +{ + SetColumn4( u ); + return *this; +} + +inline RigidMapR3& RigidMapR3::SetTranslationPart( double x, double y, double z) // Set the translation part +{ + SetColumn4( x, y, z ); + return *this; +} + +inline RigidMapR3& RigidMapR3::SetRotationPart( const Matrix3x3& A) // Set the rotation part +{ + Matrix3x4::Set3x3( A ); + return *this; +} + +inline RigidMapR3& RigidMapR3::operator*= (const RotationMapR3& B) // Composition +{ + OperatorTimesEquals( B ); + return( *this ); +} + +inline RigidMapR3& RigidMapR3::operator*= (const RigidMapR3& B) // Composition +{ + OperatorTimesEquals( B ); + return( *this ); +} + +inline RigidMapR3 RigidMapR3::Inverse() const // Returns inverse +{ + double new14 = -(m11*m14 + m21*m24 + m31*m34); + double new24 = -(m12*m14 + m22*m24 + m32*m34); + double new34 = -(m13*m14 + m23*m24 + m33*m34); + return ( RigidMapR3 ( m11, m12, m13, // In column order! + m21, m22, m23, + m31, m32, m33, + new14, new24, new34 ) ); +} + +inline RigidMapR3& RigidMapR3::Invert() // Converts into inverse. +{ + double new14 = -(m11*m14 + m21*m24 + m31*m34); + double new24 = -(m12*m14 + m22*m24 + m32*m34); + m34 = -(m13*m14 + m23*m24 + m33*m34); + m14 = new14; + m24 = new24; + + register double temp; + temp = m12; + m12 = m21; + m21 = temp; + temp = m13; + m13 = m31; + m31 = temp; + temp = m23; + m23 = m32; + m32 = temp; + return ( *this ); +} + +// *************************************************************** +// * 3-space vector and matrix utilities (inlined functions) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +// Returns the projection of u onto unit v +inline VectorR3 ProjectToUnit ( const VectorR3& u, const VectorR3& v) +{ + return (u^v)*v; +} + +// Returns the projection of u onto the plane perpindicular to the unit vector v +inline VectorR3 ProjectPerpUnit ( const VectorR3& u, const VectorR3& v) +{ + return ( u - ((u^v)*v) ); +} + +// Returns the projection of u onto the plane perpindicular to the unit vector v +// This one is more stable when u and v are nearly equal. +inline VectorR3 ProjectPerpUnitDiff ( const VectorR3& u, const VectorR3& v) +{ + VectorR3 ans = u; + ans -= v; + ans -= ((ans^v)*v); + return ans; // ans = (u-v) - ((u-v)^v)*v +} + +// VectorProjectMap returns map projecting onto a given vector u. +// u should be a unit vector (otherwise the returned map is +// scaled according to the magnitude of u. +inline LinearMapR3 VectorProjectMap( const VectorR3& u ) +{ + double a = u.x*u.y; + double b = u.x*u.z; + double c = u.y*u.z; + return( LinearMapR3( u.x*u.x, a, b, + a, u.y*u.y, c, + b, c, u.z*u.z ) ); +} + +// PlaneProjectMap returns map projecting onto a given plane. +// The plane is the plane orthognal to w. +// w must be a unit vector (otherwise the returned map is +// garbage). +inline LinearMapR3 PlaneProjectMap ( const VectorR3& w ) +{ + double a = -w.x*w.y; + double b = -w.x*w.z; + double c = -w.y*w.z; + return( LinearMapR3( 1.0-w.x*w.x, a, b, + a, 1.0-w.y*w.y, c, + b, c, 1.0-w.z*w.z ) ); +} + +// PlaneProjectMap returns map projecting onto a given plane. +// The plane is the plane containing the two orthonormal vectors u,v. +// If u, v are orthonormal, this is a projection with scaling. +// If they are not orthonormal, the results are more difficult +// to interpret. +inline LinearMapR3 PlaneProjectMap ( const VectorR3& u, const VectorR3 &v ) +{ + double a = u.x*u.y + v.x*v.y; + double b = u.x*u.z + v.x*v.z; + double c = u.y*u.z + v.y*v.z; + return( LinearMapR3( u.x*u.x+v.x*v.x, a, b, + a, u.y*u.y+u.y*u.y, c, + b, c, u.z*u.z+v.z*v.z ) ); +} + +// Returns the solid angle between unit vectors v and w. +inline double SolidAngle( const VectorR3& v, const VectorR3& w) +{ + return atan2 ( (v*w).Norm(), v^w ); +} + + +#endif + +// ******************* End of header material ******************** diff --git a/examples/ThirdPartyLibs/BussIK/LinearR4.cpp b/examples/ThirdPartyLibs/BussIK/LinearR4.cpp new file mode 100644 index 000000000..f662a7d90 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/LinearR4.cpp @@ -0,0 +1,467 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + + +#include "LinearR4.h" + +#include + +const VectorR4 VectorR4::Zero(0.0, 0.0, 0.0, 0.0); +const VectorR4 VectorR4::UnitX( 1.0, 0.0, 0.0, 0.0); +const VectorR4 VectorR4::UnitY( 0.0, 1.0, 0.0, 0.0); +const VectorR4 VectorR4::UnitZ( 0.0, 0.0, 1.0, 0.0); +const VectorR4 VectorR4::UnitW( 0.0, 0.0, 0.0, 1.0); +const VectorR4 VectorR4::NegUnitX(-1.0, 0.0, 0.0, 0.0); +const VectorR4 VectorR4::NegUnitY( 0.0,-1.0, 0.0, 0.0); +const VectorR4 VectorR4::NegUnitZ( 0.0, 0.0,-1.0, 0.0); +const VectorR4 VectorR4::NegUnitW( 0.0, 0.0, 0.0,-1.0); + +const Matrix4x4 Matrix4x4::Identity(1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, + 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 1.0); + + +// ****************************************************** +// * VectorR4 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +double VectorR4::MaxAbs() const +{ + register double m; + m = (x>0.0) ? x : -x; + if ( y>m ) m=y; + else if ( -y >m ) m = -y; + if ( z>m ) m=z; + else if ( -z>m ) m = -z; + if ( w>m ) m=w; + else if ( -w>m ) m = -w; + return m; +} + +// ****************************************************** +// * Matrix4x4 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + + +void Matrix4x4::operator*= (const Matrix4x4& B) // Matrix product +{ + double t1, t2, t3; // temporary values + t1 = m11*B.m11 + m12*B.m21 + m13*B.m31 + m14*B.m41; + t2 = m11*B.m12 + m12*B.m22 + m13*B.m32 + m14*B.m42; + t3 = m11*B.m13 + m12*B.m23 + m13*B.m33 + m14*B.m43; + m14 = m11*B.m14 + m12*B.m24 + m13*B.m34 + m14*B.m44; + m11 = t1; + m12 = t2; + m13 = t3; + + t1 = m21*B.m11 + m22*B.m21 + m23*B.m31 + m24*B.m41; + t2 = m21*B.m12 + m22*B.m22 + m23*B.m32 + m24*B.m42; + t3 = m21*B.m13 + m22*B.m23 + m23*B.m33 + m24*B.m43; + m24 = m21*B.m14 + m22*B.m24 + m23*B.m34 + m24*B.m44; + m21 = t1; + m22 = t2; + m23 = t3; + + t1 = m31*B.m11 + m32*B.m21 + m33*B.m31 + m34*B.m41; + t2 = m31*B.m12 + m32*B.m22 + m33*B.m32 + m34*B.m42; + t3 = m31*B.m13 + m32*B.m23 + m33*B.m33 + m34*B.m43; + m34 = m31*B.m14 + m32*B.m24 + m33*B.m34 + m34*B.m44; + m31 = t1; + m32 = t2; + m33 = t3; + + t1 = m41*B.m11 + m42*B.m21 + m43*B.m31 + m44*B.m41; + t2 = m41*B.m12 + m42*B.m22 + m43*B.m32 + m44*B.m42; + t3 = m41*B.m13 + m42*B.m23 + m43*B.m33 + m44*B.m43; + m44 = m41*B.m14 + m42*B.m24 + m43*B.m34 + m44*B.m44; + m41 = t1; + m42 = t2; + m43 = t3; +} + +inline void ReNormalizeHelper ( double &a, double &b, double &c, double &d ) +{ + register double scaleF = a*a+b*b+c*c+d*d; // Inner product of Vector-R4 + scaleF = 1.0-0.5*(scaleF-1.0); + a *= scaleF; + b *= scaleF; + c *= scaleF; + d *= scaleF; +} + +Matrix4x4& Matrix4x4::ReNormalize() { + ReNormalizeHelper( m11, m21, m31, m41 ); // Renormalize first column + ReNormalizeHelper( m12, m22, m32, m42 ); // Renormalize second column + ReNormalizeHelper( m13, m23, m33, m43 ); // Renormalize third column + ReNormalizeHelper( m14, m24, m34, m44 ); // Renormalize fourth column + double alpha = 0.5*(m11*m12 + m21*m22 + m31*m32 + m41*m42); //1st and 2nd cols + double beta = 0.5*(m11*m13 + m21*m23 + m31*m33 + m41*m43); //1st and 3rd cols + double gamma = 0.5*(m11*m14 + m21*m24 + m31*m34 + m41*m44); //1st and 4nd cols + double delta = 0.5*(m12*m13 + m22*m23 + m32*m33 + m42*m43); //2nd and 3rd cols + double eps = 0.5*(m12*m14 + m22*m24 + m32*m34 + m42*m44); //2nd and 4nd cols + double phi = 0.5*(m13*m14 + m23*m24 + m33*m34 + m43*m44); //3rd and 4nd cols + double temp1, temp2, temp3; + temp1 = m11 - alpha*m12 - beta*m13 - gamma*m14; + temp2 = m12 - alpha*m11 - delta*m13 - eps*m14; + temp3 = m13 - beta*m11 - delta*m12 - phi*m14; + m14 -= (gamma*m11 + eps*m12 + phi*m13); + m11 = temp1; + m12 = temp2; + m13 = temp3; + temp1 = m21 - alpha*m22 - beta*m23 - gamma*m24; + temp2 = m22 - alpha*m21 - delta*m23 - eps*m24; + temp3 = m23 - beta*m21 - delta*m22 - phi*m24; + m24 -= (gamma*m21 + eps*m22 + phi*m23); + m21 = temp1; + m22 = temp2; + m23 = temp3; + temp1 = m31 - alpha*m32 - beta*m33 - gamma*m34; + temp2 = m32 - alpha*m31 - delta*m33 - eps*m34; + temp3 = m33 - beta*m31 - delta*m32 - phi*m34; + m34 -= (gamma*m31 + eps*m32 + phi*m33); + m31 = temp1; + m32 = temp2; + m33 = temp3; + temp1 = m41 - alpha*m42 - beta*m43 - gamma*m44; + temp2 = m42 - alpha*m41 - delta*m43 - eps*m44; + temp3 = m43 - beta*m41 - delta*m42 - phi*m44; + m44 -= (gamma*m41 + eps*m42 + phi*m43); + m41 = temp1; + m42 = temp2; + m43 = temp3; + return *this; +} + +// ****************************************************** +// * LinearMapR4 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + + +double LinearMapR4::Determinant () const // Returns the determinant +{ + double Tbt34C12 = m31*m42-m32*m41; // 2x2 subdeterminants + double Tbt34C13 = m31*m43-m33*m41; + double Tbt34C14 = m31*m44-m34*m41; + double Tbt34C23 = m32*m43-m33*m42; + double Tbt34C24 = m32*m44-m34*m42; + double Tbt34C34 = m33*m44-m34*m43; + + double sd11 = m22*Tbt34C34 - m23*Tbt34C24 + m24*Tbt34C23; // 3x3 subdeterminants + double sd12 = m21*Tbt34C34 - m23*Tbt34C14 + m24*Tbt34C13; + double sd13 = m21*Tbt34C24 - m22*Tbt34C14 + m24*Tbt34C12; + double sd14 = m21*Tbt34C23 - m22*Tbt34C13 + m23*Tbt34C12; + + return ( m11*sd11 - m12*sd12 + m13*sd13 - m14*sd14 ); +} + +LinearMapR4 LinearMapR4::Inverse() const // Returns inverse +{ + + double Tbt34C12 = m31*m42-m32*m41; // 2x2 subdeterminants + double Tbt34C13 = m31*m43-m33*m41; + double Tbt34C14 = m31*m44-m34*m41; + double Tbt34C23 = m32*m43-m33*m42; + double Tbt34C24 = m32*m44-m34*m42; + double Tbt34C34 = m33*m44-m34*m43; + double Tbt24C12 = m21*m42-m22*m41; // 2x2 subdeterminants + double Tbt24C13 = m21*m43-m23*m41; + double Tbt24C14 = m21*m44-m24*m41; + double Tbt24C23 = m22*m43-m23*m42; + double Tbt24C24 = m22*m44-m24*m42; + double Tbt24C34 = m23*m44-m24*m43; + double Tbt23C12 = m21*m32-m22*m31; // 2x2 subdeterminants + double Tbt23C13 = m21*m33-m23*m31; + double Tbt23C14 = m21*m34-m24*m31; + double Tbt23C23 = m22*m33-m23*m32; + double Tbt23C24 = m22*m34-m24*m32; + double Tbt23C34 = m23*m34-m24*m33; + + double sd11 = m22*Tbt34C34 - m23*Tbt34C24 + m24*Tbt34C23; // 3x3 subdeterminants + double sd12 = m21*Tbt34C34 - m23*Tbt34C14 + m24*Tbt34C13; + double sd13 = m21*Tbt34C24 - m22*Tbt34C14 + m24*Tbt34C12; + double sd14 = m21*Tbt34C23 - m22*Tbt34C13 + m23*Tbt34C12; + double sd21 = m12*Tbt34C34 - m13*Tbt34C24 + m14*Tbt34C23; // 3x3 subdeterminants + double sd22 = m11*Tbt34C34 - m13*Tbt34C14 + m14*Tbt34C13; + double sd23 = m11*Tbt34C24 - m12*Tbt34C14 + m14*Tbt34C12; + double sd24 = m11*Tbt34C23 - m12*Tbt34C13 + m13*Tbt34C12; + double sd31 = m12*Tbt24C34 - m13*Tbt24C24 + m14*Tbt24C23; // 3x3 subdeterminants + double sd32 = m11*Tbt24C34 - m13*Tbt24C14 + m14*Tbt24C13; + double sd33 = m11*Tbt24C24 - m12*Tbt24C14 + m14*Tbt24C12; + double sd34 = m11*Tbt24C23 - m12*Tbt24C13 + m13*Tbt24C12; + double sd41 = m12*Tbt23C34 - m13*Tbt23C24 + m14*Tbt23C23; // 3x3 subdeterminants + double sd42 = m11*Tbt23C34 - m13*Tbt23C14 + m14*Tbt23C13; + double sd43 = m11*Tbt23C24 - m12*Tbt23C14 + m14*Tbt23C12; + double sd44 = m11*Tbt23C23 - m12*Tbt23C13 + m13*Tbt23C12; + + + register double detInv = 1.0/(m11*sd11 - m12*sd12 + m13*sd13 - m14*sd14); + + return( LinearMapR4( sd11*detInv, -sd12*detInv, sd13*detInv, -sd14*detInv, + -sd21*detInv, sd22*detInv, -sd23*detInv, sd24*detInv, + sd31*detInv, -sd32*detInv, sd33*detInv, -sd34*detInv, + -sd41*detInv, sd42*detInv, -sd43*detInv, sd44*detInv ) ); +} + +LinearMapR4& LinearMapR4::Invert() // Converts into inverse. +{ + double Tbt34C12 = m31*m42-m32*m41; // 2x2 subdeterminants + double Tbt34C13 = m31*m43-m33*m41; + double Tbt34C14 = m31*m44-m34*m41; + double Tbt34C23 = m32*m43-m33*m42; + double Tbt34C24 = m32*m44-m34*m42; + double Tbt34C34 = m33*m44-m34*m43; + double Tbt24C12 = m21*m42-m22*m41; // 2x2 subdeterminants + double Tbt24C13 = m21*m43-m23*m41; + double Tbt24C14 = m21*m44-m24*m41; + double Tbt24C23 = m22*m43-m23*m42; + double Tbt24C24 = m22*m44-m24*m42; + double Tbt24C34 = m23*m44-m24*m43; + double Tbt23C12 = m21*m32-m22*m31; // 2x2 subdeterminants + double Tbt23C13 = m21*m33-m23*m31; + double Tbt23C14 = m21*m34-m24*m31; + double Tbt23C23 = m22*m33-m23*m32; + double Tbt23C24 = m22*m34-m24*m32; + double Tbt23C34 = m23*m34-m24*m33; + + double sd11 = m22*Tbt34C34 - m23*Tbt34C24 + m24*Tbt34C23; // 3x3 subdeterminants + double sd12 = m21*Tbt34C34 - m23*Tbt34C14 + m24*Tbt34C13; + double sd13 = m21*Tbt34C24 - m22*Tbt34C14 + m24*Tbt34C12; + double sd14 = m21*Tbt34C23 - m22*Tbt34C13 + m23*Tbt34C12; + double sd21 = m12*Tbt34C34 - m13*Tbt34C24 + m14*Tbt34C23; // 3x3 subdeterminants + double sd22 = m11*Tbt34C34 - m13*Tbt34C14 + m14*Tbt34C13; + double sd23 = m11*Tbt34C24 - m12*Tbt34C14 + m14*Tbt34C12; + double sd24 = m11*Tbt34C23 - m12*Tbt34C13 + m13*Tbt34C12; + double sd31 = m12*Tbt24C34 - m13*Tbt24C24 + m14*Tbt24C23; // 3x3 subdeterminants + double sd32 = m11*Tbt24C34 - m13*Tbt24C14 + m14*Tbt24C13; + double sd33 = m11*Tbt24C24 - m12*Tbt24C14 + m14*Tbt24C12; + double sd34 = m11*Tbt24C23 - m12*Tbt24C13 + m13*Tbt24C12; + double sd41 = m12*Tbt23C34 - m13*Tbt23C24 + m14*Tbt23C23; // 3x3 subdeterminants + double sd42 = m11*Tbt23C34 - m13*Tbt23C14 + m14*Tbt23C13; + double sd43 = m11*Tbt23C24 - m12*Tbt23C14 + m14*Tbt23C12; + double sd44 = m11*Tbt23C23 - m12*Tbt23C13 + m13*Tbt23C12; + + register double detInv = 1.0/(m11*sd11 - m12*sd12 + m13*sd13 - m14*sd14); + + m11 = sd11*detInv; + m12 = -sd21*detInv; + m13 = sd31*detInv; + m14 = -sd41*detInv; + m21 = -sd12*detInv; + m22 = sd22*detInv; + m23 = -sd32*detInv; + m24 = sd42*detInv; + m31 = sd13*detInv; + m32 = -sd23*detInv; + m33 = sd33*detInv; + m34 = -sd43*detInv; + m41 = -sd14*detInv; + m42 = sd24*detInv; + m43 = -sd34*detInv; + m44 = sd44*detInv; + + return ( *this ); +} + +VectorR4 LinearMapR4::Solve(const VectorR4& u) const // Returns solution +{ + // Just uses Inverse() for now. + return ( Inverse()*u ); +} + +// ****************************************************** +// * RotationMapR4 class - math library functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + + +// *************************************************************** +// * 4-space vector and matrix utilities * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +// Returns u * v^T +LinearMapR4 TimesTranspose( const VectorR4& u, const VectorR4& v) +{ + LinearMapR4 result; + TimesTranspose( u, v, result ); + return result; +} + +// The following routines are use to obtain +// a righthanded orthonormal basis to complement vectors u,v,w. +// The vectors u,v,w must be unit and orthonormal. +// The value is returned in "rotmat" with the first column(s) of +// rotmat equal to u,v,w as appropriate. + +void GetOrtho( const VectorR4& u, RotationMapR4& rotmat ) +{ + rotmat.SetColumn1(u); + GetOrtho( 1, rotmat ); +} + +void GetOrtho( const VectorR4& u, const VectorR4& v, RotationMapR4& rotmat ) +{ + rotmat.SetColumn1(u); + rotmat.SetColumn2(v); + GetOrtho( 2, rotmat ); +} + +void GetOrtho( const VectorR4& u, const VectorR4& v, const VectorR4& s, + RotationMapR4& rotmat ) +{ + rotmat.SetColumn1(u); + rotmat.SetColumn2(v); + rotmat.SetColumn3(s); + GetOrtho( 3, rotmat ); +} + +// This final version of GetOrtho is mainly for internal use. +// It uses a Gram-Schmidt procedure to extend a partial orthonormal +// basis to a complete orthonormal basis. +// j = number of columns of rotmat that have already been set. +void GetOrtho( int j, RotationMapR4& rotmat) +{ + if ( j==0 ) { + rotmat.SetIdentity(); + return; + } + if ( j==1 ) { + rotmat.SetColumn2( -rotmat.m21, rotmat.m11, -rotmat.m41, rotmat.m31 ); + j = 2; + } + + assert ( rotmat.Column1().Norm()<1.0001 && 0.9999 -0.001 ); + + // 2x2 subdeterminants in first 2 columns + + double d12 = rotmat.m11*rotmat.m22-rotmat.m12*rotmat.m21; + double d13 = rotmat.m11*rotmat.m32-rotmat.m12*rotmat.m31; + double d14 = rotmat.m11*rotmat.m42-rotmat.m12*rotmat.m41; + double d23 = rotmat.m21*rotmat.m32-rotmat.m22*rotmat.m31; + double d24 = rotmat.m21*rotmat.m42-rotmat.m22*rotmat.m41; + double d34 = rotmat.m31*rotmat.m42-rotmat.m32*rotmat.m41; + VectorR4 vec3; + + if ( j==2 ) { + if ( d12>0.4 || d12<-0.4 || d13>0.4 || d13<-0.4 + || d23>0.4 || d23<-0.4 ) { + vec3.Set( d23, -d13, d12, 0.0); + } + else if ( d24>0.4 || d24<-0.4 || d14>0.4 || d14<-0.4 ) { + vec3.Set( d24, -d14, 0.0, d12 ); + } + else { + vec3.Set( d34, 0.0, -d14, d13 ); + } + vec3.Normalize(); + rotmat.SetColumn3(vec3); + } + + // Do the final column + + rotmat.SetColumn4 ( + -rotmat.m23*d34 + rotmat.m33*d24 - rotmat.m43*d23, + rotmat.m13*d34 - rotmat.m33*d14 + rotmat.m43*d13, + -rotmat.m13*d24 + rotmat.m23*d14 - rotmat.m43*d12, + rotmat.m13*d23 - rotmat.m23*d13 + rotmat.m33*d12 ); + + assert ( 0.99 < (((LinearMapR4)rotmat)).Determinant() + && (((LinearMapR4)rotmat)).Determinant() < 1.01 ); + +} + + + +// ********************************************************************* +// Rotation routines * +// ********************************************************************* + +// Rotate unit vector x in the direction of "dir": length of dir is rotation angle. +// x must be a unit vector. dir must be perpindicular to x. +VectorR4& VectorR4::RotateUnitInDirection ( const VectorR4& dir) +{ + assert ( this->Norm()<1.0001 && this->Norm()>0.9999 && + (dir^(*this))<0.0001 && (dir^(*this))>-0.0001 ); + + double theta = dir.NormSq(); + if ( theta==0.0 ) { + return *this; + } + else { + theta = sqrt(theta); + double costheta = cos(theta); + double sintheta = sin(theta); + VectorR4 dirUnit = dir/theta; + *this = costheta*(*this) + sintheta*dirUnit; + // this->NormalizeFast(); + return ( *this ); + } +} + +// RotateToMap returns a RotationMapR4 that rotates fromVec to toVec, +// leaving the orthogonal subspace fixed. +// fromVec and toVec should be unit vectors +RotationMapR4 RotateToMap( const VectorR4& fromVec, const VectorR4& toVec) +{ + LinearMapR4 result; + result.SetIdentity(); + LinearMapR4 temp; + VectorR4 vPerp = ProjectPerpUnitDiff( toVec, fromVec ); + double sintheta = vPerp.Norm(); // theta = angle between toVec and fromVec + VectorR4 vProj = toVec-vPerp; + double costheta = vProj^fromVec; + if ( sintheta == 0.0 ) { + // The vectors either coincide (return identity) or directly oppose + if ( costheta < 0.0 ) { + result = -result; // Vectors directly oppose: return -identity. + } + } + else { + vPerp /= sintheta; // Normalize + VectorProjectMap ( fromVec, temp ); // project in fromVec direction + temp *= (costheta-1.0); + result += temp; + VectorProjectMap ( vPerp, temp ); // Project in vPerp direction + temp *= (costheta-1.0); + result += temp; + TimesTranspose ( vPerp, fromVec, temp ); // temp = (vPerp)*(fromVec^T) + temp *= sintheta; + result += temp; + temp.MakeTranspose(); + result -= temp; // (-sintheta)*(fromVec)*(vPerp^T) + } + RotationMapR4 rotationResult; + rotationResult.Set(result); // Make explicitly a RotationMapR4 + return rotationResult; +} + + +// *************************************************************** +// Stream Output Routines * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +ostream& operator<< ( ostream& os, const VectorR4& u ) +{ + return (os << "<" << u.x << "," << u.y << "," << u.z << "," << u.w << ">"); +} + + diff --git a/examples/ThirdPartyLibs/BussIK/LinearR4.h b/examples/ThirdPartyLibs/BussIK/LinearR4.h new file mode 100644 index 000000000..ee995326c --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/LinearR4.h @@ -0,0 +1,1099 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + + +// +// Linear Algebra Classes over R4 +// +// +// A. Vector and Position classes +// +// A.1. VectorR4: a column vector of length 4 +// +// B. Matrix Classes +// +// B.1 LinearMapR4 - arbitrary linear map; 4x4 real matrix +// +// B.2 RotationMapR4 - orthonormal 4x4 matrix +// + +#ifndef LINEAR_R4_H +#define LINEAR_R4_H + +#include +#include +#include +#include "LinearR3.h" +using namespace std; + +class VectorR4; // R4 Vector +class LinearMapR4; // 4x4 real matrix +class RotationMapR4; // 4x4 rotation map + +// ************************************** +// VectorR4 class * +// * * * * * * * * * * * * * * * * * * ** + +class VectorR4 { + +public: + double x, y, z, w; // The x & y & z & w coordinates. + + static const VectorR4 Zero; + static const VectorR4 UnitX; + static const VectorR4 UnitY; + static const VectorR4 UnitZ; + static const VectorR4 UnitW; + static const VectorR4 NegUnitX; + static const VectorR4 NegUnitY; + static const VectorR4 NegUnitZ; + static const VectorR4 NegUnitW; + +public: + VectorR4( ) : x(0.0), y(0.0), z(0.0), w(0.0) {} + VectorR4( double xVal, double yVal, double zVal, double wVal ) + : x(xVal), y(yVal), z(zVal), w(wVal) {} + VectorR4( const Quaternion& q); // Definition with Quaternion routines + + VectorR4& SetZero() { x=0.0; y=0.0; z=0.0; w=0.0; return *this;} + VectorR4& Set( double xx, double yy, double zz, double ww ) + { x=xx; y=yy; z=zz; w=ww; return *this;} + VectorR4& Set ( const Quaternion& ); // Defined with Quaternion + VectorR4& Set ( const VectorHgR3& h ) {x=h.x; y=h.y; z=h.z; w=h.w; return *this; } + VectorR4& Load( const double* v ); + VectorR4& Load( const float* v ); + void Dump( double* v ) const; + void Dump( float* v ) const; + + VectorR4& operator+= ( const VectorR4& v ) + { x+=v.x; y+=v.y; z+=v.z; w+=v.w; return(*this); } + VectorR4& operator-= ( const VectorR4& v ) + { x-=v.x; y-=v.y; z-=v.z; w-=v.w; return(*this); } + VectorR4& operator*= ( double m ) + { x*=m; y*=m; z*=m; w*=m; return(*this); } + VectorR4& operator/= ( double m ) + { register double mInv = 1.0/m; + x*=mInv; y*=mInv; z*=mInv; w*=mInv; + return(*this); } + VectorR4 operator- () const { return ( VectorR4(-x, -y, -z, -w) ); } + VectorR4& ArrayProd(const VectorR4&); // Component-wise product + VectorR4& ArrayProd3(const VectorR3&); // Component-wise product + + VectorR4& AddScaled( const VectorR4& u, double s ); + + double Norm() const { return ( (double)sqrt( x*x + y*y + z*z +w*w) ); } + double NormSq() const { return ( x*x + y*y + z*z + w*w ); } + double Dist( const VectorR4& u ) const; // Distance from u + double DistSq( const VectorR4& u ) const; // Distance from u + double MaxAbs() const; + VectorR4& Normalize () { *this /= Norm(); return *this; } // No error checking + inline VectorR4& MakeUnit(); // Normalize() with error checking + inline VectorR4& ReNormalize(); + bool IsUnit( ) const + { register double norm = Norm(); + return ( 1.000001>=norm && norm>=0.999999 ); } + bool IsUnit( double tolerance ) const + { register double norm = Norm(); + return ( 1.0+tolerance>=norm && norm>=1.0-tolerance ); } + bool IsZero() const { return ( x==0.0 && y==0.0 && z==0.0 && w==0.0); } + bool NearZero(double tolerance) const { return( MaxAbs()<=tolerance );} + // tolerance should be non-negative + + VectorR4& RotateUnitInDirection ( const VectorR4& dir); // rotate in direction dir + +}; + +inline VectorR4 operator+( const VectorR4& u, const VectorR4& v ); +inline VectorR4 operator-( const VectorR4& u, const VectorR4& v ); +inline VectorR4 operator*( const VectorR4& u, double m); +inline VectorR4 operator*( double m, const VectorR4& u); +inline VectorR4 operator/( const VectorR4& u, double m); +inline int operator==( const VectorR4& u, const VectorR4& v ); + +inline double operator^ (const VectorR4& u, const VectorR4& v ); // Dot Product +inline VectorR4 ArrayProd(const VectorR4& u, const VectorR4& v ); + +inline double Mag(const VectorR4& u) { return u.Norm(); } +inline double Dist(const VectorR4& u, const VectorR4& v) { return u.Dist(v); } +inline double DistSq(const VectorR4& u, const VectorR4& v) { return u.DistSq(v); } +inline double NormalizeError (const VectorR4& u); + +// ******************************************************************** +// Matrix4x4 - base class for 4x4 matrices * +// * * * * * * * * * * * * * * * * * * * * * ************************** + +class Matrix4x4 { + +public: + double m11, m12, m13, m14, m21, m22, m23, m24, + m31, m32, m33, m34, m41, m42, m43, m44; + + // Implements a 4x4 matrix: m_i_j - row-i and column-j entry + + static const Matrix4x4 Identity; + + +public: + + Matrix4x4(); + Matrix4x4( const VectorR4&, const VectorR4&, + const VectorR4&, const VectorR4& ); // Sets by columns! + Matrix4x4( double, double, double, double, + double, double, double, double, + double, double, double, double, + double, double, double, double ); // Sets by columns + + inline void SetIdentity (); // Set to the identity map + inline void SetZero (); // Set to the zero map + inline void Set ( const Matrix4x4& ); // Set to the matrix. + inline void Set( const VectorR4&, const VectorR4&, + const VectorR4&, const VectorR4& ); + inline void Set( double, double, double, double, + double, double, double, double, + double, double, double, double, + double, double, double, double ); + inline void SetByRows( const VectorR4&, const VectorR4&, + const VectorR4&, const VectorR4& ); + inline void SetByRows( double, double, double, double, + double, double, double, double, + double, double, double, double, + double, double, double, double ); + inline void SetColumn1 ( double, double, double, double ); + inline void SetColumn2 ( double, double, double, double ); + inline void SetColumn3 ( double, double, double, double ); + inline void SetColumn4 ( double, double, double, double ); + inline void SetColumn1 ( const VectorR4& ); + inline void SetColumn2 ( const VectorR4& ); + inline void SetColumn3 ( const VectorR4& ); + inline void SetColumn4 ( const VectorR4& ); + inline VectorR4 Column1() const; + inline VectorR4 Column2() const; + inline VectorR4 Column3() const; + inline VectorR4 Column4() const; + + inline void SetDiagonal( double, double, double, double ); + inline void SetDiagonal( const VectorR4& ); + inline double Diagonal( int ); + + inline void MakeTranspose(); // Transposes it. + void Matrix4x4::operator*= (const Matrix4x4& B); // Matrix product + + Matrix4x4& ReNormalize(); +}; + +inline VectorR4 operator* ( const Matrix4x4&, const VectorR4& ); + +ostream& operator<< ( ostream& os, const Matrix4x4& A ); + + +// ***************************************** +// LinearMapR4 class * +// * * * * * * * * * * * * * * * * * * * * * + +class LinearMapR4 : public Matrix4x4 { + +public: + + LinearMapR4(); + LinearMapR4( const VectorR4&, const VectorR4&, + const VectorR4&, const VectorR4& ); // Sets by columns! + LinearMapR4( double, double, double, double, + double, double, double, double, + double, double, double, double, + double, double, double, double ); // Sets by columns + LinearMapR4 ( const Matrix4x4& ); + + inline LinearMapR4& operator+= (const LinearMapR4& ); + inline LinearMapR4& operator-= (const LinearMapR4& ); + inline LinearMapR4& operator*= (double); + inline LinearMapR4& operator/= (double); + inline LinearMapR4& operator*= (const Matrix4x4& ); // Matrix product + + inline LinearMapR4 Transpose() const; + double Determinant () const; // Returns the determinant + LinearMapR4 Inverse() const; // Returns inverse + LinearMapR4& Invert(); // Converts into inverse. + VectorR4 Solve(const VectorR4&) const; // Returns solution + LinearMapR4 PseudoInverse() const; // Returns pseudo-inverse TO DO + VectorR4 PseudoSolve(const VectorR4&); // Finds least squares solution TO DO +}; + +inline LinearMapR4 operator+ (const LinearMapR4&, const LinearMapR4&); +inline LinearMapR4 operator- (const LinearMapR4&); +inline LinearMapR4 operator- (const LinearMapR4&, const LinearMapR4&); +inline LinearMapR4 operator* ( const LinearMapR4&, double); +inline LinearMapR4 operator* ( double, const LinearMapR4& ); +inline LinearMapR4 operator/ ( const LinearMapR4&, double ); +inline LinearMapR4 operator* ( const Matrix4x4&, const LinearMapR4& ); +inline LinearMapR4 operator* ( const LinearMapR4&, const Matrix4x4& ); + // Matrix product (composition) + + +// ******************************************* +// RotationMapR4 class * +// * * * * * * * * * * * * * * * * * * * * * * + +class RotationMapR4 : public Matrix4x4 { + +public: + + RotationMapR4(); + RotationMapR4( const VectorR4&, const VectorR4&, + const VectorR4&, const VectorR4& ); // Sets by columns! + RotationMapR4( double, double, double, double, + double, double, double, double, + double, double, double, double, + double, double, double, double ); // Sets by columns! + + RotationMapR4& SetZero(); // IT IS AN ERROR TO USE THIS FUNCTION! + + inline RotationMapR4& operator*= (const RotationMapR4& ); // Matrix product + + inline RotationMapR4 Transpose() const; + inline RotationMapR4 Inverse() const { return Transpose(); }; // Returns the transpose + inline RotationMapR4& Invert() { MakeTranspose(); return *this; }; // Transposes it. + inline VectorR4 Invert(const VectorR4&) const; // Returns solution +}; + +inline RotationMapR4 operator* ( const RotationMapR4&, const RotationMapR4& ); + // Matrix product (composition) + + +// *************************************************************** +// * 4-space vector and matrix utilities (prototypes) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +// Returns the angle between vectors u and v. +// Use SolidAngleUnit if both vectors are unit vectors +inline double SolidAngle( const VectorR4& u, const VectorR4& v); +inline double SolidAngleUnit( const VectorR4 u, const VectorR4 v ); + +// Returns a righthanded orthonormal basis to complement vectors u,v,w. +// The vectors u,v,w must be unit and orthonormal. +void GetOrtho( const VectorR4& u, RotationMapR4& rotmap ); +void GetOrtho( const VectorR4& u, const VectorR4& v, RotationMapR4& rotmap ); +void GetOrtho( const VectorR4& u, const VectorR4& v, const VectorR4& w, + RotationMapR4& rotmap ); +void GetOrtho( int j, RotationMapR4& rotmap); // Mainly for internal use + +// Projections + +inline VectorR4 ProjectToUnit ( const VectorR4& u, const VectorR4& v); + // Project u onto v +inline VectorR4 ProjectPerpUnit ( const VectorR4& u, const VectorR4 & v); + // Project perp to v +inline VectorR4 ProjectPerpUnitDiff ( const VectorR4& u, const VectorR4& v); +// v must be a unit vector. + +// Returns the projection of u onto unit v +inline VectorR4 ProjectToUnit ( const VectorR4& u, const VectorR4& v) +{ + return (u^v)*v; +} + +// Returns the projection of u onto the plane perpindicular to the unit vector v +inline VectorR4 ProjectPerpUnit ( const VectorR4& u, const VectorR4& v) +{ + return ( u - ((u^v)*v) ); +} + +// Returns the projection of u onto the plane perpindicular to the unit vector v +// This one is more stable when u and v are nearly equal. +inline VectorR4 ProjectPerpUnitDiff ( const VectorR4& u, const VectorR4& v) +{ + VectorR4 ans = u; + ans -= v; + ans -= ((ans^v)*v); + return ans; // ans = (u-v) - ((u-v)^v)*v +} + + +// Projection maps (LinearMapR4's) + +// VectorProjectMap returns map projecting onto a given vector u. +// u should be a unit vector (otherwise the returned map is +// scaled according to the magnitude of u. +inline void VectorProjectMap( const VectorR4& u, LinearMapR4& M ) +{ + double a = u.x*u.y; + double b = u.x*u.z; + double c = u.x*u.w; + double d = u.y*u.z; + double e = u.y*u.w; + double f = u.z*u.w; + M.Set( u.x*u.x, a, b, c, + a, u.y*u.y, d, e, + b, d, u.z*u.z, f, + c, e, f, u.w*u.w ); +} + +inline LinearMapR4 VectorProjectMap( const VectorR4& u ) +{ + LinearMapR4 result; + VectorProjectMap( u, result ); + return result; +} + +inline LinearMapR4 PerpProjectMap ( const VectorR4& u ); +// u - must be unit vector. + +LinearMapR4 TimesTranspose( const VectorR4& u, const VectorR4& v); // u * v^T. +inline void TimesTranspose( const VectorR4& u, const VectorR4& v, LinearMapR4& M); + +// Rotation Maps + +RotationMapR4 RotateToMap( const VectorR4& fromVec, const VectorR4& toVec); +// fromVec and toVec should be unit vectors + + + +// *************************************************************** +// * Stream Output Routines (Prototypes) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +ostream& operator<< ( ostream& os, const VectorR4& u ); + + +// ***************************************************** +// * VectorR4 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * + +inline VectorR4& VectorR4::Load( const double* v ) +{ + x = *v; + y = *(v+1); + z = *(v+2); + w = *(v+3); + return *this; +} + +inline VectorR4& VectorR4::Load( const float* v ) +{ + x = *v; + y = *(v+1); + z = *(v+2); + w = *(v+3); + return *this; +} + +inline void VectorR4::Dump( double* v ) const +{ + *v = x; + *(v+1) = y; + *(v+2) = z; + *(v+3) = w; +} + +inline void VectorR4::Dump( float* v ) const +{ + *v = (float)x; + *(v+1) = (float)y; + *(v+2) = (float)z; + *(v+3) = (float)w; +} + +inline VectorR4& VectorR4::MakeUnit () // Convert to unit vector (or leave zero). +{ + double nSq = NormSq(); + if (nSq != 0.0) { + *this /= sqrt(nSq); + } + return *this; +} + +inline VectorR4 operator+( const VectorR4& u, const VectorR4& v ) +{ + return VectorR4(u.x+v.x, u.y+v.y, u.z+v.z, u.w+v.w ); +} +inline VectorR4 operator-( const VectorR4& u, const VectorR4& v ) +{ + return VectorR4(u.x-v.x, u.y-v.y, u.z-v.z, u.w-v.w); +} +inline VectorR4 operator*( const VectorR4& u, register double m) +{ + return VectorR4( u.x*m, u.y*m, u.z*m, u.w*m ); +} +inline VectorR4 operator*( register double m, const VectorR4& u) +{ + return VectorR4( u.x*m, u.y*m, u.z*m, u.w*m ); +} +inline VectorR4 operator/( const VectorR4& u, double m) +{ + register double mInv = 1.0/m; + return VectorR4( u.x*mInv, u.y*mInv, u.z*mInv, u.w*mInv ); +} + +inline int operator==( const VectorR4& u, const VectorR4& v ) +{ + return ( u.x==v.x && u.y==v.y && u.z==v.z && u.w==v.w ); +} + +inline double operator^ ( const VectorR4& u, const VectorR4& v ) // Dot Product +{ + return ( u.x*v.x + u.y*v.y + u.z*v.z + u.w*v.w ); +} + +inline VectorR4 ArrayProd ( const VectorR4& u, const VectorR4& v ) +{ + return ( VectorR4( u.x*v.x, u.y*v.y, u.z*v.z, u.w*v.w ) ); +} + +inline VectorR4& VectorR4::ArrayProd (const VectorR4& v) // Component-wise Product +{ + x *= v.x; + y *= v.y; + z *= v.z; + w *= v.w; + return ( *this ); +} + +inline VectorR4& VectorR4::ArrayProd3 (const VectorR3& v) // Component-wise Product +{ + x *= v.x; + y *= v.y; + z *= v.z; + return ( *this ); +} + +inline VectorR4& VectorR4::AddScaled( const VectorR4& u, double s ) +{ + x += s*u.x; + y += s*u.y; + z += s*u.z; + w += s*u.w; + return(*this); +} + +inline VectorR4& VectorR4::ReNormalize() // Convert near unit back to unit +{ + double nSq = NormSq(); + register double mFact = 1.0-0.5*(nSq-1.0); // Multiplicative factor + *this *= mFact; + return *this; +} + +inline double NormalizeError (const VectorR4& u) +{ + register double discrepancy; + discrepancy = u.x*u.x + u.y*u.y + u.z*u.z + u.w*u.w - 1.0; + if ( discrepancy < 0.0 ) { + discrepancy = -discrepancy; + } + return discrepancy; +} + +inline VectorR3& VectorR3::SetFromHg(const VectorR4& v) { + double wInv = 1.0/v.w; + x = v.x*wInv; + y = v.y*wInv; + z = v.z*wInv; + return *this; +} + +inline double VectorR4::Dist( const VectorR4& u ) const // Distance from u +{ + return sqrt( DistSq(u) ); +} + +inline double VectorR4::DistSq( const VectorR4& u ) const // Distance from u +{ + return ( (x-u.x)*(x-u.x) + (y-u.y)*(y-u.y) + (z-u.z)*(z-u.z) + (w-u.w)*(w-u.w) ); +} + + +// ********************************************************* +// * Matrix4x4 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ***** + +inline Matrix4x4::Matrix4x4() {} + +inline Matrix4x4::Matrix4x4( const VectorR4& u, const VectorR4& v, + const VectorR4& s, const VectorR4& t) +{ + m11 = u.x; // Column 1 + m21 = u.y; + m31 = u.z; + m41 = u.w; + m12 = v.x; // Column 2 + m22 = v.y; + m32 = v.z; + m42 = v.w; + m13 = s.x; // Column 3 + m23 = s.y; + m33 = s.z; + m43 = s.w; + m14 = t.x; // Column 4 + m24 = t.y; + m34 = t.z; + m44 = t.w; +} + +inline Matrix4x4::Matrix4x4( double a11, double a21, double a31, double a41, + double a12, double a22, double a32, double a42, + double a13, double a23, double a33, double a43, + double a14, double a24, double a34, double a44) + // Values specified in column order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m13 = a13; + m14 = a14; + m21 = a21; // Row 2 + m22 = a22; + m23 = a23; + m24 = a24; + m31 = a31; // Row 3 + m32 = a32; + m33 = a33; + m34 = a34; + m41 = a41; // Row 4 + m42 = a42; + m43 = a43; + m44 = a44; +} + +/* +inline Matrix4x4::Matrix4x4 ( const Matrix4x4& A) + : m11(A.m11), m12(A.m12), m13(A.m13), m14(A.m14), + m21(A.m21), m22(A.m22), m23(A.m23), m24(A.m24), + m31(A.m31), m32(A.m32), m33(A.m33), m34(A.m34), + m41(A.m41), m42(A.m42), m43(A.m43), m44(A.m44) {} */ + +inline void Matrix4x4::SetIdentity ( ) +{ + m11 = m22 = m33 = m44 = 1.0; + m12 = m13 = m14 = m21 = m23 = m24 = m13 = m23 = m41= m42 = m43 = 0.0; +} + +inline void Matrix4x4::Set( const VectorR4& u, const VectorR4& v, + const VectorR4& s, const VectorR4& t ) +{ + m11 = u.x; // Column 1 + m21 = u.y; + m31 = u.z; + m41 = u.w; + m12 = v.x; // Column 2 + m22 = v.y; + m32 = v.z; + m42 = v.w; + m13 = s.x; // Column 3 + m23 = s.y; + m33 = s.z; + m43 = s.w; + m14 = t.x; // Column 4 + m24 = t.y; + m34 = t.z; + m44 = t.w; +} + +inline void Matrix4x4::Set( double a11, double a21, double a31, double a41, + double a12, double a22, double a32, double a42, + double a13, double a23, double a33, double a43, + double a14, double a24, double a34, double a44) + // Values specified in column order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m13 = a13; + m14 = a14; + m21 = a21; // Row 2 + m22 = a22; + m23 = a23; + m24 = a24; + m31 = a31; // Row 3 + m32 = a32; + m33 = a33; + m34 = a34; + m41 = a41; // Row 4 + m42 = a42; + m43 = a43; + m44 = a44; +} + +inline void Matrix4x4::Set ( const Matrix4x4& M ) // Set to the matrix. +{ + m11 = M.m11; + m12 = M.m12; + m13 = M.m13; + m14 = M.m14; + m21 = M.m21; + m22 = M.m22; + m23 = M.m23; + m24 = M.m24; + m31 = M.m31; + m32 = M.m32; + m33 = M.m33; + m34 = M.m34; + m41 = M.m41; + m42 = M.m42; + m43 = M.m43; + m44 = M.m44; +} + +inline void Matrix4x4::SetZero( ) +{ + m11 = m12 = m13 = m14 = m21 = m22 = m23 = m24 + = m31 = m32 = m33 = m34 = m41 = m42 = m43 = m44 = 0.0; +} + +inline void Matrix4x4::SetByRows( const VectorR4& u, const VectorR4& v, + const VectorR4& s, const VectorR4& t ) +{ + m11 = u.x; // Row 1 + m12 = u.y; + m13 = u.z; + m14 = u.w; + m21 = v.x; // Row 2 + m22 = v.y; + m23 = v.z; + m24 = v.w; + m31 = s.x; // Row 3 + m32 = s.y; + m33 = s.z; + m34 = s.w; + m41 = t.x; // Row 4 + m42 = t.y; + m43 = t.z; + m44 = t.w; +} + +inline void Matrix4x4::SetByRows( double a11, double a12, double a13, double a14, + double a21, double a22, double a23, double a24, + double a31, double a32, double a33, double a34, + double a41, double a42, double a43, double a44 ) + // Values specified in row order!!! +{ + m11 = a11; // Row 1 + m12 = a12; + m13 = a13; + m14 = a14; + m21 = a21; // Row 2 + m22 = a22; + m23 = a23; + m24 = a24; + m31 = a31; // Row 3 + m32 = a32; + m33 = a33; + m34 = a34; + m41 = a41; // Row 4 + m42 = a42; + m43 = a43; + m44 = a44; +} + +inline void Matrix4x4::SetColumn1 ( double x, double y, double z, double w) +{ + m11 = x; m21 = y; m31= z; m41 = w; +} + +inline void Matrix4x4::SetColumn2 ( double x, double y, double z, double w) +{ + m12 = x; m22 = y; m32= z; m42 = w; +} + +inline void Matrix4x4::SetColumn3 ( double x, double y, double z, double w) +{ + m13 = x; m23 = y; m33= z; m43 = w; +} + +inline void Matrix4x4::SetColumn4 ( double x, double y, double z, double w) +{ + m14 = x; m24 = y; m34= z; m44 = w; +} + +inline void Matrix4x4::SetColumn1 ( const VectorR4& u ) +{ + m11 = u.x; m21 = u.y; m31 = u.z; m41 = u.w; +} + +inline void Matrix4x4::SetColumn2 ( const VectorR4& u ) +{ + m12 = u.x; m22 = u.y; m32 = u.z; m42 = u.w; +} + +inline void Matrix4x4::SetColumn3 ( const VectorR4& u ) +{ + m13 = u.x; m23 = u.y; m33 = u.z; m43 = u.w; +} + +inline void Matrix4x4::SetColumn4 ( const VectorR4& u ) +{ + m14 = u.x; m24 = u.y; m34 = u.z; m44 = u.w; +} + +VectorR4 Matrix4x4::Column1() const +{ + return ( VectorR4(m11, m21, m31, m41) ); +} + +VectorR4 Matrix4x4::Column2() const +{ + return ( VectorR4(m12, m22, m32, m42) ); +} + +VectorR4 Matrix4x4::Column3() const +{ + return ( VectorR4(m13, m23, m33, m43) ); +} + +VectorR4 Matrix4x4::Column4() const +{ + return ( VectorR4(m14, m24, m34, m44) ); +} + +inline void Matrix4x4::SetDiagonal( double x, double y, + double z, double w) +{ + m11 = x; + m22 = y; + m33 = z; + m44 = w; +} + +inline void Matrix4x4::SetDiagonal( const VectorR4& u ) +{ + SetDiagonal ( u.x, u.y, u.z, u.w ); +} + +inline double Matrix4x4::Diagonal( int i ) +{ + switch (i) { + case 0: + return m11; + case 1: + return m22; + case 2: + return m33; + case 3: + return m44; + default: + assert(0); + return 0.0; + } +} + +inline void Matrix4x4::MakeTranspose() // Transposes it. +{ + register double temp; + temp = m12; + m12 = m21; + m21=temp; + temp = m13; + m13 = m31; + m31 = temp; + temp = m14; + m14 = m41; + m41 = temp; + temp = m23; + m23 = m32; + m32 = temp; + temp = m24; + m24 = m42; + m42 = temp; + temp = m34; + m34 = m43; + m43 = temp; +} + +inline VectorR4 operator* ( const Matrix4x4& A, const VectorR4& u) +{ + VectorR4 ret; + ret.x = A.m11*u.x + A.m12*u.y + A.m13*u.z + A.m14*u.w; + ret.y = A.m21*u.x + A.m22*u.y + A.m23*u.z + A.m24*u.w; + ret.z = A.m31*u.x + A.m32*u.y + A.m33*u.z + A.m34*u.w; + ret.w = A.m41*u.x + A.m42*u.y + A.m43*u.z + A.m44*u.w; + return ret; +} + + +// ****************************************************** +// * LinearMapR4 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +inline LinearMapR4::LinearMapR4() +{ + SetZero(); + return; +} + +inline LinearMapR4::LinearMapR4( const VectorR4& u, const VectorR4& v, + const VectorR4& s, const VectorR4& t) +:Matrix4x4 ( u, v, s ,t ) +{ } + +inline LinearMapR4::LinearMapR4( + double a11, double a21, double a31, double a41, + double a12, double a22, double a32, double a42, + double a13, double a23, double a33, double a43, + double a14, double a24, double a34, double a44) + // Values specified in column order!!! +:Matrix4x4 ( a11, a21, a31, a41, a12, a22, a32, a42, + a13, a23, a33, a43, a14, a24, a34, a44 ) +{ } + +inline LinearMapR4::LinearMapR4 ( const Matrix4x4& A ) +: Matrix4x4 (A) +{} + + +inline LinearMapR4& LinearMapR4::operator+= (const LinearMapR4& B) +{ + m11 += B.m11; + m12 += B.m12; + m13 += B.m13; + m14 += B.m14; + m21 += B.m21; + m22 += B.m22; + m23 += B.m23; + m24 += B.m24; + m31 += B.m31; + m32 += B.m32; + m33 += B.m33; + m34 += B.m34; + m41 += B.m41; + m42 += B.m42; + m43 += B.m43; + m44 += B.m44; + return ( *this ); +} + +inline LinearMapR4& LinearMapR4::operator-= (const LinearMapR4& B) +{ + m11 -= B.m11; + m12 -= B.m12; + m13 -= B.m13; + m14 -= B.m14; + m21 -= B.m21; + m22 -= B.m22; + m23 -= B.m23; + m24 -= B.m24; + m31 -= B.m31; + m32 -= B.m32; + m33 -= B.m33; + m34 -= B.m34; + m41 -= B.m41; + m42 -= B.m42; + m43 -= B.m43; + m44 -= B.m44; + return( *this ); +} + +inline LinearMapR4 operator+ (const LinearMapR4& A, const LinearMapR4& B) +{ + return( LinearMapR4( A.m11+B.m11, A.m21+B.m21, A.m31+B.m31, A.m41+B.m41, + A.m12+B.m12, A.m22+B.m22, A.m32+B.m32, A.m42+B.m42, + A.m13+B.m13, A.m23+B.m23, A.m33+B.m33, A.m43+B.m43, + A.m14+B.m14, A.m24+B.m24, A.m34+B.m34, A.m44+B.m44) ); +} + +inline LinearMapR4 operator- (const LinearMapR4& A) +{ + return( LinearMapR4( -A.m11, -A.m21, -A.m31, -A.m41, + -A.m12, -A.m22, -A.m32, -A.m42, + -A.m13, -A.m23, -A.m33, -A.m43, + -A.m14, -A.m24, -A.m34, -A.m44 ) ); +} + +inline LinearMapR4 operator- (const LinearMapR4& A, const LinearMapR4& B) +{ + return( LinearMapR4( A.m11-B.m11, A.m21-B.m21, A.m31-B.m31, A.m41-B.m41, + A.m12-B.m12, A.m22-B.m22, A.m32-B.m32, A.m42-B.m42, + A.m13-B.m13, A.m23-B.m23, A.m33-B.m33, A.m43-B.m43, + A.m14-B.m14, A.m24-B.m24, A.m34-B.m34, A.m44-B.m44 ) ); +} + +inline LinearMapR4& LinearMapR4::operator*= (register double b) +{ + m11 *= b; + m12 *= b; + m13 *= b; + m14 *= b; + m21 *= b; + m22 *= b; + m23 *= b; + m24 *= b; + m31 *= b; + m32 *= b; + m33 *= b; + m34 *= b; + m41 *= b; + m42 *= b; + m43 *= b; + m44 *= b; + return ( *this); +} + +inline LinearMapR4 operator* ( const LinearMapR4& A, register double b) +{ + return( LinearMapR4( A.m11*b, A.m21*b, A.m31*b, A.m41*b, + A.m12*b, A.m22*b, A.m32*b, A.m42*b, + A.m13*b, A.m23*b, A.m33*b, A.m43*b, + A.m14*b, A.m24*b, A.m34*b, A.m44*b) ); +} + +inline LinearMapR4 operator* ( register double b, const LinearMapR4& A) +{ + return( LinearMapR4( A.m11*b, A.m21*b, A.m31*b, A.m41*b, + A.m12*b, A.m22*b, A.m32*b, A.m42*b, + A.m13*b, A.m23*b, A.m33*b, A.m43*b, + A.m14*b, A.m24*b, A.m34*b, A.m44*b ) ); +} + +inline LinearMapR4 operator/ ( const LinearMapR4& A, double b) +{ + register double bInv = 1.0/b; + return ( A*bInv ); +} + +inline LinearMapR4& LinearMapR4::operator/= (register double b) +{ + register double bInv = 1.0/b; + return ( *this *= bInv ); +} + +inline VectorR4 operator* ( const LinearMapR4& A, const VectorR4& u) +{ + return(VectorR4 ( A.m11*u.x + A.m12*u.y + A.m13*u.z + A.m14*u.w, + A.m21*u.x + A.m22*u.y + A.m23*u.z + A.m24*u.w, + A.m31*u.x + A.m32*u.y + A.m33*u.z + A.m34*u.w, + A.m41*u.x + A.m42*u.y + A.m43*u.z + A.m44*u.w ) ); +} + +inline LinearMapR4 LinearMapR4::Transpose() const // Returns the transpose +{ + return (LinearMapR4( m11, m12, m13, m14, + m21, m22, m23, m24, + m31, m32, m33, m34, + m41, m42, m43, m44 ) ); +} + +inline LinearMapR4& LinearMapR4::operator*= (const Matrix4x4& B) // Matrix product +{ + (*this).Matrix4x4::operator*=(B); + + return( *this ); +} + +inline LinearMapR4 operator* ( const LinearMapR4& A, const Matrix4x4& B) +{ + LinearMapR4 AA(A); + AA.Matrix4x4::operator*=(B); + return AA; +} + +inline LinearMapR4 operator* ( const Matrix4x4& A, const LinearMapR4& B) +{ + LinearMapR4 AA(A); + AA.Matrix4x4::operator*=(B); + return AA; +} + + + +// ****************************************************** +// * RotationMapR4 class - inlined functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * ** + +inline RotationMapR4::RotationMapR4() +{ + SetIdentity(); + return; +} + +inline RotationMapR4::RotationMapR4( const VectorR4& u, const VectorR4& v, + const VectorR4& s, const VectorR4& t) +:Matrix4x4 ( u, v, s ,t ) +{ } + +inline RotationMapR4::RotationMapR4( + double a11, double a21, double a31, double a41, + double a12, double a22, double a32, double a42, + double a13, double a23, double a33, double a43, + double a14, double a24, double a34, double a44) + // Values specified in column order!!! +:Matrix4x4 ( a11, a21, a31, a41, a12, a22, a32, a42, + a13, a23, a33, a43, a14, a24, a34, a44 ) +{ } + +inline RotationMapR4 RotationMapR4::Transpose() const // Returns the transpose +{ + return ( RotationMapR4( m11, m12, m13, m14, + m21, m22, m23, m24, + m31, m32, m33, m34, + m41, m42, m43, m44 ) ); +} + +inline VectorR4 RotationMapR4::Invert(const VectorR4& u) const // Returns solution +{ + return (VectorR4( m11*u.x + m21*u.y + m31*u.z + m41*u.w, + m12*u.x + m22*u.y + m32*u.z + m42*u.w, + m13*u.x + m23*u.y + m33*u.z + m43*u.w, + m14*u.x + m24*u.y + m34*u.z + m44*u.w ) ); +} + +inline RotationMapR4& RotationMapR4::operator*= (const RotationMapR4& B) // Matrix product +{ + (*this).Matrix4x4::operator*=(B); + + return( *this ); +} + +inline RotationMapR4 operator* ( const RotationMapR4& A, const RotationMapR4& B) +{ + RotationMapR4 AA(A); + AA.Matrix4x4::operator*=(B); + return AA; +} + + +// *************************************************************** +// * 4-space vector and matrix utilities (inlined functions) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +inline void TimesTranspose( const VectorR4& u, const VectorR4& v, LinearMapR4& M) +{ + M.Set ( v.x*u.x, v.x*u.y, v.x*u.z, v.x*u.w, // Set by columns! + v.y*u.x, v.y*u.y, v.y*u.z, v.y*u.w, + v.z*u.x, v.z*u.y, v.z*u.z, v.z*u.w, + v.w*u.x, v.w*u.y, v.w*u.z, v.w*u.w ) ; +} + +// Returns the solid angle between vectors u and v (not necessarily unit vectors) +inline double SolidAngle( const VectorR4& u, const VectorR4& v) +{ + double nSqU = u.NormSq(); + double nSqV = v.NormSq(); + if ( nSqU==0.0 && nSqV==0.0 ) { + return (0.0); + } + else { + return ( SolidAngleUnit( u/sqrt(nSqU), v/sqrt(nSqV) ) ); + } +} + +inline double SolidAngleUnit( const VectorR4 u, const VectorR4 v ) +{ + return ( atan2 ( ProjectPerpUnit(v,u).Norm(), u^v ) ); +} + + +#endif // LINEAR_R4_H diff --git a/examples/ThirdPartyLibs/BussIK/MathMisc.h b/examples/ThirdPartyLibs/BussIK/MathMisc.h new file mode 100644 index 000000000..1738753f8 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/MathMisc.h @@ -0,0 +1,384 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + + +#ifndef MATH_MISC_H +#define MATH_MISC_H + +#include + +// +// Commonly used constants +// + +const double PI = 3.1415926535897932384626433832795028841972; +const double PI2 = 2.0*PI; +const double PI4 = 4.0*PI; +const double PISq = PI*PI; +const double PIhalves = 0.5*PI; +const double PIthirds = PI/3.0; +const double PItwothirds = PI2/3.0; +const double PIfourths = 0.25*PI; +const double PIsixths = PI/6.0; +const double PIsixthsSq = PIsixths*PIsixths; +const double PItwelfths = PI/12.0; +const double PItwelfthsSq = PItwelfths*PItwelfths; +const double PIinv = 1.0/PI; +const double PI2inv = 0.5/PI; +const double PIhalfinv = 2.0/PI; + +const double RadiansToDegrees = 180.0/PI; +const double DegreesToRadians = PI/180; + +const double OneThird = 1.0/3.0; +const double TwoThirds = 2.0/3.0; +const double OneSixth = 1.0/6.0; +const double OneEighth = 1.0/8.0; +const double OneTwelfth = 1.0/12.0; + +const double Root2 = sqrt(2.0); +const double Root3 = sqrt(3.0); +const double Root2Inv = 1.0/Root2; // sqrt(2)/2 +const double HalfRoot3 = sqrtf(3)/2.0; + +const double LnTwo = log(2.0); +const double LnTwoInv = 1.0/log(2.0); + +// Special purpose constants +const double OnePlusEpsilon15 = 1.0+1.0e-15; +const double OneMinusEpsilon15 = 1.0-1.0e-15; + +inline double ZeroValue(const double& x) +{ + return 0.0; +} + +// +// Comparisons +// + +template inline T Min ( T x, T y ) +{ + return (x inline T Max ( T x, T y ) +{ + return (y inline T ClampRange ( T x, T min, T max) +{ + if ( xmax ) { + return max; + } + return x; +} + +template inline bool ClampRange ( T *x, T min, T max) +{ + if ( (*x)max ) { + (*x) = max; + return false; + } + else { + return true; + } +} + +template inline bool ClampMin ( T *x, T min) +{ + if ( (*x) inline bool ClampMax ( T *x, T max) +{ + if ( (*x)>max ) { + (*x) = max; + return false; + } + return true; +} + +template inline T& UpdateMin ( const T& x, T& y ) +{ + if ( x inline T& UpdateMax ( const T& x, T& y ) +{ + if ( x>y ) { + y = x; + } + return y; +} + + +template inline bool SameSignNonzero( T x, T y ) +{ + if ( x<0 ) { + return (y<0); + } + else if ( 0 +inline bool NearEqual( T a, T b, double tolerance ) { + a -= b; + return ( Mag(a)<=tolerance ); +} + +inline bool EqualZeroFuzzy( double x ) { + return ( fabs(x)<=1.0e-14 ); +} + +inline bool NearZero( double x, double tolerance ) { + return ( fabs(x)<=tolerance ); +} + +inline bool LessOrEqualFuzzy( double x, double y ) +{ + if ( x <= y ) { + return true; + } + + if ( y > 0.0 ) { + if ( x>0.0 ) { + return ( x*OneMinusEpsilon15 < y*OnePlusEpsilon15 ); + } + else { + return ( y<1.0e-15 ); // x==0 in this case + } + } + else if ( y < 0.0 ) { + if ( x<0.0 ) { + return ( x*OnePlusEpsilon15 < y*OneMinusEpsilon15 ); + } + else { + return ( y>-1.0e-15 ); // x==0 in this case + } + } + else { + return ( -1.0e-15 *maxabs ) { + *maxabs = updateval; + return true; + } + else if ( -updateval > *maxabs ) { + *maxabs = -updateval; + return true; + } + else { + return false; + } +} + +// ********************************************************** +// Combinations and averages. * +// ********************************************************** + +template +void averageOf ( const T& a, const T &b, T&c ) { + c = a; + c += b; + c *= 0.5; +} + +template +void Lerp( const T& a, const T&b, double alpha, T&c ) { + double beta = 1.0-alpha; + if ( beta>alpha ) { + c = b; + c *= alpha/beta; + c += a; + c *= beta; + } + else { + c = a; + c *= beta/alpha; + c += b; + c *= alpha; + } +} + +template +T Lerp( const T& a, const T&b, double alpha ) { + T ret; + Lerp( a, b, alpha, ret ); + return ret; +} + +// ********************************************************** +// Trigonometry * +// ********************************************************** + +// TimesCot(x) returns x*cot(x) +inline double TimesCot ( double x ) { + if ( -1.0e-5 < x && x < 1.0e-5 ) { + return 1.0+x*OneThird; + } + else { + return ( x*cos(x)/sin(x) ); + } +} + +// SineOver(x) returns sin(x)/x. +inline double SineOver( double x ) { + if ( -1.0e-5 < x && x < 1.0e-5 ) { + return 1.0-x*x*OneSixth; + } + else { + return sin(x)/x; + } +} +// OverSine(x) returns x/sin(x). +inline double OverSine( double x ) { + if ( -1.0e-5 < x && x < 1.0e-5 ) { + return 1.0+x*x*OneSixth; + } + else { + return x/sin(x); + } +} + +inline double SafeAsin( double x ) { + if ( x <= -1.0 ) { + return -PIhalves; + } + else if ( x >= 1.0 ) { + return PIhalves; + } + else { + return asin(x); + } +} + +inline double SafeAcos( double x ) { + if ( x <= -1.0 ) { + return PI; + } + else if ( x >= 1.0 ) { + return 0.0; + } + else { + return acos(x); + } +} + + +// ********************************************************************** +// Roots and powers * +// ********************************************************************** + +// Square(x) returns x*x, of course! + +template inline T Square ( T x ) +{ + return (x*x); +} + +// Cube(x) returns x*x*x, of course! + +template inline T Cube ( T x ) +{ + return (x*x*x); +} + +// SafeSqrt(x) = returns sqrt(max(x, 0.0)); + +inline double SafeSqrt( double x ) { + if ( x<=0.0 ) { + return 0.0; + } + else { + return sqrt(x); + } +} + + +// SignedSqrt(a, s) returns (sign(s)*sqrt(a)). +inline double SignedSqrt( double a, double sgn ) +{ + if ( sgn==0.0 ) { + return 0.0; + } + else { + return ( sgn>0.0 ? sqrt(a) : -sqrt(a) ); + } +} + + +// Template version of Sign function + +template inline int Sign( T x) +{ + if ( x<0 ) { + return -1; + } + else if ( x==0 ) { + return 0; + } + else { + return 1; + } +} + + +#endif // #ifndef MATH_MISC_H diff --git a/examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp b/examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp new file mode 100644 index 000000000..365d90f6c --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp @@ -0,0 +1,984 @@ + +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + + +// +// MatrixRmn.cpp: Matrix over reals (Variable dimensional vector) +// +// Not very sophisticated yet. Needs more functionality +// To do: better handling of resizing. +// + +#include "MatrixRmn.h" + +MatrixRmn MatrixRmn::WorkMatrix; // Temporary work matrix + +// Fill the diagonal entries with the value d. The rest of the matrix is unchanged. +void MatrixRmn::SetDiagonalEntries( double d ) +{ + long diagLen = Min( NumRows, NumCols ); + double* dPtr = x; + for ( ; diagLen>0; diagLen-- ) { + *dPtr = d; + dPtr += NumRows+1; + } +} + +// Fill the diagonal entries with values in vector d. The rest of the matrix is unchanged. +void MatrixRmn::SetDiagonalEntries( const VectorRn& d ) +{ + long diagLen = Min( NumRows, NumCols ); + assert ( d.length == diagLen ); + double* dPtr = x; + double* from = d.x; + for ( ; diagLen>0; diagLen-- ) { + *dPtr = *(from++); + dPtr += NumRows+1; + } +} + +// Fill the superdiagonal entries with the value d. The rest of the matrix is unchanged. +void MatrixRmn::SetSuperDiagonalEntries( double d ) +{ + long sDiagLen = Min( NumRows, (long)(NumCols-1) ); + double* to = x + NumRows; + for ( ; sDiagLen>0; sDiagLen-- ) { + *to = d; + to += NumRows+1; + } +} + +// Fill the superdiagonal entries with values in vector d. The rest of the matrix is unchanged. +void MatrixRmn::SetSuperDiagonalEntries( const VectorRn& d ) +{ + long sDiagLen = Min( (long)(NumRows-1), NumCols ); + assert ( sDiagLen == d.length ); + double* to = x + NumRows; + double* from = d.x; + for ( ; sDiagLen>0; sDiagLen-- ) { + *to = *(from++); + to += NumRows+1; + } +} + +// Fill the subdiagonal entries with the value d. The rest of the matrix is unchanged. +void MatrixRmn::SetSubDiagonalEntries( double d ) +{ + long sDiagLen = Min( NumRows, NumCols ) - 1; + double* to = x + 1; + for ( ; sDiagLen>0; sDiagLen-- ) { + *to = d; + to += NumRows+1; + } +} + +// Fill the subdiagonal entries with values in vector d. The rest of the matrix is unchanged. +void MatrixRmn::SetSubDiagonalEntries( const VectorRn& d ) +{ + long sDiagLen = Min( NumRows, NumCols ) - 1; + assert ( sDiagLen == d.length ); + double* to = x + 1; + double* from = d.x; + for ( ; sDiagLen>0; sDiagLen-- ) { + *to = *(from++); + to += NumRows+1; + } +} + +// Set the i-th column equal to d. +void MatrixRmn::SetColumn(long i, const VectorRn& d ) +{ + assert ( NumRows==d.GetLength() ); + double* to = x+i*NumRows; + const double* from = d.x; + for ( i=NumRows; i>0; i-- ) { + *(to++) = *(from++); + } +} + +// Set the i-th column equal to d. +void MatrixRmn::SetRow(long i, const VectorRn& d ) +{ + assert ( NumCols==d.GetLength() ); + double* to = x+i; + const double* from = d.x; + for ( i=NumRows; i>0; i-- ) { + *to = *(from++); + to += NumRows; + } +} + +// Sets a "linear" portion of the array with the values from a vector d +// The first row and column position are given by startRow, startCol. +// Successive positions are found by using the deltaRow, deltaCol values +// to increment the row and column indices. There is no wrapping around. +void MatrixRmn::SetSequence( const VectorRn& d, long startRow, long startCol, long deltaRow, long deltaCol ) +{ + long length = d.length; + assert( startRow>=0 && startRow=0 && startCol=0 && startRow+(length-1)*deltaRow=0 && startCol+(length-1)*deltaCol0; length-- ) { + *to = *(from++); + to += stride; + } +} + +// The matrix A is loaded, in into "this" matrix, based at (0,0). +// The size of "this" matrix must be large enough to accomodate A. +// The rest of "this" matrix is left unchanged. It is not filled with zeroes! + +void MatrixRmn::LoadAsSubmatrix( const MatrixRmn& A ) +{ + assert( A.NumRows<=NumRows && A.NumCols<=NumCols ); + int extraColStep = NumRows - A.NumRows; + double *to = x; + double *from = A.x; + for ( long i=A.NumCols; i>0; i-- ) { // Copy columns of A, one per time thru loop + for ( long j=A.NumRows; j>0; j-- ) { // Copy all elements of this column of A + *(to++) = *(from++); + } + to += extraColStep; + } +} + +// The matrix A is loaded, in transposed order into "this" matrix, based at (0,0). +// The size of "this" matrix must be large enough to accomodate A. +// The rest of "this" matrix is left unchanged. It is not filled with zeroes! +void MatrixRmn::LoadAsSubmatrixTranspose( const MatrixRmn& A ) +{ + assert( A.NumRows<=NumCols && A.NumCols<=NumRows ); + double* rowPtr = x; + double* from = A.x; + for ( long i=A.NumCols; i>0; i-- ) { // Copy columns of A, once per loop + double* to = rowPtr; + for ( long j=A.NumRows; j>0; j-- ) { // Loop copying values from the column of A + *to = *(from++); + to += NumRows; + } + rowPtr ++; + } +} + +// Calculate the Frobenius Norm (square root of sum of squares of entries of the matrix) +double MatrixRmn::FrobeniusNorm() const +{ + return sqrt( FrobeniusNormSq() ); +} + +// Multiply this matrix by column vector v. +// Result is column vector "result" +void MatrixRmn::Multiply( const VectorRn& v, VectorRn& result ) const +{ + assert ( v.GetLength()==NumCols && result.GetLength()==NumRows ); + double* out = result.GetPtr(); // Points to entry in result vector + const double* rowPtr = x; // Points to beginning of next row in matrix + for ( long j = NumRows; j>0; j-- ) { + const double* in = v.GetPtr(); + const double* m = rowPtr++; + *out = 0.0f; + for ( long i = NumCols; i>0; i-- ) { + *out += (*(in++)) * (*m); + m += NumRows; + } + out++; + } +} + +// Multiply transpose of this matrix by column vector v. +// Result is column vector "result" +// Equivalent to mult by row vector on left +void MatrixRmn::MultiplyTranspose( const VectorRn& v, VectorRn& result ) const +{ + assert ( v.GetLength()==NumRows && result.GetLength()==NumCols ); + double* out = result.GetPtr(); // Points to entry in result vector + const double* colPtr = x; // Points to beginning of next column in matrix + for ( long i=NumCols; i>0; i-- ) { + const double* in=v.GetPtr(); + *out = 0.0f; + for ( long j = NumRows; j>0; j-- ) { + *out += (*(in++)) * (*(colPtr++)); + } + out++; + } +} + +// Form the dot product of a vector v with the i-th column of the array +double MatrixRmn::DotProductColumn( const VectorRn& v, long colNum ) const +{ + assert ( v.GetLength()==NumRows ); + double* ptrC = x+colNum*NumRows; + double* ptrV = v.x; + double ret = 0.0; + for ( long i = NumRows; i>0; i-- ) { + ret += (*(ptrC++))*(*(ptrV++)); + } + return ret; +} + +// Add a constant to each entry on the diagonal +MatrixRmn& MatrixRmn::AddToDiagonal( double d ) // Adds d to each diagonal entry +{ + long diagLen = Min( NumRows, NumCols ); + double* dPtr = x; + for ( ; diagLen>0; diagLen-- ) { + *dPtr += d; + dPtr += NumRows+1; + } + return *this; +} + +// Multiply two MatrixRmn's +MatrixRmn& MatrixRmn::Multiply( const MatrixRmn& A, const MatrixRmn& B, MatrixRmn& dst ) +{ + assert( A.NumCols == B.NumRows && A.NumRows == dst.NumRows && B.NumCols == dst.NumCols ); + long length = A.NumCols; + + double *bPtr = B.x; // Points to beginning of column in B + double *dPtr = dst.x; + for ( long i = dst.NumCols; i>0; i-- ) { + double *aPtr = A.x; // Points to beginning of row in A + for ( long j = dst.NumRows; j>0; j-- ) { + *dPtr = DotArray( length, aPtr, A.NumRows, bPtr, 1 ); + dPtr++; + aPtr++; + } + bPtr += B.NumRows; + } + + return dst; +} + +// Multiply two MatrixRmn's, Transpose the first matrix before multiplying +MatrixRmn& MatrixRmn::TransposeMultiply( const MatrixRmn& A, const MatrixRmn& B, MatrixRmn& dst ) +{ + assert( A.NumRows == B.NumRows && A.NumCols == dst.NumRows && B.NumCols == dst.NumCols ); + long length = A.NumRows; + + double *bPtr = B.x; // bPtr Points to beginning of column in B + double *dPtr = dst.x; + for ( long i = dst.NumCols; i>0; i-- ) { // Loop over all columns of dst + double *aPtr = A.x; // aPtr Points to beginning of column in A + for ( long j = dst.NumRows; j>0; j-- ) { // Loop over all rows of dst + *dPtr = DotArray( length, aPtr, 1, bPtr, 1 ); + dPtr ++; + aPtr += A.NumRows; + } + bPtr += B.NumRows; + } + + return dst; +} + +// Multiply two MatrixRmn's. Transpose the second matrix before multiplying +MatrixRmn& MatrixRmn::MultiplyTranspose( const MatrixRmn& A, const MatrixRmn& B, MatrixRmn& dst ) +{ + assert( A.NumCols == B.NumCols && A.NumRows == dst.NumRows && B.NumRows == dst.NumCols ); + long length = A.NumCols; + + double *bPtr = B.x; // Points to beginning of row in B + double *dPtr = dst.x; + for ( long i = dst.NumCols; i>0; i-- ) { + double *aPtr = A.x; // Points to beginning of row in A + for ( long j = dst.NumRows; j>0; j-- ) { + *dPtr = DotArray( length, aPtr, A.NumRows, bPtr, B.NumRows ); + dPtr++; + aPtr++; + } + bPtr++; + } + + return dst; +} + +// Solves the equation (*this)*xVec = b; +// Uses row operations. Assumes *this is square and invertible. +// No error checking for divide by zero or instability (except with asserts) +void MatrixRmn::Solve( const VectorRn& b, VectorRn* xVec ) const +{ + assert ( NumRows==NumCols && NumCols==xVec->GetLength() && NumRows==b.GetLength() ); + + // Copy this matrix and b into an Augmented Matrix + MatrixRmn& AugMat = GetWorkMatrix( NumRows, NumCols+1 ); + AugMat.LoadAsSubmatrix( *this ); + AugMat.SetColumn( NumRows, b ); + + // Put into row echelon form with row operations + AugMat.ConvertToRefNoFree(); + + // Solve for x vector values using back substitution + double* xLast = xVec->x+NumRows-1; // Last entry in xVec + double* endRow = AugMat.x+NumRows*NumCols-1; // Last entry in the current row of the coefficient part of Augmented Matrix + double* bPtr = endRow+NumRows; // Last entry in augmented matrix (end of last column, in augmented part) + for ( long i = NumRows; i>0; i-- ) { + double accum = *(bPtr--); + // Next loop computes back substitution terms + double* rowPtr = endRow; // Points to entries of the current row for back substitution. + double* xPtr = xLast; // Points to entries in the x vector (also for back substitution) + for ( long j=NumRows-i; j>0; j-- ) { + accum -= (*rowPtr)*(*(xPtr--)); + rowPtr -= NumCols; // Previous entry in the row + } + assert( *rowPtr != 0.0 ); // Are not supposed to be any free variables in this matrix + *xPtr = accum/(*rowPtr); + endRow--; + } +} + +// ConvertToRefNoFree +// Converts the matrix (in place) to row echelon form +// For us, row echelon form allows any non-zero values, not just 1's, in the +// position for a lead variable. +// The "NoFree" version operates on the assumption that no free variable will be found. +// Algorithm uses row operations and row pivoting (only). +// Augmented matrix is correctly accomodated. Only the first square part participates +// in the main work of row operations. +void MatrixRmn::ConvertToRefNoFree() +{ + // Loop over all columns (variables) + // Find row with most non-zero entry. + // Swap to the highest active row + // Subtract appropriately from all the lower rows (row op of type 3) + long numIters = Min(NumRows,NumCols); + double* rowPtr1 = x; + const long diagStep = NumRows+1; + long lenRowLeft = NumCols; + for ( ; numIters>1; numIters-- ) { + // Find row with most non-zero entry. + double* rowPtr2 = rowPtr1; + double maxAbs = fabs(*rowPtr1); + double *rowPivot = rowPtr1; + long i; + for ( i=numIters-1; i>0; i-- ) { + const double& newMax = *(++rowPivot); + if ( newMax > maxAbs ) { + maxAbs = *rowPivot; + rowPtr2 = rowPivot; + } + else if ( -newMax > maxAbs ) { + maxAbs = -newMax; + rowPtr2 = rowPivot; + } + } + // Pivot step: Swap the row with highest entry to the current row + if ( rowPtr1 != rowPtr2 ) { + double *to = rowPtr1; + for ( long i=lenRowLeft; i>0; i-- ) { + double temp = *to; + *to = *rowPtr2; + *rowPtr2 = temp; + to += NumRows; + rowPtr2 += NumRows; + } + } + // Subtract this row appropriately from all the lower rows (row operation of type 3) + rowPtr2 = rowPtr1; + for ( i=numIters-1; i>0; i-- ) { + rowPtr2++; + double* to = rowPtr2; + double* from = rowPtr1; + assert( *from != 0.0 ); + double alpha = (*to)/(*from); + *to = 0.0; + for ( long j=lenRowLeft-1; j>0; j-- ) { + to += NumRows; + from += NumRows; + *to -= (*from)*alpha; + } + } + // Update for next iteration of loop + rowPtr1 += diagStep; + lenRowLeft--; + } + +} + +// Calculate the c=cosine and s=sine values for a Givens transformation. +// The matrix M = ( (c, -s), (s, c) ) in row order transforms the +// column vector (a, b)^T to have y-coordinate zero. +void MatrixRmn::CalcGivensValues( double a, double b, double *c, double *s ) +{ + double denomInv = sqrt(a*a + b*b); + if ( denomInv==0.0 ) { + *c = 1.0; + *s = 0.0; + } + else { + denomInv = 1.0/denomInv; + *c = a*denomInv; + *s = -b*denomInv; + } +} + +// Applies Givens transform to columns i and i+1. +// Equivalent to postmultiplying by the matrix +// ( c -s ) +// ( s c ) +// with non-zero entries in rows i and i+1 and columns i and i+1 +void MatrixRmn::PostApplyGivens( double c, double s, long idx ) +{ + assert ( 0<=idx && idx0; i-- ) { + double temp = *colA; + *colA = (*colA)*c + (*colB)*s; + *colB = (*colB)*c - temp*s; + colA++; + colB++; + } +} + +// Applies Givens transform to columns idx1 and idx2. +// Equivalent to postmultiplying by the matrix +// ( c -s ) +// ( s c ) +// with non-zero entries in rows idx1 and idx2 and columns idx1 and idx2 +void MatrixRmn::PostApplyGivens( double c, double s, long idx1, long idx2 ) +{ + assert ( idx1!=idx2 && 0<=idx1 && idx10; i-- ) { + double temp = *colA; + *colA = (*colA)*c + (*colB)*s; + *colB = (*colB)*c - temp*s; + colA++; + colB++; + } +} + + +// ******************************************************************************************** +// Singular value decomposition. +// Return othogonal matrices U and V and diagonal matrix with diagonal w such that +// (this) = U * Diag(w) * V^T (V^T is V-transpose.) +// Diagonal entries have all non-zero entries before all zero entries, but are not +// necessarily sorted. (Someday, I will write ComputedSortedSVD that handles +// sorting the eigenvalues by magnitude.) +// ******************************************************************************************** +void MatrixRmn::ComputeSVD( MatrixRmn& U, VectorRn& w, MatrixRmn& V ) const +{ + assert ( U.NumRows==NumRows && V.NumCols==NumCols + && U.NumRows==U.NumCols && V.NumRows==V.NumCols + && w.GetLength()==Min(NumRows,NumCols) ); + + double temp=0.0; + VectorRn& superDiag = VectorRn::GetWorkVector( w.GetLength()-1 ); // Some extra work space. Will get passed around. + + // Choose larger of U, V to hold intermediate results + // If U is larger than V, use U to store intermediate results + // Otherwise use V. In the latter case, we form the SVD of A transpose, + // (which is essentially identical to the SVD of A). + MatrixRmn* leftMatrix; + MatrixRmn* rightMatrix; + if ( NumRows >= NumCols ) { + U.LoadAsSubmatrix( *this ); // Copy A into U + leftMatrix = &U; + rightMatrix = &V; + } + else { + V.LoadAsSubmatrixTranspose( *this ); // Copy A-transpose into V + leftMatrix = &V; + rightMatrix = &U; + } + + // Do the actual work to calculate the SVD + // Now matrix has at least as many rows as columns + CalcBidiagonal( *leftMatrix, *rightMatrix, w, superDiag ); + ConvertBidiagToDiagonal( *leftMatrix, *rightMatrix, w, superDiag ); + +} + +// ************************************************ CalcBidiagonal ************************** +// Helper routine for SVD computation +// U is a matrix to be bidiagonalized. +// On return, U and V are orthonormal and w holds the new diagonal +// elements and superDiag holds the super diagonal elements. + +void MatrixRmn::CalcBidiagonal( MatrixRmn& U, MatrixRmn& V, VectorRn& w, VectorRn& superDiag ) +{ + assert ( U.NumRows>=V.NumRows ); + + // The diagonal and superdiagonal entries of the bidiagonalized + // version of the U matrix + // are stored in the vectors w and superDiag (temporarily). + + // Apply Householder transformations to U. + // Householder transformations come in pairs. + // First, on the left, we map a portion of a column to zeros + // Second, on the right, we map a portion of a row to zeros + const long rowStep = U.NumCols; + const long diagStep = U.NumCols+1; + double *diagPtr = U.x; + double* wPtr = w.x; + double* superDiagPtr = superDiag.x; + long colLengthLeft = U.NumRows; + long rowLengthLeft = V.NumCols; + while (true) { + // Apply a Householder xform on left to zero part of a column + SvdHouseholder( diagPtr, colLengthLeft, rowLengthLeft, 1, rowStep, wPtr ); + + if ( rowLengthLeft==2 ) { + *superDiagPtr = *(diagPtr+rowStep); + break; + } + // Apply a Householder xform on the right to zero part of a row + SvdHouseholder( diagPtr+rowStep, rowLengthLeft-1, colLengthLeft, rowStep, 1, superDiagPtr ); + + rowLengthLeft--; + colLengthLeft--; + diagPtr += diagStep; + wPtr++; + superDiagPtr++; + } + + int extra = 0; + diagPtr += diagStep; + wPtr++; + if ( colLengthLeft > 2 ) { + extra = 1; + // Do one last Householder transformation when the matrix is not square + colLengthLeft--; + SvdHouseholder( diagPtr, colLengthLeft, 1, 1, 0, wPtr ); + } + else { + *wPtr = *diagPtr; + } + + // Form U and V from the Householder transformations + V.ExpandHouseholders( V.NumCols-2, 1, U.x+U.NumRows, U.NumRows, 1 ); + U.ExpandHouseholders( V.NumCols-1+extra, 0, U.x, 1, U.NumRows ); + + // Done with bidiagonalization + return; +} + +// Helper routine for CalcBidiagonal +// Performs a series of Householder transformations on a matrix +// Stores results compactly into the matrix: The Householder vector u (normalized) +// is stored into the first row/column being transformed. +// The leading term of that row (= plus/minus its magnitude is returned +// separately into "retFirstEntry" +void MatrixRmn::SvdHouseholder( double* basePt, + long colLength, long numCols, long colStride, long rowStride, + double* retFirstEntry ) +{ + + // Calc norm of vector u + double* cPtr = basePt; + double norm = 0.0; + long i; + for ( i=colLength; i>0 ; i-- ) { + norm += Square( *cPtr ); + cPtr += colStride; + } + norm = sqrt(norm); // Norm of vector to reflect to axis e_1 + + // Handle sign issues + double imageVal; // Choose sign to maximize distance + if ( (*basePt) < 0.0 ) { + imageVal = norm; + norm = 2.0*norm*(norm-(*basePt)); + } + else { + imageVal = -norm; + norm = 2.0*norm*(norm+(*basePt)); + } + norm = sqrt(norm); // Norm is norm of reflection vector + + if ( norm==0.0 ) { // If the vector being transformed is equal to zero + // Force to zero in case of roundoff errors + cPtr = basePt; + for ( i=colLength; i>0; i-- ) { + *cPtr = 0.0; + cPtr += colStride; + } + *retFirstEntry = 0.0; + return; + } + + *retFirstEntry = imageVal; + + // Set up the normalized Householder vector + *basePt -= imageVal; // First component changes. Rest stay the same. + // Normalize the vector + norm = 1.0/norm; // Now it is the inverse norm + cPtr = basePt; + for ( i=colLength; i>0 ; i-- ) { + *cPtr *= norm; + cPtr += colStride; + } + + // Transform the rest of the U matrix with the Householder transformation + double *rPtr = basePt; + for ( long j=numCols-1; j>0; j-- ) { + rPtr += rowStride; + // Calc dot product with Householder transformation vector + double dotP = DotArray( colLength, basePt, colStride, rPtr, colStride ); + // Transform with I - 2*dotP*(Householder vector) + AddArrayScale( colLength, basePt, colStride, rPtr, colStride, -2.0*dotP ); + } +} + +// ********************************* ExpandHouseholders ******************************************** +// The matrix will be square. +// numXforms = number of Householder transformations to concatenate +// Each Householder transformation is represented by a unit vector +// Each successive Householder transformation starts one position later +// and has one more implied leading zero +// basePt = beginning of the first Householder transform +// colStride, rowStride: Householder xforms are stored in "columns" +// numZerosSkipped is the number of implicit zeros on the front each +// Householder transformation vector (only values supported are 0 and 1). +void MatrixRmn::ExpandHouseholders( long numXforms, int numZerosSkipped, const double* basePt, long colStride, long rowStride ) +{ + // Number of applications of the last Householder transform + // (That are not trivial!) + long numToTransform = NumCols-numXforms+1-numZerosSkipped; + assert( numToTransform>0 ); + + if ( numXforms==0 ) { + SetIdentity(); + return; + } + + // Handle the first one separately as a special case, + // "this" matrix will be treated to simulate being preloaded with the identity + long hDiagStride = rowStride+colStride; + const double* hBase = basePt + hDiagStride*(numXforms-1); // Pointer to the last Householder vector + const double* hDiagPtr = hBase + colStride*(numToTransform-1); // Pointer to last entry in that vector + long i; + double* diagPtr = x+NumCols*NumRows-1; // Last entry in matrix (points to diagonal entry) + double* colPtr = diagPtr-(numToTransform-1); // Pointer to column in matrix + for ( i=numToTransform; i>0; i-- ) { + CopyArrayScale( numToTransform, hBase, colStride, colPtr, 1, -2.0*(*hDiagPtr) ); + *diagPtr += 1.0; // Add back in 1 to the diagonal entry (since xforming the identity) + diagPtr -= (NumRows+1); // Next diagonal entry in this matrix + colPtr -= NumRows; // Next column in this matrix + hDiagPtr -= colStride; + } + + // Now handle the general case + // A row of zeros must be in effect added to the top of each old column (in each loop) + double* colLastPtr = x + NumRows*NumCols - numToTransform - 1; + for ( i = numXforms-1; i>0; i-- ) { + numToTransform++; // Number of non-trivial applications of this Householder transformation + hBase -= hDiagStride; // Pointer to the beginning of the Householder transformation + colPtr = colLastPtr; + for ( long j = numToTransform-1; j>0; j-- ) { + // Get dot product + double dotProd2N = -2.0*DotArray( numToTransform-1, hBase+colStride, colStride, colPtr+1, 1 ); + *colPtr = dotProd2N*(*hBase); // Adding onto zero at initial point + AddArrayScale( numToTransform-1, hBase+colStride, colStride, colPtr+1, 1, dotProd2N ); + colPtr -= NumRows; + } + // Do last one as a special case (may overwrite the Householder vector) + CopyArrayScale( numToTransform, hBase, colStride, colPtr, 1, -2.0*(*hBase) ); + *colPtr += 1.0; // Add back one one as identity + // Done with this Householder transformation + colLastPtr --; + } + + if ( numZerosSkipped!=0 ) { + assert( numZerosSkipped==1 ); + // Fill first row and column with identity (More generally: first numZerosSkipped many rows and columns) + double* d = x; + *d = 1; + double* d2 = d; + for ( i=NumRows-1; i>0; i-- ) { + *(++d) = 0; + *(d2+=NumRows) = 0; + } + } +} + +// **************** ConvertBidiagToDiagonal *********************************************** +// Do the iterative transformation from bidiagonal form to diagonal form using +// Givens transformation. (Golub-Reinsch) +// U and V are square. Size of U less than or equal to that of U. +void MatrixRmn::ConvertBidiagToDiagonal( MatrixRmn& U, MatrixRmn& V, VectorRn& w, VectorRn& superDiag ) const +{ + // These two index into the last bidiagonal block (last in the matrix, it will be + // first one handled. + long lastBidiagIdx = V.NumRows-1; + long firstBidiagIdx = 0; + double eps = 1.0e-15 * Max(w.MaxAbs(), superDiag.MaxAbs()); + + while ( true ) { + bool workLeft = UpdateBidiagIndices( &firstBidiagIdx, &lastBidiagIdx, w, superDiag, eps ); + if ( !workLeft ) { + break; + } + + // Get ready for first Givens rotation + // Push non-zero to M[2,1] with Givens transformation + double* wPtr = w.x+firstBidiagIdx; + double* sdPtr = superDiag.x+firstBidiagIdx; + double extraOffDiag=0.0; + if ( (*wPtr)==0.0 ) { + ClearRowWithDiagonalZero( firstBidiagIdx, lastBidiagIdx, U, wPtr, sdPtr, eps ); + if ( firstBidiagIdx>0 ) { + if ( NearZero( *(--sdPtr), eps ) ) { + *sdPtr = 0.0; + } + else { + ClearColumnWithDiagonalZero( firstBidiagIdx, V, wPtr, sdPtr, eps ); + } + } + continue; + } + + // Estimate an eigenvalue from bottom four entries of M + // This gives a lambda value which will shift the Givens rotations + // Last four entries of M^T * M are ( ( A, B ), ( B, C ) ). + double A; + A = (firstBidiagIdx C ) { + lambda = -lambda; + } + lambda += (A+C)*0.5; // Now lambda equals the estimate for the last eigenvalue + double t11 = Square(w[firstBidiagIdx]); + double t12 = w[firstBidiagIdx]*superDiag[firstBidiagIdx]; + + double c, s; + CalcGivensValues( t11-lambda, t12, &c, &s ); + ApplyGivensCBTD( c, s, wPtr, sdPtr, &extraOffDiag, wPtr+1 ); + V.PostApplyGivens( c, -s, firstBidiagIdx ); + long i; + for ( i=firstBidiagIdx; i 0 ) { + if ( NearZero( *wPtr, eps ) ) { // If this diagonal entry (near) zero + *wPtr = 0.0; + break; + } + if ( NearZero(*(--sdPtr), eps) ) { // If the entry above the diagonal entry is (near) zero + *sdPtr = 0.0; + break; + } + wPtr--; + firstIdx--; + } + *firstBidiagIdx = firstIdx; + return true; +} + + +// ******************************************DEBUG STUFFF + +bool MatrixRmn::DebugCheckSVD( const MatrixRmn& U, const VectorRn& w, const MatrixRmn& V ) const +{ + // Special SVD test code + + MatrixRmn IV( V.GetNumRows(), V.GetNumColumns() ); + IV.SetIdentity(); + MatrixRmn VTV( V.GetNumRows(), V.GetNumColumns() ); + MatrixRmn::TransposeMultiply( V, V, VTV ); + IV -= VTV; + double error = IV.FrobeniusNorm(); + + MatrixRmn IU( U.GetNumRows(), U.GetNumColumns() ); + IU.SetIdentity(); + MatrixRmn UTU( U.GetNumRows(), U.GetNumColumns() ); + MatrixRmn::TransposeMultiply( U, U, UTU ); + IU -= UTU; + error += IU.FrobeniusNorm(); + + MatrixRmn Diag( U.GetNumRows(), V.GetNumRows() ); + Diag.SetZero(); + Diag.SetDiagonalEntries( w ); + MatrixRmn B(U.GetNumRows(), V.GetNumRows() ); + MatrixRmn C(U.GetNumRows(), V.GetNumRows() ); + MatrixRmn::Multiply( U, Diag, B ); + MatrixRmn::MultiplyTranspose( B, V, C ); + C -= *this; + error += C.FrobeniusNorm(); + + bool ret = ( fabs(error)<=1.0e-13*w.MaxAbs() ); + assert ( ret ); + return ret; +} + +bool MatrixRmn::DebugCalcBidiagCheck( const MatrixRmn& U, const VectorRn& w, const VectorRn& superDiag, const MatrixRmn& V ) const +{ + // Special SVD test code + + MatrixRmn IV( V.GetNumRows(), V.GetNumColumns() ); + IV.SetIdentity(); + MatrixRmn VTV( V.GetNumRows(), V.GetNumColumns() ); + MatrixRmn::TransposeMultiply( V, V, VTV ); + IV -= VTV; + double error = IV.FrobeniusNorm(); + + MatrixRmn IU( U.GetNumRows(), U.GetNumColumns() ); + IU.SetIdentity(); + MatrixRmn UTU( U.GetNumRows(), U.GetNumColumns() ); + MatrixRmn::TransposeMultiply( U, U, UTU ); + IU -= UTU; + error += IU.FrobeniusNorm(); + + MatrixRmn DiagAndSuper( U.GetNumRows(), V.GetNumRows() ); + DiagAndSuper.SetZero(); + DiagAndSuper.SetDiagonalEntries( w ); + if ( this->GetNumRows()>=this->GetNumColumns() ) { + DiagAndSuper.SetSequence( superDiag, 0, 1, 1, 1 ); + } + else { + DiagAndSuper.SetSequence( superDiag, 1, 0, 1, 1 ); + } + MatrixRmn B(U.GetNumRows(), V.GetNumRows() ); + MatrixRmn C(U.GetNumRows(), V.GetNumRows() ); + MatrixRmn::Multiply( U, DiagAndSuper, B ); + MatrixRmn::MultiplyTranspose( B, V, C ); + C -= *this; + error += C.FrobeniusNorm(); + + bool ret = ( fabs(error)<1.0e-13*Max(w.MaxAbs(),superDiag.MaxAbs()) ); + assert ( ret ); + return ret; +} + diff --git a/examples/ThirdPartyLibs/BussIK/MatrixRmn.h b/examples/ThirdPartyLibs/BussIK/MatrixRmn.h new file mode 100644 index 000000000..544dd921e --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/MatrixRmn.h @@ -0,0 +1,402 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + + +// +// MatrixRmn: Matrix over reals (Variable dimensional vector) +// +// Not very sophisticated yet. Needs more functionality +// To do: better handling of resizing. +// + +#ifndef MATRIX_RMN_H +#define MATRIX_RMN_H + +#include +#include +#include "LinearR3.h" +#include "VectorRn.h" + +class MatrixRmn { + +public: + MatrixRmn(); // Null constructor + MatrixRmn( long numRows, long numCols ); // Constructor with length + ~MatrixRmn(); // Destructor + + void SetSize( long numRows, long numCols ); + long GetNumRows() const { return NumRows; } + long GetNumColumns() const { return NumCols; } + void SetZero(); + + // Return entry in row i and column j. + double Get( long i, long j ) const; + void GetTriple( long i, long j, VectorR3 *retValue ) const; + + // Use GetPtr to get pointer into the array (efficient) + // Is friendly in that anyone can change the array contents (be careful!) + // The entries are in column order!!! + // Use this with care. You may call GetRowStride and GetColStride to navigate + // within the matrix. I do not expect these values to ever change. + const double* GetPtr() const; + double* GetPtr(); + const double* GetPtr( long i, long j ) const; + double* GetPtr( long i, long j ); + const double* GetColumnPtr( long j ) const; + double* GetColumnPtr( long j ); + const double* GetRowPtr( long i ) const; + double* GetRowPtr( long i ); + long GetRowStride() const { return NumRows; } // Step size (stride) along a row + long GetColStride() const { return 1; } // Step size (stide) along a column + + void Set( long i, long j, double val ); + void SetTriple( long i, long c, const VectorR3& u ); + + void SetIdentity(); + void SetDiagonalEntries( double d ); + void SetDiagonalEntries( const VectorRn& d ); + void SetSuperDiagonalEntries( double d ); + void SetSuperDiagonalEntries( const VectorRn& d ); + void SetSubDiagonalEntries( double d ); + void SetSubDiagonalEntries( const VectorRn& d ); + void SetColumn(long i, const VectorRn& d ); + void SetRow(long i, const VectorRn& d ); + void SetSequence( const VectorRn& d, long startRow, long startCol, long deltaRow, long deltaCol ); + + // Loads matrix in as a sub-matrix. (i,j) is the base point. Defaults to (0,0). + // The "Tranpose" versions load the transpose of A. + void LoadAsSubmatrix( const MatrixRmn& A ); + void LoadAsSubmatrix( long i, long j, const MatrixRmn& A ); + void LoadAsSubmatrixTranspose( const MatrixRmn& A ); + void LoadAsSubmatrixTranspose( long i, long j, const MatrixRmn& A ); + + // Norms + double FrobeniusNormSq() const; + double FrobeniusNorm() const; + + // Operations on VectorRn's + void Multiply( const VectorRn& v, VectorRn& result ) const; // result = (this)*(v) + void MultiplyTranspose( const VectorRn& v, VectorRn& result ) const; // Equivalent to mult by row vector on left + double DotProductColumn( const VectorRn& v, long colNum ) const; // Returns dot product of v with i-th column + + // Operations on MatrixRmn's + MatrixRmn& operator*=( double ); + MatrixRmn& operator/=( double d ) { assert(d!=0.0); *this *= (1.0/d); return *this; } + MatrixRmn& AddScaled( const MatrixRmn& B, double factor ); + MatrixRmn& operator+=( const MatrixRmn& B ); + MatrixRmn& operator-=( const MatrixRmn& B ); + static MatrixRmn& Multiply( const MatrixRmn& A, const MatrixRmn& B, MatrixRmn& dst ); // Sets dst = A*B. + static MatrixRmn& MultiplyTranspose( const MatrixRmn& A, const MatrixRmn& B, MatrixRmn& dst ); // Sets dst = A*(B-tranpose). + static MatrixRmn& TransposeMultiply( const MatrixRmn& A, const MatrixRmn& B, MatrixRmn& dst ); // Sets dst = (A-transpose)*B. + + // Miscellaneous operation + MatrixRmn& AddToDiagonal( double d ); // Adds d to each diagonal + + // Solving systems of linear equations + void Solve( const VectorRn& b, VectorRn* x ) const; // Solves the equation (*this)*x = b; Uses row operations. Assumes *this is invertible. + + // Row Echelon Form and Reduced Row Echelon Form routines + // Row echelon form here allows non-negative entries (instead of 1's) in the positions of lead variables. + void ConvertToRefNoFree(); // Converts the matrix in place to row echelon form -- assumption is no free variables will be found + void ConvertToRef( int numVars); // Converts the matrix in place to row echelon form -- numVars is number of columns to work with. + void ConvertToRef( int numVars, double eps); // Same, but eps is the measure of closeness to zero + + // Givens transformation + static void CalcGivensValues( double a, double b, double *c, double *s ); + void PostApplyGivens( double c, double s, long idx ); // Applies Givens transform to columns idx and idx+1. + void PostApplyGivens( double c, double s, long idx1, long idx2 ); // Applies Givens transform to columns idx1 and idx2. + + // Singular value decomposition + void ComputeSVD( MatrixRmn& U, VectorRn& w, MatrixRmn& V ) const; + // Good for debugging SVD computations (I recommend this be used for any new application to check for bugs/instability). + bool DebugCheckSVD( const MatrixRmn& U, const VectorRn& w, const MatrixRmn& V ) const; + + // Some useful routines for experts who understand the inner workings of these classes. + inline static double DotArray( long length, const double* ptrA, long strideA, const double* ptrB, long strideB ); + inline static void CopyArrayScale( long length, const double* from, long fromStride, double *to, long toStride, double scale ); + inline static void AddArrayScale( long length, const double* from, long fromStride, double *to, long toStride, double scale ); + +private: + long NumRows; // Number of rows + long NumCols; // Number of columns + double *x; // Array of vector entries - stored in column order + long AllocSize; // Allocated size of the x array + + static MatrixRmn WorkMatrix; // Temporary work matrix + static MatrixRmn& GetWorkMatrix() { return WorkMatrix; } + static MatrixRmn& GetWorkMatrix(long numRows, long numCols) { WorkMatrix.SetSize( numRows, numCols ); return WorkMatrix; } + + // Internal helper routines for SVD calculations + static void CalcBidiagonal( MatrixRmn& U, MatrixRmn& V, VectorRn& w, VectorRn& superDiag ); + void ConvertBidiagToDiagonal( MatrixRmn& U, MatrixRmn& V, VectorRn& w, VectorRn& superDiag ) const; + static void SvdHouseholder( double* basePt, + long colLength, long numCols, long colStride, long rowStride, + double* retFirstEntry ); + void ExpandHouseholders( long numXforms, int numZerosSkipped, const double* basePt, long colStride, long rowStride ); + static bool UpdateBidiagIndices( long *firstDiagIdx, long *lastBidiagIdx, VectorRn& w, VectorRn& superDiag, double eps ); + static void ApplyGivensCBTD( double cosine, double sine, double *a, double *b, double *c, double *d ); + static void ApplyGivensCBTD( double cosine, double sine, double *a, double *b, double *c, + double d, double *e, double *f ); + static void ClearRowWithDiagonalZero( long firstBidiagIdx, long lastBidiagIdx, + MatrixRmn& U, double *wPtr, double *sdPtr, double eps ); + static void ClearColumnWithDiagonalZero( long endIdx, MatrixRmn& V, double *wPtr, double *sdPtr, double eps ); + bool DebugCalcBidiagCheck( const MatrixRmn& U, const VectorRn& w, const VectorRn& superDiag, const MatrixRmn& V ) const; +}; + +inline MatrixRmn::MatrixRmn() +{ + NumRows = 0; + NumCols = 0; + x = 0; + AllocSize = 0; +} + +inline MatrixRmn::MatrixRmn( long numRows, long numCols ) +{ + NumRows = 0; + NumCols = 0; + x = 0; + AllocSize = 0; + SetSize( numRows, numCols ); +} + +inline MatrixRmn::~MatrixRmn() +{ + delete x; +} + +// Resize. +// If the array space is decreased, the information about the allocated length is lost. +inline void MatrixRmn::SetSize( long numRows, long numCols ) +{ + assert ( numRows>0 && numCols>0 ); + long newLength = numRows*numCols; + if ( newLength>AllocSize ) { + delete x; + AllocSize = Max(newLength, AllocSize<<1); + x = new double[AllocSize]; + } + NumRows = numRows; + NumCols = numCols; +} + +// Zero out the entire vector +inline void MatrixRmn::SetZero() +{ + double* target = x; + for ( long i=NumRows*NumCols; i>0; i-- ) { + *(target++) = 0.0; + } +} + +// Return entry in row i and column j. +inline double MatrixRmn::Get( long i, long j ) const { + assert ( iLoad( x+j*NumRows + ii ); +} + +// Get a pointer to the (0,0) entry. +// The entries are in column order. +// This version gives read-only pointer +inline const double* MatrixRmn::GetPtr( ) const +{ + return x; +} + +// Get a pointer to the (0,0) entry. +// The entries are in column order. +inline double* MatrixRmn::GetPtr( ) +{ + return x; +} + +// Get a pointer to the (i,j) entry. +// The entries are in column order. +// This version gives read-only pointer +inline const double* MatrixRmn::GetPtr( long i, long j ) const +{ + assert ( 0<=i && i0; i-- ) { + (*(aPtr++)) *= mult; + } + return (*this); +} + +inline MatrixRmn& MatrixRmn::AddScaled( const MatrixRmn& B, double factor ) +{ + assert (NumRows==B.NumRows && NumCols==B.NumCols); + double* aPtr = x; + double* bPtr = B.x; + for ( long i=NumRows*NumCols; i>0; i-- ) { + (*(aPtr++)) += (*(bPtr++))*factor; + } + return (*this); +} + +inline MatrixRmn& MatrixRmn::operator+=( const MatrixRmn& B ) +{ + assert (NumRows==B.NumRows && NumCols==B.NumCols); + double* aPtr = x; + double* bPtr = B.x; + for ( long i=NumRows*NumCols; i>0; i-- ) { + (*(aPtr++)) += *(bPtr++); + } + return (*this); +} + +inline MatrixRmn& MatrixRmn::operator-=( const MatrixRmn& B ) +{ + assert (NumRows==B.NumRows && NumCols==B.NumCols); + double* aPtr = x; + double* bPtr = B.x; + for ( long i=NumRows*NumCols; i>0; i-- ) { + (*(aPtr++)) -= *(bPtr++); + } + return (*this); +} + +inline double MatrixRmn::FrobeniusNormSq() const +{ + double* aPtr = x; + double result = 0.0; + for ( long i=NumRows*NumCols; i>0; i-- ) { + result += Square( *(aPtr++) ); + } + return result; +} + +// Helper routine to calculate dot product +inline double MatrixRmn::DotArray( long length, const double* ptrA, long strideA, const double* ptrB, long strideB ) +{ + double result = 0.0; + for ( ; length>0 ; length-- ) { + result += (*ptrA)*(*ptrB); + ptrA += strideA; + ptrB += strideB; + } + return result; +} + +// Helper routine: copies and scales an array (src and dest may be equal, or overlap) +inline void MatrixRmn::CopyArrayScale( long length, const double* from, long fromStride, double *to, long toStride, double scale ) +{ + for ( ; length>0; length-- ) { + *to = (*from)*scale; + from += fromStride; + to += toStride; + } +} + +// Helper routine: adds a scaled array +// fromArray = toArray*scale. +inline void MatrixRmn::AddArrayScale( long length, const double* from, long fromStride, double *to, long toStride, double scale ) +{ + for ( ; length>0; length-- ) { + *to += (*from)*scale; + from += fromStride; + to += toStride; + } +} + + + +#endif MATRIX_RMN_H \ No newline at end of file diff --git a/examples/ThirdPartyLibs/BussIK/Misc.cpp b/examples/ThirdPartyLibs/BussIK/Misc.cpp new file mode 100644 index 000000000..03f34812b --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/Misc.cpp @@ -0,0 +1,346 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + +#include +#include "LinearR3.h" + +#include "../OpenGLWindow/OpenGLInclude.h" + +/**************************************************************** + Axes +*****************************************************************/ +static float xx[] = { + 0., 1., 0., 1. + }; + +static float xy[] = { + -.5, .5, .5, -.5 + }; + +static int xorder[] = { + 1, 2, -3, 4 + }; + + +static float yx[] = { + 0., 0., -.5, .5 + }; + +static float yy[] = { + 0.f, .6f, 1.f, 1.f + }; + +static int yorder[] = { + 1, 2, 3, -2, 4 + }; + + +static float zx[] = { + 1., 0., 1., 0., .25, .75 + }; + +static float zy[] = { + .5, .5, -.5, -.5, 0., 0. + }; + +static int zorder[] = { + 1, 2, 3, 4, -5, 6 + }; + +#define LENFRAC 0.10 +#define BASEFRAC 1.10 + +void Axes( float length ) +{ + int i, j; /* counters */ + float fact; /* character scale factor */ + float base; /* character start location */ + + glBegin( GL_LINE_STRIP ); + glVertex3f( length, 0., 0. ); + glVertex3f( 0., 0., 0. ); + glVertex3f( 0., length, 0. ); + glEnd(); + glBegin( GL_LINE_STRIP ); + glVertex3f( 0., 0., 0. ); + glVertex3f( 0., 0., length ); + glEnd(); + + fact = LENFRAC * length; + base = BASEFRAC * length; + + glBegin( GL_LINE_STRIP ); + for( i = 0; i < 4; i++ ) + { + j = xorder[i]; + if( j < 0 ) + { + + glEnd(); + glBegin( GL_LINE_STRIP ); + j = -j; + } + j--; + glVertex3f( base + fact*xx[j], fact*xy[j], 0.0 ); + } + glEnd(); + + glBegin( GL_LINE_STRIP ); + for( i = 0; i < 5; i++ ) + { + j = yorder[i]; + if( j < 0 ) + { + + glEnd(); + glBegin( GL_LINE_STRIP ); + j = -j; + } + j--; + glVertex3f( fact*yx[j], base + fact*yy[j], 0.0 ); + } + glEnd(); + + glBegin( GL_LINE_STRIP ); + for( i = 0; i < 6; i++ ) + { + j = zorder[i]; + if( j < 0 ) + { + + glEnd(); + glBegin( GL_LINE_STRIP ); + j = -j; + } + j--; + glVertex3f( 0.0, fact*zy[j], base + fact*zx[j] ); + } + glEnd(); + +} + + +/**************************************************************** + Arrow +*****************************************************************/ + +/* size of wings as fraction of length: */ + +#define WINGS 0.10 + + +/* axes: */ + +#define X 1 +#define Y 2 +#define Z 3 + + +/* x, y, z, axes: */ + +static float axx[3] = { 1., 0., 0. }; +static float ayy[3] = { 0., 1., 0. }; +static float azz[3] = { 0., 0., 1. }; + + + +/* function declarations: */ +void Arrow( float tail[3], float head[3] ); +void Arrow( const VectorR3& tail, const VectorR3& head ); +void cross( float [3], float [3], float [3] ); +float dot( float [3], float [3] ); +float unit( float [3], float [3] ); + + +void Arrow( const VectorR3& tail, const VectorR3& head ) +{ + float t[3]; + float h[3]; + tail.Dump( t ); + head.Dump( h ); + Arrow( t, h ); +} + + +void Arrow( float tail[3], float head[3] ) +{ + float u[3], v[3], w[3]; /* arrow coordinate system */ + float d; /* wing distance */ + float x, y, z; /* point to plot */ + float mag; /* magnitude of major direction */ + float f; /* fabs of magnitude */ + int axis; /* which axis is the major */ + + + /* set w direction in u-v-w coordinate system: */ + + w[0] = head[0] - tail[0]; + w[1] = head[1] - tail[1]; + w[2] = head[2] - tail[2]; + + + /* determine major direction: */ + + axis = X; + mag = fabs( w[0] ); + if( (f=fabs(w[1])) > mag ) + { + axis = Y; + mag = f; + } + if( (f=fabs(w[2])) > mag ) + { + axis = Z; + mag = f; + } + + + /* set size of wings and turn w into a unit vector: */ + + d = WINGS * unit( w, w ); + + + /* draw the shaft of the arrow: */ + + glBegin( GL_LINE_STRIP ); + glVertex3fv( tail ); + glVertex3fv( head ); + glEnd(); + + /* draw two sets of wings in the non-major directions: */ + + if( axis != X ) + { + cross( w, axx, v ); + (void) unit( v, v ); + cross( v, w, u ); + x = head[0] + d * ( u[0] - w[0] ); + y = head[1] + d * ( u[1] - w[1] ); + z = head[2] + d * ( u[2] - w[2] ); + glBegin( GL_LINE_STRIP ); + glVertex3fv( head ); + glVertex3f( x, y, z ); + glEnd(); + x = head[0] + d * ( -u[0] - w[0] ); + y = head[1] + d * ( -u[1] - w[1] ); + z = head[2] + d * ( -u[2] - w[2] ); + glBegin( GL_LINE_STRIP ); + glVertex3fv( head ); + glVertex3f( x, y, z ); + glEnd(); + } + + + if( axis != Y ) + { + cross( w, ayy, v ); + (void) unit( v, v ); + cross( v, w, u ); + x = head[0] + d * ( u[0] - w[0] ); + y = head[1] + d * ( u[1] - w[1] ); + z = head[2] + d * ( u[2] - w[2] ); + glBegin( GL_LINE_STRIP ); + glVertex3fv( head ); + glVertex3f( x, y, z ); + glEnd(); + x = head[0] + d * ( -u[0] - w[0] ); + y = head[1] + d * ( -u[1] - w[1] ); + z = head[2] + d * ( -u[2] - w[2] ); + glBegin( GL_LINE_STRIP ); + glVertex3fv( head ); + glVertex3f( x, y, z ); + glEnd(); + } + + if( axis != Z ) + { + cross( w, azz, v ); + (void) unit( v, v ); + cross( v, w, u ); + x = head[0] + d * ( u[0] - w[0] ); + y = head[1] + d * ( u[1] - w[1] ); + z = head[2] + d * ( u[2] - w[2] ); + glBegin( GL_LINE_STRIP ); + glVertex3fv( head ); + glVertex3f( x, y, z ); + glEnd(); + x = head[0] + d * ( -u[0] - w[0] ); + y = head[1] + d * ( -u[1] - w[1] ); + z = head[2] + d * ( -u[2] - w[2] ); + glBegin( GL_LINE_STRIP ); + glVertex3fv( head ); + glVertex3f( x, y, z ); + glEnd(); + } + + + /* done: */ + +} + +float dot( float v1[3], float v2[3] ) +{ + return( v1[0]*v2[0] + v1[1]*v2[1] + v1[2]*v2[2] ); +} + + + +void +cross( float v1[3], float v2[3], float vout[3] ) +{ + float tmp[3]; + + tmp[0] = v1[1]*v2[2] - v2[1]*v1[2]; + tmp[1] = v2[0]*v1[2] - v1[0]*v2[2]; + tmp[2] = v1[0]*v2[1] - v2[0]*v1[1]; + + vout[0] = tmp[0]; + vout[1] = tmp[1]; + vout[2] = tmp[2]; +} + + + +float +unit( float vin[3], float vout[3] ) +{ + float dist, f ; + + dist = vin[0]*vin[0] + vin[1]*vin[1] + vin[2]*vin[2]; + + if( dist > 0.0 ) + { + dist = sqrt( dist ); + f = 1. / dist; + vout[0] = f * vin[0]; + vout[1] = f * vin[1]; + vout[2] = f * vin[2]; + } + else + { + vout[0] = vin[0]; + vout[1] = vin[1]; + vout[2] = vin[2]; + } + + return( dist ); +} diff --git a/examples/ThirdPartyLibs/BussIK/Node.cpp b/examples/ThirdPartyLibs/BussIK/Node.cpp new file mode 100644 index 000000000..612cc42d7 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/Node.cpp @@ -0,0 +1,90 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + + +#include + + +#include "LinearR3.h" +#include "MathMisc.h" +#include "Node.h" + +extern int RotAxesOn; + +Node::Node(const VectorR3& attach, const VectorR3& v, double size, Purpose purpose, double minTheta, double maxTheta, double restAngle) +{ + Node::freezed = false; + Node::size = size; + Node::purpose = purpose; + seqNumJoint = -1; + seqNumEffector = -1; + Node::attach = attach; // Global attachment point when joints are at zero angle + r.Set(0.0, 0.0, 0.0); // r will be updated when this node is inserted into tree + Node::v = v; // Rotation axis when joints at zero angles + theta = 0.0; + Node::minTheta = minTheta; + Node::maxTheta = maxTheta; + Node::restAngle = restAngle; + left = right = realparent = 0; +} + +// Compute the global position of a single node +void Node::ComputeS(void) +{ + Node* y = this->realparent; + Node* w = this; + s = r; // Initialize to local (relative) position + while ( y ) { + s.Rotate( y->theta, y->v ); + y = y->realparent; + w = w->realparent; + s += w->r; + } +} + +// Compute the global rotation axis of a single node +void Node::ComputeW(void) +{ + Node* y = this->realparent; + w = v; // Initialize to local rotation axis + while (y) { + w.Rotate(y->theta, y->v); + y = y->realparent; + } +} + + + +void Node::PrintNode() +{ + cerr << "Attach : (" << attach << ")\n"; + cerr << "r : (" << r << ")\n"; + cerr << "s : (" << s << ")\n"; + cerr << "w : (" << w << ")\n"; + cerr << "realparent : " << realparent->seqNumJoint << "\n"; +} + + +void Node::InitNode() +{ + theta = 0.0; +} \ No newline at end of file diff --git a/examples/ThirdPartyLibs/BussIK/Node.h b/examples/ThirdPartyLibs/BussIK/Node.h new file mode 100644 index 000000000..5a49d278a --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/Node.h @@ -0,0 +1,101 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + + +#ifndef _CLASS_NODE +#define _CLASS_NODE + +#include "LinearR3.h" + +enum Purpose {JOINT, EFFECTOR}; + +class VectorR3; + +class Node { + + friend class Tree; + +public: + Node(const VectorR3&, const VectorR3&, double, Purpose, double minTheta=-PI, double maxTheta=PI, double restAngle=0.); + + + void PrintNode(); + void InitNode(); + + const VectorR3& GetAttach() const { return attach; } + + double GetTheta() const { return theta; } + double AddToTheta( double& delta ) { + double orgTheta = theta; + theta += delta; +#if 0 + if (theta < minTheta) + theta = minTheta; + if (theta > maxTheta) + theta = maxTheta; + double actualDelta = theta - orgTheta; + delta = actualDelta; +#endif + return theta; } + + const VectorR3& GetS() const { return s; } + const VectorR3& GetW() const { return w; } + + double GetMinTheta() const { return minTheta; } + double GetMaxTheta() const { return maxTheta; } + double GetRestAngle() const { return restAngle; } ; + void SetTheta(double newTheta) { theta = newTheta; } + void ComputeS(void); + void ComputeW(void); + + bool IsEffector() const { return purpose==EFFECTOR; } + bool IsJoint() const { return purpose==JOINT; } + int GetEffectorNum() const { return seqNumEffector; } + int GetJointNum() const { return seqNumJoint; } + + bool IsFrozen() const { return freezed; } + void Freeze() { freezed = true; } + void UnFreeze() { freezed = false; } + +//private: + bool freezed; // Is this node frozen? + int seqNumJoint; // sequence number if this node is a joint + int seqNumEffector; // sequence number if this node is an effector + double size; // size + Purpose purpose; // joint / effector / both + VectorR3 attach; // attachment point + VectorR3 r; // relative position vector + VectorR3 v; // rotation axis + double theta; // joint angle (radian) + double minTheta; // lower limit of joint angle + double maxTheta; // upper limit of joint angle + double restAngle; // rest position angle + VectorR3 s; // GLobal Position + VectorR3 w; // Global rotation axis + Node* left; // left child + Node* right; // right sibling + Node* realparent; // pointer to real parent + + +}; + +#endif \ No newline at end of file diff --git a/examples/ThirdPartyLibs/BussIK/Spherical.h b/examples/ThirdPartyLibs/BussIK/Spherical.h new file mode 100644 index 000000000..5db1862d3 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/Spherical.h @@ -0,0 +1,298 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + + + +// +// Spherical Operations Classes +// +// +// B. SphericalInterpolator +// +// OrientationR3 +// +// A. Quaternion +// +// B. RotationMapR3 // Elsewhere +// +// C. EulerAnglesR3 // TO DO +// +// +// Functions for spherical operations +// A. Many routines for rotation and averaging on a sphere +// + +#ifndef SPHERICAL_H +#define SPHERICAL_H + +#include "LinearR3.h" +#include "LinearR4.h" +#include "MathMisc.h" + +class SphericalInterpolator; // Spherical linear interpolation of vectors +class SphericalBSpInterpolator; // Spherical Bspline interpolation of vector +class Quaternion; // Quaternion (x,y,z,w) values. +class EulerAnglesR3; // Euler Angles + +// ***************************************************** +// SphericalInterpolator class * +// - Does linear interpolation (slerp-ing) * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * + + +class SphericalInterpolator { + +private: + VectorR3 startDir, endDir; // Unit vectors (starting and ending) + double startLen, endLen; // Magnitudes of the vectors + double rotRate; // Angle between start and end vectors + +public: + SphericalInterpolator( const VectorR3& u, const VectorR3& v ); + + VectorR3 InterValue ( double frac ) const; +}; + + +// *************************************************************** +// * Quaternion class - prototypes * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +class Quaternion { + +public: + double x, y, z, w; + +public: + Quaternion() :x(0.0), y(0.0), z(0.0), w(1.0) {}; + Quaternion( double, double, double, double ); + + inline Quaternion& Set( double xx, double yy, double zz, double ww ); + inline Quaternion& Set( const VectorR4& ); + Quaternion& Set( const EulerAnglesR3& ); + Quaternion& Set( const RotationMapR3& ); + Quaternion& SetRotate( const VectorR3& ); + + Quaternion& SetIdentity(); // Set to the identity map + Quaternion Inverse() const; // Return the Inverse + Quaternion& Invert(); // Invert this quaternion + + double Angle(); // Angle of rotation + double Norm(); // Norm of x,y,z component + + Quaternion& operator*=(const Quaternion&); + +}; + +Quaternion operator*(const Quaternion&, const Quaternion&); + +inline Quaternion ToQuat( const VectorR4& v) +{ + return Quaternion(v.x,v.y,v.z,v.w); +} + +inline double Quaternion::Norm() +{ + return sqrt( x*x + y*y + z*z ); +} + +inline double Quaternion::Angle () +{ + double halfAngle = asin(Norm()); + return halfAngle+halfAngle; +} + + +// **************************************************************** +// Solid Geometry Routines * +// **************************************************************** + +// Compute the angle formed by two geodesics on the unit sphere. +// Three unit vectors u,v,w specify the geodesics u-v and v-w which +// meet at vertex uv. The angle from v-w to v-u is returned. This +// is always in the range [0, 2PI). +double SphereAngle( const VectorR3& u, const VectorR3& v, const VectorR3& w ); + +// Compute the area of a triangle on the unit sphere. Three unit vectors +// specify the corners of the triangle in COUNTERCLOCKWISE order. +inline double SphericalTriangleArea( + const VectorR3& u, const VectorR3& v, const VectorR3& w ) +{ + double AngleA = SphereAngle( u,v,w ); + double AngleB = SphereAngle( v,w,u ); + double AngleC = SphereAngle( w,u,v ); + return ( AngleA+AngleB+AngleC - PI ); +} + + +// **************************************************************** +// Spherical Mean routines * +// **************************************************************** + +// Weighted sum of vectors +VectorR3 WeightedSum( long Num, const VectorR3 vv[], const double weights[] ); +VectorR4 WeightedSum( long Num, const VectorR4 vv[], const double weights[] ); + +// Weighted average of vectors on the sphere. +// Sum of weights should equal one (but no checking is done) +VectorR3 ComputeMeanSphere( long Num, const VectorR3 vv[], const double weights[], + double tolerance = 1.0e-15, double bkuptolerance = 1.0e-13 ); +VectorR3 ComputeMeanSphere( long Num, const VectorR3 vv[], const double weights[], + const VectorR3& InitialVec, + double tolerance = 1.0e-15, double bkuptolerance = 1.0e-13 ); +VectorR4 ComputeMeanSphere( long Num, const VectorR4 vv[], const double weights[], + double tolerance = 1.0e-15, double bkuptolerance = 1.0e-13 ); +Quaternion ComputeMeanQuat( long Num, const Quaternion qq[], const double weights[], + double tolerance = 1.0e-15, double bkuptolerance = 1.0e-13 ); + +// Next functions mostly for internal use. +// It takes an initial estimate InitialVec (and a flag for +// indicating quaternions). +VectorR4 ComputeMeanSphere( long Num, const VectorR4 vv[], const double weights[], + const VectorR4& InitialVec, int QuatFlag=0, + double tolerance = 1.0e-15, double bkuptolerance = 1.0e-13 ); +const int SPHERICAL_NOTQUAT=0; +const int SPHERICAL_QUAT=1; + +// Slow version, mostly for testing +VectorR3 ComputeMeanSphereSlow( long Num, const VectorR3 vv[], const double weights[], + double tolerance = 1.0e-16, double bkuptolerance = 5.0e-16 ); +VectorR4 ComputeMeanSphereSlow( long Num, const VectorR4 vv[], const double weights[], + double tolerance = 1.0e-16, double bkuptolerance = 5.0e-16 ); +VectorR3 ComputeMeanSphereOld( long Num, const VectorR3 vv[], const double weights[], + double tolerance = 1.0e-15, double bkuptolerance = 1.0e-13 ); +VectorR4 ComputeMeanSphereOld( long Num, const VectorR4 vv[], const double weights[], + const VectorR4& InitialVec, int QuatFlag, + double tolerance = 1.0e-15, double bkuptolerance = 1.0e-13 ); + +// Solves a system of spherical-mean equalities, where the system is +// given as a tridiagonal matrix. +void SolveTriDiagSphere ( int numPoints, + const double* tridiagvalues, const VectorR3* c, + VectorR3* p, + double accuracy=1.0e-15, double bkupaccuracy=1.0e-13 ); +void SolveTriDiagSphere ( int numPoints, + const double* tridiagvalues, const VectorR4* c, + VectorR4* p, + double accuracy=1.0e-15, double bkupaccuracy=1.0e-13 ); + +// The "Slow" version uses a simpler but slower iteration with a linear rate of +// convergence. The base version uses a Newton iteration with a quadratic +// rate of convergence. +void SolveTriDiagSphereSlow ( int numPoints, + const double* tridiagvalues, const VectorR3* c, + VectorR3* p, + double accuracy=1.0e-15, double bkupaccuracy=5.0e-15 ); +void SolveTriDiagSphereSlow ( int numPoints, + const double* tridiagvalues, const VectorR4* c, + VectorR4* p, + double accuracy=1.0e-15, double bkupaccuracy=5.0e-15 ); + +// The "Unstable" version probably shouldn't be used except for very short sequences +// of knots. Mostly it's used for testing purposes now. +void SolveTriDiagSphereUnstable ( int numPoints, + const double* tridiagvalues, const VectorR3* c, + VectorR3* p, + double accuracy=1.0e-15, double bkupaccuracy=1.0e-13 ); +void SolveTriDiagSphereHelperUnstable ( int numPoints, + const double* tridiagvalues, const VectorR3 *c, + const VectorR3& p0value, + VectorR3 *p, + double accuracy=1.0e-15, double bkupaccuracy=1.0e-13 ); + + + +// *************************************************************** +// * Quaternion class - inlined member functions * +// * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * + +inline VectorR4::VectorR4 ( const Quaternion& q ) +: x(q.x), y(q.y), z(q.z), w(q.w) +{} + +inline VectorR4& VectorR4::Set ( const Quaternion& q ) +{ + x = q.x; y = q.y; z = q.z; w = q.w; + return *this; +} + +inline Quaternion::Quaternion( double xx, double yy, double zz, double ww) +: x(xx), y(yy), z(zz), w(ww) +{} + +inline Quaternion& Quaternion::Set( double xx, double yy, double zz, double ww ) +{ + x = xx; + y = yy; + z = zz; + w = ww; + return *this; +} + +inline Quaternion& Quaternion::Set( const VectorR4& u) +{ + x = u.x; + y = u.y; + z = u.z; + w = u.w; + return *this; +} + +inline Quaternion& Quaternion::SetIdentity() +{ + x = y = z = 0.0; + w = 1.0; + return *this; +} + +inline Quaternion operator*(const Quaternion& q1, const Quaternion& q2) +{ + Quaternion q(q1); + q *= q2; + return q; +} + +inline Quaternion& Quaternion::operator*=( const Quaternion& q ) +{ + double wnew = w*q.w - (x*q.x + y*q.y + z*q.z); + double xnew = w*q.x + q.w*x + (y*q.z - z*q.y); + double ynew = w*q.y + q.w*y + (z*q.x - x*q.z); + z = w*q.z + q.w*z + (x*q.y - y*q.x); + w = wnew; + x = xnew; + y = ynew; + return *this; +} + +inline Quaternion Quaternion::Inverse() const // Return the Inverse +{ + return ( Quaternion( x, y, z, -w ) ); +} + +inline Quaternion& Quaternion::Invert() // Invert this quaternion +{ + w = -w; + return *this; +} + + +#endif // SPHERICAL_H diff --git a/examples/ThirdPartyLibs/BussIK/Tree.cpp b/examples/ThirdPartyLibs/BussIK/Tree.cpp new file mode 100644 index 000000000..a82e7f1d7 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/Tree.cpp @@ -0,0 +1,217 @@ +/* +* +* Inverse Kinematics software, with several solvers including +* Selectively Damped Least Squares Method +* Damped Least Squares Method +* Pure Pseudoinverse Method +* Jacobian Transpose Method +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + +// +// VectorRn: Vector over Rn (Variable length vector) +// + +#include +using namespace std; + + + + +#include "LinearR3.h" +#include "Tree.h" +#include "Node.h" + +Tree::Tree() +{ + root = 0; + nNode = nEffector = nJoint = 0; +} + +void Tree::SetSeqNum(Node* node) +{ + switch (node->purpose) { + case JOINT: + node->seqNumJoint = nJoint++; + node->seqNumEffector = -1; + break; + case EFFECTOR: + node->seqNumJoint = -1; + node->seqNumEffector = nEffector++; + break; + } +} + +void Tree::InsertRoot(Node* root) +{ + assert( nNode==0 ); + nNode++; + Tree::root = root; + root->r = root->attach; + assert( !(root->left || root->right) ); + SetSeqNum(root); +} + +void Tree::InsertLeftChild(Node* parent, Node* child) +{ + assert(parent); + nNode++; + parent->left = child; + child->realparent = parent; + child->r = child->attach - child->realparent->attach; + assert( !(child->left || child->right) ); + SetSeqNum(child); +} + +void Tree::InsertRightSibling(Node* parent, Node* child) +{ + assert(parent); + nNode++; + parent->right = child; + child->realparent = parent->realparent; + child->r = child->attach - child->realparent->attach; + assert( !(child->left || child->right) ); + SetSeqNum(child); +} + +// Search recursively below "node" for the node with index value. +Node* Tree::SearchJoint(Node* node, int index) +{ + Node* ret; + if (node != 0) { + if (node->seqNumJoint == index) { + return node; + } else { + if (ret = SearchJoint(node->left, index)) { + return ret; + } + if (ret = SearchJoint(node->right, index)) { + return ret; + } + return NULL; + } + } + else { + return NULL; + } +} + + +// Get the joint with the index value +Node* Tree::GetJoint(int index) +{ + return SearchJoint(root, index); +} + +// Search recursively below node for the end effector with the index value +Node* Tree::SearchEffector(Node* node, int index) +{ + Node* ret; + if (node != 0) { + if (node->seqNumEffector == index) { + return node; + } else { + if (ret = SearchEffector(node->left, index)) { + return ret; + } + if (ret = SearchEffector(node->right, index)) { + return ret; + } + return NULL; + } + } else { + return NULL; + } +} + + +// Get the end effector for the index value +Node* Tree::GetEffector(int index) +{ + return SearchEffector(root, index); +} + +// Returns the global position of the effector. +const VectorR3& Tree::GetEffectorPosition(int index) +{ + Node* effector = GetEffector(index); + assert(effector); + return (effector->s); +} + +void Tree::ComputeTree(Node* node) +{ + if (node != 0) { + node->ComputeS(); + node->ComputeW(); + ComputeTree(node->left); + ComputeTree(node->right); + } +} + +void Tree::Compute(void) +{ + ComputeTree(root); +} + + +void Tree::PrintTree(Node* node) +{ + if (node != 0) { + node->PrintNode(); + PrintTree(node->left); + PrintTree(node->right); + } +} + +void Tree::Print(void) +{ + PrintTree(root); + cout << "\n"; +} + +// Recursively initialize tree below the node +void Tree::InitTree(Node* node) +{ + if (node != 0) { + node->InitNode(); + InitTree(node->left); + InitTree(node->right); + } +} + +// Initialize all nodes in the tree +void Tree::Init(void) +{ + InitTree(root); +} + +void Tree::UnFreezeTree(Node* node) +{ + if (node != 0) { + node->UnFreeze(); + UnFreezeTree(node->left); + UnFreezeTree(node->right); + } +} + +void Tree::UnFreeze(void) +{ + UnFreezeTree(root); +} \ No newline at end of file diff --git a/examples/ThirdPartyLibs/BussIK/Tree.h b/examples/ThirdPartyLibs/BussIK/Tree.h new file mode 100644 index 000000000..208176817 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/Tree.h @@ -0,0 +1,92 @@ +/* +* +* Inverse Kinematics software, with several solvers including +* Selectively Damped Least Squares Method +* Damped Least Squares Method +* Pure Pseudoinverse Method +* Jacobian Transpose Method +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + +#include "LinearR3.h" +#include "Node.h" + +#ifndef _CLASS_TREE +#define _CLASS_TREE + +class Tree { + +public: + Tree(); + + int GetNumNode() const { return nNode; } + int GetNumEffector() const { return nEffector; } + int GetNumJoint() const { return nJoint; } + void InsertRoot(Node*); + void InsertLeftChild(Node* parent, Node* child); + void InsertRightSibling(Node* parent, Node* child); + + // Accessors based on node numbers + Node* GetJoint(int); + Node* GetEffector(int); + const VectorR3& GetEffectorPosition(int); + + // Accessors for tree traversal + Node* GetRoot() const { return root; } + Node* GetSuccessor ( const Node* ) const; + Node* GetParent( const Node* node ) const { return node->realparent; } + + void Compute(); + + void Print(); + void Init(); + void UnFreeze(); + +private: + Node* root; + int nNode; // nNode = nEffector + nJoint + int nEffector; + int nJoint; + void SetSeqNum(Node*); + Node* SearchJoint(Node*, int); + Node* SearchEffector(Node*, int); + void ComputeTree(Node*); + + void PrintTree(Node*); + void InitTree(Node*); + void UnFreezeTree(Node*); +}; + +inline Node* Tree::GetSuccessor ( const Node* node ) const +{ + if ( node->left ) { + return node->left; + } + while ( true ) { + if ( node->right ) { + return ( node->right ); + } + node = node->realparent; + if ( !node ) { + return 0; // Back to root, finished traversal + } + } +} + +#endif \ No newline at end of file diff --git a/examples/ThirdPartyLibs/BussIK/VectorRn.cpp b/examples/ThirdPartyLibs/BussIK/VectorRn.cpp new file mode 100644 index 000000000..5d2b563e9 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/VectorRn.cpp @@ -0,0 +1,46 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + + +// +// VectorRn: Vector over Rn (Variable length vector) +// + +#include "VectorRn.h" + +VectorRn VectorRn::WorkVector; + +double VectorRn::MaxAbs () const +{ + double result = 0.0; + double* t = x; + for ( long i = length; i>0; i-- ) { + if ( (*t) > result ) { + result = *t; + } + else if ( -(*t) > result ) { + result = -(*t); + } + t++; + } + return result; +} \ No newline at end of file diff --git a/examples/ThirdPartyLibs/BussIK/VectorRn.h b/examples/ThirdPartyLibs/BussIK/VectorRn.h new file mode 100644 index 000000000..8357f9997 --- /dev/null +++ b/examples/ThirdPartyLibs/BussIK/VectorRn.h @@ -0,0 +1,238 @@ +/* +* +* Mathematics Subpackage (VrMath) +* +* +* Author: Samuel R. Buss, sbuss@ucsd.edu. +* Web page: http://math.ucsd.edu/~sbuss/MathCG +* +* +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +* +* +*/ + +// +// VectorRn: Vector over Rn (Variable length vector) +// +// Not very sophisticated yet. Needs more functionality +// To do: better handling of resizing. +// + +#ifndef VECTOR_RN_H +#define VECTOR_RN_H + +#include +#include +#include "LinearR3.h" + +class VectorRn { + friend class MatrixRmn; + +public: + VectorRn(); // Null constructor + VectorRn( long length ); // Constructor with length + ~VectorRn(); // Destructor + + void SetLength( long newLength ); + long GetLength() const { return length; } + + void SetZero(); + void Fill( double d ); + void Load( const double* d ); + void LoadScaled( const double* d, double scaleFactor ); + void Set ( const VectorRn& src ); + + // Two access methods identical in functionality + // Subscripts are ZERO-BASED!! + const double& operator[]( long i ) const { assert ( 0<=i && i0 ); + if ( newLength>AllocLength ) { + delete x; + AllocLength = Max( newLength, AllocLength<<1 ); + x = new double[AllocLength]; + } + length = newLength; +} + +// Zero out the entire vector +inline void VectorRn::SetZero() +{ + double* target = x; + for ( long i=length; i>0; i-- ) { + *(target++) = 0.0; + } +} + +// Set the value of the i-th triple of entries in the vector +inline void VectorRn::SetTriple( long i, const VectorR3& u ) +{ + long j = 3*i; + assert ( 0<=j && j+2 < length ); + u.Dump( x+j ); +} + +inline void VectorRn::Fill( double d ) +{ + double *to = x; + for ( long i=length; i>0; i-- ) { + *(to++) = d; + } +} + +inline void VectorRn::Load( const double* d ) +{ + double *to = x; + for ( long i=length; i>0; i-- ) { + *(to++) = *(d++); + } +} + +inline void VectorRn::LoadScaled( const double* d, double scaleFactor ) +{ + double *to = x; + for ( long i=length; i>0; i-- ) { + *(to++) = (*(d++))*scaleFactor; + } +} + +inline void VectorRn::Set( const VectorRn& src ) +{ + assert ( src.length == this->length ); + double* to = x; + double* from = src.x; + for ( long i=length; i>0; i-- ) { + *(to++) = *(from++); + } +} + +inline VectorRn& VectorRn::operator+=( const VectorRn& src ) +{ + assert ( src.length == this->length ); + double* to = x; + double* from = src.x; + for ( long i=length; i>0; i-- ) { + *(to++) += *(from++); + } + return *this; +} + +inline VectorRn& VectorRn::operator-=( const VectorRn& src ) +{ + assert ( src.length == this->length ); + double* to = x; + double* from = src.x; + for ( long i=length; i>0; i-- ) { + *(to++) -= *(from++); + } + return *this; +} + +inline void VectorRn::AddScaled (const VectorRn& src, double scaleFactor ) +{ + assert ( src.length == this->length ); + double* to = x; + double* from = src.x; + for ( long i=length; i>0; i-- ) { + *(to++) += (*(from++))*scaleFactor; + } +} + +inline VectorRn& VectorRn::operator*=( double f ) +{ + double* target = x; + for ( long i=length; i>0; i-- ) { + *(target++) *= f; + } + return *this; +} + +inline double VectorRn::NormSq() const +{ + double* target = x; + double res = 0.0; + for ( long i=length; i>0; i-- ) { + res += (*target)*(*target); + target++; + } + return res; +} + +inline double Dot( const VectorRn& u, const VectorRn& v ) +{ + assert ( u.GetLength() == v.GetLength() ); + double res = 0.0; + const double* p = u.GetPtr(); + const double* q = v.GetPtr(); + for ( long i = u.GetLength(); i>0; i-- ) { + res += (*(p++))*(*(q++)); + } + return res; +} + +#endif VECTOR_RN_H \ No newline at end of file diff --git a/examples/TinyRenderer/tgaimage.h b/examples/TinyRenderer/tgaimage.h index 7a4dbfae9..9e2cbf877 100644 --- a/examples/TinyRenderer/tgaimage.h +++ b/examples/TinyRenderer/tgaimage.h @@ -24,8 +24,10 @@ struct TGAColor { unsigned char bgra[4]; unsigned char bytespp; - TGAColor() : bgra(), bytespp(1) { - for (int i=0; i<4; i++) bgra[i] = 0; + TGAColor() : bytespp(1) + { + for (int i=0; i<4; i++) + bgra[i] = 0; } TGAColor(unsigned char R, unsigned char G, unsigned char B, unsigned char A=255) : bgra(), bytespp(4) { diff --git a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp index 86c7d3a74..ebc1042b4 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp @@ -23,9 +23,9 @@ subject to the following restrictions: btMultiBodyJointMotor::btMultiBodyJointMotor(btMultiBody* body, int link, btScalar desiredVelocity, btScalar maxMotorImpulse) :btMultiBodyConstraint(body,body,link,body->getLink(link).m_parent,1,true), - m_desiredVelocity(desiredVelocity), - m_desiredPosition(0), - m_kd(1.), + m_desiredVelocity(desiredVelocity), + m_desiredPosition(0), + m_kd(1.), m_kp(0) { @@ -54,10 +54,10 @@ void btMultiBodyJointMotor::finalizeMultiDof() btMultiBodyJointMotor::btMultiBodyJointMotor(btMultiBody* body, int link, int linkDoF, btScalar desiredVelocity, btScalar maxMotorImpulse) //:btMultiBodyConstraint(body,0,link,-1,1,true), :btMultiBodyConstraint(body,body,link,body->getLink(link).m_parent,1,true), - m_desiredVelocity(desiredVelocity), - m_desiredPosition(0), - m_kd(1.), - m_kp(0) + m_desiredVelocity(desiredVelocity), + m_desiredPosition(0), + m_kd(1.), + m_kp(0) { btAssert(linkDoF < body->getLink(link).m_dofCount); @@ -119,14 +119,14 @@ void btMultiBodyJointMotor::createConstraintRows(btMultiBodyConstraintArray& con for (int row=0;rowgetJointPosMultiDof(m_linkA)[dof]; - btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; - btScalar positionStabiliationTerm = (m_desiredPosition-currentPosition)/infoGlobal.m_timeStep; - btScalar velocityError = (m_desiredVelocity - currentVelocity); - btScalar rhs = m_kp * positionStabiliationTerm + currentVelocity+m_kd * velocityError; - + btScalar currentPosition = m_bodyA->getJointPosMultiDof(m_linkA)[dof]; + btScalar currentVelocity = m_bodyA->getJointVelMultiDof(m_linkA)[dof]; + btScalar positionStabiliationTerm = (m_desiredPosition-currentPosition)/infoGlobal.m_timeStep; + btScalar velocityError = (m_desiredVelocity - currentVelocity); + btScalar rhs = m_kp * positionStabiliationTerm + currentVelocity+m_kd * velocityError; + fillMultiBodyConstraint(constraintRow,data,jacobianA(row),jacobianB(row),dummy,dummy,dummy,posError,infoGlobal,-m_maxAppliedImpulse,m_maxAppliedImpulse,1,false,rhs); constraintRow.m_orgConstraint = this; From 53fa57bdc4ee17891659c6ac7700e69f4dd9d04a Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sun, 24 Jul 2016 23:50:18 -0700 Subject: [PATCH 104/115] make IK compile on Mac OSX --- examples/ExampleBrowser/ExampleEntries.cpp | 4 + .../InverseKinematicsExample.cpp | 3 + .../InverseKinematicsExample.h | 2 +- examples/ThirdPartyLibs/BussIK/Jacobian.cpp | 31 +-- examples/ThirdPartyLibs/BussIK/Jacobian.h | 3 +- examples/ThirdPartyLibs/BussIK/LinearR4.h | 2 +- examples/ThirdPartyLibs/BussIK/Misc.cpp | 195 +----------------- examples/ThirdPartyLibs/BussIK/Tree.cpp | 2 +- examples/ThirdPartyLibs/BussIK/Tree.h | 2 +- 9 files changed, 14 insertions(+), 230 deletions(-) diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index a6abd4fd7..bf4ac2233 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -136,6 +136,10 @@ static ExampleEntry gDefaultExamples[]= ExampleEntry(0, "Inverse Kinematics"), ExampleEntry(1, "SDLS", "Selectively Damped Least Squares by Sam Buss. Example configures the IK tree of a Kuka IIWA", InverseKinematicsExampleCreateFunc, IK_SDLS), ExampleEntry(1, "DLS", "Damped Least Squares by Sam Buss. Example configures the IK tree of a Kuka IIWA", InverseKinematicsExampleCreateFunc, IK_DLS), + ExampleEntry(1, "DLS-SVD", "Damped Least Squares with Singular Value Decomposition by Sam Buss. Example configures the IK tree of a Kuka IIWA", InverseKinematicsExampleCreateFunc, IK_DLS_SVD), + + + ExampleEntry(1, "Jacobi Transpose", "Jacobi Transpose by Sam Buss. Example configures the IK tree of a Kuka IIWA", InverseKinematicsExampleCreateFunc, IK_JACOB_TRANS), ExampleEntry(1, "Jacobi Pseudo Inv", "Jacobi Pseudo Inverse Method by Sam Buss. Example configures the IK tree of a Kuka IIWA", InverseKinematicsExampleCreateFunc, IK_PURE_PSEUDO), diff --git a/examples/InverseKinematics/InverseKinematicsExample.cpp b/examples/InverseKinematics/InverseKinematicsExample.cpp index ae1ed8f17..8f902b008 100644 --- a/examples/InverseKinematics/InverseKinematicsExample.cpp +++ b/examples/InverseKinematics/InverseKinematicsExample.cpp @@ -113,6 +113,9 @@ void DoUpdateStep(double Tstep, Tree & treeY, Jacobian *jacob, int ikMethod) { case IK_DLS: jacob->CalcDeltaThetasDLS(); // Damped least squares method break; + case IK_DLS_SVD: + jacob->CalcDeltaThetasDLSwithSVD(); + break; case IK_PURE_PSEUDO: jacob->CalcDeltaThetasPseudoinverse(); // Pure pseudoinverse method break; diff --git a/examples/InverseKinematics/InverseKinematicsExample.h b/examples/InverseKinematics/InverseKinematicsExample.h index ca0d1e3b5..845925ef6 100644 --- a/examples/InverseKinematics/InverseKinematicsExample.h +++ b/examples/InverseKinematics/InverseKinematicsExample.h @@ -1,7 +1,7 @@ #ifndef INVERSE_KINEMATICSEXAMPLE_H #define INVERSE_KINEMATICSEXAMPLE_H -enum Method {IK_JACOB_TRANS=0, IK_PURE_PSEUDO, IK_DLS, IK_SDLS }; +enum Method {IK_JACOB_TRANS=0, IK_PURE_PSEUDO, IK_DLS, IK_SDLS , IK_DLS_SVD}; class CommonExampleInterface* InverseKinematicsExampleCreateFunc(struct CommonExampleOptions& options); diff --git a/examples/ThirdPartyLibs/BussIK/Jacobian.cpp b/examples/ThirdPartyLibs/BussIK/Jacobian.cpp index 646513b86..2b0454ea8 100644 --- a/examples/ThirdPartyLibs/BussIK/Jacobian.cpp +++ b/examples/ThirdPartyLibs/BussIK/Jacobian.cpp @@ -8,7 +8,7 @@ * * * Author: Samuel R. Buss, sbuss@ucsd.edu. -* Web page: http://math.ucsd.edu/~sbuss/MathCG +* Web page: http://www.math.ucsd.edu/~sbuss/ResearchWeb/ikmethods/index.html * * This software is provided 'as-is', without any express or implied warranty. @@ -30,7 +30,6 @@ subject to the following restrictions: #include using namespace std; -#include "../OpenGLWindow/OpenGLInclude.h" #include "Jacobian.h" @@ -468,35 +467,7 @@ void Jacobian::UpdatedSClampValue() } } -void Jacobian::DrawEigenVectors() const -{ - int i, j; - VectorR3 tail; - VectorR3 head; - Node *node; - for (i=0; iGetEffector(j); - tail = node->GetS(); - U.GetTriple( j, i, &head ); - head += tail; - glDisable(GL_LIGHTING); - glColor3f(1.0f, 0.2f, 0.0f); - glLineWidth(2.0); - glBegin(GL_LINES); - glVertex3f(tail.x, tail.y, tail.z); - glVertex3f(head.x, head.y, tail.z); - glEnd(); - Arrow(tail, head); - glLineWidth(1.0); - glEnable(GL_LIGHTING); - } - } -} void Jacobian::CompareErrors( const Jacobian& j1, const Jacobian& j2, double* weightedDist1, double* weightedDist2 ) { diff --git a/examples/ThirdPartyLibs/BussIK/Jacobian.h b/examples/ThirdPartyLibs/BussIK/Jacobian.h index 1c0bc4572..b1c683f8a 100644 --- a/examples/ThirdPartyLibs/BussIK/Jacobian.h +++ b/examples/ThirdPartyLibs/BussIK/Jacobian.h @@ -9,7 +9,7 @@ * * * Author: Samuel R. Buss, sbuss@ucsd.edu. -* Web page: http://math.ucsd.edu/~sbuss/MathCG +* Web page: http://www.math.ucsd.edu/~sbuss/ResearchWeb/ikmethods/index.html * * This software is provided 'as-is', without any express or implied warranty. @@ -72,7 +72,6 @@ public: double UpdateErrorArray(); // Returns sum of errors const VectorRn& GetErrorArray() const { return errorArray; } void UpdatedSClampValue(); - void DrawEigenVectors() const; void SetCurrentMode( UpdateMode mode ) { CurrentUpdateMode = mode; } UpdateMode GetCurrentMode() const { return CurrentUpdateMode; } diff --git a/examples/ThirdPartyLibs/BussIK/LinearR4.h b/examples/ThirdPartyLibs/BussIK/LinearR4.h index ee995326c..51f57a666 100644 --- a/examples/ThirdPartyLibs/BussIK/LinearR4.h +++ b/examples/ThirdPartyLibs/BussIK/LinearR4.h @@ -195,7 +195,7 @@ public: inline double Diagonal( int ); inline void MakeTranspose(); // Transposes it. - void Matrix4x4::operator*= (const Matrix4x4& B); // Matrix product + void operator*= (const Matrix4x4& B); // Matrix product Matrix4x4& ReNormalize(); }; diff --git a/examples/ThirdPartyLibs/BussIK/Misc.cpp b/examples/ThirdPartyLibs/BussIK/Misc.cpp index 03f34812b..6aa696d55 100644 --- a/examples/ThirdPartyLibs/BussIK/Misc.cpp +++ b/examples/ThirdPartyLibs/BussIK/Misc.cpp @@ -69,75 +69,6 @@ static int zorder[] = { #define LENFRAC 0.10 #define BASEFRAC 1.10 -void Axes( float length ) -{ - int i, j; /* counters */ - float fact; /* character scale factor */ - float base; /* character start location */ - - glBegin( GL_LINE_STRIP ); - glVertex3f( length, 0., 0. ); - glVertex3f( 0., 0., 0. ); - glVertex3f( 0., length, 0. ); - glEnd(); - glBegin( GL_LINE_STRIP ); - glVertex3f( 0., 0., 0. ); - glVertex3f( 0., 0., length ); - glEnd(); - - fact = LENFRAC * length; - base = BASEFRAC * length; - - glBegin( GL_LINE_STRIP ); - for( i = 0; i < 4; i++ ) - { - j = xorder[i]; - if( j < 0 ) - { - - glEnd(); - glBegin( GL_LINE_STRIP ); - j = -j; - } - j--; - glVertex3f( base + fact*xx[j], fact*xy[j], 0.0 ); - } - glEnd(); - - glBegin( GL_LINE_STRIP ); - for( i = 0; i < 5; i++ ) - { - j = yorder[i]; - if( j < 0 ) - { - - glEnd(); - glBegin( GL_LINE_STRIP ); - j = -j; - } - j--; - glVertex3f( fact*yx[j], base + fact*yy[j], 0.0 ); - } - glEnd(); - - glBegin( GL_LINE_STRIP ); - for( i = 0; i < 6; i++ ) - { - j = zorder[i]; - if( j < 0 ) - { - - glEnd(); - glBegin( GL_LINE_STRIP ); - j = -j; - } - j--; - glVertex3f( 0.0, fact*zy[j], base + fact*zx[j] ); - } - glEnd(); - -} - /**************************************************************** Arrow @@ -164,138 +95,14 @@ static float azz[3] = { 0., 0., 1. }; /* function declarations: */ -void Arrow( float tail[3], float head[3] ); -void Arrow( const VectorR3& tail, const VectorR3& head ); + void cross( float [3], float [3], float [3] ); float dot( float [3], float [3] ); float unit( float [3], float [3] ); -void Arrow( const VectorR3& tail, const VectorR3& head ) -{ - float t[3]; - float h[3]; - tail.Dump( t ); - head.Dump( h ); - Arrow( t, h ); -} -void Arrow( float tail[3], float head[3] ) -{ - float u[3], v[3], w[3]; /* arrow coordinate system */ - float d; /* wing distance */ - float x, y, z; /* point to plot */ - float mag; /* magnitude of major direction */ - float f; /* fabs of magnitude */ - int axis; /* which axis is the major */ - - - /* set w direction in u-v-w coordinate system: */ - - w[0] = head[0] - tail[0]; - w[1] = head[1] - tail[1]; - w[2] = head[2] - tail[2]; - - - /* determine major direction: */ - - axis = X; - mag = fabs( w[0] ); - if( (f=fabs(w[1])) > mag ) - { - axis = Y; - mag = f; - } - if( (f=fabs(w[2])) > mag ) - { - axis = Z; - mag = f; - } - - - /* set size of wings and turn w into a unit vector: */ - - d = WINGS * unit( w, w ); - - - /* draw the shaft of the arrow: */ - - glBegin( GL_LINE_STRIP ); - glVertex3fv( tail ); - glVertex3fv( head ); - glEnd(); - - /* draw two sets of wings in the non-major directions: */ - - if( axis != X ) - { - cross( w, axx, v ); - (void) unit( v, v ); - cross( v, w, u ); - x = head[0] + d * ( u[0] - w[0] ); - y = head[1] + d * ( u[1] - w[1] ); - z = head[2] + d * ( u[2] - w[2] ); - glBegin( GL_LINE_STRIP ); - glVertex3fv( head ); - glVertex3f( x, y, z ); - glEnd(); - x = head[0] + d * ( -u[0] - w[0] ); - y = head[1] + d * ( -u[1] - w[1] ); - z = head[2] + d * ( -u[2] - w[2] ); - glBegin( GL_LINE_STRIP ); - glVertex3fv( head ); - glVertex3f( x, y, z ); - glEnd(); - } - - - if( axis != Y ) - { - cross( w, ayy, v ); - (void) unit( v, v ); - cross( v, w, u ); - x = head[0] + d * ( u[0] - w[0] ); - y = head[1] + d * ( u[1] - w[1] ); - z = head[2] + d * ( u[2] - w[2] ); - glBegin( GL_LINE_STRIP ); - glVertex3fv( head ); - glVertex3f( x, y, z ); - glEnd(); - x = head[0] + d * ( -u[0] - w[0] ); - y = head[1] + d * ( -u[1] - w[1] ); - z = head[2] + d * ( -u[2] - w[2] ); - glBegin( GL_LINE_STRIP ); - glVertex3fv( head ); - glVertex3f( x, y, z ); - glEnd(); - } - - if( axis != Z ) - { - cross( w, azz, v ); - (void) unit( v, v ); - cross( v, w, u ); - x = head[0] + d * ( u[0] - w[0] ); - y = head[1] + d * ( u[1] - w[1] ); - z = head[2] + d * ( u[2] - w[2] ); - glBegin( GL_LINE_STRIP ); - glVertex3fv( head ); - glVertex3f( x, y, z ); - glEnd(); - x = head[0] + d * ( -u[0] - w[0] ); - y = head[1] + d * ( -u[1] - w[1] ); - z = head[2] + d * ( -u[2] - w[2] ); - glBegin( GL_LINE_STRIP ); - glVertex3fv( head ); - glVertex3f( x, y, z ); - glEnd(); - } - - - /* done: */ - -} float dot( float v1[3], float v2[3] ) { diff --git a/examples/ThirdPartyLibs/BussIK/Tree.cpp b/examples/ThirdPartyLibs/BussIK/Tree.cpp index a82e7f1d7..6891f0601 100644 --- a/examples/ThirdPartyLibs/BussIK/Tree.cpp +++ b/examples/ThirdPartyLibs/BussIK/Tree.cpp @@ -8,7 +8,7 @@ * * * Author: Samuel R. Buss, sbuss@ucsd.edu. -* Web page: http://math.ucsd.edu/~sbuss/MathCG +* Web page: http://www.math.ucsd.edu/~sbuss/ResearchWeb/ikmethods/index.html * * This software is provided 'as-is', without any express or implied warranty. diff --git a/examples/ThirdPartyLibs/BussIK/Tree.h b/examples/ThirdPartyLibs/BussIK/Tree.h index 208176817..673f41c9e 100644 --- a/examples/ThirdPartyLibs/BussIK/Tree.h +++ b/examples/ThirdPartyLibs/BussIK/Tree.h @@ -8,7 +8,7 @@ * * * Author: Samuel R. Buss, sbuss@ucsd.edu. -* Web page: http://math.ucsd.edu/~sbuss/MathCG +* Web page: http://www.math.ucsd.edu/~sbuss/ResearchWeb/ikmethods/index.html * * This software is provided 'as-is', without any express or implied warranty. From a6216f4f24693fdd4e178b92db9af223e9771fe1 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 25 Jul 2016 11:48:44 -0700 Subject: [PATCH 105/115] add robotics learning grasp contact example add wsg50 gripper with modified r2d2 gripper tip expose a fudge factor to scale inertia, to make grasping more stable (until we have better grasping contact model/implementation) --- data/cube_small.urdf | 33 ++ data/gripper/meshes/GUIDE_WSG50_110.stl | Bin 0 -> 23884 bytes data/gripper/meshes/WSG-FMF.stl | Bin 0 -> 108184 bytes data/gripper/meshes/WSG50_110.stl | Bin 0 -> 20684 bytes data/gripper/meshes/l_gripper_tip_scaled.stl | Bin 0 -> 49984 bytes data/gripper/wsg50_with_r2d2_gripper.sdf | 298 ++++++++++++++++++ examples/ExampleBrowser/ExampleEntries.cpp | 1 + .../ExampleBrowser/OpenGLExampleBrowser.cpp | 2 + .../Importers/ImportURDFDemo/URDF2Bullet.cpp | 7 + .../Importers/ImportURDFDemo/URDFJointTypes.h | 5 +- .../Importers/ImportURDFDemo/UrdfParser.cpp | 23 ++ .../RoboticsLearning/R2D2GraspExample.cpp | 235 ++++++++++---- examples/RoboticsLearning/R2D2GraspExample.h | 1 + examples/RoboticsLearning/b3RobotSimAPI.cpp | 2 + examples/RoboticsLearning/b3RobotSimAPI.h | 2 +- .../PhysicsServerCommandProcessor.cpp | 21 +- 16 files changed, 558 insertions(+), 72 deletions(-) create mode 100644 data/cube_small.urdf create mode 100644 data/gripper/meshes/GUIDE_WSG50_110.stl create mode 100644 data/gripper/meshes/WSG-FMF.stl create mode 100644 data/gripper/meshes/WSG50_110.stl create mode 100644 data/gripper/meshes/l_gripper_tip_scaled.stl create mode 100644 data/gripper/wsg50_with_r2d2_gripper.sdf diff --git a/data/cube_small.urdf b/data/cube_small.urdf new file mode 100644 index 000000000..804f7f0b1 --- /dev/null +++ b/data/cube_small.urdf @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/gripper/meshes/GUIDE_WSG50_110.stl b/data/gripper/meshes/GUIDE_WSG50_110.stl new file mode 100644 index 0000000000000000000000000000000000000000..a7b584732a514acba85785903075f20c46da1634 GIT binary patch literal 23884 zcmb_jU8rSOk=~>6=Rx8Xqo58(5JPZYTC^V&yr+)?cGTcgJNPsh0u7^xjSL3K%LW@! zL})?gDTy@0yr`3r@i%JjIa~YzHR?mu2ZIk0oEa1qe-H$jsjq5%tG>1NUN?D|OVX*F zs;|Das%q8VtM2K4`1{MR`2YNQ;%_GVnRoaTKUc5*^6;AHzHIr%55Djw$d~?l`||R8 zzvS{X-MRenjbD5d>?&f06*WC#dBz1tHwfoY1g(Jn;h$gU+zrAxsDYItUiALcC+>$m(KYa^2;*?{n!{?hB4|~1?%WN6`>3l@gzag++PUw;c3u&*0*6I?-(=9q zR0CNN7U}&egU&%;K+p=Z)!Tl%CsNZRtj3-Of>uC-d%Gu611m*fh1)$*5wrptG2HG9 zYK2&_Cyo)+z^@{Z&8A-=A2owu2ZC0yr#ttX$K6L#I8ap4Q>mQH$ETP;WPJu{GBBtqhgeRWb%CSPwirk4fdDg|lPj9)nYc=Zk zc(jvNpXbvwLeL7HD91h?vR(h_&G$J+YSi!X$hVL45wrpa<%&2ZM{3mX@o0IHeb}lt z5wrpa<=}Y9vo7u)E3rzA`aK@4-XtF*1g*e9IXM2?;`G0^vR0#hk4L@-pO2swJW*~C zUWutuzrn{dI89|$D+JaKE3P&XKd?Bx)M~5MsNaYi-V9<@BLpJN_Xo;>_}caBr$4k) z1&-9H-^f4TGNx&SK*hico+vxVY=|>*q(=Ql9p^qq2vk1zK{+_SdCSGaD@&|WqkiK& zW^_jg_7&`da&U~gPg-eT0mgEEuuAltTb@ft_A2py4i2lH+S@C_Yd1BCK)-^g>^_BK zg`gEUDEmGpJ5dLo!PKZ<&wqW^PD6xMj9Y<&a&TzBN{#yU{MUDeX&ND{V(Qxf<;tPm zr}$F8o`2a#*RLwVDyHs(a&TCu-m$l*M*VtSNj^phs}i>=btMR^tDQa7JcG0<&!uAJ zbtP3YLge2frSA^R2O;II?5;~7ki`i;2dIUgYqX*uUE2Zwea zS|L^{qe`~>)s_|V(IEPMReVKVh2N;-+(*~1Dgu?yeNgs&%+{$7?Cq&hzi}QjA0q@# zF!MnCqsIc4XVeqo4vp1Ai^H4)Lc#Y47x zNu3%@Lj1K%I{g?UXa!G{V;}Fid zw);+<;!M*BK`U@j4vzS9b`EOPFJyb)6^;>tR^Xr|>M%J7t3bcCQ4I4B2) z_FZbgp|aImov^fhcgqSKEy8N|jQxrlaHwqcRwqT%G(yk{9F$`p@n`g1YQUkg)thjP z5VQgZ<*>C%JmvF)8gQs=^(L_zA!r2-%E6(1ml|-WY&9l1A0cQ34$8ryeU}<=sLc80 z`3PEpgK{9+z8f=EaL|f;c?L%atcrb?a&TxDrAGZiM%=QOj1aV9J`zzf=>3XT>K8Kd zpFMGepcObM$3EiE=)2UYU&yHAz+592}!AN-J<^7oF|@0@+Rh?all7&t9Hf@H;`jSuAzxOoYKy(<1)m z=8KkJ|MO?#_k%>tJtD1Q5>lti_mGUBBtqg$NGC5#>#iD zh_s4*a9+}KU>~7DtmyZ61mA1FP=4=Bj=FOq(n|AhX=o63+p4kp&F|h)V`aBKpJkcb z4w0JUQ4#O{$2TmueeBC^UHPgMkyep^-h|s#p{{tB?Ge-Tl?@I>Kn|-o1-uEj9Cq6- zJ7guoZ`ASjJ`{m!4=b&)K31_3oP*;L`-pRQUbQ1uah_WQA{}SGaLmXI{3;@?Y*jL+ zZg-xV$RK;k&39f|n!1{u0;j0@Iv&$X=gIx5bn2{#X?mySrhNCKsYFGjRd938;QMG+ z6&hraeq)8(=Ul5Ds|qWvW67ZLID4IPS#im?3exBIRl(#or{ z%m8~1tE)O4>=DDhTMTe=Y0sz{ z-JAjTh}0OLAgmMZhyAK%Fs-7lhJCkA2YbY@?^ZX?o$=z!+QEvQSu_C(J zxyOo{9%0d4Zannp28SYOwYjPpVTQ(TsUF4Ph?_TLuC`f~$BLRB!8>(DR1QVZD$o&y zih$r88XraQPF)f67J^oV!=6588?iDD*T6~uCVP49>2!!@u{L_Db<$>`4HP%GZHfnFg1C^^S_ zLUf!K5%Wvf_4!ByZ}G{o)vv6U{P#|PXKlU zMZ}Y6t1~EqR#+kW{B~VY6Z?pcQ{?@2_vsLB1q5r_Lo_{l+x>?pzjgTxw<3GfEAzG! zi&M_8QU<0VPJu{`B2E@~;v4c9kyh=DY?}5zyK-1wf2&o!YSiz^VsGSi!ZJprmA}0T z;>)kU_3)OTU2%@IQokpQ-9^d_2sN*SvvJGaiP(=+uOaf^x0c?d+BbDxxfC^>hI)TrOcKW6}A1S*EJ*Ob9g zD$zMoqkdV(F+(0BqVi*wk+M$K1yVffLMqqzsPI8Jr_E>NomI=3|6F zCt^NQ21n_M&XF4R8~risYJ|u>uRR|eqo+Y45H~&<41p7MuoLCAYc*OXf?n=*U4SwSRug2$z96eu=8x~Xc0P9Yw&azVR_YgV%gLR;`)nf83i;ST_=!r5`VGE3=VetZ1XjrBN6Hc_?}1R^c{s>t9d8FWNiso%(d_T3Qz6(fDOPMzDQL0YL_*74T!LlIHO_4#3^ zpdk9^N71O?IFGrH?)gy>IFH;%$`-1*bOw)AYSeG^mCVNoflkDHqzsPI6P+V9>Nomh z*3}4+eO`YH1dh?uAQ6Zgd%hv2KiIdt@h{|Qx@NID*o_xfl=1ny?DNHM!aaf-ML_1~ z=KGNTZxqcZ%opWj%pvETA>IJvP9AbhykM8p32Nd-*Q1H} zr|(=o{j@!A^9~rZNlrZB6Vn~e6Q^l}pjEjK3gUy-so!r;&t5|WIBXJ9=hV|QLeL7H zC<8rB7p+r2ZqLGAqgEf5dHWbaD|n(D9C*`z+}=xiO>2cnGrA+hIyXcF6Mx@%!FTjSKmL|F4-^1?Y>*k^waP55oliNKQ+{i^)Umv{n%pOkG+b>1FRgDnKDN~{tw zm%i)ypcOb&w%jb4^AUnp;GpcQoy*gJIj_Fd%4)3sHlsd2RtQ>wgK}_`r*sS|Dk3#4x_n;VWXjXV-(-vf?>Ln4_Hx5M1E0M66ohKF5PbJ(-%n0YHuvgA^FJY+D%WZ#CW1A z+f~^uwboT;&2Pn<-$PanR+W5to9ts{w{7_y3+f7413IT_?W$4(t3>4OwdYVoTItQZ zM<70|5=4PH$GyGzHdPe6tv5As9*MyIIALk`VYMXDy=Hrf{9A>V-1MtT4R)T0=vP}A zY!TXt?lccu=ffgeG~h@?R!mt{tt;J!RePDx>k9jQ=-OKZp6!EbH%-LH&P1^y$KceO z75h~pz_-eW?Zr<{(RgR5Igiyo6$hfgoFnS|omZRl^yQti)>uS+{r3&9!|b(&-g8f= z;}wVRBQ+kMib(E0gB_yAEo-{ZU}`i6zFI@eJ~q!s?lzuRt9=+sPiH%a%hTMiDm5#_ zrBz*dtQ28#v5G#nsuEvSo@eZ~L0o!j1ZIn2r5(c@<7c*i%Dd0CnuE-_zHzv{{{e(* zJRke0692r&1yMK@p;kAH7iT`Ioh;x`%?eRDwAzWNv!&wKKQ{zEZ!@SGqOlTwURG81 z0Q8CZ#F>a^YRde4jNlG?bgT-#v1|NvzMKzM8ilYVqSt^!5o->8D-N0Q>EDo@V+LPp z)(E0CA1z1!M&2OYKi}>{)4ufsO$63Lp0HXY;%=})I8XXgj`lXe$bu{8ZM>7|T`f9X zM7Kq#rbXm!a*T*4&P}h^@D%m7g6WBX{1;8FaN30f7Bnt8us6olHC~ zSdI1HtO-PFc)N?w)6*{nMc5<#dH&Obd> z#0-dP6ruH25dbs@waOmT??W|;fXsP7%Mm-T=fk4F$!$ht3&C!gl@Yh1IFC<-2rJD~ zkKipO&S1`4v8q^Yk4O!oO9Zmn)Rjjz{z!ycVO6Z-$}t0BR<%ZrLw+B@H}XCoTB9xE zg4MKqXWRXQLlJS#`P-9>NL^I`>WvQnn|@8USP4h5#(&b6T4~&1#pj1VIc>doI#Wje zPwX?CO+K{?Vs15xfL9<`J;~Agq7^@9g{~3Q5J8Uexvj?E;STs*&v~9lz8U1IV2Rzg znnbkEc36``5o&eAc8#d7IaISkG_i6TTa_b@$B7|@*d#ytWDJs=dq7W&$L_%(-C{j^T;*k_0(Y@rH zefHYBi_}BOwNz3rT~KsWB;WC#bB;a7TxV~e-ygs8dOc6`wa0jmG3S_Ljy2|(b1m1k zy{zv4pMOJ+_2{oC#Q&kSde!da$FD31N7w$P4cf0Bu9>|3?VnZqjB8egORwGA27C&E zhC(nUis-twe)5Zp1)?Yug1LZ(q^lS2%b-JYp`G*5zI3lLBUl#XN(9C%g2t77)yZHm_zS8tYvBNlFv}uPlE@WaMg{vn(K(3vG@P5bZ_=IR}`*#zS;m z$vz)Ufn14zk1ea1$yO4>2}w{mS#|rehR-=cwc$5-!CefQBTFq8{rggJ3S!Z4vjK(K)cM{=fq}=7^-wwij<4FvCmr1%Z6YsJ+l%qs?!Djpjb@lU@q+? z%vIOP89Xl=Lgo+L*5jzY<#vCczeah9rAWDToovbTvLR$v!)>Lbh@v$;d2J4-^C&4- zw>j$rZ*~N@U@PcIBZ^F~)QYkcDOZmP87JhY$593$pFZ4HfTD$$U*I?PV?MN7ij=G8 zoS(IxmklAGqTJRxE^j?2R)54$rNdIBT(o@gBvi6Gqlh zIxI!X)v=2+GSAC~;1~>BaodbMOQg13G6w(Ab7`Veg&X{J6+TldNWPTwUdY zz#D*^VK*V#6XF*_NDA5==hY4pbMy?dB+pw#h%2Tw@n7C>c8LBmMIz9i*syZ2`%h#5 z_w-ttcH}(r5q%5>YcYMUZ@D80* zTf}NYl<#|8?8gmvs9rHeBG69$lj9e(L{43edR27mb+O+vAealivf0wrgxJ&Py4Yug zkh0J|`-wiWPDkrrSwt^Fl>cXH>F{QQRj-&L5oj+j*E?}rb@XaBA!htLwe+?O2SaJM7kb6}1kbyZ5FN_Dn%L9o7S$`}f?Ur_h99lgy|RdF3Gvp2l#^VYuX@E4 zi9maQVt4q!P4MM|?&rJ4PgeZCjA&w`+lNk`qgW_>5n>!6 zq%5?L`m!K-(i!^cY!Lw=wtO>K?FpqUiQu;0ZTtTR0$eN!^%>8T2q}x(KW~pBE+idS z(>NYH{HV$RxN;*AXu}GxhNv^NB19)b%*lXYE}lVM_sJ)OnU9#1g*Ikz$Shs`z&vS$ zm~&ssk_fcnF;8EQUC|bbaP7#iu6ea$83c1d53!+^QIGG9Az2rWI!+% zdc`|$&+AHvMx5B1@od#Arbqy|Oic=Cxi)ygYTVfA7!N=R(%*!+!8l`F(BB_PikA2*-6T9ewIG9_U{(tE!6a zOpyq*bK-fybG1+lhhLpbh|@A4mppAUDZBJd%v9{_!h}NWIYlY8Lq-Kglu#R%m zP}xRC79+%p3<&fDTs(4JLq^s&gb?)&0^A=o5Z33K^^1<3!cM0o|D@wrs!!;Zm8HDIaLH;*REMm|Sh;E(N$vSZLeOXpm-L<} zLe^v?g6tM%wys22uDVIf5IQu)ML=KfYo<<}6=At# z-7nfJSXZA;)=f$TtPu7y6?#X9L|86a_lxR~ekBo@&GjFf(>_OsL|88AV^JM4eh?zi za*q^C5EFHkT*oU$P!EGLBQL^CNrdInD-GwLaB?^9Vhw7FUUyoqvb0}j29*wpp!qOd zvdSIRfmovJ>Qb)q7+?FCKqws&fmp(xXgyRQXiRSXTOzKRkUDSmD)_NLC>>T--K6D` ze*E7tU&bf>^>pcVO~-|J-f_jFZ{HV^mrR+PxZ~Je>PgLY4bS^&eYgBd-*!zj=yk6` zFhwHJZh6gsu+im+?Guhl#^-t^i3$Y+%OIEwy18QEc^_<<6d#kfCUL@s+ZBQ-QZCwW z&v-bzdoXlVZ~9RD-(yP>pI@SNNCb012UkL1E6U2KI-j>i>tKqMi#Gobe$V@LcAcb&5E0w9 z+fHs6JaZd#wD@gl{Hdq=`WKw0bw~trK?hfEJ@1y+zRbJj_3nNns)tL8l#BK!UC#*4 zABpTN9C1$k>Vv`AA7!W@;H|C#w*#!#06p29l_XCxK5B6dP z=Pe!(Z#F;AKkp2!Ln4?9I=I$L^{amK|MtVN3+8AY z62V;1!PQ~UE2-Kt-z!)XYqMFeD5glcXw#bab!4b~)f4e^*7c6PI(eiTheR+JbZ~W; zD)i3{h~NEH*I2KfI{Gk0%0>IQHNWMg z_%u2}ZrMlcV2YHBHpRyn;-lvs_fq@(#YfF7-Pu-0QHfwK=-}w;d4tbh8b>_2X; ztK>olNm4QR$Oz^#y)uX|MtvFINvrm~YFlE^&igZPVbz9%e@jOOz4Ll&MYsI56d86l zo1+lC+mZ;h5m#>Xku#j%GZCL#X^dZW+-YSH%%yavcU~JWofzNr&{+SU9h(XyMao6H z_E7~vOR6n;-WxL}#si9Q*G|wncz-6jAW81kyrSe2WBq}D9&!qTwQ^)#uR^C`D zDH4J9P_H2Pn5x5`cO@adCB&Kx2<8HUpA62^*@q6U)`1I8=e2MCna%)Elk>dNkGkd8 z*xog9xaYkJ!PPp6KpXkPQ~QBvU-V^sK)IQvZJLfNgJ3S`=9--2?FzvZDHm;czSeQ$ z&r9PU9D2I+#9XaIBA5$0sI97ao_EUhFY_=f6aUo+rbxL)Urg)h`^Y)*@n7_gEqZ*U z>Xk%bor4QHxIX83TT2GSmww$f*2UP0DN-)lh(rTFgRL(5bU^${idXfgXdM#4T+qRF zKf3*J>-_kz9bIF?Zq)O^6e$;NL{!YC=RL4|bN(m#`Ju)k5zGZ0T=%1MoB`Y7L(X3l zyZFP~6@n>JF4}l9pq}h`uPogjpR@CD?B!>=mq9QWba186^JX5`GQZb7HT*@Vc2)?c zNV#a^2{&>Wc3$nTcp`q%b9sJ;(=IH7U@qw3N|=70|I<3=*SqWjg6?Hrz)?U0OQFCKi1akqwQQPzG|Kixv9ldLWyAE9$g2Fop zv|(LjlRSesiS@kS)^*G8O*5F&Ugx5i4^SimZSt|C&Z%?8ei=WXyre-+wNT2ET=<<& zVmou*NTs;?gd#!y-yQZMf(|~rB~P5M_68yE z4VWV3qD|hO)O(z_?ms6UJacz=`43Meq%6sW-}&s;^S*z2K>U~?L&M$|>3tMaBm(W> zV=hj9Qh@sI$Rz{f>t@~^*4n9cNCb012cP!REx^0x$G_}9G#uMl>tKqMi#9#ali2Bb z-nVaW&Y%CoxDXyGWl1jnUDp;Lylq>2%eb-ON&jw8Sq5}~A`xg)zM_7oUGT!~@!>mN z9gJWu)`9b3&wIFD%lx0Fj}70ix>03)&;g2+%ldR?`O_s�NcfcUWQjQ!2tq1V#%k z=-~5V&pU_q2FKETbh=1quS}70(T1g)y^HL%>zf1OYiK?i?bJFXg1MlBPn12cpyNsL zb;E{+OX!ZGq)54F!>^EEd*0LUwa;%@bWPZ#nU10?OL9RHM_11~bneo4i-q08<|ei? zMIz9K=Qq0<&yQ~jL9spL*e(&w1q4>De&VFoS1-Qfq#k8obrtdh97d?;^yKmU|E8o>8GiIQQrl4#MS< zQ{fBV!6 zPtS8lF2{8A0~Z8u-8IGEIv;z^zPlIawI2LKqRXkb`Yy#<0cd+p(c}IHO4@ugA#qyn z@G=PI`lwUm;Lm@1`vV??j_!o0`R#0J8SbcG_ITY zc++U#rC0=d^~!~O^3&v*StUbS+>rMpW#Lf-bJai4G8j~2X{*KobTlQz4(K0wbwKB0$A=WP3koRfhy0H}X%B5I@v6VT^Dj4!`$)UQFVpCS$QwBk{Qe4HA z8V5)3>>X}Vw#p^MC-o-91{1=i=z1&8po%{}KWM+?vGAEi7{}iiyqQ;zR#Ps`pi8j` zGymrN>qGR=7V(%})(^NfiM)z}z_mlib?)pLbE}z}} zwYk5)vS*WIky-P!9?c2OlCSF))h&yi@?%!9ladPy@c;eKimDK&) zdBty4XyF%aI5GI-<-qgRWeJfv5B*Go} zRU_LMbpH4Tf77289E9ZR^`9^NA9hqv4tW|ne!lkM;`6CTFH`SaidrAWqVfdmt=f+j zpSbL1|D7Fw#i9td4Q{dS{jJ6oP!Z{F9@ArZkt zSNOG7HcOr}73gDrI zKkI)@lgBT{Q(yN=pENaJeRJ;5{fGM<298fiibPylshxkq`sT?AR|4I6>*lKJ;mxfD5TdUfe@yx6*z^RNG>zkf!96=e`uwcs+(+T_FML&t|Zk1N^#spp@X*F7{@ zM)>BEKRC+>FMA5RMja*e`CzMqjq=WUxrM*x#^#h)TZ+jt6vAW!$=TzOk@cB-Fn0kI zJb!hrJ961WlS_p4x?#`R#6Jj+9;Zm$zlNluLN~+q@5|w4dD9Z?4ibbGTr%&XQ(GHK#Dw#I% zx{^Krjw^#;E|W{Vvo?edAQ~jEFQF_WbSYM@$t7avD}>215|m|xF2y2@t;}h!$ubg@ zWt2f6BZEavF5#c0Y-O^H1Z5eaOHm`&2%Tm4y|2eO4qo_XUb(w|NR*=)G+BnBScI8> zbI#qJvWyoyl@AwmyQvI*(ES*%OmX1m6wE z`uLl&jN4yp8g6diDwGt7a7TXl-u6^TzajkT&k7Dga+%B^n0gy@tfMSr&e1Kxd|Kx& zMXitY%>i1?X5?>DmXW*c=J1>yet0B*Sk{??+Agmjdst89}hM`!C zy0$V|Mo3vkzKO`eyL1QAWB|dK*7}KK?`xPWBcv=t%?DGW2%cH0&`(~Q-@D1Uu%P}d zenzSL9ui^lhhWx!p)cP5{QOsTjt={csqJ`)T-M*xSw=`%hND9wO#TpjH5h1e+Wjs2J~xtHs^it@~E)yIe893a+zEr_~>gO&fC5@ zZvi1LJTEUMDJEwKrnl6YC1z0H3S0Ezg8X|HjSUxdSj~B&qDX|v27-Z$fi_u2NLhx{ zE0;^<5`nHQnJgouEF&KyXTOpNlRpGUt9y$k%LpmUa1fG9`n2brU2#-+-_MO=9XGC| zam=On2hR;EzK7L0mu?H?1%2pUfOkgEO-`J1aWHH$R#bgL{8rA7ofnKKa49Zg(xkS* zxK8kr_T##SZC6zEf4`?mOd`-`uC3oZmwa`EA3Sv_5Py#C8g@Kb#UJ z%2sS2*y@aH+6N1|{;F)nW1<__gs2w3EH-T4!hG5HC}Q2t%S^BSM7# z>rB?IO4fa8-$Kg5=i1U>4bRYlKrt8-<^_>lqjN2_u9dv+pycd;hok1htOzXV+ zrj_)>(JOTpy{UyZ*8Jc3dz7uNSY9tE*A+Ud!*>g-$LijCj2gM6xQO}hRtTnagO10^ zcb7Ir~%a2(NCh+4`{^`SZsrgv9^F#l*8R%7OLX5b1Ucpf#S}N;Wii?<9bGUy(RUr10 zC;rx^U#!<1_7wD-S6Nw?DN)46SLelM{PYv) zcywu%a8Z}0v2u@faS)KpT(H9DJ)Vm#_Ry=5gz)IbNO7xcm35ht0g=#%e~%dzHtIF6 zpwH-*%2sS2*lOyzWBiYQ{7Ko0$3)pHAxbKoS1{?GOO&lF#YKG5U}5ahk1&oknplz&>(AFJBh=qshmsT90=YuS2C@zAm z9%|pMNS=7!fIX!{$rGh4w3!Q5AP)_-?;a#?f4#6@Vk~*Pq(l)EB|;rb22x}=Zt&7X z2}K5pK%2Q>1&SD^-lv6?wbtdlW&dInD{{qMax?ouoX z5o=*xior?5U|4~kS4sU;yMPd1`_&W2_twurOK}nOd`#*m=Pt7Dj>hW~&zzv2gN%S& z=7JUI*`CxHz;}cg({6vF&wDy&U`iB0Sw>Q48Czbi5>{K-DjeEU=M0R1T;_rmDA!8r zjI0jLN4=FD!*M2uV@ec3Szl7;yJykJd;i=hv3{e@87NOkB2R#=DECbwe?Si@4@&B6 z>0CmbR^Cs19Mk!grML*nkdr#^szxI}d1b}0*$ACqF#>X#3q7Q~G^w-KhY7LkV3lyK z$#Ya9p z9jTFFw{mM81klU{-{sSHs&bO=&e=3De5m<EwK?`zqL zKr@%@A>B5Fw_mnDk^lY_HF6$p6oJ(|{ArBinDpt}`Hhptb<(BCeq304pFq{`(R}9uQ(vta{?fp2x&oii<#W z9Wo!|XgP+~c=Pp%=_iH`0%+!f74W=z?_nUejqVyY+_W(9_|e}h>oO&Zz|*ctCsc&* zCr`Zlg#(HA#x?Y%EVP*mRzS|MzZDQY2{CZU(!_ZmwNch(N)&+{EWG$VK9Do)m<;V|HxXW3W51dYA<@# zQP#B-7lAzZ?u+*mVg*HpRrl;EJ$*rC9~NZ<+ROzj&@Ll!M|B{~{==jFhq5kHG9Y3a zVfG&$?LQoZk*m0j6=K@DV`%^J+OT?2 z*ew(pBqfTVh#Kg)yPl$G&u32d@1!Uy5oj})iLU0(_E8k66VK)PQ;y5wxT`2p1mCUp zJnWt8_MTTzf3)^p?3dxMm=Elu;m5E7t$ANZhNEacn$+4|P-~2iC6?kMD8>Xj`s|`8 zn)~^}*pj2ZSKiJD$Ym~Afud`m<8CvG)H9l|kDWk~T2i72dcpfDPq?Ub;B2YWiPqkmj6Md?Y<(#0OQEVTenM?N2^R^SBpxyph@;#k1@Mxn5 z$|VAwUwuxV_|prm{9|e4QWo0G1zXvXo4tWgdjrm|lue=tRD^ZDdmUx3qp7~ztHpmE z1mrRod>8M^=sT(XO4}tKEE(w!Uc0V9Qlbd^?ovatZg;Bh4m3F&*Vy&k=vptVz;$uY zGx=_;#jgwFE=A?L0rms`

      ;6df_Qf9zR25;CCAnY)u8Y%6azY%vvZCL3 zWRrxXL=mvG-m9HO`R*wzJNoa^&PyWLy5QpZ(0jE_G=n>622X9ZK~>K&Q=mi<@M*nw ze(lY6iJz%@{>)hi9R%bu7p!ip=c|jUW;y$0fAR&FtGW-}x>s*6a>T*?cAyc7bS>jq zLR>XB*Z;}x&lN=?(B?Na>FY^U({D!c>a`3A=8`?6w*g595Pw(FH2~RnMnDJc^v!#z zQ^*sar;)#GMlKP|1%w?rPOz$!_hY&K2vrM*U-3Q)XF6hEYfb^M6TY3Q=gVj(jCrQ) z-cW2M9lv7*>l(l|@{%sJYUk08ULqtHW)rJf*8uhq;&9{jv9VM&kd!C_kx$oT?jyfC zZ)k0Q9#vQ*0&V7UXYfHnq+U1>TSHYGNr@uxRMQo&8{Q_rA}?7@ULp}_GZ(DO-s5>E z6XFM|p6}|f>xoQ>BDhAL&Ua&!?^0%FPZv0fikgf$X)yV20p+{Ox`?8>TB9R1Bk&~B zHL~Gk-HCM4@CQ}AU{OY(&0Meop6$9iIDioMT-q--o2qJ(5=9_0&=ttnDSI7ECk+>V zsOyO=3uxwo6_73IYV8+-Lz_B<v1=ifh)GP2`WdPCc9uH1MK}sIu)+${9^ZQXiqk^EHA0H8-990cQ z+E}6}5`i|qY2|sNsjBw%?32T{Ga#5t_K@zwQS^b1&>&>r837%5$4tMgUy%^oY2@|o zX`ix*{A%Q>yGyswX`f4R5fqh7 z)frXJTd6|-fr(cv3uxxTY*L&z6?&Y$e$-@rqB)(uN=g(#PaIQq{++yJ-(9uCN9Yt; zBG6_oSeKrtrb2%WAx12qs`JG+p1QfNqQ2`(ekhhsk#t0lCcO&ftG3FS(p5^o8aw4$o~AVJq}M zke7T%_4XUcOQbBcnG4pXIwJiKH|Ta6L>H>iOG*@BEA$tUb?Z$wU1D}{RFfBU|B#j7p%bN6c(|^+>K&N6ah=? z3jMic-C1PaMdof4BiOp&VjJq+-7?yL^ri~^VzVE_e1H-~U=`@Sb2nNa@6q~r%P!61-~%G-8b2(c{EqF;-NagKE#o6p28a-`b-( zT(Vu_If_0#>Xk(>m+YbEHKbkYn}m4VAY|Ve0Uh=o#epU55+NrTyc&^^wT>TH5f7orG623=<``;P?eKVt9Y5BAAeXsdU1R{}q~Q&E z;>4-`)j?$w$%VEZIVyM4&fHzvi7I#S3_dGBn`_oOO7JNFs)J2?%`5Fs z)j^lyBDfmuc{$`IKVI4|QEotaRi{Q?g1RBl%!S!R_Nr^IrxW7p;d@HYplYq8L=jxS zrpi23og2_8z;>!SO9a}?1?ys8qU+S=PLW4L(e;%#_O{c&ZfgBzAEiz+BtmkT*)*pa zKr9%xr=SjGU-C>iGk)j$`y$D$4?zxnKo~`R2rA96fR7-c{T0u~?sN zGbM_k%)p!i+)4Y|8C0|UoU#ll3vK4YeAp9{+vs_IGgY>SP$mNkSFq8hr@s2~7toX$ zm~(?GXq}H6bA!LDw$3t`A`xiwmts6`1kL&JgxGAe3?)l)$sXdXL+uh@QI&I>&1BRF zB?4_!JoQ%!_7eglUuZ@yN6TD5*pc5%h{-ha<7rm}3Py|Xd!P*~;2Rm}73Fq;-g$+3 zujbFRS-7G|1ls)dEE+i>eoT$@dt^W`7j)Qr`pERR6Qa36Fh$Bmn=<`CXZj;nT$XtC zlu>@Oo;`D=EXjqo{eoHHeSYGXQ||SfpSfP`4VVHhK97)+=nd%?FG(!^a-?6eX8OL5 z(jG;?RywCXM`z*wczdTvA=siKzcz0{yhB;|ZFFw%h`lGHC{YAX8uZD}Y>J6(Kdk7_ z8=k(4qYzjh%!Tzx*`Rrw12>!OuCUGDNzI}+d8wvO^*2PMzIg+CWl0zZMk$6 zSHDSun;gqx)nh5T$${qw?wgDI9!9P`WAo@weuXv&o>+Ej;n(VGfk9C2;ZsxR?#FG@ zAXw71W@_?%Xdek-xfG%>GlIAbMam6=*s|kO^+$c5L5D<0)OCf^H2;wpnDK`lIt?)|nt-`Gt zbV!8dQivckg18Jt$_;|;lZ%qESGHu(ArY2KA%e^Z;xZH|HwdmjvsUt@*Fc1<|u#7sIQ!g48uuMuPD?dUUqTv&V^eWO8sNkx9S1?$7En`Xzf z@F!oksCe#CEu62BxL*yCh>dfa`xR==EB@dPeCx$hB*OiI$Ya!-KhIoLd&794z{91xL=L=i4e`}Eh@%;r7X$iegmc|$=-DGqT=@nA^Yoo z%fyb4z8p!M6-Y;o$jBwa{RYT~#QFS+g~gRkuh>?SOMY{N-WVaykb3ns{TJ`izFW6W zVWXdZZezYCpuT2w+8yit#sg{<-n$Gpft!$yRt**v&nJYWNQC>fo?nRb$&(fpe-}YW zu04;{3WlG1M&Zaa@kY!W#5rl(!s0rlOHw34TAlv&Izp5?dr|QZ^j}Gl2>CrB`XUg$ zA>DM_i^cuRy9mi8R~mikmU=UhY=v(jVYJ?fby9C{`ngT)?N9s;n`@;GmF!V=v)?sY zcd)r%?$F}mf2(K&QzYU)-Picftge;n^%ktVfn=XwcTw@bMh7D#mw6A`e7WTyagHD_ z*+l=96p4UE*ca&E)T416`~1S<1`&khlHZx3H&F?({isF7uM@(hSh=oWHMnq)-|d_y z^9wt?osi%9Fg})ASN*p(^6MV-F7od!{jW~FJ-+vF(@;_*;_sKn`>$VEC$;Zr+#{W_ zv!kEeDOIwn=9vyca$W7;;6FN{PO63a7rHw?+}(d*^&fcy+IXStmHd8*)JI=Coqwr+ zxcZFT6>pvuN{U3tZ>M-(Z$cb8X-4k82tsl}5`8Poe8uCekB0cI#{?xEx<8-DJHNo+ zlc)$7eEM>Z|MadpsTt4hYa_oi;(48Z9_`<@@T}aEYSd0hibVW+PhEe)p*pEs zTcH--W$!q@%I00mTeN&5E)kMTewl=#&w+9N3HQF)s{4zb^Cd+h2Cl8^e}1q|s+_8~ zcOV`Ap73U?A9}tKmk7z_e(_}PzMlTQjelDH`CEGva;7esANbcVtCL#acCe zf9l_lwtjv1^Ul{{BtqJd?$8$v@=ty2mDVS0eA7WlF8QSx&wKrfQT}y@p2#cLv~5CC zBtqJd{+*v@xB08rRd4y-#xG;?3qA5%KYiXT@b7%9PU`E=aDRWtp1b{JD@$5muy=Y) zQY1otPl&$7I%2RteXds$pZ$u1kX)xXyuhEdwNC1K_4fLT=g0WfhWokmHysy~6p4^u zIifSKRipeilOHWk7PoQ`l51rDdj9c$*Gawf9Nuxil;-^SkBV~lcX=Z&DH7q%IsEFh zdb?W17k18<2+7s|+q(V}=#U8c?Iq7U z!E5LLFl}tfbC;auAS74+$8Ppt?_VeNdM9{Ez2>+1@80@Y?p5o)j7f?_NPqLZO1Jj# zgI_C_#AY6H5Rz+arAz(p^Xb|3B6OTQY_R{~l}%f>f8~{!q)3GH(2P5;)H&+Q)#_0MZ61a@?SD~-TzY4d~w8FWa5<0MZ61aT!bMepdijos3@ z-*|1y&WA);F1-uOj3BP0rsy3Vx3OF5xu{$Q9TH)=^e!wjg1C~JqIY!MR=cI9%w6=m)n~BX*2ceuHzQv z{!P7-_K{y2lf9*Hi;%5OZM-OVa%3D5;eLDTa?0>eN-WHMsG>V^$tA5$-y9$vv{%ce zy_)mgDEEs{(pGtdn0fr7+!>}rV&+MC&{<@CTz63} z?I0sx<+5^JzuG{1wX+&L8Gqx_w`1~)Nw6E&1LQZ7(tEXh+N=4JA`xa6R#^2QzB%&e zj*kBRYg2i%Pd(E?NG`JjDExQ`@{+eEclV$D@Q;!aZ9QN1N`3`O>Pzp{ifON=@+A1M4|+b_IVE4;nOUf!#juRxi- zS~2a_VrJK%C}yvw5N1zRIQv87yJoM}n)Yh>5+S+d_nmZxoEY-vJ1;Nj%sa0D--nV2 zlOY%C6BF#!=AQB9J3sb(gLiidA-PO`t-gguZ(97?)9-NZPpv^A@9gH4w$y8p|B$#K<}(c~A?Ouk!q)`hsEGn4jepT1YJ z{H$N6CnQB8%$~}8yY2nqgZ&Q{czGW``-+2*TxLgBxLAG9bRF&0rjPQA3pXB@kQ9lK z--@H}m(X6V(xgXoPg>r}K}asMzbd@82WkLjuU1TZHQsqCibS|`ZuV;L&|ZyqcM2i7 z%#N(EppyD(9qrY2*4_2ae;0L*ONvBDAESS9>aqg=t>fnA4(#60iPTtk98ulx_1$vt z8vps>-xm*juxcnN^1E|D(_T%*{PbR}nD%Op4vCOou=BhU+N)Ix_G*WQK3077x-S!wA`#NxJn!pXJ^TxgIyUddXAU_C$z^tAg_mCk9i#6V z?0>hq>GG)yUr9)cL`V-+nLa&Z`QOOZH#zVH5}e8*Th^x}_D*sdfd>6aiiiaout2bL>&Uc{7H(7z`i7X9_8rZFLywP<+68RA==f!_i3XD?61=2YK{(x zuw3$1XjF&f!roAy2_6X{Z$(w^~zFQgxVYOX&-x{(jgI+%f1UjVk3UV@0Fle5`n#8`m~Q{Q0b5e%cbv0>8~mY z9gI-lSb`3Tpte0xWF6E)DN7*?mt6l*9W?UvI}KK@8k0R4Wm_p75}|g*%Azt#M0Lpb z?#L6(>AQWSj>JZ+%WvmlOcFtB#hj}PL=m_o!gA?52>M$#0-?r%+X?)Y8;PLRY){;I zY9x1mHt9P6agLl?F5N{zI1J=Os^PWxgxhk90b3s zjro@dSRq{_%ZjjE_NGc%>tfFNJE;y8m>J#xj%>6JuSE_+L}?8y1XC#)+Gh!W`DR9TH)Ln17f&ad<;h>o1RJ<01sBFOVi z#rsGI%cZkHe0ibl49ffM5<%>bu2dt&68Kd!j^;R~BkN7UN*wO(QIq z$_9h1S)ZY(JkiLVo1}GPDicCS5o|?yVj5w&^f>f8`~u+tA+rpLKo6aKm$>ogA}p88 zION0&nD!J6jQ%U-&KU&bl!e+t&2)496K~z`JZQFvMwqso@f)otn-#t z3R+J&JT7e5a!83h=XB3Dm90!p4aB2_sGS&6f^l&4kqCKSPq$uHeo$Pa?zpf=ofp-c zNQ`i~bPliQywTTFBZDjkfFT&6yw z?m5uE$o5DA2~8sD)%Qsk*V#>bMVE;?#&iFft5uwKvUjt+^CHwx%qGr#lElEXX3 zhV!PEIta-nZ;sHvSol|Nyw-!G!f!gpA~UG>QCN4fs_uD*Umcp)==>4k8MlmzxfF|V z$FcdQyYmWLjSg3~Z(Ih!qcv4db!UdYxqMGhlKaHiaQmT61un(f#~nx0d4u2C_uQE9 z>AlA#v8SJvV*y^o765 zYMuLit{RdjYh-R+Ovc15grIfquUS4M5A(rMO(JBim)^tC>)gMfjvhH9TrOo@6BFy| zb?(zTS0g9yQxu7iHEa6UHWw7cr@S=If4)~owyr`*E?I~5yc?z!#K#cg_Io>)N{Xxq z8-FvsYB_FiNrkJ&`3r8I?&y#RS&jC*|J?p)$$=eX{mM_3Ita-nPaV?h+^2OOiS70Y zU{vzpcYOV4}wZne(+ z^@lcjCgPp!)Z4zkQBF0DSI_RM+U#smHiwY z5+Q5k^zSIHQ|sI>XP#=XD8}J(*>yvw0CgG^Kem0Gf9jvR)l-evheWv5bFBD0 zj=*kPSAk_E1mifRpq5{~LPw>;a!I-F`v%z&s2b>Mwp%a3w`+fkwLQ0|(qXxzT=#v0 z>L!pm8L49F`*Gn)^PczN>ibuG#*!U@J*V(p(}oUOA0e*~ z%O&ONdt`jZk{yAauvmkp4IQ-3Ltf{WOUl*v;he~j5rG}Oh$ZP$85Mm(j#rjT%2lz; zoVTD?6yY)=DB7h@Wo#P=in}4lT}zR2^@+H=jJE^}63jgo#H7Dg<^AnquX; z?*+U=X2FL zI|6G(bLkUIi`brDi~fbYj!K8+l5+J5=IS|pF*FMTYhH8db5)C&LDA>zb9*WsmP^Xj zk%+6D^tMG71Y#FgooyTQadz-RVq4uIN{6LLxhA5T+G}=%iouFYR-mE7JPni%%O&ON zCj-~1vm@{<(Omk(%p#zNYD`Lp<&tt$J6)&N{87mGsGvS|1q^w7LwJ&Mebwu!z>V&+FWBNx5pxr%!&=I?srp zC}Fr{-52Aac;$1vvRqQGie08UObA4{j0lQ$=^CQm%@@=^C<%yV!q} zL0~T;V!K5Y(NoQ*ry9q0Ly>ar%|p+7hMsC8^xnA)!rpt7`@!W`oYH#j?<4#*j}BA_ z-rdPNknRo2QbG*)V}$?gco!kLS4@FEi73;nv<``2E}*H00eYC$kw!2DToOU!2v)BW2tYk43vK4& zwlnfHqP({?pjxyV?XOoY37R)6Qti^(%Y#$yD6+i*q6o6iSiK?HVba%%Yuop$lLN2Y zqS`c1Nz9XC4DtW?1A-}NOGKIZ06^)G2<8Hs=0Az~SB$JfA(#R#iJzD-p08yvNa@Mjk;ZE}(Cz|5Q-UyDtOc`>U2DZ|gf= z`O+J;mnSDS)@`1fv<}sPELycmUbS+~)5w!p!45+8iYY)#1bd8wP<|y5%mp-AJ?YFx zx>rmAmqf7Vm(_vMVyyuIEASdDV_iViIG7Se)Oz4qCCSlI2EklFXP*zIfJ-8-t^ZWg znZb0gB!anszUiGOC|+fnbEbexBCdMpiKK%_>yQZM;&IHHdB2_WB0wYsZHa(B2a(o+ zae%_T;x?=RuLPsLa|bTzulJ65SINci8GScBABaofl8CXpKFBh1mIVZJu?}YqrpF<@ zL?WOs^9)J^b3q4tXnN#n9sHaC*8^kTRcqVyD#+R^MTsIF+Vz3!C21Yht2BbSfadrJ zMmJ}WT<8_gV0HvkxL1t8_%hGAL@*c7wB~6XnV!x}0hdG|9wYLl$5DgkhTqGa~%G@*v9FEf?A{*UF554oh(njMh4C9e-!| z_s{Ps9hQ>gE@%mf|8fR#1CcmQ)tuQd|V1F$Oh*F`jcvQC_0<SY3^EoD3ii)CY_X|n(cj%y)s1Pp2 zMNkw?@0~r5V!O|=-BMJXPw%|#@6f>r=&%$Q!TWabt0#`n&nQb#PqlQN$^I@8&|xVq zf}ULptyFmQto8X>Ybolvo33Bk-+^HSbXbaupl7f`YaNs`_?$CXipn3-H30iNFpPi> zOK}mL)oL9SOZ>|H^Oj?6TZ+nq0%T5*WPjHfjc_S0g7bOBUqt^;|3l2OT&A659S(v3 z_)F(kfz06qBB_4|@8)*H{o5u?P5cN)^lmtGFqf2zHt#I8j%*0al@meq9zP*=sNHa-gSn(!v^m$-It6zv1whfGoS4@!zw0R$` zb!0$UJ~P2!dy}=+FaMrIoZzMHiYHMaS=|uVlF8cZLUnEZIzC25@ES=T!a&^m`lnmz0Y( ze8EPaYzWJx{mLSYCn_DxCFP<+^2cfjfDkXg9Q`fcVMMOccf zPiC*K4vDZ_HX|?FE7=pf+me}cv{zEDMA%*5kr0;4?s3cZigu~$G#u6?ggP-poAlXJ zGG{()1wz?Mo$vxdR#zv#X&psqnOQTZVJ@PKjv@tcw7UqaJ34YJOZkX#;mU)7kx4SwxZwK10Z8rnRj^JznXnty=CoaP7;$(Doqo_g@0Sj6DbVi$>iD=t( z6V)Nd!TSUtICep<+bc_vdk%MRkR8GM1nA&+TvmsrNV)Fbz||oUyib4*ey)_&VJT9s zyEkxkNCfW_pu^5n)K-=v<+^(VSBFIKKEdcn^8UOG!ce4KcW;m#!TSX0;C#NUtt>_6 z>UstL-@W3z9Xe#*p1oI=OGb$d)=ftriGV(wN0uE2SvQTaTy70O^{NP1^jEGT&H(Xy z_7!C*GXHe*M0ey8!5JWQSYOC6@<7{N%60QZSBI4)xnx`sI*OnjbFNQ7WgPtfIv+Bw zl!A>$)S%93AMij;e#IhP1Io3h^S&WEK)xo%$K zc|Xvu>ljss>z8VN+NFiJ^&LlE9i(Q>>`Pb7|ccLEr5U>0d1fp~G@Xxj}06s#b-+4SK-n$cC_7{UV5qX$;@0J*T8dxdFXN zo%+$%wFA{ai#5d7{srXt|_ZtxtO>bYw%Ihnh=| zBaJ9JmFgv*s-2glNV(c>ovs;e<~$n$meyQ)KGKMy52;>)N)CM2a!I**{+l%$Wprdi zz+*I*_A3XGU>%lA%GG|H?v+P6G9s`(cpSD3>(aeI$lWxJqOc%W!t2}iC2~)P?b*hLE3D#jLQm)eH+i_$=P~Q!g>a9f-(a1x#mF1FhmEC;Dx)~8PABIa= z-6D!;&O@Ga%O&MP-zv%}@Eu|NWkXmlUtij=GLg-)+BBB+OkORoZppppA*E6XM2D!ZA8fnH@pV4aKk5QuEi$0DH5 zMxXQ!vIu*?D^5B(HD*4t)F5@%$G;{o?v9gVH^M0dapO-?Tm;a!=Ii~St3zgFmP=+% zw9IK9xV|eXT8Eaad)w_py&rUS$ovXp(p)lgGCI^KFb9fer2#~)%~iydR07VF$wYNJ3`ExT|RvEP-UukbwRW& zgK#Ao9kEP0RwMSwnn%*3?g9>++T}!5#N%I z8*{_h33*}6rRbilUWM4M_4Pdw?H~2X{Yws2rtB4zN75rl-+^!??I6V5+2#FDjIHbl zE!stxUL`X13Ui=)qUT2Ua0}^J@NebBGo*)YHESknme8RQt`38US;XwLTv!@t7x6vm zc!B03$BZ1F!S><#cM%!n>4f7m>lQ(!C~s}ztRX-M_Iq(5o%irzcRYbiVAr}!85FV^!&Rz zL`!Tq9G@+H~Bt z6s?01=xyeVOd>3odU6(Wjm&+X({s>Jv=umq>s6t3VdjiXA}p7B+7)t*EUiOXm!6!4 z5~L*J^NY_a%$kv<5td6mIm?bi>7eIedK?n*Y{~J3nKLqpuw3eC=gx;me@X{E2Mr}i zNkpZ?2ZGEQnM7DF_2hK@3OeXdQi7C3(9SP#JW&H82+O6%!8Mumd?+3073WtH0ezV> zGKsKUdOoe2+QT3-KA}n9=VRM+E$PCdx+%9GuCLYY@~J(nE!VZW+%)usB}n#<&tN`Q62V) zqrF7S?U$N3yjS6>DyC}S=#U7@CC|L0I_#5E%7vx-*(l07ieM9ouv~H#M0MB|CFN>; zvulpAGe~yApOhuJ!1)!N|jS;*ls%z2Sg;ZXXeBm(VO_n5j5k6iW2p73gf z=5o)Sm0zWGz!UlO&C1oj`(%-+WjHz{0%Ou#dJU$t3C%1j)Xug(Ohz^2n5+nSuuTrvFC;ZNsgk_+w{qgyJ{_^UrHiQ zY<)^9a}<>b%cVwcPHUpQqLCX)zm!Bg{py9OtWh+Luv{vZlpTi}IYkCT>6elS`nPdY znWLygST410j19#&Xl^70qh-1MQhQf)OJ$Ctv})7yVY$@$r+t<94hzZ0pSB`LQP_&3 zD6F2MM{P7U5=twuJ+x`QPj$kTzU;=_C%~Gj-s#v z$6c(I%u!S#ESFpbQR^a>@cNJltof`_G>x!aa;>;Js?pPVrhi-CT@;a3JLI-Kt%)Km z#YOb(TR%CX{%#xF&3w40J(kNo`H|~GQmWAnDwbOS*{>+cXOM2Ms18FCa5^cuv~E5bjUxDD%sp4LR*zcOQd|UC-JBI331PXE z-2!JmXz=)x6g4+St{R6q&5Y`>Hqo|Py$WaMM;bX!-?U9!1ZMN0FUtPgPEwYhbIql_ zhtIalT31tC1lcg0HSkB(fPxJv})DYK3U!f z%hmIg*;bfm9tT-8U|ZqTI7v(1WPgc*lLST6Sti`y%^KBU~e$=}Xdo>={R zM2G5?L|86;*PzTexL0PKOSyZKmCoKAp1#*aA07vfJdLni^5zivr-LBtng}Q5?oIwu z?)>DMkIah7im+VDd&2bka1i#1BjxT*QgxF4r|-$Qy^;varN_Z{SX>0g!8a=;0zGVe zv3b@yy^;varRRh1ez-aicQr+iL(A26+fmiz42}+oz}{NxAw?0H1$& zUN(fiUqacLxWnQVef8C!r8#GfRXQw1%9S@@;D6Z=_MS{Nac71AMQ`1CVp#Q+tCbGR zCFQy|ggh@B!ru3(rfxv-36@vXbZM{f&b@oooLep_SKdg%II!?OUjk^i=ZPL!rm#8aSVuT5zZoH>;mFv zx-a^Py16XxUo>%Uz|a#lecI=FTL{rn-CXV>xFn*9xMc$!*%0zBj%@?+B;CfnO5I%6 zz0&spq}(P{UE$j>M?zRGeRD+L%K+jgdROK!jfL-&Xo{4J_7WPou52F(!CcV6ZKES* zbudNBMVoI69T~w~(7|mW$W}hv%2K4E-4pneIp4PsK%8Q!Ca8UZG%Wy9ZZpO(bo5*lnUs`f?zJ_ z;5INca&yaDQlwnH9_@T&Ltt(5eAqU0WQ#tQOU4x-XwF0S5}Mm2&megWwe=l8+XljX zNk{pvrC=P4Q1fr@8XXA%eS9OywtfM?zRGSY0CAc*PVc7wsivh0O6v zBA5$0xQ$+s4jHeEEGZZ5xVeRPWCU|T2e-}0MZ98)l&kzo%!eD{EP}iwJs-9W9rVQU z`59#?Qm*nV<1t4<(6cY?SGG-vBJy3IpPZH=2k?zC$ERZkq8mf&jyTa*sj?%Q`xFtVfmw^BSW8^Uts(5Zt!6ctjI z@q&7%+EUOf=0bb?!Z(AyJN3Ur<9XQ-mMh0a6n#%)sA9er%3M+|TLCsyhVrr@*wUG- z%NAC)qM1tDO0|JtyD1$-S`+5PQqU9Pl4xah%}c!sc^p`GV$RcT8eh`dDjULbDO(8y zSvTbQU@l`T#f3J_P14SJHiYF;Gb<3}B?%&_>Rh&~y-ACRRqzV|#8gd3yceo8L20=N4q+svF zT=G8Tkr4LQWHoVv5{QAcAH2oXeJq!hEAMq431M%4RueZtfsj=k%O&ON`-z$BJ`!PX zu~t(z8q)};?qj*6TzStHy^?hwiLkeEtBISr1aRs;mP^W&_l2QD)_o+x-b1dY?pbH9 z`&ce1SKfPu4q5k+2z%?gn!1ghx$a}Rq+EG_8#>tA;fYa%uIT9BGuM59;JS}&+gqB@ zAS*?gxwNe^*L|!k_vX62I|?1LQX~pl`;?+EKPXzM;V(mKD#)O{?Mlq>HfLq|4*ja@pH@a^byyo$j~ESHok zW7oj_yW?m7c5|ZdYa{(;&8AUQ%PE{W6Zc!~oz!)APfM*Y$}7C@Rotz;^w#I|6O}fW zHh5&L?@}xRXnW7L#mIU2|HgYHhJ7}&41&47nldf*bV1v~`gL&c^^u_`m44l>R(Qk8 z4!%pVax3IbPd)O_RfX#h;J)yv+Dr1=>^q$3v#`7GQY-?!vNw#wcb4YgbN`v)h2uMx zK`_^Ck4;Y{I^9tCMjyPXcizTl^VRGYEFC|^=kfCT@xK{)1?xQjY z=K6Tp)2X5pdKO-J0B@NB(UK6?Zu=rLJ@Cm@h1+N1=JLmc*jmycJVXeWV&$IH zc2?^1@7fhk`~){lmv@~WAN0rJ#F)k1LziL^=oQwAzTH1Z5PvL~ns}BFF2%}y@10qxnl&31KC=>t|JT^Lz}r}6fBdCUZbeEL zy2uD!|u&(mJ(`>f~wto^>vdd`Pko+|s8=J_?##w1;d5L_xb zpIUA3yn=5!T^_r8=cqKoYQ3{?UeIaM6@`;$vW@CQRO@nitS=F+MDiUsVqS2~V>JuE zX~V>kQxnVHyM94z-@OkcU5OA}Dmj^3_QcGB!8>aBwO98{BdpfLjpqgZ-l|;a&Eo!G zq6-n%5aCKB-#4es4gRwAoA_rPxzEcFC(7Pze~n-An^@A72*IV2Gs*WoHl?8UA8+yR zidRe{tk&vZ&kgD={38DOU>>`}h-geiCn8*l9D6<%Km$nQn1%PHA3?1+mf* z4>*LYB`rdK^<@1y1>3v49y_>vnA28BG%TALw9Bbn_`)ab0Wi_O>+7+>5dyWa-RL(| zx+fD@PsW}LXMg3|vF8VwJsFX>C&}gHdeoCa!fLUtGqe@0)uPv&dm$sl3Rg|okM{~6m-nLQbi@OahvvcEDa{y{3UCnFLexKwg-J?hCI zVYS#_@eY2R%IwLAMDk^S<<0(wQ`(c6PM%C>@?>r|o{UI@u%kqu@;@5!WRS2C1MIJS z-~Z>7_GFGkJQPVAhRc930Dj2@h*8XJ;{^FF`kSq zI}+@p3><%Fpgo!D#*?|(cruniEw|~=jFwV$(J(<m0_(}x zy`6q}5iyWFnahnQVAH*e#P8_)F?mb;$wr74{pCD|Xu0R6XeeU%0`HmY7ro)b$#0(RtxjxH1$nN`aByUTB>J( zpi$!6ab>kIUry5)OUc;HMu?Ugp+L}R_wD?!T9_}VX|AN?{a`jiwA4%kq5_?4;~QML z2RXvUMuTCR<4tVbgy&@=L@S3QxPaJ5Cu=TI_a~wR<1yT54q6wp5E9Li!;xV$+U<>t z|3~j252({rD8YRB%~m2Vr=znGqNT@l8ll!J(ZYPSJsVx)dB#Q>A<;Fuv_gDOH9t!K zxIaV-^VRKUql7#!8zE6by48g+J*aGm7UqjlNi=C~pQjNL6QxIwjgMl6KYC>lEzDOD zVbqq^2f|2@P-!5j9x=YV){I>w!Zg({j6PHK$ViBmYAYb9b$#0(qNUo(XsN!TH@rIj zL-j{Sf_l?vsh$ObMu|^jSB(jOF1JkBSGzFwA9!YB4KRA%t~z}n6I|y%qX^z zMsNwWmaa!gBxu(9cAkqC=BwLH){<-lx3t#M{Sgug)8{_dL$okoJxcUC=Fuk`L8H>d zzUq-E1XI+K%7$oRzKSqwC9ASN5V(pO8;UmHZ+PnV@A9`(J^Og=W^FwySiEpSYQhB-+EE0=wA*QvdtPeCG1VUry;!Tz^L|u2 zGNox{`?2l1CmIF)7F7wp{Lcycz7-MA{jxW2=+0v?%ggH-MFD-wM-5xdW*UK|jCHZWhTAN@UVB3fN^PwrJzDpw*U zaqH2Xh=WhfEtwu6Q0w5#%Yu#dykO#qpQ+|=6Y=rU=_U7WKNefj`DE%~uLkiG=T&T1 z^h|}Iu-V}FzV|A$8?^1LpzDeS@ouVhA0=W*rz$0rsUBFvVe5{k7QVYWd1wIFR!T_E z6NxyZ!>POuR4SAp@oeAYsa3(^R!`h*+bZbsd~q_;x~Mhy+~cWTH_Y@;4P~M`*{E@U zt^CW#MxEzt2m9~dAAhCNskZk#a!F9J=ZW~3hkj{$)q+OBmcdmDD}TX#-iwIp?FZ$Z zLj>l9t$?MazZp(M=V>GI2SncOT#^&qE2u+F=ad=?IDK)3$9iAe~5|x8eQNsTY)Bz8Fi$HnI^CqgdobHG1Be6wT2@ zMLVGc^Tn7*wvmmHSj!?OI@3$+38S4*g85=>C)>zINX%%F6J_cp9;IlfmMYo_C73V9 zsIrZ0gv7oUsn}i{E$bzEQ8R$@5fVSB+e(NM>W_2Y=t27+N-$qH z4$||o5fas?d)7uyhNDE;5G~9X<1V=#W?ZEa63?kesEq)n-IJmLJF93XlwiIXKgu?; z5fYcGXPS*<4QH(?m1tqU7zfKX%sfvcB)%5cF(x?LDbork1g>2KB$(2ENm1&rz0V^* z;V|tJyxP?>>Gh4|d!?-YANxKiL84+Kp+9dpG|9l=ZKbgZzvQZ4qw#7bZ3ixHr_zh= zSf8 zyIFfUij{t_-FqIBA*`iPW?$ov9wW4|F|{ zkQmHpTOlD@ZmgwSDv7nkXvzPzR1!JKgpK+>U8zLN+Q>8#ar7Y}apIY6=y4@lk+I8j zFhT$5(>U09clA`qam#6xG!7n~@_6d#sHG~6=c&~`s{zsyiA(%y^QzRUKQ7TDQO$FW zxP)lQX>8U@vk}*4v+3_MZeA7F`6?oApWLMrTH+E^r?{?DCL5LzE!84%-6Bz9YRP+z za+|ME?L#tp8o{v=rz5C!Oh~l)$lzg!B`A>vL`NCx`cpIGu#0Uc;C{ z`+fTAgA$jZxGCxzJ|PsfArg-BvC)#4Q+4R~=t^R;9V-I<^ytgc(aTs`*5$8$YN^%Pj%~rELv$TXCsu^g7qc z#-FG4dCHDm(aH%%pT9fx%CkioY=}g+u8m%oIz>x``EuXrIMEzlgH0<$36ZFA6%rVi z>ej<0o;9`A<0`FnRa;5Bvkiv`BS2jnNKhJDcPh3!?Q93FfQY%|?K_ZH0tHOX}X#fA=72gL*J-=LGMZ zcCPTcVk3)P8zRYJFC!#)w|jHU?2P?k^U7f##b~K|#52ziUdikTN8;swJhAxw_hx0Z zA%tk@9{lek5eeRjGS`E9(9UhqQmtUt7}L559+SK>VC!PL(QJ-qo##fPdd>6!r_0>7 zN+=U#L-Il`yGLbNui~)!ge}dxUFNo;aTOAxg}W$~Cei%JD1X4IOJl`H9x=b@aQ|4; z_UZd41iSm~PQCOhuW(m)?6v0d4@ddka_YrgiMyi8%C~H1k5;2T9pJy$;nOt2YF#j6 zLQwsiU8z;iv5h4}6dxMkAL{gJ%$3Mm+x*OF!I)!jrgo=zXSi?h@-@dU8sOi0-{F`m z5yJGWSw;8vc%#)V)m!*8erV=L3A;Z2oIfpiVa}@5jK8yuLquFsvxQ&!Z8P7M$m;y^ zzy2CD{c>We_Cnsf8qNP=%_e%g^aK5KB|>niWVf3(?cc3>KYk>3OWXcwgw+~%?yTTH zy&g}sp2Rk$5^-YEky!o0{=O@beBZuxUhwLH^HM9H=6T+GeT~xL)K1%|yC> z)rXwj`h^Q}V*@IVN+YaRl1>8FZBacHOk^9?h-gzgH})VAu0--}arU#po>7;Uzw|z@ z40TsrTl!hkda)zBNBOQq2riY(`9Ixqb?YErxxDh~(P@O$n)3bppxZZoX~o@a<5nVm zX>At`J|^pX;%%R=3ifP3x8Kpi;RKAxvAD^|7exjjeO`>?!~H z`a9DIYAdC6?!EJZKdh`4-#nRZJWs@tU3<#kY<8#bN@U$V{K~9g_13ZR1?{-cH|`r# zdewc0%O_F~x)LGGxH9W}`*EXNKi92k@~0`S(g?d7^q~{K{SQ4B@9`Ad=t#uwu1%9G zr?&E4i5ev;-|=;(2fwPdBK}fao*yk66qR-k!j(wA*F8Tf zSn%_K_>=u#B;s)ObIM96vS#CT^2riYZ;Jj}X9UYsz`GI8xQNn7O72K@(w6urM z8TiZ%ueE>p^D8P=TYDUfAgyEd!(a3Xb4rKu(l;Sk8z!eX=fq_S36CZAw=Ade99hQS zwTiHkC}B^!rQ1NlYB9}wt^Q3NEtQq9781Hnk(#SgAz`(w4I8oU)|?3&*Ny~_n9OZO z^$70(z_VELTRmD2D=}@Q&UJCxo)$}QDJ^;A6)oI(kwk+5g+SkJAw&5H@E#c4Y#6=9#^ zB=~7I$8GDs^rfDj7V78t?wteS?+-V(gPy{{S4a<&%#PFYv5G`vX{rMG2@NNM2J^;5=65Wpx{g_kcQn7WHkofx35u#Po z>^Pa~q5DAFKtkf{qc)HbEjRMst+_mGzWa8$ZZBn14ot-0f5kBv8wZ z2E3Sv(t7cdXFDHRi!JKLc46ysJ#MHvIIorThiZ2u*tW!Gaer)UxJ&hi=|M%HmK(Lj z{jqlZq2`Z~4ZPRDy|F+>k8Z2R-IwOgqPD`AT8!cKJnZuZWMkG-)$=Q=kth-*-1|T- zC!%4$waXt+H5UT4aJ+dQ*Q4DfQM}9qru;k_S2$}?%e{qx zOSN-c_2PzP10_5vqy zn=hkM;mpAZS(o5hJ8)jFl?NiT76~`@l}E|C5s4Lp$p+@-YGKW}tu}q~L9@w`{y@Tw zmgQO7f7FJRpQ_O=d7&1r`JPvUh*}r-$)9+mTPnN{0@q5dS|ywo-FVNsw^k z=$YWX6Xv-hTrHfn1w`~Xqh^bfZFwY$1PP4W_q+>;`106ACBLQp0}0f^bAMS_GIm&*Ic#rZE6KOG@Z%Z*EAqW;rWo8M0a zMlWJiquU=`j{)~xxMHZX;r54(mUN>5dDf=(#PWZuW~~sYg|URX=4+Q7%IirsaP4#N z`jLLp^L#~@WJ!sXs*uMI67Ib}c9if)#2$3DWTt7qhZyUJM5ZFSuv@%(OLLyaFKFmhHCKV5WH$?yo_YDqtN zULC4O+viuccrem~NMJlKor@!4!n(6cw3i`yp%#ue-MY{J>F3;w$Of(%c#8|JF?zlF z+rOVIelD_JA;GO6cfIh~t@>{JmApq`UZ}-&l3P`n`0R;}#a9r4V-%xh-TA?zeZq%R z@}i?135@5}tvjd5S9wK|)nI9K^Q{?%RP|iI~;9c=@*!n}P46+&4`)qh?YB&l$z*OSVu1 z5Bj@ExbKjLk&Ugl@5y~t#eYa%sO7#xnnc8FSKOG_od}e;Z-FEy9WheSVa@U@RBVPw zkZ|7!^&}g-4_*)tiBDKeM3tQi|rl)~VZ>!i)>n;-R8`Bq_ygfOi<|nIuyEklIMW7arP|y30 zMq<&Nck&;kSQ#v@`%VYj>d#cFwYe7*?~zie{y@Tgztf+H>mJQ1-X9@Q%Y9qJGm6L6 zcSPVRZ#)-{^TzY~67kQWt8$Ns4OMd_-1q8zh?p^`c;zn<0=2N8=&hwG)mNre{4@$q zs26hDee=V_p^hU~^2&e`Qzu2>Ebu&^h^xPtlHZTUE)uBazIEbyOsu>t_h+)7xo z(qc?<&7yy{er)eidrsd-ggCEnZg5`T28Fl%iAyz74JIE#sVk;wcJwiDAXT* zKB{6Gs3aT(q2d@!T17{gwAH5vQbeG{C3KxQC;j}*oxQ_0X zTPpZ_ilPl;-1(`X`XpS5OHfQ~7ev+?T>R*>{DUZ&;56OOOyPHwrr>RH^vR0Ugne`EqZ{jVFqr z{CVbLUZ|zMH!O*TZ#;2pjs&%p z(ZW>;>Y;2%-@3giVx*0nURiO!5lP$lSt zdFhqY&Mt{@kJeoB(ql}|B8>Eo5|Woo@OZPgUxedIl?n;bQZ{Hb{wSkF)q?ARa~laB zZ;p*@gwfLD%B~Eack|}a$-li^iTrkM(R%cc`@_ce>9njwrFVZ`R`J0}{KYF%Z#CwK_5F7|S2nLk=j6~Wb=A(9)BZrJe*=nGhdU0KxN~~d;M6IOSYJ2f z>NZbSZI%3GVpBy}2@-B}|I{6ym0i7Oefb50hbY2YkCuw$}_gsWAQvMu6y z8@}(=CcpBT$xX|8E5b^U!22LP?+@b_l(qaKFM09Ve6ysR?rXT%qZX++jecpJ<@v_fuda!K#M`P0n ztA%$FcwYX|69wDnRElk1I@)(7n6I)I*W+qz@!_(AH$4=qGwk6sg6g5P@Wukq8%M;& zL^LA8l}NsLAB5+fd~#nw`QG)hlS791u0#l~IsJ?4ag`|CQ1<4WW3ksJ-=0QTExhA^ z?%yS1>a1h2c2jQmU5Vt2cO1~28uGAIQ4Jf#O^bo(x7wgpuC+jW}MJd@= zc=@dH{C)nbSGuZ z;N#kdH=dZ*HLEBS*H649x%I~iYGtsis7v6!Qc1T}QnwYZ$f%|26#BcWt&+N}P=W+{ zvfR3|qSWp8#(QNVp&698@$PoDV?AXfB%~xRZQC%N z5Q$5q*JufXeQ3n#wvxYKUz95AaU#Aobx?a5PV0&U zZ;&Wb_hr~SAlyF*IKPGkp)FONa#X zElQp2`ZvG(%X>4FN+d2JH%LTV7YWf)Hj%GfJ<{(b;7P(&mpli;$4D9c*MFv==USz+|$a zZ<$5BEgEzQt`a2bMzRkOKJYD`5grW z8N|GByyAUQK&YDYEYf#SxrB^-uF31YdL;+`RE=60pNp!w5{`UX^G`>J*7`=0X5!vK zO_KlUQJ`#y1otJi`h@#Oc0zWB^^GLWHfpc_wtRa1e#(YOFkg57$WF*!vc8d|*~V>y zN0uMC>S1L=B$%(e<76jfFInG6(riP2cnqTi^Tl1l>g&EwBg|f+z7O{(RjQb+2ktnS zmR*8vP|Y(EqNUm@+@nSU))!?t!PGNB*c5gTa^e%(Ela%|DrdEUa|dNzi9{wf>45lP4lyU z{fXM(yig18baDxl2=QF|0&@$LweiW5qm!TIogHI|y~oMb658|LSn;2-+1tk^r_Eok zZcm~eGT>*^czY7&M8D|UJ-s|gj!F)Gt-fOe3B0XI*CIv4{0Mn-88L|~KOB|3DW_gJvm}Y@`v5%8Mj0A9{GQH|86qk{ z!lpS_I$e6hz~rqjep1c^N^F|Hx6zKC*J;Sm(q}Fjkj$faWLF}k;#@hN*WOL#B`!VI zJ^A;CYpFZ?B`?&{_busI%a2~4So(Fxf&RW1!cv8itTqPE*a+{x^1L4?I(jaZDk`CR zgtSewj%q8PTi4WFY4P`{g>xl4VYN6Xo93M8jH0PI-^7%y=1yCACn%=+D|NRz-m8Ue z<#`;#ZSUCfvJ#@D?hONCKDE>L)Qemy(Q@d9@z-da__%VHILc05-nAaFkfmzbB`OBirOk8 zAzFBk8xz#$zU_0-QvDI;OQQrvdp1I})aU_%MxxJiko#P;)VNYwW;Uw`S1uEsMb1FD zTKYaR8zIe%-D~Z774DpIy>_WJkJ~CO6+Q9W>nm+e4%HVK*H6sIli$6MO6)9%nC8>crn8;YzH%aOWgC zQjbJtBHR;&NZ1|}g7dOAFdc2(%mi!IG_5WK*G9LO?q?niR?ChI8>!2xtZxbOqYAAT zhO~Tdw0%Z6UoBzl%F`oSmntJckR`YzNGP9?XzNo`_7NLQM73;b-BR&?SxF|s*hoCo zZn)2$KAwj={?4!Y*NZwe$776cr!{B%W<0oH8F~7OKnW6bAN3S%+tz~#_Vkf(wIU@< z?1+u=zrXc}IzgwO8WK-9}C1e({mK~LL1=njy zCc>^VLg2WvwbrxOuIFq4wXB!P--ZPLN9g0K{|F;}J2f||KJknWgwBg2a!N6^d(#yC_zG} zc`u39Bc0G%=u5aZP=fhpZ!08F3q5kz21<~~-h=Y&mEy+XeI2!7=1Wgi5~zh^I<&#npbwv*)2j@& zoBlr2xIzgMG~U8rESYTRyikk!-<%|m)&nI-(0Gg6U#YGQBv31Dz0#GA)Lha?|r`ad3pNBGwrk2p6mKtZ})x9 zxzBx0uRZdpCI8Q#&p)QZPwl^}dW^q6`1aB0_{}e#hkWq`KRXQaWc@kwdK^0Z)Z?~B z3Cdv`zaxfeew6%9DMN2DCX7ugXXP4;mkG#9)H5>3iqR>5@OkHS>L>|T*hhed_s9kU zqBD2ODMp!5^#ohn-eWK|H*1)9Sm|oH=Xf&MttUT*gpenu*2^ zV#h8k$A8~tQIgP?bgA{l~5}jFDtj%m`4$3)GH2;Glyr_ zl2^yIgvXJY6Lnid!p@b>)hA*op;nYTXH<=7^h=qU@QQ)s%^8J%sYYwUancQi=+LCA zLB0|p+kQedqn6G27#!vK1eW?}Y zJRW(5fTdr`%*5*Oy9ACma|-`bjn;(Yq#Fv+p-JQ6GAr*TFcaMhzDUb>x3ANJts%q!m$9Wxl{%!Z74kdp6+H+CIi8SUQeEuk5W8)d-G4CbRD#>Y<*a$k2#@u7Tml8ID9wU!=FQHaRo&MBGqqCs zz~>w_U3BF~oh}L0C}9~*-}Cj&WmbmPGbPk&{mn;Azp!;fPYl&4ao$HSoxE-LXZFNU zjS}mAdfN2%uU+scgj(%;=f#sFMhEr~*3IeVw|&_2J?O|!PA!hh!`)Sl63;$<^Yp<- z);e8wR|&P!PM3sglt^+@M;%-_OVldGZip19o~cHORMVpnYL$A}5IHNH)7BH$;L7mi z$IQFjJKHU@dZrpBa78$7)eCxJD4|w3Yk8)nqW!NpYpGFU=ke!H`eUdswZavHp2`@i zQDS%|Dxp?5zG9DWHkBh#jb5on37z?F?008K>(`t+eeQQIoUC4Y@rd&4?_W9(`L1*?FPI0P(w>pJlueV#BU^ zVo8~}hA~JW_WiT-8lncw7@43| zs%e70!LF>_`ZHm*AlNr}Dk=w>V?YDHN^oRhSH_?(*1_>dM+RfKrjHoxRVLsUR*4=J zvL--n(&&w9C z*vkMF1U2e6$;H$5Ad#)iQ7vnxeR|i4w*l>jt*g-(6>xCF~HJS+p0e+ z5Y#A<5VIl!?e6{`E;Q$^Hbv!;q;O7UP=y*I=p6?&3NwPopQ|>1ut0^-9!TP+8A_g_E zQljY9AVI4XqZ#uy;hK~?d*xl|ufwuZVgxJDoNwJas7Wz0!8rz^s;;&D{2jKhZ&rDZ z+I^&u>1kntR`5hQh`-uiyZ!MP)F6h+WmZE3tq_B9#ISc0v)k?6foc$gR*-FMybB8x zw1OwfLB#KRto?x%$0i;3Gp(0!jS@+2h#K!$SO@1)%H3xPWUDEkQSnx$kDwJ|Q1+~9 zj0MMo8ubg=#wMTVRW(G=3Na{044YT0Ij^WuzmR#RMX!bkT6KDrT3nAWx%%AsYqxJ7 z!NTMzWyCn{&R_WPWE{!)2vVa2WQ;jHElkh~F(_Bn;$2scZ?Nuy)##M5`qpeqLN$HF zbm=9wdi|4~vG9)>k7o|<+(1UNj86wmQGCT$Gpq;UZfxlIw1S}B)$HKCY zP%FsIE)Mbsf$UVH1ZqJH)D{)@5o!e)F@iAbI{wt&EA~hGhW!~Hhj;$eGu5;Sc0JBN zFsK91QH&0mxnq|Ka`X!4cpsrwy02AL52rbGkBx_Fl&}mv2KqNls1;;n8-(TW?;9qbQwpx8I)c|PVnODC#bSI$(Ugq^J(;~QJ||58<* z_^*Rsc%Q}ir^Qf0t&UrE-gK|mUo$%Tj7wG_rmtjbNbt*NWXe3Q&*#nB2UgUy2~-Xm zKV=LhXayQFD=!IZXa%2;V_vntPM{ULODi7do@F-%H0qbK%>%EctQ=V>0V~D`;*U13 zc&_Vi6lK)GJvqo#HAJWt<>=MFZM^Tb@dm9L$~exw49HbAM5q za>TIndwh2q57khHU+(oqj3Gj;C`XJ3Y+m6@5%mQPt#DjBQdL8QT2YP|>8ypTTKhv8 zR!N?~2tUpFp_)FTsKf6FDf$E&%J7+LN-%Ka^p`cNSqAzvC*Wnm!_8{C3roW(VE8)_bLI z8Ysgf-&utBAwsPvM~t0U9<^<_C3Y`p;nY5hIUsql;Ksgt*RkHttdwf_~5+K z+$qBfcQfqihi&|hd8L{@B4Xek$k~ons@O-#IUiLMSk%%TzkcJkoFC> zT>?k>JOICxzp-`ezFh)-kp--{ZYR;7m1d#@*INBCmIBeGg?%FmYGX(RX_oV|~% zokxtPU;UFMYBj%T-8^Z;h&44<$f{8Sazoft>WojRTp{bTGcvU2&ncdeH~j?P6rN$( zoMz9q*IoD1gH=NsM7gH^mc=+E%|s>CipQh7PcUNH7f=1cEf!0yblqMO)+e7OcCVVL zMu{ZbUF{tgd7nVk1B6>8Pks-sDrEJ;!%uzDtxXKqsNa*eh63=JB{PL|$?2RgDsq z^^2__RHI*osi%n0&I-|$(C^lU3AMtt3pH5|d9N?BQjHS!rpXDu$3vVhp;lJMe18np zD3RV~jk+;fg!_e+W$1Ez2^h8K?z$$;_AH}fWYs$!S;KfrcYCG2NZ^=_jeCl32Q@3z zC{fmdvk4T=C>;;paS+4kDe8!ssDx_TL~~cutU%aX@BHNeWgh2yXE4!S)$r{!--d(E zL~Z*S+wQUJ39R@&8??&yZ~q!1avCCN1y7WnsQ+mFdYs*>RD&3_f?U20A0lW4Pn09Z zy;j3bR*P!XFXW=~YKWi}JW-Cy<9F@%bM^;Tlo7*Z|1zSN$lpwmNVE`^)tGfybpIA3 z<(_4$Jb#yA-|!9)v`QTj!n!-=c+e{K%B>*VpZq0IIpO&zq1wO zvR6X{tvbD`ZMKgQ4ZhebSW)J2ev1R!l8|%4yGyzuQdVO|$9E*mowEJgziom4*desa zI|QxZiE@I*NXWQ1B&qkbWyZ%ySx1g+qSa>R(=v0B2Y z@#`JRh+%U67N_|xLpAVABFPO=VNS6Qi|*INlzWz~a{n$XSKdp|Ds@B%T&+1Cv_cG( z?ce^rSHu`1XoVP*gRmNK-Q}3OFT|h~)$LW9?RC1V`IqnMPUhd!TMXO> zC&itUXH?cGkyZfBmo-*QKBF?BR_XrO6GJshn2bATPmC6kt2oax<-lNI?QSwJxRG| zna39%b7Dq^^VUB9!IwQMCxckfaV*GZVV-0g&6t-SrXJR zD-wKS%~{ouk}p0x`I~$a);E7{>k`zY7$Xu`^>IAPtl9*uK;w8n!RJ0$@%c>S<*Xp& z?*N#I5_}3HBiD1mH1qszmDS}|LmAE08)RilJ{ z6VQp_J%KN^GTM)$rmEVp*E!2?wLcbTrf-z=4VHPp`}0Zc^__Xwi{>IyJxiJqz7Rl1 zv8xIlWSp1GsHz^iU1JLu;J{vU+uQZ zd!_x+w*Y0Y&OUv=WhbA$pA)K40%L8u6yte|?wotZQR_N{S|v}uM_yH*-*oug;&sQ^ zPH$c8o-2V_j`s=Cr%&9zXzqsBJ<(=LNvIWM%$V4rzvHZL&OP+Y-*{H~zD{f6o4APa zk>l4byXvB^`P@~F66M?l_qrSZ)*;l2Z!jaq{ny{PZ1)XUJE0mS^jxW`$6vm7?!L>` z`k3q3rnAfYqqC=~PPqNPxjlESIqKOg3CO&wm(idZ}4z9b37*0^r zCb-thL=6d6tS}L|R~CDcSI9Fn&IC1W0-fgbN3O$Tvd689uD-18dxb||IWLEo>h$& zs4vL0f^6C5b$h1{*R%;6o4jXP#-J|{w1Uj@22CwvP}3%?yT0$YFhMKOkhw>eV|eAr z1Uq!FvOm5f2pQ*K=UT#fmCtP@(CO~~ucp2r(<&YBUauI#HEqJ^ysMV$=p)<;wEamt zUfAtI$FN5R4X+uHQ7x_?SZm|B-SzB=UJ2E-30vtW0{-o%w*UA=ylafW)33|s3C|2Y zglbxZWaSb3SN=|)ezO&_ZDOQv=)HQ4K^f13h=(pjrHIpvy|ARgy>XT#Jz-p&BL9Q)-&KLxftD&$WBoHyMa=y=A2uC3O8zRYQbYB{{9B z7p-53@2O}1us`~xgRZr#CLckbgYl&WzOqn_5*iN`^b=~OHC0vmzQkvVjYqx$Xofr< z_uBLg%S^su@v}$?&9BTaHl$Z9({(fbq+_r&;^)|!xRq(Ox}(W~)b#MZ0z>9eovmEi3D)aH)^`Ek&meD_v~&>l~$aPpz% z{zH^=`gJJuWUQVavHBiC-fpS-$E))>Q)sJ;edLv*R)L;CA}DPfxqCX6I7HNC{c$;W zGX1sg5L%Mil_Q{5dBOzJ@7h$7;n|ZB_GVGk^>+dKUg4oUYut|Px@|;E-o92r-+97d z++<3BA4V%uofN1AJ>-dAJ0j5aITEegz8zh&KvB7W+DwcSJ4y%VzgM05ol9D_Hj>`> zb`c*PTS9&v_{*{z^D6`Se3R(&uvQ!awYGR!ier;ElWbQ97RU70rubb+N1EDIpF#;F z;OG&Aed8MAlYSlP;5k1PNIt=H!F=5p(afR!4 zV)1&o#1r!RKmxy=(huFOI8Z`sm^#ocMw-e#iN!E~}rb5evel_xgsHN&oVI?xd-^(o8`)Pf!g zg5us1b&YbOs|NI-u%DqlNDBh}*?`8!CM!qqAZ|v%F}Az1IqA7UpHw7mQwc(_w*zf% zUSHXzucA-_2{@(&LFL&OcPiYg+*(tQ!W9RuU2W8!Vp|sn^4p{t8;L0wYhlN-8_JzN zm_i98_Ouekn%^BrS(?Cz^7It^YyA~sbm5j3_A^|g%5ONeb=b1ChY z56NAWP5e8xkak76lOWe*V&C~Si(~xoku*FtS6SY)N`dP~^X6knoAfN=v8{z<{4Sj2 z49+5B!n&|HZfZL#k$uc*oe4v@RTQp|XQEw5+Vj!G^7;;DW0~z`<-~+~G{9Ek)jwZ@vPQu>KXZ{o8_+fziNzMQz0+Ui@2$2J`U|yquTIKl^w>osI@Guwg?#`C*b*O768;QT93FOs>0$C6?S{%^~NHZZjex>4PPcS*r>%975i@UP@)jp)9Z@MP0!Cm=H zxuNLM<(9ff-@A;E|BO{%cxJ9`aw8Q(2_&i})fL}(%+|PD=!osUF`DQTYn6fraWr;l znyT`0IN4!xN?K}?BtC2sO-$TROWL}D;`%EKN#g2@ELU@1jnN$2v{va~!4ps`x1yFx zzi=Lz6mWqNo5miK>oxL2%HSCkN+9t;-COLrXgzsrdX^E05j`29`GY$VEw#f%u; zy)haRH3@%gasojKB#LY&ikWu#q{I3MMxb*xXxYPXyk*e^j(}QckB(CH8^3~B+l*wy z>M2F?jrsw2jMflC2_*P+*Jax|lzM5ga@!=B8@q74UUU=1+V{LksOvg5u9hykAiW3= zqeV|&a5D3GR1zV!=8)Tz%Z01})#KKnWziob4_S zi`Yw+eICVZ%x{kI!ST&#ZR-^Z)Pg%Co;Wum2D=AtQ*Kqw=bp8}??#KiEw_?>D?%km z3qon-K6ET#I34KtT!C4HS%BUOLYF%ClzZ({XH7tS(=L=WL*azII6yb2`;&D7P1daloCEAb3=}Xwy6lXvwtE+#U{Q zfhT?*?WmoXUYjN_3E&90dxbj=wzC|Wsl9uyIdyU!!tE>}0iU9Ra3&yA>r0!{XYvp( z4!C>eiB-3^Ylk22OsmUP+@2afk$K|T&+XbF6FSp{?M04&yJbiV!o_5bHa))wUH06W z+f&2+98W||P;0}Vy3zxgT{r?h&mqm$_72r@*;azKcZj60Z(*M|&(tHc7rM9!m-CMa z!bCRF51Fexv$pxX$su2!kuiRtSC||VKK4qGlZ=^b1M?*`C6T| zBd<>82&kp+IGLR3JBRcb<;IBIL{DmVzTrdX zI-OJ;%gYrgfy9mU@nm=2YI1znKt{NCx1xv5ENDusF}H7rdtaXDn$?854{b>^%8esTpdZpOYm1@pdb9-ty!g-=-M=U)vuA?&O??NsPm@AlR_J(C}eOfTrp014& zXiZQcnb%?isa)nGK@WKwc-3L0-=4uVBlxcZ_qCAbiJ9{(m0m`X^ly)2%69Lit|R=< zlg#6*q?Iejl8noTNZWPGCAilXgjEI>%I&+6G^FPtZqERTWjUisto=@M%OsBV$F2Jf z6#M+~bi?dhoL8`2p15DxRe5+aiEbM(LWb=^57+hXL+lo>C+0Vnu$|1>vvs83w^Qio zT_)?%N)b>!OUrHnA$?W~IK5lTH?yhf0KS}E<^35r=oerr}RBJ{zpqOJqN z=ta#-1SOEL+1pAy?zf6`Dbo=xI}B1kS~ij zliJ+Ua`^Y>q$!A$`VSz57KMz!M}Mjg z4Y8ze)4ed1K;lmAM&i|X14zcV^^9-~8sX;Q<4Zqh*5?SQCEuzq9<*^KEk0~yL?_=R zntjDX>5dF@j(}PZo%@pmvWk?C))6O8&QwJ{n?jqm(;_H=gngg>Wb>`AL>9I%V(1Su zl4zDlUscRPPyz|Z!+prReVs{Qy={!>YLcchij1Rc=d43e0tve@t;N9b&Lp#ej%c=)S8-)GNsqK?x*gw6zesmE6}{G}96H zPv-X6{4|PwGda!?P|JCZNSxZ8*OV^5$%vriYs7vjlWEP_3kXUe(QrX~amVAcnwm*E zBILv-amM*jdTnXui#vVb_ffj;(FWUG^Ci8u z6{~yRyDbOp^(ISvCTeVNm&>nu4koiY+*0Rmy~Awu`(;6=`nqUuPV&M~0tx6L8|}%v zmHM|crRcxW909f9`yfHk+D)b_kN8WmE|(DWDs$6VQr_*dT5rfr`EmRhGQcHG<9}J# z=N~@>Q?~_W&uWEFAhF8@sQDu27UK_udBcN7dPy&hnlubrfE@y=A z5^I!nE*6hE%M(!R=q`8Cu+4HZ-ZqyJj$?YDQ!kS6mMa?xlt7|`VIt{cmrY)Y`xx;# zum?KJi0x%O0kuNB2a$*DtL68k{fyXjtuyNLs}J62(V9XDB=UPEkaL^T$?gXVBkEo6 zj0Q4dMCKqGlIs>TF==!iX=$TR zQq#?MR4WV3rF)BiF{0YV1|Pg8V~@w80=3@%x~_^et1rF#TlEj2N}7qaGrOVqeUG#b zCVfQLH7~?-SM}uMlU>A&M~}o|#$TlOGkc14s(*@8#J|kOnFR?r>`5G&;cult2_!PG zjkx*FM{$?kTSiob1mn%ED$$uhQw7EWY3QvW_?L~xH#e1{+}KW>4cIPERJ)GBhAk`5 zJJac0nC2`>mCre5{IWVt|OWR;-ucG`gYbp0mjr9Ii7q>-u z){^wrK!)}N;r-4W^dme3|NX3RUNx99MddNGzSJ?{vDDi8$?=1+^`%vv@3J`NEsH}h z>xAQ7w~i@Lk`}f6So_#!(sZRt;=MX?n4$$M=c3Syq4dPP_A2{6&&2PW%A~@TKaS_w zKN08LERjx>jCSpx^<7-tvy9oeQGXh~nz~kwd^}Hq8HIg*yt09~@yau?@297Xh_nyE zi#KjZu6a9o0%-C5A$1soJ^c2d{WXdLC9vJ{s>dpm$5o>C@I7WDc1Az^;`v*&+WZMe zK&@z-C92R522$U9x?GiY#yB{_3TMpDs<+95}c=_KrKRKne5^_6_^H z;B!Y@&)63KJfbL20tw!$KViklZA>pb`(bSg38)2oRuE)Jf0_Mx^J-xb$_+Qo0 zqNcy!Ga`D-;Z4>zbp>TYJ$nliFk079^mz>`Ox{ zYrL<-jLv#d58v_WAb!}o$IWZ$8+n~SmU?a8Te;4}He%DI`sy8e)y%86Z9br| zH}3TJ<(o*`sGYc^)nc`cQpIUOS`hYzw7>?x^y%{5EijZod#BEosL}?SsA3-Ka`c7O=$W_jmAHd zcU|wL{@Cx8`s=Y*%m!YaDSt6erJY`ebHt?FBGm-xms+`7!O?=?bIuvPpEQly4Hqx`5kPyh8lHa>kRmvan~X}5-tISKR%w#1(2e%F!Ps$n#D z>}3RV1#Q5rv$unl2Dl>Ci0;mI;Ia!d3dfru7&QHfR_WKLZcljvYVp|}?XN{X9}!(z zR-dy0wP4=}g7=D}DF28bU8K3j#R0WoOoEWmDH_dQIDwjlYY^0eGm0nj_c|bLVjNw! zECWF;*v~w1a^gU2Q2(}a(C{@1j*k$>o^DtaWmhHto*XTfx9+N1+V_!=vYVq?U?{+6#IIROcYk!m@pcdbQ8Dl1(ot`sjPZI;}hO4c_ANn`dU#cH+ zqYsWs_IK?b8&pzf7PWklrG=7F`FmB%zJFA282(s>EwN`*lf&psn+RIaJPN^_z|qHh zm45RII_EW>t_|;lPL7ns(!XkT-~G>Is0C?3NNjoxg$6}ZQ1~TeO9NZJZ7_2J-oK2Uv4VR%bci%S}+UG4%w64 zEB~n1j(x_6MmyW6CSFLT^|#w{1k~bfl+Sx1HeCN)DZ3Je;mQfu;60=c+3@;{oB8XH z%tm&4d(wkiQd>JOj(}S4+SMa}Yt1kEQ~H4sp_?A7_bnYjJ^fm91k{>$$%I@e304mo zsCycGzMSLsGGY+@P|KQI6QPGZaiU*^+GS@1jazz?dqzPmn`yPkh*ne`wf+sW(W&n; z(fQG2+Vl50Zbrd1m?zfbo#OXX)2VS;8iMl<&PSd|yqh2veoLXl^N(@sE~K-O8F5JY zr7o8%nO8}l^)>nLXV9rL$8a`ayL-AeCKfTT)Xx{`*7iRrOKokPLYiuT*Nk-dchq13pW5V!maT%IZ%lwI*LRaP&a}w#4S(u42tPl!7bF-^nH2^3}r2 z#!}M#D%r2F1=-uGiR62{QVz+hP450^AQ^VoJ!{vQ7K&rGC*co7M38`52A#dtR%T|> z2XkEy{wb(bcYGU<&%arLpac>>%8kf`Qe&xqj_z42&Fn0$dmfAL9NfSWP|G=ckNRVjx-?!8r<{B(&Y7;uRng@%w8KshznnUpiv!v?e5Jmd zZ{siGiF{qIlI};Lb-N7lBt0JtwIX8%7X{jsipBju$vhFX>MlBWv;vji9)zJ5^pGc7 zzxau6xqm@+%~TjlAi>As^-#uA$r)r=R1ZT5jQpZ?q`0p7x@cJQn#J*X#7Nvz+=(uS z-bGO2*=D&YEh!Z>iz;Q$+3{kP<9iV`*3H@$%SC)Yu6&qSyDOSs+Ye72WXR1ZI9`J^zm82fY%D34-!dDg{jAZM4*qz~2m@{; z!v5z8uWzf7?_M9g`Se!=C6M5~(sQ%IUUl5CPo1p@<^*QrOkV&VJxlJK*F*%((VR9?0;6}z8YBtfrc zpS!1;>D@%C6Y-4mkbRZW5V=?5jw0dxMEs!dK(5ar%@gA`Z9}V~!|};&ixBK7*n>QA^IjkHeRM3YYciK3 zpcZ`Eu~U;aeb9~CvH078dED5A_IP5z*ORir=O|p)`2d$I_`HI%KoHXUH^W|~9(aCB zD|rLnB7U94#?Pj5`ReGC;+a~tq(c=q<>7|vvD&2E6UyJkmKW8>bLrbi-9EelDcyS{Ut|f3(vL|P7Gd$*w zJ6>_t9YF~s__btE---CU^=edTxs;0>M$3EU?COa#4C>-#LK=b+NI-jnU=lbOKk#dS zZA=mnrv-Aw6Elih;th-Y;z|4aAt-^_<>QF7*oWGTi^kRGn{#=GqYtiQY$UFphEpd7 zqpMR}A~+J^=!5+)2$`HDzA- zeR5;mQvVM(cHwyCiERry;lZ~>+^g)l3?-0&b5jtGX8GgMq6V$LagN&oz)=Z%RuGI{ z48*?;4RGksgIs^W9RN>cx)h>QJ7e*%v2ol}4fY!EmASA@$(lVFdnDK5PQ?2y8c6bY zXw`|%cmDbM>V0gnV$m%ICr0!}P|N*&=?vIX9S%eU;u=-d~$W z)Jot8s0BR~g#LftpdPhH(98V_5ws4q;28};u&!MT#hFZ|m+nynB`_w~k|12EorLup zIVzb67i8%B_%YdHx23t7?RQG#U8Re}5r*lS-}Q7SQXZ^Nzy=#8DL#KYB1k~3Z{Zo@ zh2a^RFE@3Oml(z1P98bRq?Wxn0&2l5us1A=Wc=VlL%N{kD1y;Kt*UcFMYYv7&CRk~ z%*K$>O>pJx?$oJA85cREd19@X9=5dXN&EKy!4Xia+3!~3blcsU2`_c0UanquMvGH@ zXoH<5|2bds-}5jq(>!s<_n3S(us1#G+<`lh0#Cj0MDnw7c>Kndii_V_1fzwy8gwyC z?65ycV|_^HmAauXj$U(A`P1(Xg1$qVC)$~+@U5+QAAJCA}dAXo1|MA z4jDAY@?;4+ zH4~p1FhKdx*-D1v6^_bPjkCprzs*Se!0L53H1-1kU;3Lm{GOxgDv0a}y&{=LO-5+dn8BULWOV6eM6v>yW zVl#3sf?6=JKVsX2wH#ys26_+=d5%x6bIUSc& z2P!}8ns5ZvDlV8KM!xJ%hRoHS7ri-Z0*>3eNxA-W6_;I@1)kW}^C#*)#DzNa{lmop zeTOGO1)=@wA^5YyTgA54c`my!3;bQOx5G-2{_5uRLP8e|wP3qEVV@C!XCGUwWIE@f zBQBvLYBP+u<>t%KcNmi(Y?DO1e9b9k)Tag*5>Sh`p^hj+v#gubyzDL*dIC?%^2Duc zP4T9}5AIP-}5gwpcGDkxZ?- zoY}bDt~oxl@35lp?}A~pFuU-KI9uD}X5#uit(C$~^$~0f+K_+D5r1T6k|!m)Q};z( zWAU*QLzU}8(-G8yk@LiU*Ffz3>X1^qlNLcO=pj#ZC=9~}^Oh@DU++gy0tw&Ep`z@U zMQF!W%qySU?eOuZM)a$TDHl16mM0ukUGdAj4@&Xrx)@3zF($`ZyzQ`%d^?oKY`i#` zkIroBOwS0NFw}x4`~M-bX5tFHPD*~WFEY$7jHyTFVsT3NGSc$mLT2N-c_KEn^i`fw zBLpRoXgPY0IRC*4(tdglBfc1p#wV6PP$tb-%H;~i#1r+R{c+mQ=gOp~%Mp}7;>w|5 z@pow+$?{&xYy`Tr#;8X}`W4?rPzy%O6a9a-z;E{0(~f8EAt-@_E{Fennb!7I*HE0?eIm7oL?bt){y@e2sK_i70vM%^BWZ_Tr&CO7nDs0B046WT&A zT+Ht2ujySSK?x-Evrni7PdZC%?bb0H+atT;-Bzyj`?oEeJ}GL%39-WX!1 zynQ2aedp84xHbc|@OCfk8<=%=d)amzF5dK2*&!U~2&e^fCr z4DInm_8eP$#>17q@C@eeJ42c$zLvRSI>?TiukhvwsHIMNqcSMh60_-r|UGmA%DD^8Ad>#)KGsl)h~uRh>V_-6ey! zrFp`jmJQD7jpc<-NH^dk4ByfrQ@&1DNqacKTmX+UWR6O3!&NaLMj$=w@M_=nq==@r}5sAA@SMm#k`tj*&W^Z zXOuuKNVD~d5!0BBxr_O61+^M>ZAhFfKCA1O=&D({GNLad@IN-7*2y*c#CU3%>efY? zGp{z(YK|PvnBi`Ny(!EUq4tRNri77iYZ-W9Qc-uav<3e%&i(s{JotJF1>j)!83}giC zHAwI_*sR3`mfe+~jDTYaYC+ronNhfu5hGc4p%%2k6FRS&GOv7@4NeQxGT`H=?cWnE zeUgOfuPG9&GXQ7s6B|9U-TRHoC2li|Jbr=$a?YQLSB$Baq2%OHRy!f$wW?vw_J3+8 zgxzb2x|PP`>Io?bYQfb2+7^W3r45nai7?#A_%4E4(085)3n)@H1r4KSzn&@Z?mWCx z&)-Q#{!y7m!I;lbDUNUIBEd(*xxbBVg?WXpbij&7DTOPHL~rV-*2m zWdca^#D)&Zbfsly?e0d6lnm`m5|+1)gzD!?kmd=)AIY?4*lO8SD$&B~5RiZ^3Bu;* zW9fpGca@IyW-2h+eg)G=2eVz|Q^*>Lx8dVpO1GEwqxC#CDzJh;hc!{;fYCwHbaa6P zTM~rj$4zPE;(pX-=LQA#8l-u`RGorDtWU|-)jtUIw`oBbd30|P8GCJ!{5~g)SXM73 zMlG}0U#Z$It(4shXVH5TeYm;?u>Jt_P!JkwRw#02JPp4$QHByo)NbZUER5EXNH1L_ zgrwpCx~7LA-DSQ?`(RKOsmR<;jy`E3!(73Z*j?m{Gw3tZG0NN&3mL`{;y8}HUb%wk zP0f*&eIev$!a{PlyY8>;V9y~qZdnU@xS&9U(L$OhoUBsl47~_#_~v_Z%*S9dxX6P< zF3gkbEDt07N=K94vscL3yMoAsB@v`a7u~xIzjtQT^T1ifwx`J5)rYt6Vf6w*$aCmI zTW+|i#5HfmRVjc3fAjv3`&wo5p3c<4vlCZ40k&IneGpk#dm(W@sq<=lJ15#2eNt?u z)Z=Wxc6nmjn;z8v;RhvXx*>)VNF1&mK$g#)PZnr&@8RZ(6Y151nM%f-jR4WY)k~pwLf2}q#$Dp_4*P>AysX&$66>kjV?*P(UW5J56YEwi zQCf{~rv*0}aMdqhT??2IL3nn$13L}hmP&_jASi(`!8#hO`d;e})Gx0st4wi=tH}Y0 zf_Z)rRJWeIRa`yZw29+ra3*~!I1&S7_3sk?(p7;r>dK|+Fb{iAUJCw%@Y=hzm;aqeQ1U8 zGOpUf-0R-t*$@X}JZrNID?JFp)AGN{)-GPOVfRg34G2iUY7(q=oAZ0cxSlur=Cz-z zGXV)JXFu}MLnL?XbYB#OREc(3(43x1$wyG@hQnwwx2X*Yu-PQ@M9D%QT7I(@MTepg zlt5yy$2emDv^%-^R#*4Kq}D`gQLa$}5BEb*>!5!KSsv1yERWwH^MuQlIO@MYTM54T zo0CAoct99wRP02eJau0I$oN?_KG{OK+GUdrwbo1vBYF7^NbjkIGEYRfBr8wpaO&Ar zkE`MVGuo?a5Q%u{POi+*Mi;E6Tg+tV&*8`1E2dKgL|!H<%S zMxnGuDpVes?d7ry^TQM4Xax0`x=!)llZ~JR5^#hH!a=Vjs`$Ou)*Nbqpcc#zPi+0P zS1Gn{NImYe+JKzW9HbAejvH*pd@ncSHp zpw?!MH)-m4L$g`Zom=u6YD>d+$+XstdfaG-vx_HgeeXyEzsU6UI-Y=94yL0?+@iA@ zPlHls<7I9LJu&!|5_M*e3}+P78u31uq^0fDOzEg2I=ckX#g9KKcG@G{{D3r1R94TR zO{ni&jPhjMpdZUTsf!&(+r*vnd<{#@xAI`C% zr(b0us0HougoTL8&|WSM=sQm= z{aL95?i)%CzG)DYKw|Nb{;Z0JR&&%}cS7jp$bs_E8xeH>xa$aN!Cdh~yVgCGh_@5y zuMroy+B>k~4Nuhjy;0ll)+l?d}MuH|(4 zf+D3LT12pt3e@7Os_Z-&O=Yi4<<;0RT%W_f;fVvU#?bk~5#`d)LkLPBami`~F_^nd z(`laW6w>|g18LjpuSx>@st>hb-|$4KeJko_W=`)ktIh8A{cl^4D3~{pq(!XK*jAP^ z8+QlQrcYkm(p5!uFw}w><%!Huhm|kUJ?OebD-5+@O&^}n%kQVmtlOW~e$axe2m}e( z5R!vZJzB4(}PCfZ_H ztp{rHHd=3KOUs8ZR%$l5V(1B^c_OI7OZ)e{G3}=B&%Nb@Z?oYWPj>$!W~kQik}(Yy z{3+Ceby#@fYsw7j=Zw(i&VmB}K8MwMV0}nd&+=Rpwg0&R*>vuzKrLA7oF_We*`Qv1 zHx(0i6RqKoMP$)(Yw7VYL59^2cKpa9CRHt^PrJUdcNtkeqg0bN&BB=zY!s*ks~_;h zxq6$)K20iZZfvWC5=c}w@FRbW%%p39UTp0C^yw(pc@Txo9F8kc3)YrUB`+WY^&3jJ z%N{VVY?B17d_NW6OSO|A0kwD=!@`?s8u$d_7lHZ|w%g{*0+Je3M+zNxTY|J8jO{v0 zRTC%TjscDw0c%T~$XZCU_Wuw)hwJK>T-}%=KAYMDH(1@BCx8~T$L_1mSXi{MuNsX@ zh@!AvSR*B-dLh}lutIF7f0fyAuifL=qglt$*FQV~wRo=vK1jiRJ2%%3UA3iUIxJsgCNiN-@IMSt;0}*hzc7s+c1Yt1SX* zz3{||Pm?gZKSFDsbCDyU*8F?dRm-vs#e`vxm{*-V%Tcy>wsvIPS+UG&A}8OC_11$s~%3F1QJ5dWL3*Pk5nhO+-8K{)6UqxZe1tfT~KRx@*}Esjd;g;T%ZCr|4on!*`lp;ww_IXFVl_*Z-Ai$67ZHWtE?Iyio1UZ(K?A$ z-0fvZwCKE4{M=xHYN7W_w(iz+4aOaBq-!4!|G?dFgYELfBEM)n?cg9S%G}ElP|L>n zfM}bzOJ!R5gxN4oor(we1Z(lOgWP>Jcz1~>9*jxEmcN~~(XHdTTU+qn9Z#Hbn2Ae| zOx7aPVH^Rq%vKbOpSxtKdY9_X(3=&^!d4Znv|C%X;qH>bTVgyhx^XJD+wP|QV7#2W z)d+8*@r0T^2OF7MYHh6!a0Jxq`}Kxs+-i+VHUPO!&0z0R`f95sV*M)fZ6zRHVR4C6KPM+F9b?p z^%LI4he|`d&exy5KU=}suykJ|RtDRuZ*_Yl!+I%#aH^?-hWSsS&dt0z3A6#dWfd?V z1mMNv6~(Sp%T=IB*DDaWPt;e9U-yiwc*BU+QP?unL78K)4Z(hfBN5Up@^xjkJ-U5M0fJhv4v*)NmEs@Cs%S{kQ z8nGo;-v@fd6Q`SX#GHAS9rNg3#_#I=Z=WI-T`nwg~6i#ZKO0{4S!dY<-W*A*-I$-bUW=EQQ*H?c(Y! z!Ic5hth#uvNG*oxQMdRiwEF5u5+XKs8+*1&t`a>-UWmC`8Td-}I5~ury?N^9bzfJx zrO(;}%JHlzw4X^m33s~+C2Y-3~8R2nO&iLwF{&+EoO5B)SB zLSt$+zCUfzVA`n`J!UE%ab3$>E34j?0DpHirufS8LTtI_KEfM)E$~F)7B11;7C-Dwjq^^x2fk_>MEY3I6l?nC@UvH^t zcAj?C@)TMfm&eT_*lRqorp7_}*fNnO&U8W06KDh4X16(hVr4Cfr{n8}a|G1lH$h-K7V80JY#aW;F+VYb$f{B>I(oMTWk^>SEAC_IpJx-?j5{<7mXL zB?yiTNWhi^p~sDIx_3_u`WAN>ZNC#od^%kf$Fu5mtLIN3+p9~&x7#Y^(wNDl_u|*$ zAHCdiQs{3CRA1-|)Lpp5t4C0&rTGV#Y)#O;NpFqzw%|W4~ z3*@&pbBOul_u_QB>+;BuxgHTAM!K>}Q(wR8-a2d88JSbX%aGNBm7G?C zt#e3q-BNL{_nm);Q0o|KGkq1ZwP=T6Tae(rYIG`=Mm1l6=1uH`pcagYC%n8T(h25y z=)m2j2ufh&e6GTljHEXYA4JAWt|2Ia*&XFLipVVT9>uzvPWgHP^b^*@&5Jv5aX@>~ ztK*21zaYJ?ugmVjQNwBNXaRrdmce-i?eWBsjXh|1O*=d;W+mqp^u#VIlqjo=q=zxO z{ceX9A{F1Z!V&fh5Nr$D;E8W7edzM-4e_KW-m>4gWKuf8Q2K6so$G(tPpnRA|2}kA zz74KKt2qK{Z8e-myiDs#?U3&4Qp-*%T8KL1&COoRPyz|)Evxp{pcP#lndDSPB&j^+vD+e;Pn zHy-P!jpO2gG*7t1=PIv<#^a^s=^O#I_&D6_Iw=kP67jLkT@cJ7%r1;c5Oz7H@>&$*X(HV#0>Zz_A0kvRE>>b&xZ_0t?fjBMR8o?ff{m&k1QM{8BCFUtd!lmxZXoX0^d*7>)Vh>tOY-KJNKIpO zdpM^v4oZvaFzn!d13@iV2a+e27UwFTSbg7p9YZjT7S?No9ty&z-)-rvl7stD}qV-CP$8+{(BPfA&IpK=I z&LL0lM-!ivpbq7K5L`J2tA>->7q5yNYQK?TeC))pX?xlz*cw|Ls^kc$1-)hWafHTn ze1wF1u0O^RPz%l#_BA}4Dqjwc#jECRMo;5;j@1-4oEEQ*WY9hk#5s={f{mX7 zjjKK@7mD_x%hFH^zsth!wf%Z8CvP<$#N>B37*TWelTu-7i9f#Rz!6Z(al;Do=0+`P z{V3fpRAi+&(Ul8dppSAx3blT`$s?|FKa1fZ_a&YPbGokh4710lJzG)uMH+g@6J-sX zE6s+?!tPBAxswC%3xEH{%Se;cR#KN*f0^`jK0l<9c;Uo!VkykiWW zvZN_TK&=-OSCYsi3u$!aCuZYBaFsH8SpeQ0G*5wAus?WWSG$*JyE+tKc$uw*Cj?+` z!j{-Gs$XBc^f)_@)5TGNzC)TPwp6#HN4xdG{)Jz)(7Hv_wM6&pDqo`BOD57f62yL8 zB{oA~PlJbM*7U{c0eJ7YVl9;TdFGK0BP^x6v-D)x65A)$|D_Tnu*e~b2WWSta`*%I@T3;#JZG0seITaGmUiy;nozKjxQI6-8 zGxq)Q`!GFj?85O1`=7n1PVG!5RJ6uJ<4!A33)){P&A{8is1Rsaf=0Ws)<7PNluPH}BEjSj~?=&>9q{WvX$&u$gC|o~acH#VI z6|D

      ZWgqkJP)%MGpG_ddR+7ZV0B!zP&|vF6C;WC$OJ+ui`ES(qZb|$eI0GENmB! zCEkXIS1@fgb}KSN2Nb9U`sS+fh z4M?-^A1_v_hgYW33m@-s1oQ;bf-vl1Dz^7b(~#l%Tm?K>X{;q(EcUv4MZL64cSiW$ z^LuDdO*T2wJ{-fEiSXA80}8u}?F)+4(FMA1!qIiFBU3w1^4Mh}SMv;3M&pUEcV+xM zZn=1*s1t?~NX&Q?B3hW=Qro=Joy=^1&>f!$-#~u(wZTveR(s=#?Omeq;j`N`!!~LV z)PgnWctYJU5?2@%k}X%yA}E2x>bfc7f)Yp^+n6O* zw7;e9oUi**J!(Y~KG|kHv7aI#s0Hf|^2D}hDY)pHD3zQiTo1xty&9TXM ziChViL^*gTQIFaq!CEG;K8GOKJW9p8`WA~{z5j5;2X$|;=c4uGt?5~gW>Bxg$N^&`$N};~RD8 zJhqSOWUl(NDO7DX>)C()zir>?ns1kHvFFFCkW_qE+gE-V;;DsNFmhc>|4U3rOTuC4 zF3O>uzB2R#W`Xyrd0-O0SJGSQ9cUwI>jsMJuPh{qt1oi3KVgkM_TAuYDi#aP%o#i-!*^rOIe>^_DjW+ z=O;=nPv&q0)Z+WRXniWq%{?Mbn>$zwM+RKsc;dHv6n#`ngC5$a64(c@Z-)A1iZ#pn zkZ0|6zYTczLJAHUeqOuKsHF;O!P>7pp{r8BDupOB*xhg_fyDo>U{wU3 z5MHL@mf|8QD~In7I4WV^2twuUM6A9z8Cf@%v@ky~CO%iWbIeeP-4vYh`XGWeAYk2x z>Q%uc^Q|$-X`uV7XzB`c^mJV$?wEBL!JGGx=82OJ>L8;Tp*TG2F@iNRAOTxq-{^nV z$j9FYVUv(*j(}SHUHu+;wUKWm`*rRLeGIE=KzlslKB+>c$GmYudP9zYTJVNE+qVb5 zkT>odii;mN!tfqFw8sQQy?jb@5rVlvg`{l9A>?1Sr%D6880&JzQtxS%r6Bs^0)R|_SO*xf6J zq!23-kl&Wsa5n9U-knLp!#dW}LM=FhdBTqoZx}I%5l{k&(ua}c&)wD}{;&zNaYA8r zih3vFAw%5|)PggZCyI;hk$wJj>|VDYf)YsZqkY=ghRA$M6dtf=7lK-FZu7)Qk0$7| z#S|u&`_lA#g4Rex48uGV8PymS!dq|6XI!)qE*VJaZ4n4^8wN@KKA#= zp;UT_*vJ-}$|d+~z3`5^&c^@V?$=dlvS&4GQdrFzXaly(#}UvfmFf>Gl(XFLN$}Tt zp*`NlmCR*IM*jr7uG*78-(j?HEU>Dl0eh9@1<};%W-*s5s0BUzPc;(Sp2abY#R1nr z7!x0dt`<@+Ms&*=sfBk*AOTwvgjVb?iLUd5iT&Z_BGiI68DV^^0!>i@-P&!j(rNB6 z?%o}|g9ZDa{T;P8m2NXQqKX~qA^)rO-xY@^OwOg!mUV5k_kQ)0;4d4)K7jY#1;IRh z7OgpDgFdC#a0Kj4NDIQ7*0boMW_GB_c0VobXZWkraEuAU0?S$S{dHRuvo%Z$wcu}I z^F)_!skCxoy4L)5Z!U6p6HOQSf3v`DPEJpytr~UG8eJMBLkX;6-_d^wS?M3DzL@fi zt-IwcyC3)c5`TLS;_k#j0=C57!+lDnz0F3E^snP3c#{=on$K>UK@yEQF%WGY+LxQP zkbo_*{`i|pP3#7V`cD?IQv&~ccN&f{o;b5(CjB;k5K?~}s)cu#;LRtPX?Dt@#Vq=L zkS(&AJ3$L2kl_1c^ISu*h3x|EvPr4j`x1ChBjDA1G9&w*YR)U&4W7J(TD5VH4ce96 zc>>-AfiyeGF)mFR={y~;V^v3@`$wsc)>x@sU$A$2r5D`Bb{M4oO7vyD;z?p+{1J68 zLqGO3NG_{U$b_-D!_deO!4MBi3!r$a{@VpoT7WryoLExZ{7 z?-ljiXfN*hv`|$Mt_!oRj^FtXloP>NkE1MX09(YXkFqilrh``pAQ(y4m)*Bqeve+U7ukUOxVc zKr76T;>7Xf0F^3ch`fFdge7?Am~UkK0%Av3)q2&54j4K}92rPpO~$FympUtbs{7O3 zoAn6$9PbvrVEof5q)6mAj#MKZPRTfS@rmN2NBgC8hP|Ps#MZSpcP&rZzFol7}cpszNk)B1detb;mIRwm>*ipnJhKz&!AWR zQL06ID5@;2%Y212C&Koc)WieLsBwJ{flnuTniIFhc=ea^2SwZD>FlbI!2UOK``V9D zucRImZ>A&*EJ1?zU?poSHMXV~&9A+W-3QJR*#E{!8w)=v8I?onWA&x%sm0#J=TVZv z-D2rO-vQ#cniUmR0&^GdkBGqI%7w9gX!!%#-y>R6K9p@;_ zoa7lJZi}qyE>TWT9TLWJ;xKcL6BGK6Qy+L-7n2r$lra+pa{;#QJZ<(+)$E7`_UK^V zyI9rzUw`Tyr-mpJ@v2|((b#Or&ntty+%VWUy&mMYT@)U<$3-oAn?P=n>;fCViN)=Uf~$`lhjreY?`S*nGBKmd!8WI;+WO!)+!F z&hZeZDNYG*IbCy%+Gu+G{GlA%EkU#RtuRFnxhq$j6{l5o2{GLXFR;IzUx!j~=gs1J zg;z{qxW?Oy z*6#GBBZre1fmYRTjnN#JyV)Gi+D~4*(6AB3XeK(aJ%QykVDnU2lY@6RRBNl`njomd{TlzJ&Q+kY@C_D6yel;+Gj3aPmtPA&UxK4lj zzCcomNYluOr!roxp((07l=?MaC0cJSP;e|Efg{G)KX)2IwY3}( z*p}E1_imVaUyQ#vhB~>NXQKp1Mo_I$TH@~2wrf%L z9$d1^jYjVZqT_MR*+@k1B5f$PP9GMD7beq!o%bzR7hV;PF-h82cNE<&-6B$U9%KE1 zeZcShTEJ+Eb`H|Nm0u{RHbTFl*Nqu&Nd)y>v{;`J_zxpcw}iALt?nK}-h~tNeSe)$ z&b$F^XAN8hFw`1pewqBPK7`FYRu~RC;(-oM_@+pHkcs^|f^aRIC^CH277GD%xo5(Vx_tx0=rM zqDY{2)c9ks&oL2RZG-Na8N>2FFz164fkrmft3~ycn{UHp)W%?cpzgp>q|BR1P108> z1+xdSya~*@;Dm3`2r63eRyn<_C)3;@!F3sBTJ)y}JHJuO{?d)9`BCN1iSikq;5G-|Dvn=zBAcToGo2`87itnGtC9__xL8 z;H$c=-Dmr`mJ6$PQ5`%Rs`(q*C|H67SBu0~4OQQjtD;_>e^ti)bEG+uw6;*0;~c3@ zDLY<6E2L4cAxRb5b|#OtlH#Zfxx=#yNmy$ zIgt`ol@_)LQEf}Bv9o3IJXub}o~&RF?^2$2wjN428(@5ISd(R1eAigh<^}f1-It(z z+schkMaAGTEY^n+FHZO$cADuT%s1Z#&ynhvFh0!lgn6sa2|7^BWz|k%`TD3eiP^-B&#Wu09ugr;F z<|(FYW2|)G_6ino{RrF< z;4zuAvx*e|2BT<9QW>^yfN=&+l-w_?R=qux91<%t0;7>g8yV{>1J&Ozy38aW=|-F7LtU*@erQV@jwOtK;Or_%qr0Rj6S~Y$OFzCm zi3Iu$X=C0s{@eC(NDMWOxX-+c{^5l8vM74(e?nv)ZLi>Z8CMgy3YVm!C||m1YDshN z)=_ZPh*m*WXK6i^dbZ47_KaNX_WD$=S2sHUq>_SbOQbn*!|F`Qj$w3Z<#ibew8FKh z@#mJVnPPhKWa?OXDT_>?Rd}^=+PYSIZBNhHPdN_R-(SQIiZ}kS@vV$%Rg7hD;*iBG zve(a{Uw*l3K`UGdbK=VRSW;&M2(6Bzf*!>+Rbl%i?cFK|)1Uu6vpAvZMC$nFgm~1~ zi$y<>=EUiFVf6FRN_4DWp^SZiR_HflB^>ru%&Z2RvRi6BVhtLm!(`39uq&eX-*GlGgHT79b z`?LGNbrk<1^PXv?w8ahes;xuVItst%I8pM!Rn3SBrtNRs1ik^}-&bqOI@xw8O_KTB zAk*7X4Jr(yl;A1?OOWt!Pu5-<`?b#F{x;s6r*eN(+-grF=OyQKEWvjl)+9;)xTcD< z+oLIO&k=#dfrPbMjQ4}!W9I5qu`f;B-NRIO{}@`Jl_Sq?)jD*%rn)WQS zoL{fE_MD%T_I2spp#b{oR>}yps^E~SX%9bTujypZL<&xCN-4Q*Y5#y91o{X4*0Ajs z?eM%YrlL*u9xSt{1;u$bqjsg+n0K)aPQ)ekpl;5!sBxQMfh9v1bsUb3U&2?-SxmQE$3b%AY|T`FynR4e%h3q$lFLFbp&Ci=MXuSEumlP8p>e)iM;}TKEkm)}oY^yozT(6W9u+C(b1;p#AInBN z&O|tlB`IU*SMhh$Ai9;;RbUAc+*e+&ReJQmlN_5m3G_SC*iXh^pxocfV{0X-$+>U* zaHhu97Jf@eQs~V%-D$p6{Ug1d1+8$c#))B%7j~*zWK~OK8_O6#8rwG1329+|C9kaN zivpX4eJ4V`0VmF7CyUyvX41aI(`F=ajf-nh;}4j(V^1zNa$jAqHuOURzgQV9t&NJO zU(fUr;d=vQ9O3vifX}}qRsT7Lc4lOWqfHeV-{DALO@>0~>>!H1=0Mvn)n^1+@g5{^ zh5EGep%$|pWt`iwJx=5XD&*zhLzP!M%J^-71lDBiJ1==Jnk7Wg*wSPReq|udiS9w4 z#k%O>6g(-_f@2hEPL#xEi9VlV$hxrsYXfPVB_!!q9bd7tU=HmcJk^9F4%^_w*1T`Vtx`Mwx2~JcSESoZ@=8Hy?Y^O{)(-OEnV!P9lHCd0c;AL}Q2C8!VGpKEA^SHg)4kDi-j^Q;sy*Fmn5zFZqWW4AVB zAwQi9Ym%gMw<2gy&tl=FeUh;R&-THZ47Er=y8gH%LG@hHR7WekDo#|{_(A{u>^y2v x93Z22k-(ZH>1!twdCzV^_m|z3u>{XS!kP?K*t6ZD>({C3{8Uv#D;yb|_zxVm7n}e9 literal 0 HcmV?d00001 diff --git a/data/gripper/wsg50_with_r2d2_gripper.sdf b/data/gripper/wsg50_with_r2d2_gripper.sdf new file mode 100644 index 000000000..b022faf00 --- /dev/null +++ b/data/gripper/wsg50_with_r2d2_gripper.sdf @@ -0,0 +1,298 @@ + + + + + 0 0 0.27 3.14 0 0 + + + + + + world + base_link + + 0 0 1 + + -0.5 + 10 + 1 + 1 + + + 100 + 100 + 0 + 0 + + + + + + 0 0 0 0 -0 0 + + 0 0 0 0 -0 0 + 1.2 + + 1 + 0 + 0 + 1 + 0 + 1 + + + + 0 0 0 0 -0 0 + + + 0.2 0.05 0.05 + + + + + 0 0 0 0 -0 0 + + + 1 1 1 + meshes/WSG50_110.stl + + + + + + + 1 + + 0 + + + + -0.055 0 0 0 -0 0 + + 0 0 0.0115 0 -0 0 + 0.2 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + + 0 0 0 0 -0 0 + + + 0.001 0.001 0.001 + meshes/GUIDE_WSG50_110.stl + + + + + 0 0 0.023 0 -0 0 + + + 0.001 0.001 0.001 + meshes/WSG-FMF.stl + + + + + + 0 0 0 0 -0 0 + + + 0.001 0.001 0.001 + meshes/GUIDE_WSG50_110.stl + + + + + 0 0 0.023 0 -0 0 + + + 0.001 0.001 0.001 + meshes/WSG-FMF.stl + + + + + + + gripper_left + base_link + + 1 0 0 + + -0.001 + 0.055 + 1 + 1 + + + 100 + 100 + 0 + 0 + + + + + + 0.055 0 0 0 -0 3.14159 + + 0 0 0.0115 0 -0 0 + 0.2 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + + 0 0 0 0 -0 0 + + + 0.001 0.001 0.001 + meshes/GUIDE_WSG50_110.stl + + + + + 0 0 0.023 0 -0 0 + + + 0.001 0.001 0.001 + meshes/WSG-FMF.stl + + + + + + 0 0 0 0 -0 0 + + + 0.001 0.001 0.001 + meshes/GUIDE_WSG50_110.stl + + + + + 0 0 0.023 0 -0 0 + + + 0.001 0.001 0.001 + meshes/WSG-FMF.stl + + + + + + + gripper_right + base_link + + -1 0 0 + + -0.055 + 0.001 + 1 + 1 + + + 100 + 100 + 0 + 0 + + + + + + 0.062 0 0.145 0 0 1.5708 + + 0.2 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + + 0 0 0.042 0 0 0 + + + 0.02 0.02 0.15 + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + meshes/l_gripper_tip_scaled.stl + + + + + + + gripper_right + finger_right + + + + -0.062 0 0.145 0 0 4.71239 + + 0.2 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + + 0 0 0.042 0 0 0 + + + 0.02 0.02 0.15 + + + + + + + 0 0 0 0 0 0 + + + 1 1 1 + meshes/l_gripper_tip_scaled.stl + + + + + + + gripper_left + finger_left + + + + diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index c5901ca34..977687da3 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -249,6 +249,7 @@ static ExampleEntry gDefaultExamples[]= ExampleEntry(1,"R2D2 Grasp","Load the R2D2 robot from URDF file and control it to grasp objects", R2D2GraspExampleCreateFunc, eROBOTIC_LEARN_GRASP), ExampleEntry(1,"URDF Compliant Contact","Work-in-progress, experiment/improve compliant rigid contact using parameters from URDF file (contact_cfm, contact_erp, lateral_friction, rolling_friction)", R2D2GraspExampleCreateFunc,eROBOTIC_LEARN_COMPLIANT_CONTACT), + ExampleEntry(1,"Contact for Grasp","Grasp experiment to improve contact model", R2D2GraspExampleCreateFunc,eROBOTIC_LEARN_GRASP_CONTACT), diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index e06d5f205..68626554c 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -519,6 +519,8 @@ void MyStatusBarError(const char* msg) gui2->textOutput(msg); gui2->forceUpdateScrollBars(); } + btAssert(0); + } struct MyMenuItemHander :public Gwen::Event::Handler diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp index a64bf44f5..597f1a4d9 100644 --- a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp +++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp @@ -232,6 +232,13 @@ void ConvertURDF2BulletInternal(const URDFImporterInterface& u2b, MultiBodyCreat if (mass) { compoundShape->calculateLocalInertia(mass, localInertiaDiagonal); + URDFLinkContactInfo contactInfo; + u2b.getLinkContactInfo(urdfLinkIndex,contactInfo); + //temporary inertia scaling until we load inertia from URDF + if (contactInfo.m_flags & URDF_CONTACT_HAS_INERTIA_SCALING) + { + localInertiaDiagonal*=contactInfo.m_inertiaScaling; + } } btRigidBody* linkRigidBody = 0; diff --git a/examples/Importers/ImportURDFDemo/URDFJointTypes.h b/examples/Importers/ImportURDFDemo/URDFJointTypes.h index 65d615ee3..2a6bdfef4 100644 --- a/examples/Importers/ImportURDFDemo/URDFJointTypes.h +++ b/examples/Importers/ImportURDFDemo/URDFJointTypes.h @@ -17,7 +17,8 @@ enum URDF_LinkContactFlags { URDF_CONTACT_HAS_LATERAL_FRICTION=1, URDF_CONTACT_HAS_ROLLING_FRICTION=2, - URDF_CONTACT_HAS_CONTACT_CFM=4, + URDF_CONTACT_HAS_INERTIA_SCALING=2, + URDF_CONTACT_HAS_CONTACT_CFM=4, URDF_CONTACT_HAS_CONTACT_ERP=8 }; @@ -25,6 +26,7 @@ struct URDFLinkContactInfo { btScalar m_lateralFriction; btScalar m_rollingFriction; + btScalar m_inertiaScaling; btScalar m_contactCfm; btScalar m_contactErp; int m_flags; @@ -32,6 +34,7 @@ struct URDFLinkContactInfo URDFLinkContactInfo() :m_lateralFriction(0.5), m_rollingFriction(0), + m_inertiaScaling(1), m_contactCfm(0), m_contactErp(0) { diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index a6a5e256e..3cccbfd35 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -606,6 +606,28 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi TiXmlElement* ci = config->FirstChildElement("contact"); if (ci) { + + TiXmlElement *damping_xml = ci->FirstChildElement("inertia_scaling"); + if (damping_xml) + { + if (m_parseSDF) + { + link.m_contactInfo.m_inertiaScaling = urdfLexicalCast(damping_xml->GetText()); + link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_INERTIA_SCALING; + } else + { + if (!damping_xml->Attribute("value")) + { + logger->reportError("Link/contact: damping element must have value attribute"); + return false; + } + + link.m_contactInfo.m_inertiaScaling = urdfLexicalCast(damping_xml->Attribute("value")); + link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_INERTIA_SCALING; + + } + } + { TiXmlElement *friction_xml = ci->FirstChildElement("lateral_friction"); if (friction_xml) { @@ -623,6 +645,7 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi link.m_contactInfo.m_lateralFriction = urdfLexicalCast(friction_xml->Attribute("value")); } } + } } } diff --git a/examples/RoboticsLearning/R2D2GraspExample.cpp b/examples/RoboticsLearning/R2D2GraspExample.cpp index 4da5cc22a..f1fc2cbfd 100644 --- a/examples/RoboticsLearning/R2D2GraspExample.cpp +++ b/examples/RoboticsLearning/R2D2GraspExample.cpp @@ -9,11 +9,15 @@ #include "../CommonInterfaces/CommonGUIHelperInterface.h" #include "../SharedMemory/PhysicsServerSharedMemory.h" #include "../SharedMemory/PhysicsClientC_API.h" +#include "../CommonInterfaces/CommonParameterInterface.h" #include #include "b3RobotSimAPI.h" #include "../Utils/b3Clock.h" +static btScalar sGripperVerticalVelocity = -0.2f; +static btScalar sGripperClosingTargetVelocity = 0.5f; + ///quick demo showing the right-handed coordinate system and positive rotations around each axis class R2D2GraspExample : public CommonExampleInterface { @@ -22,7 +26,8 @@ class R2D2GraspExample : public CommonExampleInterface b3RobotSimAPI m_robotSim; int m_options; int m_r2d2Index; - + int m_gripperIndex; + float m_x; float m_y; float m_z; @@ -39,6 +44,7 @@ public: m_guiHelper(helper), m_options(options), m_r2d2Index(-1), + m_gripperIndex(-1), m_x(0), m_y(0), m_z(0) @@ -61,36 +67,9 @@ public: b3Printf("robotSim connected = %d",connected); - if ((m_options & eROBOTIC_LEARN_GRASP)!=0) + if (m_options == eROBOTIC_LEARN_GRASP) { - { - b3RobotSimLoadFileArgs args(""); - args.m_fileName = "r2d2.urdf"; - args.m_startPosition.setValue(0,0,.5); - b3RobotSimLoadFileResults results; - if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1) - { - int m_r2d2Index = results.m_uniqueObjectIds[0]; - int numJoints = m_robotSim.getNumJoints(m_r2d2Index); - b3Printf("numJoints = %d",numJoints); - - for (int i=0;igetParameterInterface()->registerSliderFloatParameter(slider); + } + + { + SliderParams slider("Closing velocity",&sGripperClosingTargetVelocity + ); + slider.m_minVal=-1; + slider.m_maxVal=1; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } + + + { + b3RobotSimLoadFileArgs args(""); + args.m_fileName = "gripper/wsg50_with_r2d2_gripper.sdf"; + args.m_fileType = B3_SDF_FILE; + b3RobotSimLoadFileResults results; + + if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1) + { + + m_gripperIndex = results.m_uniqueObjectIds[0]; + int numJoints = m_robotSim.getNumJoints(m_gripperIndex); + b3Printf("numJoints = %d",numJoints); + + for (int i=0;i=0)) + { + int fingerJointIndices[3]={0,1,3}; + double fingerTargetVelocities[3]={sGripperVerticalVelocity,sGripperClosingTargetVelocity + ,-sGripperClosingTargetVelocity + }; + double maxTorqueValues[3]={40.0,50.0,50.0}; + for (int i=0;i<3;i++) + { + b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY); + controlArgs.m_targetVelocity = fingerTargetVelocities[i]; + controlArgs.m_maxTorqueValue = maxTorqueValues[i]; + controlArgs.m_kd = 1.; + m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs); + } + } m_robotSim.stepSimulation(); } virtual void renderScene() @@ -179,9 +290,9 @@ public: virtual void resetCamera() { - float dist = 3; - float pitch = -75; - float yaw = 30; + float dist = 1.5; + float pitch = 12; + float yaw = -10; float targetPos[3]={-0.2,0.8,0.3}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/RoboticsLearning/R2D2GraspExample.h b/examples/RoboticsLearning/R2D2GraspExample.h index 353f684e5..10d419269 100644 --- a/examples/RoboticsLearning/R2D2GraspExample.h +++ b/examples/RoboticsLearning/R2D2GraspExample.h @@ -20,6 +20,7 @@ enum RobotLearningExampleOptions { eROBOTIC_LEARN_GRASP=1, eROBOTIC_LEARN_COMPLIANT_CONTACT=2, + eROBOTIC_LEARN_GRASP_CONTACT=3, }; class CommonExampleInterface* R2D2GraspExampleCreateFunc(struct CommonExampleOptions& options); diff --git a/examples/RoboticsLearning/b3RobotSimAPI.cpp b/examples/RoboticsLearning/b3RobotSimAPI.cpp index b29e0e429..ce9f032b7 100644 --- a/examples/RoboticsLearning/b3RobotSimAPI.cpp +++ b/examples/RoboticsLearning/b3RobotSimAPI.cpp @@ -560,6 +560,7 @@ void b3RobotSimAPI::setJointMotorControl(int bodyUniqueId, int jointIndex, const b3JointInfo jointInfo; b3GetJointInfo(m_data->m_physicsClient, bodyUniqueId, jointIndex, &jointInfo); int uIndex = jointInfo.m_uIndex; + b3JointControlSetKd(command,uIndex,args.m_kd); b3JointControlSetDesiredVelocity(command,uIndex,args.m_targetVelocity); b3JointControlSetMaximumForce(command,uIndex,args.m_maxTorqueValue); statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClient, command); @@ -627,6 +628,7 @@ bool b3RobotSimAPI::loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotS } statusHandle = submitClientCommandAndWaitStatusMultiThreaded(m_data->m_physicsClient, command); statusType = b3GetStatusType(statusHandle); + b3Assert(statusType==CMD_URDF_LOADING_COMPLETED); robotUniqueId = b3GetStatusBodyIndex(statusHandle); results.m_uniqueObjectIds.push_back(robotUniqueId); diff --git a/examples/RoboticsLearning/b3RobotSimAPI.h b/examples/RoboticsLearning/b3RobotSimAPI.h index 98c7e1fa0..3666700d2 100644 --- a/examples/RoboticsLearning/b3RobotSimAPI.h +++ b/examples/RoboticsLearning/b3RobotSimAPI.h @@ -61,7 +61,7 @@ struct b3JointMotorArgs m_targetPosition(0), m_kp(0.1), m_targetVelocity(0), - m_kd(0.1), + m_kd(0.9), m_maxTorqueValue(1000) { } diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 420fe37b6..469c178f8 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1216,16 +1216,21 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } bool completedOk = loadSdf(sdfArgs.m_sdfFileName,bufferServerToClient, bufferSizeInBytes); - - //serverStatusOut.m_type = CMD_SDF_LOADING_FAILED; - serverStatusOut.m_sdfLoadedArgs.m_numBodies = m_data->m_sdfRecentLoadedBodies.size(); - int maxBodies = btMin(MAX_SDF_BODIES, serverStatusOut.m_sdfLoadedArgs.m_numBodies); - for (int i=0;im_sdfRecentLoadedBodies[i]; - } + //serverStatusOut.m_type = CMD_SDF_LOADING_FAILED; + serverStatusOut.m_sdfLoadedArgs.m_numBodies = m_data->m_sdfRecentLoadedBodies.size(); + int maxBodies = btMin(MAX_SDF_BODIES, serverStatusOut.m_sdfLoadedArgs.m_numBodies); + for (int i=0;im_sdfRecentLoadedBodies[i]; + } - serverStatusOut.m_type = CMD_SDF_LOADING_COMPLETED; + serverStatusOut.m_type = CMD_SDF_LOADING_COMPLETED; + } else + { + serverStatusOut.m_type = CMD_SDF_LOADING_FAILED; + } hasStatus = true; break; } From 8270096fad4edbcee9e07742ba239cb271bbac09 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 25 Jul 2016 12:30:47 -0700 Subject: [PATCH 106/115] add GripperGraspExample, separate from R2D2GraspExample --- examples/ExampleBrowser/CMakeLists.txt | 2 + examples/ExampleBrowser/ExampleEntries.cpp | 3 +- .../RoboticsLearning/GripperGraspExample.cpp | 231 +++++++++++++++++ .../RoboticsLearning/GripperGraspExample.h | 23 ++ .../RoboticsLearning/R2D2GraspExample.cpp | 235 +++++------------- examples/RoboticsLearning/R2D2GraspExample.h | 1 - 6 files changed, 320 insertions(+), 175 deletions(-) create mode 100644 examples/RoboticsLearning/GripperGraspExample.cpp create mode 100644 examples/RoboticsLearning/GripperGraspExample.h diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index 0678eaf4a..38e4175b3 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -210,6 +210,8 @@ SET(BulletExampleBrowser_SRCS ../RenderingExamples/TimeSeriesCanvas.h ../RenderingExamples/TimeSeriesFontData.cpp ../RenderingExamples/TimeSeriesFontData.h + ../RoboticsLearning/GripperGraspExample.cpp + ../RoboticsLearning/GripperGraspExample.h ../RoboticsLearning/b3RobotSimAPI.cpp ../RoboticsLearning/b3RobotSimAPI.h ../RoboticsLearning/R2D2GraspExample.cpp diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index cac015d61..60c62c43a 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -46,6 +46,7 @@ #include "../MultiThreading/MultiThreadingExample.h" #include "../InverseDynamics/InverseDynamicsExample.h" #include "../RoboticsLearning/R2D2GraspExample.h" +#include "../RoboticsLearning/GripperGraspExample.h" #include "../InverseKinematics/InverseKinematicsExample.h" #ifdef ENABLE_LUA @@ -260,7 +261,7 @@ static ExampleEntry gDefaultExamples[]= ExampleEntry(1,"R2D2 Grasp","Load the R2D2 robot from URDF file and control it to grasp objects", R2D2GraspExampleCreateFunc, eROBOTIC_LEARN_GRASP), ExampleEntry(1,"URDF Compliant Contact","Work-in-progress, experiment/improve compliant rigid contact using parameters from URDF file (contact_cfm, contact_erp, lateral_friction, rolling_friction)", R2D2GraspExampleCreateFunc,eROBOTIC_LEARN_COMPLIANT_CONTACT), - ExampleEntry(1,"Contact for Grasp","Grasp experiment to improve contact model", R2D2GraspExampleCreateFunc,eROBOTIC_LEARN_GRASP_CONTACT), + ExampleEntry(1,"Contact for Grasp","Grasp experiment to improve contact model", GripperGraspExampleCreateFunc), diff --git a/examples/RoboticsLearning/GripperGraspExample.cpp b/examples/RoboticsLearning/GripperGraspExample.cpp new file mode 100644 index 000000000..ebdc39acb --- /dev/null +++ b/examples/RoboticsLearning/GripperGraspExample.cpp @@ -0,0 +1,231 @@ + +#include "GripperGraspExample.h" + +#include "../CommonInterfaces/CommonGraphicsAppInterface.h" +#include "Bullet3Common/b3Quaternion.h" +#include "Bullet3Common/b3AlignedObjectArray.h" +#include "../CommonInterfaces/CommonRenderInterface.h" +#include "../CommonInterfaces/CommonExampleInterface.h" +#include "../CommonInterfaces/CommonGUIHelperInterface.h" +#include "../SharedMemory/PhysicsServerSharedMemory.h" +#include "../SharedMemory/PhysicsClientC_API.h" +#include "../CommonInterfaces/CommonParameterInterface.h" +#include + +#include "b3RobotSimAPI.h" +#include "../Utils/b3Clock.h" + +static btScalar sGripperVerticalVelocity = -0.2f; +static btScalar sGripperClosingTargetVelocity = 0.5f; + +class GripperGraspExample : public CommonExampleInterface +{ + CommonGraphicsApp* m_app; + GUIHelperInterface* m_guiHelper; + b3RobotSimAPI m_robotSim; + int m_options; + int m_r2d2Index; + int m_gripperIndex; + + float m_x; + float m_y; + float m_z; + b3AlignedObjectArray m_movingInstances; + enum + { + numCubesX = 20, + numCubesY = 20 + }; +public: + + GripperGraspExample(GUIHelperInterface* helper, int options) + :m_app(helper->getAppInterface()), + m_guiHelper(helper), + m_options(options), + m_r2d2Index(-1), + m_gripperIndex(-1), + m_x(0), + m_y(0), + m_z(0) + { + m_app->setUpAxis(2); + } + virtual ~GripperGraspExample() + { + m_app->m_renderer->enableBlend(false); + } + + + virtual void physicsDebugDraw(int debugDrawMode) + { + + } + virtual void initPhysics() + { + bool connected = m_robotSim.connect(m_guiHelper); + b3Printf("robotSim connected = %d",connected); + + { + + { + SliderParams slider("Vertical velocity",&sGripperVerticalVelocity); + slider.m_minVal=-2; + slider.m_maxVal=2; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } + + { + SliderParams slider("Closing velocity",&sGripperClosingTargetVelocity + ); + slider.m_minVal=-1; + slider.m_maxVal=1; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); + } + + + { + b3RobotSimLoadFileArgs args(""); + args.m_fileName = "gripper/wsg50_with_r2d2_gripper.sdf"; + args.m_fileType = B3_SDF_FILE; + b3RobotSimLoadFileResults results; + + if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1) + { + + m_gripperIndex = results.m_uniqueObjectIds[0]; + int numJoints = m_robotSim.getNumJoints(m_gripperIndex); + b3Printf("numJoints = %d",numJoints); + + for (int i=0;i=0)) + { + int fingerJointIndices[3]={0,1,3}; + double fingerTargetVelocities[3]={sGripperVerticalVelocity,sGripperClosingTargetVelocity + ,-sGripperClosingTargetVelocity + }; + double maxTorqueValues[3]={40.0,50.0,50.0}; + for (int i=0;i<3;i++) + { + b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY); + controlArgs.m_targetVelocity = fingerTargetVelocities[i]; + controlArgs.m_maxTorqueValue = maxTorqueValues[i]; + controlArgs.m_kd = 1.; + m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs); + } + } + m_robotSim.stepSimulation(); + } + virtual void renderScene() + { + m_robotSim.renderScene(); + + //m_app->m_renderer->renderScene(); + } + + + virtual void physicsDebugDraw() + { + + } + virtual bool mouseMoveCallback(float x,float y) + { + return false; + } + virtual bool mouseButtonCallback(int button, int state, float x, float y) + { + return false; + } + virtual bool keyboardCallback(int key, int state) + { + return false; + } + + virtual void resetCamera() + { + float dist = 1.5; + float pitch = 12; + float yaw = -10; + float targetPos[3]={-0.2,0.8,0.3}; + if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) + { + m_app->m_renderer->getActiveCamera()->setCameraDistance(dist); + m_app->m_renderer->getActiveCamera()->setCameraPitch(pitch); + m_app->m_renderer->getActiveCamera()->setCameraYaw(yaw); + m_app->m_renderer->getActiveCamera()->setCameraTargetPosition(targetPos[0],targetPos[1],targetPos[2]); + } + } + +}; + + +class CommonExampleInterface* GripperGraspExampleCreateFunc(struct CommonExampleOptions& options) +{ + return new GripperGraspExample(options.m_guiHelper, options.m_option); +} + + + diff --git a/examples/RoboticsLearning/GripperGraspExample.h b/examples/RoboticsLearning/GripperGraspExample.h new file mode 100644 index 000000000..1088efffb --- /dev/null +++ b/examples/RoboticsLearning/GripperGraspExample.h @@ -0,0 +1,23 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2016 Google Inc. http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + +#ifndef GRIPPER_GRASP_EXAMPLE_H +#define GRIPPER_GRASP_EXAMPLE_H + + +class CommonExampleInterface* GripperGraspExampleCreateFunc(struct CommonExampleOptions& options); + + +#endif //GRIPPER_GRASP_EXAMPLE_H diff --git a/examples/RoboticsLearning/R2D2GraspExample.cpp b/examples/RoboticsLearning/R2D2GraspExample.cpp index f1fc2cbfd..4da5cc22a 100644 --- a/examples/RoboticsLearning/R2D2GraspExample.cpp +++ b/examples/RoboticsLearning/R2D2GraspExample.cpp @@ -9,15 +9,11 @@ #include "../CommonInterfaces/CommonGUIHelperInterface.h" #include "../SharedMemory/PhysicsServerSharedMemory.h" #include "../SharedMemory/PhysicsClientC_API.h" -#include "../CommonInterfaces/CommonParameterInterface.h" #include #include "b3RobotSimAPI.h" #include "../Utils/b3Clock.h" -static btScalar sGripperVerticalVelocity = -0.2f; -static btScalar sGripperClosingTargetVelocity = 0.5f; - ///quick demo showing the right-handed coordinate system and positive rotations around each axis class R2D2GraspExample : public CommonExampleInterface { @@ -26,8 +22,7 @@ class R2D2GraspExample : public CommonExampleInterface b3RobotSimAPI m_robotSim; int m_options; int m_r2d2Index; - int m_gripperIndex; - + float m_x; float m_y; float m_z; @@ -44,7 +39,6 @@ public: m_guiHelper(helper), m_options(options), m_r2d2Index(-1), - m_gripperIndex(-1), m_x(0), m_y(0), m_z(0) @@ -67,9 +61,36 @@ public: b3Printf("robotSim connected = %d",connected); - if (m_options == eROBOTIC_LEARN_GRASP) + if ((m_options & eROBOTIC_LEARN_GRASP)!=0) { - + { + b3RobotSimLoadFileArgs args(""); + args.m_fileName = "r2d2.urdf"; + args.m_startPosition.setValue(0,0,.5); + b3RobotSimLoadFileResults results; + if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1) + { + int m_r2d2Index = results.m_uniqueObjectIds[0]; + int numJoints = m_robotSim.getNumJoints(m_r2d2Index); + b3Printf("numJoints = %d",numJoints); + + for (int i=0;igetParameterInterface()->registerSliderFloatParameter(slider); - } - - { - SliderParams slider("Closing velocity",&sGripperClosingTargetVelocity - ); - slider.m_minVal=-1; - slider.m_maxVal=1; - m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider); - } - - - { - b3RobotSimLoadFileArgs args(""); - args.m_fileName = "gripper/wsg50_with_r2d2_gripper.sdf"; - args.m_fileType = B3_SDF_FILE; - b3RobotSimLoadFileResults results; - - if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1) - { - - m_gripperIndex = results.m_uniqueObjectIds[0]; - int numJoints = m_robotSim.getNumJoints(m_gripperIndex); - b3Printf("numJoints = %d",numJoints); - - for (int i=0;i=0)) - { - int fingerJointIndices[3]={0,1,3}; - double fingerTargetVelocities[3]={sGripperVerticalVelocity,sGripperClosingTargetVelocity - ,-sGripperClosingTargetVelocity - }; - double maxTorqueValues[3]={40.0,50.0,50.0}; - for (int i=0;i<3;i++) - { - b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY); - controlArgs.m_targetVelocity = fingerTargetVelocities[i]; - controlArgs.m_maxTorqueValue = maxTorqueValues[i]; - controlArgs.m_kd = 1.; - m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs); - } - } m_robotSim.stepSimulation(); } virtual void renderScene() @@ -290,9 +179,9 @@ public: virtual void resetCamera() { - float dist = 1.5; - float pitch = 12; - float yaw = -10; + float dist = 3; + float pitch = -75; + float yaw = 30; float targetPos[3]={-0.2,0.8,0.3}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/RoboticsLearning/R2D2GraspExample.h b/examples/RoboticsLearning/R2D2GraspExample.h index 10d419269..353f684e5 100644 --- a/examples/RoboticsLearning/R2D2GraspExample.h +++ b/examples/RoboticsLearning/R2D2GraspExample.h @@ -20,7 +20,6 @@ enum RobotLearningExampleOptions { eROBOTIC_LEARN_GRASP=1, eROBOTIC_LEARN_COMPLIANT_CONTACT=2, - eROBOTIC_LEARN_GRASP_CONTACT=3, }; class CommonExampleInterface* R2D2GraspExampleCreateFunc(struct CommonExampleOptions& options); From b221d2ad18bfec48efeccbe24302aac206948d7f Mon Sep 17 00:00:00 2001 From: Mat Kelcey Date: Tue, 26 Jul 2016 11:09:12 -0700 Subject: [PATCH 107/115] add targetPosition, targetValue, kp & kd to pybullet_setJointMotorControl --- examples/pybullet/pybullet.c | 72 +++++++++++++++++++++--------------- 1 file changed, 42 insertions(+), 30 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index be5994c16..2bd48e963 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -294,27 +294,29 @@ pybullet_resetSimulation(PyObject* self, PyObject* args) static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) { - //todo(erwincoumans): set max forces, kp, kd + //TODO(matkelcey): should this just be three methods? int size; int bodyIndex, jointIndex, controlMode; double targetValue=0; + double targetPosition=0; + double targetVelocity=0; double maxForce=100000; - double gains=0.1; + double kp=0.1; + double kd=0.1; int valid = 0; - - + if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - + size= PySequence_Size(args); - if (size==4) { - + // for CONTROL_MODE_VELOCITY targetValue -> velocity + // for CONTROL_MODE_TORQUE targetValue -> force torque if (!PyArg_ParseTuple(args, "iiid", &bodyIndex, &jointIndex, &controlMode, &targetValue)) { PyErr_SetString(SpamError, "Error parsing arguments"); @@ -324,7 +326,8 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) } if (size==5) { - + // for CONTROL_MODE_VELOCITY targetValue -> velocity + // for CONTROL_MODE_TORQUE targetValue -> force torque if (!PyArg_ParseTuple(args, "iiidd", &bodyIndex, &jointIndex, &controlMode, &targetValue, &maxForce)) { PyErr_SetString(SpamError, "Error parsing arguments"); @@ -332,20 +335,31 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) } valid = 1; } - if (size==6) + if (size==8) { - - if (!PyArg_ParseTuple(args, "iiiddd", &bodyIndex, &jointIndex, &controlMode, &targetValue, &maxForce, &gains)) + // only applicable for CONTROL_MODE_POSITION_VELOCITY_PD. + if (!PyArg_ParseTuple(args, "iiiddddd", &bodyIndex, &jointIndex, &controlMode, &targetPosition, &targetVelocity, &maxForce, &kp, &kd)) { PyErr_SetString(SpamError, "Error parsing arguments"); return NULL; } valid = 1; } - - + + if (size==8 && controlMode!=CONTROL_MODE_POSITION_VELOCITY_PD) + { + PyErr_SetString(SpamError, "8 argument call only applicable for control mode CONTROL_MODE_POSITION_VELOCITY_PD"); + return NULL; + } + if (controlMode==CONTROL_MODE_POSITION_VELOCITY_PD && size!=8) + { + PyErr_SetString(SpamError, "For CONTROL_MODE_POSITION_VELOCITY_PD please call with explicit targetPosition & targetVelocity"); + return NULL; + } + if (valid) { + int numJoints; b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryStatusHandle statusHandle; @@ -357,7 +371,7 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) PyErr_SetString(SpamError, "Joint index out-of-range."); return NULL; } - + if ((controlMode != CONTROL_MODE_VELOCITY) && (controlMode != CONTROL_MODE_TORQUE) && (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) @@ -365,19 +379,18 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) PyErr_SetString(SpamError, "Illegral control mode."); return NULL; } - + commandHandle = b3JointControlCommandInit2(sm, bodyIndex,controlMode); - + b3GetJointInfo(sm, bodyIndex, jointIndex, &info); - + switch (controlMode) { case CONTROL_MODE_VELOCITY: { - double kd = gains; b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, targetValue); - b3JointControlSetKd(commandHandle,info.m_uIndex,kd); - b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,maxForce); + b3JointControlSetKd(commandHandle, info.m_uIndex, kd); + b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, maxForce); break; } @@ -386,31 +399,30 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) b3JointControlSetDesiredForceTorque(commandHandle, info.m_uIndex, targetValue); break; } - + case CONTROL_MODE_POSITION_VELOCITY_PD: { - double kp = gains; - b3JointControlSetDesiredPosition( commandHandle, info.m_qIndex, targetValue); - b3JointControlSetKp(commandHandle,info.m_uIndex,kp); - b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,maxForce); + b3JointControlSetDesiredPosition(commandHandle, info.m_qIndex, targetPosition); + b3JointControlSetKp(commandHandle, info.m_uIndex, kp); + b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, targetVelocity); + b3JointControlSetKd(commandHandle, info.m_uIndex, kd); + b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, maxForce); break; } default: { } }; - + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); - + Py_INCREF(Py_None); return Py_None; } - PyErr_SetString(SpamError, "error in setJointControl."); + PyErr_SetString(SpamError, "Invalid number of args passed to setJointControl."); return NULL; } - - static PyObject * pybullet_setRealTimeSimulation(PyObject* self, PyObject* args) { From 4b75c5d9d0a95763152f0f9f8bc2d0d4876d7cb2 Mon Sep 17 00:00:00 2001 From: Mat Kelcey Date: Tue, 26 Jul 2016 11:36:34 -0700 Subject: [PATCH 108/115] add another combo of args to allow kd to be configured in the CONTROL_MODE_VELOCITY case --- examples/pybullet/pybullet.c | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 2bd48e963..0a1a205bb 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -335,6 +335,15 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) } valid = 1; } + if (size==6) + { + if (!PyArg_ParseTuple(args, "iiiddd", &bodyIndex, &jointIndex, &controlMode, &targetValue, &maxForce, &kd)) + { + PyErr_SetString(SpamError, "Error parsing arguments"); + return NULL; + } + valid = 1; + } if (size==8) { // only applicable for CONTROL_MODE_POSITION_VELOCITY_PD. From 98c6181ba85aa90cd98a5c8a87f40b9cfc922766 Mon Sep 17 00:00:00 2001 From: "Erwin Coumans (Google)" Date: Tue, 26 Jul 2016 15:36:21 -0700 Subject: [PATCH 109/115] fix screen width/height issue on Intel/Linux add command-line option to set png_skip_frames when taking screenshot series --- .../ExampleBrowser/OpenGLExampleBrowser.cpp | 40 ++++++++++--------- .../InverseKinematicsExample.cpp | 2 +- examples/OpenGLWindow/SimpleOpenGL3App.cpp | 6 ++- examples/OpenGLWindow/X11OpenGLWindow.cpp | 3 ++ 4 files changed, 29 insertions(+), 22 deletions(-) diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index 577d24c85..d0fae2254 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -157,6 +157,7 @@ void deleteDemo() } const char* gPngFileName = 0; +int gPngSkipFrames = 0; @@ -763,7 +764,7 @@ bool OpenGLExampleBrowser::init(int argc, char* argv[]) loadCurrentSettings(startFileName, args); args.GetCmdLineArgument("fixed_timestep",gFixedTimeStep); - + args.GetCmdLineArgument("png_skip_frames", gPngSkipFrames); ///The OpenCL rigid body pipeline is experimental and ///most OpenCL drivers and OpenCL compilers have issues with our kernels. ///If you have a high-end desktop GPU such as AMD 7970 or better, or NVIDIA GTX 680 with up-to-date drivers @@ -1101,24 +1102,6 @@ void OpenGLExampleBrowser::update(float deltaTime) //printf("---------------------------------------------------\n"); //printf("Framecount = %d\n",frameCount); - if (gPngFileName) - { - - static int skip = 0; - skip++; - if (skip>4) - { - skip=0; - //printf("gPngFileName=%s\n",gPngFileName); - static int s_frameCount = 100; - - sprintf(staticPngFileName,"%s%d.png",gPngFileName,s_frameCount++); - //b3Printf("Made screenshot %s",staticPngFileName); - s_app->dumpNextFrameToPng(staticPngFileName); - glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); - } - } - if (gFixedTimeStep>0) { @@ -1153,6 +1136,25 @@ void OpenGLExampleBrowser::update(float deltaTime) } } + if (gPngFileName) + { + + static int skip = 0; + skip--; + if (skip<0) + { + skip=gPngSkipFrames; + //printf("gPngFileName=%s\n",gPngFileName); + static int s_frameCount = 100; + + sprintf(staticPngFileName,"%s%d.png",gPngFileName,s_frameCount++); + //b3Printf("Made screenshot %s",staticPngFileName); + s_app->dumpNextFrameToPng(staticPngFileName); + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + } + } + + { if (gui2 && s_guiHelper && s_guiHelper->getRenderInterface() && s_guiHelper->getRenderInterface()->getActiveCamera()) diff --git a/examples/InverseKinematics/InverseKinematicsExample.cpp b/examples/InverseKinematics/InverseKinematicsExample.cpp index 8f902b008..4c36037a6 100644 --- a/examples/InverseKinematics/InverseKinematicsExample.cpp +++ b/examples/InverseKinematics/InverseKinematicsExample.cpp @@ -84,7 +84,7 @@ void Reset(Tree &tree, Jacobian* m_ikJacobian) // Update target positions void UpdateTargets( double T2, Tree & treeY) { - double T = T2 / 20.; + double T = T2 / 5.; target1[0].Set(0.6*b3Sin(0), 0.6*b3Cos(0), 0.5+0.4*b3Sin(3 * T)); } diff --git a/examples/OpenGLWindow/SimpleOpenGL3App.cpp b/examples/OpenGLWindow/SimpleOpenGL3App.cpp index 1423f2841..971df3734 100644 --- a/examples/OpenGLWindow/SimpleOpenGL3App.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL3App.cpp @@ -753,8 +753,10 @@ void SimpleOpenGL3App::swapBuffer() m_window->endRendering(); if (m_data->m_frameDumpPngFileName) { - writeTextureToFile((int)m_window->getRetinaScale()*m_instancingRenderer->getScreenWidth(), - (int) m_window->getRetinaScale()*this->m_instancingRenderer->getScreenHeight(),m_data->m_frameDumpPngFileName, + int width = (int)m_window->getRetinaScale()*m_instancingRenderer->getScreenWidth(); + int height = (int) m_window->getRetinaScale()*this->m_instancingRenderer->getScreenHeight(); + writeTextureToFile(width, + height,m_data->m_frameDumpPngFileName, m_data->m_ffmpegFile); m_data->m_renderTexture->disable(); if (m_data->m_ffmpegFile==0) diff --git a/examples/OpenGLWindow/X11OpenGLWindow.cpp b/examples/OpenGLWindow/X11OpenGLWindow.cpp index 68aa22720..789be7803 100644 --- a/examples/OpenGLWindow/X11OpenGLWindow.cpp +++ b/examples/OpenGLWindow/X11OpenGLWindow.cpp @@ -516,6 +516,9 @@ void X11OpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci) m_data->m_dpy = MyXOpenDisplay(NULL); + m_data->m_glWidth = ci.m_width; + m_data->m_glHeight = ci.m_height; + if(m_data->m_dpy == NULL) { printf("\n\tcannot connect to X server\n\n"); exit(0); From b4cfee87453f22b82647d1563aff34a3f59ee4ec Mon Sep 17 00:00:00 2001 From: Mat Kelcey Date: Tue, 26 Jul 2016 16:15:08 -0700 Subject: [PATCH 110/115] set dft for kd to be 1.0. note: this is only applicable to CONTROL_MODE_VELOCITY --- examples/pybullet/pybullet.c | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 0a1a205bb..d2b7a496c 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -294,8 +294,6 @@ pybullet_resetSimulation(PyObject* self, PyObject* args) static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) { - //TODO(matkelcey): should this just be three methods? - int size; int bodyIndex, jointIndex, controlMode; double targetValue=0; @@ -303,7 +301,7 @@ static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) double targetVelocity=0; double maxForce=100000; double kp=0.1; - double kd=0.1; + double kd=1.0; int valid = 0; if (0==sm) From daf91de77878858611c601ed89ff14651eb3fb44 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Wed, 27 Jul 2016 09:11:08 -0700 Subject: [PATCH 111/115] fix ffmpeg stream to create quicktime compatible videos --- examples/OpenGLWindow/SimpleOpenGL3App.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/examples/OpenGLWindow/SimpleOpenGL3App.cpp b/examples/OpenGLWindow/SimpleOpenGL3App.cpp index 971df3734..7cfc75652 100644 --- a/examples/OpenGLWindow/SimpleOpenGL3App.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL3App.cpp @@ -750,7 +750,7 @@ static void writeTextureToFile(int textureWidth, int textureHeight, const char* void SimpleOpenGL3App::swapBuffer() { - m_window->endRendering(); + if (m_data->m_frameDumpPngFileName) { int width = (int)m_window->getRetinaScale()*m_instancingRenderer->getScreenWidth(); @@ -764,7 +764,8 @@ void SimpleOpenGL3App::swapBuffer() m_data->m_frameDumpPngFileName = 0; } } - m_window->startRendering(); + m_window->endRendering(); + m_window->startRendering(); } // see also http://blog.mmacklin.com/2013/06/11/real-time-video-capture-with-ffmpeg/ @@ -780,7 +781,7 @@ void SimpleOpenGL3App::dumpFramesToVideo(const char* mp4FileName) #else sprintf(cmd, "ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - " - "-threads 0 -y -crf 0 -b 50000k -vf vflip %s", width, height, mp4FileName); + "-threads 0 -y -b 50000k -t 20 -c:v libx264 -preset slow -crf 22 -an -pix_fmt yuv420p -vf vflip %s", width, height, mp4FileName); #endif //sprintf(cmd,"ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - " From 626a913866158e5956cfa2ae7f5f6350e99d783e Mon Sep 17 00:00:00 2001 From: MiCroN3000 Date: Thu, 28 Jul 2016 20:15:38 +0200 Subject: [PATCH 112/115] The kinematic character controller with various fixes and a few new features like, being able to set any vector for gravity/up, jumping in a certain direction, possibility to use collision masks, angular & linear velocity, angular & linear damping. --- .../btCharacterControllerInterface.h | 2 +- .../btKinematicCharacterController.cpp | 461 +++++++++++++----- .../btKinematicCharacterController.h | 60 ++- 3 files changed, 395 insertions(+), 128 deletions(-) diff --git a/src/BulletDynamics/Character/btCharacterControllerInterface.h b/src/BulletDynamics/Character/btCharacterControllerInterface.h index dffb06dfe..c3a3ac6c8 100644 --- a/src/BulletDynamics/Character/btCharacterControllerInterface.h +++ b/src/BulletDynamics/Character/btCharacterControllerInterface.h @@ -37,7 +37,7 @@ public: virtual void preStep ( btCollisionWorld* collisionWorld) = 0; virtual void playerStep (btCollisionWorld* collisionWorld, btScalar dt) = 0; virtual bool canJump () const = 0; - virtual void jump () = 0; + virtual void jump(const btVector3& dir = btVector3()) = 0; virtual bool onGround () const = 0; virtual void setUpInterpolate (bool value) = 0; diff --git a/src/BulletDynamics/Character/btKinematicCharacterController.cpp b/src/BulletDynamics/Character/btKinematicCharacterController.cpp index 31faf1df5..60e49b750 100644 --- a/src/BulletDynamics/Character/btKinematicCharacterController.cpp +++ b/src/BulletDynamics/Character/btKinematicCharacterController.cpp @@ -132,30 +132,37 @@ btVector3 btKinematicCharacterController::perpindicularComponent (const btVector return direction - parallelComponent(direction, normal); } -btKinematicCharacterController::btKinematicCharacterController (btPairCachingGhostObject* ghostObject,btConvexShape* convexShape,btScalar stepHeight, int upAxis) +btKinematicCharacterController::btKinematicCharacterController (btPairCachingGhostObject* ghostObject,btConvexShape* convexShape,btScalar stepHeight, const btVector3& up) { - m_upAxis = upAxis; + m_up.setValue(0.0f, 0.0f, 1.0f); + m_jumpAxis.setValue(0.0f, 0.0f, 1.0f); + setUp(up); + setStepHeight(stepHeight); m_addedMargin = 0.02; - m_walkDirection.setValue(0,0,0); + m_walkDirection.setValue(0.0,0.0,0.0); + m_AngVel.setValue(0.0, 0.0, 0.0); m_useGhostObjectSweepTest = true; m_ghostObject = ghostObject; - m_stepHeight = stepHeight; m_turnAngle = btScalar(0.0); m_convexShape=convexShape; m_useWalkDirection = true; // use walk direction by default, legacy behavior m_velocityTimeInterval = 0.0; m_verticalVelocity = 0.0; m_verticalOffset = 0.0; - m_gravity = 9.8 * 3 ; // 3G acceleration. + m_gravity = 9.8 * 3.0 ; // 3G acceleration. m_fallSpeed = 55.0; // Terminal velocity of a sky diver in m/s. m_jumpSpeed = 10.0; // ? + m_SetjumpSpeed = m_jumpSpeed; m_wasOnGround = false; m_wasJumping = false; m_interpolateUp = true; setMaxSlope(btRadians(45.0)); - m_currentStepOffset = 0; + m_currentStepOffset = 0.0; + m_maxPenetrationDepth = 0.2; full_drop = false; bounce_fix = false; + m_linearDamping = btScalar(0.0); + m_angularDamping = btScalar(0.0); } btKinematicCharacterController::~btKinematicCharacterController () @@ -190,7 +197,7 @@ bool btKinematicCharacterController::recoverFromPenetration ( btCollisionWorld* m_currentPosition = m_ghostObject->getWorldTransform().getOrigin(); - btScalar maxPen = btScalar(0.0); +// btScalar maxPen = btScalar(0.0); for (int i = 0; i < m_ghostObject->getOverlappingPairCache()->getNumOverlappingPairs(); i++) { m_manifoldArray.resize(0); @@ -198,10 +205,13 @@ bool btKinematicCharacterController::recoverFromPenetration ( btCollisionWorld* btBroadphasePair* collisionPair = &m_ghostObject->getOverlappingPairCache()->getOverlappingPairArray()[i]; btCollisionObject* obj0 = static_cast(collisionPair->m_pProxy0->m_clientObject); - btCollisionObject* obj1 = static_cast(collisionPair->m_pProxy1->m_clientObject); + btCollisionObject* obj1 = static_cast(collisionPair->m_pProxy1->m_clientObject); if ((obj0 && !obj0->hasContactResponse()) || (obj1 && !obj1->hasContactResponse())) continue; + + if (!needsCollision(obj0, obj1)) + continue; if (collisionPair->m_algorithm) collisionPair->m_algorithm->getAllContactManifolds(m_manifoldArray); @@ -217,14 +227,15 @@ bool btKinematicCharacterController::recoverFromPenetration ( btCollisionWorld* btScalar dist = pt.getDistance(); - if (dist < 0.0) + if (dist < -m_maxPenetrationDepth) { - if (dist < maxPen) - { - maxPen = dist; - m_touchingNormal = pt.m_normalWorldOnB * directionSign;//?? + // TODO: cause problems on slopes, not sure if it is needed + //if (dist < maxPen) + //{ + // maxPen = dist; + // m_touchingNormal = pt.m_normalWorldOnB * directionSign;//?? - } + //} m_currentPosition += pt.m_normalWorldOnB * directionSign * dist * btScalar(0.2); penetration = true; } else { @@ -244,18 +255,28 @@ bool btKinematicCharacterController::recoverFromPenetration ( btCollisionWorld* void btKinematicCharacterController::stepUp ( btCollisionWorld* world) { + btScalar stepHeight = 0.0f; + if (m_verticalVelocity < 0.0) + stepHeight = m_stepHeight; + // phase 1: up btTransform start, end; - m_targetPosition = m_currentPosition + getUpAxisDirections()[m_upAxis] * (m_stepHeight + (m_verticalOffset > 0.f?m_verticalOffset:0.f)); start.setIdentity (); end.setIdentity (); /* FIXME: Handle penetration properly */ - start.setOrigin (m_currentPosition + getUpAxisDirections()[m_upAxis] * (m_convexShape->getMargin() + m_addedMargin)); + start.setOrigin(m_currentPosition); + + m_targetPosition = m_currentPosition + m_up * (stepHeight) + m_jumpAxis * ((m_verticalOffset > 0.f ? m_verticalOffset : 0.f)); + m_currentPosition = m_targetPosition; + end.setOrigin (m_targetPosition); - btKinematicClosestNotMeConvexResultCallback callback (m_ghostObject, -getUpAxisDirections()[m_upAxis], btScalar(0.7071)); + start.setRotation(m_currentOrientation); + end.setRotation(m_targetOrientation); + + btKinematicClosestNotMeConvexResultCallback callback(m_ghostObject, -m_up, m_maxSlopeCosine); callback.m_collisionFilterGroup = getGhostObject()->getBroadphaseHandle()->m_collisionFilterGroup; callback.m_collisionFilterMask = getGhostObject()->getBroadphaseHandle()->m_collisionFilterMask; @@ -265,29 +286,61 @@ void btKinematicCharacterController::stepUp ( btCollisionWorld* world) } else { - world->convexSweepTest (m_convexShape, start, end, callback); + world->convexSweepTest(m_convexShape, start, end, callback, world->getDispatchInfo().m_allowedCcdPenetration); } - - if (callback.hasHit()) + + if (callback.hasHit() && m_ghostObject->hasContactResponse() && needsCollision(m_ghostObject, callback.m_hitCollisionObject)) { // Only modify the position if the hit was a slope and not a wall or ceiling. - if(callback.m_hitNormalWorld.dot(getUpAxisDirections()[m_upAxis]) > 0.0) + if (callback.m_hitNormalWorld.dot(m_up) > 0.0) { // we moved up only a fraction of the step height - m_currentStepOffset = m_stepHeight * callback.m_closestHitFraction; + m_currentStepOffset = stepHeight * callback.m_closestHitFraction; if (m_interpolateUp == true) m_currentPosition.setInterpolate3 (m_currentPosition, m_targetPosition, callback.m_closestHitFraction); else m_currentPosition = m_targetPosition; } - m_verticalVelocity = 0.0; - m_verticalOffset = 0.0; + + btTransform& xform = m_ghostObject->getWorldTransform(); + xform.setOrigin(m_currentPosition); + m_ghostObject->setWorldTransform(xform); + + // fix penetration if we hit a ceiling for example + int numPenetrationLoops = 0; + m_touchingContact = false; + while (recoverFromPenetration(world)) + { + numPenetrationLoops++; + m_touchingContact = true; + if (numPenetrationLoops > 4) + { + //printf("character could not recover from penetration = %d\n", numPenetrationLoops); + break; + } + } + m_targetPosition = m_ghostObject->getWorldTransform().getOrigin(); + m_currentPosition = m_targetPosition; + + if (m_verticalOffset > 0) + { + m_verticalOffset = 0.0; + m_verticalVelocity = 0.0; + m_currentStepOffset = m_stepHeight; + } } else { - m_currentStepOffset = m_stepHeight; + m_currentStepOffset = stepHeight; m_currentPosition = m_targetPosition; } } +bool btKinematicCharacterController::needsCollision(const btCollisionObject* body0, const btCollisionObject* body1) +{ + bool collides = (body0->getBroadphaseHandle()->m_collisionFilterGroup & body1->getBroadphaseHandle()->m_collisionFilterMask) != 0; + collides = collides && (body1->getBroadphaseHandle()->m_collisionFilterGroup & body0->getBroadphaseHandle()->m_collisionFilterMask); + return collides; +} + void btKinematicCharacterController::updateTargetPositionBasedOnCollision (const btVector3& hitNormal, btScalar tangentMag, btScalar normalMag) { btVector3 movementDirection = m_targetPosition - m_currentPosition; @@ -330,6 +383,7 @@ void btKinematicCharacterController::stepForwardAndStrafe ( btCollisionWorld* co // m_normalizedDirection[0],m_normalizedDirection[1],m_normalizedDirection[2]); // phase 2: forward and strafe btTransform start, end; + m_targetPosition = m_currentPosition + walkMove; start.setIdentity (); @@ -339,15 +393,6 @@ void btKinematicCharacterController::stepForwardAndStrafe ( btCollisionWorld* co btScalar distance2 = (m_currentPosition-m_targetPosition).length2(); // printf("distance2=%f\n",distance2); - if (m_touchingContact) - { - if (m_normalizedDirection.dot(m_touchingNormal) > btScalar(0.0)) - { - //interferes with step movement - //updateTargetPositionBasedOnCollision (m_touchingNormal); - } - } - int maxIter = 10; while (fraction > btScalar(0.01) && maxIter-- > 0) @@ -356,6 +401,9 @@ void btKinematicCharacterController::stepForwardAndStrafe ( btCollisionWorld* co end.setOrigin (m_targetPosition); btVector3 sweepDirNegative(m_currentPosition - m_targetPosition); + start.setRotation(m_currentOrientation); + end.setRotation(m_targetOrientation); + btKinematicClosestNotMeConvexResultCallback callback (m_ghostObject, sweepDirNegative, btScalar(0.0)); callback.m_collisionFilterGroup = getGhostObject()->getBroadphaseHandle()->m_collisionFilterGroup; callback.m_collisionFilterMask = getGhostObject()->getBroadphaseHandle()->m_collisionFilterMask; @@ -364,21 +412,23 @@ void btKinematicCharacterController::stepForwardAndStrafe ( btCollisionWorld* co btScalar margin = m_convexShape->getMargin(); m_convexShape->setMargin(margin + m_addedMargin); - - if (m_useGhostObjectSweepTest) + if (!(start == end)) { - m_ghostObject->convexSweepTest (m_convexShape, start, end, callback, collisionWorld->getDispatchInfo().m_allowedCcdPenetration); - } else - { - collisionWorld->convexSweepTest (m_convexShape, start, end, callback, collisionWorld->getDispatchInfo().m_allowedCcdPenetration); + if (m_useGhostObjectSweepTest) + { + m_ghostObject->convexSweepTest(m_convexShape, start, end, callback, collisionWorld->getDispatchInfo().m_allowedCcdPenetration); + } + else + { + collisionWorld->convexSweepTest(m_convexShape, start, end, callback, collisionWorld->getDispatchInfo().m_allowedCcdPenetration); + } } - m_convexShape->setMargin(margin); fraction -= callback.m_closestHitFraction; - if (callback.hasHit()) + if (callback.hasHit() && m_ghostObject->hasContactResponse() && needsCollision(m_ghostObject, callback.m_hitCollisionObject)) { // we moved only a fraction //btScalar hitDistance; @@ -404,9 +454,11 @@ void btKinematicCharacterController::stepForwardAndStrafe ( btCollisionWorld* co } } else { - // we moved whole way - m_currentPosition = m_targetPosition; +// if (!m_wasJumping) + // we moved whole way + m_currentPosition = m_targetPosition; } + m_currentPosition = m_targetPosition; // if (callback.m_closestHitFraction == 0.f) // break; @@ -421,27 +473,30 @@ void btKinematicCharacterController::stepDown ( btCollisionWorld* collisionWorld // phase 3: down /*btScalar additionalDownStep = (m_wasOnGround && !onGround()) ? m_stepHeight : 0.0; - btVector3 step_drop = getUpAxisDirections()[m_upAxis] * (m_currentStepOffset + additionalDownStep); + btVector3 step_drop = m_up * (m_currentStepOffset + additionalDownStep); btScalar downVelocity = (additionalDownStep == 0.0 && m_verticalVelocity<0.0?-m_verticalVelocity:0.0) * dt; - btVector3 gravity_drop = getUpAxisDirections()[m_upAxis] * downVelocity; + btVector3 gravity_drop = m_up * downVelocity; m_targetPosition -= (step_drop + gravity_drop);*/ btVector3 orig_position = m_targetPosition; btScalar downVelocity = (m_verticalVelocity<0.f?-m_verticalVelocity:0.f) * dt; + if (m_verticalVelocity > 0.0) + return; + if(downVelocity > 0.0 && downVelocity > m_fallSpeed && (m_wasOnGround || !m_wasJumping)) downVelocity = m_fallSpeed; - btVector3 step_drop = getUpAxisDirections()[m_upAxis] * (m_currentStepOffset + downVelocity); + btVector3 step_drop = m_up * (m_currentStepOffset + downVelocity); m_targetPosition -= step_drop; - btKinematicClosestNotMeConvexResultCallback callback (m_ghostObject, getUpAxisDirections()[m_upAxis], m_maxSlopeCosine); + btKinematicClosestNotMeConvexResultCallback callback(m_ghostObject, m_up, m_maxSlopeCosine); callback.m_collisionFilterGroup = getGhostObject()->getBroadphaseHandle()->m_collisionFilterGroup; callback.m_collisionFilterMask = getGhostObject()->getBroadphaseHandle()->m_collisionFilterMask; - btKinematicClosestNotMeConvexResultCallback callback2 (m_ghostObject, getUpAxisDirections()[m_upAxis], m_maxSlopeCosine); + btKinematicClosestNotMeConvexResultCallback callback2(m_ghostObject, m_up, m_maxSlopeCosine); callback2.m_collisionFilterGroup = getGhostObject()->getBroadphaseHandle()->m_collisionFilterGroup; callback2.m_collisionFilterMask = getGhostObject()->getBroadphaseHandle()->m_collisionFilterMask; @@ -455,6 +510,9 @@ void btKinematicCharacterController::stepDown ( btCollisionWorld* collisionWorld start.setOrigin (m_currentPosition); end.setOrigin (m_targetPosition); + start.setRotation(m_currentOrientation); + end.setRotation(m_targetOrientation); + //set double test for 2x the step drop, to check for a large drop vs small drop end_double.setOrigin (m_targetPosition - step_drop); @@ -462,7 +520,7 @@ void btKinematicCharacterController::stepDown ( btCollisionWorld* collisionWorld { m_ghostObject->convexSweepTest (m_convexShape, start, end, callback, collisionWorld->getDispatchInfo().m_allowedCcdPenetration); - if (!callback.hasHit()) + if (!callback.hasHit() && m_ghostObject->hasContactResponse() && needsCollision(m_ghostObject, callback.m_hitCollisionObject)) { //test a double fall height, to see if the character should interpolate it's fall (full) or not (partial) m_ghostObject->convexSweepTest (m_convexShape, start, end_double, callback2, collisionWorld->getDispatchInfo().m_allowedCcdPenetration); @@ -471,30 +529,34 @@ void btKinematicCharacterController::stepDown ( btCollisionWorld* collisionWorld { collisionWorld->convexSweepTest (m_convexShape, start, end, callback, collisionWorld->getDispatchInfo().m_allowedCcdPenetration); - if (!callback.hasHit()) - { - //test a double fall height, to see if the character should interpolate it's fall (large) or not (small) - collisionWorld->convexSweepTest (m_convexShape, start, end_double, callback2, collisionWorld->getDispatchInfo().m_allowedCcdPenetration); - } + if (!callback.hasHit() && m_ghostObject->hasContactResponse() && needsCollision(m_ghostObject, callback.m_hitCollisionObject)) + { + //test a double fall height, to see if the character should interpolate it's fall (large) or not (small) + collisionWorld->convexSweepTest (m_convexShape, start, end_double, callback2, collisionWorld->getDispatchInfo().m_allowedCcdPenetration); + } } btScalar downVelocity2 = (m_verticalVelocity<0.f?-m_verticalVelocity:0.f) * dt; bool has_hit = false; if (bounce_fix == true) - has_hit = callback.hasHit() || callback2.hasHit(); + has_hit = (callback.hasHit() || callback2.hasHit()) && m_ghostObject->hasContactResponse() && needsCollision(m_ghostObject, callback.m_hitCollisionObject); else - has_hit = callback2.hasHit(); + has_hit = callback2.hasHit() && m_ghostObject->hasContactResponse() && needsCollision(m_ghostObject, callback.m_hitCollisionObject); - if(downVelocity2 > 0.0 && downVelocity2 < m_stepHeight && has_hit == true && runonce == false + btScalar stepHeight = 0.0f; + if (m_verticalVelocity < 0.0) + stepHeight = m_stepHeight; + + if (downVelocity2 > 0.0 && downVelocity2 < stepHeight && has_hit == true && runonce == false && (m_wasOnGround || !m_wasJumping)) { //redo the velocity calculation when falling a small amount, for fast stairs motion //for larger falls, use the smoother/slower interpolated movement by not touching the target position m_targetPosition = orig_position; - downVelocity = m_stepHeight; + downVelocity = stepHeight; - btVector3 step_drop = getUpAxisDirections()[m_upAxis] * (m_currentStepOffset + downVelocity); + btVector3 step_drop = m_up * (m_currentStepOffset + downVelocity); m_targetPosition -= step_drop; runonce = true; continue; //re-run previous tests @@ -502,10 +564,9 @@ void btKinematicCharacterController::stepDown ( btCollisionWorld* collisionWorld break; } - if (callback.hasHit() || runonce == true) + if ((callback.hasHit() || runonce == true) && m_ghostObject->hasContactResponse() && needsCollision(m_ghostObject, callback.m_hitCollisionObject)) { // we dropped a fraction of the height -> hit floor - btScalar fraction = (m_currentPosition.getY() - callback.m_hitPointWorld.getY()) / 2; //printf("hitpoint: %g - pos %g\n", callback.m_hitPointWorld.getY(), m_currentPosition.getY()); @@ -513,10 +574,10 @@ void btKinematicCharacterController::stepDown ( btCollisionWorld* collisionWorld if (bounce_fix == true) { if (full_drop == true) - m_currentPosition.setInterpolate3 (m_currentPosition, m_targetPosition, callback.m_closestHitFraction); - else - //due to errors in the closestHitFraction variable when used with large polygons, calculate the hit fraction manually - m_currentPosition.setInterpolate3 (m_currentPosition, m_targetPosition, fraction); + m_currentPosition.setInterpolate3 (m_currentPosition, m_targetPosition, callback.m_closestHitFraction); + else + //due to errors in the closestHitFraction variable when used with large polygons, calculate the hit fraction manually + m_currentPosition.setInterpolate3 (m_currentPosition, m_targetPosition, fraction); } else m_currentPosition.setInterpolate3 (m_currentPosition, m_targetPosition, callback.m_closestHitFraction); @@ -528,7 +589,7 @@ void btKinematicCharacterController::stepDown ( btCollisionWorld* collisionWorld m_wasJumping = false; } else { // we dropped the full height - + full_drop = true; if (bounce_fix == true) @@ -538,7 +599,7 @@ void btKinematicCharacterController::stepDown ( btCollisionWorld* collisionWorld { m_targetPosition += step_drop; //undo previous target change downVelocity = m_fallSpeed; - step_drop = getUpAxisDirections()[m_upAxis] * (m_currentStepOffset + downVelocity); + step_drop = m_up * (m_currentStepOffset + downVelocity); m_targetPosition -= step_drop; } } @@ -579,21 +640,63 @@ btScalar timeInterval m_velocityTimeInterval += timeInterval; } +void btKinematicCharacterController::setAngularVelocity(const btVector3& velocity) +{ + m_AngVel = velocity; +} + +const btVector3& btKinematicCharacterController::getAngularVelocity() const +{ + return m_AngVel; +} + +void btKinematicCharacterController::setLinearVelocity(const btVector3& velocity) +{ + m_walkDirection = velocity; + + // HACK: if we are moving in the direction of the up, treat it as a jump :( + if (m_walkDirection.length2() > 0) + { + btVector3 w = velocity.normalized(); + btScalar c = w.dot(m_up); + if (c != 0) + { + //there is a component in walkdirection for vertical velocity + btVector3 upComponent = m_up * (sinf(SIMD_HALF_PI - acosf(c)) * m_walkDirection.length()); + m_walkDirection -= upComponent; + m_verticalVelocity = (c < 0.0f ? -1 : 1) * upComponent.length(); + + if (c > 0.0f) + { + m_wasJumping = true; + m_jumpPosition = m_ghostObject->getWorldTransform().getOrigin(); + } + } + } + else + m_verticalVelocity = 0.0f; +} + +btVector3 btKinematicCharacterController::getLinearVelocity() const +{ + return m_walkDirection + (m_verticalVelocity * m_up); +} + void btKinematicCharacterController::reset ( btCollisionWorld* collisionWorld ) { - m_verticalVelocity = 0.0; - m_verticalOffset = 0.0; - m_wasOnGround = false; - m_wasJumping = false; - m_walkDirection.setValue(0,0,0); - m_velocityTimeInterval = 0.0; + m_verticalVelocity = 0.0; + m_verticalOffset = 0.0; + m_wasOnGround = false; + m_wasJumping = false; + m_walkDirection.setValue(0,0,0); + m_velocityTimeInterval = 0.0; - //clear pair cache - btHashedOverlappingPairCache *cache = m_ghostObject->getOverlappingPairCache(); - while (cache->getOverlappingPairArray().size() > 0) - { - cache->removeOverlappingPair(cache->getOverlappingPairArray()[0].m_pProxy0, cache->getOverlappingPairArray()[0].m_pProxy1, collisionWorld->getDispatcher()); - } + //clear pair cache + btHashedOverlappingPairCache *cache = m_ghostObject->getOverlappingPairCache(); + while (cache->getOverlappingPairArray().size() > 0) + { + cache->removeOverlappingPair(cache->getOverlappingPairArray()[0].m_pProxy0, cache->getOverlappingPairArray()[0].m_pProxy1, collisionWorld->getDispatcher()); + } } void btKinematicCharacterController::warp (const btVector3& origin) @@ -607,62 +710,99 @@ void btKinematicCharacterController::warp (const btVector3& origin) void btKinematicCharacterController::preStep ( btCollisionWorld* collisionWorld) { - - int numPenetrationLoops = 0; - m_touchingContact = false; - while (recoverFromPenetration (collisionWorld)) - { - numPenetrationLoops++; - m_touchingContact = true; - if (numPenetrationLoops > 4) - { - //printf("character could not recover from penetration = %d\n", numPenetrationLoops); - break; - } - } - m_currentPosition = m_ghostObject->getWorldTransform().getOrigin(); m_targetPosition = m_currentPosition; + + m_currentOrientation = m_ghostObject->getWorldTransform().getRotation(); + m_targetOrientation = m_currentOrientation; // printf("m_targetPosition=%f,%f,%f\n",m_targetPosition[0],m_targetPosition[1],m_targetPosition[2]); - - } -#include - void btKinematicCharacterController::playerStep ( btCollisionWorld* collisionWorld, btScalar dt) { // printf("playerStep(): "); // printf(" dt = %f", dt); + if (m_AngVel.length2() > 0.0f) + { + m_AngVel *= btPow(btScalar(1) - m_angularDamping, dt); + } + + // integrate for angular velocity + if (m_AngVel.length2() > 0.0f) + { + btTransform xform; + xform = m_ghostObject->getWorldTransform(); + + btQuaternion rot(m_AngVel.normalized(), m_AngVel.length() * dt); + + btQuaternion orn = rot * xform.getRotation(); + + xform.setRotation(orn); + m_ghostObject->setWorldTransform(xform); + + m_currentPosition = m_ghostObject->getWorldTransform().getOrigin(); + m_targetPosition = m_currentPosition; + m_currentOrientation = m_ghostObject->getWorldTransform().getRotation(); + m_targetOrientation = m_currentOrientation; + } + // quick check... - if (!m_useWalkDirection && (m_velocityTimeInterval <= 0.0 || m_walkDirection.fuzzyZero())) { + if (!m_useWalkDirection && (m_velocityTimeInterval <= 0.0)) { // printf("\n"); return; // no motion } m_wasOnGround = onGround(); + //btVector3 lvel = m_walkDirection; + btScalar c = 0.0f; + + if (m_walkDirection.length2() > 0) + { + // apply damping + m_walkDirection *= btPow(btScalar(1) - m_linearDamping, dt); + } + + m_verticalVelocity *= btPow(btScalar(1) - m_linearDamping, dt); + // Update fall velocity. m_verticalVelocity -= m_gravity * dt; - if(m_verticalVelocity > 0.0 && m_verticalVelocity > m_jumpSpeed) + if (m_verticalVelocity > 0.0 && m_verticalVelocity > m_jumpSpeed) { m_verticalVelocity = m_jumpSpeed; } - if(m_verticalVelocity < 0.0 && btFabs(m_verticalVelocity) > btFabs(m_fallSpeed)) + if (m_verticalVelocity < 0.0 && btFabs(m_verticalVelocity) > btFabs(m_fallSpeed)) { m_verticalVelocity = -btFabs(m_fallSpeed); } m_verticalOffset = m_verticalVelocity * dt; - btTransform xform; - xform = m_ghostObject->getWorldTransform (); + xform = m_ghostObject->getWorldTransform(); // printf("walkDirection(%f,%f,%f)\n",walkDirection[0],walkDirection[1],walkDirection[2]); // printf("walkSpeed=%f\n",walkSpeed); - stepUp (collisionWorld); + stepUp(collisionWorld); + //todo: Experimenting with behavior of controller when it hits a ceiling.. + //bool hitUp = stepUp (collisionWorld); + //if (hitUp) + //{ + // m_verticalVelocity -= m_gravity * dt; + // if (m_verticalVelocity > 0.0 && m_verticalVelocity > m_jumpSpeed) + // { + // m_verticalVelocity = m_jumpSpeed; + // } + // if (m_verticalVelocity < 0.0 && btFabs(m_verticalVelocity) > btFabs(m_fallSpeed)) + // { + // m_verticalVelocity = -btFabs(m_fallSpeed); + // } + // m_verticalOffset = m_verticalVelocity * dt; + + // xform = m_ghostObject->getWorldTransform(); + //} + if (m_useWalkDirection) { stepForwardAndStrafe (collisionWorld, m_walkDirection); } else { @@ -682,10 +822,38 @@ void btKinematicCharacterController::playerStep ( btCollisionWorld* collisionWo } stepDown (collisionWorld, dt); + //todo: Experimenting with max jump height + //if (m_wasJumping) + //{ + // btScalar ds = m_currentPosition[m_upAxis] - m_jumpPosition[m_upAxis]; + // if (ds > m_maxJumpHeight) + // { + // // substract the overshoot + // m_currentPosition[m_upAxis] -= ds - m_maxJumpHeight; + + // // max height was reached, so potential energy is at max + // // and kinematic energy is 0, thus velocity is 0. + // if (m_verticalVelocity > 0.0) + // m_verticalVelocity = 0.0; + // } + //} // printf("\n"); xform.setOrigin (m_currentPosition); m_ghostObject->setWorldTransform (xform); + + int numPenetrationLoops = 0; + m_touchingContact = false; + while (recoverFromPenetration(collisionWorld)) + { + numPenetrationLoops++; + m_touchingContact = true; + if (numPenetrationLoops > 4) + { + //printf("character could not recover from penetration = %d\n", numPenetrationLoops); + break; + } + } } void btKinematicCharacterController::setFallSpeed (btScalar fallSpeed) @@ -696,6 +864,7 @@ void btKinematicCharacterController::setFallSpeed (btScalar fallSpeed) void btKinematicCharacterController::setJumpSpeed (btScalar jumpSpeed) { m_jumpSpeed = jumpSpeed; + m_SetjumpSpeed = m_jumpSpeed; } void btKinematicCharacterController::setMaxJumpHeight (btScalar maxJumpHeight) @@ -708,14 +877,16 @@ bool btKinematicCharacterController::canJump () const return onGround(); } -void btKinematicCharacterController::jump () +void btKinematicCharacterController::jump(const btVector3& v) { - if (!canJump()) - return; - + m_jumpSpeed = v.length2() == 0 ? m_SetjumpSpeed : v.length(); m_verticalVelocity = m_jumpSpeed; m_wasJumping = true; + m_jumpAxis = v.length2() == 0 ? m_up : v.normalized(); + + m_jumpPosition = m_ghostObject->getWorldTransform().getOrigin(); + #if 0 currently no jumping. btTransform xform; @@ -727,14 +898,16 @@ void btKinematicCharacterController::jump () #endif } -void btKinematicCharacterController::setGravity(btScalar gravity) +void btKinematicCharacterController::setGravity(const btVector3& gravity) { - m_gravity = gravity; + if (gravity.length2() > 0) setUpVector(-gravity); + + m_gravity = gravity.length(); } -btScalar btKinematicCharacterController::getGravity() const +btVector3 btKinematicCharacterController::getGravity() const { - return m_gravity; + return -m_gravity * m_up; } void btKinematicCharacterController::setMaxSlope(btScalar slopeRadians) @@ -748,11 +921,25 @@ btScalar btKinematicCharacterController::getMaxSlope() const return m_maxSlopeRadians; } -bool btKinematicCharacterController::onGround () const +void btKinematicCharacterController::setMaxPenetrationDepth(btScalar d) { - return m_verticalVelocity == 0.0 && m_verticalOffset == 0.0; + m_maxPenetrationDepth = d; } +btScalar btKinematicCharacterController::getMaxPenetrationDepth() const +{ + return m_maxPenetrationDepth; +} + +bool btKinematicCharacterController::onGround () const +{ + return (fabs(m_verticalVelocity) < SIMD_EPSILON) && (fabs(m_verticalOffset) < SIMD_EPSILON); +} + +void btKinematicCharacterController::setStepHeight(btScalar h) +{ + m_stepHeight = h; +} btVector3* btKinematicCharacterController::getUpAxisDirections() { @@ -769,3 +956,49 @@ void btKinematicCharacterController::setUpInterpolate(bool value) { m_interpolateUp = value; } + +void btKinematicCharacterController::setUp(const btVector3& up) +{ + if (up.length2() > 0 && m_gravity > 0.0f) + { + setGravity(-m_gravity * up.normalized()); + return; + } + + setUpVector(up); +} + +void btKinematicCharacterController::setUpVector(const btVector3& up) +{ + if (m_up == up) + return; + + btVector3 u = m_up; + + if (up.length2() > 0) + m_up = up.normalized(); + else + m_up = btVector3(0.0, 0.0, 0.0); + + if (!m_ghostObject) return; + btQuaternion rot = getRotation(m_up, u); + + //set orientation with new up + btTransform xform; + xform = m_ghostObject->getWorldTransform(); + btQuaternion orn = rot.inverse() * xform.getRotation(); + xform.setRotation(orn); + m_ghostObject->setWorldTransform(xform); +} + +btQuaternion btKinematicCharacterController::getRotation(btVector3& v0, btVector3& v1) const +{ + if (v0.length2() == 0.0f || v1.length2() == 0.0f) + { + btQuaternion q; + return q; + } + + return shortestArcQuatNormalize2(v0, v1); +} + diff --git a/src/BulletDynamics/Character/btKinematicCharacterController.h b/src/BulletDynamics/Character/btKinematicCharacterController.h index add6f30a6..3d677e647 100644 --- a/src/BulletDynamics/Character/btKinematicCharacterController.h +++ b/src/BulletDynamics/Character/btKinematicCharacterController.h @@ -43,10 +43,12 @@ protected: btPairCachingGhostObject* m_ghostObject; btConvexShape* m_convexShape;//is also in m_ghostObject, but it needs to be convex, so we store it here to avoid upcast + btScalar m_maxPenetrationDepth; btScalar m_verticalVelocity; btScalar m_verticalOffset; btScalar m_fallSpeed; btScalar m_jumpSpeed; + btScalar m_SetjumpSpeed; btScalar m_maxJumpHeight; btScalar m_maxSlopeRadians; // Slope angle that is set (used for returning the exact value) btScalar m_maxSlopeCosine; // Cosine equivalent of m_maxSlopeRadians (calculated once when set, for optimization) @@ -61,24 +63,34 @@ protected: ///this is the desired walk direction, set by the user btVector3 m_walkDirection; btVector3 m_normalizedDirection; + btVector3 m_AngVel; + + btVector3 m_jumpPosition; //some internal variables btVector3 m_currentPosition; btScalar m_currentStepOffset; btVector3 m_targetPosition; + btQuaternion m_currentOrientation; + btQuaternion m_targetOrientation; + ///keep track of the contact manifolds btManifoldArray m_manifoldArray; bool m_touchingContact; btVector3 m_touchingNormal; + btScalar m_linearDamping; + btScalar m_angularDamping; + bool m_wasOnGround; bool m_wasJumping; bool m_useGhostObjectSweepTest; bool m_useWalkDirection; btScalar m_velocityTimeInterval; - int m_upAxis; + btVector3 m_up; + btVector3 m_jumpAxis; static btVector3* getUpAxisDirections(); bool m_interpolateUp; @@ -94,11 +106,18 @@ protected: void updateTargetPositionBasedOnCollision (const btVector3& hit_normal, btScalar tangentMag = btScalar(0.0), btScalar normalMag = btScalar(1.0)); void stepForwardAndStrafe (btCollisionWorld* collisionWorld, const btVector3& walkMove); void stepDown (btCollisionWorld* collisionWorld, btScalar dt); + + virtual bool needsCollision(const btCollisionObject* body0, const btCollisionObject* body1); + + void setUpVector(const btVector3& up); + + btQuaternion getRotation(btVector3& v0, btVector3& v1) const; + public: BT_DECLARE_ALIGNED_ALLOCATOR(); - btKinematicCharacterController (btPairCachingGhostObject* ghostObject,btConvexShape* convexShape,btScalar stepHeight, int upAxis = 1); + btKinematicCharacterController (btPairCachingGhostObject* ghostObject,btConvexShape* convexShape,btScalar stepHeight, const btVector3& up = btVector3(1.0,0.0,0.0)); ~btKinematicCharacterController (); @@ -112,14 +131,9 @@ public: ///btActionInterface interface void debugDraw(btIDebugDraw* debugDrawer); - void setUpAxis (int axis) - { - if (axis < 0) - axis = 0; - if (axis > 2) - axis = 2; - m_upAxis = axis; - } + void setUp(const btVector3& up); + + const btVector3& getUp() { return m_up; } /// This should probably be called setPositionIncrementPerSimulatorStep. /// This is neither a direction nor a velocity, but the amount to @@ -136,27 +150,47 @@ public: virtual void setVelocityForTimeInterval(const btVector3& velocity, btScalar timeInterval); + virtual void setAngularVelocity(const btVector3& velocity); + virtual const btVector3& getAngularVelocity() const; + + virtual void setLinearVelocity(const btVector3& velocity); + virtual btVector3 getLinearVelocity() const; + + void setLinearDamping(btScalar d) { m_linearDamping = btClamped(d, (btScalar)btScalar(0.0), (btScalar)btScalar(1.0)); } + btScalar getLinearDamping() const { return m_linearDamping; } + void setAngularDamping(btScalar d) { m_angularDamping = btClamped(d, (btScalar)btScalar(0.0), (btScalar)btScalar(1.0)); } + btScalar getAngularDamping() const { return m_angularDamping; } + void reset ( btCollisionWorld* collisionWorld ); void warp (const btVector3& origin); void preStep ( btCollisionWorld* collisionWorld); void playerStep ( btCollisionWorld* collisionWorld, btScalar dt); + void setStepHeight(btScalar h); + btScalar getStepHeight() const { return m_stepHeight; } void setFallSpeed (btScalar fallSpeed); + btScalar getFallSpeed() const { return m_fallSpeed; } void setJumpSpeed (btScalar jumpSpeed); + btScalar getJumpSpeed() const { return m_jumpSpeed; } void setMaxJumpHeight (btScalar maxJumpHeight); bool canJump () const; - void jump (); + void jump(const btVector3& v = btVector3()); - void setGravity(btScalar gravity); - btScalar getGravity() const; + void applyImpulse(const btVector3& v) { jump(v); } + + void setGravity(const btVector3& gravity); + btVector3 getGravity() const; /// The max slope determines the maximum angle that the controller can walk up. /// The slope angle is measured in radians. void setMaxSlope(btScalar slopeRadians); btScalar getMaxSlope() const; + void setMaxPenetrationDepth(btScalar d); + btScalar getMaxPenetrationDepth() const; + btPairCachingGhostObject* getGhostObject(); void setUseGhostSweepTest(bool useGhostObjectSweepTest) { From a7a9182953a5524c3ec49b6a96058583b9b8b0ef Mon Sep 17 00:00:00 2001 From: Mat Kelcey Date: Thu, 28 Jul 2016 16:47:05 -0700 Subject: [PATCH 113/115] fix warning: extra tokens at end of #endif directive --- examples/ThirdPartyLibs/BussIK/MatrixRmn.h | 2 +- examples/ThirdPartyLibs/BussIK/VectorRn.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/ThirdPartyLibs/BussIK/MatrixRmn.h b/examples/ThirdPartyLibs/BussIK/MatrixRmn.h index 544dd921e..1d3eda690 100644 --- a/examples/ThirdPartyLibs/BussIK/MatrixRmn.h +++ b/examples/ThirdPartyLibs/BussIK/MatrixRmn.h @@ -399,4 +399,4 @@ inline void MatrixRmn::AddArrayScale( long length, const double* from, long from -#endif MATRIX_RMN_H \ No newline at end of file +#endif //MATRIX_RMN_H diff --git a/examples/ThirdPartyLibs/BussIK/VectorRn.h b/examples/ThirdPartyLibs/BussIK/VectorRn.h index 8357f9997..99bd67da5 100644 --- a/examples/ThirdPartyLibs/BussIK/VectorRn.h +++ b/examples/ThirdPartyLibs/BussIK/VectorRn.h @@ -235,4 +235,4 @@ inline double Dot( const VectorRn& u, const VectorRn& v ) return res; } -#endif VECTOR_RN_H \ No newline at end of file +#endif //VECTOR_RN_H From 72e329962ec94dec0e6ee324a157f31073195fcd Mon Sep 17 00:00:00 2001 From: erwin coumans Date: Thu, 28 Jul 2016 18:06:03 -0700 Subject: [PATCH 114/115] fix ffmpeg mp4 generation under Windows as well. remove static variables, make them local, to avoid multithreading issues. --- examples/OpenGLWindow/SimpleOpenGL3App.cpp | 7 +++- .../Featherstone/btMultiBody.cpp | 42 +++++++++---------- 2 files changed, 26 insertions(+), 23 deletions(-) diff --git a/examples/OpenGLWindow/SimpleOpenGL3App.cpp b/examples/OpenGLWindow/SimpleOpenGL3App.cpp index 7cfc75652..25d283119 100644 --- a/examples/OpenGLWindow/SimpleOpenGL3App.cpp +++ b/examples/OpenGLWindow/SimpleOpenGL3App.cpp @@ -776,8 +776,11 @@ void SimpleOpenGL3App::dumpFramesToVideo(const char* mp4FileName) char cmd[8192]; #ifdef _WIN32 - sprintf(cmd, "ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - " - "-y -crf 0 -b:v 1500000 -an -vcodec h264 -vf vflip %s", width, height, mp4FileName); + sprintf(cmd, "ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - " + "-threads 0 -y -b 50000k -t 20 -c:v libx264 -preset slow -crf 22 -an -pix_fmt yuv420p -vf vflip %s", width, height, mp4FileName); + + //sprintf(cmd, "ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - " + // "-y -crf 0 -b:v 1500000 -an -vcodec h264 -vf vflip %s", width, height, mp4FileName); #else sprintf(cmd, "ffmpeg -r 60 -f rawvideo -pix_fmt rgba -s %dx%d -i - " diff --git a/src/BulletDynamics/Featherstone/btMultiBody.cpp b/src/BulletDynamics/Featherstone/btMultiBody.cpp index c683a179e..d56f1db14 100644 --- a/src/BulletDynamics/Featherstone/btMultiBody.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBody.cpp @@ -299,7 +299,7 @@ void btMultiBody::setupPlanar(int i, m_links[i].m_eVector = parentComToThisComOffset; // - static btVector3 vecNonParallelToRotAxis(1, 0, 0); + btVector3 vecNonParallelToRotAxis(1, 0, 0); if(rotationAxis.normalized().dot(vecNonParallelToRotAxis) > 0.999) vecNonParallelToRotAxis.setValue(0, 1, 0); // @@ -714,15 +714,15 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar btScalar * Y = &scratch_r[0]; // //aux variables - static btSpatialMotionVector spatJointVel; //spatial velocity due to the joint motion (i.e. without predecessors' influence) - static btScalar D[36]; //"D" matrix; it's dofxdof for each body so asingle 6x6 D matrix will do - static btScalar invD_times_Y[6]; //D^{-1} * Y [dofxdof x dofx1 = dofx1] <=> D^{-1} * u; better moved to buffers since it is recalced in calcAccelerationDeltasMultiDof; num_dof of btScalar would cover all bodies - static btSpatialMotionVector result; //holds results of the SolveImatrix op; it is a spatial motion vector (accel) - static btScalar Y_minus_hT_a[6]; //Y - h^{T} * a; it's dofx1 for each body so a single 6x1 temp is enough - static btSpatialForceVector spatForceVecTemps[6]; //6 temporary spatial force vectors - static btSpatialTransformationMatrix fromParent; //spatial transform from parent to child - static btSymmetricSpatialDyad dyadTemp; //inertia matrix temp - static btSpatialTransformationMatrix fromWorld; + btSpatialMotionVector spatJointVel; //spatial velocity due to the joint motion (i.e. without predecessors' influence) + btScalar D[36]; //"D" matrix; it's dofxdof for each body so asingle 6x6 D matrix will do + btScalar invD_times_Y[6]; //D^{-1} * Y [dofxdof x dofx1 = dofx1] <=> D^{-1} * u; better moved to buffers since it is recalced in calcAccelerationDeltasMultiDof; num_dof of btScalar would cover all bodies + btSpatialMotionVector result; //holds results of the SolveImatrix op; it is a spatial motion vector (accel) + btScalar Y_minus_hT_a[6]; //Y - h^{T} * a; it's dofx1 for each body so a single 6x1 temp is enough + btSpatialForceVector spatForceVecTemps[6]; //6 temporary spatial force vectors + btSpatialTransformationMatrix fromParent; //spatial transform from parent to child + btSymmetricSpatialDyad dyadTemp; //inertia matrix temp + btSpatialTransformationMatrix fromWorld; fromWorld.m_trnVec.setZero(); ///////////////// @@ -919,8 +919,8 @@ void btMultiBody::computeAccelerationsArticulatedBodyAlgorithmMultiDof(btScalar case btMultibodyLink::eSpherical: case btMultibodyLink::ePlanar: { - static btMatrix3x3 D3x3; D3x3.setValue(D[0], D[1], D[2], D[3], D[4], D[5], D[6], D[7], D[8]); - static btMatrix3x3 invD3x3; invD3x3 = D3x3.inverse(); + btMatrix3x3 D3x3; D3x3.setValue(D[0], D[1], D[2], D[3], D[4], D[5], D[6], D[7], D[8]); + btMatrix3x3 invD3x3; invD3x3 = D3x3.inverse(); //unroll the loop? for(int row = 0; row < 3; ++row) @@ -1323,11 +1323,11 @@ void btMultiBody::calcAccelerationDeltasMultiDof(const btScalar *force, btScalar btScalar * Y = r_ptr; //////////////// //aux variables - static btScalar invD_times_Y[6]; //D^{-1} * Y [dofxdof x dofx1 = dofx1] <=> D^{-1} * u; better moved to buffers since it is recalced in calcAccelerationDeltasMultiDof; num_dof of btScalar would cover all bodies - static btSpatialMotionVector result; //holds results of the SolveImatrix op; it is a spatial motion vector (accel) - static btScalar Y_minus_hT_a[6]; //Y - h^{T} * a; it's dofx1 for each body so a single 6x1 temp is enough - static btSpatialForceVector spatForceVecTemps[6]; //6 temporary spatial force vectors - static btSpatialTransformationMatrix fromParent; + btScalar invD_times_Y[6]; //D^{-1} * Y [dofxdof x dofx1 = dofx1] <=> D^{-1} * u; better moved to buffers since it is recalced in calcAccelerationDeltasMultiDof; num_dof of btScalar would cover all bodies + btSpatialMotionVector result; //holds results of the SolveImatrix op; it is a spatial motion vector (accel) + btScalar Y_minus_hT_a[6]; //Y - h^{T} * a; it's dofx1 for each body so a single 6x1 temp is enough + btSpatialForceVector spatForceVecTemps[6]; //6 temporary spatial force vectors + btSpatialTransformationMatrix fromParent; ///////////////// // First 'upward' loop. @@ -1522,8 +1522,8 @@ void btMultiBody::stepPositionsMultiDof(btScalar dt, btScalar *pq, btScalar *pqd btScalar *pBaseQuat = pq ? pq : m_baseQuat; btScalar *pBaseOmega = pqd ? pqd : &m_realBuf[0]; //note: the !pqd case assumes m_realBuf starts with base omega (should be wrapped for safety) // - static btQuaternion baseQuat; baseQuat.setValue(pBaseQuat[0], pBaseQuat[1], pBaseQuat[2], pBaseQuat[3]); - static btVector3 baseOmega; baseOmega.setValue(pBaseOmega[0], pBaseOmega[1], pBaseOmega[2]); + btQuaternion baseQuat; baseQuat.setValue(pBaseQuat[0], pBaseQuat[1], pBaseQuat[2], pBaseQuat[3]); + btVector3 baseOmega; baseOmega.setValue(pBaseOmega[0], pBaseOmega[1], pBaseOmega[2]); pQuatUpdateFun(baseOmega, baseQuat, true, dt); pBaseQuat[0] = baseQuat.x(); pBaseQuat[1] = baseQuat.y(); @@ -1557,8 +1557,8 @@ void btMultiBody::stepPositionsMultiDof(btScalar dt, btScalar *pq, btScalar *pqd } case btMultibodyLink::eSpherical: { - static btVector3 jointVel; jointVel.setValue(pJointVel[0], pJointVel[1], pJointVel[2]); - static btQuaternion jointOri; jointOri.setValue(pJointPos[0], pJointPos[1], pJointPos[2], pJointPos[3]); + btVector3 jointVel; jointVel.setValue(pJointVel[0], pJointVel[1], pJointVel[2]); + btQuaternion jointOri; jointOri.setValue(pJointPos[0], pJointPos[1], pJointPos[2], pJointPos[3]); pQuatUpdateFun(jointVel, jointOri, false, dt); pJointPos[0] = jointOri.x(); pJointPos[1] = jointOri.y(); pJointPos[2] = jointOri.z(); pJointPos[3] = jointOri.w(); break; From 80dfec170b5d28885f2841629a22aa7b04f42379 Mon Sep 17 00:00:00 2001 From: Mat Kelcey Date: Fri, 29 Jul 2016 14:43:55 -0700 Subject: [PATCH 115/115] fix setidentity bug --- examples/ThirdPartyLibs/BussIK/LinearR4.h | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/examples/ThirdPartyLibs/BussIK/LinearR4.h b/examples/ThirdPartyLibs/BussIK/LinearR4.h index 51f57a666..b0c542249 100644 --- a/examples/ThirdPartyLibs/BussIK/LinearR4.h +++ b/examples/ThirdPartyLibs/BussIK/LinearR4.h @@ -580,8 +580,11 @@ inline Matrix4x4::Matrix4x4 ( const Matrix4x4& A) inline void Matrix4x4::SetIdentity ( ) { - m11 = m22 = m33 = m44 = 1.0; - m12 = m13 = m14 = m21 = m23 = m24 = m13 = m23 = m41= m42 = m43 = 0.0; + m12 = m13 = m14 = + m21 = m23 = m24 = + m31 = m32 = m34 = + m41 = m42 = m43 = 0.0; + m11 = m22 = m33 = m44 = 1.0; } inline void Matrix4x4::Set( const VectorR4& u, const VectorR4& v,

    3. @yvERNBf>; z`IP)+2(&BA!WN@xJ#XE#+vUk;mbhHdT=aWZ75m3w{RMx0!e7lQu4L95-B0D^uVxij zFYCu&${qFj*z{C$QVR1))50c3`tQxAD%L-&fBPi07k`NxR_kvR}en+dxIL zqS@4+HxKE(7fZYPyV^5*R>nN$ty=|L3e0LYFN^x|@gcqMIce=#L(|cPQ_0Qq=b8Ts z5mdZ6nnfK?eMpbWEZ4k*Cq0Fpcx~j!QrxA$tmKQbs1bkuqTjDBirKkrwfm1oX6rR+ zO#Vhtab>YS=i5|X{^C<{Wx0OrUMer%^L!l3JK94ERyP|}|Iow;D)3CROTn99`@0>D z%+O~kT?)){_a!G%eQ6JQT*Z9(Rgj4hRJgCl^iGrPmRIYW$5&}C1!lQNwa!cT*?X#b z&635_nHWI@o^|$ssCw1j!>rT+_tLl&nB^X$HvJSx+b3o)YrY6JF@g&B^%(jzGhOI= z-)J?pxJ!XqIHGFW57P=5BYJl*KiquQz$=K?hQA|K{I!j~uava*javsA7q)dVk2F|o zU<4I7GB9uZ{63??rMBkYEMr^>%wmTE#b0;mnM=qvUSGU!EGpl|%(yqwzz8aEgyXw* zOE$AakGf{DTbsS8z%2jDw(hLZPkK|3DyEDw%e`6Wnp0yR>>kgP-AqSUN7gi3jhtd& z1Qpm5v5)ZFqqe@kiTU8}_bvryVe8@VQddv5fBCMPIezX810ya4^ubI-m{`(InAz1l zQct-Q*ze+9z~6J8>aUV7j5DWKpJ!kM71-zVtnXBicS?&mbL!cJE(K=c%s|tEGqg2M zPU>&g3(xPG0ifdl%w&#|F>q*ib5qBqUi>Z0!ubk+M_)Y`o%lMNSs`0m^H!ByYI(9V z`asgWX&>ZNnOmIJpS4QnWv2zj-`nb4TPNdo6_hs(RkKr@!xt4c8{PU)^=f)lf0WJL zpJOkfX(45w*j+9ZG5b}|YT|F zRpE60afrDt`)=1ZP_epkUUfG6dA(kf2fU5#$%;_F8U@UrGtambn1y@DUvo?^MO!_* z=F?$_!M+lT-6C|M22M-Jug0~zq&LiaQOCXIs<~`2w6a1Gvvl#q}trdobMU!QeYN)0Vw|3 zU-y0`9K~Gy@|hV!YnVGS&GWMRjN&ht^^io(EAP1ZJ*_V9x#jIHzrWR;H@t_MlCi8; zcQbdJ^<21+xDS>5md0VgJSOnecUP8#)wlBRQjhw z%*Rv0Tnfx$UkJrtuq&CH&@rMY~(p=&pq{l0;cEBs^)?NTaw;R`$jLk=C09ByH_)n`A6MGX4esgT_Yzdu=Qvf zdovhk_Ov#ivOfd<7G~i%&(9wrUm3+xbTNx=T<99lQNa!#ioF!{DIwDDPW(8+2yNcU zOn&K*OMzK9`(Wqcn%}4z1)G@xfhk=xOH|;Tk-sb+|I+Spls%n3Xk@UTi(+3FJ^Ra( zI=jIr_IuGQ^55>h#UYXDVy+n!nV%z{RsYs5hXo&`-~9}7F?MSFAglk*1t z7G_~P)-?9YFy^)DWlm$i42+-xuO_$l?&FOwHuW?wB_HfkU>3GxCXM$_Zhjir%shTG zm4OjdxcjShlk%8VU(_^HmFnk31!lSL4|cw=*#W~WSf{LkJpf*R>|@yfs^cbmU8OE& zy~2H5Jp(G-t%Tix>`!j@GB=0JbSW?k&moVs2bbII3S?G~-{Lw~sBn+9>?>lMfz3^C zg9|PNX5p39v<3@OQKREAW}^mAUDq5H?is-8guHa~r|jlO$y2!66=vZqidXKc^`<(H zzO#iO$qs^wUH5e1*Rt!ZV*fr}=;GhK4p-N^e6KqM$rbAw)7{N!NNAfGW{0WJXDfA~ zZAvBGQvNbY-m6LV9M{U}e%j{Z#?8tLpOZ4u470UfgX>yVgFkKVsS@ zMo_`5BE{aU`mw$;zgis7kskCoVhe2(6_~}YbYTuHLv2u2rBUU^V}y_2l`^?pZ5H0>0AoT!ZV_2 zA4d+Nl0&W}3Oh4HuHtIx#Lc>}Gw(+hQ{88-*M*%qHBE8#)el>Ahn=~tMm)V-x7@pr z*_jwY#id-uRH?)by2E{KRHHLp%(~MMb|yQ5Ds~3-%`EL|5vuI-ZMv{CuOALq=M%T; z4m-1P#h!FL-Iqo>W@lmq6}WAFqR-f#qBm|gYIUFPQef616|QDZ<$GoEHNJvHf2vPQ zp3XCbojHACn3@~9S{HVvsfVe!G;4HWXO`SuL>;}qPIuUuOGb32*jyDn!pyh$|F1sBr&zPDKbYf2U-8Kc`9$nx=_{e z^KW!rm%e0f`ug-LzPcgoOjKYNo^^IfGip-kCo_x!%+ACJD)R3rtP0uR>JB?|ce*;X zxad4X*qNxnENo-k5-&ERSq0V@LQ>Wi6jkxLHtIrBesH>|YP)fxE+l359ku;U3wm&Q zm2ox0J_94D*ybswdVIf0H~$ca@%V0CX!?%{M)5bRT?)*?E6Y8@(YEwD*(T%o&ZVwv zj*8!{aJ6LeR^8!q2HkE)E&FUYgwKh;g<0-~^ZxoSV|i zv|J{g^Eoks3inJV45jnAKRgD~;^7%@#hV ztL?%p>{RlCDs8p-y2Iz3wl|#iUY%&C zYe~HB(76T%_n`YdmEq%a&J0m+MvT+fEl=x5nxv7NqxH{We5>b!x2c@HtCP zYG=R5G{{U*eu6jf$8c4#aBscpy_8;m)st^#$wYR=96$d&vG1js_TUonX79mn1!nzn zq^SDor@p$w&b)fR0L`jf%}1O%^stcnWyTP_e9d&;>LFn&ru9JmP|LL5^VP%D%c28x zhXK02V>}z__jtX1 zc~LwrR-1|(%4L>h66U2vp=#W=k@`LMKPvZisLIf0q%IuIuR}xCke?IuK0Xp=x@>hQ zbHj{2o)<gH@SlGxRy@JDx5)~lhE@9VU75YskMfmyc$L)3)rU+E5QvkT9C zDqi>6Lfga$D#msTQH9&h)>SjP=BbYlpp`+5?e7k!H!y+<_dPhaMqkP_=WAPNo2bC7 zpj{#A!GXEDL))xZzb9>)_Jb|7O^l#o{L>Ki*YJ7zuIEw*Fn!f$bbMT*EwoLHpaP%5 zcxh=F!RA3f9>9NE3j87Yvp5EGu?i|Qw2yGJ; zm~~`Huo~HRitf-hPxJ~VbKqp-hi_xe-*X46ud__kg|>M%N3iO5l#iV`plNB^5Hi{jb|xw?3$G?WZO^Gj#eP3z zY)$sU=sGS$o!ic%%$N*b?BTA)hpJiWM(7ShdQGxe$~X9Tqt&4_CPq-<9@X-6EkqL< zjb&PTS###&g6dA(2wiBKE3$>C2C2vDLfdRrFGRJPG*)+LnZQh+t|d&2pyIcvLh9D^!TM);q+ay!pb}K3@pdEEkr0;x zv+x`;`z&iX{nTQKF-#SAon2J)xDcv(ogJbJ>s!;V+zF#c%V!%$wnw`Zn6<1%sCpGP zTo)p^rZxXPE48j)+)Q|K)0kE3wY3r1Xz|g?KC&D}P=VXiv=vl{zWK0(k1U4@%$n9J zOquEW>q05jwCh=lQ2CqLePmLMpaRc=rp^4K1pTpUnIRO{%43SD8E3oeLT<$wpj)xG zQV9xtx!ZVfEx(BoRA75!8q}#0v_B-7kFbgg%)-58|J{VLltysBIZUWreg#ZI2+{k-M<=Bqk=2ELO;ck6Q4}6ujESE44=}6gMLjE`YA?GfzP=7 zPB^SR9iH;aO2PC~RA82CgwqNf?LtSIr?5{j{S+gpz$b4_OW&{?P2FwS`+nZ)QeYN7 z74tjD33=$vm3-z6rk~<{er;fcVv?(GRSjDYljYVFrgIenee_d|pd!uq2*ngx|Ek)} zVG%TM^GPH9C%Ij17qjp#;2QeBi_@mw=ZrZ_Kg9?t3i39X_w8SYTe&!fVjh2I2>lcl zn04**2(@liSKXnX9;sJ`%4b?<2>lczs7SpjLNPnsx0a=8<#vWr&A@3!KCWHD-V(gLyZcBi@N4Ms5p=(Sp7YJitf-)Hw-IJ zSyBu(s-G+9QeYO&gLw7)uixz{BRiR%FD84jZ^!3M?6ozmVx|3dz_Bi7_+M!ZjGzLa zSoxjTr_b!HFB+P|woY^@FbjKaO&d4lf?ejv7Ur^<6Ag@@qV|>IipiM%Hzpsxx@phc z+1TvI6jxMWmU~otJf$1O_Wi;ZJ}2ItxPpN9zou1A){|C`8ESvbd`^s@0-r22ZIh=L z#rNN$mW#6{7kU^i%`GkkW?`FV=lVTei6UnjmF|4$n!Ta|pQCvN z@{cC8?a*Q49`iZzw=fIGD|XLUzKP<9W$6LeEH!5SVAokC)Yg!$x{wL6kHWr--`$;UV}~snWd6cL&qAqU)d8!EE=13t z*b|AJfOPq8`!)LqH7?UtFYogZD%!k_y>#Uu^E4AZG2;IY&iC#Pe~ByNpD(ZB{Z(h(A$o4ew%>mF8#9ZU=!pu<`ZS$K-I&_h_gS2EEv z?rv$7qh&W;h@R!xk%>K*bon0qHG4bV-rY@4^nFb}@z<92@gD~HXq%XY>fP)ab?j7k zUA`0NFBHC-)J>~y6& zUz2yy!l~2t^yVO@BCeeiqpH^IstfTFM>QNpndenJl#UlJXpUzpB1S%_5u-Ad_)HID zjwb#RkLP6g*QeNFE)?OFdX8zZ)s?dz~y3jVQOR?(PB^`B#wmG0t zTiRKBmm#!GjG&^cdDIkSDbll`i6W-S0c-!erh3YZ5`JimruAtJ4oU z>JDwQ>&oi%*ZEt9&^A$lS$KExcXz#NQ|DHeA+$}5prX4`Qf>L8lkU(q*QKvXm)31D zgtmza%)gq-pyD zlTpL)7Czc0Mo@v<=GF5L)6(Y!8u)0NsK6}jQJE%qtptU|Mf+%*7(oTLP_8zt@1gjh zd_LMHDliM%f~F0A(2!bPzGKv5+9pO&;qKwOm2E+7OYSs;wuuVN!ZxjGt8WES(}Mgp z2XlCFjKZf$9DSJFyX>WX;(C2^@Z;GAMo@vh60;!YB&YF#4ScjsRA3gK5lz$ET(|eG z`P6*Ov`vhl0>^fC`R{$(Ub*m7A8ivAn1xrC>%z~>vqLMz`DmLML4|u>vi;+>_Rcwj ze6&qeU>45KxW0YVU#i69VLsaCrfJ_39Md*2f{MTA7-~oG zGmlfPo~L9gd&9V4KH4TKFze!BubR!@#!*ro-ZqHI$O)D3m3vILL%Cai9a)2(h&A?^l)QqQ^|ND=C zOARSLWj%c>(>5`Jih{GtsjsR9=nic&Hn=(cymyp7h-sUsz^pMPJ?d_~0NtT&CJP-v zws~0>b|&s`p3N22o}K}|(GrhO(}s>7NclQlQYE>n7$c~N`?jL`Fl#b@9diE^9q8<} zpKW1hq5`u{)-hH57q2`{)qPs7FWHrLuPy9MjG&?&Z(~A+WKN~DHsWu)#S;1-?uQ?x^_1@{qQd(>`YW(7Pe4L8`Yr`T}`u67j`B_P_d+huKIowpgZi$ z@7qC*ZI&-=sS8I1W{qA|QZ=zO-&d5Hwx*Jo<}N;JOIKv z)U9Sk%Fpb~kct)6_-U^^@_odwMn%6?RvwD9j!|Y5{V3xc08JA*$ zJ*`cD5_Tp=P!X3$h5SG^0Xs1HLc?B4KRWVY?Yd}r&>K4QRskeaD6)}FbnTT zUgd1kn)3B}tc0D35mdPQ-Ew_8(7359^}Ni^LGvw1l16 zG&D-J|Kv}Purq%u5Tz=$x#kg1pV4We)VlN6JdRsWndK1_oFW+sEe-D+yrX`v7Nbso z_R8ZhCl7S@QkL-v_9$kbVZV#&zMW#!zyX@>FehJSG$?=D@9o*lSHlP@+}mhfxhfUd zKG#0ZTuW47*0iW-^|0@2&)(mqdgox9nv{R|c3aq)7(vB#Pqcbj^0~+1bJm1t7(qp==27ZF{s$h1Gdkm&@)Y;F1PN_( z(!3}&qryFp&^BKsW0$m$M;@VVp7=3JnFsHC9NK2O$0g{i zJPvKM=EP5_*!`!r&^B=!0WG4`l#PFRgtj@VOO%TF>8{72Z4SQQg^qVPW(#c-BdFL} zKT2h8@R!G-Z8p5qor-L?ZJ}+V0<#WPjZ$5c-S#-N&26DUl=7eYB(zQ3Up$WDqoUQV zQ;$3jZS&k~jZ)WXNi~_ai4j!Pw4zldo>M!t&Cg<#-F!n2651vzFzYODV|z$|>;;kWuN_SzqJXh%ZZ#5)zo4;+d3 zTe6Ugww1gY32hUzP>o}vrlmNOmM$)+NFG+gSQ6SMDliN0d1gpI zY(bZIy|RV2iPyY<6{X65_|PM?O>A%cruy1PH1t_k`gKtj10$$#_g7!0sXzmt6egi< zq5`w<`fJ*)hzROql%aU0ZDIr!coyV)=OD^Ape~=?d@coM;q~Xr{yFFEWz$|Prnx>|fBX71--fB$S>=PfU0;2x(h)detfstx!=q-=X zHamPDse<=i_c*l8ji;(m=)4Zzi%i?Z2r95wVm9FOrgXDqesAK4R4xT(ow*mOKJ9Sb z)73}YT$!>hJt_RDIyCm7fe}==d$>KVy3(uEJFFJPj=L0?wewM=y4C8s$8lmy=-r!s z2@X^znbwRERJg~eVyVkh&4S~-!nMSswH`#O3%Q?qglma=$ZJb~m#4gyCVPczi4jz6 zeif-!7Ydl8p@hZ!ME0oRV@tv z{L>flA5)^tKk=8iBIQOe8h5a;>JzuowGCAGdyGV7dn%#zFPLtNtXh%{Ku5& z^l;nj4W;rIla=3GGQwEF`@V5VJI`767i`Rb|8aTZmhaeQvC3bODlli|Ed|*>mA@uW zHk8_TS+Z?aWGMq9sQ8%GnM+OIKGE`3_K%9AMg59de_UDUQec+*$Op9>O81+_SjX~* zyN&}DvbQs*bxKV1Ro$Q7K9q{yEoY569pX}87G4{EH&JB-t=vIRuZ@Jg%<;J#iwM107TS*$eg2DR=d*|~N#I}oB*yr;%SbPQh z<*x7jg|8q+P=T#d(+<@xPxsbX-qQa>n0vZKs-4qTd)o6C6*!7wo96F|Zg{Ccmpxlo zuL(ELHIGz#OE20|KPIDB{;rez@0jZRH(pt8iMt!pi@rtmZ<=HY)CO5r(Ja&_do{U9rf>B+oGIFSMqqgO%F3e8t!LQWNF7l%$P2obsMF%f6?+InwPDocV_>b zE(K<}&+fhkWhr#T6z_Kjqg}HMRQ%p4QoYJB-E*XxY~$3U@|36CB5$kR5iSL0;g!|2 z0xK%g@wP+NvyFw#U7aJ<`g?N|A997V98*$HG?3du?7-EDTT{w5BBnN>o_l*Lvu2=) z5mdN)hKh?TQ{|ZT>d~5lE(K=!+gPH^)Yy&0s6ZEg{7hBuQpB}asrYDne>OF-PapRl zYTCScCe?1*K*dyXu1C_oyA7ZoYF<@fg7+x~e4@k9RdmX{h;4N5HeZMaK;S$N;@mq^|7Qqby} zW`i7%>R5*diN+H4f#m1&!}lI0#@v+eSoY+Iq=*US%`x$r zTv@1YM^Wk<>waPcyGU}SQ*a6@bKh%@U41s`sVGs_6a6!eL|GBsel$j<*#9bVMtj*t z`KSVR_tQhnGHW+`{m*2H^47{f3s00cN@q_;tF_&pBx>DdJ+c3)xwaPD+q^tA(!dBR zqT0l$yS<+!7Pupd%)eBjW;0Wmw;C&>TlE;#zvrt&l{e5^Qjb<6N zMp`=jQ&scT@Z~NAW}VN$UD@xk^O zbI7%YE(K<-9~Z5%d7mc!*g>vfuMf)7@1F;o#~RNwFoFvAxl*lC(hquL^LnZLE=A8_ z(W>8Pj}t4hV=L}06VneJvo|g8VvcV2wJU;(&v^}CGo$+ZvYwv#`Cf zFK4fo)a}9x<6cyd(U4bbvhTZ_SdP6)n|Fv(!|6`q`0Qz2cN)J%9#M%_Jip;JuM|w0 zw_D<@>7T1x;;b3eIYt#3q*=f8lCxqI zW5kFlN%Iol{1X+0c;zm(;Df|pevrM&(X%&g{42Frv9}@q7G~irlfO{dIEcQ@)z}#M z=hUS6m2bYgy>ygHOm!>q0{h6~_PDB;--Q3zZMku{_#{^Z6-}x|sYTCjB^K~`%6`G$ z@ID#4-3a^ogiC>0*kagUG`bu0$$Z$z`7*VuEuo^@r%`Hr+rJXS*ddr#qmDGCLYGsT zGe=H$DKHCrZFcOA0C{---exmL35w1439AzmOZBF|>lS_eF z?$ID%QUsN1eMj{@6Kj@Nk?KX(M~Nlb0~<%=%+Dj$+RaZAv-mu)Q%$czf4x4S#-t1} zF@g#l+xaVq$Mq=T&`0XRk6B#`%z9ZON@dvmC^02Fc57PizuQu9=wqv2`uj<%AHL@d zY#DAvi;-<eBui8O>=2VhxO-!re+b9w<%6o<^9JR_iVW zX5lEow3GAsY31drTvdF{ixE_~XBpkXlTqFhEzQ|A=D8G@g(CyMD@sv>>i0`&9$1;i z#F>Tv-Gn9nyErDY%YUcRRB!k`Lsj|E#0V<%4Z$WxP~q;|+n3j=aQ83O;3>sj3e3X0 znY}-+HKsfD8d&0CdLd`5imDc1iHGSLu3Pz{N`NIErv7)Hmg8Z1Ay-|RbM^xxo*hXs zf(ks-nzoZ_QM&?96UC7fBdAyqSX!+r8(=w(q-WYzrha9oBnEaZ zSY(YQj->v#ua-EHrv6%26B`9s;z+tW)T6T23$PqVQf+uoIy&)BuQ-zWD>*E2B)vJ> zRQuZpSmH>Ezr;_F^SjgUzwNQakrX4SXxH7Vv}OU8<4Afiqzg6Lv(6GnQdD3T?xCjr zlwlzK#_u4-kg{G?8A;5AR zN%L@})0{WwEpa481!mzf@p}6&sqDO?hMDo~NZRx#uhhULiX-WnEQXrTe~Tlj|NU^H zQ{$DfOiDZDm&43W>`00cRQM|(5}gW&y&sIVcaH1tb0kFtX8G$U5}hiGG{4+d<#`*4 z>`3Z=C!8o%dTn2qk=n6DaU}gjE9?8)aU>m`d9Q7r?&fnO#ozK*awJNH2yUC*Tb=q6 zpCc(oP~opNNpu`ZBd-O}uy2}}1KE)j6`19J6QAhRMqNG?N>$5LFt@WKDMnD?uZBr< z97$IJt+kN7BLfj;T#chne%) zkrba&@tWiFC)Zhi*V5iMyuZ(p6eFm>*2C*pPSuMERWH70PRzom$+uN6rc}LP1Qq`3 zltiaC>YNckqsLVAIg+9Rvv5RxTfO6RB*h3Sa1_x$pf&mGJIFkD7ODu6D^;ghY z;z)}3KYR8!=}S9~4l#aUM^cQS!e6mxIgX@KJ6NF8C9gP=q5`w9A9E_tR%Q9ZfXXx9 zNRRuDgx$h5uO_9%$6ng-?{@7!%gFxN( z^h5mvhB%U91QmE?ojS{=f2Q;~lA;2$@Ql2zvoxg65+kU<@zJT+8d`|I!2Y*l%hyL? z7G7CRtKYaaMf85`6-QExpu#-^*s`%X)u05cHan7{0<&;V#Qs;M+EL_TW!GlM#hb5U zRs4+hmN+Z!&t6__9@E|uC&!1^V%4NY9WBQ>vdy%{ls;dgEk1Xllgg+JRXSSYb64Va z8TCoFj+Xe`mDp28eI4D|a-1WBuQs;z%Y%F#rsJ>h8_>bsE%7i#(jPJdHEmd*#`g4^ zgJ>pum|`S}uO}X+_)9$BeKy6Od?1c$vWF=~P~rb#$Z|YPSCralXRiJk^ zt0c?uFuk1E%I>{-kk7-k@zc`kS(9#-c$gwt5LtxmY!ukap0H(*&yf_fP>p0kUWfZ? zo;|c)9El?-Mo>{JZLC_nql@J@#8w#6#{O;jAfF>CDliLKggn2xUWZCe%1q)MiPzTu zC6Xmxlm0JXEXO%As-Ksv&V?u|J4a&V+}Kz(y>Dkryhibtcn$eM3HE4=CUGRi2r5c_ zRz|H%*VPhtQsx`9^-$sL`Di~olA;2$-0f=emIm~ya2gWNOx$-=-{7yd8jkK@i94yL zd3UxTtIaJtJv)+O1Qpow`EB^&&a`8)ZI@!#Q&eD<|En$Etd_sw%~zWyWlOZhku+gR zjA~xBt0j)4>$bZrAtK%k~os?t{0=S6#L8)M^gV+ zFqSxy;x93mEOj^)x6+e1l41lE{x2#m$B}ek-4gWXRth@9j-;r-EdTeBmg7j8=1E4% zTCxHCIAx#L|4o!79-qbeE2?I-I$7f0iEWI(6K?eZm5OXZH&$)(VwV4FCrg};-HM1& zzuIx>I#XKqL&gXy{9jsG;*HGh>cv94TFE#n%5J)-z$|xbueWuPJ;)PB;--rcRJ`IZ ziwn)@Y>B@xdu*+3YoFu$yfHfuqXM(sM9-=7%2L%V8*K3~#k1)DrrHt@(@hIXsHOS4 zT8@WlhHPbNe1S{0c$lIBv+z2x15Nu%6xL(29n2o47(qqEjc9dZOlQmSFpVBjouS5}DliLMC4W)%Q3J|({)YW&{tX7+YuLBry~1lUb6V4d(#meQcctsDMa8<8u`1(N z?JdV&^hrQF>bp20#eYM126z?0p&oiW< z(N`)`D)tw}2rB$viCK=nXvOtipK?QD`sff#y({F(dNc=@nfmzr;@(Ro85SltQiauw5QH-Dh+k&R$ zELV!=G|EfjFNzAx!nVNQ>ffnO8Lr*5Q(P~on!R3ViT7s`ty^Yfen&z7{K~VkEnR4G&*;V8pQymBQ-6o3(E9T%$NTd{ z%Hfo%%?WSK!IQktjs~ll>Pst@y+7-J7@|Crzp}*pv&+k1)iQFX<#>M%PBVnMHS`#f z?EQ%mR0OpOQT;!gZ8_eb(X$3p#(iB4@%}^wW+i+UqRJ#ZRP4f?<+rOl?W7zxi zpPRud=)h!4ygxtvC0IR7JH-<3&wrT8{&DL`R&Ss8XU10jsn6;X_Lc9N8W=&vz@@?J zwlT$Wygz$Q97LCoMBC#1i3-e``i!?>PO=>D&u+__Q2nAQ=pZ|J?p+hAYE>I)iDT!Q z!lA0uy#!1AK7%%fs9T%HT8?|`H~HJq!@76uGwc?M5mfBH5Tfej9czgXEZ4)W=thk? z@3+Mv78RJKehyJRe;jLxTP!b3{7`}pEhtMH*vWHJgD|xv{QyfGJD(pdtg7xDXo=q^ z?yaVkiuKUr%@HJSp%_8Mg5IGjr2KPS~^M^aQ^79NwPHTE2_$9C&V zZP{h>_-{p3o8EmbansDvzo;7fTVG4OIF}SFraBJoV>xcRHQHRY_r-M}aq`3nD)O~1 zq9SYevmCe3ejNg-K-NYiZlS2aEIcEccKTdKny!69;z)`SR1_~7rUtzpU^yP9*-GW2 z+h5kEtn7M<3e3Xu#=Xy~!t`maKoUQ)&@YOq%DsD9;@*j~KKH10+$u`72PGpWpd@*6 z_-2r(#`y~S0gQ~GxZ5Y~y6pXl5mXePTul9Ryu0Oie;&IYLt_Ki+LhV+6BU?+Gbe6W zWAf16zw(i|q~ZQz--X-bFL*NLri2oODJ8q4VFVTK9`0b@BJ}6ifh7K-sKBfrx`e6m z3GtTWFB-G9D9!sMD~Z1-Mo_Vz6_4)rvmAfX&K1kjw%Q+%_=}Y_i^jxUAac77n{-Qrb7g8}_4Yp?G&fs+`=JX1sJ82W_OtoW8%<4b3 zu$o`8pCyi@#~XzyZ?ibdaU?xhtu#%zal|fsDT|4}g=*YeO$!}clxpQzW)J*2!o&zF z+}lVyJDl45x!V>;QdD3To^@U?$rVncc^l$LiV;*~zEV{EI;w}|IFe?YQ-ac2%WQEZ zMFnPI8{_#^=|*(2_BdM{Nv})^Q8bf#GIk`zem8ZSVCC&R#c~`;CwKdpe!bGr7DrNy zpkml8?%QK#S&q+kdUgwaeD4ce97$(n4_4;n$(A^hu6+}%I`tiEi6d$8CLwB7r?Hmf zNZLCll)8tHx5beZBd9nW6ryHFj=b|3r0u);0{X5l&Himjy)bY}V(+dLQPI=iU&E@!Zc&o|9-97(gZEKZ9n zj7Z*!TQKW2)3`h5BG(psSUj!tc@QUn8q=sVe<>jXmPoUle}} zv#?ET+9#E2(8LMR_H6bS#Rw|=?&khgwMOwCTK(}TTl_^)fmx%qP-W~}YB~O*pT--M zg~rr9$9uzMJpg-6@sFN%F1jy~8|@@(l;47K=ef-U}{7(oS&D_o7c zusVHkY>qAdqNu@SK6%))sWzq_-0Q|5uIjq>a-iaj+x z%VHnQ{nftD=;Zw!hWLwO1QqyH%#~*udeZy}Lk;m4MFnPIAIwLdwi|sLKi3d{QH-F% z@9OD)n=$FDZuF+o7e;^f7exhT;rPhgc%GadcB@X}3XCfSc&Fmrm!BXXYn1IoJ=z;H z+rS7a@Sf+MI)6?&Uow^!v%e@RFbikP{Py+hJd`ocOX4qz5meyQlBQK1Sc+!t%u8w5 zUlbLXg>8XX?pAoI#Xq@8{6#T>3Vasjr@J(Dsq^JWw)l&p0<*A9^Qv0f=JYK0CA$Lq zi(&*7_!Q30U%T4U9~l1VW{pf1Bnq-;PvMk;XSRWW$mYi_&}lpv+#^)+TFXo z=%c&2z5CgbwEeO$wd&<6OMFYyhZj@3#;>=;g>=VQCS>MVZHXJIrkz;WlhPJSP!|?$ zH86sTzp@omaqBi%jw9)VI}Pdgj~dzHFN%t^-Y``)-5N_gMRDBKv@CC`Qs>c=ZSfcV ze{6kqm=#C!^$>JfbkVRtV3B39;I?ynlHe8s!QCx53oIUj2Z!KpL4sS5>F!_w5@68) z!98fO;PO??%w5j>-tP~dXCJE0Oy8OAs+O8_(1M8Q)wyNo0n2P=*)@zz)xXg7Vn?Y4 z#J`IO^z!HPJ7?SImIZeyW+dJDMM1g!@~<{Cl5Qg<#CMan+001#ENMY`Wy4n6WhCvD zw5|TK%2vgUq-a4z&Xon^+J@U~mytAfPZK>R>sl2vaKG49C%-)TV3W;Ull#l%mvc94 zvLAPTZ2F&7m4624F3(5Hzlp=t(*tx)i}8MgGZmDtM{KcO4%4uE#HiBrhRj5KulUPx zwuDceP62W@(*+kSm$Afjixx!Se2#dwV>;;lb;|A(1 zgJ?kn&NvO@@n&Mjf0<2`nQr?K=!I)Ts~S&5We}UeYqIk&axlO!Xy3QnVmqpUfw- zTwiBjzVeDrU!Rt0sS{1?sF;xy5$J_|fw*^i)zOcJ%~8xqiWWrdnHVXrUHHXz8A+G5 z|60GeFjp}nDI(AdM=-^bas&0EeOblt#7OEX);Z_dqe;th-tWKK%t-3*?O**fNcUQ_ zJ+OlqNzsA`PZiTSS0~Q1v4iywyW`B#RYQFU^um!wF|lF~-Qzi_6||ciz+8ka#N0&; zm}UCvlMjZ7cIF*lRzn1~mUNdM_SNMcRuR_t5(2MYEmUHHYV=+5Q76KFvM z_D~vwRjwy56N`Vpi7g zeF*fzXJ{Bn=5^O8zMCzc5F;sC5P`X!Y6qM4)aIV)Lj9b}hd?iUvxf2Jx7PZf(Ram` zX0v_0#E0ftZ{`c$4cc)?~y(w}C2Dr2i(uw6#d`(v_N*WOii7)j9!(fw|P%L;d{*nI-5Q@y^4 zVJ%G9RG%kCQnVoA==`km$oZ?bTdm%%MYvU|V0DL)6cOlk{@-vJ`u2+LGLl|AT}Y=c zl}9rp>6=4YW!eN6Y-S{_elELgn(2zojHI64y7N^5>6n}=q9?VE)XYeV7DN>JC%ZgY z;)?AulAa7Js+&%T)CGx=6cOkZ`(JjMxYiZhWh5Q>IK6&prPa(xnxS(hxuD*0n;A*V zi%(^b=cjCDB=vOMy{|d;9m}j&1k&qYiIEg7h#2?Jr*cu1zigM0ba>8e`gWsCI+hqo z5rJOE_k_!d&(GN|BkAaj$#sn#$+WRDuhsBm2038ZF{k3UOwWw+W`{WETg!j%WR$HM z9J4p&;4eTk?Jllc?T*sSVT!-->sC3W%y!+)uPw66e+OOlp6=8m;rhk$@|x?A@mV3_ z_3qE)m*R$3xm@JbR@G}_2hAL&h(NDi!?MYQ>95&toqppHJ5>E)oiuZpq6HC8e)~*j z|Kf&ITWuI)Gi*}@OLo@GVTuU!IgDU zb^6#^QWE%cx#~ByrRLgNv>+l|nXK|n$&1bxF|^~gGmRcQzno?cQ$(N__G#Mjnv+-0 zDD#TkMtC7wC(s(ht=9DS0$=n4$#{ z*xzV>SFcyie<-WDk{l7}HRjI@veTqv&X;KPEm_4LDtbmO&6VV6LB!3`ndK)@XKlAm zf6&iM0s|5a);Wm7H1v9QndbBjo4=?id?mZAcj|`C-(z5uFpQEZ+lk}%`{{1PVTxXl z5@nYI=27n>4pTqExVTfSuin++FhvU@etVNmo|=5ab~#K_e)Cp*o~yYoNgSq#Kres1 z8u8;BabhKLS`vpTS`bm?Wj5J${0-avx@LOmaBK14>Uz!|X(9r>>?+yh@wL~T9R&JH z=w=U*{CInZ!*pcz^fFuF<2G{+e6cLOEdBX$n>kGVPj^Dan}H<9+UjM*VTu++EKHU` z_A5eYhr{%K)n&3uu0{@rDI(Ad-z?R54L>K&>}&3Dm|`x%7Gmxq#`lPyME=AbbrgNg zffhvIz3HppGofNmv+fRuDI(Ad$0IRpR86Uhy=tRZ^A`#*wh@87lEz2T8OjQ2tOHaL zj|lX_@kq5%^ONe^CyHt2FhvU@{E@o8nMcn#l}%?S4pT&+mw%jZuhBp~2<_`|m|`Tu zv4U}ozF42MCU9r!K)sSUOwob}?9;?@bNpyv+3J2emN-lifnNATs7g=#AS%!7>2R2$ z1razKAhw<^W5kb}x;Y%Ch(IrVv!uFEj#O158#x@NXhDR3Ci9|1cI&Tit2i8{h(Ir# z&l$$HMd5)Db^Gd$#9?~jRXUmSMx4zYreCg2Cx3boXETTC#q(kExD{u+9Huv$e6AmF zDyx~pwBv^~a(2mMHglNnJ(k9q^)b6t_~A4%$G699m%}tkrPb=n=`ZzhVhde(KE14V z<*3cfqZ6y7m#Npr+00v-Y;HRF_Sq5JWedH%XtpZ#x|U|PP_!W8vHxmIXJ^n+hq&Ysqd&!7cI?fp=d!w-GpIs?C(eIIS%K*qN@qz znXN+|w$O%2!eolRaW=Ds)?N`NS2c{YnJu(Ng)rH*~}K2>TFt>sbZY%vW41Bx2nymn`X99 zv>;;a5*m6yJHd=3(;7JaIO&g<^lBGvQ*{RiMlOeU{il(SitnWGHrhf_!mq zu)`LL2=v1DPc_2fN6f)>2I@Y<7K#=`;8URQKMv&=8LRczJBck65$J{QpMFR9V$oT2 z)o+L`6fKDGzrpf5Zi{|dS~_f@h(IswF^2JL{S3NkgUhNSv4!3onnq?QA7?WM)wBI+ zg=*XA(bk`|Q1X>W`k8o9Q<;vPxuh%)%ZXfSt;u=+hzFM z@hq2Kovw&JNo=8LL4-dWwCV9yR!vmjVYJ3Rim}~4zdHJ4f*NB69221Cl%jwj{IRVQSBo(^Q7Xtp|8)jrqQ+f|EriM6)lJu zQ8`R@D|W=ou%;%xHUfdhSJgI0w#DK%;*awK5^q7O`#XeuBw^!6cOmR*R!^xXpy96>o=x>59-65+bfrb2pm>r*}idU0Im-{r>k4nvCROSOyXZyOd8DJLh9 z7ej8^(}^cFQ;Jvi>#VQrV#Jf`e^$*46x01m6w}wbmJnz`#O_8fY%}h)J<;JwEnFqP z?vuK(UYKNo4}o6(Uw*G&5q+sk3H@?K0pIUHM8AzUY|~C6v*zWR)O!ny=n{4b{d`?6 z9|FDb-4GL7&rVL*LM-& z?PF%%#Hh_w7#k@*pCxR~p9r%_a2CxkdEIiMa)~ z1m7m2>5TsS!g~J9{913FBhZ2fe6z&HUN&6MJshTQBui-_0=-%fPbiNXckC%wd3^ld zGDNpqpGfcSo8LkUB5*tsf8wQ7x}7les)kWM#3!o~%icR~*!_w16z@&U^}SN-ch}#k zho_@_twO}eKoZ$z+I73oW^UEW_gVC?w~2MrA)opX=!N5-_y9_z(htJ!sv}2>`esXr zsQf6IToZlCKI*WZMm`VIZ4Ta42kLz8L!cMV?dXKJdSYEoCf9SXPQ~~z3vXZZa1o$MD}wSNiV#5 zriRYVtOumZV`0qTIVrcF=cPl=Ua<2o4Ux>zY8cIyrPS^I$*Ii)$$bd)!u!!zzpr1b zmbJokXly5?6@Ihp*CSXK?=aI?26-TpLsWaTIy0=@jdqx`MvIzhyz*3jEq z0%b}cvuBM-CwCW1>O^N=qw(nypZf5u+&%f3eaO;dqVK5gC7z2v(;u}{(t3Xv@xYy- zU4nI=gvmkMLj!mA9kn~s&cVSET;;uBS3f;<=}?rR?px1mt3?@WE2T}iZ1-)g$XL@6z)B>{% z=Bt4f;_UHf(#pHUT1h90;q`UmLZLeD%%lKX5K-~3IQz#+X=PLeM&$dnoo?{^Rh1<9 zcpn128t$e()+wz#Ol+9+tPXb6UnV;)re9wc`1?8SUC^FV^)<-?*KWtz6*H!jBMK%9 zWXyBS?$<4yJWV^dR24=$2KfpP6IZ9q3JfE!?HSU^Ux^iT?wB}xMs<2??Lq>Re~Ggj z>M+^mE;C@JOE6gf{mZF9!&5hW7DV7vr>~cv4%VgqcoA69JDm@KUiW*%*=IV3$>dA< zeLUPYR8QOc+-!C|eE=RPdZ{B`Yo-@LTrdQ1}k(qVt33P zCLcO%h-EW8QJ+1?svn0&SZF~6j%LG{@jOK5&XQFx`#rr6fnGQY4C7#nEc!)>JUVOU zN51ia2%K@y?6ql>9zG$1PQ1g9Krb9!RF~1Bv#xV@mpDERg zM@pU;eSFMlRi#vz4}o47V+>(HP@0CwTc?Hajw0uI!D^+HsrJbVjiS>w4DfNF1 z^IB;6vi4EC?|}?*<$uWncqKXo*pN(5+LcT%Jsjz~2O@6YIbt`8${>3zZVn#;y?&$J;6`)O$zB&Y?p`{bP^ZtGLSMX?&q50#P9!^Ge>j#-7D>y|C-=#> zs&I5lojF}W9|FCG-ac$6T#!yaa(HX^UaqHSW>K>FFUc)F58_oMp9%5l9`7PB*Ch5a z!x)&WvVOO`ovK$kqlFek;FG30nVt1?h7UPa?iWdX2=wyz-GR?4=#xpOsMkM*S!h9o z|9v#QQCm-KKVF?!Y4{N6<#4XIyk@2EF!ixqKo)(W&B0wWP+wX3c4(~AeifpjB%2=wyLOBR%Cso!3? zB~l;wT%ZLJ7%L6K&RkcooRrdPcYlj-j)Pt}C!&~`q=+8>A(t*ge8?D`aW>$O)HlAb zsuSEvp__d_QJ@787>P)G`A`F0ZT2zs_~B+B0==;J(5!DwXI*Ud1T|*%G=UaGU_>>H zVbeS5S>uYUxLVSOKrb8xv=2AGw_bL-ubf(Wjz9|{Fy_;DUQK%IF{i@#P5L*IHy7n%$Ri5P|a*+F_a9P3JAVRU}Bg$d~WX3+F+UITvTpV=HIT%#*r2 z!5RB*g)EYJQqwm1%MN|~sbrqi3M0?he75THq*hYNbXd0JddPyjR`-Tf@p3n#e44=@ z&oN3+CC8M{st+-%;u~s;d5bTRvq~2yj}kHtdf~k|Gs+8j@lkBU1rsH zSpvFa!StG$Rk=ckYfP9~wN=O!Tb#@;nOPODL|jPEB6QM~1vE3Oq6HCWGhMV-*Uu(h zX4O7ba_Aii@@ZyPMFe_b3+XI1I=|jKwS;D7Rjwi8${=P|9o_n>J$cw?l9^SpwZupE zMLu06Lov7tsMRS|(+_?u{6Qog#b`9-+Zo0wH6 zJ-lLPzY{Jm6SL}+W>@WnIkHM-R^>W1KDl;l)p94PuI;Je)@EW>MGGRhCWC7;TxQjz zTbk)d*WQV_(ZhWR^y0b?uIzAYKT_weqO-WSrjO~XyN7lb{fSu>5$MI$T3jRGR%{K89i%&7oD1H{z|F0(3ECUAuUS0~^-xLS)V3AkblTWc6xnZOkatgwm}L_Gfa zqRo{AN2xZF>fus0)eWjqRpai%zGsDA*n4OvHDxtDzIRrKSrsja_~Ft8`_rqRN|#wR z`gTRV?2jDQJYrVmb!KoCkMA7wBkc%(P2b~GP3kbKq6HDydx!;!>TtLo=Q-&KBLclJ z&(m%c)!}eG4%gzK1rc1W#dR}o#a8ad?e(~C3WXh8(mCUPyI z%dE=Pj9k^o6^)2MFN|Y`!L@K)6UX&%m<_P)m{$ygYvH&ij_cvjf(U#H#B4-0OI*9e zbxVjqFYL#p+Cz0wTpu-=^qtXy2z;BQqC|B#T#v(g!iYdG?8k=DBBYVlJrX+1s%Sxk zKVDUQRaLJWpVdlA%&Le$FaP-9DkrXXVzp+B0QmlK{8LrfR~_~HcAFG4tD*%F_-5$~ zX{!9>3Q$(CM+AD|6EO^~{NxHyuKq*|A}~K12G@{rEg9F5Ap*Vd%~Hh{)sWShmsB&e zDq0ZXp8?$2pGp5UESs)D%&Le$FPudgM$wHsRA}lpnweFn(^pyx=xZ%zR=v1un|DBYyb?vxwNJ&Xhs|{j;z>mdB0eNo zWb?OoE>G&?u5n^vqIS9)@uVUGy+$NlWb>DME>G%_1|il(yMe=#`pLj`_N7euCG(`- z9JSW&dpb&1%J#&p_|;mf_K%XcZakrE5IHo&DzUtQ?sv9C0KE`>s?a98^#b}L^e3)} ze|zYzIJT*^ZbCe%XhFoSj+^Z@ZwpA5C$-GkWY&w44fXzOZ%ss?*O<1O>=v5~$ls@3 zr+eJloL^n~A=cqZ#WxlBZ@bOkNHI_9<;mM^{wBxeNj;o;j7;-jfWwoDmL=o1*r~D< zl+2TgSE3sFf!CwI`Mkf*K|HBwK}477>+MIM=a()|>g#pO<@PEu`XKS7A_Bci?Al;o z&5~cb{JSU1)KtH$>#N5TPb#(@(WPH*w^gM=(&b4#kz$If|7ACwf_PHVf(Y!#ROOw1 zx2jjAgJzyoM4;D=(497aPsVdp`r7IF92K>{wq~Bx*|}HSQ^!S0=1J|H{1@9YBPH{s z9(%OTF1|OPba_(CX8B^*qM;oep45<}tL*$MBPH{sKHj+4=CAdbCl#+m-=FVTF8|Ee z%;8Bz3nC7tT4M9}gf36&<=7i?#*;?+FXBl>1bVejy~O747hRsz8BL=_sjdU`ZsJL; z`6qpuNneC9Pil=nezjN9-^`PWeT@25sexi>fqwcn@uZ^H&cwgk{2dnar1}vxpRN%% zD)rFGi6<2;h{(2bo6X;Vxjda6TV&>9q z_5}J$+T}@|w>+8kbN7b25%HuV0=-Hu+iLSS*6zH0N#4<_QTi`5^Q7WaER$xb&ELE- zPingn%j}4CxuwgK`X;8bnw_$?W}Z|;pclR;+K2mgnu-=xbq?Z5MGGSGs8#l7JM&7H zCv{=e9JMz^P0c*1h(Iswm9(Fj;};cmrIBV1?3gSYZDU@PWDe|B8#mgI|B8~#f$blI zkFTv%J3chgH&PuGXhB5R&717)(fOry`4NqeslN?VF`YZ=f*)4<5a@;Dkz!(kP3oIt zt@MfAOMH<55sM~lv(MWFq|3$HwC4^LcCWQ&E>^r2dSUJ&<;5rUMa{L}Ib5t?)uB8w zF}Gwc*7L?;|yv}buQn`pGXvra->tY|?*mQNPj{PnEM#kxG#fxwlG9d#?> zVnqac;RvRa>cP83?=4g{NnEU$i?D^5yC_}_oFp2o-b|dH+tcA< zMFe_b3?_!AO5uTC@4D;Z#KnphL|}iT6=cjXxpjRvhl>>v=!Lz9G!(XUR`b)e)V+y| z6)lMHN6}WPmaCM78)@cZMFe_bpC;YD;c;f(af2N$R?KP`?J!>%1}*Hw`hoo&E>^T4 z0;3XrV{*KTnEYQ~hl>>v=!H*&zQW!(T?}l~)8S%83nFkfU>H3c%@)s>cGsDRixm;* zg>RPX;mSS~k0M*?eZ<9z7DV`GGT~E`TdDWe*Hws%6%pu#^Et!#zVmibAa5s!Jqi0R z&aXl%&9zS_%q3lR$^$oMtH}onXy$HvGN!Bj?d2%R+-)Ikd)pyZBPDaURa+Eezit{S zT@Jb@-K6SAT5-(e`F`kVyXN!=$sC`n?~bzH%LvKroj;u>F1l63$C`=H&tIkKuZxdw zt&)@*8~8GB4?E;H;^iQ|*MHV^x0zGlnOVNXJ4!wDP6wT zGmGlz_3hH=!o>HA7DPPH)W^QrAfI&kUR9Px+UlJ|Gv6yB(Cc-V7(3<6eA4B6&37b= zewM$wE>3)}qql!=UtN$}GT&>emfzcD7U!1C_d4+RVfNzOxn)m>?=`G$Y8{%ProKje zuV_KUZsU7<{`B0^<$E2QIIXU9y_T*=e6NT=uXERi*|#Vsx_qz6-p*7pfA-dAiMvHx zB5&)N_NdMg(q(U55msL$JJHW!Z$%3t{9`cXti@tfm0k`*EF#eB@gKA8usy``NBpuB z+b91jYS-?jTM`Q`S`cx6$Q*mj^9af8w1#nF^e!=V<#&1jF|nZq5f~+?3TfU;Q8Q-? zeT~@O5P@E}(xX-CzUwl@v~P7m;(Nt8?&B--?7kEkm@O9PU36}+Frdaguc&Jh-z!=W z(WT#fdwAan>GHis|NMh0vMyRP-zy@}3ul0aQN7MOIiXuahl>@jyFSf4TRe@B%t_t$ z>lt?A**T@l#ro;^o^soTmJSyyS`bm=$aLHIJEwHHSRee6LH)I@nZw132=w~C)kHgP zQBLV{v5MFU>SXtv`qx!ut;Ojk+vme`O6Fqi6ZeySmN+JvS+(oD8TR}JIi<_2nxQ}w zwWv;2J*-}O3$KM}yf<+)M)z0wvJ}-Kq_Bk+MELKqw(>Ws<}9I^SrrlJh0l=KNNNsN zuYNA3nOPMrh?rAlp4}u{gmjrzH$)6q{Ti0k%&dwC^uo7EyPW5bsAID#X=YZvuw#_n zX*6XSVphcnHzUPR`$kM|szv9FlYPK>^-F@XnweG6f(U{r9`OJ+Jfwz#X!+;O~4p!Ioyy!yM$;d09aY zX=YYM3nK6-(AmVwrE2<*#BfZ^s?*MPvCEIlFPT{tXMlc0$m_l8z*mJeGpnKn5!l}h z<4{Bb{n_clnweD*fnL~J`j+gU1bWr5(wdo7(SisZ!Sqe_SK0LJ8znR|t0Dru@EOuq zTaCl@@q$7#vnpB;fpaZlDOgriNB>5as!iWWrRY>@Vl zbNwuD+^_F&tNSu1>_%a%q%XtzpNmeEs)fU1juu?Y;u_a5j!t}I?ucxo6BCO$BG3yn z9F3^PiA9cM9ra04c0davaOF+>?R$ktS(m=fBvwa6pck%+4dcW0?7H*Vtok3~V#RTO zdR!Nq+1Ys?4ttMbT=*hHKlvrEW-eB=AmYUC?`-C!clY7uY&oUw3@)UZixm;*g`3-WHWm`?`2VSTgYTpW_NDQT&x%^F<)VHHHP^T4!k^WS))}vUA5)EHWT8F;df^O* z*eM$fQk#dB)Xc?-7DT+8JJJ3lYfkBMv8GErKy4UYPFE%_Rz#o|&VyKcpuOI4|GX+o zT&x(|ah-`#oA{QFQ;qOfhg3o0VnqugaK%d1hOg@C_bpy1=3+$zdSTS2?EG63J$m3J z#aygtLBzS|-E8JWc27*E@2;;izPY3N5Em;V(956I%J%wEJe$~AKW{iw;ON911RTx8 zwlH##D4(F4{wDQ!-#AAEt}KWnrSI0jrs(c^5pl8Nwa^P^%Z5>B`Hn!dUt=6DRS#%V%4v z6p+)|w<_ExlqQ<{60hNGn$DWUrl7Ou8JV z+a7OLLqmjSeo=gbc)vNMDtK*YG0E(t^i9KMsrFWFqnR!AZvHlQ-?(y;*+TP>vgc=S z%SvVoUA3s4ZC@=bUAEBO)%U1=^;&6W3q=beYAcnWhJVH;-_L=Uw^sd0S zhVv5t8*G%TlwNf=O!pzSP_!Td=R~w$a;vsZzVx*k@NA|JfnM0(h(Gb~+InICrz*1R zQh^pk;M&J9{wUu>kK1!eoi8}iw<^M%fmfnB08*}d&_ya{X+{eoF#Aw%-_u*a$~H+c z$1ft#3&)CKB)-vGKk7G5g%igwS`dLbk-qcFK0wz@R7)`*G9u6mcc2X;!JldM-t9Ft zGpk}xOfsRZz2+c&@GD|5)U`GwP$WBEt!9J zQMPvW-gBiSGpk~hAcpbzTB$O1bsu6@MGGSSdfd+Ll((dGnN{y!ysJ8`sH~Y;6%pv= zk3Jom*=kbv>YABV(SnGrm)qN2L~-ddt6p8VRjo@|RWq|HBGAhpubwxlsUJPep!XBA z>c2HQ*sT4@C*Z|vwYLw9ik8f*>W?LM-tv0D@Cdz=m{rk&h@@59+pPS@C-F3sAtk{V z>kDgURz(DQVec`FtE5UgYsfjp%&M3tu!R^`X!pE86MZNofo5h^v>*cSZ5Sg+d$4K7 zP|eJ$h(IrYyo&5yRA0MUSTnOKS`dLflzw?wcHO#mv}R^iM4%V;1^PPk+5#33X^vLzs zeLWEo7?0^I?D0i(=Y0|SAn}Fcwa^Qnh+&K&rOm3d5^CmRMGGP@@)^bfQg$?3-crwq zixm;*g_(%z!iVXTjH;IiMEr{^XGEV&3Uync6R8?qN(uY7V%&0U&J}L$4dUNF& z>3N&1rplFPr04DEdUNF&>3KVf&2Hrx>3Iv*_2zm8((^W1i<9daNYC5R_2zm8((`t7 zz1^B3((|@h*ZZMrA0Rz%lXWM#R;^05t|n_ua;=&%w5!SL-EOTK>3LhM>&=?pXrXv+ z22T|6O2j<;M{kRDy;;*6Er_7ZV17J#4jVKi$ zJ#Uj$Hn~=<#ebb0U2m>cdlveg$y%Cjts3chTdeEdhicW(3(>>6b~0Iu`-)SmMta^B z>w2@MH(C%udftvUvRkW0dft{GUGLwhRt*v8HLOV|N1fQMRUzO(;MF{WgIh@ z$tc1(y54TB8tHjktn1C1-e@5`ZD@Bf(X*{Hd*J?tyLpE zZ;N%kS<@R4=;iNMq~~q1t~YCXW7`o;dfp~$al5r@q~|SI*PAuH(Siu<`4kx@D8ahk zT&so%^rGx+e$39K=Pg**n`_lb&)a0BTdq|jJ#Uj0l$~0&2klJOvvq6LNYC41U2oR( zCOvPH^>?{ejpm7FaE}bHWEiC9ZLzL5YkH#v5j00NKkku{p0~xi-mK}32=t=(Xnx%B zB0X=5b-h{Bn{uBS%#ft#?dW=Qts3?*(&zlViN(6!tm%zjl-0~&ruHL9&)Z^MZ`Sli z3nD0^njcqQq~~q1t~YCXBLcnry`A*DE!Op(L$zvXK?Lb}o2=OF)~b=7x5c{N^{7@2 z5$Hv$Ni(?qB$b$S8wBfmbFCUaMOr(X!Tmkb^EO$3+pSe2J#WFf-dwAO2=v1DL~G}+ zTLkNRv!*v%5J7t0CM$NkwQ8j2Em+r^Yt;~eUf3&%Ir8E^f_1%F(;LSc#&#SlG(#>a z1?zgVrZ-v;L3-XMD|WkeWTfXUSl65D$Pj^En28L7^t>(B^=3_PT637e^BP*$n8EWQ z95S6_Ob|b)xE>+@&nm^=3_PM4%UrF4`mev4h3B-dsn9c>-IA zd4;}9E!V_iU2oR(MhhbF-iASX-WKb6v!*v9&zO(;E@!g?)jTrf%L5tn1C1-e^I@F<*ouJ#WFf-dsn92=v0a1Ti{XDs8c@H*0!h z#=%I0xx^q+**X^Mdb6fCS`dK|!!StC+hSdB*7QaMdf^i>4AS$qSl631z0raQ%+&Nd zeraK`t~YCXBLcnf&C*^*_udxkdb6fCS`gu%Wssh?#k$_C>5T~V^3AmjQsA?4k`f=Q z@L}J@xeqBEo2-lF){&8JreOU{KH()rO_Mb<`RtdpGELTv<5OKyJ~dh2%{`;<(BY6c zOsddaM^-J{D3g_-xsHq!piNeU;yN-?oHkic%B>?Kb#BEf-K@|}8r~)=b8}r6DRP^v zxy@Btq~~q2{-Imr6?U+bVwLVTRI!B?M36eSIgC`g-HNUC_nIiy&t&aPM4%UGXqv2~ z#;3i8LHccqb=+9P4K0WuU2>BZ+T2<-(r;6&NfO3bj{}DO;#aytJ@ORdLR~&b~x*X<2%Rq zOp4>?YEm9|E6?ggCAL_foVCf(f(X(pH(A-ttvt)r_fxAq>3Y|t$}>cuSMK-Uo2>Ee zR-XN{rH~~^J3J}rhNA@$m3PO|FVE{$o*kT5+S*9^gQ^-Q3Ev+f%Ar z;iS2pmMYH>fnKD}ZLxQER5<o zpm$rVCh3#2HaQ~DYxLi}%uIc$&eEwo8`-&&)r2(AS^pd@h-lTLm&ppBZsi&2e_E^q z${L_(K?KGX`lfnKAB(j{S!Wax=!NSxs`2Wdz+$y=RvO0{D`}LQtlrF(XE=)@R>ym% z1gnj+(l}ZWK`P@WYdpJ^XQVPNSZ$mu&k%uLIG-~NQUJGD37l2H@wzt(_b^$HkSotf z0o-H_Yq#=@6u>Q30%sL)v><{Mz)e;fbSuwD0o-CGa8?0F1bUGIxXHSKZsi#%fD2Xv zXBF@}4+fg7NXeCFqyTQR<~FN<`w{m;hY3~!XBBYtnpeD!*@u+CxmJx7z)e=uc5Bs0 z0bH;WIIDo;wGfT1r7G{tO9d-|vkEv`5aGW^%iDVeD}i&Z8Y0jOpSofEK=)uJaIRHD z3nKphp{tpOl)#67VCEK502izT&b4ZYKrej%#GqV#v|uH0u2mxiaFf*+xmN9-m}s)* zA=m8s^WcB~{wP@2n=8-0m@vU)om8$o>(pzM$tvAkc}9BPCTp9zm1m^qEm+r^E6>n^ z2-5R5S+U!#JPTVgO0cdsSDqmPz5WdO-fTp=-fra?=`IV_U*-xSQkFJZ!xR|p{jy-3O2WSwNUlAJWd1#5?M?KxTyLHgk)tAcYK zIx$ns9VS>ioa^BbfnKB;ZnDO=s~djHN+4L{nX8ZxLAul?YcX>L6}FaG1aFrLuvRr! zQ=tVBq~~q2&Z%2RM(W%)t8}wMHzLrBYG%xjU!^2ER#bEy*Wanx{>B<_vg#$*W@EO* z9z$R7tS&54HS4RdQ(ZV(5P^A@b|zl$3$Tv#cB*tj1bX2Nhj@g)N^7!?bbu?h;Y^LbMXnZN-CLR0sdU0fjcX?yX|ykTKfASNWLBrr2`z}g zRT%NG6wYhKqzTtasL}}$=!FrLzQQhMT3b`3)TgM@2`z}gwIO{m(z&w58n#^Ngb4J) zbsO=who0WW%G0bmjlF>?w#?uchuC`zgA}I&tUS$?PG~^{Rg0M)zc?htX~D|VTT zLJK0OX4?#YwMSoJ=N&Fsd73Moa0P+!(H}*d{ykQ(@-$aEp#>2b`G|A*_$S zl~jfFZ(XZetrzNRsv|=SB5<8RXI{n2TCD5Mn%;;&FP!@t2I+ZQtn1C1-e^Gtu8`=9 z+}+tM*7fE(GDM&kjx@s{J#UM3y;;*6Er`IiAu&N;dn#Dho9oCBfnFFf=$teBs$gAj z*7QaTB5+kqRozO>ab?7xo^*AU$uvy56kmjTS`U{tPLsX8%F3t~YCXBLcl} zhC}u3dy{Ea>5iisFH+}rw6(eV>t3Txj!HKxbjP0FWNs#v?&?mB7pZe=R_Q)RHC||; z@4?OB_uzOX!yt8T#VXxgQs*{V&yuT+NS)hJ>E?>0g4x!Y*-6{-fTPeoWY})SisoD=gOL;C6)BmUtiH+B zVzlerD^4x_q@C^)`K3S$A~04GVr+b~ z5P|nL4AS$~tm}Q2s@o8OUZgT^vKF_iG~Qw6Q}y9VbDg6j)%$=25&qvnO6K}MQZ(o4 z9Ymm)fB&l5!*I#E-mK}p^7TrS)l|7sj`X}u);8tZIMVZWbiLhrIMVYDu&y^((4hqp zr04CZ5WAY*q~|SI*PCk%5J7t0CTsk1)f~=hXq*q9AXwL%Ywpm32-5R5S+U#I^d>!T z!Mfh8>5T~V^3Rq?Yg@49HtTJZ*0#yYvs~{(THB81HtTKse+Mam3swT>x;|0>H(9Zn z>-tCm+))DOx;|0>cXXuPx;|0>7pw%%b$w_-1Sx=mxny0PA|QrZ@g_oQvX9r*qB)%LAD#3`WusZwn>D== zfnL~q41@H%CF^>#rZ-v;;h)Knp0{FMZ`Sli1bX2-h;~wkMG4mR=E^gCR;1@`vPw5s zp5b$&vx&ad1?zfq<|b zSj>++ETrcxSl631y|MR^p0~*=-CTL*?}?=6Em+r^HNDY-2-5R5S%2HDJR?1C!MfgD zd4>q|!Z%A=bi?Kd*7fGfGqfOr^t?@0>~<^9NY7iat~XbnAp*T{1QP?zzO0IMy;;+n zm{iOl_X_EGo2=5!m1q9mPI}&wb-h{B8!d<+jsr8u0Ym#A$<-duTx2=v0~H;3nK8|hCzDXigmrY@(dB^g%OobuwLBS#k$^H zd4?85U=KBnK0THPSl62?&k%uL*cWI-JsKfc*PAQP(1Hkmydphs!MfgDd4>q|!su!k zr01*a=JMrA@nXXvZn`@mBfnNA#>D%zpcNOb;b3HX$5aFNuke;_@U2pyt01@bg zGeFYjC|bp0UGKnBhh@_YvTTx`x5+w?tm#d9-X^PezuljJW=o{!ZLzL5YkH%F_!`Y1 zUn6ne#b1ePCU$*ov95RNyAPSkGv0y-((^W1G0oNVCOvP9b-inJswEJCUc}vKepGfK zJ#UM3y;;+nxb(~*Zzbt@JG$Pi=}mgxj;{AFb)Qj%Dd~Aztn1zTNbdl8A)55OP1fRe zHN8pC+hSdB*7QaTB8W@VQPy>NQc2I-VqNck?F#x3=tX+oj<&6<=}mgx7VCPmrZ?$% zo2+!qn%<=6?dW>5rZ@5GIr_`YXG^sPts^bg^=3_Pv><}?yiHc@b~U|8&)Z^MZ`Sli z1bUI4x5=v4uBJEXd0VXO&6?h%=WVhcGHZI1p0~*=-K^!Ti*>zO(;E@!MS9*Q>%h92-lXSkv9333dK1^A32gOdkgcBdyiL}A zb~U|8&)Z^MZ`Sn2Uq~F5W{`^)p9rl7mzTGI0W zcoof$46&r=ZLzL5YkH#v5ya7H23b96Mpm-3#k$_C>5T~VB8EpZ$O-DOI$FT$7=L$S zUo?XZvDjLJSskq)t0P(vLF|iWkc*kV;hkU3VqI_6^hN}FVV|ZwfHI$1tn1C1-e^Gt z>3N&1_v>nUlb*N5y56kmjqetFCH4hUQJRv+VqI_6^hOIJu)jGRrWSCR#`i1qB6dSow%PU zX0fg}YkH#v5&lR`dfpc6db6fCBGAh}&WY*Pif6ioNQPqtBOh@zP912mt~YCXqXiMz zr)iIDbw3MOv*TkTdf_v4ShKAlYc^UCfwKXJN7w=$;rOSEUifAWgY>*D*7bf~B$@A> zBf>wEAw6%4b-i~cn(Lcip%>2Q=xm~HUyF6US<{>JyiL}#WKD0<^EO%amNmUe&)Z}T zN>|gH)NU(;q8>d;@4eF*fz-((o!zYev=^mu9hdOclW zBei4@wdBdmkN|0ho2+5Xy5TQl;!M#gOx9k)^>E4046+_|OCh?xo8z+}!v8)pWbb2L zsy$WIK9$3VK(EDb9X6{2ovq$w{uFKMW(uGM5v$(Enf+5!@5#-GyyMzf zOZ-CY?H*;l9hyP+T=qzy1renBZn7G#tNcFtqGhrA`yo<(M+AD2vb@Ra ztFF2{Da%_ONMWAU<89uer3dTpG^DzbyK^EAgVYvU5K-;QQIqv^$B=@PVURAl#rotaFANtrwlU-2Xf_PeCAV0gd`GLzj50>=ueVAL6CvD$b)QW{4DdSS$%FLG-RvF_eUD_{M7*%vJlfuosJ zD)SGuQcp@D4|SUEL!cMN6;d;Aa9OZ+IO~R!(wiC7XC%#VlNF*_H=H!XP1d$_b;C(B z++yu;)(uAsBCuD|+^2b%)rPdg&ysF9BG8Kz;7nF09pmVR|K1^s_0Q*d^uV-_1X>V* zql;Ko64kd@*SqAkWUOxxKl8$V?4Mtep0~xi-mK}37DV`aJL!2_tn1C1-iSaiTmcY+ zS@s+j>w2@MH(C%udfq1MNV}Teq~~q1t~YCXBLclh6D@xIX&C1c|0`J6n>D@h9gv>4 z$tvBf>5b2gcD(xkD_GZ?HNDY-2-5R5S%2Hr^d>!Ti*>zO(;E@!g;9cbyyD&n*7ash zZ?qtS^t?^h-*z>&=?pXh8(&d7G@*?P_|Hp0~xi z-mK}32=u}yO?3bh+gq&b&6?iWuP~Nik0EBG*WE4F^*+&Oy+8{h{NtSTye-!Cepplb z5a@*woOmE(x>>C2{d2!*zSxck|15*_ye-!CW=(Ir7J6YOqJCATrNz45tm%ywMEK`d z3uaffSl631y%B+4m{Ca^a8F%p_+KIV{=`(iT#E?*{Ob6O3fAYzbLm%E#|Q9Q=*9W` zqk4AHt2ag34`I4Md4Gh%NHq0}OJ=u+$>ecIhxb8&yW&+KmHtK-wa|iyT0dQJLk-2Yw#q`yGgwlklav;OPr{Gd%_R(xOTd>q+?}`uhz9dZ zy4_(lKdU0QQd{ru7<%A;kv;@^;cuc!S-XUFo3z8*uFoY%O+3JQ;jAd$Y;RIW%bj)H z{jHjFwuGff{XKFP`{zRql2 zZTwuND4yG*T<++-vfeU2H_EdCR$O&+?TLaBR$()hu6#bkLJK0WwN!<)sgM;-dhvPM zoDzsYFPbR_SOw5kmp_@Hs5Oo>>F<&rJz5aq{~Z^)(91!F_@JKw_dL= zq;HV&J0j2vTT8LMb}_5%kYf6`hJ^(FLj2_yLvEU^>ps0S|ME#Q^IN$|{k`C}IRY(+ zzrzDhB^N19&>T3f#^p^vO=Ezp7peA0&T)1+cn z$DXD15Q&!VVUiIGy69Qm3B|VX>&u2c%()%2J6`uM4l`Tr&FcL9e(3s$>C8R!c6{BMXn+4*0wFIO6Bs&uL^J6#rOEJeuS+0di5^8?y36uWU47ko&TpV zK;zD-w4`77YyS=wS`a~Bfk@(?U*fjv-jDax-#o&+EpInpS3I1!#(4iR^gk%H+Xo` zZJYnO&noAqwu-yFM7^|ISm@O~_MP2&(iP{reuVL2vuc!fjoL=P11*S%dH%1>|M<;P zwFr4L>i;6pi|@r(a1q=KgT0-5Td-GiFAVl}?w!F=K=bz6F{(|?Evoza4i+NNi{Ax5 zdH0tux$%Rl5_eMdqu+rRMDUa4C+xP0-vz%DejkWHFMfOceq02NK@}W>+}na z404YQj!k0U>lmii#2it@=5??TfnGeCcvQK+quT2*RUqo2n!BKdg%(8cSmcr5wu(nA zk6a$Lh(IqM$vmQ61dmuAxjbrll=9f)yYuMfQOsUEVtIVJ2p+LKa(UDu0=@Fe;kkI^ zy1yf~#TGmHz*nlyKz_O(Er__Wc5JR2Yook-^l!1n4E_Hg(2LN~A6rGgJP`cl^lQ!F zGohzo2A?SXa`WRa4}ZKf(4yvPb#{CQ3oVGC-xnQxBD8Dpesy5szW>x`6n7DUUi93e zgU`({D2@n@Cmc&KB4ebc{$_scyA($R#}kevXh8(^MDt@$q`oVl@5WyXy{I3XAA38+ z5yA0G24PNC96S6u~@*2=t=375JD3sizC-@sfKxjhX<*4Q?;> zZYMhM-!wJ?90S~EMR7y~X8>qH1dUiHp18l9;)n>&01$y*6h{Kp2ONlS??G`ya6I8y zf?gCm0tcI%jNt3~5fn!R#}haDe7qJSyemcfS{2|3hu16z)=*v zykG8I*N^a?Zh)UIS`gtqb<=GX#VWxui{lj{(93)OrrWB&H#`=5DK2t0Kno(g{^s4| zYMtZaOzs4NBLgDP%j+@TJ!nQIXhtTy85#Fo=UQGLbN==tXhz08QSj^)Er{@XqSq>l zpn@Z*HzVU-?c5!`ys_!EiXy1sNXk(Zy}WVfT-T5AMy>E>WISq}YazlL!CtE-57;3d zWbWj&3a^D;UX1Zt^<(8YQCE%?FSfU^(94S@&UO8WD2i|wXnnwI1GFH*i*{bCD6R{R z@BFL~fnHvu_F5J3sVz9Zb8JToBD}ck-Q&aa&7vX2cb@g3#f#LA7hcJkCvrA$5NJV! zml?c!Ji0we{Mve{sJ6L-uT|*f<*tC++gq-gC&~@jEe>yLVWF3ouL3-Z{0ML5tu*CPADYhu@`78ZJWvkd3DeuTH?bVe;& z5JCBg*P>plC_f3#Q{H@+SEJ6|(aW1_d99)xC^#2#9z-v1KIdH5kML%F!kh2%OwYL% zBD|TJ*D7z;Cpe1Ywb09(&v~u#W_nSyAqrW zIS-;2&)I@w!jItD80SLHgJ?kn&&D`^xvk<|3C@MwDny_cjelMVd#&PK3C@L_2hoe? zo}AhEx_*SW5)MY6_-i48=enG~+*VNzRGbUBRd_A*;+c6cR?9IH4Navnr4o~H+6 ztsg--P;oBgJct%V@Qj~xmfI@cE8$$otwIEPQ6}R35-$((UJ2(yFAv6B5W#B?&Uo%U zCr&fO6~*XR8i?;ex`73V@P55~6&z39pE&Ykx= zCCJ_kG~drQ3T~(To1wf7@XO>)m^-W)*rlc8(gvQ&aJn` z@%DF}H4a7mcncyZckur1$8{9%?>g%!M4%UCG}zzeT_VnG-dZi*f(YIvGQMaM>5f6( zCF0EXe-Y^Ap?A56{`WenJnsg`<$uOn`?hA1siO1R&A-hYXmTx+TzDkH`P+Nyw%d1$ zZJ42QL=Kfvxnp=$#820;Aj127-b$GFm9kNu;v9tt^zz<^?Y7E$AHmgj{C+zkyeIAb z4$4o8^Atxo?>#%$^7@$5LcF(OnAxYOtIrS1T2cPrfrwUCTDgBs59cWu#=%PM)$fzX z$&k~rzTbgf_zX$6ujgR(%ke_$TCo@_S&LWp^=8_+mNy=qR(TP_d%6<`>`-?phw$$} z3nIKR?>(z=mE+X6ltZ3V{y+qJc`?RAVC6ORl0DD4}o6zr0H9-dyUodF~7?b zXJdnr!MO(_${kN57ccJP-D7OG=ITbB9ddh|AAw%@Zm14mQf2iaZznY*I>t&;P1{du zzjChScL|?fR|y*>@7a#Q_p)HhdSgR?%T zy@>cD<9vHS>SPX@RD0?~s$nC(S3Rv59|FCw_Yjx&`{XKJ%JM4Ltyo{bLd1)CJMH%s z-+Aw&V(GMMel|b8dhL^zzm_9-_yCy0Y|}j;i>>SYN9G7t-3(5`OwWEu?<6 zu&127rGrX!J2tptaoUTBeN!Xs{l8}N-bdgQB|9#dqUKkM@gdL)dk?+AJwMBDbGKBR z?#2506(VZoYHgo96z1I{&6X`vKW?Tf-|!>Q3rB%r?09CI^9IjS(`v<7_mVD)Zobxi zA9!xWa}v&rZoKl=&cXAjcnczUPQtSQH~R4UoK~s9Gp~3Adhr~H^R0{cX?2+S+lX#z z)st9Xt7;cpSuRznY|gL6`%&dUx>x0nXX~!gP-Q$?5OKM5no_w#Tr_cDe>U9y>(5#0 zWDOo4A5Y293ww`YTwk`)UVFH!8uchPxDs}r2_ov;8@TK1AF_Jy!`^()zSyU$T0!F+ zuZ3PX3TT*r^JidJj>)QV-5BfJMm@}ep>Dk5*(%R2_#IF$fm(yVX#e;!%}qF;qXiK> zbLBaU`*eB#m{0b3?TiTY^7ex~#MLsFd zl3ClUdi1Q&f{1)SMVPr)2FFM7{euFdrcYNH>Nw*g{@0?HzbB4rlQYmM=XYwsGw12X z_bWu~`1*MCyl}Tq(>Lxp5(lRI+(lKRagNtQFB}Div2I;KvGe6XRj^@rW8(KgQ5330Xl^BVj^(X{<1L8b6&TN+-1k9qE5UOto?qd$(97G)^bk{?z7IU8 zQdPBk73*u&^vbKu&>4xm@$s>R^i4yir-8WoHPxl3PX35*J0gDlFwY$HG^y8jhc_jK zrqW|n>-tXqh)19o_8!AXnB-vK`$i4bn-@;>iSMI`xX@*US#EtQ?;e+m?h4GD*F+Vi zagNtQFB}Dik@Hpuk$P?=71AWeYLxnwX?^O>cX?ldXH5J)XqLh6#QEDWcvqX}SUkT% z3nF-rfoD(d`=Gg%;5io0uMmM=-fq2z5OqHnI!jKq`c15_RYU9CF;gTx8Ju6mw~%Ua zmgg7AN99$&(1^m8AR_$3Mf0;a7rk72HKd04txOxWqmeVeioX_mVeg@Lz9X~fy0?^C z_}a;0PBi{8S~dO8k3cUR1yo12VytL-Frj+VG{!oVAZ?(C zaMv<4Hk>&YzYm&)bIkJI2k)Ho9E;~yXh8(;mGSJ!eILAY&T}lDUm*g$yi+F+F)RFA z(f!1ES@K=1uT|aKrU)dzKEe65ct29%ds#~yUHy-=UpniL__iaW>BFRf?oa1=&uZ=; zLq*?tc~w^W<#;Xh!rntXEVsTArPn1>qu)BS*Z4k)h}7#71a^jQ^6ru3xe&knoJ##k zBMPsDUN{Pfw{}h!ku2)G-H+b+f+tx66|>~q#q-^;x#59ySC=|}Q!a;7)m)A?Yd#q~O zSUhZ`0wt+cXhDP*yF5g`nm>whAt9nJwF)hW@Zy-)DlaAmI3^+jy}a1v-J?sQ8lrc| z^T0a#9cV#>7rQ(}@|@p`K$e1{3AG9>i0~qx*D5b23XX}0Krb&QdiR)~x16}9(~H;i zJJ5m%FYkJY#zQ)Y`^9RAw$v)LAi~SqUaP!(E;yef0=>Mv>)oSF+B~B1g90KmwF)hW z@ba#Q7-d%zr}uXh-KbS)L4-F02)Mo7%jbggIU>-@%je!b`sYX~vPFI&64TQ~3nIKZ zW569Ba|Y%Y9an!Z22iWef(UQ!>$S?8iwd5LA_BdkqUb!dvfn zi2kGY2EJ=MRm`MTp#>2q-Ibo#DsLSncpZfZ^zzm_-aSqoYZYjEuY=e|zXL6Z@YXvX z;%f2Efi+`hij~wVv>?J;EqSf-)=`4jQHVe}#Xs~r(1HkWt?nTr zmrgbRNIgf`)GD+f0#C`~_W%U%0U!dsytTS_k3qS1?#h0to48NE11*T~*6JSO^3NOX zMGt3-52HsOrk+rJXLe}xG2^7fg$dyHQ(T2AfUPPDyC=Q!@pmSaJLx6kAu zKE3pZ9I<PWveP5J6GG<_zS%L2vI>@ZKvT(97E+_3klZ?Q5B+U=0y*GuA>2BD_6P zFYXrDP)IG07%ECotI&c7il}g^@9n(`-g`v^dU<=V-aQiJ%cMfGl@rm|;!gn_3nIMz zeGl<^K~2@KKzmV#T7?!wQ1*#GC67Nh5PWWc2=wyy_q}@z?pRpeIhI@GqEi60Ai~?< z_YmU~bXFzIs-h>g3N47BOdWr&ZW!LVf#7okM4*>3M4*><=H=a^%!ih$>gv^jy{BR= zv>?Jewe%2IR!>zU4(q^KY86@#L9^xfb9KY;PLTs}itJnqy}a{b?;d<+5Uk(Dvv`Wk z@n`9XCf&YuGu7jftpo3=RcJwkbu(NR+_}PAe{>(zSrwboH1OzH{CTZ2A4D&It2S@w zs&3}aD$^W~weURKL+s)?m3KeyY`ajW?&@gYcXpctvAjO#wmTL?Y`-5aub9gmG_m7v zoUKle(Dv`yofUmN0=@io0A-T&RA(1I-u2I6-W~i{A%KW+HL_8CfU(4#^_@vSM-~5c zxS97;-W~jiKrei5qzv@5yZU#CHXqPE(1Hl>e%{k9NWc78-*+bba%XLcUihS`bw-b$ z>FYI%|7!KNl$^Qezg;t{8i7=WipfdzcZ;8s#Q&ZA%u?buM8r?m%R63dS+LD={;vK1 z2s;lbD~fJy7f~`O_>p0TQG(=*oUW-DWJyELIf?^I0E@r+$xfk#X)C>%D^s&iuQH-rxL5>Hj}HoB#W&#t15sS~R3~ zwP^!?(*Lc%tl*Q9|4)S%K}B%9|BnK*g7XU$SIZ1H?;gsdo^8EeHI6iNO6<50nc04& zW&M)ixbYVv^9roCUj8}3=~?1-{dxAibHFEYXEx&Bjy5mZbYp5Qdua4(YE z=Bt~n@HjK+t9i1^(@7x(W_9h8;M966gEi(KR{XqglqqF3cdo^+P#8hQ=8_4{Uopb^ zH*Fm${$4b}G^t)pCeQB?Qeakt`|(bp(wVKL6Sxm%oipB?9P+jEeT5zhBdDl4`L>;TFv)eYwa67xU>06!A%?7vGZS<5a}V?{tTBR$X8*=J z`-2NPHu>E@aR^qqb=G>xf?(s|SgcO*Czl{)| zhv+O|w#1Qi|U$2)a<+>gxYz`uFloc&C}RbRM8Hg*UpFe@{)tNYn9So^$o zHL6TsGc@y;ZpWML6-H1o{bane`%hsl^Aw`jR97!)Zi>&%p{G5Ja~hYt6{$92z15&h zyt8o2jmWO8>#Tu^aZch7*COMWasN2p=TuzuPvmxHR$M4P z%4zeSG_N--A5vge*Tr$p&^cEl>+`T;?a8ce%8V)I{Lt$1_sb2O|L(pS>9K5s72M$> zd?(BQL7cO!!tKbBV%*v{?s@239NN*WdYCzMj5S^3oT>5GBZbJ_3eQi7@^yu4>t1H* z_vaNxP*J{0oYN`pM&y~X{F|59HQn9cCeid+^m#~uS=~;>IZxfW6)Lb9`Rh|c zceR7J;+%HZQz8=zuC-23yE^s7xyY+axz`SFc-8r4+7P!_^>G>_s94uH-ubCZS|sPw z+y~$L`c-Gc(PX#w${`xFI$e%)POnRibSbsg3M*1JCpmrMkGg-%7@#qNikE(kb5hgN zA{lG*F|OEmospY`sav#5NP$_{V(2%YlH}C7QNoo1IV zj=faP#Qa+;q`<6jOI&zUV4-};mA3+^X#r61!mzjq`ByCo7`tBw{UY59~`Uw$`N;L=e2k9vEce2OWas3FF(CzJVOt<}>CjAf__WdHPQIK9TO9T~Y}539 zaLfTW%cK5g)A1akwu_3wJK~(TYTk~_D#5+B$FXnS`49S;m2Gl`6qvQnj&t5gxE=XE znich0YBOtPjG3qEDr-=@b7u1W$h~eGt=ERcJJ)94kL>Hd(ZbP=R@F{vbL4g@vwB5c zg%MQD85-|=xZ-}K_{)5ZeLuD{F*h@t?~61EDKINMik>g~l=*vVds9F1oWk#m-!Ocw zYIKeQx482a`dHzu{1x%Xzt zkRp@?y^HEH>J&1M-uu_R)FxVEFG2<0=Y^1^Zn$qf_`|*RcKwh7v#_tw?n$Zn&CaC7 z?la9BXpEo&=O|RkvF@SUWI;|hZEcs30<*Ap(Ud_IG*jnT$Joav3)T+jJWfeco|dnc&vuG>4&blv>Bv*lO?g%MQX z?1T21*fiR7JUYSs>)o;;1!nc4W6a8v!K&vSBX!|ubEWMh_qVxa6-H2jvk!h#J=(Ne zndF|c!V1i~u&JJtB6_s3b?C7(_)_1AnJnpp%-!V!LU#<7d`Df(`vJM5#e=GdthB}Py& zDk;{vR`GU3F6LuYuX?~udoa*kx;-nTz$_f?sIG7OLD$|i(A3U4M`8pOV`juU(KL## zS;EIiEONxHyLEusonwATfmt{z(cZZEkGa<$^f&EFER+~QMgE1c&hw3KM;b2YV^nLN z-89(W!6Yarq`)j3yM!>~OB>TU*8Ka*If)Te{HW?Vy{6rd@LujT_c^Xjk@(W4evQnb zu^qE;)TR+G5^LT&_`HdqmRVs072)5!&HJ(DKPuiH$9g>WzLMx zuP}lNY-4nFhxKraI}>!Q@tSj-eFze^*+WG32K31+m ztY|)apt)AjR!cXT7^2VvOeoq&&j&^WsBDXmRGc#mtX1SjWM(%>B~LL ztuiU~Hqo+%V7k^g2yC+*nfmvzEu};!%$oN`#CfW5U+aZW zPgr5ae}0WI+p{##F_#WWjG*G{nGvUY%f1$SFbVPQOC?PH4;t!*OZJ8om=%>6>$I%Z z$9nT4{#H|lJ#8AzYps*dZ<827#c>&Nt~BdsB`)P-EU13h&HPVyy`v-TH3^@ES>aal zeWx?z1JO@^Ij+CN2r6FA6>%VRbf~aC%VxdYjBrU)`6x~oaEtqy_VQtRCP)%G2Y)ol-g6n9Z_kOoLOsBy}e6`1wm{aVichpRkwSaGIVcK7G= z!=)>yXpEpD_l#Oj=8|hYwGjW80<*d-uk6_K>_Cx{wA$Iz$hEeYo2tJ!p`0a|`g)Pu zNtSbKNRszA_Ia9x7wG0T`D3B1+hT&o2r9C@B%N3>EjaV+>tjvk2gB4WZxz?O3o2*+ zYtyXFVzq@WA6uvp=dRQ+{g3og+5RoBF@h}yKZ$Bm%RFZW&uFOzjFX{bpaNSDd2PM; zv^jcOt07IBhZL9sF#+U|zZgH6=#H`T`r zW`q=&g<~+yOAdB1Lt1~Q3h!T|upcCLuj3@R>%7lR%U#ELe;lo2(JxDDGS9bhcRuyC zEYgbh^oADq-lfXU$N`Rb$H6u&#D*Q4+?+kjs`oPv4YhVuv@c!7SzXz+Znxkb^|qbG znBwEriYBc?3d{XMT+qF)WV@1V1B~6we*QiQ8YHN(l=}^U4f67?Tw4|0Fx>heAAV=Mocd3Lf z#X`qGMRd<9&eSnqSgpM~PG`HRnX=`m`l9lAg`b64_&d?QQRP~gN(+BiJ8OR%`UO$( z<&Y{)O!Ylh+yK6-^~~GW)UJ76O}(`}q`)j3D}{J)IJbN4^ZMR+g`)wEkJxW$^?czR zck+oJ<@bk(wS+MP72#GguWJr-vPx5RuVw3y0<*B?Q@ff|)~x??rrJNXMyQ{o01D@8&I%nF~!*opm2nGN5l99^DMct^(8 z7rs{8`wlmauCG#SWl@C@RA4)%w@W2Pn8n+ctHfDFLJG{n--%w^Hk)WB6@Fg5H9vdk z7eod2E_xE4IMLj`8l}d^h838_uB7ZD$}?FZUduMZ^t!Rx&G_8l(C@(>n(RBtb1J;j z^j7BZICE*%7`JEfwbM$&`(&;eMR!gOCEVa3rF!{kth< zUH`34^tNv$Mo_`tob0~I^HL$6>Gq1L)AbqW_ZB~e6qtoqfym+tub3`{Pg|zmWr-0~ zux~EAdirzf(`P4{eqHX%-?wE}sKBi7)xEU6wn@8ELGPhASjF4LIAgP2^xjmls~mg9 zaUZ<5vy{^`CM9@F_Sd%JX6wT^{mpL`6h=adJtZA>f%8{CwyhWDL8DH(^P;jL1$)n> zXRX*#%IQ`vC3s^pC{CDiNuBh7S!ESQP{FQp>>KB=er%3<=&pFJvrc{?tiY_v@0W5a z)=CN9vCP?b&uv(UQ0f8>tr3Q7sZtfDKIP3sc7e}P3J)? zp7hS^g>LSI7su)8qw_0_pn@IL*z3t({Wvvvv2&&T6rFca=8yuj${de&BpriSSZPvp>WgkkRAAQOp3zR8H7V8+{5dzIz^p^5QO=c7bROROs4ll$b?p3L{m;*{ zBt}rt=uUBmJ>C43qCL<2uFBep`o-aiAq8gTS`_6p%9LV_yUXv24u6na56jVBmyOCP zF@g&Ah-0rfzF*P2{ZLumZe*;U^>Q5x6`1vo73Iuda?$duMGm!mq~^{opqJHsUZ3e4 z<$OFd#rpF6I;&)ZDCgXiR4a&frcW|dgw^l$o}tkU}xz4%Z`XK01XR-rG} zSn*Ct=bN6Fy{DqD8b&#js$8)u4CYziciY~TD=$t~x9AO4zwA*?lPs64wMExjH7}NQ z9<9D)-AY|!ot+uwyxaYYfWODQMpsB z<9*gy&zVxr&OcME>0TYc>h^U^?BcR|z|%bxMo@v{m=N1?mo(PKSbb*u%OM43;W$S7 zU)`*0w$CZ0Mb;!W^g=1;@QVkXI;^&R)ZcZ=@`Ec z%V?H#Yp=h0*f}(c;`oSHgr00!Ka}PFCCJo=JLHcUt>SNP$_; zq((ba+ND~Vy*KXrc3gM=PO7c@4$G+VY;*06c6uhIS$F2GweXyTcs}{4o8?S-ee|0W z8Y8GUMx)Q}LYJ+FO}LfhteDZhF40cLZ?AgKXLv==KNsyxn0VDHzm$K$jW54dAoB4-65s8#t16H=dq^PCRK2p(6@eSMlMQG zPW&sW*0;IWS&gelIVVb`S&OHvwRZm+<#zHXaleb9!Fv2u01I&^Ng>Rfg}NP$_{ z|ApxC=$wkVn@xZELT!y>6rNLfyehF|jcQ)*Y5jKP1{x!%!1JT`QKOow)_F?m#O(D$ z3e1{*H_B;OHqF{d?}vpbcJLiJW7Z2g@v_tyK}A~EXy@}jX;wK}!xCa)kuv(oU8T?d z=P89FGLEP?f(!9Yn`iaS=?(O=Z_iU0K}C4nT~_g~s_<85J+Ni%kOH&t-bHQq{1G)^ zUKjoIPwN#%P*E;dw3Deos`blo9^1Q)8RWLmBXsqj$A@MzI7bQha})iMbF&rk?YsIb zjGzMN67+_*(oc5%IwSPD3tK{pP}YQKr$&=htJe_zR!zQ5lBK>Fuj>>ZpaeuvfwK>K zqTdv+PDBsZ)0=G#DKIO1=9!kxQ-_KS*Ud+CP#8f4&OT@@Jo_iAXv2Z}<1>vz3e3W* zPNV2QJFM8QpC~zVSm-{8_de`tLd?5c$2~dYl4_r&d#FdD0!KT#R)7ECH0_W}XYSiB zq`)j}$Fz%i?(%N`&Smt4f2`2RfC?OgX{YpcFF8{lRMR8gs1;IRR=9uMTVz?AhE-Gl zZ^f%s`6g(LpdviW*tcnhyXe{;^<4AbAq8gPISEm`@fLUF zgk5T6>z6e~P_bcRl+$}M-9Nm#jQKyEaI5}(O1(R`MM!~J;gPy;n~3?RNGaVZDm-Vv zSqi*#_t(TxbJoI-+fm!(5ki$`d#qN!mm-M&W zQWQo|fxVeLq~E>ljD6TbXL>KcMg?YtfAeBpV(hGYI_vkYXVw@&1@>loDvJ3?<{sTp zCtfQNQeYO2$J7V^Y^q|jx7L|<9~Mg@+jRLfcKU$wPld0myfworjtI6EhI#|ee>{pTy{ihul~FoFu4kqdG8 zhik4l{U5z|WEq|D(iOYNS5cB{L}^xG(;Pzb%%WwHY|g3E`MtlXwde2e<}E#6&3-gg zzwp&%`*jf|xx$QEw@vL=atmL(@+qfftNh;Iv|iHWU3Xp0@6`N*oi#>KfybtrqG4H` z)8%W(x~rz@6%VpH6W2c@`OObK7ufWC;Qfuqrn%3HKe*d3+*9|bGzgsses?^!5T{!{ zaNRLNH+fJq^sP`qXHAZ}*@83w?dmBvde;$Eu~4g!0<-9>9Xd{M=FQq?Gk?`cReTJL zpyK<*C7iiG-3sP#Hxn+n{AxhNh3KZ%|o2Ua%hGfGI@IOF;Ib7 z^!X0Of@9Rv1Hg+hZF@lQl-QY~^Oy*3NgKAmd1|bDzg140VS!aJN0bz0?e>lKVv*Sbv%jSSfDus74l zV7j~XuR6PARH&b$0(*fFP5-&z{P(q!^3Q9NLki5I(ZZqQc%uZZr1l){o>|t^I|fEj zfmeif9zJl#S+jnRcMMcu)}@BUosK7Oc&ijb+}Yd7-94_fO4>A5V+0l9YxVV~yPbWl z=Ew~lUI{5M3s*wuE!kW7%+q;krcX2nwm58w|IWE&w;EGQ`ZPy|=klA3*Q#r#IWU5X z592S}KVPA?>#Z70Xj8;|mN!<9Bboyhm^Jofs@?kUQqre66xI6_zgJ%OAesXssHoa5 z&E7h`l=Nwi@l{Ki$@LkCUS2Crf zPjhtKS=Q8ev5vOWUJfZRtJVt_ZM$2H^ht~Q@5Y*0xk~EqK6qJS1QoF{DYn>EO8PX% z`-Li+xwC3(W;0NMS+v@1(>jp!*^CWcGngMH7tzdS;BSEUKD=&1)Vi9(d{924W;O#O zs2Eu2vVEy%wDj4Ghb_vOP3yC0W;0NMS$N%OZ2z;mc`k9kVm1RKsCYUl&5qt1EqylQ z(?$vAWQ{-6Q^aPV0<-YC(J^+nGW%|?NaT6snODBGv1im-Ml#CYsG8^DliLw8(L3%eXv>h?Ks7321ZbE<64S6>SDC? z*^IRD{Y>0kS23G`3e2Ln3^uKRNuSMV)wjQKE9_RxW?%#r^v=Mh6)@?u8Aqlo({tnj zm)VTp^QYQnb45#LGrn7xYCGAYC9@gzj-}WycZiZcn~~v8SrfJFu*+-)Mo>}r`&4`G zswnBR8L$1A&m8~kmOGQ!3{+s&(n+cIiUv{AXEUZ2X=>gdTGU)1Hsi{FFWToR!fXbu z8QZi{A$i@H*1>IhQkDK%_~`MK%@->(dTa(BqsvDr_SsHRlGzMAKOs8&x0adRD!a#K zU<4Jz<5TSWt)isQW{my3mHDf}1((?jRA5&1ohkN)OwrP3GvXIEFu6r8J*vJ$IYF;t6PWI49qI~W15}6K$K)QBdmBZX|vn5 z(KwIIzz8ZHy`E-gDIFz!He+}Z+8y@DESK2~RA3gi7+SyDe%npFaM1mW*bI!I;x4tT z1=MPZY+n0qy31?^w(#6#)9eLzqa?E#_(`-*{mFmK z))i&l&BSJ41QppAU9uN_7A1W)x^SA?ccf6vW}pJIuq{wE)x54|)`WX5vl-apu-{<|B~owAAX9ixvde4+Mo=+o zLW&)8HA?zyMy}C=P4U=WF0&b^z$|*FX4C4F^xvy3x;@cU+P+dUn?Y|4ZCXu}{N|9} zQrfh7C;3e!j&?!}{BxptyZHvWhS&^@pkiZkiXDAATKa6pof)IezB@hDF=8`Nfmz{E zwBYQqCTejvm)Q*bzW5FC{K(O>^?1{9*ldT{42+-xk45cQdS5%JvzgcYe54z(85ltY-bIC2 z^kag#^7>~Evl*zsEbJ>p%VtS1lkd)w%w}K&6?mT~`m9!I^KHw+)@@=lP=Q(4SA-Z= zxVRbArIlhf10$%wISN%xZvV?|FQzGGGf;t9*t^IV`N}D`*qIZG*$j-J0_R$^CKFxJ zoO!jjW;TQB7i_9ZkX*xnGd-#~u&I(j`qc?{%Ez1Qql@dU#AaXw6*!j=BC1>`lX6OE zW;0NMSyY)|Qze1)s}uh1+R5}u68d*yGcbY*oPE%>>et!4J?)`lHUkxyMU@FQRT4j5s!!~CPh}xC10$#i_rbV3gG|{o^jtt}1}ZR%Dids~B#?e}LTb&XX6w?TrU9`T zIJ2O4**3kcmi#^&$1ZvcP^7!rJNKc>Yz9V9L2uh_dOI%tH|`%_9c&8hcU@*PP=Q%E z+7TsW4Ka6><1(9p5mZpsfK6}trC&L4q0mtC+Gn4+%x0hhvv5=*-g(PVLlp`xS0`Wu z6;%CTQ?-KhDEgx{n}G_$r}(9kCfy$7heeR>5maR3&Ruou6bjprUP7Fd_qDGgna!YTc$;eQy!9liQ?#jG(HmpvO`N^VEj(g`K1gf^MyQ(2 zrn)Q16>a!QR1f!k8+YlIaXOCJ42+;6*Y(frrKI-RjGw+O;htDL(PJ}Efm!(me_@yH zQbqb~Mrzbe=lH*qJT?O(sGu4$o2ta5Uq=?5ai86=#w*$-HUkxy)%<|5pXyOX`fSG5 z_dl?v_It%+GeTL1cG*;~CbnL4&k|q|zCfY(Wk3o!v zO_jyo+S`IFGwiDGS<+`S4yGjRQ%9!hJF6~NU(DEe21cO^UjwmcBn0nhJ;!>Dqd=kXjl4HOP{njnqRrsmgUr28?+87FzeTG zGwsU#q}O_cD3@EhpUr++myR^o7(qp(K%zbTww69=@mG;Jch$0jx^2%!Aq8d?&y{GO zd!(gLS}c97le?$-3wlkv+8QI{$Mm*OOpldJTHvwi4exiO+?HMI>4z^St$c1osI{Xa+)7f9 z^>Ul%%cf(Sw+<;V3)`^}g=$TA*EcSw8%?Sa>b0oAYe;pL2_Lw9r?k~ST|B4ovoH%= zJ~@C*{=jWrt+$?Ye6_*|D)6ccQDI8~ld`b69!FL8#E9BNetL6}cGLUVf79PgUEps+ zE=r?6b4Tex`Uvp`#GcwjntF2_yyJv_kHj34%!;aw6tfxFi-@zeiMRFUbJ+4}O{Vi0 z^L3{;RR&@+FoKHb7xlC6XOBpq&A8Wbpc&BTTg7Y!v5q#;jNUyJTYgwkebPYF?At?% z*$j-J0(%#+88e2MYx5jchu92MU>1H`s`vTxoZEe9PyJklqM>Vr*9WgO`5Qd*lt~`a zK`;9$pTY<#u;tUU!QuR7QH2(I5s?}4Kt%yUli5vCiJ9ri7 zE!o=6rv0%@nz;##prTWgzIKH-BGTt3PV{MQ9&LJBe?;5_DliMj64&YpaQePXTI`!B{TKaI@%#_0wbs(4%sG#IGFGD zJy+DsXxB(HH-QSw!hSQ>e#c>woEY2SiG@jWBFYuh}Bx8!X!Bn<(g@7CdrAC^qyFlBu}3wGD)7^o5|^q zNOB^|HPhr6VUj$3l)z7-CrBd6i75AIa*UvYNpd2;gC`ay$%!cUo>)+USxk}>>lr+; zFiB2Cx%b3^5mYcq{^S>AlAMTgk0wV2W-&=lByI4-!X!Bn<=ztuW-&>g-ul7{Cdr8? z_h@pApn^$qBEN$t7ADDwDEFRNP=Q%Yk`tjDJh3oIPDHu)#DWo2FiD=?gK75*BFTv; zS4@+m0<*%cgh_HD$`#Y(7(oS--V9Pk(l%dzbZO)_3uXk*a9_Slw?)ah{i0>GLT3HSrn}Ik`Ad=}&9uA2U?Y z7{RN6pG5mDwP~X^rpD-u6J_WasKE218pzUdYRs8@I-$8YhkN|3FpKW()|2O`MVoV~ zomYNVdmHuPdE(;;DzFFBE|$g4%ZnX$sK0Uz4Jj}SM+vI_?2@GBe%3=45*+vgZ1PI@`nM7RPM8b^p-_4LJG{naYYCweu@0mO#Lzo zOzfREOJ(Ah7&&h)N;4cQ{rO4=CVq+h)lB_j1QksD63Z6MMNdDwPwmOoQh(Rgn=L*5 zEX)eGt2R|nD0fL~y)Eew&z2syI8-q4OUz<07ybD1kE+ke4tiy+?I8tbVVf3$Dev^B zRNhx0{n?V9otRVgof1jTX@{^X+6Mt zvT8ujYBK#<4I|iB!mXY6W}rP9yeE28U>5J$@MN8Vccn;wHsGBo(pNv|Il+Q82lzdB zkBRh^3B01%NLcCPqGi93g z^qyESf(q=LLNFsttgvQIm|5WT)l+7~i9z;L*9Wh(5M@X8 zP+Lol^PX5Rf(jfT={btHaN@%?v*D<~tne?$lsD1dnx9zkS~2CFzCw#vf$H0d@+R8b zdt$)|Dwy&nDm!>$Val6mZ_T7PDliN0KD0tllsD1d-V+N(P{EXU`YJcoSrX+yY6AKws&@tsrw6{lkV+0krMg?Xu6U8Te(wix7qP-21-WWjzQ{L%s#;J0dC~u;@4U^uez$~V`(<}Dq zu11tM(cUhT-b{HDH6oexX3CpLO39=*Q{Kd%NT2j(%A06!!=yJ;-b5NoCcT;RCbmQ} z>CKckF(=X|y_xbR+S?<&nery~N;2uqly^GK!IU@EK1-kUX3CprZ-+^5ro4&vluUXv zGG7 z_V!3`jG%%kZ(@3-PkJ-uO|-X1dZPlfnDQplSo)+lQ{F^-d!#phUmWf5{Dff2n`m#3 z^u`D(a2%tWJEFXa_Et=KqXM&-@+OK)`lL5g-b8yVCcW`&nerx5Ofu<>=S0tgM0peK zt(f%22r8KJCMHk%q&HLEM0 z-b{HD?d_4?7(oRdTL`ASiT3tLZ&Y9w)r(u{JQnTBMU*$u-X7_V5mbcFgPCn&w_WD8 zndT;TQ!>%blsA#sl1Xo7wuu{+KDW)xHnH0-bK4j}1vA@3WlNviW@ek%ZI`)iRA3hN zW+9l_CU)CpZW~7&=Fo}6mdv7uN1r|Wgx=Tegj>B-eT@-R;5VeZ+7J1(zP8fMdb2@D zfmzIK6A>tVZhLI!yn34M<|giKrZIvFyoTh@Nt8Fy-VT%AsK6|yyoq0wKIzSrH__gP zNpBpHaYV%tTnMJTiS{;3dSe6?;c=HKZ=$_jCcROCS$HQBf+=sJy6RjzI(wix7 zqP-m^y)l9coJ)`cF;U(`d%H|}qXM(SXU>#2(cUhT-WWjz&LxCk%A06!mq~9_U>06= zsx~Cbn`m#FNpI{qc<;lWM(>J<@+R8bBfT+#3LNc-s3OXnXm81+H!3g-+p!Q#c@yoe znDoX7DsT*@Jxq!6CfZvv>5U4^3il7DyovUXm5}7#t15?j?_x$V1;1Hn`m#3^hO0{g-2?pyovVqNN=1o z;H(DkkF-ZTQQky*d!#o;P=WVgT45o|n`m#vq&F%s3x6BheJ|!EO|-XS(i^zvCRK{LN7DrO|-X1dNbusG=jyX zH@9wXzf5|E6-<&7QLdOKXOf(1r!A(*dFI0N6sF1fxO{wn&zkjB>*<^Ap3x^RZd91X z^Q`n;b;i0SUKTmw9U9sy(I}6_|zJRtP5IiH!G% zb&Q}Q{F{GB)IHJn>MoJ@AqBK0YzwsFMSB6zo&er{02sl~#WqH}4lT;8pZVc=y&-E} zjc1Et z`x-p%MX11Wo;<^Ly{5igxlt7f` zRA3gf&crEOKJUz|GcnH|?~D;tFzZZQtmX60%sLbE?D5X1z$|8+iEIws>zH*W=Go(& zF@g$aor!V{-0PTiCg$1Wol${V%sLaN95~A{>rBkE$2(&L70fylK@#lC$*eOm&mQlL z3e4g)UtSIId1q#wiFx*TXZ#JY&*OEYowD4= zn1$DkC^}-DiFww{J7WYD%sLZiWcj=^v(CgkYv!F%fmxyJCYW_5=2rBkEX5JYis9@HaC@#zAotbqe=2W}S(0vzT{g z)|qHDi+N{eorxi~eBPN^XJVc;^UfGS1+&gXZdyL?%&app&zgB>RA3gf&P1A8KJUz| zGcnJad1q#wiMOsHVAh$K zXU$%87(oTI&cr5LKJUz|GcnJad1q8$7PHPoBU(Q1%&app&zimHFoFtZorz|)eBPN^ zXJVc;d(oi+v+#-#T|=z%mS(pkd(q)6j9F)5lP%_*@!mz1fW$h#dv3B~-WemPVAh$q zSj*>~nRO=SSuyX7S~!`lP#ZjX4aXQXT`iTDliLM z40-Sn>rBkEV%`}es9@HaXlBdjotbqe=2-iFww{JLC7oZ;0ndwQ9sV6Z5Q@cg6@R@YwYJgIH%` zo;CB%sK6{7m1su?Vx5V3*33I&1QmGqp}jwebtdLnGw+NF%)(wkdm9q#Ow6-p-WemP zz`H1UP7>=(%(G_R85Nj?eMJanor!tY%sXQQ6?mT)f>~!`o;CB%sK6}jD?%{qOw6-p z-WemPz&Q%lUlHp}%(KTkqXM(AchQcd#5xo6?D5VRK?TmW=snJ>wKXx%9`DR=@zeKg z$C)0#pXc}KKJUz|GcnH|?~D;t;9NooW}S(7_IPJhU>3ih=lAJ8@64<-G0z_F9E!kv z2WKDD2Z?ni=2YoIo|sZ70f^r-{*PM(K@dBI3d~}1nMmWn zS&nISqSjp|*73JxLY;U^&p{B|f)Grr6SeL#v5pZ`Fs)8}XW%BtR58)T?hUHbM+Iha z1tM41`7AP%%S15K47NYJt2~aNf@|-%qAqZ+OBtcJez?(%TQy2z1QlFSJn0M9>i#e9 zd;aN|@%pE%1KsZnt_&$KD}1d+*PE!{-jU$eIQO2!2r8KJCVDn-;bShm{tp+O1oG`e z1!m#zM0;RwAFT6ddP{Zdm!z1dCicqnyJJp<>)N^HlaG;n;u%KXPAc8oiR+xXhL_jd z$mdC>`^1rhlYHX(h6;?Jf~%I(9p^lUJeBUL$Cb)lf6T|=3TCeQ4LtQESLgcNHuJm0 z@p=p|*O#Y9u$5qYqd5Z+*y)~ncnnl?oikT5`|F8Z+n(-Zh7nYRkHG{sk=S0%HYzZS ztK^@!@G-ee1hYpk<9EknU>g&H>1d*)6%*1JK?So0TxIM#vK3Cvr~8arpsJ2f2q`cN z+ZZ`|epp%$IPr=4?QVIEZK>W~;#pc5?{mZLYDMF!I_t+@s7&*UYmA@*M*+HsbdI#&)ccJNhelCU%+6a?=HHm^)mZh%jyh|xOKSD&GeQc? z!ZDx7usTKbhALvTPkRbpaQQny}LW#RBvf`)N>g_ z1!mzl6e2FQi{3x#JI`edBdB1eh^xu{eQU|9QKfq|VqarQj|l?4zhd7M;_EXzRPH5b zrTcIQ`>Q?f&!}K7oG8%1g|F`IoO<})7gfIco+I011!j?pnoM_nBo6Yx)4D+2x+<-X z=e+nhf(qusi8>8j_(q&4sGBscr|x!d#2#*s6_~|bIB}SP3*W3^FX#=sI;e}Ssd@(@ z%!Lz4>ACRXCs8fV(t7%hoFmjT&5DJNfePlriIEIk_&$8ClWx3tzM50d^ND->tuQM* zioV*qhrYCaj`}n45c|YE9$!(xTsV=ffeT;r{q&|bX}(%ie0xZNSvZ1+M^PL(an#09 z!gJwM=`MU2K?Sx2s(PuOO@G$0r{}_l3e3V*DMZ~5%IV6qt17$jVFVT7-($_bwz~DX z_r3ms3d{<(_Ksim)|Cfs_4)@!P=Qxn2&TM=_Et=KGZ)GfD9;D+J{Z2bOnDRS?Qs*> zCzydvcU8uAOg)MyZ=$_5linCX1ykO{TL&(DOkfjsN=s@f_G3bi>|Nv_nWw!z(ImUh^>bc@3d~|&m?>cY`D17Miu$?Ub@ld|KS{ibcy+PQ zlc#t7ih9htx_Wh?pCm?5!DKG;w*D;qqf<)1b)bx%G5=0Tfm!$siB}s^Pv_Y7oZi;s zp~MI(m?~x>*ngUMzfLRt+kt#~?);nz6_^!1^OW+F^-*=*Vo$vuf5gi<{W5!R+=_it zPwpR@+3Q{PPQ}Z@MKc8N?#g~MQMc>)tHYjp7(vCT&GqDe3Si&p2A&%`wg0O{4`XFpE6a zPhFHH%wZf0<)|^@$$^%`w?C#79ww& z) zA<_aPsK~!CRzBb8cEn#{IdJ=$>fNn}`ISfuRAAORJ5Iina696!h3CkBOkID_-|((= z7(vCD8L=|D=Iw~TQuOuUZ&kBg0}YcFsKBiJAH>OJ6>dlT_iFF|`?cEj)F8v81x8RY zDk)Z8t9U!&uXuGE^l-F5>a>WHEB9TGFlljWah$9$ z?P`Qci>=qJs`rBBsK%jw)4O7a$u2L z5oR;+oT#$@R(<_q(^!|;42+ne4;7fTe;WNZKcA2I zY(|%5nc&e41lO>AUjHtlxMv2P!bDAB-4O<-LBq9A3VfVVVO+ zH9V*A2$$hp9koASNwcDI1C0?>;Q0v=pK-ZrFsy)K7d}*A*3)g`<+=B+MSPkg!-kV; zUYD$<53v~-LB-B(@v?vA8xfz)=$GSl*{=E&kIld_9LHcB^J(?`zZq51sZk!Afe}=M zN9z3DW~e2&t~MV)lMI}B}_G9 zGq7*t93|Y(3n;BKTrO#t&AQe{d~ zR+rffoG0Ln1J6l_@?ZB;uRF2MN@6oGf{O6Gr2Kmq)W8{A9CqPD1!mzn3DNKQd+JoJ zB{sY8VFVS+pHGk#htvJTbKyH>71Ym9c`=z?_)vja;gLGuv*Yxe@6MN<$%PN+3^=pE z`y+7^dq(L$r#5w7=(0j#1QmD>CK~Wq7hN|p(q%RS6_|y;4e>aWn(3rDU%Sj^U<4J| zH_3r`Oc_0U_C1%`3{+rN_%}C`i|H-D7c!fO&AtydM=aeTdCK1!m!R zOtl}gepB7f)Ha!k&An;^Zo|XmbtoHnAC~z%0B=P;2k`iu&y5=B6*P85ltY zj;J)k<-R3t-PSOhfeOsR`8>V(Nf{vb>At1{u^AXa1iVhP5A74T$srHE6)HO2Xe6tj92(=# zuNoG5RyRngX}5Wn9P&VcSqJJil4phvjq&^W#7EWj-ht~aJ_bfm5gad=!*#z{K*x7} zXz?*nfmy+^gR$gX{n2_`_Y|39%{*1*a3guAd4F#%it|#OKT>P|v9Eq-`A729k<+2M zC>{epNr=9ydg)nq4Y{W9rO+`@f#*cK2!1e9U(EfrwR-0IkOH%Mw{0v}Wgiyfzs)#% zs+X=le7()bzz8aW;{`3T%G8m%=$;x59|IMb6`V)1e~jCI^wg0aTOBwLFM%4ai{4C50u5@sW;YZrklZ^6fmKc{|R?@wy4olltKCKD%U0pE4RFs0iN; zUZB>#b=FjQl3F_|Fe}_jy57p9J71V4XFutKUi(1>-hF5#_1W);+UIw6?fv_^9J% zcHzU%!mOkg4dv{#Au;|N-ryJ(9|I$(!1EL0Lha%z_RpFY9|IMb6&%}J*PthQ{f1gP z;t#9r*0Jf|%8Q^Pe67;nI4`^Ao@ucQAAS~Q;o6B1SIZ37?;gtIvI`%!IBbb8|C}Iu zmbjhlQz>T~_0tJ&eeSReA4X8InN|&SiEGI|l~VHZXkBmeNoOp%@Sy^;{`*#fY?|~a z*{4$awjQSEMJCui$%PLisF+6U8cjCbOZKUhY=y_^Nng!#*o6-jnANpUf~@sc2HSVx z`+46eUCL@M*@X`ysMt)aIDf?m+jrsnd(i~lqZSLmTIf{OaI>KrMW!S-GFdR3aNueJWtelVd@NP$^JZ^X+iZ8O`x)8Dd+ zlXZ>QG@E_q8Y8v>??XJ+2>f6pP+q; zUK**g5yyfG%)%>8PRc!-=-jJ6R}Y9|!K}ik<7J)scaoW72`dH^X|D5U`N8w;!w4#_ z(%RB99quLj9E$;2P7CHox9p%)@*<_obN$AS@5yiF^@6&L-J>~ky^ijR_Q z-jn)u;#g3DSzT!bY3Q7*$v(%j_GDI-GGmH9PaMndmmA3c?!KAK980jSk<4q;!Es}tmf)P}dr}gVjaW|5Ej-|w| z>1uzQM2}-Z1!i?S6(^s%b1T{BSlZCL6?^O`k7L0IDthIPllybtO!hgJf3{~xIZM4U+V2i_khb@$d^)UxjmPh?Pjs+vAD7+(1zE$&fvd^*fIQFfY|Dd18 zv7iF8g0-w<|J_}^mRiqR8RKy*!P;9gznu)$`jYu=D2{gIwRKACBezTG)x@!21Qm0J z#>)>^+)oZTmLJ>cn46jP_r$TF0<*%S==riw>A$D8_c#{(zW5FC{AkzH&M`Xo@rcK< zU<4I-Y}zklK}J2LdJ~UhK?P>vs3b(I)g^W8z=|Hnf)P~U-G}z4Zu&?S*jP*VCXNLa zm=)>;;`?1i^^gjMb$8-eFoFuaiwZIH?K>(awV21Tpdyq7eTAs4I)(J3_x@GPv0%SL z1>Wa{kfm;@w;ueVZV|_V3e3X3LY4ig`Ss4E#hz~;Mo@us6xx|$-9y!6K~9fjK?P=E z?-JrSRZvfzV@24v4*n9( z7V_=G2r6(cA;f2!M(d78Cn)yqLj`69l?t}cv7{~>t*^A5q<$mcK8&COXCJi6nQydi zw=&7|?L!4-1(gc6&#_EcF-k9dZidQA91BKJ5$=N%O83)4OCI)o`%r;dL8U^nUjdQ( zh_ zRA3g4c0>biKd9_Y13iufBd7?f2$KEkgv268RNbuuJdOnwn1!Pfc_R505E?2Vyzvzk zK{Z6OUu99Pd3N1ke+QjF91DIHX5rW+grWTgOy^jSW5Eb2f~t;Wzgpy<<5XV~Us~5E zjs+E%g`+l&aFJMg0)F1(STKT$@NeGc{aF2R{pUT71r?Zu<2==0J!r3cE`Q47STKSL zY-4nF$pM3$Fbun31hsrNx22#e(B|4&cEBKS0NeNNV+Ra!!Z7TDfe}=&0|xDVZ~MM| z?0`W|7=~RiP=Q(OfI<7~+rDofJ7AC#hRZG(?0`W#;oI!n7gRLbyvh~S$$4Xp5bS_K zP8cq`U|=Mu>$16`4L^z28OQ;HoG?rS^6kS2D%b&o94l-<0fU?{43jUI z71YDoTxSqUoe6ScEBLV3fuSXV+Ra!!Y~bq%|Hcau>%IVFxb9tA3I=> z6NX7XzfEEU6+sQ89Z)IcfI&_ehFvgFfmz{J!VVbZgkhL`!3ZjXnoHZS%wz`)a>6j| zf`JOm!WK$vWOX{}adX&@xv#uc zJiS`oX3hg!KDIZibh=VQ_dn9h&Gv73jS*}yL8Y|!NkZ%@^PC<$qoq4woD3ZU71$PN z|B@G<)<;ikcSzI6mHpmlVOID&Zddw6Ev%ixozbvQI&a{eAu4dR6C!o#4%MdCS?5m9 zp&!{stx*so?5mI0lj={7)+`%q-NbB$1!u!`K><2;Ry7#$3-FxtR1SFEfevsJW0dKJcX!tQHuMXk zf}K@p*MB>1z$#ip?wPl(u3huIJN4G~kOH%CtR%NhpS$x$9~=#Ed<^%fYzyZw&Eb51 zXmqH5paOqc+NGdt4t=spQ}clAa z$sp$in`{09($|~s1az*Q>yt0(_h1JMa>CH;f`NS^V3ED~9JXU2*a3r_FciCBU<4KH zfI(gqw(r}=4jANw;raFjl&N=5#daK4umc7;VR*iM7(oU074n<7Gf2nE*s>w;duk%?-B64 z-kb`rH0@ePE*s>wq1YP`BdB1P4RXb>eQ!W^*&w$K#ZDWjz$_ez$iuYIfNmw+)BA0a1Zj z;j7Co8|1cOnEwcN)$ra_1^aV&eUM!?Xm9u6Eg8FPklTh~{sSW+g};kOu=>F+8|1cO znEyaUus?^F73_o&yfI;y4RYHs1Bm~?2r7b|H-gmqmnU|)ma9Sgf` zklTh~{sSYZ2zK5GRzKKfgWNU@^B<_dtY8-g+vh*nWrN%{3_ERL1Qo%~3%0-d!7dx* zw&C#~sKBgXHwoM4KiFl1+%`P^10$#ic95|BCwg|-Ah!*V|3C$19j2Y}X!mK`=ReqG zgWNU@J8fVD6~Rszw!bpLE*s>wVc2N{6_^$5ykYxm$iXfi9{+(6R0KPE*!~I&yKIo# zhR1)P0<(f$N^Jjq6uWGY+lI$~U<4Jx&Lp}AcG;jk(QTjqV3!SY z+wk}gjG!XeVa2;&(Y&2pHpp$m<3CV=S;3Ajw$FdC%Lch^c>D*uY|yT~HuE3svO#;_ z+suEk%LeWLYy12MyKIo#hUc`wE*rGdyUqLuyKKwVVJaFmkruw+GeK>cG)2B44a)c*kyxuhPHj0gIzYrZNm(Bx`)CDDsUVV zf?YPqZNr?|{&GlxSvV?DMI*UvklTh~nuA?7Xyo(i^4bFj+>xosGxIZ%OF?6N^l54KNpu*(LyZ5XCG@cZIuhgXE2 zgvn)t+%^o;92h|bj$^drJGpF-+lFDM4OCzjyKK-d+O|(~u*(LyZ5Vdiz_VqS4ce*O zW|{-fNeFh?Ah!*}GzUgd!7dxL!@2F#9PF||ZX1Sa4pd-P!LMldy|gQ~Pjj%#2Dxn* zra6NBUcI>}UQu@0p#6VspXOkf4RYHs4$&MKK?NS0Y9`2KgWNU@(;TS4tYD{7JD@pe z4^wj6Fidk`1Qp@)V3!SY+wj?X_?FYzDh*klTjG zW?%#r?6N^V8n(}7u*(LyZFp=3Dlm&ZbJBaW5bUx+ZW|t(fg=vPY>;<`&Adr?^kJ6` za@#QMw1E*+;5Q^zhFmttZNsqB1}ZR%T{dVJb=zk%*kyyw;n5rzK?S>P(4O(OPjj%#2Dxn*cG|$cjWdpLKWCQ>a@+7|4ve4z z=MwaWms~c;ZNsqB1}Z{XOY>?ZAVVVOYsKCBS`!kTs2Dxn*ra4f7 zS>fNDT{g&V!?4o^Mo@u$lPUqpWrN%{3_ES00<&;Drank68|1cO*l8mafl&hcrV#A1 zL2es{oiXDliLY=R`q}%Lch^cupG_ zK?Tmpg6j|g24_LMZSu1nC1w)2OOSR1fB%m-_+X4WrN%{+}V$YYIfP6eQ+J7 zIRak*hg*2Cx4!o`t(TC00{JMo^PhMRco9_Kv8kqrJTu5U!(o~u*n!{SH$TCy``+Jp zY$Dvq5n=m$Ec?Z=t0TlO|_br(p^cs2r97U)9zxG3+a!FOLJh=`j7&%0!NhK z7-f2w)0avKla!JtG;hZlIbJv7iiQ@^gKl4RH+CqaF@lQl-QY~^O!`chgYL4v4MGac z3b&HO4Ns^Sx~_He?e45Gf(pF*&`#+eZBkP!*Dra0kOzo+t=q)V z$bkJ0d-G%e5BKbnQK5d03hV{s07l*)7%(AB5F))G( zydvaGdf<*+vwn|v3{+s&rG~|2$CEdLH@tWDc2c{?m3EUhjnx=IMfh5=zXL*G&j^Bq3)K!!!p*P{EEQmwHA!KFz_7B;-tDnC3tQ zX5n?Cy8$_pkTZ$Pt|S;i1v`?^Zs3kjbFd=`Ig_~TN`eZ^!s|w^3$&yBzB@f#-c_DG zK4=$qhxrKJcb@hYcDQCY@Njf|rhz?7$jiiK9~1ms_AsHn&mHDJ!pC3_6Y?@~*~bJU zs9+Bh+MV6;`49FmAukh`eN0e+S@>%T!5${$W#Y1r2}V$X=SMsad6zO6Y?@q>|??nCbWCK!~6$(n9wfs4)Y)EVM5*@j?aIv zhY5L^DE2YI2rAgagd7|=ro%wi7{a*%L*{(~J!$eF~WIZ(llB;+&V zFwKGAmiD8??xzl~ zlH(Z6jw|H);4rO1RWIZNL4FX5y&y1xitsVm!-Tv{JpKa}n8mIq|BtToj=Q3|zWykP zU_lfN7C;dcu%TcBX3haM3Rtj9QDYYsMeHROf?$g!)~JZFq}V%AnK{Q;LB*Qb3l{9X zqfy_r&YXLmHTiwsKk~^Vd#^ip=1$qO_x_%Zxh7RjjBJTHDa-n9fiY2wDs-Q+>>rqV zg6SuL7|}SIQ%^9Zq#`lWjH$1~)DuiUDLDB=Evn$u6HLgcYGQ;_PcZ!?Og>RBPCdaa zlZwPhQ^Bbxn0^w75w)m-Q%^9Zq^gM#PCdc&lQ8*273!tuSe9|>38tTf$tP-21*e{1 zu1QrBBb<7I=_iJhPgJ2^&2yJiPcZ$&aPo;>6P$X2nF8O3a*cSN85ED+TDEomkCBKs?cqt;*R+um@{HH zV?-6|rS}-Td11Z?=8P1aF`^b#=#zofr3n^uMhs_+s6xH;e9JP<7r~s7Ih-+~7FFmI z4!;NHi(t-3!5Jf}P%k|zvyAgaFlVG9o1qp}=rcIWI9~*FMoP{YQH6TxS(#;=FM>HE zjx$Eoq6&>T&^3wqBA7GcKKaXphC;pcJkB!C7r~qnM>az(s?f*@IT_3s!JH9KHiPp; z(3Mb;&Cs}w^F`1}P}OV(=Zj#@h`$MJhFVmi&-pCld=bnU@nkbppWcmJ`V>VK0P{sKXT)&Eh+0&^`68%} zS9Qgm^F=Uc#Bj!lD%4Bw7@&kOUj%bT3}=j}MHQScf+~MicMfpA2@#sB=~m@k4kBNb@g`Q)`WnjJt=8S|HBb+I6^jGVKbBQxW(C1f?&EVV-%!#OKHiOeCFr~tCLWNpX z!ATWZoxiHt3{I!OlnT!Y6{=7#PN%@?{8i0nO#REFW}m$$`b)rOaE=JpwXeu#aMlQV z@IpR`6G_mo816Bs#Fdwsm8VSc^T1}Pg_BOucU6(i&`&}?+;cmbOFuu(ZwWR-Evn%B z6ig7QYBqxtNidltuoikvBW^f`2CX)m z73#%_B$ydc)ocbQl3+4PU^5zCm_mYnwTf&;Q^AQOm`vh1l|(I^ThdZ+A_*pBR5hFN zTg=SB?2N!>s6xFsWdpMhs+!H%Xxzr`l6EHrHbX6{;It5Q239qj(ZB0C?iGKGzZ-0Z zD%7iamT)2oCX)mU*F96LRK@3~yjAiyXcQCwYL?hzd^fKp(wh54~Dcq1SwtagqlndQ_x2RH0s+}i*q<2$Y5 z*O*>3wxJ3=7qX1gLNGPNb7F{omU`(?0O5v-B$!O%R@#1ls}@!0-7d>Giv=@T+`=x0 zHx%ln#|^7;E%u06bHQ-`(y1M-9v}UNdRNM_OP-!haki_1Gc&NBe^rwfPj@xutIL-5H*K+FL!n-895*8$cu*0}o-7-%Y+>#_dwIXs zu$zr&W%l;w&?k&qRKb}USfjqGNsCVgUSRs1c7UI>#%&FSdg+}n%Q$%mJeea) zruP!P+v!yRqUyK579B3X+Rf}crE#{aqIs5l{OrDFyDlC5@a=YNDAY^O<1AZglWFGK zQ3L$QlQwExwW`o#h{>c|-D(azd1wFXhYO8^RtXvRG~*5 zYiwa=24-h?&duP=3~-|%V$tVE^XPJB24-hCk`{VRaApSR*$|!Sd5l~JW@cb^hU44} zwWxwKGcZk}s!0pZ%)smn$GI7*P%l06k#)w*49w2(oSVU!8Q>qobDJ|WFnOV3H@{v5 znBj(*8JL~n??7k2T2!HDKB|3~nSt3EuGbDbhKV+HeXo2s1M*3t8r!q=3P|v+zigl!0Zfv z*{fZQT2!G|7mgKXW?*)P=iCfcs268ufEx~xEHbH>nSt3Eo^vzwDC*JGYaVl#Ff#+Q zGd$;Js6`c=nE^sK#Ec+#Ff#+QGd$;Js6xH;8{#>LnHiX!;W;-$Evn$m3^2qo-sQ{; z%+Bzfo1qHzYVJ8nauDT?G&#=jvUN@1S}9vk9FpW zAxRFR+>s_%g?f=B2YVUcSV)qCDEFkvNs@z-3~wyB&dXMuh_k0`UH_Pz1(F;@xhGAo z7VK@=`knQY@CFHz97K7b$XMAHJNe-esys@Z7 z75Ht+wqKAWIf(K=ldD3#NRor3jc+U@$w8EdHx~86SyHynzNUgCIf(K=ldDA)B*{U3 z$2S&|NcwwJlSMw|( zNe-es%u!T}DsU$%+wNB+$w8Dm(&Va8FFixCX3g-o+^U!D;Rl>F)sQ3ybr#-O5Vw`B zcV|4i%C@MFTzKnwjwf>2dSk(}y_ENavh|*jWq6yYT5l70(kF{5@CHz}y-oc86zYX{ zgR<@20Pi?e>#YcHLZ!Srm92Ltyzi84Z$*ejt5z(k7DNC^q1Swtkv#{49^P0~pjKkYj*~)n7ISm>R zTsZjfz=o?u739Lfjm9??a^c{^J=t(os23v6vh}`;tTVW9@Zp|pxLQ;}E*zX{d}ARO z4nEwI4OfMFkqZY^8Q)mQg@X_GWW&`$E*xBBcw^B|$})1{;KM!HaJ8s{TsVlw_{Q?m ziVwMeEi=YHvqy-j(;li<^X{|LhW~c%k{$gmQ=ec=o$gDjAQuj@HNLUj`Ps{E|08$v zGdH=dp-?Zq^I>(dK4(>}oQ&Q}^lqnDL3m@ST5l|BQHB1p;3iHPvfqZh=$|vi2jJh+paPZ-tY`9uf zK`tDGc6?(YvwhMJhj?<^s!%UI^U;9~4jDYMCyR`XVA;wvl06119Nt*;D#$W&$l#GZ zS!A`SLeG4hC1B6NpnJZt=+^aH=_i4s2j33P-Sdq_Evi5^vTVy)lE4Ou?fJ%{3iZ&ve`0dPI0*(O*!1H4^`zz~dWB|D*PHH?478cwNTHbH|@D{am%<<{MC44QHv^&vo2dXYh)%4 z{X=!uB`1eB7FDR1e#0!g;cwSgZ*O|CzZq{VYEcEU>SbGo{x^pWcAv~VA-u7uLcN-M zPRbj!cObn{+bqF9hAuW#Ny}E1l$1Bv!q^W-${VzIAidS13e-Q#wpuDFZ_wU>^j3v> zp&nU+K#aXnq`X0U2hv+DszCj-Y^$Y`@&@hgNP4S6y--~$!8OIsGg985y~CtGwWtF1 z&$6wSO3E9wcbN323iU!QtOWfOJ0M7TgZ6eLz15-$)W6EMS}G}T(B2g%{WTQgg_>Ro z`YH5iVB#$(Z_wTqC;h2KKNoepvaLQy${V!zFi!eYg?f?l2K`jkq&F#V(B6imw^~$z zdSuyF=OpC~+S`!yR)u<@{#k;T3VkP`mg=RJnk=e7UA1hh*OKxE?QJ;ePd`h&P%AFM zVTGRCEF5VS558%!3=zR=%QBdBXy#wj33iZ;vQkIeO z2JIb4Z&KbMw`|90J_Yd=(L3xAr4y3nQRH64Vbhm->2JP)gdaFXcNO^}yg}GhHR(;t8?<*Iz15-$-8QBuf$|3J9Y}9g zs294wOYk6(L?Y!~qA#4Jw^~%u+>h?ZW&Y|O|1g}}M}`_?bVZJul=rB?t5+nwNq>XG ztm?UaxB)!$53R2#n5v!W?Cgly<+rIOgC5_&Z^^U4{@GK+c4cgnT z_~&ztT2#@z?~?Kc?QJ->PZjE=Pa;g{2IURf+i-55T2w*G8_Z%=lisAfL3=xr-g<3o z#L>LYNqK|zt~j?(EvnF10(T!!-k`lplHRINFS6X=JFA-XCglyPZjE=M;+aUpu9nQ=bYQ8*MUC! z^twSE2b4Ex??8I1MHPCt15pLa8?<*t(pwekrROnbxPkHp?H%U!sYMlf55}}jP~M=u zE0W%-P_O3oLCPDnch0$e`qbC>LH7v+C@62x-huR1iz=E?1}SgQ-huR1g?i~eWf>`N z(B6UcR*NdoM_PiBiv%bsZ_wU>^j3v>HSg4h(pzH&jcWAyh&AFtd4u*2q_0_6?b+mQ5Diz@WmM1}>FH)wA|(pwekrB8`0 zBjpX++mQ5Diz@VviW~qaZ_wU`bNf`GUK*We87Xhj-gZ6A?Nf^?G$O~!^&po)Fb8@W zylVxnHbfI(Ei15)HT#VJ=YQ9$6p-=;?Hx#OQr_tMFG+gy?B@APFDlyjJL=JAM1KmU#(PA%~?h+ z9DI0S!$D_Opg_YL1m7h1MnO(ozb$C;R|k53NN0c9{+~Ctp`Y9QR?958ssH6az5IC6;aY6RF+%pKI- z&v9-tO@Oc-fLio(^&HEx+b?SGS9ozve_e;=tnRJGzWNQppW`gN z?8V>saYyyDYEeb=zMEkm?t1S>cgiVSG!*Kk*GiVn8}(Or{zlKZ@9K38(p97iz0YH2 z*gsEqkIcN@t+Lj^TtOfy)JvZwm@5OG8eDZ?s`aeaW2IL?V5;3^eycy*!+u_xPKIFYOaAzF2qg(6NV@Y8riz=G?LDm_}bKsp-p2)NRK`;k;SuLs{xeNj|POl@m z41zh(%c@W>lFOiu<77FK%OIEoy{r~hkX!~q64&JO~G2j8sV$xv3zB3?A8&MOKR{$RUH` zDr***95Q%hPZn7f4X?&8NDdi1vL}nIznUt@S%XF^>sfT(G3Jy~S6sDhbuzAM(;HaTSQ$et`RIb=|7C0S&0$e__mvdH9+K?IjIi%bp~JhCT? ztQJ*}Lk1&R)+{nPWbnwIEV3%piyShT&a!5aN&JHR_3vXA9m!r$xh3gdW={FOP6C+O zV7{-_Yk!hl2EpvF`ni2$8zh&(BbTI?b^o%A5|uq>8~1mo-^T4jDYMUwp{WhC;pch=8sE zRSdegdhhF#twv#_ia`OFB#ZUgg+5DA#h{BF$zrvrf>bdG)UqavNfm=GcAH@qoqCZf z1}j{WEN&`D6@xBzZ%segsznu~ia`OFHCarm7<94YEIL)Fm!2_MMyeQev3nP@=+vSL zQpMng%bF}ERSde=lPp$+dNt2PQpKQ)J;`D{!$}o`q%27m>nGuD0#q^RVo$PIEvg_@ z463rM$zoE)po`u3v-fBy)Ju;DrgMQR23_n(7OO=S%@~eUG3eqz7OO(N^jtvaG8lTW z^qw5Oo^g8J={b!lN?0ES>!f(Dk)jq=aIF+Dd1XC|j*Ku^VLua`uqxDxl_lnA>UD(I z2e}M_*^^#o?Tk4kGR~~kF^5HBS?_jPMsgVhvnRc*7FBRf3$ScuoJEI~FR%iJ=js=# zP_O1)boGn(G~LfW)^9$nuhH+T-%$4t{a2IEF6QlcyuY*eLbr|j2Uuq?&z`)q zewKRaT?y+mfOQ7*?8!T;MHTw=LB$=cGni*j-dPpurB?ygHU#So=Gl{XR*Ne1DVk+u zoxwbN^3JMIFTGZ>jI1-5XHVW)EvnGxe3p@Q2J`I6JF7yy^jgU>vd&Zg8O*aM z@2m>-VttkQ`ElXq5&Dw@|IS!XcMp1iXv)Qk0b*3)a=nXEIIXTJqz(P?DC ziY{xmqgLMY;+**x2-CtF~9st(tYu=fxGni*j-dR6Oz4YFd zWn`VfJbUuaYEcDy8Q6PJ^Uh?Q!908N&Z%EF03k-HQ%xc4AkE$9|hWRM$a$?U9DPxfL?@simZ1S+1b!8u; z7FDpTj=fpDV<6A4%|t(KvB%u1(*#KsgDy7Tpif^F>cyTucJ0+HGRb8S z%!pto7HUxidluQ-7pK>KG{xU^`}JnatBxwvq6+p0pY(t$_xg1fj@3QK9PeN4aEN)X z`^<(yy_(1B=n*IS%kSFCY_#z2g<4cW${X}-oWe&ge2W)9EVjbjK2@lf{!Ur8$8D2* z*LD}WJr9~{$Ww!h3iIyB$*@uofNiORMFf932czqfoV{M zdXchV?|Z!slFJ~N1HG)@UALj}_Y4F?nvhe|+4| zD10;HmmB@GD-P{w)uIZ$S7O!E6}IpS%L z)Xh3$dPAXJdd~+Lw%ICvN|(R8jZPfe*mFHTx;?OcpZE6<{^15U;l_2XT2!G&8nwIk zw(&P^{dAZzrV91aZeO+C+D z)bqB6LcR139ww8fyQtnd^{%aV3Gh)Doa0(k_|&2bJr~gRGPt9^ckDi43ZE*}OV7$I z8+z*iKXCb}VG5sGRMGrBu6}4|zvIH2!}XyG^=h8&V;|km4?OgyaDAvn6?)XOj9fVQ za7Q+rTqr3}#)JACY#v>5;o!pqX`$By8CbHgj9&FT#uWuF9DKMZ8?F{rkP8Pf9jEY- z3kM(W$%d;!z4Xk-T@+k6`0&7nla3_K$cTkpIOyUq=}oVKEF%{VK0L7DYEgxr`Cw(h zg@X?dq=jx>zm)rAR?;KIR&2hu_n>P23d6mb3iK`tD8cpxqG zDC*JGYaTPb!G(hl4{W$vR6#PAylowYlM4qQ9!LvSsF!}jEF%{VK0L7DYEcELViLji z+XT6A@Zo{9P=$Im_xzW6d-(&e+R$9L^e5&o>*v*xJGam8x$3)o`ru*JXJgvumwvb? zU-G8Ss-L@TlApfBkBCdg-Zb71Id7m_bL>y%jg^N~8*J6SJlhs9ppQWyvcla*Z$>YcWzphZ-0^R2#$KYmxoki&sv!C^SPaR8~A*~?Qk3T{G8k2 zHt_j5x5I7V^TT%P{TMN6JNtZ(F8;x4w7FpFYQ-7*zE$qha{<@wD_Xg%rSI=uoVmrD z@hufc*W&29cytRK-7+5C0!O!uN4LPyjr)P4YjJcV#tAoFlL5T>N{t{#EBcT{ovZx@*y4{J`pnVV~c3`taonMwrb(Q?x_cCczu z#k;o*sIuV``ca)_Glur?OW(NSoE7JfZYb32HEiRtjc47n;~;Kh!nEc5dZ+hyt35Qv zUOBN>HDc@$B|mHK!amieHx3McFR|A;)wf^wFOMDB8H&vYF7F3*?CRc{HO8t%73*El zx4LcXHG&$%Vb;Shb=^}>;uDgG;!${ZvqUN`HvcsCyeq&Dzd#gtT zwY&dx^V{yTulv_gBOAv`6@6dpTYd29N#&Yb^H?3aZ8!g$<@R&K<~J4U^~>&kt9k8C zDGxcDidDyU^*bE2pZnv9qpVuS|EEv&c&F3KkDlyYG{4o(&n)j}&N|RtzQ^dsw^GGZ zD}cWmIHNpzWB%p~ckkqj$$Pp(p5LLNP_KO+>QR02`qcOfZacAy@3QA)w^=#bsznvI z{0hqA$Qk9kL%59(e(K;ybvV-9@c9l6g?erE{fgB}ldp=~=>50O{=1K-xyRxP`%)Vn(Ig!9VRF790DCxNvb(AmE4FWu;gPr5#XN7=2v=vdu6?2YoNtvVOeiw@O(7rj%icUR|P z^6@{H`<}lbDxMnsr2FWN|G2}x-@)=^h=)P3)kCp`YY+j!;DPuzM-J?*|;cC^*4t76}2?W(7;56eHj z#oyzPhrQy~>^#q1c;OBWg?i~X#QkcAx82-#Uvg(2Jld*76{hpN6)-}b~~ zuGgUN+{ufLvT9MquXnyt9(`BG>g*}pMwgL~x)+vR3?oHyJzo;cU0UN z`W@#sG)wx^_TQnQP%qvOdH1XLWAOP$yDoq0;vZgjv{kRGcA8P1yYw0r@3l?EJsV7R z?@sFCc^6fSDt78Pqx{>7YgF}J^y2OIber$o$=~_X4h@BR@rlhRLjA3N-S3U<)?n9l-G^yTk$TcpOj@+ow2X` z&!}$xo|i^8wxJ3>LHS&)&yr~;Z|;77!m|G7YD`0+UW_&vL&W{qe-n4wO)L4%zZ+@Q zq6)?&j6mvbFeYJa!ni~g>cyCZF+{zMw^#qJ`rVWj{PH+=)uIYU7>prm#fbHvuMS(S zr~hK_kyb6LU=+icrT$ioNf?_jE>VSgG5TX{Qg7qtx3{Vuozu(z?%0u5Evo3h=_&ob zIc0;mjm5XWyWIS;75$8x#xxY_b;eq2ugNH|-o`VBznrhN&T2m2Z=_X=DzLp_ZTs=x zSGOvbUmt5nVH>JYFMQi!ZTo?!(lEMYWQp@9Z=Iv~ZSvOdjN_I!enHdv1=XSo{7!k> zFNmnJV06jIQWff@-w-s%#SavWE*V*>MHTp+hPD0X_yvpBFQ^LjYVJ9rO2g=qk)?hs zoV$7Jn$RPHT*f~88b+6lEY+fl4?jIAXWUrd6A@J!Mwg5%RiR#pDs#q=b!3UC(yW5$ z@?1ogYI&m5Y56!rm%I<^C*eAub)aE%$;eVIsz6kkGYYIDOGK51(Iq2GRj3#4e0kel zwCkRe4Wr9=PfQk79DL-AoKawXPu#Y{k%rMFBTM}(^}^F2Z+qf=|1s9RLUhTT}~P_%3e79jr{P>I#$mjvK({qJNbu* zF3USZ?31_RN36wq*L-uZ`^;_e&?u{3OWpf!e)Ww@RL{-(Uxn%Tv}uo6@s7@;87-yH zQpNPeKFlW}R($kbK5LIydY<|1A+NXH8f2D?i_y?;o3X{EvBLmHBSxpLSrJm=x-Tz0TWW>K(UOVB8Kbxv$sQhS6)X zsN#xtKjgE%{=U2`Y~#nf7n(1(`?uTS=FwIy-=E&DXusHp<)r6BOr1UnZ>b|bHQnBN z%FTFhRAU>ecy?5W;*wL|DG$1l$EqmbHAkK4+}T@)m^yuydLgPT7(>>_YWCvaniaR5 z>js)pRxPTy{*Wb$_v~Bc9hY+(%gz4Y4EyC#S5zY#3iUd2T&JS_q}R*IA+khNX&7BH zvc%a|wBBV9Rfg!2&pw>DA-b%;6{1SZ=#r78T2z5+qhJ(RKRI!2*w&kuD%1P! zZ6K<&j4l~jsznuuDhtMt^<5NErDb%vKO#%DAgU}FEAq~%pM({Z`z&V}T{5y%iz*OR z7K{k%$P!VdWpv5NQWffj`(cO`>-|7fX&GHIvQ#fbl?7u(-fNo*M3t7&WqdzRpQQ>! zl?9`~`Ywv7(lWYaWT~H}UU*`M$gloZ>n>d0GP-1BsTNfrsw@~o)_2j>_wH<{5y% z3!=(`u_EuH`bi*iM|HD|E*V*>MHP607K{SxvjkD4Wpv5NQWffjXro|6Snmg-O8YCK zOGcJzQ3Ya>0#EL^jm0+YWpDlRPt{3>jkK>FII#G*^M!Ms#$6P#PQeI`pNmMTKy(oE zSBMvEpSEmNvZw+PM!|@%{#J-8Eu%|Dmik%h)%;d_OuylRlbBdiux zAX8i%S4eITCZZ*F3?mcMzhs3QLUK^?NS zmT`5=)+U8|#WQqRy$!_EmT`5=*79r*7FEQvGVVFA560CoTbmT>rAH)WYc1pIn5|9U zDqgi=pW^i&_XF{?Wn3Mzwdq)?0`YW#Y;B&hwU%*p%+@A_dLf=J7(J(Ktz}#tv$e^B z+-resZ633=>65@(KC`? z!J-Pp(*?4%dCJyWWNS^#*7Erg6zUb9U2z+Tr!BIzCT43xG|aP46^N$`WNY)3t+kA+ zW41O~5KkA3l4G_ueNxEQTE^8eTbnGZh|l(Tw#S&k#B6O+s8@_7;(j2Wwv4M|ww4h~ zu&5$NI8lLYtwFZd#B6PWY;7L1wFR=ZdCb-_Qi}>?YYnosCT43H?*>bZOT*vDOyn9Yht!GDb!29 zVaV1RWNS^#)-t9J-(3~R!{*4=<|$iikgYW_TbmT>)!cJrYYnosCT45XF+uJ%N4Bxs&Fu&4s@bk68GWor%N z>X@xf7R1vzqvV*aO`jC9wT5wZ%+@B0DiBZSjD=IS)-bM)+1jK~ub3N%`+<1cFs_c- z+Vok7r*lThFWw$?DNj@jB|QANx%#j^zQv|(Hw zv$aW~UNI-v+K>G=F^sEYwwC$5U{OWPgvD(zCShz6v$aW~UNI*Zw}Du+olZy(((*@(|n5|__@Bb)bMlXJ=nCrvaSIE{Tg?hzYU)%<=wFR=ZHfC#?{|pvY zfJ$JtHf{si+8o(h8?&`Zp_V5d;MHPJaX#Gx@1%Vy_ zWNU5A)~3%=Fa3rgTU#-@jM>_>hpON^RO^>Tw_%-c55J&(mU=b!oIL=@*4mh@P2Y;| zn2Z&9-^Ep%j!4MXI!2cJ&T+wO_T);dO)@t&A0 zsz6q?WE7aPwGP=@8?&`ZppJFAzN!>wl-PV z1Hf1@W^20=uw${dMZL+9>nJ7kq^*c_ibA~6UeqZ&%)0wr@c-688fYD{l)+UQ8 zVpTROkgavd)|!~DEs?D)Vz#zKwzi1b+OicthHR}vw${XKZSq3ywM4eIh}l|EAY1E@ ztu--Qn=Gn8R<%U7wn*7phit8h+1jK~FGPZ6D;flkGyf%rY^{me+GJ4$GqudDrfjW4 zw${XKZBnQg_PT6~sgbR9$kv*etxXnHASYWQTbrkBtwXlf#B6P{Aop4!TbsvhZTh5; zt#!!OnwYIk7F8gtS|MATr);f5w${XKZBnQgqRNWVWqof)w$^pucCLxp+GJ71b%!ij zeQ4jx>uhc3+21>4YmKS1wMn5~Q^s|wmYDQyi@ru!9z31!!V00O?waKCiM3ohz z%apD4$kv*etxXp805DdJ+1m6;AzSN_tu--Qn=Gn8R9P`@OxaqGY^{me+N4k~+z+eP z8#3}&=mB7K8MC$Nv)BW`STSa6MZq2bMwjvZJXutMsIp=dn6kAV*;*5`wMn5~cw$$K zF6*O8MC#?q6+o^FuF|HT90h4iP_p@K~z~WR*c!&^hqIG>yfQBF=VK+BZp9B1mTGl9#pn6xMNha1M|8ED`Aux>ZVDDv{B_g$ z<%v&rE$(Q)G``gz{yfjE`E3_F<#$7@S`HsHzdU{G6^gzim-(MohRPSHn8b+*T^lQ$IVb>l-%mESzlrMR~JvQT_>Qsvg~ z|Gqi@ZwQ&B#p0W^Gpz@ny39K6Nws(7u|Hb@%|BF3p4Gj0Wy=oO#KgdbAP+vNlk@%o!sZ9@`Fx&;x_*L>@9A<^smj9ZcMA^ zE*w#f+jO6@?9^>;a9>~6!4AA`WaAf9g+_pw;db8~H}vzacIrQdHWccm=QLIX+V+08 z=78SzW;d{LwyUDKAE)p7w3~EXUwg^9Yc&+=weX;)%gv_zrg-j09;-gDJm)rEyr2Dg z!5UUAs?g(xnUfzZ<{f4bF89sH=J2tvmcJa`qaX`#-ghsT&pxLL_7sIz&wH?-IdVg!X{<&9}CB`f$kN>t; zF}uUUeC|dI$_+l~Ra`i8Vcz|R*UHnotRDOH+rPZDU*q+25>k*Q)8j^xgG5KY=D?~$m-W?Z+t~isOfzax zg&sq!Y_$C{enO`)cF|?y8w&NBSG`a^vrFH&jeEwo^V9#llU@I*6OCF_q5G6&8{fIe z4ZUofJ>@ssHWca=XWGPVyxRMD_xiBWcKw|`Fr;Z(JjT=x)`bir+4CQ@M1}uXyL1 z4A=QYd%oMJ>q>TE*AZ6V$&c=JL3#7ay^D3wg`#)6EPMR23*CE%uWWbP%UZRlV(Lnl zlny!MW%uAS>V^)Nx^cg(V*ft5XeiX{%o&%KC+*O?`1Bnx9S?j%*B`fpKtZec2~Qr&R*S)d}@=%HdHb2kgLkCrmRu4J76hnWAfa8xF5Q$ zX;(gDgN8!A^caE}9e1ni@~8Fejt{TZIJ&AZbFVF@Wqph9&*8oO{d?|oQ!n1Yj@f^W zhC;pcm(8*_KikUrZgq zZyRX8_+~@)K&GskDjs=mQn~KAYZp)K!9Cyd`Q6<&Z>?<)dTx`3LcL!3!(nBYcLo&G zex+jNNxQk9w(MtD%76u1^fAG2bH(pH>fycVOBgp z{h)Ha4>m0Rz47A3&6{sf9{<>&7|9%c_cXWv83)*1F1Xi_Nd%i%keplY;{D27e;iU= z|Br<^DLt@|@#%c?4u5cKPu<7*U7s}SweyMxl_=H-F&TifWl-B#}S;z)btwWk}ksAB9N=gjHXbwu38y9-x$ z?Or(6u6W=0hC;o*I0ei8blW2C2fme&Z3j>ytNs!+%fhy*oInE zfo%+H+s4Q1_cH(OdUV(iRj3!f;jp&-c<$;Ki|?;J-X3|^c%v3o9B}j0VfmS@{g`^> zjAE5rj zJ*(Th92fRO73!r&I?J{?dPep3v=i)|pN0KMzmzJly*X|BfjzHe&yzyEn!n&*-#p7a zu-O#*@^O~559E$5M|&Fm$%*F`aO1-88`g5_VMq# zTeYa-iq#Iv-@boPj55v{dxY71sh)OGrx8}Gp_5-aDL?Fuz9GtB?h3i4m^J9OgmV72P8Ly26}1x2GN5Z>ZJJJ#6Ns z`Bl634l#qOv+SVHFERIgzly#6gb*jDt*hdgr!UT5LZzvW8O}ZALUYXcmF*tKg;+Ex z)T`MuG5xkj%vaACd){hG+h@MGH6Q#?|M0v!YN?xYoA(RPc0_%7TV~>(2b%VQUxm%`fmgzwf+nP0z1)vfEF(!n{6bcK+T|>x5_cCFjr1XW<=}F$&&s^0qhn zj^n;H+dZ+9{pRv3`Nongs`$&fv-4NWbwX5wUd};F+2^kMt^N4To6JkyU(avct!FW2 z_b>B(IxWb}^T;5~_}^_DlPzO!{%C8v!Rg_xC~ZR(Ppr2fziwf#;+${Z#eOVNE@KzH zFw#z2aAD(HsTbB$$hocp*Hl35?(HAUFu7ooD!ud)2&h*besCP39Us8}uw`{(_Hn_|QCi)F}JzF8?uV zQ3c+%^S0d51v7p%pWP1X<$-$}3iZ-`LeusZ z%;Mbp(2{n}X`9=pE`6Y(P%k~-kjvQnM>B8KMz+I)?Qn!&$d~?d<>LE27c2g{*o*l` zTdq=YB@EpjR?VLCi&?T4-kpd4#2i4{Lsh);*30>Tdsi*Ec1D)%z0czIqjtk=`;R_o zDAY^8Ay}DJpE8SP^|9+b)X%>E;rx8ufE9})uI^Nf*zu|S*vD2Z{_$-`zR{<93|8{o z=^0aPv!>nc&^4`kAyb&Qa)?dEGVeTR&gj_BUh-mi=S-iaipgW2$#?zeH^tX0@-20( z_5Ndyp4H!eI%W07{Yt%%_s!cf!r#68wi#yo+J{Gn{BE+S;@YjB%^%sfdof`UbI2Qh zIM2MZT_@XRNy|KS-pXJjr<;22nq7LY?Ka13aA9V@0NbY)Rj|I=>fXazNZZ_P&b|IK zv&~~;8VdDlb{k%|%VXxFKP+o!&B`0!YMb-t=kp#|zF6hYq0*4PVU|s;9y3E9?reWK zKU5l$MHO34nx9YXyF&5Vj?88B!px=DFX>{>e`E-=&PkzOr@sGW-fmXc;)|_W|JZ-~ zyUpdu`|LM!b*s+_eZDq-^Yg~vVh-50zukG)bsN8+Dw@yQ1CGDnEEw6_cD!_8L!n-J zhGyB2_ve_oUAoyl|1h+1?y5rfFUubJ`bo3fkZ$(Z|7_e)sMm8H=jXpZ)3w-OdG7hk z*F0{X-*N?8bl%LWMHS6s#aa|s7V>tqtwD$6e>(P>rwhiS;krvYEp*vD7C19wJ21Z^12?yS`=zh zhV>{_s26KdsO98!J!ez@RTBuE7jf>PZjf~fXU(62+yg3W? zD7C0Uw~ZN9s71Z7?c?TT)T30PUc8cdMc4Hx)}m08GOS0bMHS8cU@ZzYDZ_dcYf-34 z<*Y}s7KI8^&UzH@JiG(d^(fY&P?IvON2x^>tVN+}lGpVp)}m08GOS0bLcJLA@v5q~ z!CDk*QlTED$A@2k}p(YjTQEE{IYf-2j<#j!ZwJ6l2LOn_q>ZRW{%UFv- zO)Au*)S?R3qEKzh>v|MxQK(6UdXy^EOOIieu@;4zlwm!JwJ6jGa@M0*i$Y~4XFW>4 zZI-bXg_=~TN5vJza>j#t+~VqD;ootcqZWmlRH#R(MHS6${PDG&&@tJ;{&?$nqYCv} zW&XOw!VYudHrj2no4xSSA5DJiiAF7|(0$6X^ZvVsUHt4%&7gm6(@>}vV|m8(b-c@3 z)T_OpH>^jo7R43VxIP$bQK&HGtVeO3Fh;ZWnaElcYEp*vD7C19wJ6k%^12?yS`=zh zhV>{_sF(h-xIR#eLQTrB9;Fsluoi{dQO>o{uzn(HQK(57)}vIRUV7XRy`mO{nv`KZ zN-e5jEeh49oNKIQ8Ea9fNg39oRH0sazG0##vJ(d+Aa1qJiV9=WbThoOV+4RtIAoYLY#=|6{=W<6)d$d zugLr&&lu+5n5n9tgREYmie*^AQj02By+VB|uPa!rUZIL*Siw?-dM%IY)ysc4EN3nY z@0_e&P1?=;1{Ex|uzH1>RL%;PeiAx_P`yGG%lrcsEVZcOSX8gB9DGb(XQL*ddW9;M zVFgPS>ctFaTbCZISKY@?HnUN|Qj02By+VB|uPa!rUZIL*Siw?-dMQPjWvlNp#x8ro zKIXgimbT0jGb_w{A1hg?XyvSC>93h(C!pSix|jJ9H7~WOg0(Nyz;f2V5Vv>U(w;nb zlDYr#l^Y86(sLopSiM3O%e;jO7HeFnT;;5Dv0~ME%L8&&t@PVs4O3LFP{lH=V5vnF ztX`ptmDd%l{txeJzu5TqX8Z>~H5BTl`;=unRR`Lemp;~vIsIP4>JBsWj3!vaYpsB( z+s3;ZDt*V?JW8{s&dOhwvC@Z%pJBC673!r&B+LHv&m-)xJI^$G^&M+i ze_~aM&pWJoTVUPd@HZ=Rt@Sz)>CZaCzC5NddwhLiV?Q3h$`;%2-#%w1ZSV=hi~A_k!QqeLD{_=w~-r6*jF~+VPsaIA_=PIkQ80472RYGxxO% zP9JQx{_3^H(N)F1lZql6*FI-v5|y8~53qjnw&ux4<~9`SrTc{3(pi)2GW!lQbH2H$ zadcJj;WS&!+pm4jjAxd0KXS4?_~G2#a@iFPg?j041M>d*p7y^_pHlq1!YHm`n#lAe zu`0sthn+v{P^?sku28Ou5IbeR=+(_x=-}8!ydb;IAPb}t+f+EXRj)bKV)FB>G3xXySD?YGK;QT%Wi$v zOU1!cnhN#OdnL~H9{ue$Pk&mR^N_LXHRb4mMf(ljAIA60rs9q_2G~hAw==gQg|8M> z46Ozhi@JS1Y%nr9cyhkKwq5OS9n5)G3~MOVYxy4r7Ps8}?Xa#Pi}PtU%oY!?Y*wuX z*i&B|R6O)zyL{h89UFH}+kV61nKiP!V;AN!o?Cn)`_w(X%@ZeVXw{;3RQ?h? z?fb_sV;)^`vxY*w9(sO*;;z$v9X2&&ioU&TUHd@Q$xL`^h*gU!n)@*im6G)~>S<2j zY0budYwo6~TygTWxLAL!h8y3BnUc6*>C?2blu}IvfvVIeu_wlCoj_uZT z2W`BbRf{U(u`27V!9I5kw5Kju*4;FBlg2hK>9S$5;kCccVLnOKm=d${dUoJuOS!iX z9@07!!#7dI-9HU1{&%-;d@npVa(T&ullq?()`R?)(uc_6gfiMZCJ^)OnwtkM^^N z9P?>4cKHKnHcuG+ost-8-Lt$RtZsNxaaOa67ijdS+AbP z-08~dhH>d$5)|syT#e+7zT@rYV+OkU8~tps4tZKByU%5t6&GW*apo4{nON5EgTF6! zwc9?nt{e1zht_!&EUFmr_f3l-TeL5krNaBi+gKH5+EBOXvt=6!^=h6a_boNjcKf-v zJN%4QT31v!e^hZ_*Nuw{Hfvup`-L@raSeXjX*GA)8R;4f3iZ-66y1hXCfk4CnY(-c za)p_5w=GuQw|&WcNtbJFaos-cOXf@BQ?0D?B@e7S*-khwcT4O%v-OM$7FF~<*A~5? zuJa{l{4&w**lByW#pL@M3iWCp-9x@Qz&^g~#%}g^^IOl_aCB8M_HTJHcGvc0oi91< z!M*L`R}OOj8u4yJp~3^%pqs<7 zlY`wF=*=jZVPSU&dO=ENSenOb=V?>yAII+I2HrWXadg!yMoVFP=$ia^vYj^j6t~L6 z6I-!Qu&6?}htABsrr7>3o#{TFi?^>j>I(|>iV4AZik8AJs9w5H z=pDpr@AqO&{f<~qUoEQO%I{oXzs^jsM+Utzj(sw!P%r(RvaCdp%o}I_-d&468QpW; zTlUVNhbFB4kLY#b7(3>Reca)rm$GV6Mf0k?VYzMWFT;;?laN_cg?h2$1)VQtoy%ay z3p!sMyI#0r06Jg7N?h!CK_5%WTt<9{3-?NNtK;nsoiC1EFKST*J6_PCQr2BB?07-v zi(}V|D%7iaZ)e8~I$s>SUeuxrcD$gcrL6NM3()cM?66%OyI$17E*JE)l+2OnCuJEs zUeNjC*!7|oRj~U7JuM}3C+NCI#|t`N9J^jrpqRZ> zazVFC$&817QkMN@m%+BztUcYx?&~+Up^BJuD4C_e6KAhY?4^T8yBiK%x1mrk{r$6y zomA+ka_pv3iz?VvgN6a9_^NO82=-_ee-cf~m#k^14b9U~agU7LZM?aUHJLtzLnJ-Z_A{lhzs~^A}_v4*GE%dvVmFidY>8 z=NK48^x>c%$FUbj73!r&9h3ghhl73`&t4q0sDgbs=wm7CUL5w}pdZJx7e^K9rRN)Z z)zF87ejLYM9QNU$AE)G79Q$z4T~o3bN4J+{?88Anj$<#5T2#S49CX@*DM6Uvf<7Gd z<9PPss6xH;8zM7-J{+s$}THK|hY$9lbc} z6|1D-t+AgneA}e99LaA(yB!jvCduA zRQ$GweP&)b>Tb8kQ)3zm^@?@%s9+xs`f(h4abo8{_*U%0L3d5bUL4&XB7OAXpdZJv z7e_6sU>^=TZOXbAhkZEc$8qe%QH6T34+lLaW!;OzJ{s6`d}v;*^lKAZ!Ozu$F2FODkIOV3bDmO~#7`f(h4anzy;-9Pk3p$`ZBIF7wI zs!%WX;h^iLtb1{uLm$p7*F5eFdU4dEisrFm9}fC)d}PCO^cz%>4bRbCQ$;qM9Z*%B z17IHx`f+?@!;^)bJ1qtKaL{#AB{tlkAIC>FJXzR>gYKFtvf=5IaEC)54*GF?WW$q1 z73{-7r%jdEaD#pvAKCDvP%rl3ppT_WY`6g%?jjqWqaP=n)v?>G;x(bGf(JI-fDLz% z4NvQZt0Hzi#bX6F+<*=Dkqu7@^@^Q!Rh^Sz9}fC)d}PDfa~CYCXzmC5aL|wABO9Kh zAE%0Jc#iIxDzf41_p9oR7yEF~kK-d7o-FL#X(`x;gN~6ZvEc^&I6kuBNuge`yDe^m zeK_dHaghz@3V-2<#=gGrx9(G5!wvdzd}PDZFQ|&xw-%2s`*6^Y<0BiM6zav^ver2r z*l>e>93R>6WKl(PKiG$ZejFd!@T5?$*riz|Hr${e$454t9iPFX3O#Ot4Y%mW@sSPB z(MwWAHatgnO%>U2cDGh_#*2M8=*RJq4Nn$!?z9x_!$ChzmDq5LejFd!aQ2l{kqu`* zP8Hd3MweBcTVfv$`f+?@!;^)bJ1qtKaL_kXB{tlmAIC>FJSo&GcIn3bU>^?paeQRM z(|)LeeK_c}sS+D*(U0RJ8=e&E#a^b?F$`?DK|hXWyxsPmkQm9w# zNsrqA8*agd`^bi~zdcw~!QP_QJ_R=1fDQMN4NnU7ioNx58|=eDKaP)Vc$$RBJ{)w{ zRFMtmTT=W5*@uIE93R>6WKjkCaL_kXB{tlkAIC>FJSo(xd6uvb2mLrcvf=4BR|WfU z&^HsNJ_a`2pdZIaHascROOIP%!wvdzd}PDZ*`Nyc;h@tdOp^?3xIsUTk8F5Ss2BUb zTIX9}!wvdzd}PDP-Biq3unz~_HC1H8+5H{wqU^&#KaP)Vc(SO1eK_dHsS+D*(2wII z8=mHIunz~_HC1H8N!`S|DA;g=ejFd!@MKX1`*6@{QzbUspdZIaHascRi+wogx~UQy zZqSe8BO9J9?88BKO~rhY-h;D@eK_dH@sSNr+fW7jaL_kXB{tlkAIC>FJSo&m@4e>93R>6q)@Neza4(rz=j)i*Z9bW=jf=YA{$O>FL*`% zEB+qrszG;+k8C)}uwaRtUr?~C27NPCV#5u(YkXwGlR~{ffahSttHg#Ibl3REh9?WV zYS1fFMK(NrQeeXkx@&x7!;?i7V7POz;ZIAR@frjhZqPB} zBO4y()6^+3*}$=y*?LrwBSmd}PCu7yD(hHr$}Q#z!_hDb$NyHRzkE5*u#7hWp5dvlAuU_1S^KxxA4LCuJ|Cw zxQ$4xx4u=`+CzL3QtGYkm8e_9ZGa7TV8eZ6!;?i7kzS7502}VWhKK#YcTWoSicEFf zMkJ(tWWz~F2a75qEgiQ3HoO8G?jswX6zcU@9tiNb4Y1)Q*lLcN;5AlPsRHrz)xylkDj zam9l0xvcu3&KBaiz=k`p;XbnA$)XDVodO%~z=r$Ch9`x3vC4=lR)`-18}3l|@{tWs z7FFm3>cECOu;D(k;U#KPVd^xieyD+ksnc<7h~E z8}3li@R1GY3MAo~!RiI-6Cuiot6#)B94i^9X!yv6b6t#JQ3WexsA$9}gB3DV%6w$Q zORj0i6%bh=L)|Mx8F6)wcyDKg43#n;+3>P;Z&w8?WTafJRKW@v>R~aG0UPeXhWp5dCxv>kT80`}jAU3LL#50|HauBa6+_)C zL^929#R?fJWj?auX&b6wg$(tu7|DPQcVNSPWW$p}y;vO~=DP<3F# z9V$#dvf=4-Rl&*XF>)nZ!CDf5ZG!WQuhYFLAYf1f%_cknSm|jU z1-v_#tv6&m4c=PZgAMnQ4Nn$T=(f|^ZQ=b~KTExk11MW>`lx20LWWA2k8F6dsG_+a zV8cDwa39(5q)@N8HeGyjvKED!l#gt9IveyXY5sz&MWH6;BO9K6TUFp~yKKuXu@;4z zl#gt9QmB{iQ((hAYEq#dr507N7KK_)mDq5PnpCJqsY1QKqp)}m08@{tWs7FMrX3f7`fZK@I*?opEp^(g)B>ZRW>u;C6hDIeMJ5?T5x zvf(AFO;u#W(;XwQ;SMz^AKCEag&ZQ+muzJUMZsDWYEnM3;mM*3)}l~5suCOSP?PeJ z4NnU7ife+#2!ORH)TDf5!^>8#SQV^Ap(a%&Hr#;?_mK_f>ZYwcb=j&FfB=_y+hD^T z*l-`&@MJ+2I4O|pO>?*d8}7h{yU2zog?hzxSwlWK%UFv-P0B|$Jbf$HqEKO~A{(Bz z7uaxznv{=hc(SO1wJ21Zs>Fsn)TDf5!;?b2Sc^iPrAlnLLru!F9;MF-eZDrIQLIIw zCgmd=o_;}9G@rF#!yVXgAKCDvP%lk z7KO@FmDq3xHrz)xJXuuHJXWklalPWmhF4tMHL~FqS09dSI9Fy5HP0+#EsEafJ zSc_^YSc~GS#EA{}T(3B?;mN{U6jvXPY+0?%DxqE^X?T7eCBV8dNx!;?i7ycXMz z71(eOHrz!vJSo(RS29;6uIo{(MRC32$c872Dw_MjS`^nSj%;|v^@<}KUUBu|$c9(E z1J(5?)}pvxab&}jg|(=bg0(1AP0GZEd#+a;+3=)LFGhU4s_Jd97RB|7S&!1=gW5J% z{0~Q0_bJO*i{g64kqu8rQ5B4*dA-z?QP!eRlX8&_PYU&7Evj`+2R7Vuz2eA*CyOeY z`@vci*DH=}cv7erpCf!aBsSc0z2eA*CyOfdxCJ)cbG>5LqgY4bTDz=Av9iR~hgpwe zyufE0>bbD4D;RAxfwvVPmZhI_78%z6}SQH%*$kJ97DIF#`y|2?qb zp6eB}9;FslG`9gZ9J9|m_{fH*&r&b+NmXFO<2JyCd$8dyvf;_13f-r`hI_E#F0$cC zpdcf!@m%AuyQCzP$ zvf;_X>Qzg@S`^nSPHed6dc~0quee?@GexXLarNQIhRa=)wJ5ORF0$dtq6*fcxDs(< z!#&q4j%;{Rs26KdT$MPn;hyUiM>afJSc^i1DfBn%Jvgx8p6eAyHau-Z6|6;}b`*P^ zS&QO&#gPq93iZ-^aA3nd*DH=}csjbOU@eL(5hpg>bG_ooh9`x3F@w|kWdj@T!G^oY zhI4L4czQAC$E+ZqmaI{69pl7?d#-RC+3;jxUXkk+M>aft639tZueic-WW$q16|7!y z?c&6Sd#-RC+3=)LFA(4r*znLP9oTRWHrz!vJXu)1;(EoA4NspG*l^Dkjw2hMEUEy* zU4adcz0P36Jy$r6Y08t!D1J^=$(i?zzHoWW$q%HLjL|)hn)WoY-&= zHrz!vJSo&m_bIU99&EUaYnO1H)!KGo!#&t=7uoP+QAKkbV8cDwa2MI| zq);yqTou^x_&f(2?!kt;$c9(l#ZSV>*l-Uv+(kA#9UoPI`mVr+hYtL}hI_E#F0$cCpOb*klxi1hn_!YO3j9IqSBnY8~6QQz5LsA KF+3;jh z#e)Y8tZw`K@;NmdzS5Sx{FkR*TtzlKDby>@c8WabdQbH8T^_rtiflM1H3f?*z;jna zj=yov?7)Wqc->llNgB*xCa~VA{(CeRuy2lE3o0Q_Z)1v2OI7p8=e&E)x2uK zhI_E#F0$e28dL?S?+R>qpb7#T?!kt;$c86{dVvkEHUI(4TyJ2*J=ky)+3*T%cvv|w z9;=*B@+=C4-A{(9*>eZYR2R7V;4KE@ao~FL3;$hrNz=jV? zY`Fhurz?xdh9`x3>7=$S0~_wahMUNSSD%e(A6BXZ>0N;h&m$YovnQ|L2f>DWu;C`M z;mM*3Fx(Z`@UVhmV8cDwa1+_^q)@NsSpqiPgAF&44d?X{&L35P`mVr+hm{cn8}7k| zo5+SIg?cs5U9jOEY`BSRcm*~*k8F4aHaw4PIG;p$V#7Vya1+_^WC0tV6kxb3u;Fnn zJ+R>(Y`BSRcv7fWyw2m%1sm?chMUNSr(>lGP~R2U@VJ&9*l-Uv+(b4!Dbx#Wcy;8? z?ZbM6ferUy!%bwv8D->*mSSWP{stSKj!0m`Jy-gVYsIHHavY+j1$5UjnPurUSPvL*l-is@bs-z!ETh+_5vI3!G@d2h9`x3#RxENgMA-h z!%bwvE6xL8_Jh41oCgru@N^6@^=;X`JlJp(+3;jh1sLuMYsIHHas0gRe<`gI29qW;hu98A{(9*>cy^_*6$S9a1S=zL^eF_xt@LOo#A|i z+1v4H05;r%4L6YuPZm`)uUfF-9&EUYY{?m1_ZdoS`9%?v3*UU?Hr zdFA~WrS~YWP*hXXOeWv&KD(4LsZ1&=X=(_06%t|8Z>{}ZXW!51UenKCUw5s~S!eIP z_S$QI&VKNU7h0j>yS?FtZ$*&3;SPaXI9^eE(25tn6+!lfyGV@)Uh%^B9k{*WhW3Vs zvNzmGc$Ev^cOZMi-IMIzaKpDE$lh=#K?JXU;rk92$9uyK--;l6!yN*(c*P6fci{Gh z8`>Kl%HD7%;Z-ht6N2mwcTci=!wu~X4`pw-lORGk2jA@tH?%iAl)d2&fm+!9c5k@h z+csoxxQo(-9h$-I|OP8?;|DWl{ztl{X#h2iZ-oX+?!SKaJPn@LdhEo7_Fg?j|>UyMyc| zcM?SK${oJ9!R;nDe7ghhCdc`AwXKrQ($A~tyC4&Uy;t9MX>h-5i<Lb}~Sc9S~< zYGIk|ZgRu7JIHQw*XD@el{>WZ#h%^gdAxFmZ+DR0-YFy$xWaY z#2#vQlN-L>L3Wcn2_mp<>~3!vga)&@IUb(|}IJn*9hIW&OvYXsV5Rt5_C$naR zBmX+sG-&m7h`U7i99Cw~c~s*WD$gh~vs6C0l}>Oq%+R9*5j>mcJU%m{f2&#;zJGd< z`Rf}=1ZpLBD185iO5wL}_BZdh+ZNxcXRRZm%Yb#+JGb~^4U%9(1`5O+O+ADs=&^{8{}7-{L0$EXC<{Bbayyf zztZGa)&}0y_-h3DmDnJ^3dpal4MgzoSc`1)t{W)_`BgxE6_*1f`3SPd{X=Y!UxnmX zO8m+pP)mBV*dV_O$*-&plpuoYjr+OSAioOv3>WSn0j%%)!z>MK69)LgD%(K0_g1x0YP{@rK{XtQ~bM+OWHfLJ1;dbWUeD zQq-|;Dwu_|N5m8 z2-MoJpuXO)M&C#xVTbhS-afK2@B-gz@zi~(O?7P0HL3M=))WVh7^zCl_*U{~zt~Fd& zC_zMWt#j!H$D{LmHa7F#yfA@4Ek5liUSaNeTbmq+T9v=bR2W^A?be$Jhx0z`ZtDsWs3pBi zY+Q47@vwZ!PPVR4f{4lsUd^8JZd0-G(c80w15^HB*mn_uS~&X9cZ2ywf}*p!nERbpiMz!qAuZsHh>0oW31QAqkZm%4jE=DI)E+rO{8AwE+7N2Dq@A;!ISadQa zvyjX{q687ieRmYALXKG+ukd^izJDn`_l4(B9GNnHMX@U6n8oo5C5Yge1jm+)Us0?I zIc9O2BLcOU)8NRIu|csa2 z;&_D;L?ll_pjf3iW^ug26aMfFLMlVRaVAp^idBkZ7RM`;AcD#eaBRtxgJPB9n8oo5 z5vWCN5pZP6*q~UYIA(EOp#%}s76HeWj17uaienbXD@33cp3vrb6sr`+ERI(wK}7O& zG4d(Jz9r+JyTgfm%H8cHwq<@!KBd^VWE|uYS_vY=p3H>Frxg2^jDrq=T2hB%gM3P{ zZ^<~wEoCK$ka`mvKX%wLL62bne}p99!H|7R#z7}R1al1RTN$2#S8MT&9x@KPo9cO; z8jXYY=3a@FQVw3(#-I2e~BJANxfkUbvH#RiRoA&rA^IUEADs16|ur*SZ(anRa82_mT8I4=U5EExwK0=0PTh1g+f5=Jhxk8$(A73;wbvur?5ZT9_?+-my)e`~B85u{KbGh%1{tSpWEgjm1XK zSw(cUPN6wQYtnh-bS}B!@6ISe zMDlzFUQ11WrNpn&;1R@+&2N#kFfCh>&^{8{}7-{L0$EXC<}r$1CesY4R&;1IMLbBgn7B2KiM$ zex=y25W&A=EwT-x8u?W~eifGkB>4!k$NfWWkY5GlS8+KU0=1|;U{oW&3dygO_?43& zg6fU?x!B-!2IN;t{K_FvOV0EPoL_}}-o5x0pATjwh~SkFeD-~2|Hpx>iRNG759zly zUmf=TPp+Ojpji5)8PCOQqtd)is^#`vU9EbN^ygEbqm|@WZobcS>+|nm^H&W+l;Aq; z(J!>r7gs8hZhe~fl687|jA^3p3wtcOGJ!y?Vr1jY`9;!iTN`~QjWMs>Juw_O`^pd{ zh`5Vv%r09b-O}0^Uv!K)RcdOuzCjX!TGO`W>h-(4^b^*`y)TS5>t1;%Jo#h&5G9D% z_k2rT{97+w#o8!Yb%1%V?+4+coXZjj)Ou)Wu0A&BOzQ1BxUL%R?{1!7S5i$KQ!zvd zBCcrJQqNj=Ce>v-*VXXaEzJFU>#A}?iX{-JLpQ{^oJeArKvW;7}R52sQwO2p2 z*&3h(5fvA<&~@9KOtpTBZT$1(v8Zpa-s;~YS0@mtwJe>Z|CDz!_0i>Qqg2JM(GUL} zsJdOcFhB_+#!hdcFTderYRO}4W79qFN9{`wRBu%pZ=SAq44;~afSx8tcAqnG}>;@}cLcsEzS`sM!Aq2-MDUwc`xbk1=u`JRE}O|{)ygL3tIhbTeB-!9A357ze5(++XTy+2Jb zSKM)derQ_~fm%D8=IQod6it8Jj}gljPB1;{H`2BC-x;C=5tG~G>AACurtdOK3Gw+A z(PAxaSOn#t2WY8*@5-RxOHyma1J^U&p6bnQBG6A09r-=MWVbU*-S?WX|L~#;OWWg@Ts`=b6RDr(FZHoZo>%+C&F02- zEy90ozEq(E5x2I>)89_`K6UmM_N!}Jhvwcb8~y9+WhD@(_0Cjko1J@8KfKJf+jG)r zqpvC(UD#lL*fzVhzVx+ysTtiD`&gqNpUl&1`t3_)JcQWbk^OPQ4YP1QGbQ zo~LT{Fzebrr{5b=Od$fb{4eu#l)EoAzY@Py`mb%wFAW#y+YZ!JC_zNB9CMnT(ZljC zRwuq_uZ~ePI5_!8>isgy{Nr!u=<2t9mwNPprM{Y&tNYbIk~*(H`|gG+W23xzd&2AJ zZVQwkV(4?ZdgKjgBF%V`#lo`r#6r z!yZ=-N+3`RBZlWauzb88k#(K=TZ3i_qZ*be8R3fTX&${({xbD+qgDzfh`{oBUT)E+ z=oYg|s{aKyClIJrp=++*v-()-xzk*ZA}h8<^Lv(1{k{tnN)Yk-OSyVrqvNToK4!## zQZse8CJ(6H7nck%hGPuIm`~qpR~3z>Y#*&EKRG`{2_lk_x?->C(PLkaQiD4+OCV4S zM?25!d+l@4+x`2gonI^uQG$p+p3Tt*EC1ZE$UCk|?47QIndE#J2$fk3U7d*$li9X^@5Ybd|f3q$IdRlTy+ zP1Od4C_x0~E3{UvWHB>le_J)J{n`WqwUQ<8J@WhLf$cq2hmp61C_x0~E1uW;y!WGn zo%*Z4>}Z=npcd9T_4BKSNAoAn41*cN6C)>%me|v1PeYIW(cl^#!tTZINc1Q~V6>yV zmzN)ko@&1|EPi*l1Om0tkLknCJbg`2 zr$gTa0=2MA)NAXWj_%pcX|PK6RgJXJSOUp<1xj}9CYxBFF0-3M;WUOBI00)bk| zNL{}2IP>tz1-eJAWX^z@1&)t&qV-#&&8|u9f(AXG4pD*#9JML++1k_GlszhZ<-Knc z2-L#1p*<$|w>MMfZVKOj=|G4QL|||Byn18nn>lk%hv%)Xs1Si#$u>6=YnU}(S5?pd zP)wl&5!jpQjIFm$N9A6vq52)WG=V@ZjK_4-#_X@6UOSqpV(UsJA~hngH+$aG+n$LQ zy>PvHvSaN80<~~lA#d;VVD$H$9n{^bRAT%<1V&VfaAi*Dw7OMY+pbIkfm)c)6U%vE zkbaviH2lw(AxaQ|IlSlX?$*ML=)W$Q*SEgfL^;mfoqMwnQ;s9~LpEm?{fD*D9lsu6 zf797igIy_YOU?XA%FVXC|rD@8;Ff29YKIdx z5P@Z)?@=$0GW*MHN;l2eQ#~6pSfW53eKF#6Sv=Gno#z@Hc)~Hu_vC`c+x0S z{jKW*wt)!Ll5%8cY@Ga0ACujCZ2;x45=5Zq(>e5|N1AG-_gWkHEYy;k78@hBbT$1; zeV|h(%O>)6%*e6cJg*P+!H@f`)3y86S13V5ax`c_-oAGBB)yHi9TBLN^pe|8oM(FM zo2uvJ_d)AFh``Z@R^3;ob0F_-t=C^RDE4-XKrI~M==9dlxH%sHKPT6es|TbV-phy)SA+^lDc0_{jgHuUva?{8mvm z#cdBJ5U7RR2{9Ay-(>SpbDMYcTRq;+{&wp0W3oBv zm(?YvU1BA>*4NcpKYR9f)9N*Kiv}mt{G=qJm;YnB@y?o7>&euf^q~(M+28AmmDIia zRkXj82$UcKZJ!%~T6^YSq!jD@l(HUv zw zC_x1GD2@RI-wF|^C4I9H1om3&sq&;k`Uk~CpJJkwNNMeFieo;-#6l1#K?L^TWXTbM zT2yME-?CuIQGy7JF-aRT0@!EqctJ7I{-%=i2v>*=lpumfG>%LK-wGu>9`f5roBuy- zAc9J*xr_yE;9H@V^sYh>*lXGA$@{HmV1G>36-p4n_9(Vn^tlnJC2y{fM6-JJ z^kwSbh1kGnq1OLzJm>htv4!6RN9trbP=bi(2hB|Xy@FpzIS_$bGU611z|0FXGU+RY zAW(t`dP6@hQ-N~0xP)35$C3z)i9CLDn{ZuWv`ZpTf(U9opWCNkn_P=W|*i-2qU ze5!C*g$Kiq{M+9m~9#jYdC5Vu`s}O|biB|H0%GI9^En)aXgX+0-9vK}Km=+@#3%%T5=5}ya(pjXyNEz7?g1S43nDP< zlkvlPxQs-FcsoiEL1Us%Bj;}*P)o+gLJ&BM55Wx%%N7aHh5P@2l`zFgl zHOTWm>pyELJ335l&CeyD<{4xmeuWZ5{N-p1Jz!7g-$0-iMy2Fip#%{!D=x$aB2Wus zSJDPXnR`c1z3Cva1zd8BN=XDt5K$_3dG>q6K@@BcM4%Stk4YOSK?G+7T&{vP5P@3A z8YXQ}bPgznTfT&%HlM#yo1aT{70}3#E@%TKh>&<(2m)=;2;giWI{8*8K?HF%0kJqY z6?`j1pq9K<;a=kMC`1rf6A*(`$f$C?qB`V^vk(MI5J7&NP2T<+2-L!s^}L+!Z|b7{{p$4GtWfUW z4S3zW+>vX4W6OHp$Vzvp)Q8_kmrc*&6U>76z7jfVEQs$%nRVjoKzB-~OaFBvee)uO zi4i2xu|&=$v+MMeH=hV16dQaeiakXPPcxGz`OXHvl|_hkE0MRdXn9-vn@*vvIa+m@ zIx}qi$E@)016l?pUbxfe@3M3XX+Y=DTP-^EG>A`JrEkLDk5(V_oDyz2m_%R<{&a8{ zEYVZ#lW70Pwo$5Cui2qjvSEl4L`cN&GroJW$31HGnODLoE3*;^)arjn^B^x;CN_rF z7@&5T&EfdHSs_Xgf!Vp|wHVb^UDy6X^|#GgVV7^O2=3i>&~JR;S^uHNwS#&a4)|k_ z(%Oc0jf2#P4Pql|+D27>p_;mIW>$#v^LwL9gJV@sTCLeVFAs{oe?$-)DtA?lKfO@h z@~@-~d~WBlR|LPzJ?wv)$7@n|+|^O-YgIuNpOF>T>{dIt_x$}n@8+OWKZ zG#Ai4KhlCZ8@j5FAD2@5|B)5qyQh2A4w^RD@7Gzk;#cLk??_j5x(G=-6R6F(BC|-MDcEF>Nn@Br#EJWC_zNB92ZUegSz+vPt8gv5vYZJ zOe=n)wra@ADr(rQtPtxRYZTkb^Qw>Rth(lwRgZt0Y(Yd|jdwCA<_RnY`Dml$q+!sE&rPQYzPi?$n58=AwIOciF_mxxMbnm3b&(8`+mpR}+bW81k*UBTB zeU00P{mt{*zFbyaeobd}6~#o9AR=jl{g(ZgeHRg^#XiiwoOvtn;__B=P zBptUDW|{P)biR!(b5};y1`bnasN^U?1li+tAmZ&*jwmh%B2bIUm(H&%YQZROLAkBj zwjgI_acfeor}JB|!n2=6J&*TQC0?|3<(`E$k_c+S2wKoR3lY>dj^(DEdg)>Yyu=|; z3*XlBet&)iQJU2KOw=5z;(Pah^cAN}6*P&R0C|jY;Lr{(~LWEff<`LRn0j zGXlrpXKfk>BN7za2qPU9^L{RRK=8S;z2hZzwsI+h2_h)((VW?2a-X4VI-8zH%cyA-cM*YF*qXFv zd(kcCjhPp#duXgh2_h&{(wrA%vZcev+nSeducCgWToe(gMOl;PTqv`v@$sH*&AcnC zs$7~!p@h6!b2js9ucWokP1~6H`7jSx>shx3cvdCTwR=QBH=hlBc0~4Fyp(+YmGCvM(snM zN1+4}vLj!7_kr@`%*GQP!u1=n;@z@Vg7=u&wlUFO8Jv}SLcVG2Lo^Chg=WNas(4Oc0 zSaE`>^7$2EHX%@gh}-++>86hqu}p~P<((aG9`WjiwSR>`tz_-qaB{r)^pUzzm3)L{ zWpURx?#`xt^uLTZ?{BLURU-sSaDSA%t$h;h)h{=}Jk_#xfhp*pn>OcLkZcE$}N)RF5lgh*^@vAiZ6(Ue8=~qQkM0vv^G`r`3{iR}jQ<8e%z(u$<0@WE@tDW-glZQI4pV z<>ai-2+PUYU0PU9ceA-=+uoQ7CVBP^$rAVTJ!IuqN8hz(*n4Y8a?SWbsPEsT$r<&22sG{SPa9Zte{ z*)j=tCN_k>GQvPIXJ!2dy?=C6z}kPd-b!m5c4Vjv@8 zAZ_iU1QEi1Nec>dXM}-dR?R*OwS>_V8^l0H#6TKhAelETfJoLAF_0lKkVY6tJ1=98 z6Gqs+3E5zlGcL#6l_4>ZMi@vZK?J>_Tg&a3R9g;w7HTn%5tq;NghRG1NNvDhVr&Zv zpKO0K>k_w<=Me)L5(8<3fppJ88%cz4$Z-q0XCZ>x#*bsAWgwZSj=jVoPz&GIGLVWG zNFxlSdlrACCCqsfd9z!a%y(MFhoQ{(>boh=EkZKpJ5n9Rjt`V=M!yh=DZ1Kn8Kn zNzvKW0E45X9rmsid-gn@KVqI;1i zcU8nd8et%v1QC>z1e|p^22v3NX@r4v2-L#Xv<##o2GR%v={y4w{H>O=8OJ~>Vjzt$ zkPd-b{N0xG6vsd+Vjzt$kWND0&8s)8XC&W>7)V77WIQW!HV{GFVn7U}_!TjbiWo@S zYw=mAg+16Zkct?{NEpa~7|66RkO47}c8){y+8~~bQodVjoFWD?5(d&qh=Ftnnjr`A znV_CW45T6kG7<*TNoaN-yfdtr_2Z-sVjvYUkdZKu&ITfA-p(t8EZVIpvNL*o7HY}* zB0weW4-N~f3u za3x0s@d3P6Rc717Kq_J&W1hhwP>VP+*Rqy@RK!3=!axS`sddES1;jw6gnv7f~lW> zSUZ#H69cJ;fsBNKbni}lVn7UJN*G8e2QiR}7|2K%NGCxAaf<;lkd~#e45T6kG7<*T zAy6w>yTm{$Vjx3iAc;>5=!8i7^+ihVb7_eK3g~o7KXW=IF-3})BFiD81QFsTex~Ha zMyaed?L%gx5P@3K2QAl6t9RZUtIBNbA2LUV5=2N}@iSQl@o#4MY&*$-O|%dLbrN z5tAASlj;ztg??-g<8q}@uyp>MAN5DFnhkw3ULl7 zt4eLACo4}SPoy<05v^e{yoQC=s-&3%WpBWl5UpoP)2bIi&^noj*2x%NCxa41pl#1P zXvRkKH;*y7)ISh`S{&EO&&0-urP@c6uNr59Em&owX)Bm zwYAwq-`L+&3vQ2@=dGK5N3ihc`_1%~Ss_Xg@!$4S>ig4j82OMjq1q1eDsw=J$`w)Ssta@hvbQh zJrN~{kQxyiQdf$-9TBJ{}Z;c)J2`w>D4<>&^4XuOjj*C4QBPYZ2d&%EY}^Y>;0?^UPA^AELw9w&(Iz{ zhm^1UYxU|yeTNS3Rb7 zuh|-`Oz@c}F27yQ-xAGO>r3x!Rn`?!ihQ1^;dS4>n=ibMtl^hG{~ROsR&8ZM<+rw> zA17)U9f?|(XNcQJ319GR0RYP%|~5jhvl=YgMEDXU*@7I}w9aV2#tW%RswQ8yuy2VOOZw+A-Z zpPX&y2&SA5ny^w-&Oe=xdK|12Ke$XRFFlXHp;TFkK9fe+E4B=GO#CoWLkkiZo3YwG z)7p~Cw@{{1E5RDX7PI2Ua*?oZoiiR|Q+^v4SouR|p zW3E)op3RYg2rQo+$%{nO@AG-iFRc`7Sxt>TU^^2%#Zin(7cEG{JXs|AWu3tzwi#uW zW&Z|S#nn?By@@~z5?F?e4JowURx{f)M+qX(f&`WuWAiFCu>ZccmGTRf73Lgs+a%3u z@o;lIf8y*PIYP2JhMpau#8C{iAaU9eFP^8{%9DhVkE|O~Ia+NQp-lLRK(9-$Hw&fV zdhVamDBb#Jy&Rc3lvGqo6~;iXfXwlNk6gn8s6R6H_v8YOo;k8QW)p#};g6_zv32Gj z&c2PUlCfFcyc~m$6>vloffghh@&s|^;~%_j2P1~^A-yAUZ+iQ(uM;)2AhBcnI?>Q; zIseaDRu}qIcKj32(I#muK?1#ADhZe4dd8bu#Ad1vd@ zu8>lS@`2ZVL!)Spbc@9esx@m2Z&^dBRPnuS9`z`+AmM*yhIpH1q3FYmvN{#nT?vYK zlV}iVK>}0A*t5SED}7u4X*=*{qJ|bEjIr`ZJ`M&fQYz=EX1__}E?UyjDEhuujCet1 zg(X5U7LQWO%unNJO069&NW71lBb4r&#E6?l|LEtJ(V?~O>{vk~+(sHj^ZHZErcw0L z*Ue&QjrGDiLo4OLmUvMt>sHbBoI&_rzG!c8Q+1T08k`)uQf%6qAi`6%QcBY(I&1AZ zXB}9HS{*0Ym+BFY`;;oQAc3(N%iAlhZRwZh$_$EuHHa-HmPXNWrRE7^)MhNB5)qiS zWM}0L)dyOT=+k$l@Gdf4bW3Xxfx~Jl?FZy^?4bJxmd_pcvI-XDsq6G;oL&iqsUt=3KYlPzn)dyOT zz;dIq`d-hT`%tiRUV=Ht+}5U1)W7I_@!DBd0rT$K!^ZbeGEmOZf<)Bs@gnoqNU`sV zk&gwFUfBB$?xN)Xi9oN1PdAIAW1>WlLPqJH&6vuOr)F-YJoQ10fnHT<6nz%5Sa9bk z+Vpf@N7@~k9fIl{TSE+uqJ3+uc8(0#DjDmYF{9%{xdM*EM4$zUr8N_T@2(iJu$z%8 zEo&;rpSwKlf72+679_UQD0)jS7dM?{^{sy;M~zOiY;!0dNT64$fCLe7^AC}n%ZPD0 zi{hA7qp7U}5okfen)91qG>32IWi}%pNT3&%8)KC><&cS6|Fq33*g|VjaJyL4Yq_}E zs+oc*#4FL=dDAhz)Ye_w*8aX~=@a&7;nQlGNTLZ7)<0vJ_uf{Ic-7J}eS4+im>AYK zO1$ul6u#^I6uc76WPH!_${qU1--6Gm*mjd6mWpKW?Sci?QLq;<)}}!Y**RyRZACYC zKDdz&ykFscg|Rv3kMgCLyJ=$|JWz3l)Fs^#F)m^|51P*voDDD*@%WY+xu&MpKj&K& zXUM(cqeRu0TRH3Pr{I+s%dqMkFF&=9e7fv!6=yO>Yb+JhPfX+NOdSR1M8;AgTpm-) zR^7hoY2`m^dFm{*4`=HO^2PM~mNHp*Uy8FCzn9uV#jXBdsg->DK2aK6NZ7;x!{Xx` z&YM@A;`C}>B3x8l7h#)5|9-X3WZt%Jtj!hU&dRa7jb8>4w4s#PoGrI%{Pv!<)zNTn ze&_E+1vt+$>M>{RJH^-)^-s0i?eFfvRN-|EIwgg!7~_8VRPBoPz8YG7CQ?%9it*xm z-fE}!Y}yk?*Sh(*iuiIRnbHE=^B%8OdqxP^~`(zXgNq;K?hq27BQ9Mm0U5N%*#+c^W6;ljq9eAI}%tTE~32% zt-g5cfBVpa1jcp|gJw>t-sD9w|DSV?b(4}O7h(K=|CpzKMydj?`SOQDbE!tWsIV%$ z{s&jNJ#AlzYj<<2KZsw?Omh+`mY)f#f5oVO7ty0@<7#JC6yI&cNU{7({BNoZ7762b zikIeG5XWQiv4G&qPYAq`TTL(-Y6;{mt=;?#`+DuH=D5rt^*IS}Dc;Th1qy za;?1lGcD$uy=L%TG#g|rciy!21>KuFqG(J+uP#HQd5J6YxN#@55_b|V+TZ6@9Ce96 z3li0m=J4W;X7gxoBgUTW^=uz^wsh40DF&wSMw-?9_oDOpd*|Jt?_W1;kq5dts?mKA zEl8xD9M3OriR3+R7GoTCMaxlwcY+isiqjsJ{%6e;z<_Ps`PB_|QjE3VHS}EU_#Pj4FTlvFh2GQALoh@g49i=Ok)!NXNd-J z+LH8AG#Iv>@^N?jpY0zKtJs&R(A`cwygJJyLl}vsbhrf%#)B)0NfsJ=I4j zC#lZSf&}J?v1z%|D8D)0+C0BlOIMGI=cQ__cJ@0gX~rH+xN0lDB8%ch1X_@oT{D3{ zS{cKGBAora(n(u`jwb@weVeGE1&J-&*YTBdId{$aJi_uQHAb$px1ktFpjSk#1l}%P zG_P9Lh%w;za?0x}++Lgrv>;*awGFFPQ5J5s+fz}mMFPFB&y#YO=O5eN2{t8|+EvHD z*6{gRW{7#TM$XzkhF7As^EVo!YG>WZ+clXjGG{kZb*WgW(t7Hm#7xw76TfZc4-(@< z6pgP1PbKj1!OMm3(_m#w{5l>?Yv*^)5$?#j*S6!10*Xqh!s}M~cP-CFYv(&OmRMt? z8DmqL&--AzNHNfY#9*3dT}!)AB&0V|l{>JdGHCspz&Vr;v><^gWNhiAValh!R@h!s zyFv>R)_mOU+EJ-GC9VAhr3x)YKF9NPwPVCb$}N@%V>^5JD%;zAwJ)Yrp#_PynK$w& z(>ICaOh!Hqz4LU8cvsp{j))n{7xN;tb~Y5qz$-I(_Ll3#)ok>;`F!53z*f=6sV&L$ zeeLaXHg)tOVtk#YJY;i%2=Zv9cw|~(j111Ttd*FSy`}x@vNnz{ln=BZfw5_g(=LrI zII)?sgkoR~VvCvnd>J3>UOTtd76fi7(^1Jx1X_@&(qk!KNo!|cXFhV5_fZzk`(|HD z1eQ<#3v2i_T00vGq_wP;R;_MpF?^;&BMks8Nc11GhHrefO?a;`M$w$T-`fIC&T@>R z(FZL^U>P!|$Hm&-q#f5S*=RA0jmvV; z-hWGHWg?BcXhGsz6^eGp@y*O#RE{64LnZO$3M=dRfuWpbu>_!5DwAxfFgN735Zcs7BplE&Rr865XT zR!3zb(1OIjGpF-|_81Z0)kxK|v#A_2yQZ=qrL{9!kQiNH9>3{cJMVg2(b4-uge{h0 zAc0;L7ER}mum2$qu3J)T99&y2yj#G51bSgxpr=cdBh--EBW1PfITW-YLHXg7 zN;AgI&i&PcB}dB&`G(k#Krih7jD<~#&{@rqvfh(MO6Lq~-08(}1!>0CjW4E0ofs!y zu54mQ3li2Co~f$I^B&b?r#v?0V(EByDdO0Uu^Fp(JHPZg*+`DhKhS{|BrqOhjfM=9 zr!zvNP;Rpckf=G5-SNeWzfLCMQDB+$z`?%w-7 zLLERc^j>3aMte<(j$;?nj1BkrO)dCvw08fMbhfLM=tx*&)h?sOhJLf7 z1qnzW+1EX0})7wQ%i(G%4FTe$xv)7%g}I<8D{~Ls(;c zq;WksO*Q!}DamH`qW>W>U+G@Bv$L0i1bP`|WwaU>5!Ixm?AxTac4TG&2NLLost99u zCP(P4YLC=LJ;|=11qq|hjn?mqk?xQF`ov;1mQ)*RLjt`}b7HJ7jnZ@<)VAJjq!_tN zNiV7`NHbQvM=^EL$#L3?#Z6Q0gU;wkSYyyVP|KLAnszM*t?*p42`7Qt3C3nD&yDc0(1HZUW9(DdFpcMmR)4E$PZ_VAF>qW#n)GQJr7u#QH(fNtj^hVNbC-KGVOKYG8gby)F%vvA+4NoStfS{$d}Pa^^yWzr})|9!{VxK)8P3qR3N z+ux^v)@@I?Kmxs@JEd0Y?;&DTCsM$heHtx8Z>+I}=^gdt4Cx&^9glce%6to*HU zvQF6|dgAU33dTU%x1@(7x92?`UQ|*(vU-fu@?5Q=Z@cWL^c%>OldtY_mT!Sy{+a2N z@PUu`+nGlLeSMfR=FwdquEr6u;(Z(K>#&Tn#o1^Z66p0QdWUUB&FfT8zNKmIqqWyY zZ+@shsTQH5*UL*MZA(|(;4J5#fmWhv?U(8cwX>{QKZ}YMB(8Myu@30d+Qhj2`Ul$kJ4STG`IY(ViS3%##N49{-=-IzwW%j!~3l=N*9Q{=~_vLXF54? zLSr2*NMMU$ti+Bka%s>z{dCLb4zwU)ZC54sPt<~r>`+FQ@)g)8uw7aE$E=oPvL%SXhC9J?XvdTGoQL>wvuLJyXns9xvG~ve%YbKkH??8EUlL% z&f+gP`(veIC9=kp)IMaYEhCn#w^=MeU~I<5p2(zjUOirxZ1UC?-Lqw2@i4ls@9V1U z>Ggo1RWEo@i=~t&h|NkJd&U2$JVCy#lGkbhf?+&X!rnnXYLi+vo_*I|>~@eX%eW^r z!j-KWG`Nl}@9&R!c$!NJi}kQ2RHOW5+eBsct$#Tgm|K+#a!*x|Krc&bS=hu=`mdw= z$!m>=+AS8mE~bzboI76b{Fqtwz8-JGlwdq6LtC$2_s#kkN_7!Qb#j0AJR6ls;C3Gx zuZ;iwmD%<%{XL%4Bn!6^l}itoH)8RlUQTzt6`p9%J|DejY;eYX7p2>=puISW?T8bV_Qel^htNou9Zy&D(yiQMzsm5|(&u#gWnSNY1wE(HVmU-pQiI zq;}-)MRzhU8ECz$4Gk_Te+#Lrjq~0i(1OH+KkwUDZ>Kx;%>mUJdrErApV1R^9-P&V zJHd<uPdUbuUYv8$w)v?RS`VEG&hT9Bap2xB(uiotsIS9_6O@}|@f8xrV+ z`xY6SPOGlZw5q@8nkTx`i#tJ)W^DbWVtQ}VOYX06>Lu>zNLXW}CB5VyT6rDucFq&s zrHH$6X*TGNO~R4l4>yD1QO_63Sb?V>Lw4|3r zu_R;t;f{`kHAZ~ZHgSEZcy+Q$4h1bpm^Ew0xc*yz^*oJNp(TdckU%foAxJw>XuSGLy=p|V zb6sn+E9bRv&n41~r5{yHKSATwuobTH%IJGWi6UW*k%7jm3)HJV6mpGMM!zr!-1lns z6*C_(r0Tt$* z3{8bXSBkZ_e24j0e?PI|j&_{m0lW1bD?&D`1Zdz9(4Q>!f9n_NpJC zJM=Wa0(RErbzq+H3o?&dadshym@#V82-=$d>iTDLSS&zTQ&nnOOZhY|n{1GM zW6Fx78@MLaR|H5&kl#&HvA5g7r->*0?`X%N{%*Df8c+pze9$ z=|Bq-3{uEgj<=`vC#Cvn8%P;7(o5@FSE_Eq&3RjX$YQKH z-2{3WC6ba_+J7YnsQa^w)}B>(WM>Jd63-laF2X(H6b3OeH}9Jm(Eo*Ck3Fj~miD%X zUiaa6t#^$cip2s1#%8SBA62zp{iARVMY3bz6&Nr9B60_i5u zi*ytRDUiagKx(8w+D!#gAq7$laVd}rDUiZcAQe&|g-e0#_VKX#~{_nP3JD@p=9^GCz6U83S>nOx-(y@ zqV`RQyM z4FyuD?d5{_hw8tzNOy;8HNSGw9<%BO^>e2JX=r37F{}1Vy`0urTOQ<8Al()uOnuHI z25<3}_bS`8m2(g3=tb(FofJr6Dv*ZOXA;JpiWErAR3P1!p9tFzf)q%d6iCffAl()u z=9jKef)q&MQXn^mbX0F`8KEtlQCvmKua`U8NP!fl0_nbzQ-M@Tfz(U|(rrP4O4s(I ztd1|qtzD?pL~H!ZRgPXUr;pn{?7Shu2RaobeIaHyXTOe=x$fm{xQ4d7+HR1f}*$-NO#Xc0^1wy z-Z?T_^T^p&4-Ru`8SXwo%7j8%hA^}YYyZe!x~S$mx~?preTP5`6872mZL@b$pKsoi zw2X08zv`uTwU&vC`l@&mDQ5CIk=$ad2;aw*L;tN2UrKHlEUS&it3#Ei>5IAs%bxz< zEd+YuSqIuV@ZU6tM~!iE)$a0^QxHhti3n0pvZj+ht6RwN@nI^a1XI}MuT5g^#Z4mV zwjZTxf}UUY_|I47-E>z)3lexDhOvYHHj#r1XOz1OL|6#)I`m8*+uB=Cd^W6>>#%IvLXiQlR% zvk>TIXFJ5j|Dwh83r5bp-j0#&bKCUnS(b9NAb}@h81vlOTkh=rjW@NOQIS9|>sgtR zX}Za)NpWiKLfb3^dLb&sDS_VLc@@rc)l}H}BzEn~w`D1bX#>Ge-0@{LWg{ zZ)snx?DmN&TJS6po-v|U(&rcL_j%>DI;R$^Xu(rSrGg?w{a>QQbZ1$OJn5$$Nt0H) z<^NJe3ley0lN7HpJ+%cRcB+3rinI{uHKD~cu{bbVbeX15S&iG!QOnt_wpzXZOBF3h z;5kn^YdLPT_N`P0{rQCH98YHkOo|kH%Wn|jbNwu*T1hXNQboJ?Z=5dvDQ-D4ibU1B zQ^n_Qt3@}}sKIv+M{57HJ*b2ROi(d8dSPm5&AH>DqSR|Gx8L@(oKeIvs_Muk!cl#P zh~8qv2z9JcvwrU>gGww@@jMrLWzIWK_}AVhP7XAP?)C4eX~zc1vWq@i2=u}em9)Pk zvZ?0RI=8&GCxW8|2`oc;KSM=NZIX8$+4@Lc%h^{Xu-q7nJ3mXbs@+kht>vL%ZgHf> zJTcaIXl40e;6IK|q1CnJC$@`PcVfj&UQNN#4#ybMmbx|+b1Rn9t~}wIXR~OrC+Ae* zaiXe%y$gE*y`{h>Qk|45m-et(Z3}^3*b5lzF(a2YcKcj4ZE{V`FV9rrUo2YKc2!ld zvv?i5>MU1bShMp?!Um{&nozP*g@%s;4bG8!O6s?GSz5R8_Eiu-q6+ zb$*eMxq9d$uaDBqb4BhmYANTVUam{0)0rlba@vW`_x;^MT{drwW>`|rE}34=Gf~Es zQcgj+)CoHgONc;=8P9np3a{iM+Mi#ktD8<9EuLCKoZ8h;IK6BE`$NQp#_4 z43QEe#e&y0<2g&j9YdtVKqBQ7m6=)~X8qklU;d-4+@*`ekJ3%k)kkKh6<(?nQ7XRu zKs~rlG_JUn2W{et^{oEAESL1dkIHC`^A*<6f`tE(jUuY$7M`@aD)sXMo14gmLo#XU z^G#HdK(Aq+w}^zy>v_;jW0p}cO9$=TqMB-@q3>0Ex5$DgQ$@}PG5r1#KLy`XLZ@qX zb=IC7{ad|~XNHOvB)oP-iht*==gs>VBQ@(^T`RUet@hyVQwxD!cruh`eXlEM#m4@k zE&3Q~IWvj`o*$)sWSv&3pC0tnrfisKIhTrFct(}6U$*#&m-j|%YUB2547}e1y@GD6 z5lI#3RO?1#es#M0G<{WkOD)qurXhh|ShI}v?DkdvrFm;@)Pzt=og;y@$=L20)wP{N z*XYL|7S$G{U~GEB#`i4RrV@E%`ckpkWYo}t1fDXc6?bjgwLEp8jGffWauyliMw35kg9!UGl1KJ4 zV!X~?lB)?LN(sG$W3Ym8R^w3OrW zd1#+sMOgYd_U)VLwu^#FEbV|Y)=@p~G?8-aZZ(NcVdKbvUe=S|0r^5@%Ojc9uLHNL zXhFi9!#mH6(>n*E>4{?Zf&AUfuN*B%crVy4&emMQZ}v1spX`(ROMO*py=I(Hkw7mz zi_X~B$nJ7ZpQHNgS3^~_Ac1dmp>YTcA#vAo%mU^1c?iu1xtqt6pW@PAv<2-4WRq|+21v;x=AJnxF=w%(@ zR-`W|mxWE%cT^10j-TBj@)Tae3qGx?V0~cy)5@!_kL;2^2S3uhriDN+YkjZ?Pr0mP zCtkI3YYi<(V9hetbYdsjv0+KQs^1&^M!BQH(RvZ-BH61)mpv}Jw4^706V?Z=+I3V6 z>t;L!?7oMw{9BsJRBxm@rR5_XElA9&c1#>^Mo$47cOyOVOOU^mj@SB`3m!5#_@r2~ zEJ}ozN^L_T?BEIEuTzXJW$3*I$tPp=uFp#ABX5VwroE4gUPtDNBylbf>8QP@M3C29 z5ws>F5gvZ;^~;me%D#iDO1xH&i>Jk#+EIc%sboW%-j@;MAvc}dp~qfqU`Z7c))?bw z+|?iCRMmm`x>yKIA?As(YqEAf2e<}V}jqB7vq6Go zA!7FDIBL7e#c4NgrpDUF&<%RK5DyE1UVih!#PT|8#Usz(sqL!wI%o?T#)~`sJtSI? zIPfY=%%=C5xMC4dSB#BRvJa?)!zfi~LBgnSqkdd5nh?>_ASebB z=w;NmQM;}fUmC=V*LOQ;y@)^y5=Of<+L1pcnQ>dWX=E)Y`0Pt@NzLLgdrvVPeAE?IL@z z&w9s(P?Q3liAV=&rUtlXm#j173)SSP1k|Uk(((F>}OCXN(mm zytE66clm6JffgjNr!n?#VzOE#cAC1L@___;#pfL@n)ZwkEQ?WAGe3P(@9mwguCEp> z(Sii_8^(&(KBC6;I;LK;g;)sms(Ud)1XUU(x@7oBF=~uHp{n%PSPzzHK>~XkJyXj& zS=DwXtDOq8wh-twzw})3a?U^z?kuaAJ=4{)$=}pPe!&tgNMOHV%z3`4oCts>|)PKF~p^aY~ zV!78MVeNzc8kW%h>YYa3&XryED>6^KZgYgj46z&UgBSYD75fex5#jUZQ$EJ*DW}~n zm{BgJ9qVX80{bIlGcMg!A1~jj*Kq_}`gy8Rvqj0n$3##VvssC&(Pvekg&XyEgW6f{ zwMbxW#)j%#R$UpX1fDD>@hN*ko2-s;``(EzfgUz|R!D8PTP?ZPW23SzxRgY%`k|hV zHKXnc|GVD;twix~uJxF`Po32$o9q&J(Ux@Tx`>(kJrJL5;xkXiS|z?#OV=!+CHF00 zA<(PPKYeV8%4Jb;3ZuDbbo&fi;IeYs#@cBlT9Cl!xU?7NXgRfc;b1L8y-XIu;+1pN zzL-P*3U>Po)nJY(RnYb-rK5B*Gp*j-V-)4h{cw*M>LVgUl5jMI+4a_MFLS0%LF$FfKy&A z`pe!^&Z;f+ED~!Cy>LeXwM1TBCR8oTM~ts*A<)ZO=dFXiw6^tX@j?YceSG(l`ae_El35#C2=u}dA-z4&SDVp0MoD`=NcIWKuAGZ{C&Fi@vEgnJ z%oFXPJ5@qkmN-RupHSP952UR`;r6}t%`L0yJL?RWPg~65FUy?}NgkfIKmCXEdJndX zB+ul)YQFR?q)kUf(yeRMO1h1`riXRdtq+;pN}>gcsC;Ai%$Ni*$}fV5t|NS8(1Uc6 z<;yHbgpTFWO=zwjo_g1#fO-6%ZZviUjq|e-HDZ0`-ufA3zP#xrT9DXWF^bRsgXmT@ zC`O4EspO*bf9roYt!W|93sXz)18BQJ^=Qygi^`ow@`efg*q@_C7g|lU*s+aYqZI`U zQ+LzMiMwWGL91ydGhl-{l~xqSY61!LqEVawn2~*L5YJO)eP}^~W`Nu^vovDVZWzxC z)2uHa&H5|^c+uU5|Cm|+x%yZAD$PYF(d-p1cwL&wa@P#mh*6D*4n%Zy%`Dy5LNB_D z@*gwgH}Z_Wkml6STr*_11qqswbJtAYh>AFp?L*W_NvUYxQi!ZHZ#(ZXewc_@`Xvy1 zSHW3pdDobJqM~y~W;@(Yy_G4AR(Dt{i54WV-_V@8Wd(lpZAR^n-`ZFR^cs|5DL+js z3fD~k#i@4OE0wp_k7kx=K>~XkW7|$W5OZloagJuMNT64%m^oab6@@Ft%EY_kG|gT^ zDF#}QzW!_fEd+X19XN__y%b@tyt*trscQ>Qs(;do1uaNmzoDnQt3K(Qi_qRP zTCpI3UN`3qjtB>L$#w-RWhv81A|okS;1o7v-idYTON+79`BOj~Rn>QAxTe zH+4}rfnH|IH)D`4DoGdBOZMco8?nLXHyLAt0UT~s%9 zQRBYtv>;*52Fw_wi%QZ(byF906X<1*L}m=qMJ4H?($qzb`G?bjggL7*V~{Q?Nf(u- zF6t)G%N$Y77^I8pq>D;Z7d7TlP74y|?97Zox~NXNs5Es^H-TQ}oxzMjx~NXNs5Es^ zW7g-iAYslj%^0MM>ZFTGQx|m;=w;sF%owDL8Z%^R>Y~P6)M-J&oGqI%NEhX#i%L@$ z{Xw|q>P|27PHo26+IhViO0$_(G?PIKUKe{aV>jwZMco8?k^0F=7v*kUR3}|jH+50B1qo{(BwbV|T~s%9Q8$5Jq<(VJMY&rS z)kzoCOolX_=gKQ68S6i|V9{>ZUI0wjg2cgQSZJ(nY1I zi@FK)BK4D#F3Mdq8PY`s>7vrqMco!8tbLGlQBJz3G<8uofnKD3a?(Y)TNmY|i%L@$ zbz6|YenUGTdbL;EwEm{Qb?KsR0=@9QOS?t-cTn5k^pKghhDfv^VeNyDmKK$(ucy+! zcFQfB)Sbus&}@c<7x5#N(|sQ#1(K64%H6uCBwbW9by2qk3G9zfT~sGsR5f)`cRweU zlansWO$`MOAe0GQKApKwAJ;US{3Y7tc7WRSa-m6L;NIdxID1qpn^4r3dSmeWZW zl^I>SsGG2OdefTA zPE(w^sGDHmMJk?+bW!foMZ4~;sA@er$$5R9y66uJ5Ttmz--|?VVk?(k>-(~VEO^|h zi@FK)!nZ2X7pLy~YjtLw)$RMUNUSyV!goE6Xu^>v4XEChOC>tU?jh2843PfVU! z=+s4Rq>FM>7j>5c=84q7PhMKBvs3lTIh?wvn?NtjpHml=D|^Q{OkLDLx+phwQTLm_ z@NHeR2l7-2naMuIaf@_O%sJ_zZrV!x6Ju9ve~nhJ&+jUgwX;Q^fya4JlMFV$nBih_ zl^r}Gms1xNq>GxXiDBcfs#WjrQnOum>Y{E75>b7}h%x^r@QS4jUG(2>rL`iN(`zlS zWRfEfjiu*jG*@RQcmDb@N_?ah1?@rIWhJhbDz7aY?4=d&`B6s;610*Kq>GxXiJJ9j zb@%3P^+{vWMIkzRkuK^^En{=r4bofW%PlL-tt(%WhC8O{aJtjq2%NWKoA~9)D9#pj z3M^lCgDCaVH5;VW#I?a9Rpk!)f6GS81Lrn~h%N(p+ajL=eU5Jzhck!qrUg^m@Je(> z@k3+n(Zt@R> ze6)D;V7eJ&7!i4hxK61;0=?2r9V@m+&M;&6j4rE%x6CYyPzV@kqEs$$c)j4i0?$)rWi<|SGKl`L<@C@8RK|l z2rt~Tqnt_vT9EjQuM!nwT`L(H;fVOuqoWi*5$NUZvq}VK8EnQ_nbD?u9d9E`P(ILt zgtZTT``%RVxHC}3gp{@r=ym+m7V&R|(G=q~y+83`{e61Ztu5uTbhmW0Ac1|J&apfg zsK+m6@}z%=rJrNpMw+qr3HOA=+4g+Q-S^%n}io&9)G=Pdm5K~Mfw^OlvH1xvIbfwjrl zxzk)-)grBY*eb+ApjUx(^rbX5geN(7a$Mfe)#1}KNZ&@m5-mtztE3$%2iB+;q8{k2 zfdgXf=E`A#~ffse^yQeqBsvojG(eqboCDDQe_AYwwdDvxjwBJ^J!e6Z|1bTVT z8798TX`E#?cBI7n{HJWH}#3F_1v7u}}L8zkciZ%k;+1n%pC^XuW$!^RE8}OSB+?cOQD< z{^YxwF>OzEMb*|80=;nlKwmQR^w8Q3?5Uob8Y0nx1l~m%d(o50(PszpD8~pF6vbWtM@2HO8+io9O|64%PoIGgRKZdrD+a zGnaSSmC1(jaK=H;An)bS|9nwd-w`req6Gs-c3t&|gI z#u==X-*gh`z6YslzfT367xTG z5h)fVDz8na_dOjhVwy~+vN{*-!AtjSFE`V@P}`VJpVD};c-w88Gao5m5VR7Zk5h{S zsVm7_N&XToMha61<9AAI`XcnoEsp*Z$4I+pOJ_ew@%lMl%J=-}i|JDaiOa*r$fRbC zoJ5KR3A6r%(PHTRqVql~Id6@XZ<9Tf z=twz#g=>UMNv}cBXeW%(&YJVu4^BF+->WMxWGbei1qtJKN^HgkomRwTt(HvmDfK@@ zikCH2Tc@>`EtO}Sd!(}5)kZx(Ci={zJKV{rz~}s^Xi{epXWqN%y&nxLmXuzbs%xpM z%+#M|`dcXb>51E@VKx?fLWEr>qN1-Y=c3c1cni7@cBw$EegDLq^5)edTJQU5rNsio zO*-Eab7&rCr*ab!IDM5~sr*v)#NJ+(`yk%0tVC}4O8>h~8U4kEP7>3O_d&d0(fO$Q z^dzqI7k;tnW z=EKCye_mGci)^hnZRgX!MRQh1QSfVU)MRJx;QY*tIY-TP9-FE9G3Q9N&%NbbGC@2BrtE~%bFdY9X8D;nBDyPPnM8}Fbq zzLASxRKhPGk-}2_1fM&#hxR_tEfv4vb^c@w&op?NVBNWb->af=SG}iB-d|h0k?paH z-*AhIUC;CEj1&n~6a}wD>PNXdYNPCRr26!+ieKl-@O3?Z-D|7p;;8o17r;8KeqLhs zl;7e=O_uboL2kUE(3o?XPc7+p&}#GPqVqSsUv%Gu68+Z?{2v0ns5IaUM-5I_C>eIT zf|J1OVm#dMMe`CO8k+=Kkf4-uYH4Jc@>|KXtDn=8^l*s;df|RA#$K%(ShD5b z2~GknNEmO2O?kT@y$dOLc*z^r>--OaUbx?j-tY5hOvx9zpmR^*5-mvJ?k)PJ-i!ey z+fN-|!XVIsgptCOHyF~p)fK-zS4SV9@zhG77w-3>mN=~1-b%diKI2Qo9|vyd!?$mt zQk=EE;-m%KGn)2qhL^2o)L_cn9_bw9fU=V}3URsJZcOH##5@uOEar&;Ou`)8WqtaG&BbuoYRw68+*{rBk4C@ZWFtOIN@v|_1~FQDDi zPWz4eKnoJqc6IeqlT8z{1pV@JD=|`-(lW5UQL0)W-1NQm!Ey$H79@)cJlgM}C-~4jO=MKgWBk%(+L_hxR3Pq$!hKSV-JCd7n^8CupPpxhjxq4M zNwG(H!bD>{enc8TCbhRVcz9dAmygsj26`b)_m51uwbV^>X%)X@wWJEYFole*4$iOT zKP~v_8x19<*Z1CWo~_^ta0GnYksW_OR_}@$pPEnfCby9{%SuJDXa?Hox#2Ucb&ZN7C&~w$|_7@uF)U z+KaAAOEH!X%&isKc+>uCaVvpdaWmfYn6#g5Mek%HVpP$bTK8+QyyUTFvQLAzym{14 zC45~K8+zrh|C*1gK>xnNh*9Wlc5VE!jB3W4O)Ug^ZCv_<&zhH$8!4od77-b>&XYQ* zEiX2gSU%{LVfan{Fn1%~#ovfg`$k$#Mow1?*Jx%T&?`C9d49QfI4_#dlL$3UY3*I( zD|*^qMdi3%7x<`I;exHLYr~SZmhSfsRkQ+r4*l4if))b3rmnrs+h%M`=K|_cjKmEU zw2|rd>TN3&muNx4Yt}7Za&`lebl1rFLvOBq9ywRf^QEALK(EB+&-lw7IRx8Nmx!Uc z0<`JXX6mOF7nf*3A}-5Q{%~D3dMBVWhN!Kz>FuYlY*ENUpjXuLw|vg4U5@aET`5M* zam}<=nHuVgDtbw@Ac1X+W*KwZXzhJpi1p{vSqSvP7Rp#&pO#uquP(}((%EI7n#r7n zy|%F(?QH0UZH)Fa)D6~h7um)CKAFWrpcl4KT5XF4THM-JYM+id{A6z@zvGKhl@z;&*)`siJ7XF(e_Wcs%G0# z$U>l3`1TY0<@`CEHEKxpQQ}rvEyv1hYR(Y_BwCQb-L3R4z4MpUXG|u2w61<| zZ`^Y~=PbjVkvT26KM{8~($nzNW!5Gq6mq5t3G_1Ok7kVjzKx6fqi*T{$vG0ZOOwth zK1yBc)vOZ#OSsN18P|=)QlR%)ZZG7sf>LJW+?@3}qnqmw=WpC$%-Ej&^ZfT$SiaYo zCt^)u4H|Q;A7#}h?S#F*N2YhqMe$m=#|vXKwx)R{|E|ql^LDf#VO-ycuw!<;8NuWQaY>G!Pl?%Au8KnoJ)Ox8@*r2&D} zLwf6bjTlIvSFX(q_`BhTI{%X15r2QL=iX%->*+mT~(OWxFS?Cx8y^tooq-id>Hhpew?6<6zRG}B9khH$|ZDM56!rGl8^(Cfv zPQV;K>dbLcg!9@kHfgUOQq8r#f!6x_Crhf3IFn&6_w9ayhj%h&`qQe0s{=xsYU`S2 zw4@5XFi(tm$M)t)7r(1(>UJ{DxV!gqhIh-Vgk`2La-Gg+t6ylfvVPwi+G}9UcZ&ty zQ!8atw1DtbGQPl29_RBf4=*3uCEA>v%btkp3Mf8hR z^z!dGn_16>@kl-YHeF4d;gb5xfld;yh2@5^=^dsMCaUXar`M*;Z6^WB+g&+^)b>u4Va z6_r>fn0Cw)eHmy`d9?+vq2;Ys+(Mw2HO7`b)zmL*>S`U5^GmcKQL#ZL{yB-h^w-U( z^N7{q>cT!;%YU$lg+MPX5qie*>Y#e%m8PYtkjYYm=;gg~7|%QN5)UumfntnGx~1ma zSY6AN%}Ssb)<0td<`&Z$-p!`%+LunAnV44bnfab}*Iy6BHilo8WUS=7yxN;JC)MTe zD@iO-B=Aa%Rhha(t@>LXZP~@FmKdz^SKG$#)W#Bu{M4@ItevBl@liBK?ZTEA76Mu* zy^}25Pb=M)X)C-w>zH2rwyZT({%e2H)*Y&#z0WpNM+*`d&vj4tIh5Xcuf=Zw;&)B) zYofG!r%dXNIg{RQH0}mJ5%!cXp3;{#;QNDP)`V|VJYP5owBU8|Yoeqf_uIKKP5+($ zL!cLaGmy>?F1)w@`TqF<-)L+{3ljMKQR?T*|K49P;)ZjEj0Ae&mkb$O)Gk#bX(G-T zXhFib(vNR|UY5P~XL~r$sr8`+3H&Z0={}XyD2Y9DD+NEh@{w{a^s;`juxu%NVzpBC z!0TqtQwa1jO5OeaQFiY^r~Tf3wQReIKnoIgkf3@pzS?8X`dW`{7dWYNn|+^tBG9YY?H^x7WvqGhgMe}^ z$|QdNi9j#>N-ZgnkIU_!n)bVMW{DOHfnRrJ-zR+7->jBjpb-NJtQ%{6EY|bMCAG6_ z<0_Fl2;a-Zec@e_GCBIBrLil24jOkSkF6nP>H?ah`b0e`6?1I%COsonbsN?>UWu`C zEvD!-m$%Wn?R;e+(90U5Ol&T>rbVcl_e)(%s_^Tcm_izNw-(oHk7%Z?>Etaf*E*KR zQR*C}eO_G~rk2!?|L%yUh1+Q1=hMqRGgdnq{PTu0pUgG}gyl-ieuM5CUqiI1n+oX_ zS5Fg1XPx0OPZroBvJMwXH7;>BtiCN_)Lha0JI$QVb1JL79lV9_h*&jb&=5b}i_w3$`&TL|=8p2t)4@O;Ky>R^>dv-H@Yy4tJH*(6$!2wt60{Bnk784-rEeKUu@ z-g{wPt;dc076QGjrQ4}Xfc|7oL+$Ob)ebO=mBy0hK+YV zMMeU>Xf0}d)y|CZ*Q}vyK6D!UKdHif=$JzKj$-lffDO;@I#Y!fByjI2eQzSJr2pXM z`J8$Q66i&FgPdPzQa7o~w8-3Z~?Op%&^k=kP ztSPKPQV`trL>j=5UH*NGzHt(0K?3(DQ$D_(^dG$Es#D8A0=-B(gSK1$@#E@e_C+|` z6Q#Ut=C%JYLVQ77w-(@a$aE zeRKY^ImaubbdA&)rHF4mC6ycA#X87dV(sXId7a8O66j^bGy12iK6;MJ=W}sV$rN?a zXroSx*&m(1NhySP{65V+Jg!sb;?5X&UDDXyZ=SWrShnDM$q_%EO}L{YL3%s98}|~W z=x<7yQ6G3M^fJdvGar$KmX>P1C##b{3lgNs!aIJ$a@{HAOMgZTB+v^>fu6XNcL$R| z3lgNIG zV<3TEMm?pZmN7~7U3lSl=SYn?Bn{d9PHOWmVWz4jwW+{-u02I)L4s6gVYE5dn};V+ zOMj49Vy#iSNT3&%2xGscolt#hWP0bgixwoX6zF?*>3D$0jEVuq2#5U+dl$YHoSweU z4-BXTXoE6pmYy!%jSO@oXG?thW88IG zkT6GA`gdcb&amrHx%TvDqzbQvUdHten=8iE1}t$;#8LmR6ay_t;M?D67XCbM;^0Rm z_Ww+vmwE3pV|*x(A+h>bcv31Zn#2c%+_R*vjiK7%6KE8m^-S3G7|YrvRLu0!Z^IfIGdUatnG2 zAk3!#?%1@V|96|dU`Ksfr+XSps*v#BNc8`)b>?9?b>G83qGWg!LK!oYS!ue@K0AcW zky(;?9v?I5mPjFG%$&-QsiaW%*=J|YoSDazc_xI+?>b4}wf){dTvwO1KKI)5*=L=- z*IIIhNp;)6d(^xC7Ha{eJMi^KO9}+m!Yu-8;*N(}>MnOa!oghk2s7~MGu@|;32aZ2 zcBE#qb45Gxt|M%DV)q#Jjmt+S%>zIFAS=~a60%>Owlny5G*buI6rIzLj4n^7u#sPEKY4Y_XG3quY2h0Ey!dkhdsFE z#5x>HFo8=8U)I|-($dGb!MHZXzh!AXwCBizcBip+cB;7qZ)&+<=>ZSX)BWWt3v zufAsPE-58ab?-TrU;<|chpzw|F1S6Lf7kVI0&C^_Nb^@}@X)(~hyMR-<4>0Kd@n8# zx{>Mgv1QSrdf=tnnZFBDhSC=9*Z(T;N=<8chT8J86ISeKME{TwouU_$Tzg3R{P&V#kxCTSj~LqK2&CU6Pi`Eh5e zdyD$1Y0rSb5=@Bo01rI{4?WNK&=+KZ1|M=kJZ$h&%iy7BzdiJdttXAxUyg^TEYi}8 z6q1Mj1W6f31Ga&)LqpW;TT7H;F+KVI@i_v4wL}}>p{L-X*YZ8|1*O7~xp4_0zE1;J zWqsW){L|(<4}C#-jh`#Z({6oc#)q8^xU_Hr;z9;#*2$NrzW$}zyKa+L-^qbk*G>jZ zh^1Q9HG-^ownrORaiZ>TFR+12f`19lGbAk~lb2NFJG?t`EWt#~kr>&(%m&SyE{LZcGu znw{uNXGA8mEzS_DHigQAjwi8;ox@qL$QJU|U%T0@HVasdTngFiEVMKwK|P=u>-kbF z!9=}~UF?4DLUy5N3m{t9k5Kmbztbwvegc8DYMaHe$DfV)Hby)dph#0+Y1bS3QY^tl zkaH}vEi<1T%d^p-QU@~K*_`iD`UwQqiZ2K8$cz55k!0S2XqC+P7_fmQm?&bsjty@c z#M1L@Y-?w!S&l5k50icZfwi(GMX-YrLHYHl^UhN9vHGs1gAFXf#M|bP?8M$+b~ew3 zvFTdv)RbG=2C#t%tTnLBBBuZQ-5s+y8AN$>+M(>hcP0coScWC795Hf?1vAk?cyIjjK`LHS1Q@wQ|4u z2?W*}Z9k7$ZiWm;n_OU&m=BTo;rJx7yst0SM}pq(x^=8&2N9aW*T=FWc{VbJLbSS? zBb0;CR+zwA`nc6c>F;`k?t7tq_86v=f_h*HCcd`_VScxFLF5&E?C$nV)B24_SN?0- zPav>XiEc}o>%wH_T|%E9x3}!ke(gP^c#id>Sb_=fz2WRkP7<5ALbpK{SD~}A%JVkg z&FR@yDXdTZB}_{1F5~%l;K?5LqggQfZs-ogfwPcr@>6+UdbK&l5=`K^3H$2Cnlgm6 zCB_8B!R$MsU(EOwhm$G*L53Rx_{FW zi#YMtdkRx5!33UZlH^d{iI4XCstqYtL?E!%k5==T=_llayweSAI4pDG%gTP&sxOE5 zpGblUJU1b}sGSc#s`S^qN?Hg6*4knSU=}to2c7hKEJ$s`hZJq9-3_fwu>=!%K1$LE zxijB*EP+fNUqK+S)`6LUtnJx2mKmViC^5^QZ{Asj%5`42>o;jB|;08jmvP10*wXk}^#G1smO4ZB~y zV}7USGmpwc4bC%jS-91F*ayex`$SU(&9%)O{?C`43`;Qap1x%FN-bbgkvJei4?fiF zJ`LsH+P8-I57$_+m9Umb{R~Y?>hbF5bse0TaU){xQS8q0NqI%V!M;QB$7n{`=`?`<$2GpUk> zB{=&j{w28cQ>r?*D%_T@P1?w?1QWQl5c%tP9e(w)2cP^URUojISP$=Y?!1F-6Fyyf zuVM+Vx$8j_TWAvtS!(w{%{Q(dtvxvMLHpFVFI|5zmO1>B#72H_l8@bsVc%=*W0I9Y zjt<(+a=Yzi#zT63=WSIFX~%-f@Gm=M>fsyD;!f>l9#M`mrbVLR$Lrd)bI-JQnO*{c zwfs-)V#}`Wf_ry*w&p2&A8Su~KhQSZXiHtK6WED1@hp0vql~qVecr=%)Y`$)SLmgh zmu|&VF2`t=%UTNr*4l7pA8Y+EmSqwBIryr*Ikzx`Y32KNrC5TA#ESdawyMxpH}qWb zJFZ!=)4!tBT4w|4$bM-oDs&^0PC3e$Hc3hB+Px^Y=!#yCv+sOZ8D$(l`e<`)^d8ZkbN7xg$-788x6l5mRt8BDg;ZVSb_<>JA=r>GwYIajh4#)a*@DV z&J`9i*XmKskgVt1&e$8v)?M$fPN)}1u@-*fh{TC25v=vEI77MqffP$Hfp@ZSE56k& zxl*?^YOgyYfwgLTgfXv%5p2&>> zSs}QzG;Mt$5?HID#}@YE>q2&SzFv>2 z*E^dszm_GBq2^eE3H;s$H!TV|sq*c@q}+cZfwlha9nZ>{!dRue{`l~InJSO6Bacr8 zQY^s)e*XmTd5g+yDa({CO(KD{#Fc^lY_GnRgXP)p11XkZ08Tw)&`vAPRhoWqe|Iz+KopZ!YYah zu^xQ?aB6CGM=MvY7{R5&Z%9VtA$Hp(f~9}G2sNKL#+Akmtgm^GZ}=zfAfu1UD;H{8 zXwtE&>{+YwN;2%bq^vKhe@|QRz?HvwPuY_sYjye!5(uoN$MLcb*{gO~RuPD&{U0eO zGYpD_r+*#+5?PnL*MGO^OWEUq?Vm_vM7IrlpKMn;-m#WaxoJVE@+6peQv>KGRY|&6 z9?{mFhChBq_Ecyj*vQmv9Ey{(Tts`4G~Ifda&25B>2h^?9szHmwLjIXtlZOoH@U35 zvR|dVQvE3{oUL8bfJ)V)NF%tjpI^hgdSC+EgOg5ETSF}Gd(8G@jXy+Qo8Y#ZR3GeJ z4pS{ndRx700dd0ag|k*u{}l+VrQ7~fS~xX1tu8Gwy*c~YrKM00OdPEV#PSDe-Ww`` z4JFQlcDgrR-oCV+KwvFgCrQc-EzJ`Wz3Jnm2gEFU2`kiSKB+jvS8nVO!q)hOko1+^ z<&|HTu~qK#NVERhC5FZEYdv@A}Da zKf^TTfVQ-)N!wYwz|W8;!NfiAkJ*RpBB%5G3`4*_7FTVA<^(<&{99Nn|LrB;2AT3o zYx;PAW)Hp$EWtzt@Q(#J$C49yHWI-IQ`GJlqbQ& zCGd~kYaU5{`^cJuf6S@rS|tSF}x#J*(#bd}MhNOdJ9K*o>4= z^4mvt<7kXlrPD>lN9zB_N0vumtqh+?7Bp%;$;k6xo%c;+rJW^8`W5&S^9ZaJIb$8W zPlCvApJiL{S!&Ma)Cg^r?~TYKuvWe&B=7$ro8a7@v?^?qWEFu%%xPN zLhS%Gk04D3)O2Oria3@V;xDRout+XM@WC78f-6V3sI`|-@<>Fl2&xe6w*R)-b=Y*p2DBznGXgM0Vo>Ww%S zq?%JK!33V0aBFKwPkvDvpbTkZCJsGU zH{n^E z*Y*!ZZ)uA|9B79Tl_{2B0?%NGY_zzGW<9+fUHhhjKwz!vR_oYkLjW;)=xz1S!1>yn zX5DF#P&0}pn85QNJVloh$nL6r>65GG0)e&YxHwkaHISr#)os*0zm4>N)Sn(6U5H`{ zCh+`+Sd-nEa_xCr`eC%0Kwzy$S$kM)lVD1*}$1d`hjc?P7F=7{Cm;`Su(XA3#1FJ|9T;EwfeKCnusJfO^ ze&r-D?3v1u-0p zBjeRBbxy0&-9U;Zn7~g4IE8fFRo&U>yL#fbNMNm9E4Hw0ISa{9N8QHa;1+7Rr>Sbi zmw^;ZFoBg1u_q5*U4L$3tMM9};4*h`%tcCZblC(#zr>0i>B_D>?#S%;m-xk4~viA~c zgkGv*)}@%z>aIL4J&@wE;}uS($$ja(dQ8)&G`AV69g<3t7JfYe=nV z-A22iwaM%Kj_QUJffP$Hfp@atf!tJ*Oc?Ct=66#hu-1x~3z^N+X!2yOZlmqXYGmwu zKf`vY2bN$0@5o^!o{N_wo);%B;1|UN)~W;Fgpak3C)RmhoEW?1s;Npb)eF3wSb_=s zW&sgm57-zoj+(Q3FiJ3iwZu_k=)FcB?9@;G^(K&F2`2D(gPlyT5G8x_FEZ-l6uO~& z8cX}Mp7a^-BIA_-uYB+(e5xO9c`XjyA{%(-&>Wf;jc@W zSpM`Si|zqm{2nxdQVo3+s>Nqdxo zOYnCiY#Ywv1Z>cn?Y89SF1P0q2hTB&f8e`pOfdugR`kj4Ci9rQh()Ir1sjD{_tP3R zxTU#d`g1J71hy?nM{@3KPIle+*;blRDoo%KLR@G27Fv&+cDzaVy0+$;~?-N^?ncP!U7blCRl*C5TAo`YF9-MeCa$n%#Fh2?Unh9e9(~ z_y#e_XBPQuv^#fOm}VAG)J;Dri)~;6=TL!nwFV~*R-+>2X*q#Hb`?zExc8EDuX<7S zxMhNS3fwWl`9ym_E?GHy9Mkj3;ym^6HRC^P!+>6zTIUU%twm=9@oBn@Hl<`T>oHpm znG7Lj=Hvu})8&V0pMC~%EWrdms|Zhnx?YBIIR{NU|01v!J`V};aql#j2bDB8eTK8O zI0`9_99enERx&7hG;4bB2b{SZ8=7HSyFS#=3~XQtCUDGDN!swWU0RPa|K-IN!35T7 z7P*fM4Vc1$*L?>Yu7w-PYa`=L`iWnh5f-;JI1*NEnHDM&Y?~*mWvt_jDgiFQG?bd;PtKJob){`W@N|6IctMpoNpN z#v*dWf$r+0+(6-^EGGUsXL+=@{3dyd>DHG(jz>6-_bQI|x^amnufr*Z;!qDP!32(U z4EI?082Q)v$ENkrR+zwAIEF3kcXt<;<1LGtf?>VF1lGcFa$()Q)!lT-SW_MjeU2lA z;4y}?c0snOyQS4?^?J&;{u;Yj3tAUNJhA;W#S{c*(8|F`#1c%1aVCDj!Tvo@w&0rFYb_*TtG+0%y*H=XqjL!>CWA(ysp1x>yVM z6YRoY)H0F5vP?(3J&HO&A5OE6Kf%NP>UW*eJmsmFRbIlY`=i4mTK zFiJ3iweU&=KIH7LX@%m<-Lt?3mS6&}D-a85b9K4bzJE>qVGiQiiKAxY*$iij+PTWE zHSd{v!;HcbOyIcQkbAlOSou@c39`$3k-%CwqCG@bEj>uSaJIQ&IjnFvCNYldjI*4> ziLH8`^1*N2`;eqkz0(b^i#AQW1+9w-tcCXyaBA}0chk*RFI`IgMPMzw z8-QCv?H%Nty44O%`TbNY$m5QQ36|@~`39r%_H*!5Tk_!0<3&Z?_1nw%x3Cu80m7bv zddO`bj7<%IolKFd`&e$Dsm!9qM|YeL6whEu+FEYB>eAZYy$rN2mS6&B`h=&NRTsD5 z=wfO5O+8FtE&Qa0@8?Iym=11~OjCfsb8VaLOwwgoFvO$!)&zkNK zXDue$UJE83&1Mk)y!l}@ZGT#`bSt;FU<3aa*1|hA*u4hNGYwxD?yi>#OE9s#?lO`M zJ0@e^ZfRl)KQv};Zr+VUOkgd%f0QKp?=X4V7f*v1v@VYQh$C)_8Mfc~3*;cHZq2!qi`RmI-A<8CR z)x=UgEY`#@?!{GuKa6%P!316(;e^of&8DC$rBoA)c1&O`+)ogHch?5@ec`7KDPRLj zFcIiDhV+WtO0x6%qxE15lVnNUZvWNiSPQT7k~DH%ni?K<$dL0oP{^u_-x|etwUkaB z(}H{3yXv=$Ntxu9p$TJPLA=zo8fxxo}zpG;!PU&f14aT%irlYW1!UWdB*})}g zl-kymzP?+k{x*U4xOh}bHk)0ek6kCy1N|LmyQ7u7x$flyfnWnm{vr+m!G06V9j#O# zoc|_(F3vJ3eR%`JkQZ;d29Y_+g`Yg&3qZN4Kln{6-;Ch5n93IzToc$?_Ig>7s(nYzu7h8r;dBe2#pu{X_hq+mX5~Iy9Am%zh*6OzH zPisz{FA!Ku$VDk#?KDv1?`|me)`K|yU2G3~*dV3C#Lb#}LQ$%|XwR_(6QUn(o!39w zffh69u<~7nnn!JW$$AY6CdQnGLc76UwBsV?lwm=~f9=C@A7BFe8R0(X+#oi0RSkNk zbQ^)dT4E2D88bvXvZfy`QRtn9e;4-+Za2umb1ziu=|7hCt+hnM65MY1mmv4@oqF2* zsFL(jS~rd*n80la-|o&d(3~Sm(;4-<2n5!`b%HOvswI6pts7mI-d7n9AVw$e=;fS=lcF+iiTBmXKPyaL{S=X+Vp>jKUz4~GkoX#-hh@mvsSU{*@)uPkyuN& z@h7)5yyHCYN|UbI&@RqidAVi(l;rOc{>j4(XE}d4(Y-yLsE=phpKP>wd7LqE2kMvY z(29hXI7uM;X|59;VsNBIE}jzztfiOgPljblI{(Fq9(Qx3;g^0Be!6}O-ZwZ#*-(3nPLH*6<5#zTF`aEBB zRas@KL3?(p!!d!iaE@e%*H_7bwwP_7HnuAjvK(Wro=}h5Js^|vrqy8Mm4^=vt=89l zMwB(j5=>xwaJubr9a{fN9X>1YgoZOIV;W~XhS+9j2%Q*NnU5d0RKpTXRCch?7LK0B z(kq&vR6E9$qfV(Ed1Lq53MQ~teh=p76Hcl8O0h`w<8xOx|I;6N5=^Xa1gof(Ka+my zJy?T&P=%>p) zn=BAmOaG-mxr`;rG_E)OZYsu$>}!`t{E=W{5%gfYp3PY8_od-%?I_4~_p5b#UemSP zpShiv#~EwsHvZ&D*84-IqXt^=6>Dzh5q~6q6Mr%u!>o;arPLzs{K|zwdFOZkNHF2t z5KjDt)nn22<)BoH##qrOjAd7h0w5=`JT z;t+vmcTG*3F`K%dI?1wDeqamF&L_rRYYnO4&sg-11w{HBYrv~E<7=+f&T- z_DW(Lx!xeeutfQbAy(MpJKC=k!|55bCNj2;f7fC2WtNe)lt@SP8;A8rSKyCQI#SC4 z<{Gwv^DT?d^VUt@YVYF*P&b2%f`1EZVcT#=(aV)*es4-sg96y5dui-bg*eFh5M#hG zI)yq(A+-os0~*pI9UWCnV68dQF=lVOj!12HLp|#3ufq@2X-VfC+s?2Su9HZF{934_ zwe+D`>M!Nz+HEAa>|XNhwU2D`B8F^e3@5>6y307jGDL5EKT2*?Y7U(=qq&fK851}U zGu)`keWg?^(VJHP93j}4V;4_qXnTldBiSe$Bj7tl7GuBt4%Q70$e;QvCY+wT0gHsmSooSZWN9Azler0KeeZ<}j zPOF-n1sm8l+=|b!rGbSVcx&4yih0mBa&u1@8Ftr4wyhLTsw@p7>r$QNYp-^b@-rjI z$jUw7ltmHRi1rMs!zV^1Dp-OE@_H|swIYJ-ruwOuK~;QcsoQDVOXZG0U@e@#8qTC{ zA4-eQj@8Cij}bCkV*+QnhPz8yW2pP)Aoapr;x&2$33}lp zx9S)|zVwMA>GNgz#DAfrhWSd;$4qbC%O{8N2h|g`r*)SqSb~X9b;F2f=LnLi>Gi06 z)0v0l7U9DhWeWt>!kN4EZ(faf4ZDVXZ%~ww(;E{wzc+jhf4)5Gz`Y5+jD#0z_0GNMAFmTjT_+Hg$tCwF0mS6(68=TX>RGj-Xv7-lnl&4sNiL7B^7H+s;CaF%j)R1~p< zlX7_0;#ESD!k?9X4Ejb*Mms3AhbPAnH*54IYR(#31Sr z&5t@%KwvF6fluHbMZS&Q7A@GLN@lbN+^)eAOu(&HGPLcVTS7D1St>6^6rxw)wi70> z7Q`7La4RC;hWUF-WrFp0WhB_Z5=_ADTmn&t@^4f@)FB0;4k`IjhYEfRYr%~OqW}Bd z9}sm&fv7`De$=4?2`1o{F@dN<`8TQ{>W~6ahm`!NLj?rZ((9m?__qy+I;23!M=Bq>KXtJhwu!!-YSZRkMnA_9T6obSew#d88lVi!H?(Ah*)+ho;-28}hRSb_<0)=FzmvRlgs z(lP^b6ii^PyEWF45=sC`chv8(Sgnj>t8)6#8a@^jOE7_F8r)>f8K69%J*mOlOdzn< z6e)ttbOFyT*KNqn1}f9v`cVI_MJSeF0?$pzy72m&a=4~5CF3Q5z*@BpA!M*;2(f>u z+c+@poAR%%6RowNFvSu~h_lwOu@epd^+oY6S41GNR(HcZGN@PtvHzv_d1#gst-Rp7 z;{Ku##S%=2vv%2$?sP#~KgBl2LLjhKghv2bRbm}6=0(!6gAuZ#NK?gdu`HC|BtS7A?5LoNf&_I&G<4Dt=dRr~);7{jwt;#x@e^Rgn6Z(_j&-{n{QU0Fv z)KOKNKf;1y0&CrD984Nq+Cxe%(A&zkW*a&hh??!qDVAVDTp2o=RiF>XRN+Oxi3HY) zYPN&~N2QR7etJD_<(8%E43+tkJ;f=OU;@v7xV^l)Kb;(+XpbyEDrrCWlBa2LETU8o zIjYV+;`AJ1wx4mAE1ydw#z`Aky;u4id{?R$eZAtT*6+q9fv9(H59#z}2lL2q7ibuX zKU`@_m<7N7=&{nL!$^;S2xc5(0AfgTFTT!- zD~)Z>2n5z@vT6}|ac2!XW~abbMW?*C?+NAHtw-e-10$T z<(vHpfxucf6GMoe``}iOu0TwwJe@n7?W=X`R7t}UOk7{Qh#WOVvu%U)QZ1=5j<+;a zQlDH;SFi*VQ(A_Q2T!6|Vvc?r@Pm6lzO*ja&I~XK1lGc%2iB`yefXr;2ej{o)55sI z#O8m)$l%8DtoIeY&+k}O(8P!y0m7}eIEtSZTq$R$bl2bXeXHOV027noj@NDTl`OHS-d1P(jG(9A;X+9UdfKwvFTtDU58=cTM<8QsQL#gRUDY(SqEGAdYtiMZGu zq{99%h$JWjkv$<@$&MLH1Iq^}z9(YH@=~EJ(yE7ywJx8HCdDU(FlmT>19az)NcmW& zX>??l#fsz5b!1buMXVmoXRP&KuPE}&1tR>-)9Vq@Zn2h-(4WS!H zEo^2fC%NL81%xkK!}`ZL0ugFTFeLb2Gj0D7NX@o}k%fms*|d71mVZPjIbRaa8@$p9 z3%mJp4-9^s$hOn1ao#YIcc=B^~C>yxLNly5XK)$3zFo%75sX7xox}an; zHu`ucipTEPGD)QV@mPqn>?Gqc2H);ZRi%r&)Me(2yeO7nqVRCco2S8gkZjO_#hYvEA|--`HC zrR~sLiq_PNVhJX2yFs4Or!$pakVAS`mreqKweUCw-_q%+3Qw`1ORsrTEWw0Vr!8bw z<^tCDqTYjY*ITBIAK}fpa2J8VT6i48P1Y`ppiq*#K9u=7!5NALnxCPTL| zeMVocT!IBHf1$fTU@dWe{OeUm3p({wnLF8^VhJWz`-A^@daK7wKjla2`0qRKKzj-*H#TwR($mq2&{#lC2*I_BS(uk)27lgg_7w=Mg;zUC>f5@m zJTS2)|9HWZ;nHI>jZaq`N&b7-f&=g28;Q()4w;BhtKEe8%m+7#o^{?KBcj+V&SS$bSKHrAx5mjsF z>B%ofSm<$abkAL$1QWrB5g>i)mt@1k3$1Q+mwa{&xts^U|kGAJ029*~Gtd;+EpI?s$v-&IHoqYI+6!Sm6 zzB~ygX8c-4{1k|XTwAx%=HKti(aTPJcM&szz*_ll_xU!?HTbG*c5>oZKNr?xA?cpG zJP9Vsv<@K+Ow1?d#9BsED~4?k5Gt5_PsH^^68!CFrt(&b}@0J#XRCt zID&bc&}~GQ^P;ZjMrvPEYy?8k0>3MGT=MIY*`g1nmSEy)%_Ssvc?v`n(d%*L`vI-4^+7Ez z%a_i6lSI14gflzvq5D~APD>g{jCt?E6e>g4Dd!Tlx!ClQIW1v7_ zEper;X&9nS>H1oGx}iVC5=`LPEJ>>@V_E%MUo}_RPav?CIM0_Jt)lehU$t;}Kfvob z))Hs!(MjMfSaManEBOip))H6h2OpLzJr-QjlmOV5pj|j7@Z5yw$0${?G_27+Cl3+` ztR>Dt$C}@is)^T`)sz9k6GzZO^9H_oJ$a1t7{0#m+^f5>t!ZxW@;cs}4I(Y8j z+f~&ML53rNz*>iH%~8))-6D6)BQ|GPy3cgJ>;^X!DAwYW%c)0(a=Cahuptn++gqph z@Y=24V-W~ksxI3zR1b*!t(O*}p588#>e$Zi5M*GY|D{{X^==-P$HDJzw%9MPI^98y zfWH%>=E>GeH_O}MZ-|YXFhBM5=#_e=CV?=PIhfij?3{et^6#2w5;vESQ(N?W!a}KV zNh-WNt6G#g;zsjIHKlS#=Y6ir^cR8h650&(A5?zyz)nc%xpXAKKKpTpHXAqrF#ER$KaO>RP?sM+{Bd8FNlu z2!D$;ALq?n6V0viY+$X9tIgzuibvG}|A)9cDfFNgRU_>?*uYx2?4phRHLcuTBhvL8 zZWNCO+|pxTo|3H!uQYvy{)h94(h9esV~Xhcohg=_P|nC#qUIWMK@0zqBrR2&xwUqW z%bOoqf{AV8_sQj2dduzdMq(|8qo$3{fxJ@gW+wTrH6$;~g^1`|gp7_j_Z`gISc7Rn zWwNV#41qj5YJpHHOo&;n+MO@T z<2v-_i$33Eb!LXJ$!jv1v@J%+Yl*WLO49z!uUeL^AD3l4l zZd>D#r76Bc_^)-PG%Udc&Z#I#6|#0{j#d+R%!Pln=RfUPaQBx?x)p1{S~$}qd@(uc zuRSUPds1wbBpNQj4G0^Ofy@ zdYsvi&H6nK;CA6%8J1u|%yBp~(w>)*+we!>&l%1qi?g4Kc}53$SLcu2+i*@#2n5!O zDiaN!K@D=5>aCl4&5o~K-HC^`93^8doM%!bjuf-yGpBdvA14eYSb_=MvvBrfyE|`K zq6xqJ>9vaE|Kq#>UjOZ3JFh{+|GIi+hw$63eCCj*yx-d@2{ft7k>AXWh5RbA~`p)-=c@ zfwI1d`MieS@mE~N%;ekZbP))wmHn^;X}ceChRxT{q`Eu!DQAz(lvo4S3ietJbzn^ zUjNmTzfHbMumlt7C<7eC5PDOQjtuI^Cp2ovFoCsjPBi$cKdcU|Jf&>i22p}e6K?%yz$^F-zpGT>&v)(Wa_>>kgY_| zI?Vrs%?tEt|D=ZChY?W1e)GwFd0YbnN)#3^tE{O%2> z^wJ-^rB%QxN^2&^UA81B@GF1N18$BeXRSzFJLXNloVy41;l zwJ;60uqS{w?L~2#1yNwXuZGk8*NnvYpuNGk?+nRa4l%ttb}(F7aEXkZ6HKIjdOaR* z_op*^epD{J2$eB`wKC`2C(jypC&s8vKs@O-o}P6{Ra}O3V*TbkAojO95@SoVq(mt2$JYH0mEVmlW-+U&>)!LPsE;lns#|7r>GB~D+3Wkm1OjVCY{((u?~+wxhe1HJc`=>tT0dL!7}SWRdA}yvNoARI zpsfLGJzDgdbQ}u*KYS|?=E?;6OHR>3=9Lo&thI3K1Jb8hCnim72gD-J3G{o1WNqk? z4h%~$aW?J&iKyI}NhP9zNUkxMc8__j+1Fbr5LjzY@)a^;iIGWL+X6BD%^(^(JX_1` zc~Qj@OgOH*LT(g-SaDt08Wek;ImfM0)lK=HNdAJ5$F+wlw#Poj_nM`vw^#U0Y71?14b6lHF;W ze)Z{v;qDr?fwda8+e1#wOCrYp>!BXe%{*ybhgx*0_fr{b-CJ{#v<+H8B##X(M8axV zYua;YZ91jR2?Lg3B7cp6`#$=5b>K=JIyK&d)}Ma(&svfvDYttC`8ZX-JC>b{e+kYZ zud78%9&AmG^9>A3Fp)KJIY~^*AX1hdr)dAfS~S^WZ-bgw zuVP2PzwJav)~d*`1QVH-%OD5a8Dbou=jSZiq!?v2`%t&HB}`4jr;=tZZxG36n*nQC zZ<<1E7vF$88~uS$irrCWRTxg4Z?9*M96ZQ|F^`F~0rtB{t6obF5>^=ge~vzD1D9=6 z!kSE?*KcnX2tmusg1j65mKf{n^*Hc$k8<E+6q<6h1GfZGD|BuV%CEq?0>54vU`)wYq)CrkM=#rqhn>Q5fF>@S$lEf zSMqjT0F8HzWSGEO#vxVZcIQ45X9_u|gm%)^E4|j$`P*5hTWXPEQX%F>Toge`k$#NzZ(3=yn?ZeiaO( z8WUlH-;nvVJ4}&tzlg>a{(JeUcFFD9}T3{ZWSi!SkkJAI{qm9Zi9^m zTv~{Fy2dpvsPbHz+$EO@1geuH)T33u=Weu5AT2*}xkw-_Tv~XZUrA$)1LxA5LF1W( zN+Q@hRY9$N2}&5LuW*$=e_+LX2G9~aw+e)Wv^+M(s5!3CgC+Is^3N_-)&{~oug9lv z6Kn%(*^j@aCN6tVr0x1hJkfKIw!4jVKi+w!A5I@3eha|o6s z&RE90f1M`MWnxHQ8qF@5X~eile;SPQsLH!UwWBSzoMl*o31ihr)^z+SB1P!2km}90 z<=?k-rlU*rFkwmbq2W#cR;mS956aX3W{)~esI zpaV%)ip!2^u^!8~kM{NQTV=%K{uE0vA=-Fje4#ZNG=y%yWJ4kjM6lraL(I4(L8v)y z5s09?#EiGE?@LR*SuJQ`y4todHf?qai|G6VYW~;=e)g6U4|uay#u4=W2!XJ}=Ib@o{r`vD+JEEWre}4d<55 zCo9*cPT-fVR|}=W1TG;&3*D}2t=^C0-HwOLIE$+kzl3GQ1hDi|Swye*+hsv=YYoe41a(?_nh3unxn~4wepjdS%cd=&4MgDj!S}(&gW0yo zKt5!Cq)>AS5x5QEeXwh3Zrb0SZ~e7d#%0GP!5L&FsmHofd{bBt{`qd4KwvG;_95&> zuOMdM_7T+lXiXpPw%eL}Z-|kx7S0+gm7mLu>y|L->op*_wGS_xVa**ziG-k~1u>7C z3z^jAJ`gt7n)7MZT==nVOJ!^w+mi(1aQWH1kV{)FI75|jNi4PLEd50klMX>vrTWl& zO;#`|;RM*oy)cHml|89#%8nEWK})E|uB<>_tJ!(g&TfT_^VizfnZeR4Z)V1W(FEIr zcg~g5`I}qwG}nJO2n5!`rG-PoAm-4WIjynf)Ev+y3ZwIO%CBvbnxB?#8? za9hZF^i6^>TZf3mxAb8==i+^(=u<}nmSEz5kX846z23aa)Z+B@yrKk4Fp*smB7#5N z#f)=%L+ehm9?erKUr;^|jg_&)-*OJKuD*>K;R`bUCCHb$d@f&H^D2p}woJwnOyE|B z^{UPsZYbGAX)m1>lJ6C6=Ptp_u9+CS0%D8Rpts= zLvcP(oUs(V&Rb4t>-!wi{DbXgs!ZzI;IGW2Z;w6Edj5M|J003yAaKp?%K~{7 zGOxxtz>~A+t!v70t2R8&^ON%Ap$W1XN3rbtz2)x37;D-E=6SlW{NRGhGIQ2~&9*@J zOjfAbg=1Qy>=Hu$K}_R3fe?w!cbsD8azP9IcQD1jg-az8>e(`Mg!v|IN846H9z~pU zP$cHH+NC8Qs>er8YDjSnu?=h+;*kxQr@U{~o^KyyEtCrXF0K=J)ux>!-v;#OFIK_r z8q_``12vX@dkvGMVSlyNxki;VOT#cevd1+ATgODsNR9dPwR$uXXkGWl6|}U329Sl= zT__dS!u6A+!IzwA^PNrkJ@;&3kAusOGcrP?!XjIh4#v^kCTxn(=Xi&N>jz&H=Nx60 zx2JHgMoSf`m5E7Nkxa5aE#rEKMC;W@l<_x)@z_H{1OjVedy7|b7fIV-|b zxMCcWmcR~RN4&7Bfhgv4Hfx@xC-8Ca9TmJ6kq{y7OTL$(+TC6=_@#2y6hVTBJ=^xM zW9SOn!G|cLnbaC9LIp z2<}XT!icd4;+bnAtLi$HzihQcB(N50b%^`X@TT&!|4{zoW;F%3qF_%TCg1!*79O0* zHzykuToO!(J4*}c7rE^@hfg2ynqUHJ32i8Sc`{L}S9A(L)V`H6(ixsy-8`9pS1aY2 z-wtM9$dmP%URp`-agcevk=e+yddwQLA(eT~V8R;=iBLSQzjc=cf3&ER)etzy;>`+~3cZ{mHZ z4WCh?6Tfn_zVKU^5Nt~)C%)CHmg&jw42TkJ__v5=i^g%A&KZ6?JzO zv)IytT^d|kc~JNf^IYY^7Jq^^lpfbzocb(#7OxoDK{)`ig8UtvS;KwSf)=JB0?pHk zYG=b>p1tC&avO+`eofi3ab*QsBv!thqy8LoRqMHPB$Z}gX2!MknSB66{waE$Nj>aY z#Dek)j@$!hafVG(Z%n+dMLLe8f&>v_e4ha$hp;f42XGH-7@X_--|q_cCL}PaXMGkO ztLJ3hVLp-#f0C)~Z8M5WSb|FE*>V^2aByN1!}T~tGdkt4+?YpNo5Di`0&Ar=g!ijc zEm+n7-G<-153I;;rj5EXhGH#g{VFC6XvZXra*9a&GvSlg=X!k}xxEa zgTKCAyygLGcwH`lAVF9CE*wmMLsrDbb$Nse+ z%$3p46)eGoxH7cN9-t+a?a$Q(*#d#JtgW}REN{xJHQmP0h+*29lwSO{-A@HeFo9Ph zh*TK9Pjjx>fy+^aC?>F06~sOBj~+$eL;2prBf9uVF_9d#8J|yvr$zxHsbXw$if`N zvkQ*}NosYJGv#J8zAVyNAh4D&rlrD;sceO(!aMD+FN}6f;GUJFb<=G$t$r0=IIgWg zU@hG05HCC}NIM%_m+!H276?HL%`S*~>Sfd_bgRU#*tev3-eE#$b*XICIPGPUIlt4n zgFpycxYecZhYqSa-|V%4>2s(td^?kdnzO9ekdL~|UM3YWss58HDqGhcW*vP0Q?sJ% zpa-k{Bdf!r8Y;iK&7m(_o@B+8LS*MgTOsSTn5}uj$L(sPs_hhWtJwk}XuaCaq|AqM z`ZnE0*;(V%OLV+4^8E}dK};~?ReR#Gq`ZQoFXEillGHMw1>013qEdIm4BD~bL1uha zn?xtVN)`?NcklAV!_rpqcnd2Wbt2JY^%bsa;RrRf#x%uoif9A>F0P**0rQwPW=adC z^Q#e5Lgg*q6?RBF`pP#(Ll)@eaB3hiUG^WSXPxf)^qpyIeJ&4t6-aRw=&bN$h-U2V zHt}I4Aul$3;azmnG}aQ|maS*5(-$XXO^2efVi7nLM7W|Bi{!Y6nggY+zb=K1w#@m#D}7bJD)P zoh{THXXqA6D-9bmUUl?ntW_s-1RIzT>`5O?J4}xj7S+~k0TgTDwh~*n1^;e}&)UQm zy9Npb)=F#+{ZY$7t+iI~j}I=6>dZUC*`pOAfwl1HfgSRa?WPZ}?x+=>isK3sc*MYo z_>YCudINLFf%X&xZAgtnFjysO2(>z0)e%} zvAg^5OSMMN2FgY+=npib(ra&H(t_e7I@wkc=imnG3T&?V2xYzNOkpj-1fKJ-do@;I zQ+!7#T^vP1&_ZjBB&}>}!G?7XR?gL*F04M75Y`xJR#{7S(0{tNz75O|G$(}7Cye&< zDYN<4GH!~i<54;N(hMebTtOuNlf-+%bY@(?mPq!=M95_<@$1w1grq>_!uIttmS6&B zSk`YGj^QyRLrDo+DG(l)z(*awgh=7n3APQf##kFV=F~=6vW4#iQx_8B)%ye! zIQucYpTFtOCw{S}E8^mWto4|{rG+?mY2|pi)m>@Gl4u#{ynpa!A#;ciB3DX1BBBlJ z-OYJbFBke_>N3FwCU9wC-PQi#yjoA{&~L3^!)URT8HYnIWGRaXwDhy@NX^-ECbgUz zFB`+)&1>9rBE5%ikLAFRKYAv7oxVYEPGX86YP-*(0O!X(;jXM{jtE#uC3=D&6>F*?Jjk%DT*G25DOUfZ}# z#=nb8CA6WGIKimxIy#-&EZZy)SW9R_X{GVKQhv}N+Q{*QjIHBRSxO14-oqf0?l2Te zb@>0$^%h`NE#LqD#zaNL#%{62LgLH}3Mzt$2^I#3fh`6CN5w8IOa#SFY=pD-VC%K@ z+J)WiHLmqvhl}^V=kxpiKhJZY507iT&YIe@XYW1pUO(^fRsBMQ-{R#av><_*qDiUn zK}XT8w7sb5H$%y5*)C|0Zcd-h(mPgRn0b@5+ZwqEw64r zQgbA*6==Sqj6i;M-lQF$yv&4iAI^#CEopXbpTM*@`cLB%BjwmRcE;+sgC?{j&Kj?K z_FYSRmF6(~B~r&979|%=y{-RD+p5Gs0$YT>U`-t&n{Pf~RP4W8X)7eKrRns*h1gi&yvPm33jM{31MKvy#wN_L zOd5?nmm1D9nC#rDq`=?BcrzQ$(U&iwZ(p~p=kEI7x@r7O^p|zk8yqc2^qRF)Z*w)3 zz1`D{h>)4>jf>;n8Ald&6G)(!npL;#$yr8)2YKbEUVchFkia_8-VcjOPkI=}*7-#% z*~~HPv|958Khup-DcgC*(C$jcbj*c5J$b9%?)WyQMb)Bue4M!7*mmGJzg#{*iGjbX z5(A#DF>EF!@;7;d1zIp8u$s+W%k|hezv(i+=tj?Kdn|fl>v*PlRaf$=<1f)OXNqq8 zQRF-iJljc$fu%BMU!^-#N@M0l)_OEC&(JSD>@EHr@|s`!V$qY^E~Q;M-A#3aE&7RB z%UF7duj%awL(lk5D~`@hh;X(~&^NgC7E{W;RS5J-OfhtG3HqgWJ&0Iat)OUL(OsOW zL%KNdyO<%58HI>qSl_yF9kru%cAI<11Nu zxK(W-!0xp%YfNL&y>L#Yb+H~QG5NjO2t4B?;=El1dSMAwqV|f7tW=q5!r_?^Xh8z= zFw^(*D+P=;&qwpvhohAo(l|=+muTLNy~#HwALq`?+bJ2L@pmyEopvgHQlHX!lo;w2 ztMs7KYa{3@$DgrGOTSEQRVvDXwR}EW{HQcXAvEv`N;{yNw-8a}DiOzBfAAkw0z?t5 zDaVY^*lQ~B?!p89D7u$e?%Rr^1qtkb>cLyZjeK7t#L&%07_NQz`3?H+9OGF`AL?sZ z2a&qiXp3Pf7%J>`bl^y6rRnWyteI(v(F|!?i&i%CyVgU! ze+yRt_)9cO);;E(X7mx~deTlmC>0V)JZ;y-D(v|5F=F{kGsj-Tl3=UTKAGGNjU~lK zikNpXN`EK>)=BH1x0pzO)Jin6vrz~v362F)DlBrA_k0*4%JnL*j1nZUPMY@fhs{6iOuwiTQhj?J;5T@;}U(x zsm{z(>9^oHQzh~zbk|3mJ;WWl4ps>C!g!?6)PAYu%i+7cPNNWoz;|RAPt!Vw^s)SX zyt*hkUx=(X=FIy21M`?DrPX|McC;+?JIeoRsFn%|C7xE|XhVI|=`o^w$w(e|=ANFB z(3shNx96^T&gqHAT-e6Qg4}b?2|aO(8w)ZOpw?}5@tK}jZoK%rrYkSqW1l{@r-{h} z1$oDBDZ1?##Xq5817%#o#Ha$ac z!ZMt#-|p-`-!fJ&>@Fr8oX)?e#OWEno!GFF1^K0A)~|A1nD&P~KQU*Ge*Q~Kmb}&a z?XJ@aJ6Yp&`OV3v=@i z+C4R~KTBLzNU0z7$FA>2g`G9&1a^L*lmrMRo)$TBwQ;+)y(sX*Ti{iM@k$?Brbndv zvCku|Ujar=dSpBu*+hg-_{h-<z~QK2cG#@a1i#mI`kI9iavQAs`Q?nRP#QT zTl$p4J%y$ACyo{*@Oq^8CGTcfik|2qY`5nTNTAnE`eORf&V_wEZykyEO6Rp?Z%*$S zF1}=FK?1LT+CyJyFsnA53cagw0r2SV< zM_CRXUQm+-t?4b?kj68NyV?> z_+=FH*ihb#8_{xmIa{`WV7doJ$Ba`r&(ld(%9?$_h_Re?dE$=0g)#7}94Wq2sg~?+ znC3n0a4N>YvSU2bjUwX7z{l>FE7o<#%t@Fp^EHjc%92io9dAmz?w=4b`~CgYY!NjM z;BR4!MMR`Kdoiu$Ia-lDC*u0H^X?yGT-=aAudGZ&S-G}I&p@^)f2*mA8Xs_Px>=-YSG)J|}D6m`8TjwMCN|=3t^{HL6FRMXORL9rkoX3lece zC+7DewNGp7S~Ev>Ep<3`roFR5pcjrF%40%=f3wQ&6WYb3palsW)0(#CO|+cXe77b0 z@nmL>SXH{xV^U(7Qe&vU}{Z?CiZT4J}AuyV2^EO4Z`@X7^5s-IS4t zqc5G}6{<2xcWpbBMq*RS9erbxlj-{5Q5NiH^ukPC^iGCigr_WZ&+pOJ4M$&rDpZd` zU72=d!tegb8j05Ittr>N(k2hObpXfc{}R7j`Jr>&oN9d*DFGJws+;&iniRw2s2G$FAnbfpBz;O{=B8P>KY|% zq6_MnqY4SkcBN?-9p3Q6ZhhqFw4BU#T`W7hG=-Tb>@cD7bh{35?5Rx}v;EnVo>E7j z%OSR243t3^hbUf1zsxt2&3v1kuhyk|}OsGSj=(Csk*w19?gL1J^ z>r>d$4fG`3Gnry+FOo~%c^x2f}gXuZ*L@+B|Hkn0tkD)z%^%*L`lV+yz zz}QB6eWIWDHlYOxRJ13ZyRG%)#zwBfrkrj<3ldmD+8u3bES*=@7k4jxQV8_I`cbyD zL`UPhL!_wv?yxEG%_8X{(1`);G?L5+8abn9za* z){kl)X)$tt2@?YwCMY#W0^5+zW=xFci*Jk(&sWj+r~$Fe(~(ND;|$ZbQU;X6^!+1b zA45fZ(r&8|#S6Y0Ba%9-GAR}yu(b4*%;m8u^=7n~d3(N64~&5=LOX;eKj6*%f+>glJ? zjbiEkvzdAI6^68?xz*|-b}q>)cBE}Fp#=#w#&g<_@u15{e#v&7$#oI+SSfnbn6Q_g zhQ~9lA)UOwc#2_cIz{&&R5S|xlP8H-rBp~@JeqxWjS+u+H1h!skv1_rZya6#~7w4<5@r!xEVJ3%!@s2JDCufpt&odZT$JRN(hHMz5)mw>{CVFvALy?T=!Nyuv?DzOMfILJW$d?~O3jhbZkt*8ty`G3 zpgYC*+jg+%@cpQ9wZ}?@Krd_sQom@@Up5jq_{~9Htj*w5wt09QOCQ%(nS<4NcYo0$ zvcUKi-2FV|)$>Yae-?;m4mJ&ytUaBd9$>K@ma~`3t%{^6Tbjw>=SO(SC>tfm2*$(g zA+#I!n~SXbX)RBAQdY?fgoGO7M4{)#o8A4npL2JGKrhS^M7o1lhV#pVAMrm^yDRyM zFh`M^A+J<$by3~hL9}V~gWu}8nK^iDXF-?hD;e^_Uv6g(TQ@S#!jOXoW~6celZy9$hf8I{yh)wuPHA5MMBza8>Y2=r28{CHP{Ma0Zb zP53ifDHUe5!k#5n`8^j+wf1baq|YGO(oDv?T=>>_f4^b zOPcaLj237?Ld~3&(DII@f7eB(a<`+E995X-2QysJ4!Xj{^<2ZwS%Qpcffgh%uMnNi z*HNkmk7bV4XEKLPE+!-}KN9WuT^w!d)$X3f zd=cwBIJa(_xVDf$!tz-a00`ol48_4;`EPwyG!QB+yIEsrPgI98!`&O0iB*_kjlJx4X!W?5c# zuxa{pwNyx8Ry$2w_}y&zwZECEP}M$^uiovKH#k3iWYVI9Y38GObmxpN6Sw=|VaUE)K1USrrX z9{j^gZXB6ipals_Pt4AB(8q=!sX52E`EH~#O3FH~V5iEZvh>HUChQwpC%#z6ollmM zRfo6<`8Nrfhf@uN0hjC>CQ6#~7~Qr&UyBQNE9W2`Qoi=`|}VH4KH(z&P|iZb_4 zda~=&Ax@v3`E>XEbfA2EEr(ptaH!&i^xL<4*!lc3_4JRwsI3M}$u0hH3J~MQ4>Fl$ zEK8SkR^K++gxbMfH_c!-l4<`>uI#junP0H0IGH1lShX`BGcTak{Dv*`U8pZhofyO3 za>}Cf!kMAcG41`(gGI=Rd%RLqTN7H4K;2?m0sLwt9=vWKzP?X4p#=%GREv7n7Y`yE zi?j<56#~7mPNX?-E>i41nVr{PvdeVq#TfRsOuVk$U&|63N3bAo+Uc8rCPP(dO}lE2 z5)Napv$_KlO=v*^>qqZP?hO&=&hF=q!xNO6BY|y5XBvKmi^8U<#{757O{jaF-ig-K z1*rcAon_~f=$T>qQeAW1PyHdDMTw)wcIhF*-zfxoVf{2M@3%4H`0GfcqFsPOpcmGU zo((GZ6+ixdVZ`O0Yr>LX2{SgEndfOzUhuz3r3%>VFUtBAlogUUn$Us-YKN1~-5Cc_ zKYs`59hGQ8<#O{tdg>ZQr{SkuVJZ<+CXZNDrmGxLVY>+}NO(p~XF+r5TypTKtxtD;4-Ol%#|@VG0+uQSdSO4&x#5Zrx#@8~vA2l}n-H*= z<#kKd&E2~z^DfTEq#eB{fnRHWhVP%$T{z^AXV<(^No%g533GGIrYF0OPY>vCGoS9p z{4AVy{$nz;|c^$6Nzb^>+RJ=>8EJev}84 zX(qxdWD`iBm#XDGFJ~gJk>6PqNq16|>yg0HYTB&S0eoKaOP(0mO(D=rt;e|IPx+Wf zq-Ed36_)CBN(c$`Qe%YvJ=Uk?S^yUjKNMLE{8|3z*9%E13NDKU*Tw9nK2(!n~ zvw?Y?Dg3REz9%VK$s~YYn4yN0TT(w-W<9jmuaep(W<|>xQ)o?%{X|L#8%xP-cI%D#liZXZL;_=5cYl61 z2DD*D;P*go{>L6hpZQ&M)H*+N`n0L-(|c>Sx2V8Fz8I!Ap9-6-e^YLb z{Y~W1`c5)`@=FscrK37}V89ZS{nr^;M5BNJIcZ@o*=KHmjus@;82P^rliXpeA(v)j zXh8x?OV4UWN=m0Zt)v}mtz)S$p8Y}>Q|FHRvr6TEu8OgL_5?ZMbGivt_ffOITCL(9 zRbQRTB65G4W!(5UT5c@qsiOr6HAb|hEm$gyce~tn%fQ4gS*5aRQCHkc za+7~)aXJ#{g}E;19l)L;qS=QOqjKkWX(ij8v=p2c=V2YAnArho(!W|iLVPN}+Gw7; zjgA&1Fk1yZf3#>Peq1ghv;FX0bWV9`Upe6e00 zXh8y7fzG~m870;pT*?!3-c?G4byBlO>>WEqY&w#{?>oEdXh9;Y4K4rFyvjF|n9-t^ zh+E5lkHkz1=6_I$g5z3=Eq|8~QI}&(Xh8yF(+e-sBrm+YiwGFD#)Mv3BQZ0clIud_ z?;r5_5BiCBms;p(K_cra$g0QGR0}iWqQv-nt$xo8|5zYzhDr?H(wT1* z|A)ZXns&5hVPk)jNKv};853sO$eI~4Y0RfVIow{)GRiy|E!H!C9W6*?%}QDI=uBGS z z)`K4{*jz^o5^9VY6^6@<@GX4l=d&iXAc3W&r-=j8jCJX@I#7)QkwzzMQb+Pmh+~Va1q| zy8?2WV6F>V>F;^MtL5(}>-DO_P}v`I1Yk}AdOKLUz1VWlK~_2TjG^{Cs&S)AHz}o0 z87nqxBaO5;2ZqY!Yvo6F=XkP3^IPkIYU8wqYeMgRro7hM7Fm*p>gY(|FVP8wtz*Qk z_tE@uj&clj;ZaE*)!*suM|z~V@FP1PIQE?d72nYdwcJTP$*Zksky1pkgLGmJH1tsk z9F_8Ehfv6UZnrpCB!3Pwp(ZtIRin~1ea#5SC&rZNEJD9cW~h6OUZ|!`XT$gIVg6O3 z#Nlu2nWE(kddR2{t!XYZPZ(z_4HR>io?)o#i|W0o7OZK@4$U>T7aJ}7gO@YZ4n{9j zB&Ij1+Z^S<(XB;Y*2{z%zo@Kh7PIuAKWTTz?47ims&27La&@=a#;h<`;Tb`10H;$< zlzq)iL5?eQhZu`a#~w|dpcO|dv^O(B2D^mi)R`AX1TI~w&99G zEUMnB#28jvo_Vl=hox5&=7!63M^dUYXK!Ibg;nAtN9jq6q z_eg0gB+}Q#>E>!Q7P|JOXSIBBgQe?_N=9((POezm(fi{+>6DZCfJu#!@G?~Pe>&J0 z)iqg(p#kB!l5&A&OQCn<&nbp~^=`6W^VhtfQ;0&K7xpH-v&`o!^LiE)11sKbWW)-!%|@@(7V3uLuAUl+5C}D1V^<{EW1K$*XH$>O=6z$ zmPIv%Krhq*rCh(G2FuXN;YR9~r5r6tU}mzH`yk(r*6zSLHeicQwb zPZ}pn&+o=@w<_*pbs6`Cv@}T*u;UtgsDSQJ-U5i}Z=R@Zj- zcb46JNT}%a5SZ8CE#UgwoYyO`DYpfnKU^ZELDW`(4#!OuywEEl6PYF?s{JqOyz) zuP=M{UZW7`h4)0t&h?;@Y}vD+9CdglM+*{aCbPO*oMhGO^<~X53%SyYpkaxvK-mg1 zvdJbv?c`c zqXh|^mFSH7wyFBXvE$|T4L-^YhXkIEAU(^v*-Wjgjh8=q25__>fwL>A!^GUtH(ZX8 z7bh1|2=u};6!eS}^42nB<^;LbzDnkqpWo*(kWgo8n~?98uWKgAxuF#m0=?R_eWs5V z9rPoe7g6i_>Z2{QUPa1trEL@fz3|ip?F9Ta-(veEQg*rflc5EPZ-XD{)2=qr*EPFA zG457ho@VljmQ!-CPzdx=l{`z%ceVsLM@z^4s}%yh)bk$(&6bl=qGX0!JVP&x(PGni zea1|0-QLbxs?uBYn5rI&l1U?vD+GE~zIayO9MAN-&3+JZDdf4HG$K+)RoqBQF#qYg zqN<}xBoDG!d}~I_JHO%?T9Clf(ysgB`;CeH!{maA_ZX_FT1qDC&!+n53$y)TTcg(N zh5l-*zkg-DM^#QpH@p)E$^84SD;88%#b2V+{nu<{{tp4NNU=Q1T@4jt)fnqG|1b(` z-Q}WK8;%wvFdpT0dR|nz7jG>ipMGa}=S1aMq)BUXP`mzNBDPA3*Y4;KmiCDJJx zSzgLdUNU<{I!6tJ;sy6z(p9ToUeGRN_z zN(>~Fd%I@&eA8HC+eh}k(nKN93rk360sM{|f#dtjS6>=%v>?%I^Dg~ShxYo&6zd6v zOBe0siIBFkrL`00T(R1bV6CDkA8( z(I_!k=5N)RSDJiCKOWXwuls7DGWxJ*=_|mL4aQj8Fd5gji9(>)TX(51o7qY4eqZ8L(pw(Q?^78-+lxn6jz5Xz8VQbhOUYKFiI<%Gu#EzWXtT79`X; z(Rqxpb@z6Zo{>XU0@m&7D7l#JlQH>lXE`oo5?3rhC{F;I@2&^Nx7I!7iXA}; zfnMr-HLq(P*?)dJxyq}zGW#H*%zT>1@oI*1Ot@?^Cs0|D;VMjh9?bo;y3za17O=4Kp;6L)b$+9LzVXty;G_`fg{vBx z8C>q^r#p|A)2q2~v>*{U>$3j&NEh9uf^~gm&ht>W^_n2xKgq5T=!I((+I2r|i^b1A zQvTJw1V;-JCEi@rXSZvu7x-npYI8m}>mGd~WzpQ(6#~6*RYTv;qw^SDrc98{UmjFO zJC1N%uh8zc8@9&hV-eDJ%~yp$FT9%R9OTbx#)JG3(zWPSh885$Qf=+wWZWM;P98`p zqg?0cg|m{Ty}Q`jFha)4x4ZHvvkwy33YzATo9reLWDw~mvU`t`Hsyu{+7e!JRh!HgGk^Q)3jnamKe2* z43!?w+b9Hj;S(91d?_){@G3S;ZrJ0mJb593*9xuSJmwmWj3Lte_aKEpFMLkav=!^? z%PouR$s>zhl-vX5@6vw66$5q8=7qVc<$W-Ihwg%??r0c8@OU7lFCssR2uMhbJ zMn_sv9@h&0Rb9S0UP3m>|B#~v2{p!yDlx{V{hy3|Jvu8Y=86~8iJohdV_8D%3Vq0` zD1j=ys0xgl+nQEpTpgC;WW%1&ZYtE@MFm||Gr?!FqcuJ!2M#0o_?Wx0dnX3Cbn+ms$(nux(~d&r2cbM!7L-}zJ5 z9eU6bH%sXqM2y&`m;Yh1oOUV8_Y6zcHQSB{iZm)ig!4ywUs>^`J}xPbVnHG}oMNx7 zls5KgSt2H;QI@g&OO3NHKk!8jx9Vn}S(ei0%5eLdn{{)BZgE~!if=Wo)y-+&EN@?0 zHJ9xM43YtdlZ~j-o{9yD^td&Yc`Bctc#&E}yY_0dycyr!s1n{l`CW{M_0u%R=pM37 z-du(__gSeq5?CjCm*LV#9xw6CFni_|IF@jq zf{-&JKJtwVUMPg(1!GLp3IyG>j(Ex2=r2C(cz8kq&{G# zJ~y(HKnoJ;d^I;mZmBI@!aTQjRS5LL8Ju=N_!W}7Ud&)GdbU^Qb|lnMlJ@nTQLI`s ze%GnHLMUEJ?t$8W{B0Z$^X3!x2MCY^vF?0*^C zrY`0uzjsjXI7r}(LF%p79vSDKpXO;(TPXy3saNgi5>E1!V`acTW#-RQb@QlT zrhO(gGesq>slQ2fJ6}P3qc__M(TKhYcWuSeTNUF-(@MXv#dvijhp4)~nW9aF`haSw z8k&mAKPu%HuTMG(#R9XM8RF3{i?L;8d0AKt>29kK=%uKqX~Sz4k>?6j69adA=4ep} zP-UYXDbMZX$jB;UkI1dm16u+0*67UW=aKUI>4HovxSYNTlP26$dd7$?$utN0PVhF3 z@_UoQw8t!6>zzXX_LIJbSBdB=`KG)45UKZ}f--6@Ylp*it^XRPonB5)EG7DMk}fZ@ zi-}q*g+MRVMkY;;eqk~tV?B==Y~qRqe|PKz${4zdem{!-`*1Q;M#WCzZ#!({N_n9k z!=h>DK!Sy75usF%kw=EhiC*Q5rtKCf1bV4z)5S_Rl_j=Sl2vwQ<7h!bRcRKb21+lR z(?)8qSVd18)t}RwQ>*vbP3r$usUC?%M##_|(~VD_T#11i*ea3Qb&On9qLSgbsI5XM zUP=$1IT#=_23+Rzimz2_t`ImDw1EyIWzjk_c=3Kt9LuisjnW^38br$Vi7PGL^r8x( zq1OfaMxTq$FO|1`qwkd(F1LQj$!C2JQwi`=N~k?PLr*KFsXTj$NUm6bP{y=&-C>v< z{^LBm{%I4(Uc=Gu*&|MG*TEolC4i>5=r!L|0ugYK8#}{$>t^sLm*qg2<)WBBz zJkNk3^4=Ub!|n8HjuwoEzeFb|6SK*R!S&>j;A{eQuQ7&7RB-reEQ_da%v{w?Aw0!$ zJzEN?KX(=;RWsV?yRSfvXw;5In%=!u?k(9JslIf! zPC7i+oZg$4_{mBZ7o)a+5rG7HVg2Zo>3&=3`f8(5zIh9!9!RLA@~dn%Dh*j_6muRV zu!iV`b<(tl-2-LgPu=*pIUhLoZF+-cw10v6c_}wxJlgeAB(FRjH=h6H)kdHfwj0JH zMN-e!GCXJ-?@{49M*_Xn7z-Z<%6eVyGv^&P0!xKn*wVBXZD4C@+HZmwS-K{#NIN-)hl_NtZv4R9r+VVXDRd7{@<6ZNv^!;pK9Cj3R+eT4 z`^5{4PNW-k{ahF?NBc+ymKe^eo-f0a0&nY@{R}!WyTJp0iFVdJbC8E~wiF-6n7PB7 zle+6I+Eo?0!UI*yR?(O0ZnGj;E_CWTfO$zzu)gyIGI^z;?^ zKz;fAtdl4=bfH3^8vCldsrsklYni#Wb%)T_clD&rz-nU4uti+4!0%2^-KJkFwu_nl zRuK_#qOJ^jS4|wOxRT@Vq9VRZG-_K}u6|ozSjMmBXh8yZn^G2x`jzB5w+3Rv&b1u9 z@H$rspUw|;|3AixlqDTieQH$v2DNcoQxCV7@8b$ zv@R1%%Vuqwi#bLW-huX6P0bg~jvV{08j=WTPu>1#A5`LoH|2U&hjsqC=JPa#s&;QRi|&rBq00isrJ7 zZzVb8ybx={T$HxLj6>LNw6lLnS($9tOyoRThNA@uwNy`9my@~LHxr#cd7ODWYk z}ze1<}J(awres~F>6KbWctJj>y{C7?#M_HEi-mV@ACp;`GPL94$z+qp!%v2Kcce7pz~AL!Zt!R`eY%@(gfR2=tmu z`x&NnY|k3f&KPz%Sx>~iBkp3D)TN9ILA<4vOG32@IY75xM*F4KrdzP(vF|Cksc2NM1o^JW!^>gVO?<@t{nM0H9}-wvdPmmLK`uJ# zBTUO;6hiTW^#dtQ`Pj(#_8mp&u2CE_Um&5@ywKR!M*5R3!oJoFg+MQLm0>^Oz0uIM zoAABk&(VSeUd@`8eb^1-LQ;^h_y#Eidf}*~XSLW{hD~fA(f>?CWhH|IUd@yX`{*&F z?fVe%Jl#_v&nfg z?Hw#R&!|&un5eqfUwL9d!k_j`?3R6*+gPFACmm4d0P9(4u z=)}k?JL5#zaiT?jrV!|b_j!8b)vCI2q2?Iz;X`ZXevSn84Sl2EUCnqtAY2?B)mjr#=!^UMUQje z7+R3P`!2mH`tD}bUpiKdw3OvYpqD!DRxiwrDhtMnkg$>pfnL}*bdF{HM5Fn-5n_v1 zbB-1yaGuw+j34yEz9G$;zZM%wpTfk;F2NivNT}C`YmxVcd>bH! zo()yrGa!MpHt8pJd}9x$Np$M zRt$ePL?O`2bNx=H>697lX+w%}e(PO6ZB{R_p`hwF2bLWu5`K;5iUkO5Abm4Po=k7gU8z*vFE8L_{RWBxA7WJk zy_B|^Im|{h@CpzUp3@GBHVI6t9ZtWsjwxE_pqfr^ac++gd$&9BrjawbHi+8e8kL}Y zeXFwEe+ttdsV`iqPqbY0pWmy|Vs7+Z=5%ZleO>y`q7VgVvgG}w!q(E-gJC1bh@f93 z`Tm2n7A-}Ji+#5-Eu*g*17gz~`ma4i;+3z)&cbcX zp^n5W*OnN!dXE&_Ivr5@7W)R(_-TJ)^KC|>L1AK7(MlXGNZ=Tw{04p%#j_$!#KQu0 zxuSLNyqIYpNColfAw~CI(+g7Zl&ySb!l3R>u|B7!#8#>CV_I%!7Ky)kFBn0B`XgRZywg? z1>DxD1oRrt5|kG?q@S4h{G8!D(w8e1Ak-d=JQ*hPyx+qwhCE=}HyY{Tt4UWfo}nha zs>Z&h+(1$F`~m*_KE1^OLh)KMp1vP!VA`M4XzaG4d%4}Y5WYS-C)dD&gsOXf&VP&; zd7&xKv8ld7pch^RG>eAND(1o~*0PnOa(y6yI_vaBv37)*<9FP2(8F6H&`Y@ zc%ox}k+au+9&7zV(kzZ?FX@{p_A}1M+Q*eg`GfIY#J$!B6=LozorUgMLRob?skD|c z@3ir`XdmIRH-h8uB7x&g(^}k&HP(C_APPDxRz@Ncw*AxCg4d)SAJvuaQG2_UlwqTr zi^Uf_6#~6b%biZR^++(fx79@1U2OzfJkO=EWDin|eB8{0TJE&Za+OIA?wwbJzB$Ly z3u%l;*#uo3jb;rRi%R?J2qe%8>qPmT*E}#v2GZ4(vx}m8jwQigqBj#cKbr#Abr-&i zZ3On9xvsT0m(i^4X;Nc6%UP6PZ_-6XhvyV%K|+n;H7bbvzb-4T?eJ9UfkZ|%3p3lt zGwo(g>W?A|kMY!`!lFz;SA{??)ODx*)VptSHs~@xbElO+uf_$puxguku%ItaCY5MD z_#039{(=XXn9^2AprSqH$aPr89d^#=Cu$E+2=qdwe0u))^p>5wa)Z4wCMX1Yq0T<# z9{BSD8+h_2TU8@c(OgC~Zj49Q`M{HWP3%P;8SO8y>=|X^Sx^OP)d@9CsPRo_6yqQ8 z{Mo*9mnA|W&`XU`U}P{K%V&A~m@rPDmNOD>3$0))ex$MVd~Vc(x4IV+tELx~X_18m zt}Id4StTki`o^1`Og6QD)KiIpUP#l*@|2fop}jR4w7AdFg7MUqWzT?KBBNdl)3FMF zbMuF#ETavLa{H#rdKYQ>qIjp4D0FopPm{F;66l2`q&E{e3Wz6@Z}H@jjRab-t*~!2 ztsyTfdKPTS|Gd#uA*dIW)!a>ql}tLsn82`73q0!+f`%7s9thL%?XO)A`+<5O?wA>j1u84u{?Ij zahAR#hNUO$)U}?C6rF8VJNizuAaUl=9-}}u+VAs)RvF$FUGq#fIn1GZ)lB;PMTkkW z(2CP5Mc0BdpAD`K6Ta`S>SaIEt{1Q%k)CHJ3);L_*IHW%S3O(=ow%!Sem7Pj&M;eD8&f>B9QdBz z4o;_4enZ;PU%nwzRDpZaD*w(5YF+C}|G~GnY|P@(vfO~lTmuUdi3j$w@&#w=S{rNY z4(xV>Z~NF^ZqLz}YqK^mS~2O`t!b2poSsE&X#bewI);kPbbWlwFOtIA$+^$#a>arK zC^l=_%I41eMc;7QKch3(LbowPKsa6JLxHo;_u`t!EW4)Ld5UVO*^! zZ_a5dyRNn6XhA|9?HwZriHL~@c*4OFN`K(ELiKl2*suu@Pcm|fn3#RaHGxD|MY-N1 zq=lG1u(T+5)PbY6GI}9RUmAWoiAlZOq+81Xj=JaO*7WSLjpmgJ2meQnJ>pWh7;$Bi zaX#+?hI;C##;%>AwRWpSU2~xIwif z6#gz=E1FkJFH!zY1(DP!k5Y52Enf4Kb$W^opL1cD99(lX$9WLPG4?FoqYf43lm8ql z*H)l66EN4J7tVH+;i$?v!)bOune^G0qXh|dl(<~><4z9aQMfI)&Tt zXG!6*MEOR_6{UE=RY3QT?XTFnVG*)>2Rb1Q7KKpMzg<_XHnpo4A&-ssRtQD?ThS!H zb8V;?`@XO4xHnmusXfQUvC=gRUE3O>&f3}@eTb-Dz@57%Cn!CLy_Qa^eE0sO?-Xra z>Bsn$5i!0#BCOeYhNB(5P}iHzpZ9srcgH33^T*l?RO3#hRlez5nr?p7%!HcTG$)qq zDZVvc!`GOOa4d-@U&^Mh*L5wC@>MCNT2-%{7^Kw@Z>ImrF*072mEE;E{bY4))s$>&b}TA6dpMi z>9aRw7uaiBUwV=#L_PRXnA8~UUw0L&NVYvb z+S1zh2laUa>(j)knT16zw}VFEST}`0FI6wxe?y?SKe3mdH#CP(dJsmUQd+H7t!sSN zrTa$Ra9@GH`*y=t7SndSp8mP2NsSS)^8zo?`<3y%VoOE$9JS6-XI;~59eZ0!hfYrO z{TeOMf*R;*jDwAmczlPg#;rg5CA9(1L^-C0^6tE5exHdv{Kh@);8fU(JH)X z1`po(+E{bZTWKq$9?;S>5;JVX>CPXF%DG$>0^_MMX1kT)w-;_Rd{%}D)YisUP>C;9 zT#PvxpN+Eq-4p`7Hg>kK#3jpg?UWa_)%Y@bWr>^Br1zJc0@v-R%&ihGC)ya@);%|B zFYcklKrf`}yV|ceM*L|n+0W}fM+?SNSK*;MXRzk!t};(AXMxWENMJl#0W2EIV$vJS zp7He*0==*|=^IPiYy5y)Ir-vPHD#2b7t*xX;IE8Ebn1ZqXBMcenv33|<=%THQ{xpi zTFEbG)4jh5v>>r_?N&Bt`p7JW*o3shd;Tv1y?Phk!QQ->m#N0=&aF?u9<(MvaY5jty}PKJ zG@bhWeCOZ(Kmxt6XNgGj%8c>rSG3aSNPN>0ne-}<72|cCg_$w_mq0J<|NmObI<7{C zwqtQ$XESTfOVp{w_`ao?f1^q}eG}&1|JDO7NW^x@$-FDB$)ss#&0j$-zk3h~^uoTO zldR2e{2K!;NRYt4~BFSXA{vts-vto1+(5>JaSV($_>vWR7$d;VK0 zv>=f+uKtfwA%R|(qgSz9XN&$%sjQ;}XMhbiwzEV1Pi892;~ew57S{ha3$!57^V=2{ z{$kqyQ7R)F(>n^`gD@gx7va7dun|9{P^iK?a=HFQ}Mpmh4ZvS_bpaqE@=Z~3QmEM?Ds->TM{@a5{pcl3X zeO=0$+pX6JT97#MB_Au6mY5Zz@3C9|&R0mF7q**P^AT~&^a6RRXa3gQJahE~bL-5% zF<$`X`B}H%-xz2?BD|AX-*sb1R;d<$zVmMnB7t7&X#cNVW`PzYcJ%D6zx17&72`#n zh5yDt0=@7``!9mEb@8hG=6T=Z`FdUE@8b1Hr&8LC{`ci#l)BicHka$w&aayDO+p}Wa+HRLwbL(iw-$E}O)BlypT664k?3*^{*61-d z*|K7+{Cp?#in0=DK?1W?{1?MoDkRV=Fm{vvD%-BCD{5WZe`~nUWn%T<#1_mtb7sXb zS^xGrG)YgHJ|OeoX-|>chJX7UElA*O_g|^3^*{o>#FY@e?}y1*F@7`FdY}afoR8@w z5ee`I@Z1z@J&-`JPwjT->FtZ8 zW>9Zt-qrr?K`eXO;hXg~c55?htJY%ytSr%jM7%TUrP!7IKiUcj^uiL7KErU0{k>~Bo@!D~JHeSqy4P+fEUSKRD(ci|iB=EGO^;=OvxsdYL-dVSdqxLvzxmO)GO&_u3ysoXco+WE+XDg>oXf7A- z-pOCkRm*;CH zM}7Yv0=(3E4EW?AFZJ-2hr_I=`=|Y@_>L{D5<|upkdK!8$gXZP_=WA=^aWEk=?z-0 zQPt70e%j-s1*Lsda~XVomO@}FDD~4kR~41Z4z!f*d{r&)ekI%Kx#AM_Cne7^)a%r= zUDb=rD$l)T$%^9@^>5U@S7mOymt~*($`MY*c=+`udb7C2y0?$LqE4#T<86FlIlgWi`F*&Z zN`N}48e?qRI&xJ%ce(N5YG(c;QrD`D(;Y52C^2yTKpGH7i_7*MTFW%gMNF}PW~#c% zXk+Uv9oxFe?fv^RT)m)+!<^=i16ivyv17y|6{- zYu}%pWcz*jWYXQ~N?Rd;t)OXLKaY|-9?mmHyk5+(Bv>a@og(Fy@DZ}ukpv^mW0{T? zB=8Mdbx+DYyoC98W}({DI7P)daa#-no+)?C72-B`t;dl}v>QK1QA)4T9T(Q>r& z9aEQ&KRnQa1jf^}cBEjodQUyx&&z?~T^|**FgEQqI5k05@vgwrY)e_tf&|8+Oqjib zrKRnCzWrkzhI(zNv4yKM%IK?3VX zFAZ7+I&#~7 zcaf2Qg;FX!v5Y0848%Vi&R9avi;;Tz zrrAuJdzJ3ad1jT8*@rh1b6Pg#XhFhvLuY-&z*Q`B#i1=)S6uGN)?94A6`~O6m40!o zuK6t_wVvY?!}exzd9-gcv8Y%WM+*{)E|TV7p{NZ0+e>`BGK-I{Jwl(Kx{GD52SFDn z*Rno(5swYby6&R$IPD9`wY{5*LQXTeVgUk`l<2(L410M$!%wt7G+ZS>Jqb%l`$cb- zk-2jV;W5_C6$=n*JuHU{${S_9MDd;R%1U2Z-GlZLT_5R%<@aAr#OSjt6auw(RJEQL zK@QTnU32ky^a8c5P~QhzK?_)1RGvBDDF#;gpBSKKq_nzrXn0}SIKHVU@MM`90|*V{ zkr2I|xI4mIIKJP^@k9;oV(OvCn4$-z9?cJTbk}DP<)KWDKYA7~3RTgbmsx`;+CQALZ z>b7}A%9U0^n@gusV4uDQJMfj#YR_-y5(9>}7IA&&sr3Lt-F0uNT}JdB+C=o;JAj*~ z(w_f@^O<(>lyZ9D!T7$6Wh~2@OWG~2BJvh<6W8XBrJeErS@67pQd+J1!>S_hWq0xN zxIZsgJ&^TTurPDp_1sIl|5{CFW|!M6eQp#>_n*zotFO?^Fz9XtF};PSs7opyNT3(S zragCc%ZTi=nuyX3LzPk?f%Vh0J%6}}aW!g**DYF*?)e<9h95x$OJ@Gs4gRcY=$)@TU5TiM8#7x$jJcP|n9Fr)y%)`iWti?8Swd!&L&j zl+tQ}w>(AksFH%eo}$(R2o39`bsFF;KGrKJhWXR`5v#ljTnMio$nnMYf}H zTsboawN+X{>$$U;Sdp`USo3H(SAGj(sKlQgTZy-AbBpOe7IMV`gc4h8nYX!U+Rt8W z7)~=aoJzoWm`9V8rtF)G*$wPP8;6w&f#(~LCM}D;%|-D)?1asT1f?EGC~c^n-dtY9 zO!N@fOHEVeU7Txcwb;gvO(dP7ZY$_*RGBB0L_%^y(W~(ajus?v|2};y8r(p1PpTrm z>|3S~=%v=YeY*zY*ruxDi?Nua1qnPILD?NonZ&sBCB&6S@d|-n*y@_L;j*VV+qAHp z(jtjt7FXOkg1b62ZEY17ak^7wY3sj0A<%1O(d}&87TU}0zM9(Vj!h%ca!X~|U{D-K z3lg}Khn_hXRuD6pi`=j~o?}U{gv!2mt!B}d;-*_ZdB|glvLhY|H5={pioRmfwmkBP zFA=Z@68Amd-jl+DV|r!1xl8ZmBl0!PCsQvk=ZXb(600#nXSNW_x7f+oxtDXr0tD_h zrPHiw&BY)md+Bk6ay7z!YTRwA{E{Z0w-mu$bIJ5)Noow(pQ^T1*jGQn?&g)n+fL`N zE^cK$mD*>%>%$$`xbu`0f$I2*)C4++QX$YwX%TJyl!jtJ{o2yUCxClKO=m%KChF$Ax7oDHu`IAkU)}nI zROoPw^#rP(?0J{&gG(N{ib4sbEML@*qZiWVfpjk)6{VY}SnucADPwwtJ(N>#a#Mvs zFRY)YvCmwrEn7iW$Y>D~J_oJwLNf^froD z6W8;(%PGrRakLX7(6K}#_Qqv z#5LPCa&5Qa{FUC6eN0)K*|)hCwPu4KZ2MF3XbKuT(dRAMOPt*$a zk*5YPuYBbYyQN&Q0HM@RyKu9L zC?C~WHq05raTjZh&l0w)^HE*0fve{9rIK|}1 z*m#a!7!UXI(n!3nr@HqYCA>y0{Tj za`@o=|J8NgVO3mR7e5#~v1?2$iKy6HqOri8IcPL?V~b+%8XJnBC}_l3lGsaPp^3dK zVvXFH!HQTA3zpa$f(2|OMC0qX#yjuxthvwk{=L`lUM_pjnK@_ebH-WyRhCjFaVdH^ zzbZ0aE0sP$zMd7Ma)gP+-rpwpC1oli_YR0_pAXlbjR}%dZ(zp4k?@KMck1J;_2hq`N3>ITaNQ*p;3mFN+9Xugt-oiH(O#HkWXl$wizWU)Xz^{w;pjr%$aCpK?$ z_yxA|{dDGIB|Ps{hy9)2*IFG^s@Iqx1D32-Il_eC|FlS~uu%DYSdh%#7-1t=^~>N8 zhrT(@^fhhkIonRKiu)YUBfM#j?rb>8 zhzG&_1>Dcz=b7$I+qc=}y$C}osh5eGYGlreR=B@_>E!-PoX+VxEn<88Cg&%3|KMJH z2X`Sbt>tDWOj^I&B1Eh6%9)4L;3!5b+)cxDo7$s%Q_IF%M99jWYO8DGj8G8V>B4<7 zIaNX+7d=W&8M57IEIQhP+zQ&-fJt_YN_=Nb9A{ z_F7;OQG-+&l&6*v2ZB33nZAA^R2k53nngrD50J?}?a^m};0{dg%&fX=tx{=g35!@0 zJxz|Tkgg2@!991}ja&5BUCPs_5T|QBQOlhwH{U3r4h6wIaNKh@{p4;XB4@1Al}w)*7I6@6ew`J8av%uq5#h>vS`RvmYz$b%rbla%T2i#r|P zWNovEA+t9rD+c{2kAmPnWTw6SIye$X#92hnmg?H^{L^Is2<~-e`e~ELK3f~bTSV6D zYI@6*FnJLKcjGaAvPwzkN1b+C#DdeO^?dn8NpmdWPC)MddvxuUGw{bv7E$+}htc7W zKGM8ud3BlT2em3|D-vQX;tZ~++qj~dg5Ya{uOj>PG5d8jx%`%Dcz*w}$`K~`DN2Y1 zAeMmmr@NhCmHlbyVyL%FtEU*hk8GiGgb9A`La#Hf^AKF;KjL@rbvbH@HN3#k^TB;zOI>ko>)iT$6v(}ChV(GjX}HtQ3x4if>pdqg}L+dCUSY5 z+A=9`OWXPt6TFrMZyVS7XP{fwHv`IUNuBd(LFD@@R^?s+R((dp2&oK9WEXBsNJ|n{e<7acNxAfapj}O%TZL$ zc;3Z$g};g;OoSZuQF{CnZOsiH_!gDRK$yRS3086C3sLRO$1=K1XQT9}7Pc7+6Fken z^^sXb`uzT#(V(oKjbIhemaq#uzJ%P?uZ__#-wfM4iV6GNp!=;Mvdpnt`tyf{Z3L@q zJ7+~dyd&lJjYW)Cy)Y}H`T6<%>y+vhzx^;nvd;%)Y$w^Ud@nArbbGH@ z|J}AAYJe!{MzG3$)!q&1EYA!oZloh09ATnK_)46#+0+_K(m@;pVU8tCu!_eRI9Z$PX=B{IP(9{JG8f&2NlxSyNPC45KbdpM60LTD2^N_|af z`7eG4N0@k%FH%`HqNU>M5ZVtS34~egOt6Ya37kW}zP+5-rIh>>`QQi>_BG^A^V-To z4?mFwJ2bNqHr2?*ir=R=n{3xv%!*E>wvzvbmX!FP^3Cpf zHpk?zq2FR|w#(&IviBm|eqK<{^6M;%w-2%cw*WJG#r=~-)> zjbN4C&A7U~pzNRBRepm16-Ssj;Ao_*zrNba#}yDmLHvO`Cljo)kBNsL6q1)yyMM?a zN0{M=@LBI`VEqjL4oRJjMggCk7TXxr6MIcA^r->nTI4Mb_& zIhkNpOqCZtTPGi|2kVr{ug0k;QulsvKd$fAR>&+sq_a9Sdm@?=bE%!79H4d40RQPPT~jwdl?ZoG3e< znx}Gv3H#i64v3#YG;||aWm^>yCnv-zb=L>UbFWv})=QY+xjNoDz18&;J_A+4&(WM4 z`!jXJW!1D-{in%4k#mkP!Fj?vq?cCHUVzAUBUt4#@e^mmdHb!Le_YO6JM0zqVT9ud z6Z~JtDS{x5fGC9PoC#KKxL3hB6X)c(#*%|$s%U>Nn=JDq=Nw^z^Mn&J&v@C}_yQT^2ov0Ai!-C>0#7H206lnz1KMg zgb#?;ZUn1-3Uz3?K1W<@)?)tFY`xWz?nchp2$dsD*n74Q)q1Y~J*>Ookz*%V^>kn_ zt;N3Enn+m(CoXH_9Q`m>)f%HpcwLNF((G$wb&_W5t0IDp1E>;?FfriDQ>RD#4lCz1 zK`aMhRtXcV8oBj%XZ)r;7BP3_EZsM7f>8-o!VxB>=KSScP;sA?^93LrAd0yWtg2Nk z$~n4wf<^R`Gxbt$#u+z}bB-{vuU8&z?w5v@^PV7zgAk}ICRpX8uXko89=C`KPiE-q zg0V&el{1;+$K1U9^ZEhr;!k{-cfDs}U+kn8^H3 zC2dyMCpdY*%=r(4XXsz}jW!zRkF*i28kl{?89V$H-jZnUw762SxYnrtB;#=NdFsi{ z6`fl~WNRN*$^CjXJG?Dht2APjL&Tjul$xBSg?p^WTKJ*!4YeQF1{uwkN2(kNU(+ff zcFto>?7rf#eUiAdxrTP~LXdG`WrXcJn8=MQ;_Ol5iuKFmU#)Z&*&1XtJrt#KgbA@B zUqYM22U@r&j_2JpeX#Sw;vl2l(dqHaG-Cs$mN0`W{^ERQ&Ufrtp->YnJjswx&jbK&nAz{AN8W%oS87EGCJ>zV0R5i!u)(YUw)*C(*HR4yWx3_TI;NtKiH7tBJAHm#N|`b zz7;=u?z+;%yeVmp%qc-e`54qLsluO^_HBCjnI=ZYIqbxZ?U9bl_kxV=-6K_wFd_H~ z7F{hj!>o38Gq@@*)*I<4baj{Y%n+P;PPrzh8h25<9ASbh6dmy(u7f!3MzAWb7~2 z9ASbh6no-8bO2%A4VYk6VXs+^imj8Z>*Mz0WTnKLV8emh

      0ZylC;M3>*tD{;R|2iWXg(h(%3 zBR42*@t9R25bE?S?P>!-e2oj^!W?exzj9jSHAG>@%DN9F<~R6IVmGM*mbZnD?4|sFWW#CU6SINLz7#HjJ*RcTwAMh7Fmw|UPu9AUwH!jv6sAGE-e8Bs7 zE&~rYu9AUA7}r>zc(;=Q32U&EN%Y8qIQS^fW#H?Kt7PCG8y6QgQpd*1y25~jr3*Vz z0Vm6@P#QX^Wl~1-D$#vv^sq@S?UP!dsyfu7Lz7xyrs~K_rFzVy=nGvle1mb741BY3abf6RFCSMJkg#-Nb2P;F7p4RJN6%&8H;t=g z;J1v63q$|+@^OU$30rz$uPM-7u}1!N^ZFGbx~BY9K2KVbR$V&G{9T8-BKMShUzF`t z8hv_|#;cY?Zx1X*i8${Pm4QoF$|${~S8}qo#oR-970+eh4&y2r_)z0ITfj#c7vBVt zb4&TS=>l$TR2hg;dImRF00PTHt87KI1L>-J8P{5+L0{|tx-<>SOB7b<0PijbPEp|0LRH{tp3A_SzUx0B0&iwq+#~dVDJ@qR@HwN}fheUriPkI&ECc5m zH56FXil1rl+C;Ux_y0fw-A}6e-6Tguy`*&R9{7b`Ra&oj_W54Xw)mKiw%BM5hFNp&(5n;?;ivh_O^;mMxMz#F~i&jN5i z&=NJ1i-k>hf|X!(+CbTN$8(ZQi5Z{&9J~ zA-iH}mFf?Al&Z8_EVLcCswlV1^r+HU*ZVOx%yMFb94+rLvbDVke2V8X@b`?XWZ+Yc zi?7Jzb?l6S5BO})W#I1{SINNV8yD+O(6NaHAMjncguiTDTr2wf$j8+R zBrIK6s{+~z;^4C9GVs~PRWk7Rjf)FI|0wym!hoYh<%Q8Y**k_OM66Xt>nw|E2U1l{ zKE6Sppn!?8^;}+U@Bz>ETn4_!IJc_^-)mf~KUc@*6@0*tdoBYnFs_n;UokG$U#Me?3O?ZX zJ(q!deBke;!7awc`k9XPE%<=f_FM*D&p7wiUbvre?p|GZ6XPlwcvIsV*Rhd&+yVk_ zEGl0>v=DQS;fd2<0Rsy8z}tH+10QOf`+Qe;q;c-KLij4<+}~{qUu|66C+gT=KCVkyw}?2fjlec5q8&(mwIbT8v@Z3Iz+%$)E42qG zpxpvnfoS%sWuS4i_d8c`vZum@FiMBM=Uq+}JjYXE)D#_>DqGtt!P7jKfq!D0+meKD zGA>>gGjwcb!3TW1=Q8je#;27cDK#`^!1k6YHj z1xB?4QA)4Yg$h_y$Om5RxeWZKaqbnp@O#F^wU+*yZ-;$lYjX)+%X1lcOXDgTxW93o zE#MuEb6<%Q-ov=Yb*v{JH)cS>(gU=i0yee4Rv`7c?`LhLquZNTTezwR>d;=YwUGcH z=(!Ahh;fw+++keYL-Y@pkLw|juyhXz+|L5bz+zy$VG%gUs_I__m&LV|MweRpZQg&Y z=-GdyJdU(z_r((7Z+R{Qf7iH520qEScs$VmwtU=p00~QvM;usA1;*n+;CHO5{#Eda z;uw!@qwyFok25UVeaT<=Y|mxj$BnCG;Q7XNwt$~Eu9AUYFfJZ9>bOWgZrp&688sC6 zgs6NdY5mJP0!f)3^Ehdlq<=T9cH|d$Dm=^X(V;(>OY|OOp$;vQt(}PA#h%N+ZyM*e zJmL3@iw6+>cje;-5J*^h5K15F0aLbCSP$Xep3A^b8RxzE<>jM)s*dWnH?20{*+#Vk z?-Es$Z>!RJ)H?#noIBF;bwq!)I#L=ZnpU*xw$UN#b6;SZ@trEIffm>X93(1t3wK%qtO?*s*HzVdg$2f-XeuZ^~zO}DawM2UzUd)W^{t^k1BrKHGg4wxBC+Eoa;Ay30xRl}8$YlP(y2nV@VC8NBz zl`xnAJWqvLd`c&wR@TR>rW;*$8$ z|Lp{jj?TIbxp$9hSZB_L9Smc;*1;JX`I$CR?sEj;UwSSB-)&qa13zwDe1A1x$Np9D z0l(#h9pvM#k-)DT)eii&sQfmP z7W#=R5Ap|?RvAcCe$N=L;5e`?6&Sx4J5ZSpwv4URd7`Jz6a1m4fY%x|0(gs2t#bq) z@Kjj(bvlG=;=2R5++-@lfip#|SUTa=(&XOJ9T=frJ-VsI<$9AES8Dlay((=|xgUK5 zlGS})%wID2ZlOoY-ZiJFFy?cfvewQH@ME6Kz>gc}9)pEf=*3-Me0HGUTRv{30tw5P zr7t{31U{@J?k^~T2)LVYU{Nc6Q?N)Hc=s-yvL&jAy@FT{#Utj?DW~Ih^Dz%*^ zUpEcFo(fA3FM*vFSO)&usCM9eqVf%t)?d9N@E=P!(xQ~au1y`sn^qg}UZaKq$y}?W ztxD_f-VsRV+>w^ABYI14p)@9#Rx9vFMhyjCE^5WnSoiL7(<<#b-j(9!c`7a=dKYq& zyzjKAR-&HsRJiT@Oozx>yX_^6KG(P~?ghoYxG|M$@_(sl56I52d z_Gwkcy4zhKIdjKGJs^|24ge|I^TZ^jo zXh@Y784^F_`~?l)yR!8kWuWnqjcqG%UCY^y`Xo{H(4VStxB0aKUpK0Kg%$IKv$PUO$bw z7TOME0_uL@(zr;YTv$|(*rK|~26y5E<7hDAeM-ldR{6;Nw`CQI%G_!6z&I-M=^YuS z=dAgupKKtL?oJsdd!S8XE0EOAi(&U;Jd`os$VMgFLhn-Mr)Aw^>-Zj3T7JciAX8t{ z8i73hcCR$TUOOu6^M1q%kMNe9}_nsNRie}N7${sv|7LJS8XE~*49!~4v@+!wR3B7Z}$OcOTR6u zu&tJ3Fp#u`^Aw6xc}cCXIE23KwSgxY)q1Aj*`5OWUPb?20NUOq8a`Yox;CNUF-o># zX-vK<)TWsFsu<%|Mc60y{#CR!uUM-6vcaSl+U(}NYJX(Py7fDlBSS^DDRzpUr2$p4 zaJi_J4rZ6C`H^6*7GG-3&eyR8=Hq^uL-;w*W#AvT_}e1zbmQEYg@tc5u9AUg8Q0kY zUb~Oi3;RxO|4|+8HVb&Iq}+-IP7_tzraG#$e&!v4zg)tR7KJ3v5$br)>L>&EH2Gn` zPpU`xc1i0~V%<9tAQ^MVMx7^<+wg$J!1z7TmsC>4mqs5~@Y`T&hEo|PuI&gU-O7qNv2>cd6w)T$ zN{+2x3d3ZnZRK|od)CU1J_o}Exx`Yy1<`0 zXW0f+9~FLF)?I2B3(oljGts{aeo`D?N!+Rm^J2jp{9)t`)7NIXe-%vSUOSxsFGz1M z**@-HK&d~%u2&6(3x`6Ldlmgx+59tsu!{62O~2LH_#uqnqJ}w@ zdM*R+WLzZ!?`B;5feiXzl#e@CfQ02IMmRhJ6|h%99DIQ1GVr&It7PEs8W$Ia{@(Jb zU2X&kTY6#pT3{J?v{4>sS^=lX*0w$HSkGnP9~)Q6z|)O$ zPiw-r8&}D|vyF>KkvcArj~hjx51Ytuo7o)4VP(RuGo^OmG*S5$M{A~c1m0y-2aqcA zSSvsvuA_}Qih+&CA8&V$2P_80Z@QOf^>ftSdt_^i0DPb4GVt5RRWfjCRd!c5xxyP5 zSINK|8W%4D>UdiEZV>?AGO8W;j;Q?XqP4#C-SrSi%Jga2PXV7U6bAl`=Q8lt##J(K zf8*T8J;DQwt7PEqjEg%@9iNkr>pXB9QF#YwA?6&zb^RHKsjA_WP<+PXvz9~T4k3j0%DvbHj zHVv)7bB&4y{A$(5+_*0pp2rsu!{r?MroX9&*IZj6t-!~PicXc!s6Vs z*cznq+7 zSWFt1i3O5G3*)h87z6H@j+mDf)T z{lv{rDBr8pF{vd?(5vKrd^Su`Kc(E~g<+Dqb2#_UsQUM8lm=A6A6m~^f$Lb$h9duU zPklr1RN30+hZhOc)fyKT@k1q|dv5Ppr%K~etD*yVm8iO3D0aIJ-eqyokBa_YhaNYV zXiLY1)#1L#G_p#AzPRs@v__rjuMY2HgAl)834Poh$mm8t#EK5%y>jV|3up8Vd!4t( zDJO%zG~X%mooaQu9ai`T&t>38jH_he`Np|FyAe{HT7#Kh3{8rszO!Ef{S`2G`xu->UxUkb^Y;$i~ z^a*d;zOK~c$A458-tP37(C9%T^iAKu*V8>H;}M=iH0*y;0y~a1B-$24FvLdySMVdt_9ArjL~Qza8IGf;QKw7 zfsbC@ZzSN+#<{y>;h!7l{@rBZ8OFH}8insQu9AW8H?Fex8^xa6kZy>fXSp*g) zAsjWL2H3zxcU7 zX!|KmU6eSwKy}qF2H@vBmx0$@!*6fke#W_9G!x#!xJm}z(zy7dK^=>18ajaME3CG7 zJF2uc7wh&iAo{suIMJb8>Xsg#)xCH#nRK%L64*huHmu;CJ(q#^G_I0?2O8&IS_$uG zTqOhVZ(KaAtvc3L@Bts{xePqgIQQ@C36ChlfpP9vDTSXiF4kYDV~Ywt;KiQH z!0#DX$-wU$*I558`MBF(pbtAK+{j9$HS?{!hiq++0{8Y@242OuN(NrlxVS9zTjb-) z0uokRDDiw}3g}x92e0M147{Onl?=R*adBb&bZnD?4|ogDW#Da%bH5EN{CVSI{r);O zpx^`E$#WU_i^f$l@NUM%`U7=ruYwPFf6ry$gN<{abO;YJF4k|=v9^K__%P39;E~3; zi-z!##>M)hb!<$*2Yia>GVtlfRWk5+<6?b|ol)=sU*Ne6JkhvH2EN3&SbvI+O)dC< zZ}40OzQwpo2L73GvHlDln_2Jy-{H9oJlnWR2EN<4SbvU=-Ba)Z-|x8${Gf4_4Ez`4 zV*R-~Hm~3Ve%Nyvc)oF!47|X&Sbw38Eh_kc7ke%PZ@8AfX9aI+Tx0zn@^M!<;08tw z1#V(g2N3b}b+Eqz2FTX-UGOfR%fMF|=YB|6c#3iE3!K6;jjLqfUl0=dThdnGmyC)wRfGzqBD9=KB|~bPqKZOy8ub{Nr40Kr7T$%49jSpl zQnq#<06xld8F;pF?lw<&j&YqW;3ti%WZ)N#>udqPYFxb1sqH)RaVs4-%cyqX-JmzbK16>yjA3hpnJ`)^zQvzkvVNr!^+4wu9+ilUqU zpX%`#6?cNH`_oO}xki;4_&<0m>?K0XoEu#r(f>!2*r_5J5eM{4BR%VgHAT=Z&>8+3fyxk9SMCB`Nu2# z43lxceJ^~T=Q8lK##J)#i^jR@k?>aQ`ZWvwtZ|(!;BOcguUTrFE={*)fsYy04t!2j zzC394lfLUZkkq*&Eecu682!VNmVr+gH554CsNq10sbwrzX)QFzGH_F?b|`QQqlN=1 zIhUj5I}kmOgaes=KK_4YZ2zP|U_cYYAG)}&+6;UyUtQ5h&av+s)ju@&rdsIR$LoeC zTj-kj8~-=dk^jopHk)v2QkOucp4Hi%h1yqZrKwifKLROuX+s?QzOnV68VqshyObfu zl|}A`80f2Vr;q+pHSEEc)b+2(rallJtz%=%$9+Xt_(acT;B(gVdl-0vah)yT9~HwZ?)G*+=qVmm;)--eM z0N!oXFd((&vEdBdrz#(`YKMLxxUy*t-Bxf{PmK^f(^C|2m!}$~`>UmEC*3L*)lRyd zJVmmga;dJ;tAigyXx!qr?9+GF7cOSu}k!m z#1wwII=i$EBzzloAoQ(0Ck6k-F3}BF>=Jc=Q<25Cv<@VE8+IV{O>_X4A8G6oza51O z)wy5o3Pz#CA+(F$e&3WFPV4VS_g zg)WR)VLlqU6oxf)VVIXPg}5wbCT3`oX35r03h->tW#Idat7PEc85iG?qW^38xcm8j zPvqwdln;-;q%>Dy^9m`zk9#fyKW$tk1Ak~-TwZB|yp|raweEv^doBZi)woIqKHRv* z`g_X9Ep*_aMzsTnh;kqMj;hi?-hHinRP^+^jv@xhy2r4YkLO)#>f5t)NK>E0rFNuJ z9VuJ?+(P(Up3A^LG_I0?FE_5U1$?z}l?;51aq-YnM@2qvXn_|RH552el)E1tRi$x> z$b7%0b(N0>Qb+poL?z#|z%sBH7=P341O?#jUK;|t7I?m8YzNXeHyl7Zmf!2UKT=fG z6+RkBhwFc&NP}944|k%or9%nsLItFR|HEpgsG6y=we<;}=D7^~!iN6x4PI!R`y*`O zEjRXl;RulPA?dsB0_Q8-4GQo@QTb}3wWjo)BaoEoWfvzclXR>l9R?&#O{-j`wb&fX zz|uzA65WlsU{BdRme$_h5qS9$j1j=*Bi;`3rdRdv4XDz(2Dc0UnZSvc1Hi7@O$ z9qpr|t&>`yCh5@1I&@k#sRi!dq$r*0qghxo)P~B0Xc;fmJYUh9E63V-8Rk(kJ zC(MwuVUnB;CxJyq!S2#o;?J2w-QuxOy?89lv7^T4m$n{#j)QboaF!HxI89iM#bX~Q zKY8h6Vz|E$>|Kg#kE5a|*hiJ?1=|oJm;O4_c95;@-r$`*mw^WwSINK!80Y?Q zTlhfZDj9f?aq-;+bsQ`ox59yhrFZ341#}d|!9zTkfxl{;yQ35yX+5z2F^zq)ZPkohOsK zVFDHd<0}eY*ICAP;7>%ke|@d~llQc5^RCppz*FIwj`wfm($l@z4Sg2s*dp_BpW+KI z_FM-3Mn8YY0Um9f`&(k+Q;my15hZ6I`M7BU9%a-};5S9(qfZO{#6A$p_bRn)S0%w# zmY^N@IZ^e04T8pY-Y*=oo;rl&C-Q%ye&AO&-*_v_vxddD0?AirrXAWMAx*+Ra$FX z(lXG?NAJ?Nl=tT?Dmvju>(Ch4+Ia*%(Q_I2hsL>=7{V7B7f%}cW98!p5J*^hH4#WL zJ>92<;R!QAq7w@RfG2w{17BgB`$ab4YmJMGNB?s9xZ;6?rHd!<8Vf7~i-Gawd5Qw2 z7ODc@;<*fbt8wn%SP{O%xVT5?-y|Q`BOqbv9?em}Jq2;_gPzO4e>bj@fgd(5E)4xY z%EuK3BrILnd<85hh=X79Tn1iaQ@<;K*EB9J4E;BKVZhZD=1y!NN=vWxdDAKbi-Ga7 z=%-AZ6bc1@)^iznYvbHc-U|0OF77191{8e2+j}kp?_gXd1Mg~FtUpl4_A2;*zwEgT ze2{UK4BTp5WBvW*<5mxlu=I>@w5=cx9_qOaJj}RC2L76Habf6}<>Lwi61MchzG{JG z;E_gk0E=4j>KUzoF|zeNUid`MW#9{pt7PB{jf*>p{u%Ododlk5R67u*bie28k0}<& z)@lX6;<*fbi0-1?pB!c2Zy6WY$|au9AUIGcGP{ypEkw@ByFaxeR>0aqb7Qg>Nt}*1uH8rkYP>G?=)=yv>mN zObhF50sqo-8F=F!Iayn-;C{xrpN$dT!?;QY-qX0a{Ckw^MavogP1{>K_Mz;`rON0P zS1JAR$}etIg4o2+fU%Y@9{DLc zHr0IGCo#g)JePqN8&}D|?-3E9+}^?p*?q|hJm=AO&IXB$_^z~>t0UJeLXjf=V;3vcUGs$Z@mvNz);RZ* zqr%4-7q9lwI(Blw2Yj06GH{RH{%kUATx0!frRB~hU{8gmm;Y=9%(cMQMbx9f#HA+F zp}vKZz-xIf1FvmdB?E6@T-=?0I<`r{2fVrGGVn#lRWk6!#&x!UCmWYI;dJa^S@-?} zNLXzM<6GK63OLFFTZ08%nxaEfWou^#c$()j@OCTs=?Cv@TxSdTeB7b6;4M>r*~=MoN-lJUOjrjG(iCq zWou&$zRYtO_$uSvPk0DlZ(O`4XXx0>f)DtYp3A^b7+1-_Pa4-){{i{9QyBQTQSCsK z(r5L21uQ7!13%}v47}coe!YR$H!iLf{dcUe4&b^9b1x!*D5Y!dr+`fg`M_IxE(33E zoO_=jyrXe(tpjyzuYwPFAJ1jr(~Wb#Y$QD1xW@V;cjsY0D)kERn(48zY5agOYTvKPrtkiAUy z3fU>L*U8=}dz0)fvf(qx&bs?LNefDDW}X##TlNB7qi&b|t?b`rEl}X!-Ha#SBXhwPsJ^3Jo%1N-chnA$u`SRULLLnC=T6l9>VcoOZ6{n zJo&gM+g>_-jVIqvl;=j-Uvx1)d4I1usPlke z-84FXexGD5E_5#_##naiMr~4zx4kq`*+#- zvd!{M(t7!W?1Qp@mF0$FRbA!!$+pWLCi_*{us@5$e<0hkQtq+4Z0O%6{xI30vcqLZ z$Q~_wtn43TACa9GeGZss`i_pDBzubN8M0wLSBn3sY(=^^$lfR0DBpG6j3?hXgTzKTQljzA~u|E-E!)_C$AtUPV9hs!q0PhRGCeZ`^6JfIWSf1m1K)_C%5 zro3Cq_Lpsz{}uTi)hDlPwCwj+4lB*u@5}!q*-yy-ld@sde&P?4T~WHb$et|QDBqxN z#*=R~<@uEC`d!RV-Hgv)gMN$(bi)3RkpHsAlkZ{aJTCj9Y_t4h<#(3s1+o{*UMhQy zY*_!|wR7eJ*^gw`T_@+)lifu2nXKb7^=gD3udy8yW{jYD}|Hv7+!V|LdWj~M& z_4}TgGi%9iAiJ6DHnRO?_mn+Wc7p75+2y5wPy@Z0;%}GzhiuDPdFHKU50nk-3FDtt z{OhuB$i68X#y9dKe^>qAYoOnzy34YM$qtnrCi^wnFyBALKOy_P?3=Rh$hMvxM&|8B z%gKMW2Kr};KS%ar*%QB?=bs?^*B_+odqw_h$!|m1&1JWg-A;Cj>>Sxp6}{J``ybi2 zWkdhfrPI~?&Elzd>jw3O{lky`h5B8sYu^U>;0NpYgR&pU{#^6&n+Ef9u>6)ao_zn1 z&ZDx=cQHSCzb^mJs?M_P1X=nKj^E*mTh@5;ZKpgt%I?|4{N&|)VBFDV+#8)A$EyBi zjVE7k)!QPwrfjqPea^{8bUoS6$_|n}Mz&Kn9RI%Jmo=Vz+ev3f**#^O<^PBLUXpD& zH?Qz>vXf<}$%gems<`>G&vjFe{F(BtA-kb$vwG;qTdIS89HRJfflk<;MT%S2c=Bzp zJUh$o)y4elpO;tkdD$am&ywBl{QUTrWW)M5mfse#pOsx!J@S8DI!DW%DBG+a^6n=8 zn`9r7U0wY^C+yEo@>|w;^8G?Ox6A&fi}}fWp!}H!beV_24d!DX#Vu<*`7V&o#j;n+ zHp@Rob)6vFDf`$3`A9F6oyQCPU;=(2|F>mJ`T(H6>_FLb`CuT3pQE_@WS^IP8NI+C z{a(^rNp|f9`XAT-zskFr`hDjQRX~IO<6n}0Z`n0u!}33_e_1+*$u3quM+9|k-Jrge zSydPV;!Z>@Bi0WP|RO8u`s?;1B-?9Ur50F;(_H*+%E{9K|hbJo!#hp3`K{ z?P7lNvj6O(ICSp_bi(nPr}~#Qo_t?Xo>ti-WSiw*>*Bnk^JS;V&XRpV_J@2h8g$@b z9Y0cbzU(LEf0}Hg_%`_uksT_#ta{{sQ97^6zAM|Tp3~&Vc+ijC)Q__4k+Q*Xl+Ng8 zJo(m^{`#_;%QnkDS$>zwUM>4$*_&j~n3z{SL3WEv!k*;qSLOc+`F&D$b=g_6_sNDT zjpDX#;D4fc>O=Qk@$0M3M)jWD&3N+tSvqrNAMaxReN^9mvaPb0$zCD*XW75VJ}MiI z-}&N~HU6S*##8T9>HI`?hHSI?Uy=fCb%ZB~k^0J)SR(62wuCk#&{K-20lI*(;{Pz&w zRsX%^e~|1UvO{H?<-1aT*T_zjy+JnYPb0sdH}HoK>sayfP&sekA)T)J|4#l7%FdI0 zOqOwOly5K9v7hXrvfpS>-z@RJk^Qag6S50sKavf5+3&|WGgS5j*>hwsl${`Zh3qY| zq23PScaa?^+b)a#c(ucL{HUi{zOD5Iydz{s%bv;?^MVBXi$6rRU6%O3z0}BmNCW-L z#a}IZt?YHO(`9d!eL!}%EAz}lWWRh(SV`XANXNI9J@@LIe^54z+Vo@kqc=f%lVz*2 zb7ULkqb~Zhr~J_k>-&Q0>#9F``%CvA*+XSdZIW+-@=cb#RrU_qu)hDb|0Bw~Pu*N+_SPTbW@M~XDk1?vX^zSp0(xo8Cm-Ay4u@mewfE_yf^MXNf;Y z_Cnc74g8-Jzd-g`*%xGAk$p?H_qF*9kB~iC_KB(C%;)Xhb$pQQBU5sICHWsJJHA2u zzTJ!`-+bkLPWE-#X8Ea`{!UXIx_?&PjrxD6>R;A)^4+YwGh}}w+bsXDl)qFh)&F}{ zcA@M?vOT4@qU<`d8^~@Z`+3=cvdr5gjYBE;@17ukvwZ!eyR7;CsC<8u{ip1|WSiB? zIIW~{`Go9RvO)Js8;Rdkc8KiI2L8K>-%EC1+13XB=ZLS$GVY@_PB&}Z?`|;u7bxx$ z*-N{rNB#qp|0}Xbbg`b<%Kv9s`oTJj0kM*kxl z=#LeDzwC4PHF!Rmdq!U2$~vCOHhLaftmALXejwXpTCTH#?9Q?W$PSSW$D`$A`v2+C zT;XrBkIKF*JMFRj_&nKnWLJ1R%$&DFy#?LWBmd3HJ41GM7we%P@2ieZ#i9F3pcD4$ z4aF^MJo!#np0i{xl5LisynD<4a9MPj7j&4H4I0c(FU9Y&ob)p3d`@i?Ui@7?B8T3KM^YD z?Jw&1mt+r=JzRDJ#T_U+TK2Rq>a}%KkNle}-)CgMAls}S`f;r4cs=OX*8`n!l)fha zWsN7_+tPVoc17iFmY=-0DvtR?mw7>ld1*A?CrIbU<)k-WI#q5d|j54{P} zxvYtPt8}}nPkjrdOFd^v=linf%7*KKx+W=}@&C$l@;_47-*3o{l08oL+p<594eP6l zzh3sIvKRa$_nad8hv{Kt-fk3sh~f^oKKHv=cJCYV_Vu#!Ww(<4p|YpQ-YMHC|3=EQ zqb&L-Nw-=2ri$B2cAIYMk^dm&KSXwD7we%P`>PK6!Fa8u@nF2dS=mEz%NkF<(^T&n zvKPrV%Rf%}SwCwkj&WgL&r?6b`p@iUJoz?M-c4k;m2H-PzVg2#`-0Xjx;F;vGOYhO z#l0f?dN=jR|GMh| zm1Q46mvw|rSpQbtj3?h^(z!}@x@@!jE8mz`w3_T1vTMt(FFQm#(#r<0L-frrVeS^4f?a4;&zeUy}NqKyQ}OTvIljs9{O>Z>YyJNDSnjt(P%vlQrxn}lW&yr9VdHA z7xRBt`Nzvr_iV+#Ap3!AxIR0(8Be}TrGKUDk7b+XpP>9#$Z}q=u2@IRLsu z71f)`ZYbL<{~1~z=gM9zJ4yCOvX{$VBRf_0df6LgZ=wD3yr*+y&z%|eJa7N6^8Z40 zgjt^v|DNpgs&9=Mx#t0@b4Y`FpI6*#vWvQ_r~LnxeM9ym*=F_ZA-_XqzodSQmZcw~ z8uaH&iaSvD;O^=v@0Vo<$sWwG4SIbV7ohEy|>`k(_$v*LmyeIF--g;-)v%I~6j&CUY*e`Rw&uzKgMsd40 zi0`AgOm>ZK>XH8$)$zRSe`K50LqE1v9p6?zs}EXq zW+?A3W$%$~mY?$loq6i_t+(fuzAL-I9eI0(Y&b9EIavK|bpCB|Yp%1CY%l5WAUjO) zlN!wTw%v>;-zSvslk~5P`Oj1SD`k&X+|{z-c!l#lv77Pa`>yhxAUnQ``KkM-s)KPy z_s31faTYdraOSG{}54w7w_|M$wjP?q(|ys~c43CDk4cjI+_JSzL7?8~yv@_(fK z2k89dd|};(^{yyW`36XT z2iZMjo8_nODXQak#WmWmg7Qn3DQ;Qg$@gpJy;t^6vL&5g?3ZDF#`zfekCq)zd=M~O z*N+Eexo&b@-d*{a_aMCVn{LLFZ*Q&t{bkFt&GJ(>_ix;{a9+O@>}z5De^>p>8c)6( zRPRq^XUR6p|A5B#ud)xzJ|??B_Nv)=C^^y5j@aq8W9#ka|RB)dw3{ye0(WsN7_S;}*c?1V1n zC+{hmxA$bfsCfGEy4v)Eal1kN>ZSSKU$)WwzpDQJSGJjcIRA^g8Be}nsXzC~{;@&- z!u-^|n#SpOLH~c)r2i`@Zdv2W_n`95lYL6IS$^^!+hD$#Px3II=!WC5mUKFnlirrn zIY73j=7sf0eRrt8&FVvMXX)+PME_^f?W#WYt)e=qXOPxGt87^|96##%qUxf5H>r;9 z`d=hn_GiYCeS`CweJad%NjKxkw>RS>d#G%){8N6DSM+1qX|mI0!+Ph5e@ONpvX3_K z?=dG==q>jpU82`let~}sobtF`xV(^Wp9+dPxfiqw`9F?j_#KJhqB9C z|3T?4l5JG)?Om)Fz4_96v5Edn>2_70`VI~1`Ip)+$i6Hajwf|Jr@EMrTb7eQ>tLkT z1M6Tj>2D)TKR)wxUg6%dhs%zU4eQUOd+7g2e-r5*DBGys9lBUAdOJ&RU=#iR((S4~ z_3fl_W&B1;=WDXxkPXL^x^`1t%*W@JlRxWVmh@Q%pHaQ%%d!p|?F*|msArUPfA&Ap zKSjDzWgFEyPyJvYYg8|K6Qp-}6a7C+x2yWpH#w;11GPVt?a^R7scW+8Vm=;FT)2Kd zu0QLbxAa&CtYfYd^n-C^U55KaSkD~Q{hsXd)_+jCugNy5cRh`7vwG2+FTEF==&vc= zuIf|YNg8kJIZ!$W$qteY$CJ9AQ(eqQ-{s^#@SZ&5KC%bOw#kO|Jfyr+=I2Ld$i5)^ zAKC2}l#>5FrTEXwkNDrH9R}h5zT%qsuPU8Pc5T`9WJ|$+jr=xk;J>5zlVz#<1+|;? ze?R#h*ChTU9bZ-B*l0Y_8!7*zWgF?gr{i7Kr+o>cmz^v7v}~h%>pzo^$iA`% z%RVFfj_k^%I=Yb}AZ%MbSdb6bWn4sr z_5<`^)A)q?|585I3Hm3hZpNvZ{+urAhvRpJ;)oCH3H|Y-KaJ|WL-mL8_#dL9S$}sB1IDQ^z0G?yi6D=W~TEUdZjvvWL7FD(7wdcU2tz2Py7G*+0sL zDjkYDL6*2f8~EQZzdkxXRQ6)o_hlQ^`!B_RAloSZlj`rMWt-_Ol-}E2)bAzTm1Vn{ zk9xnUep27(q_eH;cCz7kQ|EtFCv~j2octeFT~El)mwiz-tf!G5^BDR+cu&sEm3>t9 z3EBCwFUgkf&HXp|ZEpL^{`S65Id5+y|6^poEjvb*`0b_hy6i^MYm@!1?D4V{*{QOP z@^AA0a{f;T`J45xS%3DE-jTA6^uF1}@j(vPrS^v;&viHi) zm1SJR^QKvS)H6YKObhA@^Uv&J{v8_3N0{&CCi(8{W#vgl20(Estej-4fYj_idE zu5S;DpDX(}*?-7BDm!2HIoUxkw6-o z??tsky>(yCncZY($=)v;`fnQkJa(BWiS4i z{^vIEZ=^f9fj|6Dbo}gB^B&HWeO2~d*|7gtD{fii$#OS?g zu=2c3{A23JcGCG`pm(3zp$c(NDgHUx7i7`dQ}O%B9w>|M-x}z@BAt(9|0zGlC9J3A zm7Mv6?5AYclnwnG`EAg^e`E2-$_`dNhc~Ey2l?$RyQl1zWW#zI`5oB6|GVOUEjvPW zupUDF@5}F8*^6Z_kq!MD`CZY#{~qxx1mi+ooJWn;omhT}QpK(B^QQcpc-s!R%FA95- zx6wOR{rZmV39>&|eYeW~O7{1%=wH%cyc+3Nq>t{M(hIBnf&4C#CC^VAaVHe>&R{_yQysG-^g#P2L1<&|Do)BS?Xe(8qNQ) z@;^fs|JOCX|825fMUZ4tM~1<(GNR zMz8zU^V-Fq)Aqt+ukI_$rI%)^&+W#K>OG7K){xIXEpQ}za;OUM_@Vl z7_0_s!#MZ@+yzgU0eAp;wSlQiodey!g@TEdX5=-(G8RP)Rzk? z`v}oZKrj8&F!cRde-Ea>Yocckw;A*J5Zx3w4Sp~2sz6!)nfp88VR#fu9V$FR;#Z>k z0d9bP^=l3N6P&|(us(bmHio0&1h^CG{B2l&8McSr485$s!+kIRH_`dki{BT-&4gdV z_0a04EazYWJpGsJxZDND3Kt#Q!qG4Z>iIm0&x>#nOf>xKrjq{{5C0}1*8d^CmjBcE z`t_IjUS`fR&(H8lgj1lNugvp3>XP}@PbK|Id?Tr^A#9}1MGMYHH~1#h=j0-FMP1UJ zxa&jY%cT6D4b$%ezSj-^8u&j6L(M1scA-z{_qyx{eP=NGmpcEZPN}Olb?K=E)#qWZ z`C)0O_cfmNm&vR5bt3DRVNUv!_ki@R>y>lU6aP+z|3_i^w-tZrmG52hy$?gpFY~y8 zPdet3LCt56oCh@^uXrVokUl%mr}Qy|{Nd_H=_EYLyPn}Z7Z}{nX1=Yv!9%%q`Uv`d640w2>Ek8pu=*Hm^wXTUP~#3?h!&Ke>YT>4_R;Yv z=+425@GAVj^nCALgx6v0I;U(3({Iv|?z%YlMPGA+Tkj7~!mCibln*mr@;!xrL)Zd( z<-hMISJAEO9h+@*JO_2XqAy9@2z2Y=PLKE^#Dy9!`93Aj1USuSe#sk49n!D(>OOS; z<%tV5Uh=h}-nOta^vW-JpP-J0un*Mr9%KCkJPpqq`jVW3UQo_~b^ad>sDB)NJ=g#~ z554kzf$kD4&fH|Ky8k)o7QrO}<5!~p32uT1p;!K#yf<>g2Vo2>1dj{CpUmSrb4hLgRrsEPR=pqktXKS! z@jK?>KNMfT{!-t2%v0uf1)pm$!kDMjb(p&3{0x*hbpV3ueYT9cr4Q?UC3Wfg+u=L+AM)>w?<8o|n~r(O`_-yf{1WgR>*0Tu z=h&~m)VGegNX1wGZivI_2EcD91i2UoI)G6m!KR3GmH6K38 zTG)Og94fjpVv zozN?PR(?n0puDFiu&=t_y8`M9pf3s^f{#M4d}I0Fc_zS_aMj<==lB&%bw2{{4Hg2VI=}``c2umVf_I$`N;8{{1O&$K3Uoa0Qfq z{yF6jcVGVby!b!eb%8UEQBeN*h^Vt}UH*RJsPpJ9{Z|gY?5-1__5NwNBHjNMHigf_ zme9HUpa0vH^}TkI<~^|s9)O47QFsyl4X?rfliB@$DFO8lTy=5L@IhD{#=yvH zPIo`70(Jg4^i$y+6|eO(nafhR8)jMQ=C1V%1M0=^AaO_FDR>Q9`SMf8)37xhVboWQ z^-4bVr330Ee|zFygKxlr(5f$yeft)E4}UQBGl}&*@K<;k9)*RjyPb-L#h~85s;oZ_ zpMY<`A@C&B@h>a=M6OrE1JH_pEzEeyHw~Xza1r#%pZSLCC@YMFMPV$g4t4)ld_JG? zk|zdzDOknG*N*jfVFH})q3_B4{!rp|KP$L@2L1&v!iWg>9(V)34?lv_VES}7e_!O{ zem)olyF-be&-Dsu`9+c^4~&NKa0vVnCc)coxp{r}vt9?r!PgCaQPv-URbh2Q{{ib) z;8mC|y{jh@?#*!X`l48G1ry=1`vx%dfJbm-SHd1+6cE zI>x|p@Cv*NGh}pg$qXZ*?sp0LWpE4p6Q;m((916mdGf*g;Qg=?d>iU|w7v$qPKG{_ z^=WWATnN90DNyH&$>io#7d{0WL9K7adI#7M_JBR%mv9OE7HYpOtZ#!mVaCj^uDq}h z)bW2QeMxlBz|J1=*TRgKeC5eg3D)qLe=NFjFcB_>NpLIF{af*~e8x+j73f#O%|^aU ztmnGT?N1b}0Cjz$&&2(lP~x>dj{E)LKsXpCz>Ha3{`{~YEDuLQ?LUS1S#Ul~ui|65 zj`Q%F#Qj-tE_@`bt1lL=hCjefa5Fptb-lM_b3PBk82BvI`b@0nh6UjLhQ1r?pTI=; zqoMD~`an1wjxhB5SZ|u$_3<2R0lUDdk?y|k=hE$Ny+RJhUN8Y_eMC;D%K$UOJ75$n z3?G0GLBD?4485#}nlEU5t*GM_*b#1k8{u}i3noL|?-15MgcITSa0Ofqz5I@%I{{C@ zvoPx&Zoi&_x*o01g|3RB@4|Xd*b5GTgWw9N^DSEG>RAkz!fP=5DtA8``i);f{A#!c z>Ude-#Qh|=)6h4~mjchj%kV19kk{3p72W~8=Hb^ro#7|ze)C)U9ESfV^rz=LpY=S%MMIhQ zF6J)#*_VCQ^YHR75T?J>Gn;zm!{t8f`-wjN?vw8C&_5in^I7LW_DSny-zqZaSMPD> zcsyLszU?vgFNU~K<0W4Y^7Vp)edd?E4X7hCaTTDPyAO@}s}UD!yyS}{UoKe4XZ{xC ze;xLL??Am@-BL*(Z}?kv3^DYw{t5SG?y|2FnEL`_{t3i|8ZY@`nRgBN4D`w`d1q3G zytiau<=lvm-j7Mdg&HsUl6fB;hUcJH{&nO(0#Czp@DjWNb^X7w{!hj0e17w!r~fQ4 zCk)ju!ibl3zxgcv?S{YQdzYb?^`hLr$~i8>^D~g|EbIH|KH@@+mwXw>ml@{qnP2i& zppK2yFTTg|`5Wr}EJ<9b@se*ld3V91&?~>>mG4LS9TZ>r9TXp3e=PNf8ZY^#Q15iO z7<%QG?`!M3Sl26cHm2@)DBn$5Z~b{d@@jo6{#^4Sd9G=E{TTi ze{|P6pA~-zABnGw&vdv6`t{p{pVsGG?dpn!lBb5@-xOU-*a5x?wZGPP^UzP={%Kf` zIzEI~p*7Fd#2xa8&%=H^488nz;J4qWe-?c2fPV8yzt7UA)b|KJ6<}qk=Ph;ap-!pe z_EggEp|1V#H~0tC^;kODN3CDX@5PFH-MQQauiSU@=Vz;-FOPl%{M?A&PkbfvJOw5H z8Lor+9mlsR@y%g890+y)5_gIC`_V~#Qcn?|{b|2qVfsn_%lKS_*?iWc`;s}xy!AXp ze>ZtPg43ba%l^sS+o0=U=w+@oxG(2T`qci`Ik3)WEOY4xxcj0%RPyf33J`MfmlYU2&N9ubWpI)#J)bo}) z?;&35sGmyud+@mr-VYx%{4JgAqpm+s0e9}Bq8uy0<^^y5{FFBIV~9HoZ!zMl5I+vi zQGN}H59(JJpCxc9Oom6G?qA}Xa(@7n`lOygKKs*t?}h0n`JW^I3-DE+_2|B24zk~R z9-{9}-DhBC@@c*7pUiy~`t?xjWv)}WFXv7A)Ozb2Sm!g5IuAfOhn9W?x~)oIhV%P4 z^oswH_=4z*80TN|`PKhq)F*k0k;iYnGLLM;Nq=>?t_SNwy&vE3-uWJGhgadPKe_it zHTVR46ZVDgzy#QGy^DJhwuN0`FBlJ#VQSYW^(0c4m4B&`KZQA5g4ywrdFXnzzKn-n z{Bokp4ex>4-_n&d^vzk9{gQc%GxQw;>Sv>WmiaYWx9FF{ zRd5a54)y#bpB1n5mQM0${Xz2j?MHMG^qU@LH2Sx6RSkV+*0aH4FsQzi;h%1Ud(QL1 zeDEPy62`(tun&xfAHi{OA=LBL`HG_R%J(X|UhtpJUx7T*uUGz|=!5oOhBzzVyWIEd zFZH%i^-SV=GW-JS{n7iO=N+zI`jqn|eaZRJ{_XhP>kNCq-mo7W0Efan54dxk4>o{L z!w=yIc(jPqUxE7`a@V?^iTF=~%i$`x7fvhe;wu$(d=~bGZKK`#yD$g&UWWt2%zuPB zPQnzJ?tYgyCk(Z}Q2h&%w<0V-|9T!Dv99YY9%j7cD~JE1uqKrKu=2l5{ob2T>aGKC7;$xs`YVSSFZnXzpB3H(Wo}mf*UA3@ zY)9N!cod$8dj9cY#!J2~`1gSQpjZBH$p153Y{aE2=FX9>|A#Q+CEs%Lu7;bT%+1Pw zjr_U!eTkyZI5-i`HtNqzT&VGqFB<>iusrn2Uyc0F!Olk9H>~UVKN)7cvBmGrv~ zZh=Rj*2{X(@3)uuZhJ|6M`{0ad1z5iyJ_vRFmd@+@ z_BZ@=y{Y9t#;CV8>-AuBDBs^Yzt;Em(2HLibT7j$Q2SfD*A4wN*7f|Fv)|fZ^z(>Y z2){S{E!`?Zzn*o!^>m@mp0GEJhws1*Q2zWQe{Rv=<+@*qUm0S20&xpq1mA(VVHEUR zkN73xH(mK>4%1)iDTa^C=T*MrI>D|`&r9l>qWaB%U$}bt9g_E;{5jJ4^X$F6uNp!x zeGIy4O23fnRnW>O@nz9Xf>WXHKd8O}KDs{1GlTnn>y>#7CrHewubiQw?Yq?S1TGlthz3>RM=5vTS z>HW6+4&tZvlIKtEpNHuUe@mAMz3lg+T`b$rT3m**P14%2ON>v>^*7zKC1qpn){!^NpQZzsfL#_hn4V0xDIZF1xww$pK#;FHyZz9urz!Gz7AFS5rbKu z24}%}@JqNHu7+FSHnbP{$85;>C9i_cz1chQ3r8w-04tMfe!30mnl<&v4_#cQXD{ z;T$+0ra+zlma?w?`(Y7S43>b8!YZ&XtPh`t+CL-fcffn#eTF`@>gbDqe>m_T%BTCa z@(v;Y`!K<%$I^{A^ix>>8h#72K63N-vFK-`n`^{pG~&hg4(?Zh)nOeN2lafq^1Bod z2f_D@->VeXb8T_`w1NwgZrB(UPU4pyzalW! z@IRhP{^dRVFOnx{{Uz|V{LkX+*I(xQ3GTnP)NTlKGvY4!s{i^{w%p z56{5!P|n45>c4}$_dtD4#?Z$Kqn~&1ou>T%!ar2MkMWye_#ejqBn&m5)E7yA((eSW z6X6u2f2s3R>Xf>UQJ3D&p!&u5eh0Tgy{}Q^yOn*^`&yOtPv8P5?*Zvs*DL2H5B|3s z{-wh7&nW)TD_>#q6^Ehbmw8OYXA+zOWj=2j`|lO6=P7+=p-<@}ntb8vAHg>sTKg`) z3p!t8;(Dt1uGH594uf)zy!_hY*U6`UU;GCJ%qRWUQS~k6`WyHi)cs4H9jH_47?4W( zy_};VzqsGyi7@95cdhFY{T1RwzlpeuFoO|)h`8hM6b#i*@=qi0EV#sHJ(4#EdaDm> z9vO)XHD2=lg3oUF8Tf!G%N7xy5hk72;XC3ZK-Ho{R^3{F?c@CmsMR*#Xg@3_JJKb~F8*0DG z=#B-{H&^;c@NWrUHS#@9TwPcnhUzE%(9dHp~St$bvLNv-(`IS{1_gB*{Jg_qh8TTzoL5-ePd|#dxAWn#!J5Y z$a6n@$Y=gu==#6`a1i_e7Omj+Ef$W4dY)c>U*fj}>UddS!TlfLJ>;ti8yNXTC-sW1 zJNn_!s{elOhZ-;Wn&8tMz68DUe~Io}xDNJt)XhI0-c#9K$H2&{?pn{&^4oy#4tNxv zfTy7LvveJ(>&j!Ujv`eYTfijf*Dqs57oQatgQZ|KsQvuL^*7>&u)Z4p0+Znh_yYZo z@#xR5-!1s*eul9=87_g#4ZWpXi+(da95DU|Loe%o{k8rVeD@muQm@uo^;>n^QpugC zJ77Vm=WWH`FzS@9osF3!Z>y z;Wen|=QmFFN5{*${NBrRFMUPu+*`l@IobD6<0W4f=5;%~7kcH7qP|?Q?)@7Lo53zH zLp66__x}>{Ltp}20mZK*KBZwfSOH2t?Vpdl_re0O5G)Fd!4hyTTmf%D?O&Vq#!8=* zM)Yw3>u-y`6MP-M1*Pv~uJydqdVJ7+hcJf(I0k+OWlpEL*7Hj1@j?5|THU=Tvcnwk zPM8PY1MhUmaRy_V9iNF(~#fb};<-vYi2J3{F@iEBNtv>qR{-(Jii9u9^d zK$+74uJydqdVJ7+?|a-muk~Onm;jf+rZsN<`!De|LyQ;y2>k0oE8hz8_|^Y}{%80L z+z-9-jia8cFtVnbLlf8vo`L#29aZt8(XD}pJ>pM?887)hBhMr_(`WwdwOqfs;Qg=& zEC%yD;dJ?66pVq(>$>}!VfClnwVs#GR}25Tus(baJ`X#=Uhww+ru?JGzYbdcFM87T z{}Z(45ww5F_b2_!yyNS+eDk2>e}H|k^1nzQGT#~aiht>V@e2aRFGIfuu7|s!SN>+` zCP1%w=<_J?Er^d}el4Nai>^KT*I-wu^)q=MB59W$SyZ~FlS71jt1nPX_S)T-_!kLDC3+unYJ@A5|Kg{|u zcoLp5^wG>Q!#+39NccX~^^1N!aiZ^K=wCw@RNs@hesCtBCHJ?81?$i zEB)yC$ohHelet*){0iN7a1Z<)YJXWj&3!NbRy=nd;6V6391dS<i>-Xq~2B3y^cDh9>4MPh!0mUb?JSO`AVHZ=PP~v)AQB!XJRf=f7_?s z{)Ae8YM%$c^~S67D)apBs%JlQ%*k^h&qsNl2mO5H;Q7$!)2sil$&+N{tM?D(TkDap zse1lH?Qa=*tbEUq$8SE_k9_Qlyr1Udvk-m_^?t~_zojmjZ-Z3QAHz3}^ZXoa3qR%k z_XX_D`*t%-M;!&A%>4=De3iqu9<==K3h4JJep1h^#(X5dUwsvidT%3--+HCrcbK2d zD>w7X1Me~BXYG@IAL)IQ_mk|CyccAj`jOA;_fpP9Pv#=$Vln3FlzxY@pSpgpcH`5O-t;Z&&g zzw;e>S-!XVUXt%7`QDT7CjI>u)Nc*`+u$DP*FS>a55Ib;-^#1&Kg68m&o}ZNuKSkf zM813E9O~~Lc`o#O&ieC`&R?7JDEa@ddU?NyF17yLV%A5#`=52+(aRe<7Nky{->UaG zKIh>jcmt-#U&s563$?zW{aATqKT`XANWRu;?*DYYsqDu-^&ap3yxafra2Kp%{2rCV zr#b8kKQa9Kq>_JvhyQya);}0u%YPuge*I;>N13zC^8h{v;Ss2x51HpX)Ft!lpGx|9 z_!i{+m4)S@_5Rz&?^`lF1m&-joHEYKO7iW32Vs7Xe4E1b&xn5xXysc$9>4iyK0Wx3 zm;S$@|D|xbF%PLLD|N~5%XieF&qGkXwXfFu#@g5HoHy&eAisyYUO7ii=}*qd4f+e! zuNHm{p!WY0{|hkGd{Wn@Gpi0DJrHKRyeA{cn+q0z`n{?1FJvDgnCC($eQW)<0rhLqZ-Lw3Z_q2>3i^1UEx#}D zbNB_E0q4WtI`Dg=8aRnx)|cJ=gm#YW;B4ZS8}aAEjF)_4$u}O(@tMCWbw3X4!ltkb zKJiesAMrmmzCQiyer4V7eCoa8&O?3J2)2UB%(Y8;DK?e|o-q zvcfxHei%XjG6&s%T8|If?}N;x6s!QNLpfhEH$AVk9v`&d|9n?7pA|fRGN+wPR{hGNfgFnJ8P|lmoP0uT>#|P~< znYpy$&wUA;Cz+F;&nff~=;x;~{e^(_N783rSO7iZ0dN$IXKwP>5%s*R_=GUy2NAFH$+} zW`WsZPT1mAr|SaiyymWTJ$IpxhAHT8z<;~`zJT>tL|+ZohEGH3JEt+Pv>qR{-{#Dv zC5(r+aXxN`wV<3gIY$MVqjmnY|2X_7!KrX2)aNnWcz%H;a90=cs zBVoEO?tPpap6qe+_wyL^pTIeA5nK;9!R>H2)X$5o$9Mj(`P)&)GFYUmyPpK>c5~Nl z;a;O&@!v=OvoKeuoA+nw{;B$;j)MPC|KdNCe)arjFuy-x?e1|fNj-OaU|R5Q0tZcy0CvTzuC-hE?i(dZ~FI0<}T+}<}T+#o+In`=>q*^=J^-DtK<*W z?+U)+ch2ZX^83}_Q1xEKH`IEizsEVRHDPTi^P6UzXRmmD{wi>uD#KV<6KcKu?vLQU zJcn;H2dy82ZW5dhXTf=J5!CSmI0vhtoEz(V?7e{cG3Y14$#5a`%6H4_?)%_2m>m{_ zWno3A`>W6TGw=o28n%Hi!}f4IoCU8#?LXYm|HAqikN7cR#!G!);c^kK}$X*a41)6QRy8I;mH5tI;2TR{h<$A8Nehn}*LUxCnaX z&(hn?IX5f}o4x7Q^-%Nm z2{T^$dz5~vz$c(rzaz*$6E17IjG7mxw>kbM!aV^*=^jsPU3-4f)o?oj&tRUU^?i-SS>2!F$qrUpA!vP~#NCH>eckU!G<+CVfUm$Va4XdH zkHT*@oC}Xb@vBOFbyy45hLTVFpWyzV@H9LJFT%g!b=bF`>n{Orf!aSW>qV44F^%Y> z0@hy+eHB;})`Qabe6IDp(t3Q*ew#9fR`3=08k9LL=UUGzt;YxL_gChy4<3Mr;8A!S zo`Rj?-SZj`mqR_z%&gy~^a*K19~rRzBIrxNM_?r=eJ66Q=atsugZ5jSImE#x@C7Jy zn#Z-CS6Yt`+V3gmkgvac{$gM&I0QxyaQF4RBtCbD@#3FEd_MA6`4Z6i)qjG15}XR> zLa%%ssb?chhDG0DUT`JU^I5FoUq<&aT;vhIJj{5>_ZoS+!Z&^9--qrnJPR+tzu_P6 zx_SHw&%%g-ZhiO=#|bdoFn6uzrSsi|&pq%y_#i9}tH9bY8UDY{{}Oq}dgSl>p6h=k zwB`}Cf9dyo<}UM&8|w1)gOdNWNB%POA@l8xulQdL7~el&{Df>qS=){bR5i)cQAh9_0C$$2?_Uw0=N9z4$H0cPU&0fAh#E=UAR6 zIX7}{b$wenFMjoTc@N}=_rZd&1l$IX!8hK&`TL_O_d6(kL>kez3RwS}=m)@|a5$8{ zBaQykdVJ7+$1|5Ha28wuWls5xd8PIEp#835F7o`zTw<9|duTn6>%)wfe1*vq4NLjV z|0%k!;5Tq7OoCHBaPO1pa1LAn^L=>p_stFBGomX13&EoBA*kP%Sy;~r^TPa4;$pbg z@v>f?`&Ho>_ygPwb-d`Lf6<*qe>;6!{ZB*}YP{szfzKXz$Y=hjWVbKHUp|VW72jRrRX|YvC-{5@6X7&C3$BAIUBq7255gnxxS`KMpSj^Zu$<9(Z^MI4{=3|`eePNPyZ;M_hPUSHi7u7d!~1z69z_8R6n`81?G>lCKYWwVzl065pQqaP=}bnTOQncOG8- zf6ko0fXm@pxB+g3lK*bzo!b8K%3i{2rG@xGkvGVHuo5LKu<|O+ib^G0~aPvj6 zFNI+=><+cRr7w>DQCJ1mflop0SJTjSGV}?okA!33ctfAUy1b99=iGWf>G&kx4|0xm zKjJSsd5>8BqA#T0J6`%xysxIic~IA5>HOwfkFQ^SG5V+p>%y*3*C+ZC+^+~9gVmt; z)#v(YsQo0L*1c-zhp;{j4u_)*eP@0bdcc10rH|e3Mm)TGyt~%*O+)_;O#H;@=D~lv zeqO-(H>2MH_rar3`d()ApVs4p_M5_7qDHxM5i3;ZD`u>_zXZxTk~yAbp7(z0bf3d5 zu*f*KUIxAj`@nthGPKUK)O#m&-UFrnsa&TY?ea-|zfxa0Ri8fp*O`a-AHwenl=!yz zd=Sv@RG5B}zY2M)!>4@KBYnx-I#W+P)bpsx9GgJd|FxWhf4lyvfb}P<^DXB_&UY;5 zQ=i|Jtm}DX=iEiYJTM>BdP{e|p_lb?+?VIcs^?*Je)Zz_F8vLGBjF-wR)bS<5jF)^n$@eS#-Dm#DG46M!6}*k_Fzfd#UqF2{ z`WRRiJ`TO|O+uFf<@Z(M^gL$=)PIA1CHxU?hhF)fWdG!Q*6X`L*V`n_c*!@D{hkZI zf%>~e=kLJ#LVg$Z?}FBM3#jjhelQ#cKZRcT%5okze&)_;G8{U^UF-T+wPRJ;Pis!-$FQ{gnmEcSREKe?70X9v`&dJj|s4ECOSo%;|tJue2T?wBJ_D zWj?IV_huvG`?Os^{p;x8hW+7(&?}$R6_e=B{VDcM{@nID@7Iw~zLUjQKM%{un*_Dr zzg@p3VExJHkHORMGJIFfPxqhJPcmpo*m{(el587`w&Q&g$ z4?Y0pe97GOc}eT>LHm{GQ2uu=`E!PRXUcb~%uSw4`E#$H-;>O_1=R8Xc73CO^>;%5 z27DV1hF+wPR9mQP6!^vPq847e1^|1K^6JGh>g6~8#l z_&LPue6sG>e=L7)9}g$NFW^i#2QGlur@B91M}Fb>2h{a^jeZ?WKsPas=$8eoe>eJr z@EAM`rSAns|7krwXunsO%MBRCxtamz!r#?-lXJ9^Ia=pW`&YuJ8mtNHLVbS2jhB83 z;~x!6L+S5(Bme)@_~J&tvhH_2Pvg@Hwt;P-%=Krk_5Rl3{OI$PWIUe@1L~WhZv)%H zu29aemG2C?b1=g+_rA>x^T6V;47_88)5XBaGu^fBU;FhYekJ@7cA4%k{%!OlU?Q9c zzlYlYC)RhuU*QqxH~+inhrw|3pTs8xo`+eDd06?U6DRYOe#P$+_x1kFV%?gbo|mpy z`^o<3I%U6P-r}R+vRW#{0VM?+u?7p>m1k5d+;Op z8B90V-M}oGv4L02YUpp^o<(H_(WGpY^qH zH#`ha!1z{04KreP{;d?TS9!O`@eCX+pnnkH{a(I%<1KY z?!I+ito&ba4mZPJU^2W8D;Vdq73=eeR*Ft<-M7Q-_fGR?`d`7LXDSv(c~)*EBVYXd0SG4)SWA3pHNyC6RYKJOsV+OWwiMA#)dBIXAKo z`uXciT&VGqZ!GnWhqItpe#twDI%MwpyHLItbp0cU3pHNyWoEy#!F*7@ORfC!o%AE$ zOZoV2s0W)u`Q6s_e@9%X@sh6)d5Xf)KJ!an`QDd4#aH*C>;HrLi}AY{H2wck7`BFbetzR*e{}qtyjOF6?Y^U9;Ms57wbl&-{}2ck0N+_w*BRAzTIZ z`PxTZsPU37KmJj$B=pKJdFA_F<}SW6_p`?QPf>rU@sjT(^G<;`pjUp$n}O$F{yZe# zxq99)-@5O;@~|eX1Dn9HOPy{!Tnbmg4R9+g^1ai?!o17fb*TAA;9Gi`^XUac^?RPa zUWDD?>+o&Z4-SUI;6ykXE`++Ce=5%oBi}yO^D?hu@DUgbTfjE(RoDf70Chip{hJu^ zGg$XJKSjU$ujl6j&e3vs29Dw!%!7O2C779WXPrMeuluM=&T9kw8^af%o`+Yw*8fhP zv+y#EpkJ-GbU6&YtjqlLyu9Xd55A$sOTM+tYXjT`z4BXg?`6!tGxZLJaxU&?|K&X) z=S0u<%`oF7-(~8%1~dB1FLlfNQlE2uj&=RBs6Pb;jsKpwUqXyu7iPTFJDRzD0>6M> z{Y&5HspAsNLA;)qrIYz<{X@JzO2YE63ak#lf@@*)iktu5J;D9@uo-Lvb^cMTPlDoq zg6n+bvGR=%GhXs-!Dk!X>ob4C71xo}7el?Vig8>EU*ft8d>1CbEGyl7BjE^`2%}fI z`!R4NOoZ)!boaZ!Z7>RwQ%7EcfA7svC&nPZJr@M}aal72L@bqqXodUP+ao5Q(>t1&q3E$u6t`lI%1MWHo-jVFC<-eaK z|2?L-gKmA}Z;nY&{(im${=PH$``3gGjySzO-*2!!7=8@b8v4Eg_2M^yxXZ zwXS!||1P;5><-_8x}OECFM+G!217rS^Sl)9R_9y$FAS&`zk|dbfv4a#D9@A5m!Ie9 zY1kUd^QQI1xL?VqzH~sn5q$j>&D)~j?QyjL0y1sp^d(|g?QRs_8%YPU5{rXFN?NvQlnOAlgY0OXRDnz`@ ze>>Ou`~=mPCGS$W6^`1go!xaM?pKF(U^AGXxH_;4eA}mA!!Z3Me_`@P!!ppT9_gba zb(~gxy{LTjl-i&VHD2;v#ODgkNM5h}lJ`sEWIx4M_CG0`+;2x<(Q&^M5jx^gVxf-*q$LJoqKl z^$cV^0giD--Y$=uqS*A_JRGN&NrX+FX2-7qoLo<`mb;=Og8i>te=Ay;T3ol z-hjHkm}73g%D_snCe->2e>i;>m>u2?^TPsA$8TqS58Ma;fG6Q;sN>5Vcllp~ePQVn zZe8n}a=$rz5w?R`zY3q<;A1D9ZzrhrE&p`)B)LLd>2kJ^lvHsNUq1i zad0Bk^(|(7DO?3}oObm^!Ld-s%l$&!uLP?YdP~EoC2r8S#SZ={j6Yp zHCzkV!_6=mh8n-!h(E{r6?jXE+lPl?1y~7IhE-u5SRXcpt)Z?riS^^~47>>chBsiu z8CTD(FcRJkwg0QE_kca&a6`X`_5JWKc+Jq~I_v7m3-iIEFd9~Xy1vI*e*)HpjbRh` z3e@pkSnmOQ!9MV9I2!8sMAoOk>2Nlj1Al}%K8f}1a2MPQ_rbrQj&F0$&958m0pEpM zA9dd83&Utw96k(dLLDE+dL#HOd=9<l?m$nmhMhNAH{lM_#mul=s#k82TXxU7hGN2;V!rrMqYCFb-harzX%V% z`4^pE5=?>GU+NRTWBB@wkHEJC>KyLjPv#p>m%VrI2|s5XW<3- zH@psS`TOSQ+0w^dzPbKk)*pctU?oFu>0;484r>|lU09z1XTc@~3SNYI ze?%ww#9!jHK8m@Pg|VwxCE{>h?RIDB?nmmwY9dS84bd^x7ZE+mSltJjh)1 zzUcE&in!Jx##bS(5quAR2fgx3d~Ng%p!S>3`eNwUU+Nh}oYeC-*H_^UsOKYf)#JX@ z@ntIMJEnKfZD-g8c89v2MAoOlZ{bQqpTzo3_&fa5&__J!>bVoi7uOZ-tTYK6pPY3cdWq z=QhJf=Wm4WIoJ%gf?7Y2^7+j0 zua1wwH>kcWan)fR_*_80rRZh+C(92(Z>!R1by8g@!UBB626s!O% z!v?SmOn`~-YxoUJhB{wr=~o;6H&{>qwCgJqECqEv*;tQ+cf#TU^@R<63j1&tUVv9& zOQIcxztz}Mj0 zP{)tG>{cegnQ+zLZhaRVdPPUNYb$;kJ`(>YKDF>^?bGioe8f*zaf17&;RSdVYQ3e) zMtxfU0PE4PBrI*{E#0Grz9s9Epfx9J{#}S0rQ&1MoW0_Q5I@}TD~#Vm(67Jra}i(J z_gC;~4_}3P{!-U4;-!wFsic3C=V}sM0Z+lRFhfrF{AGq`bKm@V?8^E)xD;A?$+v+# zyHtKXkIhP_>zjXvtLv#d9Usf(msHlMn2KU5~uZ|lX^ub^=Z8|w_)UyIdvtU zob&#iS9$Jaj$Zx)@D=}d_=f5)^)ylS+{OI!!hFVlNF5`o>tpx{l)8FTXCK%P>V78@ z_c@#m=RrA#w-TQN-eLI3oVU^6HT9m*??GLU#4igm{zKyCs`!#Tzh3zz{&V7I7=DHD zD+c}g%RDlvdcNR#I-CXde59_a)FpKkNhN*Vr`_*W9Bc}Y!-!|x{c2FxXT`s&;`929 zf04NV#H)k@xSs&W!lh91SoOA`j@Mv39AeZrmh}m6CfwS{&E**UY&WvKO*E*LvQJ-8~X07FM!sZtogr7 z+!PfbtLE$#KbH83hF@9yDnY;g(oZH;PfxCU!#+^YU+Nl1T~bH+RMOAIXD2)cQw;xv zo$l|CSqhiIjc^alvCHXl!MrdU%0H*C`<+YtLii2T`Bt-@0yE>Q{X{4ARrJW8?JoD6 zmx8gdKGgoA&&T~j@IgbLmvyZ#V(7I_e5F2JkEJhR_`lA2FW3(bg73jrdE8vOz-;&2 z{CzkQ{Wv%c&Vpx%Z=Ki0?|}Q@4fy2U+=stI-LK9UN4)swBQ8|GreXR?{zBAI6qbWK zpw*wAUuo)j1Xh5RVLd2w(DQnT`+j}A;vZLewZ0ekWuH%RE&HtX2?6!iIh)UUOM;C! zch)(u&a?PW#^+BMfnOGw9qN80PVb}CXZhTL-`%jN;cw}R8+uurRqz>8NzQjwMwZFBA3pHNyH6mYA*xqM;d7maxhr9>n zInnbUjLxtA0p8OO!eX!lEC(yXIQR@~0(Zk>@G{i(g`2NCzP$|pKCBObgWxbjFY6z1 ze>D8m(93!v_ou)ahJFs~U&6)kJ42r?pZi_A7nXr9LOsuntmpBmzdfK{@>e3RDy$6~ zL#w`gja@&{usD1I)`MMPJe&q~zYAFZ3T}jtG;w)q!)KbhYaM?~=~tjnhS9`X@qZD2 z4Q3!N6V&-c7ol|741IIf6JaFvNL|{$9l9>CCwvoXz393tT|YxVi}ks1AzWXw@An||AHY#?2AmBSLcO0lPINyS`h%>WfM;Pw>MTl~R=v5< z<%Rj-gHYGk0lx}`mACiB9QUB-o`qfWIKN~KB zi{V=6*H3go_e18Y=W&+&mY?jW75^M_Y6V|{mi}JOeH1JPV_NfahR+<)`bF`|Z$mhTWjnzr}iA zI1s*P=%t^6+%F1C8+z$`C-+alGw?jT40U}HcYymxpyi|E|EK@=-!E|^^wXAAfW z>;%sgyZQ4Z@#WDiKwHB#^3~(M*Z!?Umju(XPtj2JP1hs)-BK4AFEy7adJ-DQ}U z^Jw)KgD%u~$+r!koiN#Fe%X&k=$pefP|wHG$$n~mR7tn*{bC#k!Qt>@cz5ZWKi?AH z65Z}nPUoe6oV>N+E3gyn3w6DI<7OD~^I1Ou|Ay(PKQk-_OTb59Mc54L`uzGAGU9c< z`X2eZbKh(K{y=vLKFB`BLD@ImkL>>>;=X`i!SCQ|7&Kn%E#F@Ze_5CQ#(VUWjE`Tv z_)WogI$QuZdgPONXF!(~-T`(0mQMCd>!$F{IDd;`WP zpTXsv-twzT+z#S$dgu#LM>Ko_)`u;i&gVC7s1cvQ`UbcM9)!nW7W%mz=7x8}N1?9I zuYY=yt)|)c)#yv-VrgM}K?g5J3Q+6Y zm3Q~oR&d-5cf$Qp`|iYFd~;TE@s|HIe6~=Bmwp&^CBS*`Yq$pLe17B381a`_FGIc6 zVI3F;yTLc$+ps_U9P0Y~`gb(qb-s^1@-5}Q*Zw}D&dnmVzp`(-A2}a?kmoE+M|@_O z0|t%Pdds(<;V+1g=?$0>q}7UXfO z+HW}@Ka+O{JOWR`b5PI6D_-j@-&?6)>t$W~m2+tI6N!&sz4(ped{2ba;TmY=llhk= zZzWjW=*QB@{^|awS9i~83LN;jyPgiUJ}K7SFNwY!tO{#E?fZoC9Z=)u?+5YEfln25 zUix#?bqVIF=KSx2C7|xdZ`^Z6d@I(+!I^LYTmtvN{qP9<17@LLU7uh7ZTRSTo$tCw zzCzUDwZEUClXFv8?XT>cu1C&CL*kpk_OJ`=34_LKz2!U9@RxPz?>G92o$RO9ucQBD7+upnXRTnnC){-}sN-YM)$plL zKzF*9^SuCXz>MV4c_-F(dYxbVwh;dUIxqc~)UgEag!|zssPp-ayPJA+d=%@=VF%b1 z_JW_n32-W$0oTJ&{YM({I^Qyne22L2wV%(ab2NkNBq;l)`;qgI6Wv|#0azTCfkET7 z-tw(!_{+NVcLm*poWt7C>Mss`sPU37J$W+0NT2!Txqg>AhQSd~&&Sfqero+kb=-6N z1-w$%T^Fq9_z}^6^8MTYd)^JHzbSkX_J#f7yD$N+gnGVhS?}pn-zlJ8 z@{c8MJe&#_L90Hg%j!?}^FQssckceJ1Q8K_spsK0&eDbJ_y2pmo@==CNNawnU2o9& z{nL8gpS}*7Kegji+wZ@-pa1UssXfoM=9k*_2Hns9*ZNa@pJZI`zE?YJa2x}tzy(m( zcb53e@LHIDlD`}I-hlm~S3S~49{Slp+$ES}qw6m})cxE}T&VGqZyWh`!ry%6m%P!` z@e{lN3*i$3b^Qg> ztxFx&+$E2$zZ!9&#!J5I_}oI>*`e&am0$9XBz`uOeU;}}&Z&MbbU#lMKQxv6TH@0O zE`Yke@9Ed8KJn{&d$r?)F)a^zjOH z6r%1p_zJY<(So>8<0aoiX7GO_Enx^Ij8!$(EWUl&+b(6n}^RvcpH7``f~HUc-1FUzEWEx&e#pRPxA?;CnqAI|;J@LNOQv89_wH#h*k2X%iNSl+nNa(mXI<*~$r&he=`@_hm>l2+-pRVgSd?k;>T`=;= zdZw4$Io=5~zU;0i!g)~7=Q_Tj#!J2fh? zURV%53`;}Z{|~IMf$QNGLw|tvgYXDk@rtV>3Etk$UF&=?+^+y*VNIy@vR;S#Pr?SU zA$%6<_(7~oed(yns_(sk`jP0z!HIAt^vc(sdiuf}uvmLHzgqBFsQc?0X1wIfgnw3; z3wq^Wuj-aM+Zgq34XFPW{ULZ1ra-TJw{&oG%nr-Ks!-3f2kURZH(@_RpTPPja27n* z@#g3MJohibXV5h<^bxFQhLJG0p_lc$xt|{vfCb?LQ1{=K_37|;X!X+}puQ*ie()Xm zKJ?1h=~Xw^*I_T%59)q~vpybnea*#BfOFwesN+Y5887*It@(bngEEPr*CT-wVCsmk_ty@XLr#cIek%>bZok)Kdtb2VgYR^Ow4o z5-)Y!mP-0=UEEyXg#F=1P}ie%iRh*q`g^)M|6;H#tPHjP!%Fu!*Yym2!EVk!8kT|O zVFg$TR)?`YTwGJwv8TJ%_56YU9J~OpK&?O6-T7RG_rLD08^MRjQ_0A8gt(J1B}_lb zUyS@EU?rdRNFQ04({bYRzv22ygv+3wM>^s{jhB39$$J5&_nBYv=A({5#4mxe5A}@w zxP!P*<0apRR3?*QwfdoV>HzB!%NXj*ZV!x#s_kY%2Ywfk$+WVZFsJ$lqeG+^bOlDv0>Uh&}pmEW-s~)%i z49EX9EwA>D#NPt2986~aXY6l*y!QJU^uJfZ&prLWC*{_(yxQ9x{R6;EFq!>2`p2o@ zY2caQx!|+l+u%kEI-d_;eNS4bp+&F}`~>_K9P)n9>Gdw<_eW04ui&#=NacT_Tr&B- z=t%*$0k;DK=km$z>X9D?zW`LfKjCw-`j0`bEJ^u4xZjsJ`r@hj3Xm@WefodqepmHt z{hp-XDvGJwFl504J|m( zJ<}tk{tCVd{tB-5tlS>~js=ec7lDhxdNBH&lq&*fgU5mkz&fx6T-W}oKMnZhv%lP9 zzm+)r2=+yf#>4g3l^>i$UiI}uZYyv*(ADpg+utL91iZGF#^WlF{M>HJ-;Vq=;x`l2 z_Sd++;fe44l>Z)7`6rUdKaBhe@Nw{I@Kw-_pW5@4cjbL@YR8p-AG=+xkIDtqw->m+ zr~W>%a@ZtH66eH@>dDy^u?0 zuMD{b;QzG!4D4uqli5ED`R>+#Fy(yqPUU`A^{c-}JN{hH=NrLWK(~F|_Hg69w(?p} z?N3@S?LV&mxvYCN;PK!h@FegQ@GNkH6J*`q7(4_V2`&Op0bf5+S9?+H7J(IDviQfaeKS2Ez7ID@3H$cxSkU?pZzbezaHaD$I}&ztB=5MKsWwBu4Q?(cP#pA z!8$OR{Rn>NfcJUI{Q>X#f6!W%S9^a&|6||_pvKK-zZUyCzwJc(x${{ayz776T9#LP zd!m0Ia44wrsn5R7+l|bJ4}iXT-1Xm;e~$7x@4NE%P~V5ZCh(u2E3bTa*RLt8TeF-v zxcdKv-Os@9!S32i#onP{SM3L^x30a-;5P@i1zrDra>>^BSJ3DByRP(~;qf;E{y=a% zsQHI$-<2;-BCq-;BR3T+0A2k)xtK@(GI%$B<7szSzsg@tx$D3?Jo`i4a=WMx$D7Ja6RVZ6tJuQsJ?piT<+-qaV_<$ zKilD##^(~&@5{g|J^6$BbuoTueZS+g8{h8A|Ns8?^Ij*eZ-VcGubm=!eJgm>Y4SM+ z&H*dISHZWye}SKY-=8hz-S$X3S@>M=xHIH)9q7ud++oPa!1w?4Ny^;w^Ou^#c! zc)9JT@o>xkleoME{tWgwRpQkTboF($+*nWfN$_WZSAn;HcY`m1Z-PCjuj@}&^*w_g zx4g#XA>w3pv7NfwV`=v~wDYVQr!k$1q)!DRNe zz4xWP2ZINA`lC-y`->aT4Qa3b;7;IfpewKZe%wz3vpn*y+$7|Zt$#Nmr+(}Drt7W7 z&Gm2U{}TOIt)c(EeC+IXtgjY*$>OPUKKrZ1pYfvWmgY-3FT3lOTmGoEEU)$|nD48= z6TxKme`MXAL4N7xNv^+Rkn5`aHH_Q)!M}oUc*gTz){*>^9{oN)He-Hr>+6&M&ZA%T z?2Nu^K%Eyg@4T3G$+fo~@@raN?cI!?rQm~LGW%***TE<8Q^$?#?>^}5s{C-|4*^Gk zQ^92Rvd)qG@IkQ0h4Q&S==yiON4}p&esMSD&qe-X@N)2GQ2q1SYeugBc~Xy*3k3H7 z4*~N*w|;L?e(!UoTr&B7$n^(P!LF81Lw+!r0UiJz3_bw5^>O{5h}^|pls~7N@*3BT z|19xosP9^wD~R`%pthsy|1jEZ5%@UrZ+qHnHge@)Z8yuSovQPt9=B4TuR--HP56^zP#5e_Q?TqJOHd|61zPcr{}GUhs)7`g14s`U-5T2j$)V@o_ih z_oaUOgW2FX(ABT~;6CnazteVitMV%6jvtMq_B(f+yYrBaC)c09;?HlOj?ZtcA%5vPGGHCa zN0~>j1rJ~y9p_n3OS&mvgZv3#9e5s?%-(y*eF&}se*oQhZ9|;52UEdupesKe{&Mha z;;QqmD}Qu1<>w+_4bBHo1(Vr3f_69xECG)J%fW@9>u+$8tSi02O~Cy@SN;I_I5_1B zDL)r<UI5p1bv&KuMR!; zI{J1(Pr66{a`-pE@4*z}wudKvpJ9Kai^Xr%e-z~xfLb5d|F0Qnm%VE0ep z*e?3B4fWU_+!_2km@K{;zfZB}*4L*$4gHJ3%RTniR{uF`sbA}VCjIMN@G3Bwe?Mbi z`>XbE?SC3K?SF3kdeYC=w7lB8g7&!vyah~Ve|PG+0Mv0Y)H6N?B9{&h>t^{e$WH>N zf>AJ;eT|dOH|n>xqs|jL|7bgCJ8C=VJm9v+Hnhj#;JVg70KF4HpTE!3e#!h*eHrLG zB#HjV(c4x1>fa-@kNWc~dVU9cc>0U_bs&Cedpt@xH~!s~UxwaKL0uP*_xN*9H|19# z|2Ob?a3z?`-VD}5T^DuT&~dANp5yWNe9Er`lgVG&P5B#9=sjA z6I>29fo^-h4F5KmdZnzp`+%!7ITz*U0#)1JAftK3@ucab4%*Z&?@1r%*l%^y%9Z z`}=@{z(YW{{;qsFa>M=~$^S|``e5G|PmRaSB=KWKJzHw2)glc%OAIv<<;II z?41Ih1KtSw{AnaEPk}1u>kkihQ(pBwh#!xDPk}9<&z}1AEOuW2SAlMPl|R%OFDcmZ z$^VAFM=19)=*sT`zX!NKIM^ev2cQ1w=y~}@DVN&K@a{DlCzu8f z0jGeje_hqTy{G&<_+;((Eppm^Khcf@X^#T%eDE=+oqX-B{o@u#|I_Gq>+6$W;gNp} zz3RW~ul6IKe;==9d9^o~cnk+ecQHP{VgF+4=f+**tmDFs*DjQsy@urnQ*QhkmjBaQ zme>0BAYSW%n}f;fuk|j+k7L0TK{sALIgP(7KbCoD95@Ah?G~A*-Ui0-*H%qxa!L_YV9rZbsdi>w6&+F7n>$8Y{;>OQyPmPCLK9jg) zfs?^0U?CU->%ddNb3xbMy3)JCqyK669@Kvea3^qYa4a|#TnM`Uc2!@Nr@Y4XBiiRJ z#;5j|m%G`2U44I`Z#4aHZT0m-&)(}u-wtc3PwVprae4<_1tuHs8kY(9kq6EO-S+m$ zX?wZy+O7fpZZPeUY<|8MIh`-+JoDc<%yZX+w|VBjiNvD}TnHxf*PU-&d0kIR@HY;g z1fC9_2X?o-EAP{LwMW158c$shx*Crq=v~wDYHttXy*D@nOx7OS{`s{35#TJ)jgL=G z`;RNXn0e_!@N)1P&wQo)67DYpANI(*a?c=_Y(3qIxU1i~Uh4X;{obw53;#>>Z@Py5 z`|`OS>sa6C#3@-kRnBMMjsFw)sq2`|GdfSZ@-KE%UiF>K_&E)%2UmbTd;enG{08v=Zyd=PvLd=Y#Xtn}1B z1O4AOivBZ+`cVYEby8n?bluX)7DbI`g1dWEd?L+^e@*xt>+)q zSNo^xb>+W7uB-CPsNe12UEsZ-tN(p?9WTkogIoU7wJfjpE~LL+3SI}gW@dlLtD-qLl!t>5po#|Y-v zb*+Ch^bP@i{$}F0&a*y$RbMLl_DZ5Z4ZU5}ul~J3`=~!hp(hH?0^NA3U%TO#w#UBf zNd7qVJ_Ne!oa@gi-IV_`@|S^EfwzLm?CnK9G7wAy4*^~O4ug+^#o%I({Q2-NfM>8y zX&&L~zqFh3HzI!d5P=ayZGM%eggg*`~v(5bjvIM3-^27FL}&n zpesKYz5+ZBobiB^I}$7e#1itQ(Urt(|i!qxkzNI0U~(c>Mp`@xQy}RsL!0JqP}y zi}t5c-y^^%SPZ)HR(>J(H>6%}J$>y}M!7XDulD+3cPnrwP~+^ge>wIKaoSho=+;-| z-=&=P#|+|oBABdv1LalzG|KtxUG2!9?2&&8xo5%MklV{6uX2A!UgZX^Bl(xntMS?& zy&A8J`Rt3A-oFaDrC=lI#_Kvq?p{9o^!K9OHvs#A+k&qCjo|w_asxf`li{a;`QYIm z`HSIi0hfY}9(kYKM;`gV!#9JkgKv4{Rqh{-T#HA(o^jXbuQET!n*^@}uYXKF-wJN= zgnZr)bmRS;qc55KE8UcT3;7ShPr&cMWcJdi=MRr|UeCW$&(FZ`!1<4h{2AcKpj-cZ z^f#ctKjkNYs{ikN-W)w$)xQ}1H-Hm7s9&zV=6LhsTK5 zKS5uAzGyAWtG%nS(*Q2*qWu-jLn+j^6r2aT^?e%ozk@G#v;6zWe+qs9eh((IuW{D- zMg7)x)OkSl=se)gH##r4^}Ch!_!L~%`X55?+n~?icZk2vk3N4@-!tfYDT)49(c4x1 z>R-O&&(D1R75oEqy{^-)e0n$K4?%t`I3AnrWPZ9vB5r_sDm(|7x6Edv5t>u=4`g4DRWPM+*EF;MU+y z9{FBR%eYz}+z6Zq7Jw~aEBMYcQqJ{1gZt~Me0S|l#IFV56JWE)-z>-9?v_{iY3M&3 zoCPMcpZYh6<52KYPdQ(_2drgzwRbIcZvbxtHEurp>USo790bk)-TtBc1Kj@@)HwR& z%aPjzzjgs#`3sP{7`zs|0d(c7Y5&u~v%q@LmG{X#?~%U~{%-I-@aZnfKZM+0{~yUW z&XoSC?Y|&jB2o{w&<;7zid=n@{5`&n9uv%ke+*24zYr9uAn;)`<#u>M^rwO~FUsdS zaL7x1=I>1F-&=0|Nc`2mr`yQi(bT{9si=SNul_^vq~KrbQDP5Jc75nA!2aAA0GfdG^>(7!f1*5@ia2z-hoC?kWt3cP^V|xiR4_pYI0lMK;7y>$OZ{@=P>o-{c)I#eLT|lC|GDV923*=r z{bwZ6e{nbUYyH1KuljQrdhQ1A1>N{+eHT++>sP;y7vQ zI2=3x91V^IqoAvA1a`)NdEj*LaIgR@0gnL}f?xCz&6{i}xCi(@Wp5F7UHuL4PlGGL zR*(EV{5}o547?h2^&d>V?f@SIS9t0>7Jd>q1YEb`#bm_a05?$ zrciE8%d5Qx?A!$2(M9{mV*eEI7|N;M68!eH=fbrtulB02I}cn8CbO@8YyZ=JqENN@NB{0Tp}w5^eOkExk>Ji?pO58pDp>W2e7*-f zYn6Py>QlihvGWYL67<=B5BooWu70<^A0qc}@XKzNSN+G~|03`V@Mci!=h|04`@FYi z_5A~X*R;IG_Xgs63wT!-<2?w!v%x&@Xwa?i$aN%tm`A_QkJ-qVg9|+6i{RH*{#cKG zSMLePodli^p5rO6{MFp=$vD{$JOCUEy79k=a%);%?QMkqO~GxzWcJnW9r*Do<6ZT- z^>F>aiE?XNUhTb&-4^guFqwU|`zU_seDwh3{|2fZ*Z=z{x2EOQ-UZmX1iZG3_SLS= z&#vFDzfa?DSLI(q{&nyza21%$UcfrB0k|=^DYzA=>xt{HyS^-@U+Q||%HPB~wFJBy zd{fsir+`oXevf=Ud;|C}{yzsg>VqS@DPM~Gv0yED3Yg5E*0cBfvi|gDUDi0d{$(LI z1DrxV>cC9OPXOKWqbWBYoV=F$)c)bvKMFjii~eXmO7TPcmFji#4!1r9lv~sCYHu(6 z9SCNC$?Wg(p|o4-zXazxd6nz0%Fm?SDDsn8peuh7a!bIc(fe<<;Jc z*n0(huZ#B8@8$S$G38Y6VCt=LaQ(lBa%);%?Ol!C2Jj9rnf+I>@3!wE%Deu)-A(zA zkpBYw8vGs9{^YZF=Lgd7R)9LszQDZOmppQJ(DnEJwJfjpZp7Xau(6Bw)$eBfn2Miu z;CZ0t$*%u@quiR7S9>$Db2M1eMf+;^ef-ckt6sMruKz13x2EOQ-oE&o24;fE>f0e9@8{oK!FK0OjF0At{6@L16GzaIWl@G9_HkNggwi@jsN z5IhsS4}2Kx_odu-?aiiqIamc=54!To-^%^lz^z!$+}_Fa7sb+f$cf1G+g4ZZ~S zrry5#zkzg{3%~a+)oG30$%`K`P*7W{x0wy@Eg#TAOE$; zPX?!g7l5w(H}KzsKY@pQ(|P|G_^t5!gXv%`=<2@<{vL2S*aSWaz65r+yepsno%lBj z90wi`y7C8fQ(pB=rQCEd3RZwVdw27m%7fr?unBw&d<%5_)$?%G-c5C33Ng0^;d2*f&X*``K;}#^;G}Vu3N192N^Gyf>(jpfUf+- zyUGhDmx7mpSA(wnP4KsXOTgPb@=e%%8hj3X$>Y!eHu-n)^Iza9@C%Rs-IeeCqqNtC zU|+BwxI35yy6w@`^80$qpA3HncsBTFupYbwbnTD+N&FuNP6DTcYb$>Xdba#o?4*ME zU;#J>bnQJx`6s~_!GD5jlp72l4CZ+By+t|oCz<`be-XbQ1eb$NpzH6;@GHT$z!s1E z*YH1rzo^`=Vz&pl0qEN62frn_4Y;jG{$TiAa0-|Q7J!$4mx7mruKnOQ@pFB!AGig$ zHMl331`Y*>fqw#B{UhMVfH~kKa59(=y5$SuXM?3+1y~8zfNuGE_*cMxfGffG!4E;V z{D9vjK97Sf;68r{@5;~SeiN9AoKJo(awm3C{&4gafF)pQ4_Qaf2CoBe0&fFde-}{x zB=Ah|Xyjde$;!V#`Bk7RziUtNb5C#(I20TWP6p%P4PX=aJm~7*x|itR4%`VG2aX3P zfo}Od;Rk`kz)X*PA$$>74pxD+;C%3S@FDO8@I`PX*t56P!}V`4`~lzyaNG4nJ`H?# zgU-v3LH>NO9=QgOd>Z_G@Hp@Uk9?2y#qJ$oBX|#}c6|P2Ay?H!`Bwb+7W^K(w2%04 z8F)3g6ucdL5Zq?N&g1n9`bHwR8FD`PH10QmjbNXRM1Lw61>N?|ME+V&c~|~W8 zRFC{B_{e5rcPKaL`c#cQ@Zul1PU*M-;E4Y7(*mv!@e>r#q_z?IoxB_(T_1r@AM!`6^ z1a#%Mhu;(24@~#Se+|FomSSfsa68b|e=+=};AP;|9{EGI7QG|DL&2lK25>3p+Vhp4 zzJ}!|Q7+$OuMGYq@MQ38@I3G$(Dm1qy9zn2rz`(7_n!q=%KdHnOS|m^?gHk5GeOtCUhuy1u6!f%uYs$;?Y9;C`+zafEwA^pxIY0r zs+;oDJo1a+PufoWsRyqDZv`I!UH|rk-v`VGXL#h(;D>?-fQNYGUxfb{{0dyQz4+_; zb29wt;JM%h9{EQ22f*dv6Wx@5)FWTGgZMcctOkzU&#^7nDS348{84txdlmH(Oh zGg2ikhl8`gICwnh+P@qALGTIi6_5PS@I7`Bds~40L0A7SyNcXi;6N}9bmiaY`OYfv zGjP&0k(>;cf?X}&ik=_9-$1v#Pp+rOUJB>j=Te_~P@fMp@LA9QTd?c%UmvUJ*Z=fu zC40Dz@;MFE@0Dco`5^ERa28k!&IMgK8RB&CJn&{$kk6UYyuk=?G*|?>#p3Yu!3E%P z;2GfA;5p#M;N{?dKv(}>JkT2m4g%A`Vc-E^4p;-a`fh{27km(04!#U-v7VI708ay5 zeR2BHVo!ex230RCuPK~mu%=3Ij{a0pSrZ#nQc*i-R&8ln@qVSnLHKD-VfCC~Q1QYF zQ&O;|O76^yRaKW(RwR6gntN5TvO-&cpW{BImM=|elkjnilVUvMX`8I)Hqre6CKgQs;a_;qCR?b&WqEn5!rUy5&8jUinhGmQVuqKGr4_TS7P&QRR#j}C zekv=iFrLUA6FB{`tkM`07ENx;tkLJ~O)2|LRXuFxw;KeCyE|IxEp6-|^V9c#{86dp zTN(d~O-O2QcfaLohrRu#oR)9o2gNhD6b06al_3K1ax{* z_E7V~A07N3$@5~x`zfIQs~tr<3V!cU{>Obpvtj||t^YR8>c2<@L9zKk>t?wb`^p`~ zm3;qB?Q40he}z*%jrmhCBSrMt^7b2nZutdU%>LBxUZAuXgT%aRHyv8RT3%14OI|y{Xd)X+MW%RSNwH;qJq@K zkHLjb`K$je_7(Tl-@idQ*M5Uj{+S*kp*ZAZ3If`G$}V%t|9Xm)SKN6Al@xUCKVoRx z#@fH?mh2u1)-4gq0aC2(U)TOK=FVp3e=UD2pI>&!4r}&#we$IVjf6jekKeeNA^Rt#yx|cC-Ijw&K<FZ5?H?-YukT}t+O~ej$NvhwjI`!K9R+)t zY(w*#M7~#`c}pVSJJ5V2kzX&+JR^}`KhXRkk>8*#KS<>J1iIcQ@*4)ajwkXP1-d>b z@*4-b?k4h^1iGFk@_hqcClmQi16}_T`OQo`6Z^Bh-^*kJx?Uy9_X~7AO5`^Wbe&1$ zw+M9oNaVK+bX`c~w+eK=Pvo}_bRJLSw+VE9PUQOsI`1a(+XgzHCi41nVn^1-!Di#D zU%din5=Nv~AYf}K5ls)yfYHQtWjo+e{I)!F{pd7yXj^&f75ROGc^ z>A1D8n_4}o|CSkHb0!A6UAKIk0XE%yw%0D^evhDU(0iqfcEp2&%nw#xf1R90a3=B% zuZ#QuQ4`EHd}n?hj~@N?bn54F_@*OdmeS*i@070-ei(V~w&r7J`gb#Yk6_!N{zW^J zwa;UR!8bU38GIeQF&AFf!Z*RE!Y?ztjf1{kEVFkIJYo3G{P_p+1swm3LXUlG-s%Z> z9q3~%du>Pu2z9rbhJ>)^Fs*MxlEAnR@OgT0vOA21)S z-6kHlA0>B#&yY_=Ue|>|#*me7yVSjNJ{5->V7N1j**W(U-E%-u@{56K} z5v)G{EJII&GhSA}H#@xjHFVbh6z%x5Fi-%5U|@+;t59R35tcjnJe9)1Ip z#M}PX^jGn-4nMQtvmE|dm475rzER~J{%e(Ao+v-WZ0fDuEQc?JZ+bXU{%VzX_zzY7 zp+xzeOrS#j4nGUN>A^(#hg9C-zgPJO66Fsx2~?=x;ZK2Yq8&A!x2wFve_{B}+Upk& zzp0roJConV@V4K!+$arb&nN746nxWT@|m~Tf(DPCM&wg|75PC7n3oJ6*7s3~LvOhq zyzkNTC3>=6G83b@^w(}~V5Uf`rw%=Ops|(VJFC|o9)7TgACLYPXI+@m_>*f=kd-&wOjTL3k~LZ*u10r{EhM`S;)(9R4T6Tf1p{%e*}n{p*`^E6dlx|7!Yy zy|z<+u*hrs4l%rqXAAmu*Or5PFhu0HM9-1%sRs*xAr&i!Z^{<_1%cpX`1%|n)|2K8 zE;78e+l*c954RxSFka-(7Wab(;nOAv-vs|p_*VFT!G8naGEwAb(GNE;+cF!UCc99Y zOXqWqXWew+HJ;ld-wdyL&i?SN@GoKaPpbbg(Q`BWMELj&;Y;9);9KDBzSv%M@F_Dz zek1q`;8TwfevXI-OX2I`&xL(R3kzWFHO??C=r_`0KouR^}BNjz-af&$^A z@LR(d6be7w%%}F+-SD=3`!vgV*Zw~QK5+Of^fb&7JzB5B;ZsV5*I##9i=O_Dp0h)~ ze^BSFYZoJ*;>ceMp9)_`z3zl>cv<`(Ak_+%!#Bfgy`F=A#^HT=%j=>1X2Fk~8=^k= zDCAeqXTA>kErYDv6aCr390J;QN$o8IYd;i4;IqDz3hfO)5ndmonrSw?s^J^H75NeH zXQ`g?qJK;H8{q5sI${m{1FGjm(bJFd{=M=$2v1rc>|_q~tp6?OKN>w(!#DL51$v%! zkMh5W9@AaJ>uLC0zNRr0ex>reOaD0m{u}t#PehOT7+zz{hRXU=2fqjW@$gxX38C}k zZSXDS!spQc--J))>&JVcrxm{GEveTm_)Uz$9zp*g?)2LMh7ZRb`vo%s!)pk9^PW;K zjsGP0)bpiY`fG_7!xwBKyv{#&!8g1udS9l!o>BcDiM;M$--BI~GDqa6Vz(6DZQpC*3+%zDx$44ygWxrlZxUiAe6Ou+dztf%+Y-m)0K;2<>gk8t zuQK3+t;L@i=s6NTwMFa>#Lp%0O-x90;J<*+Jz9t(Onz*yt+y7tXVS6`Lx$-@U473N#~ib;F}kVo`V=K zspi<$#x3n};fv5e3BF;1C_Wnf*DAk*wEG$GPr|$Yx2k-F2u`P7dzk}=(C#WBjCHZ!tVqB1ib#b`!wn`%xnd% zpDC{hVWyGrDugfCP5k*Ye2wAlxlR3>!fU)|8h}Kik{!#Tk<7t@4#GM}{i@tMI0Hcuh0BjYH~7qQ`_KylRlo z{Z!`I(|$=lN#%G`=Qxyxa~xRsL-u4oCk6W?>Ect@+npI!_LOZ+%|` zzn1U?W8oW55nlU448D1DiKj^y!|Qaz+xX}HOB9%Jh1U|~_0NE4yEldMTL!sHWkj3l zD7@Z;PjmQI^yJ!uS#ymJ{|$nEsZy^-`jysqpyBPhnY&E%YuqLxUw@M*$m}h+FqH2b zG&|$ya^!>Q61OEH9&EXb*v(~L)&90Od>VhpV>jgE@XaTQ|6jphYxr<|zg7Gk0RIs3 zjZQy&75NsPgKND$M?ROldK7wk?<(!G(y7;Oh7bG0FCrL0eiVGeG^y`&__N_#x9$-# zN5L#2^TtI-oo?itF{%)w4(L9zOqzY_jb^dATx zOcDMQ_+^F<=SgS1eiHfm-^I@ZkZ*x6AV1go{s5o5q3GB7YMVXjSIj@UkJt;oAXoH1 z!iMT__~ug4W2Ue0Ivc)e1LWbKhR^*&h#Bx-z}F8GJvzVj-HZP7l;|l!{!sW7CN^DX zi{aDO6ZtgcPlaz?A%tm;@M?rlC12Hj;%lnk$!Au<7w~m)9WOo1z_;z#`i9v30R6ej zr%FGmfv<&caPsOi;nQfxVaVSC-^_VbzL*LA3g5zhLm<2KH&*Y_B zpywF)hOdOsc03opj(oBY`tO5p{aoaA9(x(SiF{)s@}I-&pI>T*-`6Cx)}JgVo@15g zYkH=;hS#z1^|Wst{LL!gl<3dX@O9`fLH<4X#@|H#Sooin-(K2F+c(`LPT@H1Dg036 zXDa`P=+XU7J$&OI>y z6+i2~5aK#9AIyVqd_(v$aW}X?<@t3R8=>b0_*Uwr=I4duoahPUS-3!HUfDe?uZ$+uU*p9Y`n~9$_^o!qMeuce?N$9;0iQ;{Jpw%|;d3t( zJu&zo9lM;%nKU@O`oq`tmjU__{4~Sc^*xJykoLDY@~!Ms)c>pD-TlbRDnCHopCpZAU=}GLWAKufI0vPw?l$ zH*%i2IeY_rD)Ybkc|Uxdbwu0oAMmZ~i$C?~`2@cCNg)VFkYW;h>wgpT>Z7##MEC;x zVv@N|WFk8WzL|Mjp=otb3p7NZVeFgtLe1nrm?PUUM z{nuY>x*PIC;2Y4tEBs{mmg|K$AAT-;>qk=Ge(>kO$DbBL`%k0tgCx#NrMm>r!3XCE zKW+ml_oLzMcr0-CWt(S;{{{Dp{2>Ct82FZHqWCiWnE{_QRRnv8yTPsS!AK!AZvTLH z&r3gnZ(tuv^9JjgjgO6I>X)Kl`_Hz@b58p_{tSh0*j?ny;HSaY-z5GVPQ6Zoj}I4q zU;MuvK8-wlU-Z1F{9qA05j`KkH#z4~8y+bBw|pal8n?aS8=nw913g9X&E%_tuzMQ3 z{(8&t@E60Ua&E8V^fBc*Pt*DT4fvG9M8SWU4}VqttdHBEKXQ=xUq4;|8eD}mAVVibJq zE#m)Qh+C!d%nv%Ro(rE#9CY2h9=`c>F}MV~55cE6`TUzI|BDEk;U8W4lIqVx8C zhe*BL^QDRK4H@Epe0|Zg7{1;)-@e}Pc3n>4JyPwT4~&)?$CdoLrA&t<(f%@JPbz-Kw_a<|H}?&$jU8hp!t z#ICmEXYeVU=Rb!2pW(B16#0z>g3U*Y|5>{Vq4P!td>Rv~?x(8Z1I{0GfAnW~H_vZ` zZ*bc89r&!3;^6Eaf*Xz^p5y~p;s4(7Sx!HnVtBi*#hvr&QsnF35yjV`|1S7k>PuP^ zybiCwKGmcv;q?`K>eZs4l!3kJXz{b)N8vX`eoy$OmwSfHZt&yb>oySnd-xL7lOp_u z>&cC?3~%d|<(x||MLxH;$kPpj=inQ7fhe2$eg>b)x&7YQ{T;r*d5?EDGcktwOt~nq z?^D`qg7U~~e>(}jaj3}u1-o}Bf2Neb0seWz+xa0*-mdffhsZZ=*DEaWZz&dRH-g*2qNfl(&aXS+7&N%T@YbJaoO9!c;D3b2Z16IAQbveD z&2xT*Z>E20{?>o2_@70dZ;pM!Yao1Mn&_#LY6KJE&_5H)swl|5Qjaw7zrU_Sg9b|axXX-5Zd=~Mkgm>S^xCTCVuf*|q zAAAGvZ|J%7W)nnzYpK+CGIqzpH#+BvN5E(Cy@UOczaBpA3#pfmugBo)$h)*&@4>gQ ze_w%~4JOhbE);*BUteyFgiraqeBNzi!BgS0$OA{B=PLNr{l%Yi1cGPb>&gFh{{PYI`W4q3Pj-DbG9ga6a8Q3+mqqly!R^jEXHqN^e zY=NGu;TvZQ@euv?Zz}K1|L>}P`p=%|*(z83Y@RK4|3o{^fUjr1-30jy3~%$dfc#DK z=bMpFqu;9h%kXvQisGx#|3|22_3y83GKKy?ht+xJAowQE$8>%uflp<^)^+o2`1p@f zFRkx#cz2(^@l>(fa=ujb4*c93zLn=k+7HLUH#{i%@095vI0-(^#`-|?9AhTNa2+{B z2-1$A0X~(5Zv1*;{}q+LSU!_R1fRnPoJZ|XyY$Q#{lUYce|z}-;ak~{OoPvbZ&@Vr zU%@YeZ<;0*(sk`p__`ORzV{+;|4fCgSNti_Qw0CH>X|RRo+s>J9I*0Dtb^*$f$+I2 zMPBpLMeteVf!gl&drekPaHRNigcJ)NhOfI*9O1Xy24BIq@Ejov`2(hlo|HF4&k})P z8hnAXk0^n!<2}qF)b~Vq_q^gdc=x>PVfZZPJmDYkX`F}Dp?`gIPGRfot}g}fso#j; z*VOA3m3Q{tpQ`+Z(!O-ZV9*TWu!jWTPsAbD@Zq{izR?GNijZ$5pYI2M4tyHx`;E*? zH^K)?MX&<>uc;o+TXa7B3ck_Q+Flz;v7q1K;%EE@A+CfU2%meL5KN1~EW_J8c9oOI z99M*cha2B#nHa5Q$EbN(UlxvRvk&f8`1EgX2?fZfyJ z-S1OeuX>zwn|~YLj=L=0yVH3i5~aP~6URRw4vXP)Ip^2$el2_|&q*~OcmckE`Fs(2 zzJzaOe5J#0T_ASdd}cCy^ED#43H4nB@9J-WZ|x!Tr_K*=D!)MLH3>ai6pCHITt9}j@w0*X zO7pja;e&TYkLJl!;NzS32sM~xCA`Yu)0%`&fj%4UY+-^Y#aZxA8fO^Qg_x^B?4!KM?u5;Rl!r(8f7F zSBQt;3k@IU4?JJ%4}U!JxlTTRBYeRAeJt`1!l#}r#9i>;syye?I&W+?Tl^{bO$0Ts z*bBZfMf@Luo|*8i|CV^}3O^UVp1A3{a}9iazQ|vR{DbfX%+EW+f28t@g_sKe8+;@4 z$w2sh%)qqqYwbfG z-vi%vj`-Qg{H)_>s^M+Bw>WvoF~|qVZ%@50fp6j5K-c{h@J+mbtMk$;@C6%5KYx~b z^(+;Ca;cZegu-ik_!Qnp-2#3%d@A+Tem(`h@gfm4X?b`Z3m@=2RQtol@O4GfANCgr z-h_AGANvn{e0vd8|N9&x{@0%%_D<_9xG#L1b0o993a?|}>v~E6*bW63z-N*F=)AoQ zzMxg?UW}ec;hUZFsQ2NUZWO_dkPpl_5Bn$b8s{yQXFsUtV8_BY9VZG*w-2vI__{vg zzt(FdeCpRC$1o0dEwlY<+n|8&zxP4UaQH0FCFl;pc*9#i8`c*_*Qp}-#y>3I>{8~Ha>o{3-g`%jjO-A3~5&5-{md@yc0&F)_@)h|U!4Mf zT&4Kmyom(hHE}n%$?$f4`PF%jusr0=^Bw1Vh5ta0`+Pr$i+=YUFBLv_FY)Jk>>dc; ze4p^=;Aadzg?>&t7(4@CKU(BBV?2Hc@9qo!fOnq@>})oewjb7$(CIju4DWuA;28MU z-^D>47k`E?m?8f3rC*Jz68)*)Q6codBN?-|)4>`Fi-d@b2@MGXe(0P7 z>hH`tMYpeF5oR@BzI0T(9?h@yFeV9;Eyu5{Gxz z7XwxBaVM|70^WU|csqPO`(K^ko>2Wx9Ntv@oNH}Ly?#)h^FWghh1cdL?lzuvJTR{p zcY}T4-S;_9fp2BMc0PLUhi_(~Gsg(w^|I=DO%%sz-)~fp^S(#lh2l@v3MoGZJrQ{K z{PP5O_xl~s!#8Xyb`L<0ea>g=>%MoonOWB@A7@?I82R1cTWBw)<6ty=!`q^N3i7ky zgCm63@pU4+`y8-d^}i{B8AyCqs{ZeUFvByvzJ_mP|E2l)w#SSAx$x=8Pk_&Ip39WM zH!{EJe15U=ydRs3o*N8r=br{AAASUR_c_<|@M+|$*P`d2@b2@?Usaws_d|Yw$s=vM zw2qWG%ppE=4IldB?8_D-ALlvFc=S96@1B!?1fRw}eLLiTfG^;D<6!t*P85HdS!XqF z8Sw7+M<&7RpSRx(J+oBLtwQVxe+GQYIa1Nt)b~F4M*8RG$UmccIQP*0_91+liL1Tz z`NHnzpvlHF?MmsNV+4XC_!Rchr%18ja(MSS@9nCG{-f*KTdIe1MV)`Xg>Sh~6hDRj zekX}PDfHV+_=DkFS&(z!iwz&<&(8Z-Cn6vJOafL-+?K%yze`1V+#CEAKIK>8HJ;7z zsXU0-5W8Q)*T-eOpn5^iI`Kc4CkFq5-NEoFy+xj{BL*kJxAYdl5$L}I-hDpx418{? z`1vXNzkn}bUDyvj>zyqA6yX07_&wlTcYLurP%izz1 zFX$z9Z-9RpKF-2E3VyxCVz-4qD>+=u2jk%DdEle{xg0)qg$R-!1!us=Q+kD(2cYL( z_*~jW$IE+$xBWTS*$@7JeBFYcp&nhYcRW@6j2pC#nfp45H@;9P?!_!4i z-K8S`DEwZ^zb-_x+zv|Mb0-R~^W=r_0rk@Tbpw3s6tS!M>b_@)-DcKDoqxs|KJ2%g zAMS+RGUU@term7n@$(AhPZ8n*_%}m6rq?^~yMCv(oi`?)T1ah0m%L#~%$#1;LB(sdTjA@T=hKo%8l>&JzC{ zo&C#5_?Df;pCa@e4Ih*XaTxqr@b33Ju7S_}M)a64hS$@ExA{Pw^Iqk<@Np+k_(S#Z zJ@-2FY z5`PYdci-o)fzN$k+EMp$55Z?O39tL9Hw_=oKhC*REAp+MiotUj*W=E`&o4yJp7?Vz zy!+g0DZKkVrXS$l--qz0^XNY}iek-|^5L5~51fPDa`>$Gg}5F59{Bi5=_eP%zX+d3 zoHv30O8MV~cm#fc+2Dlv(qO5teoy2ec=w!tis8e4=#1;R$h+qc4e-t6pW9>iFYs~B zlXd=iA3m3HRFC|3hPU5Gc7HGTZ^*m(z>a^GdNph&4SP9yO5ojn!JpylIajQba0E-> zo3|8#WgvK4^*DLy5AX&568W#N`zKS8FwZ9r{o$jAxAAP{{SD<8A)m#1s_obSpBtBY zkv;?u!l$wBYdl+&r(gBO?oaTId|x;Xe)|i8KyyW?5C(bpi5`A|hkqmF&HK6x^cIYK z>XHA|!|!PF?9Ti=#KTVyd2_y3CV?5 z+{5R4_&N`NiHE<(!@uF-H!^u)XYt?F!yjb$&ic>-C!+`7b^EK(i2Z=Ko_2}8^s?Osd@$h3j{1G1h zI1hib;dfmmCo~ z%{d@V|Tb zU9Roi{}CR((8E`I_%l5GH6H$65C4{j|H{Mnx~}tjZSCRr@$gw5{^*c5{c5_jqvp>Q z9{KZ-uVcLH{`Y412K1EBtse5|*}9?gdL8NEkM;1UdH5?m{M{b@Ne{o$@SV*A-+TBz z*LPm89Xx!6hd;-|FExCM+26U}Kf2E&-}{En{n^&=oz-iSN50m>pYP$9dHCl%e2UrU zceXCi^zbKn_=`OJG7tZ(hyS;S-}t7^{haRMt33P#9{yGj|B8qI*u(#9_+5k5uPtxx z-2VX{{umGc7Z3lu;cfq1$?wls51KvlTiw#RKYM%lgFXCI!*|x7&-KV(=i%@7@UMCJ zRUUqiC7su6goiKj@FyDH4DHpf+dcA+8@{tRtaoeY{-k>NgAL!Ao+%#rau0u!hrisz zFZ1v#Jp4O`@2sEy;gR2UY3Fgs^6>c{zQ*vK&BMog&l!=`kf9`LjLzH6H#U^cNf@ip$aetVjMm5C5Bo?|)n8^*X@A=X?119{wT^e~X8I z%EQ0m;Xn8AzlZ$le@C*nIiT)ry$gy8%gUl9<&_oD>YBo;n&6mf^W(h2vf9|7qIf)r z&djSRtIo-*iA0L#6jnuRstQYMs&k66v!@zv@T|h>(xPak`Mc+_!t$J={AhOG&}i=X zqCs(^Yfy$MK557}qj5rdW^rx2thA`GCN`p?IJYV`yL3TbO;u?{$#iQg+mt!RO6S#N zM5oR&W@51%DLOP1$QWfDvEtczHACWsrBylO^U|Yv5o53>k`~R2mBor`BGolH#=aFP zi&Y!1)6LI?A(b5&5}g<=tDGOJiq5L6ttigUwf?KEXhmglOv+|Qr{)cb4l1p#DjYOq zXc&MAk<55$tSC0Wv^o|os;n^8tu3kvqGKma9yww{G+JFdE1DBsEpk+S=-f%QWo6kC z+4)taHL)#TMIEQ=MJAeojpEVL4dgw}E@ip}4(&z>i35*gf9 za6)=o*wFcvQ)(+~!m=j7lcX)?Rh3ni;OE%sGbarjHGS%Y%97zZ6{R%>t&oZStn%zg zM)fQcl=4}n6|rJ-r^M(mCMHCNmPF%xo>*HGTVTjFP&2$F8X9(^-R@t_98=}un##(u zYW$rL8J-`KxmA@#qbe)r#j0w|3%tVR#cD>!X4RHVDlCslNWxG?hUL|m$caq8RW^K- zd>EcnJ)*31UQ8o6#MUl7Ew8pZ9;+yx8mq1?kLA{c_R34;UP)AnPAn{~ke_l!+v-O$ zvQB$K6a`N({(V#e16)P#NHlrt6QywiUtE`As2c1ySXmMqH1WrDqs>ZN;aWF&L{dL5r2Om(Mii z-5c!+2B&pYkY80;G&fc}IySGgC^o9Bu(~?*Ju`dt8|^C62X|C4eQNeR(_!)##$#>u zZeuzWN>3~_vbLtCvLdHAEE6#M(~KX(lx@lg~5xYgM;Lq0>N6{6VR5v&EH*2Wo)N?(6^RzjE;LoD zEHTSo5Uy~=^9!qHM@@%_R+~UaYr^ECQ?hnG>!XQ&O)P4n)220Sk7#8)Ffz6AVtd;- zXEMT?XvA`%rFN#Wq9|rfT8q_#GSf1KuU;^SPOF$-T2UOGT4-|e>;*-pwN0R-xpPds zOsd0OvnCbAiuu63(4cY2YmYJsrT4y~-58_X__MQbZ!6-8!cDYp5o+0n!_A*h^R zVb;<(AMKCTm1gf0#;9_(NgkwBm|aVx6R7C?Qqwoh-YFK8nB1qRG$uuC=4@FL$;$F* zWthRqMr3g4Pqh&!YnN^Fs?4O`W^Yz){wbOhHJ(?8;^n0ajO(FgQ?O0C$gXjvvln6@ zT4@#oDO6ZoEI*)0JP1t6RbEhA= z$T6i&i|5WMt{P=xKFbVE4O?+lw5YIXPAtqz0%N>-P)26P(7n@f`K>`Ef2R7 zwH4K|SOvAHHd$nc57FqDsUs$4N3$o5HmRfJk^DR}f4WQ|k#sXFwQZJ$k14d%*}^a# z3-_#%benOFs46k}eMQZvNVb{v>@e&&N40HBM@O>f*?X&J<(eK3J-jqlRxDDXe%aWL zN>9`qNi%z<(xPzjuo<;gnmNjFcFE8 zt2FQ6a8D!sv(iS^u4<9tZASujqi#FBIsD+nVNzanwbO{fCf4mbGeVuC>=8kNVpB4b zXfG@@J~Gs7t8F)%8t!eX7N*;bB71=`ZT5kq&FW&>+#FZfN}4KlBkQz2v1iX1RaRLY zGhHZDl4-X&#T91uEz6BW!Vh-bMr(r6hYd34GJ~Sgk_8K*akEjVG(MPMM(5cbve^db znmm0$=t$bMiqZwPN9I?KHltgX_x9LkPOhz@XAP?|E0L*%UH8L&l|3mhEt(nbh{DvQ zEqLvP(j#_t5~X?JoEIKYNaL>-G94vht7f*X1*6kMUK-nsb$dL*!AOQ#Cd~fAj%&MZ z2~VJ=j&Ez;ux(beV|qw98cipOL`U197f#_EQ!$bvSe?lgc_s;+U={|`trIKOarBffVD_;K zu57Mlms@IT&}Kc7vHIcC8W@(A=xm7CInXymq*>cKRQeDzRhd(YFj2SlGslUeD$8oi zE9}fTwKQ+AOmC|-U%K6dn2|ZVwB%4zQ!~}uahGjR9d$+UMmd`qCZClsW`xYH^j~q zwq{Y2k0*4Pw!R`I%&KP3`#M<;Bk3Hgg&SleXS|y=tF3rv;Vi0*FSOk>Eo|Aa2Hutm zN4+cuwz+GoY#ZgL?b{lbnS?ANoD|HV zb#^4vE`J?XXnRVPlVfUW?{-+H|4TxVXAkVd4xBvBVcyU&&Y7mdZOM;4KsGHJiI}6f z(XrWuwPiKc*|~|+Mi@6|5i87d+9fi0o}En1aw~`Rrq8)Ei|iqE6{agD%;Ax=QD$o@ z>xZUg3A1@yADc{{=$NFK{b+SwO=dL5o_d?r%kE9v9tfBpWwRO?7Ea35=49BU`K30G zGICZhe7N9A1gf)VWo!OqI`U}q7=k1rJ&nF*cbDNRV^_y;5{QJWHn~W7%&sB%dD=NT zPX3Y-gmIP{n%TLN0NSZpc4FcB@h>a4A`Dpbe-B+1r!9bn`qYJ(?RnOUejmpw*U^@IcX=IJTeDhS^TIskS?2JIA$ch)f%do!VAq zXFy37+NFt3_6Cv6FvfPc#Z7k%k7O3wFx%6Y$nc4Ub7O5i(z+6QlCXuzEH7LzEvKSp z*pRUQ$uRG*2@#jtdzmgC$>z;SB=juXoKx0RhYhb|-W)tbVzbr6xu8EqalR(35FZW%-ph81|Dmq=yLM zGn{B;Rdj019Dh~LZ)+Z{Y`9V~r-lA@Orj#`rPU@0C@r>6+QK2*KEQ{!Pi0K9?e*!b z?QIs+Nrq$#g5&SLHq04j_I%FLAY(OIE z%s;ZrGA`+z_B~O%A}SiGo?jTxEnHYuSy*hI=!X+em?%#(E92R@v$iA8cl!358W9W=b}5QRrvKMO~(Jak}lyrERtD=Bohd z_EmrqbMRJbPLSHx|EPHiWkN8dJ;@Yvrj0vhp6wZUB*Pq8g~2vkkg2lE4M#`Ec_{g2 zR};|Dm9=)M=vdf>To0=Tn;lU5T+-fOynN)ibsh648?ZzP8t#4$oIqY+q z!qlbhGX>?2V7&^k=T6E{v)QJ7fT32Z{FqNHX{$ECePFI{cv3Zu+W zGELpS^mi+PviY-J6v7>9+vdfdJhpFM+S1$(-B1&HTY zL%&Ym1Io=C9gYmn&<5M%vkddkgxI`TnF;lA#{d7px0NEMpP3gJ%+t{lGbhNb)E2IU zHx=viyr*(P0x8bbHPRhBbn(Zf=+M&&6 zLT4g7EqG=!sY#eF*jMn(v$zFjt7H~|VfM8{XA7h0*XsUgHDt2qWxUB_#^hz^NApLF zoRHmdZHo*s^Gr@fQB^pbngQ3oyy;MB+wqvC(mu=x^JYD$&i#RuhgbwVjy?SF}d@y^P;)tmkGDcUtQ|f zR$N@jWw@+EH5nzg~K;_5~gR9FR)z++lOe{on42=<+c_!EdJhUw}$rp z*)k@EwpMAMxH8P)tT|5L0jLJeINR249IMcLy7Td-9X45r3>zt}*|tZ=SK6c#^*Vuu z676je9*)^w7%|&3-I%oJBZ&|9!oetA$5fnY%Df(BY8Sp9oDky3&{Fe=GJJKp)a(oM zD{W`b3{!^0$EMzz4(k}W)f=Icw}l4}mavSdsH|96URhh+{vvVP21cGCbfRu3&vopx zxiTZ3Q`UB%dH4W8I&+5uBQa}^ zC=!fCGE8O>A2r830isLBs>AY~IHAi*ht+YI{n@nnT(fHpClYz0st-84#}=K$rISO( z?wud%J2+{hY@#{8u%>8EBz&v6?ElnuWxH)0S=&!!s3}ph?jqTAhMqVPEF;PMHw~^9 zV~W&}l$Uw>|2tdNsijFuP5=i8D6+e%&i0+PP@sk4dc|-pH8q@rm}8oKyx52keU+4sxi8)+j>&onz3CB z{Oq&SRFcw{QI9IQngOSL_4gE16OwCRzhBSb9?j~S+e}>y)ha%D1)#S;`Gf@XWIK+TlhX!QI!7+! zFXmTxLP5oug>4oI;;pp`4T(pFo;W zL>6h16-br|Nm68}?&o^(=m0lWt;3Hkh2jK40e#0xP$j|>_hPhti`+$mADzW(PMB_0 zQW;WAm4+vY&&@Yy2$2D(Qo#|~?L<3-_{23zEqCZAAznss(7dM`t!qyYjH3%wK3J~> zc?X^2gQ+4@>R#+m8YEw3oDfi_5?KXL8qH|2KFo=8=ICZsy-ml?*dyTL`YSI(mXTn;ctEnr{^Fms^iZ%$~r;tE{XNN&UZP+VU^xR7(gEKQV)p#HI6 zklYLHW&z0aS1QgK;;X_fZ_%~NjhmOlE&B!N(DK6X(~TBX<|FDf-iLv2L}hjoQHs>4 zB%1O-JrzahvU(~ZVhT$wSI&PERT&B+pIT`BE(?by2_*DpNZS5>=4#PG$*O=a)|4R^ zQ?E8doeI(~>xYniQKjy7&_{LIPP{9P<rBM4j3NjqUvX5Q~s_W+TqEiepD3)qM$f=j_KmqwsDqP;7#DkOq zA{Y2KF$fVM0E{!WXjr@~EDM4Ys>v)?pryg3l$ltv+n~BK)GO|Lq{%T8;INW*hZ3Kf zB=B)2v|aqwFmVmR$1^vJfYcA=alG!#URLfph&%#LqlY_y8@zor*M=c?;iO0w%YQ;}E<-?)`DI1yEUX<&(s=L|eG? zIoW<*JlsCOII9QfNyYX_U;-_@*8}VrtiCKZ>lKya{yy3)w0er3j{GioL$oB3FY2g6 zmOf2@4|5Y=lExUa&&g_mg&A~fP9t=~nTRcGuF?OBxFN+4Ne-#9!;&a$@@UH4VR#C&wc=wt{RI)CFt~=H*2XjN>C%nxrBcMr$L$qqW%=(G( zRX@z;Nc~aax9D7)qm3F6fRl%XqFiL0pTr<3^=xI=Sz@ZM%F*J}rTsahKwMl;^5BM& zJ`#_n;I;^4&@~;^0&;2$Ih$s&VtyBHK0J$o}{Oq9N_@i!-J0p|h1VXj? zUgOsNwC3XaUn40KR91Q;XO^fTO0G)%mXAKL-Q&K7nk|HE;~&M^%~JRROXj?CSrJag zL>HQR$eTtuQ2MOINVm-BlN~LB1Nu&Dh>>#Ts(Jl)SG>a1nhPX08bl1Q_v)#ElVSB? zl)>X&xrJP45o`QBv%wX!SVD*^^hJJJ4d*ULB!Y&0Mu%LV%zKB^6JS%vN!wO?J)wI* zdw*<359qQQU@{3=9Af1bv89i9@HBY_1bxDPdvfs|<>^Jc6Ij1@_5mGlBMgZ! z?;|pOtUMD%9Hd@cWheD^0CkwJc&W%pz**N^xEy2mzV}2DOOQzs8PeWpqB4(FfLU$o z1s$Ge(=!I*qIyJ4mL6<#iblbx(L@K8r)^@=H1KDvH=4rX?Z@}8tvOyvUh|VBq-()J z^Kr}f0A-7DgAEVKUxn*_Yt7jXone&SFMPr1-3q9PJf*br_C;2bca~L(t%7mJL+M0e z4$9TrDMj!guZ#`nr{jC=x&0^wOT3=+ObXnP9WJNV1AkoF9KHhIs03KbX6A2C`f z$e%1+gu}ry`8Wy>$6NmT6;`vkc%yUqU_@@#n9%1ZAXH+V$EQLnhnBF(&2BS<+6|{a zV6E|~)l9ZHE(8i`ca?{wIj`4uv&m&1o!$g}=!0I}LR{ zp%xR_;{jFhW)>$+HW(1G_+z$VQ9l+wyjCBh>m)0#IkRNBQ>aZIv!ohZ<1 z1g`1B3_z8JVki~>B_lafR?WrwME%Z`k(le*%;>_nf)>d?4CB*DAn#H4f}pPtn>80Z z>XY*+0Ahovw4?a#2}}k^`vw32nNb_#Lu-lv2Mj1ZyOv~lPK~x>vxh+j04(rq7#2 z8WO2u6=wZ<+mRK)YQSB*29C5f2=4Ced(x4yP$tZ)uhFA4M{(+ zHDv{9i{)8YP)zUaYVzMlbP|_nJcdAoiVeoJP+=)K0%&_pfb=UKdW*OugQ`4Yec_^q z(!39JyeL>&O~d1;mVK-lTz9AY(!c;gqU=wfcjCx!ewoWn1To`exqec}aq{laqw z4${FhJ1Pc4pbFbco2_Fz^kF1${@aQw+mDfDV|G{XcXP{~u$7Po4JmNdM;(55h_o}% zC&pqiEe`z6Y$DankdB??{yLIcR3sXYg8o%sT9gos(HMzRaKE4&w(T@|KsMnCL^?>dGKnzoN{`Yh>)Sa2q$a6uk4d8 z+QuyW6GI?pU+=7@O-`&SrK~x@#89OADd4~&5cs1ut_zw*IH)2arZTwLNA+F}EFAFO zMMzKk>_f&({V{3!>WZ806`NZe`xBZ|ByZ5nkGTarafR&{E2u~w^F%70_L<8inypsz zU_4nKqpgVw&Y32>gyZ!EnLN0eaYCc3g;M=jzO>1-TQA{TUV#_6qAoPDoJnZq9aaz) zY(BU0aoWm4gXhC7&3F)5mN&+8Kl`*^`@xr9-Pvo^%6o@WqFAi<3hT^26Vw3%e>F$0 zS*AXEn|vpW?1ilcdk8 z1|>QwowH~yX{(Yb0bhpVL+B%FZs4|~+ug&mdwk68c!=gk^s=Jj4_*BT$^85FocbJ% zfPPMc@LLKqlFWW#dsFZaYs;5$j%7X?mJtZyewYx$Ho(a<2L-62kUT8LG5OY6E z8q897?7WFiER;45s-$8RnTu=ENmN#3iXj>ovxz=biKx^OW9Ie`x!u~35||A2h&8+m z$C*}VRl%bF!#uTUQhmrRQLFTe!Yh;d2CY;Y@*7kR7~9w^J1E|0K5La&JoboiYstC9 z*1<1xkr`%pQ9zYnC0K^vUDCzKav2)XxvztVp#1zE!@zhRZO4x*fsQkB1YB81a(q%C z${ixE*)UXucO5OCY43y)5JSgn%+20>r_cnM_nW&ILUEE*nFk?cNqSJ8J#ZCIAyq&$;3Wjakg~2yVC|?0ef(>0^mIUJsy325!}(%+jXC_xkTioOkN`@> zH7O)}3~3b+n_hFvHy!-47*l}OhyhDM+(U?<0}c>K9vsmgOJ(!Kv*C@xEN3ge%j#1*PSSK&lBG)!Mh^Rw z@Dw$~dS&{uC>jsFK5;%t%th{H)=MRjmZ{HI_UhW>!jQXq_5iW2%n}j%U}k9;GfTt2 zC$m)Cybw)?*i(vIf?ox%o9i4Vq;q{MQWP{iAPKSW_0(zy* z1$lP57=w3Inv06Y=Uu4NK%>9H;?GE7V;ayD#pP7jf*}UX`$SC_dY}>^`hv|k;O3Ka zl9NO7L_qZR6~6f^l8R^lrUI_;@+iq%id$ESPFiiuerm zcoVl5m-bqLR$yX)aYrSq={5}+}HTHh$z8Vfb~A^wsLuz6zVSQ+St+WL?R zeZR$_$-f}PY54eX7Ki(s)%X?bW+bMOkbG3VA~4tEYKX4Z%4e84x-yngs|0{4a0P^Q z_>H}j>1O>vms;`&wmZZ|aajcKCiuFkXYJ6xvHvTCA1I*2SAVS*sD$2GPMAp))nW-4 z%%S&WEb zahJQtEV~g+iV!06RqCaoa>#mBOI8kFXA)D$)Zyn+$cc^(Ljz5IN=}wEtu}C1iV-S? z%A$=S0u%xQ&M7T3eo51!3*LlNQpV$hf$th39LhLpQLcztw;nU06KzuShxXNr?uqLC zYca*NBWFnhx3KF7CpGl_%QQV4N~9LuBEvW7;W8?+h-rZailyP_FSNPi@>;5HNHq@U zGNxNSB2Q(h?{bO4iu*3w^0~}b4Z>t`?es>{oTh!$DoyT4eNY=vbA~M~iE#k|aHCP# z?&|l4o<+R@gW0R17wO&*g9A-&>XL@$~;o(S$Zd@NsEbaHc5Sk zuvPGcuxOsZqOmst$zeJ`ubeF7QnOA)ZzwAS^(rP@MuK zAV`dhsPeGB8i3NY!6DZWy~Y*haL+${EFF)KsKn>pJ`>P^gD=PXE4?1iat?uFWN2ij z@`4fs#Am6x!=d1Fs$mdzh8SB3Jb$@pBQ>;ifs~SDRr#^7Q6YXr9de_oq`uO(DfeFJ zpr;V0;#cK$dJWz3#dUcEEuB_z$V2Nx)s0C)>tR1iEnI9PAMuead2VE=z`+7?=Q|lq z&0vD>UG2E0ly<;k+Ntsm&c6Tw9lLuKFaLYuAuuz@4xH*}2X z3S>9)8(nx}8Y!3j-pL29nXGr9rz)j6yJoybPu0ps6GeGzpf1ce7sT1rJy%cErC$q} zjc0^JtMX7}iG$hV-z!Mo>P2iq;29MsV4-4IWRj{5B4W}M3b_))>jA_DhWc&ufYuG) zB+2qC0#L!JO@D%T4Z0fMfJ7s{C(UZ$D$B2MbVEfB;q}1)f!L9mt2uGxSX?L_&N8aI zoQ|k(-xkoEIK3verz+#5h7${)bM^%V@2w`6B`=Lzlmi%xE@GE4QK1br^v}2jLj|r! zbM2xRGrXZ5VmcGA9rkFY`ten`=k!DdA*e16Er@}V@x)lvU(skQHqorqj|>N6ISsD8 zmUeEg4B^NAbLj{Qsv(?WbD3SQ3twu2l*Hct6z#*+0rsSAXz?G{xG;&ftx16*f(x!6 zNO+b@Ee?feJuR&gs|IcoMj*=mW9NoZ=z0aM-u|`!m}o6t?ik-IU$A2l!cs}_*RqkM zh-DZQk5EDB&F>$sA9uU;YB(kM)e!u$4{B!l$@gAGzX9hQGQjj``%9>Z5rJ^ELW;BLAfp zAT=u(OWOd<9U|~?|K=4YVq+@M6g9_m@#xzb`lF)4kUgGjFcEwqkwBVpjp1vIvd#Tq za`!-PN@>Mlp2sGz#{6il0LcT2aq=sqko-NPsIOvRN?Y+!t(cL%fNPRvEH3VB{J!1I zNqB}5Wx4sbyO3j~OTss%SWWdFCu zn~Fs+0Sd9OMiR^rBCh8ZM&3>1Q1aL8ekLVr7UPJIsO3!d#;QHRP1SJfic<7&G9R}T z+!g|CIGZ1HnxQVBnCdU3sE2ZN_(Y?LK73`G+MNAgr!tH3uP9@n`T28$l zzqoAb*r%m6G{Jz|Re&k`((^EG=a!F)} z)FE_g-1s$4r;?*nHQJmY=dD3X4wm# zfDR_uOakLfU_RcGWdc~HOHNJE7U~%|94^9}|NMIOe)u{_aM%DgpN-frUsQpWy~}KP z3oc4WQEfn#?3GlWlyJG_n?38uY#Sf7tRy}Dyj|R&n)V*0v>1|+4Hh5VBLVuq7YH&fF{MVsQ2IX14_>U~|M8v>^D9@*EaA5s z{MmCjytvVf$XCBpCy=fwOAs;VIw_v@Z-6XP-ctCYq=+#QN2e!u_v`6TKmGj6@cMPz zd)a&0r?=j2&BTM-@Ac1r{@I?sqzhUAwNG%E)EnK(9@-go4CA}yS1*9s(Ih+TE@}RN zz}e}T@6UwCN*GQ`oCnkkih5^MlYkCX@QnXUUx2xcUOd?0I-=PvS>=eM}NK(h)uRo2@Y^#-+{H2NFp zh7BO3(i0OEn`QzV(qeG*Vu#03SrH^KeZ*+I-ejj|Nzf2zd!Res2KP`xg{-xo?$;|^D~k|biz@$jUvPQvCrHU` z!|0T6+(OhWUGaQ7o4J(|6WTE{lhgdSkz+~W@#*p=KRR8Xc66jKVJ&fnd&IH6jdr_DDVgCJyZ(f3FaqHi;eA~o zw~QzOwGSste%UlHz>nbe+2sBqT@19t4mqIpd^-A`{sq$Z5#%*dcn(|BZ7r~l%!nJg zdpTi2Jo90^$tcErZFPA8M&%fm+U&TY%3HdFH&fx#D&$Ynea_c_(CJ5{UAJ1IGsInL z_!TBP8)+bs6t8Vp?kJnyi!J+C>4T2k%QJTJ$O9Piw}D;KPC^~>xzc1f+cF} zZ`2xZXZPUU_#BoB<}@t4SVhXr&(hI&+ruK;uWgQ{l|?UI&~}2^L%Cs|lSNLyhihH7 zt4?J*{7BVI8`Xc9?X_I5W*@0Ykuk|~I|P9Ju)nxqCC)PH>|=Pd3Eb0HxAjwzT8w zet-XvWH$r;$(1rLn%=DG8i&dTjA+8+>6=Lx6a;GtJdZM73r`{RL`pY4$e`1L4Fsli z;LeEMaEeM|1hhV;NbcpO>PM(bRPX#RJ41U5Zqfn^&={Tg8nFZL$M71um~S**d}&Y; z)&jL}w=J0lENs4p@pWdOFkxkf5i4wDTwn4dA?44r72P|_hd!rkFmTAYLnJeA(1Vx~ z=d7&StBP;j<;%NHSysj2jlZK35hYNZH+!)q>6)kKfv>CHrr?3Fvb9CjU`C2ZgKKdt z9t8p`Emd_GSFl$yE^4}@37;7;jo7%7H`|u|D!xxY1D~*;lzqDR1i1h?(~oVh41Ngx?r`l2 z4NXkHwwZlJjywGfHes^M)-y*&Fw?eJ&TgH3jl_aR8l?}U?eES38Ai()1x56)YJx;6 zNWF1czY6jL=DfC;Ex*HjxQY*k^t*6ZY}sOp9sQ(<@2 z8L23GZj>FMuAUoZZKtwoQaH4$Cjz@t;lpIpc%byaaI}R&AbVd}&S3A--@}TG3Zmkg zAv^iNwjW{hE@w7UETs#DCE&6;r3VS9JOig-=(fYrJ0r#3<>kOHPv1MW8&PNN!`(Df zi!Fr;R_m6Ssbu=L9YbZayTi2a;fBI7e8w56aIWbGkbp@XkCv3#9+Tr0kzRmw$Vz;; zO%2S8#dfqrB0W84a-|cyL4l3!V!!Dy$&9`U#FNZS`fTvPs_JXt4J6Bi^4j@mVSEXi z^6j_Io2483VR zV`nDDws7}Z(IT}*E-Jg^mF-7OAW2jD87!!+H?u{l8e^=O-H#4Z);p*i79)MtC4%b zeELU5>bY|XLDL$6_J@u1f;Nb5uN@+8gZ}_4ZFv@DWJ2;mBr2>0FeS}RW&g)h@f4Dh zi_*LTJ*Laj3uZZfD5C;t4DRTl4~+9V!vzYg&(Bf{8SNMWq|lmJY`WZjH;xSUAkl{r z$0Z*JHJOo)PaMaKcpwVR(^Dsa2uK}chAi@#a(aY{t{WKfsG(eMX;$g(J5=}swBUM! ziJO`AV5*eJTwjpv-vJ zIGvQj2)$mt!X-9K8@|rfU(LS+QADA5lbtmXx}Iu9JUo)T!gXqpD|r}gF2B+ z;%H~qm0-???ph*U@njppJ|XW^+Du&igK%T~1?j;1&xNKacgbOi7xVcN*UqFr|9?_6 Bog@GN literal 0 HcmV?d00001 diff --git a/examples/ThirdPartyLibs/openvr/lib/osx32/libopenvr_api.dylib b/examples/ThirdPartyLibs/openvr/lib/osx32/libopenvr_api.dylib new file mode 100644 index 0000000000000000000000000000000000000000..89cad77109fae57c0a3cd118ea41ca351b6ddcab GIT binary patch literal 300188 zcmeFa3w%_?*+0IUEXf)cPQWM;BcS3XLd7U;O+gJLn{W#kHHb=xH&CivB)g*3NaD$c z498>9idyT1*4EnAzKtS?H=2;V*>EW)VgZ3dREoPStpR-@0ZRVg@60)yO^BDazxV%s z-uIJya(3p-JoC&m&ph+Y%rlp>@#Nd<91ceuoy?4g-T?&@PSp30d`d)bG@~^1KH~W5{@~ijG=@$-jII4C# z9CTeBV0syL?(6jQaD%^;6UP{yJp|B zaQ32ZaO5O89gAS`pi2Wt^v}Y<_oAXZZ@;~0_WifdUg#_G-FjPBI@b1aI;u{0IOul5 z5k*EEw-@^s&7FUz71kBUUFSL-gUO;scHa^NTx}+7-w0A2=P4AUWMmJdHtE zROFw(c<%f=issIrvjE{;aiolPIzr$F-PpWiP)J_SKx9!-&Y0`R#Kb@jXgZ=i(6wa> zq9p%{isqv(Rh2IEE$TM?I6@+QY~HNLn{W>}( zA?-aV0^L{~EYJKXj(H2n#JRqrIsW;#pHh~!W1J3_n{F(Q)2#G#POZ<*{H#XWp@5@{ zD(UvGsOXMceYbW*b*+;Yq_HCWr@W>|2X^<6-^mCAv*>c6H=}$*On{0JmBL!#YKx|&#?&TF1<8b zB7H3V&{xDN|B8y{%`Ps!_0HKAo~}4NNSg*ox?h81!5#j4W_Pr$&gHlmX@>v@-B=t5 zilJlfJW^pb&r^6Y4rwV@biWD*`FJIsqM}LTCr|X|jJNgnEr@AB1l+ohRr@5Y{nrPc z(RfnvsBr!|9a;A*xb=?Ni;5QB>bq;iJ#%kcuyFSL`xX`5x^V8LcRYZ106ETcI7%<0 z2e{dW$HAR}hP!f((=iEz9=r=>M+TnzoQ{zY0MgEUa(?7={0TvW%*i=0H z8;o#1XTU!a?qV6*{m;19osJFNM4gQ=<}=lKeBk)!u9^AlACC0fvt-tlLlGvKo|J@4 zlN^`W?{N7?dAS7-(~?$)GXx5TJ4amiK(TN3yb+V;-nQu0MGuU~U3BZb*^3t}y1RHp z?gIaOG{(6L=3hF;4jnOl_M&2h6pzS`i3d93pMfWeUvk{(_!|6E!1laJ-QgZHLd98l zSr1XX&inBOy#C@vtUErp4;yxAhE;W>V`L1xGif8r*%@9H`O>j=ZFf!MaO^uJj|I2= z@b*i`*eM*23jslXXFUKt1hGoD-dX=We?1)N;Xn@udN|O-fgTR@aG-|+JsjxaKo19c zIMBm^9uD+ypoarJ9O&Ud4+nZU(8GZq4)k!KhXXwv=;1&Q2YNWr!+{{S*LjD8|#s7rW;w)gLfMf*A|X9LRs zU`q&c&z-~2#{yZFkd9vGnN@T%h+nSgEj#!qKorSA??J)`z4A5aZBcL7@5{g)%4t^4 zX5};}r;(27Z2-M))4PLYo8AzL8_XG+B0+M7avzZc@7#yv2)%Hz!?BKg7t5=)^66lP zf)Cw?9l7i7u)?oqxIW;&z(ry#c}0vSMmM)2hO%}c_#x&OlCl1^VkBb~{z3g54*j4D z2|`5#962;}Hc*Sb>t4&FKwg8g5IK;> z0r?T{Gfsam)BDp%yy0ERO3oU9Qp^FOK(%kK`QuBN$s|;zYpAFXWg}7?7BztlzKoz( z3Xkb6m)R`6nvj6n*4`uziKR~ua1zB?;>SOMFXKogZQWhKDpH1q`T$F$&$_vM^$ZQ2 zJQHr((9j|fPNG4?ozmMt?@a04LGLu_W!;2w;T0`qb&mpv6bj)jjeM6s7vP83h5{mz z$`|l)0AJ4J3(B1&(a3z-KVp_LpD(3X<`b4)na>`04J1RBOOZ?)T#5`GkiY3urKHU= zDh8b)3)gHc;+TE_iW!t4j0;w*OR?Hf#oJNeddt^daVApgb*@>3 zwc22rpMEe!=6EC9n0OU{sDv|&0=JO?{=3EXs<}<~L_A=7LeRm@#~IanT?%lV+TQhp zZix;mp^&($eP-KBifoko^>PTEhwYCOW+(6PvUqD?X+blR+VenWiNUp4n zTobzCM0-2Xx-xb}E;lL&(h(h$@8p9~F#s{-&r!6tpnPMvwx(9EOP+=1uF5a<(?T)&QA3(lAPx`0$)2MtwT4Gg^g!QmTpMAGNg)D8K>JbuNwfh)-6@$+c#dl99d{=!1KEi(;zG{sHBzZFfnK&;Bzg5dp zeEiDx_ICZ4TU+`d0*ptOS7JQitZDz)ta=?omT(!4PHU{=xA0Gz5oyzP}cT@MEPTx zHbRtD(p%56{YrZOLhrNEdx%~Idm5?baKfzm4!n_v%&J1VKC|i}y7!n>E9u^0R((!) zrdibw=p)ygRU_$6GOK3N%>l`DN2^l$Q_ZUP_&&U>Ed+Y~ZnJ7IsEwpi8Jd-^aL9te z4X{9jC=x$HT~p1l(*zCRc%;Rwx}R>yta^@avsv{T-5qAt2Xq_Fs)KYJ%qkZIK2mK~ zT}*eaSv8t&m05Ky-B&;x-IZq5%XFVHt2WYIZdU!BZY9d}IowjS>O#0-KSaf>x`y5# zO7ETY7D?|idasw>SLhuty+L}fmfj=uULn2H$>xit_epxskzOAwt-tiXL~o+>9;f#N zgvzWM@+G{7q&JV={nC3cy}P9M1$rB$cN4w;DZQ=qzAe2MPw_m1&-r*R#j^rZG9T%1ti$mzo(epV;mJk# zd2qjj=Sn;{{^OX8hXeFkcyKJlaTj2A!u;!Fp7sIl{E3>Ws%2TqT*agymH_<5_x@&R9$Dk0rpL=~X(T z4PNSuGf*h%jPKEf&X`FTI^!j}&>1y!p))?C3!ULXcGMZe>Bi`cTlpTNGv4L9r86qQ zB&9Q+?5%W0?)$MiV?W}lGkR0+KxbS=x7n=ujOXY=XRM-IYF2HBYw3(JW6y4R@GM?#pX5pEG=UzO7k9{6O*it+(_LS*m2Ztg=4&Y}PRp+9e7zx7L3JV1ibGY4C zIxTz)J--=J3@Z~wzWL8 zcfQ18^c|Jo>i5)ydY9FaCUk9~&6`k~*zs-``%f^Bm>kLq6U+lHC>#B@{wRepAHQq? z98k?iR)(=CCS)dyQXk6P$cX!5BC;8Q`3I**g^bmI#8`%)qDUhZ2tyABhm z)TRSwo-;ClGZ$k10w?&w|6ti}a2a`SZB0&GyWTp&2Vb?`I@9kQj|m~?#2z&<+<`>V zapAj2tgZ9b$r>qXP(wx@HFJdSX4D#Q!z)gIqM5&;DTFDFce9b-NLa}`WPUAxjB##} z-*Q+>b{y9Fc|*Z0#dfmW5zLZo*Ve=XO|NW;B->@&%vqdU&b=@N!_+8A;ejbYOmJJM z;=02`;64B*Z+p=N5&vi)-{r&;gInRPqs^o)(i=Yn--Bp^Z=(zFEpQD)q3Ra{L&y9= z$q$%~k@m9uRpC(%Mwryw>jM@3R)t4jOlK3vJ-`m#4R6-h~C?V0M7DH@iq+pDe`OCeymFRn+2r~& zUvEg(LrGYijGSTkTg;Mhq)+U8FSoL$^kb(#Ra>*8DI$(V&fsh=WX9yAJCoI5kO z`2f>5mY%x$gb~Of@^1MCf1x;mCGSKuR%Zy#Jzd|&K(AHdk zIR@0SWFP3qX8JP$++SPM&=fXv`h?7ausNwuIN~w#nYWpf)b4CbuSsu&^vD9TRu0$O zrGp8N67Ov>&HJIu?dJI!im$h}`}!_>z68OgpJr7@5@6HW#nf@=e_?irHKNI8cK}#f z*H0mSjy5<)+Ph@^riCb%ut2$wIGq0YEaaHwHpSCcmq@9235i5~Mtk6hRxSW+H5jNJ z8c?Nlhn^-3GFU;k)`B4BD1;v|`tg%%L36t{rIv^{ld2%5Y985m)%;90w$TJ`g#qNs3>Uo~!e+MtNHv+Ge`0*4sb7&nvt; zOm8#GG5kN#Ur#YBDlit8ts`cpc`@R`2J#VG%v>kZ)O(xbWag&#r772k|!r4f!5EV^&6M`)(`^cQ`ea(eGzWD+K~}op*QhnQ9>OP`aR!im#pYZ2;`z zhNdOu;bvo15k|2b!L^w0g}@^yn5ee;E3i=EdH;l%lgmyn2@?jk$WVppgpKJGs6PYBd{3qY1%DzX938-nZHecH z)ubEB$ls@|js>C)gfxdX)Wpi4l2^T2igXBRq^Netr|e&cyDfec8E;O(uwU}SSb8T$ zP*^P}{}|Yfe2-D+&YYN{J^BG&SpjYkrH^uG<*Q_T>ay(Aj9sNA$qru$6fF?*Q6imY>5g5!j7iIi^kDAp$$_Vg{NSp%_NcP%apVrL7|} zf+LN<$AG}dD-a?it7NIuVx%E)Ak1Y*)THzN8q7{>qj*D~{E@{;70=7;o>YXah#|x{ z4IKtL=oC1rPfi&cnhq@BfDupRrYsSWKMs~6488~9Tjou!%uY43U1&6mNm-O0P%R4_ zQ!XD89LaWLTx({#+2>{_8xvi2Uv(uBXS-x>OA}c<nX=n+6I*pg4{z;WBhvreU zz#|Gym<1f_Q7!)kG&5&fnB#| z#dVy0feYp9*gBGD6&2R1dCFTr#g2D2BBT~U`K5kU>s7Nb7-Wu59hUNmc>%|xE{x|f zU^@u@KnNz96?-h=%)$nx(A%Cz|J(j;C z!_A5d?Q(iLW-FWD#n=MM8C_rtIz(%|$5KiX-A+Il7^HYPAMx%`6B2JXOXw`?e*%~j zg!kw|+nDwmwye+40Z0|wB1ub%lGf)d^PVO1uD0@CYvqkVQo2?-)pVHmcnRFn(UFH# zM-Jg9I0{b(<12uJ?*joIGsUUL=&+uo$03~Y$KFwBU*rBEN6K^ zY<-p;+{_B0nB1(^d_$*qTcv29gSbXyVtp9+*D2XXz3)IfJ`3$Q)zoMIRb}SHG708+ zS3;>^?8#nnJMf!eh0^HEE%e+&2wFXZg96YwC{+Pi{WgM7$sXCI)gp?!OkO}L%&kqm zP-SBlREtBQzhdxZPDbX_qoJWD8HT~fpRKTxYH=*|4nu$T5rZ%`Vj+I|ti$n|QBbRcoKdDFv{jE*% zBrOhwC~1+LTs_Vz{Im(EOm^A~kexQ|lI*mn62jt%slR98`Z;isX;ccq0I3HZ;O{FW z_%Z~V-b#8epf@1LU3mN5>BxGu575SY_v1J7r0?q3`F#SD+<_!|y({ym|8v8XumK6% z;OlQrJ(0fg=m+{IC!FiW3WgdIHzY$2n9`Bd2+U--$pN^r`Y!y6!!-wz%#`KnHNFeQ z(X!9lArv*A#l`<1e)TFZrF^kp9P_0xkc zaeUaovg5qf$p5#<&R~E@So)f_IK3@?(d7{Ca=x<{M|qxn(qH zxZC_{Tf>TCn+Po|gV!Ij+SYtTuzKgfm9_~sQMKeRE8D8*Jegir^k{mc6}`S6$?a6p zS14*L02ih9pR3)8NZP4(-;=d_ELyu6;&|DovK~K;iys*Oo~+%IHGfa)sPoZPusX^j zgfWr8v^#@BeiJJ?^Ehg^)+P1~yS(hARl9#ZrFPR*rT%fXP0QC+>OWJR-<@OC=N&*D z<jb^k-eg{g_7 z@@$W%(!_SLMJntW!n+TnY+IXcTA?)6KCspfJNhL2LF&4{>5TOaWQ^h6XO?C*BMSLm z|6lFxa=A$yH?EEhh~}qPe<^aMeS6O;(3$JXZ1qRjJDv_qasWAUsPOL#?K=&x2tM(M zoc_+uXon8p&j2xt4 z40gu3FwP@KW&k3O2!Dc%GJ}g=v`twkAEGl6&2s(~Zj8OI>|k{MIzt4$lnlM0dXARv z-NBy*{;ah&+#P6bZ?6n|0ho+kdWqYil_#>{%T(stk$aJW92C65{GQ)q4P*;nIa14! zYy>0O!dDsfAFqQGyL{&==w}$TKtaREb|lg1A25e&3XyY+lC`5s-u2zgum|%Z55oG+ zQK?#XKw+Yj>l|P-yembXG}%0ZkzQiZ`yA>SL%e5{vyu+8x(u*#+87>>?$e^a^rgQb zmIE=_Geiea@4N;&1{q7-WZjcwq21Z29^_|;*VYtP#uV{Ut8-~U6iRu9Dg=gE*voVY zOOl@#$?ux2H4pzG(qLe~#m%k|rtD`R3Q^hyleTj$+FDVnC~Y=q=maofNN^+pOAK>@ zurR@-o-28n3mq=`5#^x+=(vk9mpqghz{Z4N;2~;!`~_v0^m$9^L@5gW1=;AZX=vrx zqY$M$ivnTWFI=YT?N9;wZYddJueRoS>PVY+3C8nMCj#VAAO!D*N6jBd&aQ#=mt!SA zj&&Wf^8zI-!whc<%(2I{axT8HDy{82X98E`#;+8e)5s#(Cn@QXU62$Y*%`8+K^dle z?55}=CHwz?9RxaT6rIaGrAxUlwg@+Nb(EW7G36d^fjkL}UCW(n#Z9u3quj}z%blvq zEg;US+{x4!gMjO6%H0pqMqmh$%T^O$KC0Yl@Tt-=O!)|Cm;3MkfpQz(G<4MGnEAUi zYq%|Rw^7iHsk>UZLiY1;XQqBUUVF0E@bAWEs>?9T$ZYYQ+ev>aYxfJlCu98)z>>2k z8RBn5vUJ1yA(9Q8vz+?Y`=Qi@5+1>XZzTK{316q+8)D!a2!FMNM=;^*2+tgsNloV7 zQ3(RqBIO9f`z}%rvByU;zjvAbdU<$fQ%@++E<#1zh-LqEyQ1C`js1 z02bEJ@mEQx95-VclF$?q^%zmCo&;p33}yKS0Tmc_etc5l73qTou&$rU7FB3M9MS7HS zB@(4vN5hA#pkf%Nd<3M=lwqu(5|Z>2Od2gV_wGcJRe+EtNlN}!B%Llvav&#*BqC8H zahHZ7gkj1@Kt+Wz}!IE---TX3r{RW_SuQXK?{3`Daj+0730BIa7s zsGvWLLd!<|QwfbgLN^k+jUgp<3c4W*Et~Y+5*mSot|Rm&3B4B3-(y>C^<5;FXFJwo zI@?D3}uVgaj@k!g%^ zr?=L$#?7t%-EV*U+sqbC&*5IA2Nh-Kf`oDO%oU%+XJ3 z4#bbuKS?~g69z<#H;rPqSa&sxa903F|-GumMyXk;MKrq(-pP#>AOo9PwpeZy}taP+hN_nRJYaQ^h!%3bV%%C=|?| zq+-V@XQ~3q5##m|Xf%O#2eY$O>}cg+uuDu=igBZxF~spjU(0$tu>PoD>D* z7UNz4kYwpfGizmcTs0?+S_y{fZ7a1v5KT%6$Biy5@e8MzhH**@)*3OvOY3AGXH}*R z4VC>Gqxrr5LlA5^2>lfAx_!tgcK?Abe`!4K5ob(r$r=3ILllPGvXj#b3eH&67bk1P z_D~T0hB!tbw*qP-P+2>El8VoBwr3vI#-5B~_=u4_z6HxQtO{pD(mO}}u>hz|7fjH$ z0EZ@kNZ3zXAwp)_&F1JA*k4#S^IoF;U3&e>SbiG0GZnsE$~O@z`Oa1HovY+KcdE#veCJZW^FqN~ zCEvM9zH^m)=jMn!%6Bg1J8yR|H%k$vm`wZU8^-?>V@bB8c2wZid;-e;TTVBt$&4 zwk6_iJlZD6vdddbg;Cb_8)%!w=Q%ehaP5ipnQfv$8yhU{TmFGRiHQdzv1qMnjx$GRG2buv z4w~YfLGd7(Z*t}qt(=xJ?zgclCF1?iSc0{&jc0?g9;C=TqL)b7PHIeDM zmVNf5GO5$B%?(vrkc`b)XbOIJ`3B#2GPnCCS@kdNKj`eYhMoXMu~QFvq#$@82${$H z&5`rL%E-V@^Ce|(nh$u(-ek8Fb^Z-<-DOLkYRzhoU@%KI>R^^?=~+rEU=baE!7Qag zvWBQPsYrrZO1oq!O_ZfHQI^tLSyCYdvvO2|Eagm6j?#Wv*Q>Xw%9){@nNGO%S+`gx zjHCJ>D!GEhOOLGCi0Wcz2IJdXFQU)OmFCTRI6j}Af*pPN=!)hnHz%}<$tl=66&&`k z%a>5|nR|*jF867rZ+Gq;_Hc4pdwU{|C=4*NPOz0Fp@>MRSD(O;+?bpa*dR9g--hJi zZMrLCLwe&MQ6dL0HM_@&paCxBCT9ly{aDz+S0VA_6aXU7*&u>7pC=h9Z(l%rvq*bn z3@E`wI#{}8H*p{gY0gGPu-LwI;oXeoXQ`e$^of*DfbHuKc`pfhe1DJhC!jixOavPd zQ~K~N7^gP+F4WdIQ8{YCI`?{*2DssY22RdwnK1jxq0~WwB-Gc)2erT3*H!<0-76XWV46*ma@|U7bZfpU4h@uQQ zLci#R6i^@E14zaOZB0$b2|)%AMlg%B32w}Kijv2&gU=BK@!*i%&vrT-SMiY0Lsys; zC6*khm3tC$K0zy=SGm18+<}ORG^1qr74S_~vYBZ!TRj3nnhi-5l*xa?I!N=d4lI zs|!Jn&=*C3{ua51CfxN6fX0-Z@x!K!ws)-@c=(&)W5727JnTW`gcsoFYbk=cDkkA0 z-asZr8rFVJd#OFC{;g{*02yinEsj!pQAc0g_Q2UWs-QQ^m&+ z+o{gyCh_F(*Oz2UP7G-cB`E#row2(5cEK8tW>r}m<_Q9`u-d9gyf{MXw|@iQEIA65 z&iMww&I~>mWPN=pIx#qorQp%5@XM0MS7N0taN9TFvT58s`x^i|(^&G*H-g6s!7PA> zq5K`;I7#F3SQ3shvC@l zPRo52?t6H);#mwyKO5RZjor!t)vY*B=N{uIdWtdqVq@0u^zE2W4^+K2atW=v z21#cPXQWJ*(Vp4h8|2*j74w7RY4M{Uhh58BY{HbSU!s}k0Vcav*FQ~KT0~xIJLYR3 z?mYzXmWAPJky^6qHwYuE3P5(Dt8bwemYtjnqX+QeH3nm}3URv&_hH4a*xX`v(kkW<3CHp`X4U zL`XrvXWn zAEEEx!nccAIIEt{z;d+y9z%L-feS(Y*Gf$1lOp5qV?#IcT*ef4#;)`lj72|oj~AOT z>VPbzZ_V6<(dcOGW4#<`AzT2wA=$Z6Y{ecH!}UzrCvrGCa`_lBC53Q5#bzt?Z&Omt zF<6BHygTCqQ9o=khs*ojlf~h6XbXq(R&&wT<)s=S}9 z1-X)7m2w0?jQ~URR?p(`Z@E&?%3i8jlpMLrp5LnIRZhJ%PAmTvG6JL)xCCnnrc7uv zY#*9e1Z0IP$*h1B`_d=szzGV@YH1Kx2fi+*iiX7FaRI`%J4IS;(E^ms= zuc4d#euVrY&&hPJ%!$^|K8%75?k$v*1$yqu>R|wu24VA&$LDJKg%o4m_VQ ztxe=bfR3yu!wUZ-^Ia2pEb>%jWn^dcJj0``ObQ6L&y=G_G5yt6KLf@&LcK7l|5}w{ z?^v0Mtp3SPrfm_DOv%C+1wHV&Z=dccbu3FQtv#x(`9eQAV6mpXbhtPvOCY+&zaO@u zHE6Si{xerOO>dRmT)*oAQ-1;>fUNjeMm$mbiBb5dD17wmNoSJ)Z))xU_q>(gtms}r z3;9Y#XB1Y7w5YE8J@)NZ0%ug&6;avk7?ww6#~J;4d3G$l!Pz)0FZn7<*JVr7z~?_! zx~{aO5T6uqnl-}yn%2}1rYW_29aLzv>+n~#~ zA;$2Qo27;8fQ*W)&>F$IFJdj%J|^=xWdd^pG`5uQP*lF_s1~U|T*xz4f0_Q}p^MUi z2lDt1@bPM+YO?ni=$t#BDU>KN8IB!4*zNTWi68p0EB??%C|p=%e**#cE+^sw@uczKh@^8F19Za@U?(Ao-u54bgp}H!8d}t0lvyTxQ5M z2my=jA!o<=SJ=N)dAq&K$u^*{9RS})=o+~1_g5&iW%n`F+U$$e0^f!W(?Q7B0(NG@ z(fQv9PBz#~*a2`Bcj^tC;qc5V$prT&LiA<%<+(f@!I1m;0eK-HEtrb{!%}V~th_%h z=Dgbsn$R(vhBhk7$=u|-0@I4MQX!pQx*iJYFcs2S+Dll~{V9}9wgA*e{!frf%yLD} zf*XlP61*UBl9}y<)>?LU1Q(q_Z>`&DG@IYJrugfnWkfGkgIdYWL{Jas3ac`Z)L-|KzjtsR%v^CQwJeep#40LO=ea zC6n~y^R+;`OpSq`BfSQjfVD?=f#kQ4f{D#1{=ODN_vN^fsQd>A7bu<2-9BDhGjKxY z9&r*}@O>Ko4Px};C0c-Yc?1)XuOs|3=_Q&luL;tR&(Q*9G7O_HnUza>bRh!XBH=Qt z1IWs1;7BfR_kGLdXqa#qZIqH=3#ZKLc7PFvg?+|2kOv!VDvWT&i)OSM1_QXn|9 zL3;$(;yE%t2oHpViU=>p2u45d(*paDT`&PcZS!F(yd8Y_EBO$ezu-cEOS_}(voLjl ze*8f#fFUUGAs2Psh+Z8J0_5>+uIJ?CL>>wzp!av6H!C!!I>ik++8WgQO#h%&GjVKv zqFx;bsMlw5QEGkWMy$3Mw)nS2t`IvQI;+l;_Y0io-ybBl4YKf(I@o{!-)` zIX##Fwd9DLk+F-y-g+J`+L`6??^q9JR+^U%}7ar5lH6YjD_n zHdyC>M{=|{-JIdn)+Fo4hWRw|1k(Q;aSxdO5EI;4B>3JEj(e(wak{DC7 zjBz=cO}<&?y-u+Z)pC}8e1!i7QFsum(PEQ0nz>yo|0ytwJ$ikdgcz(JN8hS5tVVLX zk7y9b{U74Ie=$Q6(Dx$buz$85j1%|g;EI5oGd6@d9@W+y*V`}A0(D57xlJptCK6=z zJ~E5ehglRSX5?6yF7bPCr2}r6(8^&aaAa;3N5vk|;NJ<1u*~3o&DWfz_uqoiz-GKb zY$h7_kIOg`XjjTQb8qpvVvn{)(Ok&{7R|ng^28UJdqu;dy`qL2LwJY9CH`xXLql6@nRYnn1|`h2jW)O9w_g~k#27hL_K<%a=aE{qen!D3w& ziZyS^G`;oGCB;-x0q#>(RY%LmdB{AHjQ&?!SEI@!H}>6+e9`-~D7_w@hBQ(fI`p$% z{e<3{s4ZomWt1=d1;}x>wl{ZRmMU|N-g@hjv)GUV&myOe*b&V48NKy3Ex>l(5y5&3 zKLjD}2%H6$m^?YcN7!+-&hg*W5l;Od-h*(gg&Fy3kpb&$ z3LrET>WR`i2`;V=k$0@w`rcfKs~%dkHEz8Pl`t77u-rYyT>7Wikp>kJT?=rZgFHet zk02NqX{gf3i2xKQOLW}TEW{|-KIGDKn#03V~xL}5~ za3vDg$f1$fp&eG^paP7`i4mU2Kp~bg6`I@?C=BFd12DCMiS~24<-ZUvM+>K{*WHK> z;+Vpr-$K##W8cwmynV1(!9C_iS>!DsH}9g~4NIq9n zKZY4vR=e<)a$|+IZcyb;yAw^)xOnFng{j|9){n}s)P7Qrn{*EAwT)g?=ZIr)! zk#0z~$^QF0{srprR7Sla?<~l8|Fon2n~i{EX6ffBvt%iXD)p*$XsZM&lS|5$r2fZ5 z$Z;L=3U9{`15ar=yBPaB{GjgqBQicXy5p>kuRFJ<; zz$=3P1h)zry~}C|Vpb6X@_ctGby#$KY0GQW-jDM)wDqBpbe@|TGhD{~ZgDbwkACv= z`*`~;Tj6Q2EJu>{lSzwvo38Iw^6Hq6BE!XMZr?Qm@~X9k_GK^c09JULi z!D6vqp$dN@U&0hf6{7ENHYYdNgnJ2-*H@U+oI!af1ppjJ);qDAA6q816 z-bO^W8!vpH39~)w^p%jNI=yy?C@iN~y^aLpc^1m3m;yjvzM;<4$g{6OsY@g}siKsR zja&I>9+f_CDf_jU#pe9`_!^Q8Drz1aj@;0A$A5Vw$C=#AcOhhvTk9Zw$I@{p(C7C} zjG7^_Z>i!T(6%#@kEIH42E+v=C zUF4xHx$-ij4#{Qo5F#*@!1fg@3$=~ue{(WR({nDM}JoM6#<6KBhzGQe7K`5if>up%B0+}*t2#dUaAMku<;%h zj=A)V--8*@zvgPmSlM&CSme;&9{~#2&zYBj*QjR)m!mF*zso)|3YWuNIzS150*HtLZojd_Gc|>J&MxMtCzSu8_@4j(|H1=N@K-EOVJaY2eQu;2;iH zqeYh-gk)@FrgFo708cD0hA@^lQe;65vRs^qWnEF$R{$e3G3laQ0k}LdE93D#7ai0; zQMg*4z8o-EKq*wMcPMJ(nfQVn?&6Z*{`}y&!oL4z^0Aqkg6z)jJ25?xY zdM%kEw|f2VWrWHepLe5hq=mlMA-08v-jA{*ASybflp_l{Jbhy??7Xi6E?kWtoTmIO z9CMsgB+0SwOn-qnE{-ppnE3s9rgt9@DM~S>Py%R=PidF{y?(=+itaA1ra9>X#|h2R z3v&&}TU^aNKY!n8H6kf8P7?filwe*0L4v0sa}Zp-_^Szy2f?iMrval3Io1XCux%ew z2HuAdMS-{&<+jK3Hvc`)cU!vKm#rUPviKaNA{n4UUYrLuJ3`687XB2zvg6!=xOjLM zAe7k=ilBcGJM`vj`jq08hl=jSRg94ZNCRznN*b`j5qk5KG}D-73e(_};+p}Yd>%|1|b^?$7saCeB83{nR zZw6+ym8p^IWo-P{C6#zRUyZlF{%K;_rWS?Q-#fQ*kUiTr?sKEEi`_DiIsyvsW~S#P6}Rp@&_Xe3hF(VSvuVjFft z)EA*n!@TfT6n<#4A$1&-~VS zzI|2Yubtf7!w4cz+i9MYH0H7gU|ADWz65(CCOJ0S-bLS8z;f*^p|&ob6#u+84XKc z?~d_DuGpBlzWAb1H)LVw>jcb{2Ew4~3rmsfFeV}Q{;nS;CicoLD@aa zjH2hT&D?l3S;CeHHE`1&<=yJ)8chAgUw|BSErI^hujrRE1^wsJ&*=p03F^?dk@cl1 z8G}vJYmt|mns zpmF48573g~?{0u*4TdC9gdxq5g%$#i>TCo z408qoNh`a2QynlzHp}d6IIgp^;h?g6I;~p|fq*ciGuuYM>6MKj>njj|PDX)F+`MFB zcM<43yNmr$-7I3r>6%Ti)xf#7YN`Xf$hlp<*>oI|Z)6au`c%FpTW^1sZw~7%h_}4S zqvRM{d(@O0i>6v}zeAk0!A**XVYf-O&qhdN3b*ngk0lc8T~^9pGo_vlx#SvCtbB#; zA|RSI(!2<7$G~(wE^U_68&QjG_O`U%4w%Rc1m)rxiRU~#$%u}YycZEhYk+IB9Tggu zZ+6Ld$v3;?f0A!@S^tQ)Z(G)%$dqS0(;EVU>Y$GQ3p8$LQ8Z z_E-jv+Q=%rJ=J;q6m$Q{&9r}Gs-nLr)r7Rgz--deon7B}_+ru4`Lvmln}%zgf^ss; zrkR;L#K#4Xrmknq#K!dC-NCf@IH4xK`ibX2XMn6U_5RP(@0R|4E9p;>eocnEr2h=* zC$mj`p!Cb(`4@lW5jR85;kci25$_EWD|pPF>;J~YG?*kO4#9B`31Spq9A7+Kv^0f| ze%5jRt^V%%G=(DG^>}8zR$dD|g9QL9&4Z)Go?w6zZzwAVPA7Hfcf(}x7$F@jBpnw! zGuMkRioZYVx-8%2Vvl(fbUv=>PV)U(4i5VGu|Uxu= zUa-z{j-1|lS9Y(GSP!zjc~`Q9t+LatwbNB~mkw6`DyX6UwDP|e=@-i{?;A$`T1hP@ zN1%QVP;w^|up81VGb)wdsg6uxj^|t~nqRIZ9LnK4ukS!yY^y70$ zFHw^Eb0qb4?izDfO(Yjrt7zpfLDr4yI!k`?^3L+U6SJ_rnL#P<4=Q=*`W|jc>rURe z#CNK^H-f@%C+~+rA|)mc)hdfcdAIvoihMlEXQ*)m+lw6)mHI@+lf&PxJC^!I_BEGT zEPLZF3&A)9*j1DT|5sEIqfkXj(e4<{IR{~?|2?ICZU*{}eyBvg*;y};Z$prnb$2TX zk+mgH;2Kij4U3cKaJ4`pW}e~0+tPdcX_zXf>u%=@hfQA7`6~ZHipP787v1)xY3*lqeAzJgrd+zu2eBB z5={6cp}z_t*I3AhB&^MV`SQ(Xz%6*=NPY%g$b<_F3H8HIm+_80|4hS%9y!dEV^&Uh zsLDeZAbDv?i$g1iL56n^qc`NNzmL2(%AD*H`Ju?^m_pY(ai1jLESp2d2UzsL5k0Zh zNW^H`$hk7r80Q%^F4@-y=2I~h8yTFDGv_SlnD=57roHJcjMT9&vE4TUpFPOfFsk67 zZ>Y7J%>tCn0sF3Va_0U!wQ~r&3$Og#|3bFFu3Z;4OnGYz4Mu9*RNp&Cf z(nSVg_3$KFwiRziV*EmR$oyfvgo60#xZq#Zht@Cv8Gb+)NhbUPCfI2IWAn=s0<}2& zhg}C1&!V^GOibf6DsQw|gs|5UMyq_D+stG6LhsK8It)Ml0oSN_N=D0(8fwX0JUUdv zcw~DVu5CVmzOwU^`w=k=8IzK^qxkgnTFVF;+I=SG`Nu$tR`Df%jR#!Dy~)Dg-1K*K z=DkH8V;2Sc(91vI7H#I}$9*`G-gWeWYnsy6-@QI9J`s#8e+-z0CGuo;>zng-t#R&s zc!a{%dh~$vm}smC4X!zs=v;63_c^zjX|GwQH03T%=`?-3Vv9`3+sVX9v%)3@ARofhwU#~l3*MqmP0A$t!( zso1LuoK~6x$Srk(rqlk5G{c|FmEKd%KD$AfY#BTWrmY!d-?tTS%)%jX=SP^J$j*t4 zfo%e9=!4spsVhDgwxs)LYOy!6hc+O}+7iOywA^?3SA?-9AHM_VJM8+iAUZdBM4H>2=^m}GA0n=Ik2aoq1i_qZU+;FC58=siOBphV83err*Ql67 zAT`>z_H>jm9y0bOTw8{|qP^SnP=0qld#d~%Mp!5L)hygs$-KA8=veu6G9INK)sc5N zAO5e+zXUV zV9tEeC2oYBd2{+0m*H&;-+>&A>)ghJ9>vRQfK{JlE*q6BuCw`=v1J{VxF2)iH{*mxH9_KTPJzBqb+?I)5k(#;a zMEaJa+w}b>oZFz^I0DOaA~nje{}z-}Zc^Qm-q6(gHi8|Rw^0-{h(^8n1dpe?aQ;aG zi~PFKdcYe6o1wq*QAd>`zk$1xY6wuUxr@9SeMJ%{Ol^9NJM$y-zgzs+9>y;xZv~1l zEnd({COSHc>Bm`b9U_C0jJgg2!>{O3V0tToVY+W4Fo(IJq2_=sFsSbBAYL3ER?uKx z|Fla$Kp-*rv=bzT;}=i`;&7cEuMm>*)F8%q0{ECoqd1IpPh9j}+zC-`?gy~X(jC&~xHj{&;OurKc^1(yMZrU?|%-rI; z40|LCs>#7wRdeCr!_4 z@DAUeX<>Bwal4gLq9I>*fPnNb%(NG2Ntl5fMq1Lxxp>2wC)~MrY;|_7M?=fp>$_6q??XG}m0!5op(aGlaik{EcZvRS;?a-LGeq~} z8Q&L|L;i5L%ozU{kv^zj6sp7%nGGOpbX%0yRbCTC9JV)!vHU2R7>kpi9x)aho|47b zWSnvlV{x7?Rg6tF^3ufEG;}z6a0qrUG!QL5QNr;W7>BNjU%S~S62x?unB^9e(UTrT ztL;sG+*gRg%yMJ#Azsg=?5Mjmy6_*XeZYA&x>al`35;U}Ovc?Op3Iu!N$I@yMQlVF zES32Xs-Ydiw*v|;9EW`c8+m1l=W(IwH2gw}hHzA|1Xb0G)IY7pI}O%&hf|#D!_lEh3n{7uu`l^Eh*gtbd8XLs*THfO>l(`kY0X%hAA-aCiaN8yOS%Q8i%riuxvu)Bx}lK-_saM6+E|JCvfC}cW@BGb_r4vJh4?%>hT=cCcK z-;7eUfuDv`WS`J;T_n{Q!*qm&bFwBaFKkP|SaQJh%S_R&_VyIbshrF!sN3 zJU5g0F`j!0?!P{sI}@q@nep7==~OQNOUHAGWZAzvp4(RdB>%>Eu8QgZ{~FJIpP7C2 zcrF#u|Gne6Cy~Ry*`F=Bo+9^uWIXrsbtugL#CWbZxcIO1XHF3OzkfV8;#!pAe_}lM zBr^VY<$v1$CHbHFKPCU*;=d&SAo%}){7?BOd=>=|l-w4+eW1^nkmQf8;7%p+D z;Sg_}u_)P?kdh8-9PH!gi;vQ429G>(G?t=x&ptT~aNYVb|&va;m?F^*vOS8Jv+POnZA+r;`| z1Imuc0pDSN0_N+O-?xuV5u14Y`6WO_=l}mKdYm3k6E(xMvNn0;YzOZDXNY(-eGZ1w zwjos-Afomjd;U3`Q{-G+&loahr8sN5Uc$@012CJ7UQT~L)|-A$x16uNduv+! z0GXf#hjq&L(vmPp6z+ztW(Uj&>N;N0G)$8h*vbWq8cfEAT_Iqt-2OHeFy?UyBHdnQ za5>lG_Mw92zz5o6PXHOrn+8vdc9sTF(3pW!HwQEE)t|KG-BMP6_sO*QQ4kufd<*If zA8m^v$nfug&35h)Nl(3K8`fJ<(f~?urduwdkdnh%IoCQmXm5J>3boh*NYELx*wX0S z27=7ADr=Rb=I*vM1jOS5QPb3d%a*sS1(&ec3S%?2!w#-Fp6INNFKql)%Pp-6-!ri2 z;p51W{xD?X^HQ<)JRDU$8~2*g4D^o)kY=p-z$|UwZ~Q)M-P@dwJ0No1kpWz9&yshQ zWKRTt>}yOR{k*zV-NCkz&3F8;$;rberR8ctK~Iy4bCPSzr2n3$c4AAW7#XSNi=F>YsCBMK`k%~xz4TO z{Lm<9gh>--zNyK$X>~o$R`(09fk8Xk9(jp%UlVr3AGt=|1jC|-0t5p;OuI?aws=E_ zZP8i>sEe)xG|>3Vb$~7wMqIw`0E31V)|oS3a0#p*dK=PV#5)GFEsU(;UxP(rC&VVd zuIZROy07KHyj^XXw;MXFU7`Ks!RY)3Cm7HmU_`5y2JUK{?QY^F&JJUM=%?4X#9=I_ zWbVYG=yuq%p;!Bhf;zY`9>N4W7WOO9Pz}qWUQ*}4RbG+~-+AgoDbQa*u_?3wS&5Hu zo%>}Zm12(^qu zsS6tPl4@Mn>uto5XHJ2UrCQQhu02_URgHDr35Ap7FpW8J47%>FS=c4uK zekgmMzBNb29o>clfq93HZcE>mUTK^Ig@@EIr76ZG!erxS%4dGa{Zs^ zC7U__*UEnhvA{PSjFM)<&n1PZeiVmCmF&|3vne*Pt{0$wcNoxRup!?!sT(lolGdJv%a_JY7>_35oVI_4~9Tg?bIJrm5KkyYcgcFJVWcn7$%SlUKVhqxunmoiG zR-Ys+fP`S}=iSWXVjGgH#b4oF3mfcCefrFRp++d0_}0d@$y(rE?jXF^-TA&_MIFB}F z)@XT<@y0(wiM2zr?DE_6Z1Iww=t335=RACu6)M?)=EY6(tu9jL&~kzk&2lGoGAhVl zgT^_27#i;T;&4Rv=ZB4w&2!(Us)UM}kQ`_ity=k$ly>TXEJyeHQMUYlOFuS){_gbS zW?VD<&*;bc9FY3opdU#`7yUQ|S$zxr7`YK^Tw?$mxrx%SYYFOaqmd*RLvfTJQor4} zK`w_b#&T#PMoV-3n`H$oPR?Af7Dnr17DhMV+X&bh(Uc95shecoEs8ZK&CENIzT+rY zM4hcT_Zzbe`zyfGY_}IKr7uSQ?D3r1FHnT#I!F{2o*kh_n5f=dI{6{E30U^RR)m>q z!EF0jjE|QdlM&|9CoTX0_nR#pSR#FLnRp(P%abu@Sh;7@9X&L3BiyL|K>ql?e2B6s zzXx90^dO*|?7~pUA0Z>X&RrO8g2!Henm*M6$5(Gle?jmBQ(cii5l}4WOEQ^jR$=&e z@O3ROTJ@1E7ru*y5@i+E8d)BEQ`~M(iXUYM50V9vDiIit)}XG>G7_*x)|b^70%CQ{ z2JQ6bW$`#JhAmIHRRvd0yo+==3vm_n&yqj#N6T$B^PEif87Zs}9MQ_Ji-V76Zq{` z5M@>zml0;gABIX?IEONTb;y-%)XO`7310%TO!*mGbG6*5r%GSSBY^TW3OA?8<0SXP zBlTwr&d`$zZ#DT9^wuE)JMSdd)~;eYj3?D?q;iirRwRYIfWVA?<#T-&IA-Pa2c(ea zorf|531WS3me`{wV1h9xpYH)AA`#0w7AUZvlBrLsnx*vMAx zGUcIK`(&hf4RSVR4VSTYj1_W&Uz}MMt)sGN9f8pUh`io-UP6KLw~(GC_zZ4%6{s{U zad~eMBBZ#45YIA9mSwmays^aP=S`xGc`XIF4HOPUDKqqB;<{5*@F8$+p{c4BL z4I{vc8tjHQrn)djJ8h$wifaX$5dQ>$^{RUOs16MpLHs~5xVtfxmH z%3OLtMwm+<86t5(Pbb~4u#yG;$>dT`&!Z0^KZ6U(c`Zw*4YJLu{T0G&{d>c7{a~`C zg5@Rv?ak?KZB1L*CytX2$7#prU~M~Se^H2y5g%eop)(%G1s7i(UtS5hapdqrn3@p z&k-y;Z!U6|?I)GE6l0E9|>exhWI&R9KPD3a<@OtB6G)C1b!o>Ykx#_hI!fhcAqpF+NJCy_Bk&pzS_*~MOidh zSGC;V`6nlQxKEB90MCwckV>fsKz+_2>|@+fR!4;D{+@zo%++^DWksY$>FLF+09nymnT*&Rt@;ZxWI$G>se!$kP@;Dpd zQpt~$;LJXH%CKCaU#^@-mGdNPsPhdeL2nD=_#qAyup^(jS16giDw>~JdjCBLlUkdF z0yC%)DKDYkBY{F`6&cUnM`Tv<_d02HACOV2Q&p)#n5Dn=Arvc~gdl#t=E~)sawWZJ)AVg4++_>Z6paC9;ZoyBN=B zkxZr7vB2mExsk+H>}7ZjlP3GMZo`LU5UfrPd`&z{)oeYQzYJD162UbX2@``@my> z>ZrsuGK~_J0a92jg>KbfNDv&73H-0XOFA5&1LL>pQ@PK^kM@@9zJSfGj|=T#4koAF zY9(z=Kiu)*?=`0B06vn65A%(8hbm5hy9s(7hLE+V^bgCZPJn%yTWLIfW3M@48ZLrU zt$B>nC1Yf3u5>B{(fOV|-j@4!3ZXWq08_T2^R$LJBHJCzmUwW7y0|XcxFJPcm%?u_ zF8wQb|Mm#{XfJIn?gOQg2vrdure*T&Y89;MPs3v?(s#ZOw&1e6!RErQ+VnDG6eh}% zoAJFO7|*bo7DB*1#%KXBIFhFy4n&>hxiH+7A8?D(kNf2k1J(Z4$Y7|b9AwbinLoHS zCKDp(KZ;FfFLCo9(8Y5@Te{xn@((pMT(FsNB=0mQKH1Ql#f>BzG+2dBhb|NGr4vtc z>Pz@d>0hdnkeQ(f+G5ZV&k)=4ZgmclRVbe*#vV9y)##uHQDXP9>?o8yKfmBhG+WeL z7H_secRdvQZfP@s)VyJX^3ED0J@!Qhs2iYzB&hrzo#+DkK0xj68jOLZ&ALJlXwN@O z31vEHC)(TL#_adE1r#<;bJ{WeSX}X7<7!a<9Wb5Mz$DG7D(U|3qE$f%Tz>6Hozs`3 zYzA|H(6|qqDScO(51%k*oxnuo!kSOxy3|L`pcD3P+>uD3*Pg)l>Vez<(hd`Uw0x^P>RxuQyKpD?^^zYN_rN8F3sVLZmY9zy{=YN|icX)V3qDOmk3|eZVehgO|yp1qg!JmBkdhXlsbKLA8_>O37LWS{ykck0+YYq99rVaOP- zP)c`S4)4qU%A#?wuCXi{A$i zeE$^2;jU7qz|yth{$oT~7&9NMM&ewS;7u3kuOqXMTz!<|#OKito-uGS`7pb&4H;ECqMc z2;Js}UkDzHCL)slfi;q9mpi`aodt`q5Jx6+O!U0b+);syrRR}})f~D>9?m!t%04#_ zkU4)H-$=qKQ0RV*DkyN!_z4u(3sIlgSw6Tp9qYz{QK%F}>ANQ3TAWWt22Khe*4dG6 z;2!zKX;||=lJt;iEy@j{!G=jg5L)y@q)d0QE3(0m zBy$xpqYbCxpfIYt(6Fx#b;&`G80HOPXoB8j+emhTve9e^{f47wETOA0KuC_3OS05G z#38XJfo1irC1P};igINB{Ns=DDIr=bEJNY8oJ)~}(C^de*3O2u;QutBm-ORbqp(?VuL$wpV@W6O* zVSR7=afP4ztm}K%9*GacBl$5qkl{N#d?CKy3p}uEG|pS6V)U>P11%BEY!Rftpv#BN z0-m2nKofC5yzt||DPnO<%EDzt27ZOH58RI4*$Lh3g&F>}k$Xo_;nNvul*c)P78)gjGnOVH`9I56?DycRJWc-@s5|R zdTr`8SgY8EANn<%iuE#)3qte>*UQ#)cde)24E#nomWc}o?+3YPa>cj0f@Eu1ko<~X zITYUpU&k?(+HZ@r@}jJFt?ZWzWICvmPD4V_{QL_ItLA5$UGlR_L=F*R^NV?*G0+QY z6;1FvDn)Jbl$b_%3gWMXUUso`c7Yi)Q%~Hvd>06I6)xt<>ZFG~N&&N!bAduL&A`FF*^+gUaX3b@w6> z=Df~azY!*6x$qgTe}KIi)Y#xJM9!*)o+XI!xPj#I){9>QGC_wUO0n&qXulp|hCpHbQkH?rnR(R{ zG-65JIUYmpuE?x^!#_|#k_`mLP8^tvKq5tC2O=>P{_%Sx=S)9-AQ0_B-a7-y-|!9y z5AJXv8p3*vn^bSP41slR_}2wshbVPwg2+;dWjJHtjES&MGQs~IN~>wv_WSTg4-Kwx z0?YC!1`?_~_M;qkZJ3QAR&;>y&JiM93=o#XT$jXFdS)6R97Tpih6}Tx+jSz!P@61A zDj{9)K3bGSz{v8|Fx__-zL-&qbm1LzvtgIuf80=E2?=Evei0c zO(E!`x?e(OX=G4W@Htg& zIQrVY8!SscN?SRGk{R2u1}_a^bD_lf?Ke(!XMTNlcGzy$zTH zqi1~#pZ%g|g(#M#8B_W~H!`-H`yn<=^sctp-gV_@7I7T5ME_beKC?7=&$?m$H`z`m z-O{lmvhhQ_YLat^XX;rgo7~j1X2Dr_!y*uVRXywN$B~PoXZ2YDH;i2ZUd9jc7ND&e zn2*KkWIgNss2HXq-2-n_&wBlzIbKX0;{6+yplicM400kp>xM;XB3umdehYJ5jJxQW zsb`%IeY9s?4qcL-^=^0{Er)uDcLPjgdRFd_6p5CF9jWSBTNt&-5bpa zlae783(WD6tJ$IAETmDcZ*hMqR6JJcW6wwZk`22)A9VrR@=l(Q`XzwoPb~daX8JQU z{Z%IVnDbOiNUqOQeaemn#iv?0<9VtJfjDA_tnV;C&F8U>GP{3Rxj#DM{)8m%Reo|O zVqg!s4eR)sD9aqafKQn@J51l zaLv28I`Iy!={Nk7x*&@I(H+I;&X>_$6cgRs$RVUH74Kb@SdQ8{3XYAf^U>zO23N|= z3?Cjoa{UXTkNs((qajNNXKmGV)OIvZQDDDNt|Ns$S76sDZ8E6O*~jLWNI%LyJJLRK`^Ur^O4dWafC>zi5lq%1*zadp+>064@ zEvi_HMeSWDpjpH!AF?Jkt-pcq9M;X;%Cvz~{#>rZM!57pJNCw2&s?gJ@a`H~X7;E&O;0Ohm0*h^3mc-B`a2FU|@r9SC=f#aUr2cw#wo zFmvu!F?PlwU|i+S((uQD1q|+0oEO0;dJ;0W^I1l>ckOXIp9BCMx2FRAh4@TicV_1= zU^aVn=-JG5R{@1BNcp&E{QxiKVUd;V*|;VR=kr_B3voyX>)ALTeK7~}b15%q;Xrud zSRM<-2T+XJUqXM%ocoH(X*MDQzed`_3kSr&{?p9PNhp9^Yu!14C9!Pm>=kL5oms%0 zg@!+qB|97Ag3#d3lZ1U14$y4dc@%LmzLpq(XbS{=E)F^)v@kBEdxOinpX0Fa+%1rJ zL6(G<4p5v7S+a0oATJX9QJ7bpil9gDIuQ;FSN8kH;nU)dH00+o_*md^F@wPVFyoNE z^T*_v=|1N0iu6JVV-I{Zd*z^iSqKNKp9`1mKwOF_1!w7QO40x`d}A4(mqX8s>CJ%1 zA~n6a8{>lYy_8-(*gmc>u-kVcB9pP}*xA)%g`w{VgpA0X92$?y2u}fTm;2o|p{|i}oQsK%$-|2|=xLqf+d5V^o z!Zka5>ERTVn4j*d56=~O6&OH6lgo@+I9T{G^9bj*cZl(fH``!UVRLksX80 zEa^C8VGCi;8=IdC2PoAAi|KDr;>s3NdRWZY>iH_Zs4o13Q`V=$kh6j^rl+hgAIm&# zKbCQ4c8=k6hsy+q?B!A?vD>f|KP$B>;Cr-|M<(^TE44L zQrYtTZQK{{ACAP*ap^+F3taj= zcE#8~e1vyg|Df(GVXub|O|O07e1x?)&GxVGVYXKfdp>;auV8>Lm>}?N;b0&T4n9i) zp8V|GYUzB@*i!b6(G?hM(Dz?sHl4xZ$yqg~V8+1h2(oiq_O`Pm|(v!9Sgz^TEF@B0Uoz zofT0N$-s0;C8HB--AR+t4!CV816#-#OP&s|&|MxM!k1xd`m_a#BT5RTS?*f#?Xs~jUYOC4Iqj*-PXb*- z=JH<9Lch&-N>|tg|GU2L!4ooXg)d#e?Lv1Ip18xZ?0NXgAqaSwW<{h2 zELV789g)08u*xw|4n9WfZ|Cmu;BPdg>@^UVED*8&iBdms2RGB77|U}NNz03AzI)A^ z^T7bDhDdp?GrR0*;cNa1Gp=OJPwSdLkr5e!JRL^%EJpU4H-xpAXd^{kt7i@z26JZ5 znRu(=FZRqM-?QrQV&z}{pp8Lm`Ij?0g*?!i;U9SE{bQ5|ng)5GX^=1};&27y00#aX z@9;G((Kw)|V;tA3INpi3jssI~$`4&%bbK)6zvj((NzxCq*z|LymFX8@zagw+($BD& z{%F`c&jubgd^_8BlYG>h8W@!Xe%w^Y;1oanQGQ&?I3djcz&pHwpWvx&1$+)p^MH!; zO^WVbyft6Ut_iX2m9E3;rb_x}*| zNa2iAk;vn}@zJJFuHqjIJ5T{Gqx_RIHcm_7{YgPU!qAK3Cg;4>8va9QH}(x)V9; zShK_MkL+BVVfb-JGvbq#xo!l^DNNwsh~w5GF`?bcv_KLa2;M4VGnH$1{LC}l|1Mrn3EA+mY#}H@3M?gWmb6Mgbz1kfp@nb z-)D}sJRhnY|NnCig&rb@Lfz!f&i_GU9j%XQzJ->d>t@*Uitn88@4E?qcmtl8=#0gn zO5P|ZCk<@=VPgy}%j$e$ykfJSzwx{(1Zj^CFP@64hem{or-mMTh>Ni?FN}VFBIhHv z4?EXnU~%bi&f(FDFUknp$Dg?f%as!#?2@&*YxUIdqN!cWvoVd{c_X;p~d1K8Mbuxf4%@+H|MV) zgFVQ$;zc14k3)dyl+7r_nGdEw$p47B;&%1<6T{0VcdgFG%+S&oT0YkDqUCwSEChL^ z_VFRaui65!poLF&EyUW(vlwrW!MW)VN2dEv`*1!Qx5L1(uGQ9gyGD|At0#w74p`m` ztxgZwGeV0ncHfP}W`>qyM38YUvJB!_A;n@8=A!tXO3aAoOdP7p(^Go3(7lN6z-Byl z;R9~=&nO=#VuAF+e`VeG(I~B&rRPlH^Z_8 zZ7OY|+DfnU--!v7c?K&4u@R|v?Fo<=$AT4|(JWt|!1cIWH$Jn33%6~zUEmM2D{t(_-Y?C`woyVCt<;$n;sH(LT@p5NJ3k!k5# zZV6RR-GvY1CZ|?T1Z4lSEL}E`cV+n-Gavj0g|}xtzpJbC84ilxxo~ zVU%$;yl1t8`2?7A%%pE0v%+`WJ_gwou)GnLnUC^Pc*OI#3Pi^83NMJSz}1#l;_{q@ zuK{9Qi75(XWn`!e7sd{-dB8%7mFasdoPrx1x-wG2r72mR+eWDRK5#z#RtZ0ballwb zT~Ub(mBv7g!(IuODAC?wf%jLVc&(7NaL;t@jbi^wsgCYZ&cDJ zvE8NHZ`B_J(jf^1A4+q~fUyzQM^V1e-dvtxdtu6R;gwmLm7h$(=Wc7qhR2|L5cvcz zhZbiSZVv?353MZ$VLRI1_1q^mrXYFN8d-1=$!V1Wx*Jb9&&Mt#d(%N|hp> zb46L-`6uYY3&w|Ar$TJ}h|q$mp=ZM@#)dwE)Z?Ld+Roqt*h?VUm4lU6$j4F^nb&*= zp3w5QuoNHcb`FhReMDE_?`5w08`?@P<>E5&uCZe}KS4M3Q+N;gN)TfG*Z$0Pw=uA#yStX*KJm;Aw?Jpv zYga_ZasJ)l)RE@!`UX2%rCRG$!jG;+Y;#nh}E5!36@vIe3r+7AsXOnog zil<*Z+r{%r@eGRRI`O<#Jg*baZt=W9JZ~1yTg7vec-|qNcZugc;@Kmf4~XYO;`xYp z_KN2d;<-&cpApYK@q9@!dpm@G7o_oaeGx0Qv$&EDeOc&1# z@yrs>vEn&iJST{!RXit(=VbAmDxTTmnJ1nz#dD5$7Kvx6crFmn3h}HG&l>SuA)XhB zXRUZT#j{a7o5ZtKJpJO?E}mD4XHY!XiRZQAd7XH6i{}mEd9!%lDxRCf^A7R6OFZup z&mQr708hhcOp~m^v%3*`W9L6H5^lscfU&cmXeAL=tcM!!AbN)Ad7{UNJ|N<-zOf9x z?YxiZW}-WYb`#w~bT(VgZlddnt|9s>(UnAbXe@Vni8c^561_@vG0~Z5$#>QeeT(Qk zqUVTs?4$8C^olzRh`dBoi5??5g@~h&o#Tnhh{h0IO_WBojp!3huo@2^1;i^*8|M?f zNwl8mHKNCfULfix+D2qWm$LIwq7tG9h#H9QCi)@KCZdOlen9jJ(RD=c5M51_g=1ek z+lkH~Y9X3S0R zAbODKRib-{28eDa`iO{UY#I;4;@8ga0AWPBvCl}YT#TyYgE|`3z<2`cWGIT1G2Vj8 zgBnlG$*4oLnL*78XfDV5L~7WP--);Q4Q;&DNIkw5_*|&lXvXd2MFjjw`yT=oLD5s= zbtngv_(}U5;H6OCrP&53vA{&l(8kAuMrtwPxB1|Y0Nek@H|g7dLUEme@&gSd(!f%@ zQBMtb(pTdxenT6lq@GT+Tk0jSLBm@y46cu1JTHGk8^@&{fnsc+x)|JswvdEzfjP2K zn2*PMpXTJvJP=}W-S`hEgDY6o1pEzc95hlJiE{bikKjb8TNz>%6izl7o2Xd}h5dbL zb2k7J&1-fn@0e{)g9&XOqfG%GT%8d=VEq1f!u$w%7+~-*37raq)o4(S%b<>iT8{S9 zSO|W^#EFB!+|7_lY(pwG~=|*&!J&P-9R_IXK8@+{6+HpWvMp|g43Xm z1DWv|)O0BE8`}7*s}RwjTh4^m4TTdnhS3W}j*dr(u#AMGzd|Ey(oh>{lTDj%Li2rX z!wZOLW2Mbv#3f?$9yGL>Oq*&X{vD7C-!2{{ZD!Ku5700{!scCNQ$!mJ;>1gr#818> zX=F7MKLV`t8!y6h;~psXgW?yV<$OT=2w0m$d+<3lqMFc3mKC%l2D{~dKv~w~F&Szn zHLv19TVeBe0Oq0i?ZK10%M^j&ailZ{fQFgGBQKU?@E|k94;a6pjrUlP1B7$<;E#a5 zah7eALNOP_?>vA@fy8xFzk%jjWg!yGRE?vX6-fOf+GZ?r;1Xy$Swz<2F-zM}Mlo$p zXPG<&kBH4h(9mWYecJ-f<#>yqY`+SCxh_h!7|%kTMZn+C#;ZF~ran%g33GHQ`hKGx zitXj6^zQ*EW>zX~URRnS+HfjTtZf!ULr$DPvfn{-oVFQ+hF)I^8&M9)e&O4c|8n!K~>DwSQ%*avHj7IXP5jH176LG@>Z{%qQ$yycJk<@%!X@t#> z%x<25hT&X6vOz_5A~mCtLWU!3YL#X&Z7x?D5z%g?`6g}dR+=@`^eK&xntz(zd$ja1k@i1%Npc?}xI?w@qPWl&clNlDQvox%?{e!tu(@e2cgM_q4-7W<0;yN;5MiyY4AAI6axMP?L+{U zrO#;60>yG^FqYe)%BbNl;_n$!k1ihI9H@30G(tr}6toP5DftbQVTa0v+5{!q;7J7h z4Q*VRdLhA+43a+rR{Z}!vW)G}oKI8!PK61(tnbl=El>_k`SU27jkF2j!BmOg(8iCD zO`@;(i4K8)eElsAeuc+8NoyE;l+9uEXA~Z+RN^-e8oF6do27WL2@}62W%GU7T!BY~ zLosFKEe6IP0U7h>5qR(>zjVCcq{gp&dY76`Xln6(k(xK5p_?fznx~?6u|pF!ou~q* zLGv-mUVw&0$wD%&-<^y%rw+ypXs*^VFpYt(hMo8kkhix{cPrFQ1pMW~8EqQqd?6m} z&BRZ(RSf;-P~WHhb5JisiJvK)B4uO{kaZW)U^&!EI^&P>E*K8`593)pO#Mcr4W|q7 zBOpiGm~Qs!46mcj8DJ0H+)T}N(9q3~sJRWAqG(z;<}8LWE87|LsCTA z%}5VUKpw0lVIdS7QSlqv_`9ouC^!!ar>siiM?eQd)cp;L%r7T9r-6_*bE#>9hFm|N z8g@6#PzN<1LsN`*Gc_#gk(%XzhMDsdyp0Wb(Cf=cMibF40~?=1!*Hh2<|sT!wul;< zJb}0P4Q+go(dU#;_BI;O?FZDn3PrbvAx6UFG`z)cXycEOZ(^DfWg&SLEZO(UaLFj0^$>b18k!0VPYGr~w;|@F+$5|w!$p?6g zpNT*7v>5@zz8euTu7G0L_fhjQ6vJj`ZF~qd8)`E(HasHysf31Mf15Tfcra`+u%OAk z(1_pA#(xG;P8+X>j^UB5q7*Z{kEr7 z=ETCd3Yt^#7C&YIDd$#H35)M zlc-q-z}Dz2Y90ru&^DaPMoRutXxJDy@fIVZ!|)bAj=I>t`0%z+x=+IVR;@#|DF+6@ z5m0}pK_`@-fWJC-i_zw-Z*sd@{L`ErP3}5l*^&~WE%A6=^BnblkGI1pHyhfsvvX)t z>hLwzc^qEnLPv{ZmCFlro1pZx_`RN{Do2Z}Nz>MN9rc&GoF$HCm)DWhu)M|Z^0qkW z!e&%@tYu!W$7`LOJ;f+*@%bH1O%A`?(_*dk_^tCifflEAvMoE_5>fUBTK%-LO^Kw- zTHWaIx}4SucU`RWoGHdUcatmDFc*e0)z*1|mioj%^B5z*YuTC=25_ z((3RxTI)T5Ca1Lp)O9Xvlc(O{7sNJjNQF8q8Msy9S!ErT2HaZO;-~|^{2uFSuiNjE z^j_C0x6kkGK-_F#UU6%y)!owIu{O(60gc;lZE%3mjJ{2?4_R$p;!^IwImsbMOTCMP zOf#v$x?-fN5!`dY-E55UzLkBD@K)h`RH)l+u~GRg<*9Pp7@fr98|Al5c7GPDh`YCs{a zL)l*C6@`+K1UdLw)9A8#U6%!12+s*7=n~`hK~wK(2Cv;@=4v;x4+%sTHn)0wZqzrc z1I0Ve2+q8LmKK@Z9OOk!qwvY(Epy+|21e^l3i#bkZhr?k*W^Z#K>ZPkK`uq&FCxag zaLM{+%RvT}dfiOhJe6rVtZ2%NTsXf)FfE6bY{9}(QD`G(h?bX;`b%@(S56U4jgnl>3RwpN0 z7NlyK|DvF3M&*)GsBbOsi?syhO_4<@z%$hzl~9GQWM?6 zfZx>~?-e*|B8kQVoHO~`ATt^*PF{nnu@)x~`wZZLe7Q}&8nd5ocF^x)nlyi&f15E*+b%`n}X!aNx77mdOGI#17 zEh1+;t*#d2peP8a%DPyZC#9IZ%Q6(a_YPBVgdF$eZG7BJwq(-xFlWuQwS<$L>@Zm6#8AXu>1lDr7%2J}Gm_iQ0~WNG^Vo0S*3PYGBY8Ww` zFD0VVk~-0kN)JXb$*tnNUyiX0yU0X8Fm@@&(1mf8O=Tj97_uZ9(@BXMyv*(3SSFE1 z4P+2Vg&w*j5+V7;x(~1MER{VtocIz+MQ)($PPEZOp}izT_QUohNmMq;O182>J`ZDy z*vlS2CQiz!YRne}{EHe&(d{Lpf%oMtU|%vjc&__#S8RP!0ccw^!)j!m%o_wz>h`rZ zIXaRTwW<=k?6mj7J#^c46h!v%NjOMb+2e|?eONzq&pHf|=+uX?PZEP@ADk?QO}3@E zr8e6F)qyXO-E}NqO~mt5->v9;OGOtR!{24D7N^Hs-Ri1$H@NHVa7jTP-$6WWSFXo_{LxcTtqB+7+#8JY2IU?tmV49_~eVNPaL$%s3w>rRTln1ti zsOygX&jIavzRQ1599O#9_b=;pXvIz^hONFOj+Rxi%}`wVj+9dEPz)1dI3&gzcJWL) zCaA0~4zRd2xg0)MmB-U$AX7c{h8tOBEUlS0v)b>)jL&d-9ayI^Dy!#WB!P~rvRYYS z-VOWZm_kOWXBl;Zil*%OW*I5~!&_%8ghw@vUZ>IOZ{#%E?sNHDuqb11X*JL=b226^ z#3DkI7zSf)=j74GB!_iUopqAaI_aC%NegC8S~zP`^|VQovI_zxD`gHEW0KE$mert| z#_@TZ*O0GPM9DX;&C9n@FFJHX%?M5F3!IO6o82ugE9Ov41=b4GGD8DKJB;#Z6FHNT zgwpG2wodYy30obQxWjCgFmLj#GEh9^x|35(dfCs$1=!+o(utm9V$$L8dL133L1|yK ztZd1W^3pQml0}vC%IDjwifa~7Td_#tVym2Oo>#r766+21fo3eWS(^hsu~_3mHgR=B z`Dzu@f3@^LhXL0#qpZE&<>EXVgVy>>E8NW(@MCh!R4*gNW&t_qg_tpXGw=s zwKw#WQMS6;(K=(AI}I#%p|GK&4WJoW==S-zvT*vW)2)sM@IyOnb~V>QM|MYvrk>77 zp1$UE#zC%;VD?qtYNhZ>M$zok=>{z1%-&&b2{0~TMsq9HG+e%V zN2|-~V>6F6BSuA524gOY!rpBiPA3MU9TQEzp)5d+CZGEA>aToiz-OEC+D+d33f0IcZvTqxg8%#oWKSg{<|4(XS3f8kp&Z*WCPg9_|1<Xba{)@)s8?o zs~3w6q6~?6Bt*;P7K>geFw&`bW8tW!1#3K5JZ*6yr?LDsoO@H)$YGy<{~~~1#naU0 zTH?&>8Lcw3F9nG?bxw)7-!jBXBOgTL`<}SpUq-}XctEtv#er^L_8|1 z{ke8KmWk^eK8$U-;ElNBiN%ES`pRlpu_>`*=@`|syuPdqW`&B29xn~bxTUl|KOEox zmZA#+^Y<ZF>qir!XG1DmfY|NS6^$E5dYQ&`1^JUYk z{mYm9lir~?eG%Sar%UV{j>MY>3aFn6#f?Olk-8X)MwSsc!8*xEAzr+o$YQkObP{(P zt6*?)I*p~iXeu`TkFXfo+1OPaV==5asy!9&?z0V}0`DT6!f3*~stD%@Xb%SV(;V+T zc-P{cg+06M^Kf7l?|!@&;N61_y+`m4R^sp;&R1sF;D9XNwM%h$jd};plN@Y1v7`4H z-r3i{9~`vlzZT)(z3F-!p*$Ax{w~sqci;D5&i4(5VI2>5x4=E#RkvZIAMvo>ffG!} zLH{$v3vX)=Hgk_he14Dc@os$*he+@aZUO&J!24+&Cc-=Gzd(mg)BZjjzQ8;9l3~2W z_jd3cr{0TRH;ni34*mu4;i25Wf{%FjzlptUY^&G41$(@M?}1-dn12YqACz@OEIrKcU?biiMfgPyg} zuY*omX9=O9Ud>>B1XFXsT-4BB1VZ`D0hNb9HBdzsOBee(b!ABA1 zAB+^E*GLWaLf>mx1~(%OkHNofi0?M=>W_x8=@}!X{~6dli!h!;9G){QeJ>bk))$fX z7vb+qMq1I!aPtbnLK*3P)v%zxE=FpwOD*axVbWjLY>V;PER^-RD4$S!iY-Pu%nU02 zN-V|z%=7T>#hbsX(H7$ZC?`}4R6EqwP}f2I0BRG|-B1reJqooA>IJCRpx%TUg!%+3 z4X0_wK#hkw1!^i(0aOvxc~CV_7eh5dd7-X^x(2En>K3Rwpzec;|2+h=$Dp2pdKs!8 z>Yq^WLwydFo?$VLf|>wz8dNsaET~ebN~jf3bx=)EZBRj|Z$sSx^&_aepne7Q2-Fs+ zKBzxI?SOh4Y7bNj+QAH{W1y^1XF%maoddN1Y6;XuPz_M6P?tlkgZd8C%}}>P-2=t) z&h}9Mwj+NApEL|B+KgJLbXZt*UTGrJ8&yaARv_lYIj=CH^c8n`APP>8UAGLLfMC6T=}~TW<}8VC^Nb*Lj0L7{;01t>4hO4 z?3ehPjB;4D2W9YMw3SE$70r5K)(5j^;C}}6R;Yep{nPHXo^S2mY{u||CVsZVpW085 zMkxL310MXh*2#C#=kndH-fV06qknxS|AgV8#~}_J;=mye9OA$s4jkgZAr2hkz#$GC z;=myee1#l%Gsj|#%e5FMLG1zl94Zxf4AkjRXG1N78ihDyL5&6GFJ3PU4?PZX;1CB6 zao`XK4sqZR2M%%I5C;x%;1CB6ao`XK4sqZR2mViT;K-9RTGN*o*A&-IEUnF-TT|R> zt)9F5{MNBGFk3QrNf~qtThpuOE-7hE!(aO1Q;ZAdwq`6o%6fZuTJVCD*3?#>C^)*v zZofbuKFTp4KHA@tN2Rv1He>N+>D^|Za-+w<_Id!UtTY=ggAb$~fJ=rM+=IPh@v|iJ zfk(3T6?Wf&xEwC*=5HT%26YaXZ2P?H|Xax~5#$s{N`9@F1Ah zn2PTc+YY<)%5m#zO_rmThmb<=DRvV`L*iF~l-1 zwT6uB0r{1z>eeLpX?T{)SgGdYz3%mZf=?Bfmb@j;^5 z>I5_Us`hp}j)&t|EI#)4ci7vqk;f1NEraSFi}u?tzMrtyH(qLA6~KpYMv!NO6oIsN zy1d?2!HX|@XrwBgy4ZZV zBgR2Wua+r#Ai2lP`2#q+9PF_u536-d4?NkyTUDit`1K`I{aPf|GSTt=9%!PUQ3X>J z+%&}c01G`k|AVT^9$vMM=vIbR;dW`op*k9Ry?I|d&vdp*9Zz;~_{ zb+)oH+TpV;&uY6oX>Ug%_IT0T!Izp?UuBZ`4+aQ4b?|FkY|Dw=-+H52Am~&G0r)czeS^@K#Lb5XGAhf?tm6Xp(P@^>4q1#F$e+PFe>! zSDkCGBj+|9fH$Q%vOT@y0Ni?gWlNk4_^zam*=g>5iWwV!`f|^K`=T?Z=K#FW9C#qs zZFF=p>|C`(@$aDna;?LDB*wMs9(AI6V=N=xVJ^NX!@LqT(OCznF%bHN-nhl*#%R;- zb&395X6+Nn-RH^9O7!yEl9S}urm5nct&E z4rOk7`clL;I^wo&HuHcI%>cDm&=n+Ni0> zBAQ*7!r8^rmerUl*q69`_`;jU-NINV6tcPSO+O58kcMub_!tp_Okj4iG>gto_+>3E zZj}}Rr@PJR&ZWsFWzy`yhs?s{4w^Wd>YF_Hni~{%Nj<-|r}iGH^>v8;qldbN2<-zx z+W=8pg1rw3EnQArT3NmVVv$4$j|gL|Irw6XdxbGSLT5NnD4mGIHlgvkT$j@78KLvL z@DV0-eL^P$2*!B#63sC}gscFPZCBb>xA6WorKRLJPlMCZL7ILViWMRn(_{xtnjQ6x z91lzR22BmL7?2i1yaKelh1S(v-;Bu~N}SfV3V+{M+Ga?DqxBx@wZsH`wQH}3-wA1V1UB0}jEi~3TQvL<+! zLRvXy0yX@m9~WWFceS{@?s`GZ=?-LRnP&wp2rKZAmV#k(OAWP)Al(LppO>SRfDTE4m-Qqi8<0ZK1cajpH%NqTB zY-+$`kdNL~mPkzZfRNXwr9`IE#!ab_ML*;3_|Q`IA;w=)qkZicT>ydn^^^nrn)=1G z1Dw^rnwFN<{Xv?MmKOYo&pte(skwK=fv4tPd~SMxskv?B0jB28k!fk$akD{M+FjT1 zxd%@aJZq07IHI+xsC5u)r$t3YRru9zN)M*@Sb8kosXhz(Ua2JlhSSJwgjR2Mg>#lUljGE_N4_ggO=KR#E z6inM>$?CS$_KmDUTzU`dO$(0bKP)(+D!Ztt+me-)jdyDh@$F0NMnnZl?X~oz6t&90 zvWqs2tf~rH`cm*`L9i)kHmICX{GA1*F+R678d5Dr?nimcd1`bT9{fi9@4yok{t$Q_ z6n~_d2xV2c5(XO6Z8zMO;Z3*1cnSI*6TQZy=XdAJ6g~0f!0}-*0rZDqX-v1h)1+{A zhDA&o#;w&9md2#do({Ryc$1!3(^r}3H70!!G{+)r(i3a?A``vFB0iwWRrI|kdL4&K zc%ZR}Pd2VsQuO@pUi&|2@?T@pTWwPMKI22I>5Bk}>A%LLug#IN^hr-l8uF(IidfJq zO!`fr;awY~C*Bu*KWOe%^u+t3x8~w9Cq+-J>8nif(U|dR1r2ZTVSI@9Mc)gWe=2(7 zebHy-L4v)aC)V`kruY!^2CLK3q=*!g;_}(DHYQ314HvKQZBLz^7#z zMnAq$eM8|Lz#k|)0DJ_(B+YK%0)_VgGoDU9@I&+?b=d(Lr!Ym`17^J*_gZG8Ue_Xx zgD@B60XP$F<2psJ(_RZbaU~uaCkx97w>qrv12e1-Ka92^z3`v+^e`-9UOyfmmKAZ) zVQI{K@5cwf?VzVyV$w{6GEDTucYuccF-pNhg@eGPck+RsnLk-L5bu=6MiFp4e<-Wq zE|`mOfu8_gr|5MYdY~sJe>6@O*2(yISckP3m|-1b$_vWX_%+NK7V#6n@nQYM6c+LE zhsknCc^r&GvT&z@Mu&S5FvI=SlrNOy@t-hfxWpNw6T|I>9sOq-HDr2=;?nY9vU;wMj39%Qf`T9G!ZHbikS2olRgVHpDKD{ zO^>1wq1QNBT8*Mx<@A!q1<;oM|C`26%tdQUv;wQIF}C_(I_Qbz2Mi z`;=Q^oi3{>T^f@QLD0Oe=!rEwM8-t;Kzt&Y$GoPDn{0(C=cYtq%DPzwOuzYan($f^ z{yymu9tTAXD;aO^1C5iO;P*N(dHccZlOw#{G!G&@j+Fc%t^tnc&mi2=|4KYGP8Qak zaI3?50hnQZVrn0{=R@AkQ8FyzIl%E@SxsSSOy2f@KCIjlGd>fcvQ70)W77AR{3;tB#D$%jhE#)GShWybq@${6Lbh)A@z71H1HDtmq zgXoIi)4(i~=CMTfD%?6XLB$jJT;O$zUdOo?dSa$gW2SKs^miz? z#G1a=M6WUFDW_}ni83r=O|R=U{nwcEl;@SF=!rFbtEqfyEaKyVSSUqL8DN^8fSCSk zEa+PelO(G!z~Wvn0b08Ov4@IPo6*K7ZQHGMCDrq`JCl#h15q9@k$ z-3UX|YfO5|QQN8Li8Xz%iC$yUQ{LKP-%$Jk*7SWTQU5h2J>{~sDSBc}-(#ZJnDmt2 zcCVr*-T|!3_EKvUZ!zKAlcVO^|6Wsh&{(ARdW>5@&-Rcq;xv5_fVdJ5jY&`WaeqBo z(i0n}B!<-kI{XW_8q+Oh&N)EOu!u>+ypC^AXfEh)z$L<(9{9N=VRf78k;ZgOd3MF8 z%CLxaSdal1iJQixr`)?%MNhm7So2xC%?2Q@#6x4crEIE;kr1Yfm^4fms$+y+W6}?T z=59q#tm(C%@%~%yz+6(%6Ki^1Zb`2({ij^4g_C4_i1$TLxmvd=dSXom zO%Egeik?{0SEWcydW}g>nUjmoQ2YVb^ubY4dg41k!*MU=Xg;VgWm!I@Fy(5#rZ8n| zzN0YZYo?qj-BQNpIE5)^bF#vewK-d1%G<0|m@+pV3RCW;Ut!AL+@LV!Z{DIXWpLiB zFy(OeY8v1d6{bASHx;H#&W{zQJkE@%DvgxMsW9bo<|$0soC|=hC^!6l--O>V;VEZD zX|6ZnKLK;THg%Xe!dswmO7D#c)8u&USku}LWrJP;bGC=Xe+FKs=p%UtJu&k-sIbUu z(4RY9TapH~kT}^D27cCgAw6dQ9=um~N|{fjm~_mKa8& z4J7s>ciYn(GzR>T2uTr z7Q6z@t%`n=iC(9%l71?;r0)k!kD@2u1{}}Zy^TZqU%-XCIWq0UI&Pbk{|rlGh827f z_b)4YVojfAqSu)8-Jn^i=!rFbw~1b3(pz7`eV>Y+Sku><=rtDc0nLp%J|_AqQ(kCH z`o33iGpnK}*8W$S{MT5-XS-oMrQ-vv>8&PujY(ewnjMOscwh9jpfPeK|B3fS9|X-f zMNd2hI6kj?O?6gd5x3VNMpwC|tYRHjk*ROenDmrme4h>rSknhh^cs_%@{S)@^u(IJ z-xME>Nl&@RyA?gLrq_N}!a!rv*Y3o8Bv0`QSkvqLBE80>?*WZf(GzR>Y*XH8O!|J% z;G~CW(}*>Fk%?Yo(p&$D_EXUl?~A?`G(XqzH_>;S{MVTN4}#{Td>J2N?SGbuUSrZ5 zy9}d9(G%~Bo-$zT6g}};;P|qXZ3;_chE)XmKP$JyIxJ072?LEuPg%1cD0*T|Uu5!M zW77A4=Ewq>cH(`}4}#`QMNh2hTTT9JO#f?lLw2{KC)V@?#Eiejg8nVTcw>etd%&8$ z&*Zz|NmtejkA^iz?z)6{g(u zUnxx4=}#(5`RUsgrVRDn3R8}{agOwpved^aOnK^)6{bw}ISNy*dX=UJb}CHy>g~iM z!Pi-k6Af%deEGZGgda2EznXCBxl#J#O*r3#D^1vC!dIH`O(xu9!hbYj^47@*erQ@F zeEsc%9ld7$YRvq#eu%r@m0M!cu>ABwX?l%G zPg(V2ie*^DX9CBEl?^)li?B4N+pIn4cRlHm^UTb=*Y0RTB=_wO?r=lm;^i?MR zH6}e}W-lt0@gd$9J!NbESkV(}`k={wjp;vSaKEGIi8Xx{0C6QA8k4>jrstH&_z;tZ z%pa{8 zHv(e1)mXS4VKMUOE4RR!UgsC-iG!dK`_Wd5@jZokN5oGR<~nlLGd?! zK@{6f_-+&az=SU>kJA6lgx@k@#?#3MetG9%TmsB9T`Lr>#kgj*!aNi53x#>c;}wn3 zpS-6q&qbu2ulzX&=fo7|*@Jr&t|~%%SRrY6PGF_NJOl86z(KL6|BN!{KKtJkHjtmG z3#D7`iJzdb6}VL3pxBRIt8gvM?*$%%baC(aEk(~g*^!mfAMTkRqcHbC&sLcGo8`cC z%e~8W+8p?onjZ1mp)mLR4qv3`YYgMNz~m?Q+Kxv>JjoIi`)F4xob51-j}*2#vE95_ z(qy|Zbyy}Y|Ccjpgdm?{PnEM@v zBd&}m_cC%7t_m7PwZhzk=mI7mxW90(GUqlVX!QQ=zPcNFH@&WRUG zx4g^d9EG_KV^_H98H^30?8eDgkqIj?+DVa^l(tZ9H*_sDb3?r(Xr+}|em}9EvwE4$qOD~oF zb1dXhnB$z^D$Fs=kfs5yZ<6#JdpxBu#}&slOLLAH+zN9%@Q}i_2JWJ1ku>bbFHx9% z^dA*w|9dXlGN#u+fBJ3UF=_HV=dB9!Jm-B1^E_v-!aQsDg2Fua^>>AN?rV?2{lJH} zN@D?*z9)Vk#ZjT0Psn`yxZv+g^k&m|0>Ko zo-+KBhIc@nrLYyaRA7u-fb9y`0^{Ca6Uj+EmfHJP;F9}_fm~qEopc+)k5Mi7!v_E zD|{_*Na5>%f2MFZ@E;Yv0r*vgZw7u(;ah>z+riIF@DunXg?9kwE6nrN3l--1>NbUW zzWO$Wd9L`+3iDj?5gpP`p5>dYFwd3cE6j6c=PS(pqlGwR=0 znCH*$QJCK*JfSeZ#rSW9dB*;2g*O3@yIlHT3!JSmzqu$@nBO2QQJCK^v?$DP4c05n z?+9+x^wY2}PmJ=wyOZ8kn0HOhxk8%rzNQVtBZJ~@q-Pc8JyOSADb0f@Z%$w&9sd|7 znDA{T{ICf>BQaWK^g$A1hJ*fYjqpU^l_tE-gl{+D-6mYPHtKeR3BO>%Cw(hQbEygc z)`Zi7QJO_2e2WSH!-TW1iqZ#7_(>BUb9I!a(u6xr_#qR1%Y;wujJmBe;UAgsizb}D zE=qs439mNcM@{%+6P~d?>Na4)518Y(bOoKP;P2B=j~mqB@NHbLD6bvx8gpzeVBDb&xP?u5Dv>gQ0mK-~?6UlDnQU+^lt zuU44)WXhhzel5%n<=fYnZ&qXaQivGxO|J{Mo1AqXzXZM}N1JQFCgMn$S#N0^te}`8C}X3u&>a?h?pG^PSb=@#2R2>F(T_1!f|TVPCey zj?e$2U-b`@=DkNO8m`&*`qozAKRu6pKTo-{Ic?sYJOo_faX9fQe{~0ZZq^i#?J~W% zRbIr78@zqfSJZo)u4$0PHJySC@Xfz(da0|;)r3I3(`!7QCfqO%kyVne)Yae!H2J5s zLn55AnI7NflfCE$>yQ4nSw<FfY1zTyN;DRt$+TZ!D`cBo3b84sz>)=zJi8$03&y!D7ou31+xs1ibb(m5HaYwa z9`CT3Wh*SmFZil5OGTjB4%s_x5H+OBt*r_%6U}m|t1bW;IS`8Ifxx7LQfQ+IkA};P zLjT*~ZgSOmhwt-q3i55!n!jA1pS%J`Bj8-6Sz*gY(NQu}4^sMLgMnDl_+B8}XoYwn zHe~y($1`%i8dgLjAS-eq1s2)Q^SE0mFWnE3ayHum2~#bro?$;ojbAj5x|-*USk7~| zS3{n5qs#YYkp_xjZ&?LVe@#vHh#bL$nrX8o8qF|#jSjEN ziNSz>*p@t}prG(8X~?7DizY+XSX*ATh*pKWPD~6A+L$9QG*$O zLJHRt(l!rDKWGkIaWPrw`6~1ZUQtoy_d+2#646x$ ze3Um`;t4>m9c+|d3eE&KFJ&Staxjfi*^6nfMCGLhg$xG#?tS#Y`7?5JzoL>E313y` znW$CEmQ;9F)xbuMrRxsPcr2P!mclk~lV{bi?bwX`?3}M=1|`Fm39c+C5y?Gx1zh^B zYnt-D5FC}=Y}rh}3a*6Iq0L%SC7P{Vm_c_rib`w&Phe9**^aO&zHH}+8GHq1=OTfk z6x#ApjuF->2sRYW4Dx~F8?S5C@S|ad^3}}cq7m>xezckyRNC^9E$r==AZD}>bE`$D zXkrnh!M%!>Ty)y|V&C2uzT)S%adFUjmk^1Zd{H~h@!}u^cY3%G715R@#5;E`*URR4 zJUB9Tp3fjbGn*#_75&;QIQ4LyM2aMTnOU zG&JD;649jQRyn*r)ksyKl#t2ifg4q7>QEqWm|#zKfU}57NNX>zF0hy3hcRp(eb0wD zQ(WjI20CBYuw5qP>*IE_tJ&l2NM54ZL$C(;$~2!7nVX#`f}1yL6ehxK9qvIXDW*FPzP5RtxYNn+b-4XLk!xQ;vT|_Q zO60BuyAKzT*;`Qz%5kLuD@fa-8vEB*Kpjo1JYKiIvDuVbTvi2<)M%B&^(^JGwia-< z=<*f{DaPfz^a^=wDu=kN00mJ=mX~e#SHQah+`EPAKFX^Es~7`x8d#yVyBo?^I2=AN znd|o1u}ZfZH#yn$G`+kAvCD5`gX8ns3P4ehy%oPVfLRZmvuR?H&DZpHSp>?fOYCKZ zUKd(QS4+K%2^4;mwUyALuQd%cd1;puESP8WA3D+A4SF7N))%4yK>v?6?& z5OI0b-r{MqF-0Y~?g|?O=cqclw8hP;SprpsEdX^5o2p4mSgiBxOD>5zudwBl zUeMNfme$OhiMwGAXhOJO4Y*illA}g*jm?=MTND-hGGD!;)m6=L2)kZ$V-TB!^Ua>v zX0CGix%9@>%<2|5t}qifw|#wiW0zNtxCDD+;+B(-xM5SX8TW6vWYfP8J9Um#E}v?^ zWa}{lWKHfCT(Zg*%ZBqEUOgT`=L9p;uq)DA+2U@OsVeMtO$sRuFHwlC!u@1q6_4{H3BpRw6e6*KRTEyr^DU@NrS(QS)c z=&-lb>Zr$+tub}OmKVE#QC>ByuX&u5m~OUP#9QN{<>f$pvt^6PTLaFB_{+Yaf2@k8 z%8ST+spuv3E+&5Rn!IR&51@h^NS?%uJ@-Ck{KCoqBL2qkVW0W5H=mQT_=^;%FXVAd zoDV|Y%|vyQmw1}z_Xko4Q0>IEs&?G;#!Erj?%`roxlEvE&E=@YX!LUJOR8rQ6x!Vt zZd+af3c0D$9Z2v=+l9oF7>P6JWIMo#vvXVG^xT%XePv7B|y(VNA;blNf171s)ux^RD;eU)5N5=&dd zE-B^AD9HUvHulAek_=yMCyGJ6Z3ec~Jge0KQ?c|o++xXou9km=QyZCtn5C)0vi5p# z8Pk!-U{$2eWUfa`a<&k)$Xng$h*{f^OHwwQTEyTotSuWi^_kW=zQ#GWN6oQ0ybwu} z(VJOvLA4ml;|^8yVdfPSNr3f1j)TOySPfTEzs|`SmIdV0%oJlps9khWv1W4LCf3X} z>8{8rbOz)>eOGY{Z{%yhNj8ykkuri?1K&Hu z76ozVYrGj(hvUp}X)-pg;!SNf-)cu|m7{~lk8mBbqL8&jl{JS?a$Naow#yUqIvJMP ze1_X6*EbWbX1aZ9jWp3Nc9l^E?{4Qp$=9`c$@49k55=Ts@yiD; z2D-y68q0!U%R?)?sG$MRYCldF;9B;0=0_qW;J+dIWYN%v5qF^qAgZRDs7Qvx=y@}z*>E&{Z3r%bKMs9LLgh%zzl zCyOz_NBf~1)O(t-k%L{iJUcFrhjm^P*2$2w_stj90XNuF_V!0&4}9au}9g0Z|nT_K#Lpeo7nngB3m79Z#nO^my01{js;RO zG`f+=r0gwyZowFCfeJTbi!;V$b)_9N++b$u{NK+qP9Y;3u`;X9OU?_yjBLp++_@}H zRVK}2@FoZQ*Mb4edwIDs_IYtuqO!Uer%)EMu;5qP`hSQKh%(z;JC?g0O)RfCCnNG% z6;#0-xgXDx%vA0@o0Arh>Ur=JxnEt5HOc=wCEyDt{Qp+$ML#LqCDzF=T3P=uU>1SaA?rq>7jpDSlxkH*rZOKXG}dAaPx2W}?Hw#1$W#Epd^_mYZzN zC&~Iwl659qUXryTtOLa-D<>zBE(gnEk#SQ+{-u?HrY5;`Xqtr;G&|aHls&=RmfP%Z zsc?9)oyPC2li54khqKRv$I5=G_MoO(PHm%;a^bHwjvXe&TA9XH(qdV1uhh^eJ_JRb zECg+p5Q6e5nVbK|-nYO(G`&Q2Ts8H({FVPc|gVxkRoU zN6)f1ck{nTm5pqE3v;5D^(XAPS|&}J@ISZ%oQR|2#N~SnGAZRmvVN3Gnxj5eJ;<5h zF~PK#ov|~^ql0DdI*u!T$vc^x+zI20r%oKJ$cH2A!#xs?@1yK~IBGb@37;PpPo6w& zR#B0AK4!5&Q)d;+RiuoaG<6R27tLFNqi(Z=HhWev=fq2k5HPqlpD_VCX5ZwoKKJpd zCC@(-7N|uqm`y$sK3WRr&7LrR;WVslw<6%L9^!C=qY`S0(bEb?cK_h$>N*%;!p*ZG zVhlEKW@FGVQ_ykVi2p<*&f#uU`ah?eo6g&QlO+*H9wQsczM9)=z0`W;meVDHe&Ya(NRg>*b?U$+ZbCA9XE_xp5+}w<655O9UZ8ovpj;}m^j2)-qF<} zJ2rkKdbEO2^#;@<%6RpdzFkMOOkE2?|wj(Co;ly$e;5yuE|gyyu+Gql?g+q!IJrt!aWb)nsknCAJ%cD141j(AkE9dYyQ z+`>#S;jUv#YsT*|bUY}?cFRL$Eja6_w1lx$(J|Uz#P@#33g9f3)Qrr42}}quO@u-|B)#YaCi* z-rB0Mb*a{uUE21G+7f}*<=Sd-Yn!OZrl@7o=JZ!j(U=>N0JO)Z<>n*EQ=s8^k2 z{C|H_>Np(LDjV3AX2eHzyr@96G$TGbP)TOQ1ku8bICd2*$%BAGAeNML;|tRg+z2W4 zTN`C!Nv+DnZH$lIc)TTzk7~`_HjR%CR1%E|q7{vgaX~GSm4?y(OP>He#*gk0_5Zx@ zhk})l*i`&zKmLfi4)*0CCVj`ZVVI?b!>u;HLEF}MYLhMZf@f@|>CDr^h~H z+~&u6VJzGHd1FA}mv%=?@m#G9f=4B#?#bu7SI%kHdVGN$KWH%1xs;{ENt%{EcG3A-aJ>$5vGUiqF+ekBw6uzA;k^AYy~4ND1|JntaLm`LbuImqLcQ6_Nxl0r&iHfgV58v8N_i)= z`|PmF$1Meps8G!G;D`!coGeNY3%xnT?(37zJnT~O-NRuJB~j`gN%58)dst-;LeE3v zdvrCmpl9=%1>35F`cZIST71XM7L(dxmdu?Bu=qd(eW=-!shT-$E;w8;{zG{dI3(_1 zb{|^iE|{2j@jt-SI__inn{S1sld!LYLsP=Ab;5Uy~-_i-zD?TO$Zg}+1U*~gzpSJ-z86-hTw33(xMC(lF|;W>LM3gO8QE6*yLG#*9}a!k_?(SGc+P+e7{^$-tDRAN+bDFD1Kuj-x5>v&n|#OEiNMf@ z9Eow0u-i?Ho59bPE4P)i05z6XMU(I?H2lS(=Vxbq+16ERJ<;jzv9r{Im9GI=_* zGx9yTy~Fm&Y>v4k6#ntu2CX7m;dk4_iM9fXmY*&0d+u9Rto~&6`xC zTD+5wS;Yx<^4PI6r$Z+*W5TTI&=1WyD7+Xr2jJN#N(kh)n{8NpKqELSVOX?+mto^G z#V*75mhcLb;7uQYDE#Kz@HX1S;(H=Iw)gfVcu*-y4cFKr|4bh4CeyFr64ei}_VPUu z9z;pfKkzXQ6q;My65co)o^F@o`=R+nss^Xdz&F3iDlOqHx8cR)5Z@2QC-%62S`r_h zgLr8PZ-osn)5eeQiS32Vi;+U+u;EFA971dfufc{FE5!FicmNVhvf)h{?;CGdjz>#) zjW#@CHD4ZgH(yKSOz>3+uITz z$1Qnb>{yR+%}Dn!BQ^)+$8y?F`~AVM6=3plEC*w{;g^pe#iNSnU#BCVU&6!b)@*zR zV8HaL6Q~cLI|twRo!TFI)~OSaN&Y*>;V2o%5bEJ`AfC%Hm^Ti0ItoDRzJ}A0iAwYv zoQ^?g5TayVB|mXG9s|LKEq6L@x=+cG0>Z(+vk=c;PlPYUbDoTC`_I6KosJjVNID&H zY*W9t|MB89ZBY4R^TJlfOKTs?LY!orE?rP*7smy$cRcy8D}LkfV_D+ra0*~>p>x2f zJBodiXAJO6oiJzooI3^#pM%+9-mE#(iU$mz1uL=f{Oo4`qFC&J8*r9^nBoCL6Vd^W z@NdE|4qsB;={N*@Iv^e4X$!V%fJ(FBlKyeH&iQx)Tz~N#_8)%}`}OOeV|O3%7?hCT z+2tj)GdaI%a{sFmd%R^ihvVZ`^-%KkcO{l`IIwJybT9ca_zVBDWAEUD_J8dZXs19s z1==alPJwm`v{Rs+0__xNr$9Re+9}XZfp!YCQ=pv!?G$LIKsyE6DbP-Vb_%pppq&Ek z6lkYFI|creC@@AhKMAG%HpA&CtkKTOcktbHqw9uI1uk=sVIB~V0b8>sxXIUF4-J`% zd?F8LwR&CJOoaIl!JF-1PL(&f+c&{wo*5}b?gB*Xp-#ih1JR5)h)W1!_bIYmzh)4< zlR%tB5T_AXCs&;`=?bOo(wvTHm6`S#o_gSg^qXC`y2cjP6v==6wX;ekHWL3EM(K;T zH{e~nu}aH!H|TZlMy4XX0^uqC>oOSM;DtFF0G3N&k$Fnn$ zT3V%*jzU|ROT2#)VkgcNG{C$ENBDM5 zvAH>u_&K3YwxMpqQ@3(gg=OA>gnA;OPF4kU33a6c{s5B!_&f!eZz70%yMxT;^mj&W z211cedT8}cOuf06!(o`U&lUkB2|Ni^-HNI_<{oh^(sZ+053cj&)CDg@c4PuBL#~s! ztYl1dy>6z>JrR8ntn!`aF>@y%oU*ysihpwOCkE|7WQ$~~2ohL?7;(Ca zkfgX%LX;gLX38+?o2&vW#4Re&AVx7@ZV^#D+u$d#aIEjCCbEj_Z1z^nvj9O3egs$qX zo3H8S+Co>fk;Ly<=a>P|IaRI8H=*!`t_tN0J*4SoZS=Z~V3l@%RiuL~kT_mO6(IXV zcJ?l^g_&hFkt@U#-$bLRC>7nCgDfS?!uBH-t(<{Z*|gA*TM-mz_mGXh#*QxAC`YLp zp-Jr(1pU^qLc0|WtHi~z?1cA(Wp`41$v zs(zzoc~?UDf3;oy;e_&?TbA#YQ2uUNzC8ZVp8qg&>k!5Fzs%mO(J_6WOpfn>Zi9%{ z&CQS_k*=V{Yp}1&*+8+~@g=71l;Sp-o}&uPy^HqNfuR?k8rVB=;fUZmE%-9Xu3LQ` z`N-i2zl-pqz5Vca;V5g-Ac*2XQ@VC9OyrQI+fvMl`oz>ly0adF%j)yhrzr9_q*<;9 z15LfPdrMTl|7wx%#{_*3(iZLgCH^k#XDxd3070i|_j*;43tAL;W*dr(lto^L#o)re zi}rd_@f@^h@2?2r=0$tU@zjD5DN6cy1@fOR^EV*B7W}u0?}PMk3gWFrPwi)wUA24P zlS$nIu&zsN&1!)pEEEAfj=`a6@hIGj6=YIW=9~0`kcnVH3;M};6`8+1DC7j`%gne2_yO~ z+ABahE)V*wX9QE$cce(ky&9_-3>R~Y`I4wwhsH{2kWOh}_4#lsGJlT1*9?4&fc7B* z5TbofXJ7*YmoTsnfnf|(Aux)8rxBRRz&{YUgMo(;_&Ea)BJd~!zd@j$fyD@X#K0m1 z4j>TrgR2nkNv4>p!e=sEsKWgizD|WlFzi<0TN%z%;n@sdq{0D)&sO2TG2Byy_c7dA zg)hW73x5liL%k$%_)8T&m*G!TcoxI&s&E;@ud47v3|FggHNz`a_(O*OuEHr~k)zr!;S*3NSL{M%@B2GG0%zaW0U!fz>lf5&ene%1KBir>5V zeS+VY_-(;-{wm77jo%jh1b$!QHy!b};(0rMbMgBbe!sx)_xL@8-+$vb8+lSubvOKa z;dd5(eeuh|???Cz#m|G^82oO78q<44rl6gG`bWz$Itl7^%r=}1bFHn#t0Q{Mbu z4TtARzb`P*+K@M^5e<3cPe~r3H-MqT&mt`*Zyu2Odj3@9`X$nuX9{*hwb|p^lV$6hh}PKp}Jm z0~A7|7@!cE#sGy-kO2yzKQcfe^iKvTgw`=YA@nH&6hiwMpb+YYK9oX;ohgOT2==Ni zgsx}U7DBf(T!_(yQuPemLTDbtwh;O)!?qB*4^58=A(9~`gwA1C*+OUp!?qBb$*?Vi ze#bCJ3hJt3*cL*28McMc1!M(V2>pa%TL|6Duq}k{WW5}TMddXZ+cSavo%sD6zhC3` zNBkbeuL8fd_`QbTd-#2d-!A+*p-dN)J{i9=@H-E`{`lPw8Sw|CJ%Zm;_&tx`%lN&6 zUn72D{FWe(3wf``ZxnvF;5Qk+nfUd=ZytUn_(5k7{WX4n!0)g4J&s=merxf24ZrvB zWB$b7r+D9mAGUBU_8W_~FXxB}^%=644{Q+&cS0wCf$OMqf6U!=om=otOj(Pqr+d3z z7c2m_Whhk_oR1LFAX~Wic;F_y>XyayHCS9YY<2oRQvY2`MrFJIs4@dT4mM9=ahzs~DDn z#nJ#@x>ivYXu8FpqDL_X7gXkKFwC9e)8`!ym$v2|?zq-SYX1>2TE&=UyVuH%iT}^~ z`p+T&HD?lrMMSa^pKvRo8Cq}gf#5F%`qGC3bjtYO|g8NV!(v}PbR!{Jz8Uf z8--#wX8>FSR=y(FhG>}AU~eoT8s-h@hI!&a0J5MMz*5{Qp05Ixq7MRCFk`Ev+qx($ zwIRgtr>ojHHHf`y>{2^bpi*pO03Guil*T+B(^r}MOE%Y*=*CV}>^yzZ^KHM-l@2s)l++-QI=BdR;s>e;*W>{>Qg?0GKM){c1J%K8@| z-^v1rKG`pUrl{}4#Y@NFz2u|(sz^uZRH#O16kS$Jr2$4f(2DP$8^tbwWUu}a>B;>Q z8;`CruF<0k40HGHPELQC9<5`w3(?=XoPorjQP42!ayEIfjh&yfdle)Km@g`pA%Raq zHp~}tc5^cq6{d`C)TVRw1(2Q@z7KuvDDvm#(rG1Ud6Nx`$N?*f-aCEx~K1Ks>5=o8mpRXgnBXqQN5ed3qVYFAm0 z%k*fKK5@*OdS1ibFMB3#z1F($e2=-`75HYy++5Iph3Nk*X6oS}*nX}ZBo!_}R2Ub! z9A0atv(~+$12B8i^&BgYbVON@2tY*BRy(e|GqNqJs@6YXN9tE zXIacFt{Y}^8^k?`GSgn- zylM^Uhm}IkZc&CfCHOQ4yC4P@-8E+E-1Rztnps;!ds{rzqXJpD=06@uWnoF9h ziIN_3m-wYD+(*L0z`GQsJ=Tzw$h3xIorCdw#$kA24og80NUT9q zJSLcEm(;b&F&TCPQk(#B`7)YPJrk_2&UHMY^Ky2A(L-5T;OC9HwX_Pbz@Vt-cA|pk z6g=IfQQzfg;Kv`b!ljgfYf2P8SR;tXkR@c*qbQW}4S2{zst?{13y=nFyw$TtmTgXE z!8xqMTFN40NCpdCDU4-g4PwbI{_HhFXV zYWGE3zuU7l>L3byE> z2Z%mE5`EE$Z3|t-F5~Ofpqvr9LR^NYyR7I!!(Q~=U}un6dd$znmB`@QJv;+w8rD4- za+Wee_hcHOx#=QRLYbQmw*0&i1pFF!F@fDHWcZ$R@dg5}l6x+4_|6jJzm7&hvtCfQ z{^N5rDl{;L&@;$|u9**QoH!3)J%blC_)h{Ous0LLk0?UMWce6dzib5Q4RashXKUF( zvaObF@sLQ%eqgqI6qab&lgqX28OyY6{|YU80Vr(ol*(fU^YPG4i<(T`lxJ+Zxw0?c zLVfmOBV}(PbSs!Cv$z{EgJ6m3-dN{;b0Dh5$puj55Dh@V>apAnYcTlbw6tEx4FvZH zUC<;V%DurKR>s$ZkX3bQx1k*WAvn4@=xPr3Zw{Uw3tB_65QJFTvl*nj{$D^O?R>K?;E?|eejRGPUVAzRU@s#qE=O0tJ zW8so#@K>N|gvf^Hwfi&Hn7s!C=-VK;9Rv6Qy0#G1l|a>5khtmL56U`Yho#f*$lH- zJ+=k{?~Q62tBRc>p+uFKs!&)i#;HI#amm>r{NP22N0&GrI4o$ZMorbY%&xHAIQH;)F+%v!2=IGHZ%jKgRYF%f;hNBFXLm70s;VHde_n;&u#Ns%f<=<*pN1z7 z**{y6d?fv|j`_hbqDlo~{qq*|4u{u2vs8_T-9I;~{5ub`fBG_e+x^o`q1-4^Wu7f! zg?!eDjk{IXM3o5~-4dPeeQS@XbvYgA2 zc8(jag&6r59p3o+2K+z$UFO_CjlUa(zwNe!2B43|IpNnSY#In0ZzBUvF3k4(-P)9yW8F1#9Uzc*GDpB zxG(mg>m%o51K6kt^2&RXAiMU0AVWJSg5;yP9x7}^<14x3uvT*AAvO=EsRU!>%=^GI z2yy0pK&@zoJSstP!Sz=_vkQx?C#duR?N@Uq5k2vW@IZz;tFVLNUv+1lOVbhdgjQ$p zk+b@F_rhX#w`EEK3oH}balcVLcY2|W~K3G5eqplm^tp8b-(XM-O2u!);h^8uL{ zTFr`hvY95F1QH5vWa~m!qkOE~$p;pP)t_OR+oM6xuJ#So&9C%DA4SP~)gPtkDW~Zv zE1P7#J$m(y&ibNHRobUWyR<2CV$PP%W7C6AV z{?k|hW@CfIqy)^q4-Rl+bE)Y<{jHl}RO0c6y$7}d2sD`z(N;ni^@*dh9teP?n6Pl5)s3V~Q;ZrfgQc~}2jv5uU z>OKjOu*cpl?OOUk%6pN6dw@@|M$3%tg~BKP8|szNSy1}L+aIVChPg0ZEPNDTLJKiq zxA;FJu%F$9-EA!u8hyJc)Mq0GGfW{AJl5oTwLeErNW0(uj5)SZgL67sPB_Nkg&Dr? z#Q9W04va|e9qCq7ZtqI|EkSM*oskx;VRa`1cwWt%Clc|s?MdpzhkuvN6~93CWO*2; z7xiJ(Lt=zsU7pXOZUzV9!F4$vhWVBuEfno#9&P(*D1;vt^=>TggR?0d?J-%3wUMjr z1@26PI*LOhrIr2w5(ab8>2L9&%;TQh%t?0XO(?p%M$W|%P6$iKDOijbS;QVD6=$RD zmN#YDe8!ictZR2ir@w!Zv|5bh4lDb}6MC3uHC6wI4eZIJB;WHa!NBo z!!s}~8g;|DXMpa2^m}AE0Egtx#W06s>8Lg(A-P3?>KclgjHR4KfdRGg$a$AeXD`{m41q(4;J=oVJP0Y@M~5>0~!-$G1Ns^MEXj zOd`ubMA(@{H)0I3oCb19(hpuLn|$W(6sLb6wDFMvsJ;-@vwbT8G%P23E7wpcWhj&u zASH69)YxO8zD#@F>N1@vUHWK%}FZqSxB*Hj|ueDm{`5MiP@yoNSETw9vP?-0u#M#?lJQI zYdOFfCidE)AR%L^Qzm1)7!Ph`M5q$#WLDG^M`DJ8kknW`usR>*9URNGl&o;hUsWn2ZHp~{!V%9kIke7RVt$}@*7 zU&iw9BhsDzb!>nFiyxth9HkNv&ZAWQ%3}6%2_ly4|2S3*fPRCdVP%b20#QIGsASO6 zWjOy_?mLg8{yL8O0>qUeuH4rbaas_&RtMt4Sg=wad0yjVbvb5-;d z6+IQv;Uz4B*=U}JEK=N1 zZc^MpZnhy*`Xd{7y$S_wp(0^~tV$Wvd_oYE@pUpMDvseO(uhh0wxcnM-AAfhtBI+N z%J2V7R45NR$K(N!X=Bv?85x1hI9atE^%6?Rx=F?)j(V9;C$rkvFhBtxI9W)kKugsYph+pp&uHdYco9AU&@_Za+*L z`E`?S&Vhw-G0to6+Nqm&;x|XYTB1opsT+!83_z;I7Ll{ zBQglLPh$J9>4Ln5F6~c18D)0xsInJGrw&wN2c6-+AU!z>*JXw!tncOdt#0}oKp^8e zn<8C|P$v>X&#uv{_oo=EW27>)CqBTi_vC#v_XN)5)1YjTd9TgDCY@wOj#u?nW7NMi zJ#T&Sg}QT{p7*YdrdjX0J8r z1Mtc=%y|uB2$FCnI@hp=GmJg6xti8=TktL1LGjmau?rpS1lK5eZ5?$oo_>eJpE zWTc#Fq+Hv#MRInvXWG_5o|LS&BPZo-a_4*;Il&0snr;MY(?LJd+{MuU;}fv?bXzhYQ8K*`>S1BNOLQF3pBJf>tqm5%^pS!JNM zH_G{G%Tkp*;{Pae zN_o7$1~8NAOiWxY%m9+-3!Gn>``1*0OyVh&stYg()^OAYp2J@?Zh74>QGSjd1OeK-TX}n-iBpXl}Su>^Qkhtd#uNn;i17!d$V%D^BNP z)8Xr)SAW`3kK%II9(mTPXTPmG4wx@?OT`j)jO)OEPVnJU1ha4;e6+KaIBWVpU47(1aV#un)+0A_3hv- z6I|Cq$?k|Nc~)|O?*eqI+YvkLfPy8k998hVBf~ar+6K!c@ryfI1hxSn(j-cVi>6W| z=D&&I92NH9LT5J?4!O~z?s`1YyY2>b%v5%a+5_=ll-&mVo(B9bkh`K6)S|B$=X?0N64dDfgyQ%Rw4_N3{ zVZ*9(i6uZh_*?ZXxPb}KCBA`(P};9hiWgi>JY6NvOUCq_gOZgA^+Eh`{J(e->0242 zZzZMTlZZn(Mc|1b@V(1WVVuTB=-wEOha1+Pmr)6Ey*NlGi=8N$BBP=LO)u5DattPf% zUNbs8T451YC5!tGyHXUXmqo6VHRhfMa)C@#Ag$_8l7UjU-_N))l{xF|{(l%40Xt?A z4-30d9Y+QJUdqo+#mlPnJ0f z%a!Z`y4wm5n_lSHspAhjcZ|BdfY{+RCr;h3=8`-M%EN_D29{2Vvtiy5Vf*a3BdA*O z!W2|}gxKP%%uRtm= z;AOw&lNZG~e#N|7RrFc0Xq@OwwBywIGqaM|!ed8&Eg>;lHYwMR{s7VCzlS#Ad`$7n z?dL8$9njVEz;7*n#n3x2J$9c-+M~(ypL~OBoNq8ERmIIx>fH5c6qXe3D)|gug{3ug zk)aNH=<0NsmaM?*a?W1=1odFGw$TXrvIZHUVOjY!)6f1gC(2d0uaiD)uc1d@=kln) z2zjz@(zD;u^IrF#X~3LypxBCeUq;&*VnATKoVU|=zV2MFuS(hmeaLN)-11;cI_=#- zddeAZV|J~yO(mAYlm)m+Qx@)MJmzlk?Jv=ikb5Jt3^by{vTh>YUn3IhkH8E0vGo~e zRi?bh?C7tbqh)G68k<6_9dCni7rJ?L1%eq!NrR~N>&Zw3&9>C;#HdaF7?q6W)-`~+c z*;Vpf*0W?8t#msiurx@Z)=pH8BA*Z&-FiUAbi~q&#urU$+E|8MXunJvjP~!AI5_=R z)dstxa!0LvcSJ@Ml?V2x;jjwe;{fH6h`YN47`zwNhra;S`1zwcXsIPb%a#y9iJC08 z-Xeb}&7rA`=R!e=PRLqLtW0?-gQEy$S6wcX>tq=M134HY{zy>PYT1b2{zM{(HkC2y zkuM~zUy~fh)V^G>=e_1X z1w;~`4PbqUv@vBihf&pF=UWQa~ zaBk}=oRbP-uJQrfbN=ASISrOMQ+r-X&ICq8Yx(RFA<+eTm@m$>f8v{7xULL6L zfO`F(L0vS^n20m3ZDMf0ICSwC0EgGg`8#)ks~` z)v~^ztgot#`d+?3)<-a6FzdTs)%X0`!dr=bOvqi{Mtk;W0{}!u41hezZr+dD z^zgHMa9rE?R02e7q+N)$N8~CSnWg%{+IOCW$K*EJHwExuJ`Iq9O?>wT30{u7btcc1 z1ZH{){={=7+^V_+Oc&{|=5;bxqz@zb2cXztk*<+E^(JX|H-N<|@g-C;iSd|qGT4KF zu!(;@R0X9t8G+0Z*o@bSKCe?I)kG>IWs%=S9*Vrza(-G4%F6laTQGHry!k-Txz|t# zxFG{@L=hU3d5C!k+u$MPXJ72XQjjh)zFtiK(z2Jz&TFJE!RTwiMKjd9$?1eF}6(IWX5F3W6 zZy**)xPycOXtVbqB6Cb8(qaO$2kU$W?9Mn<4zy}pT4pI}>4mV|A%Z(GN0y-~fRe(J zq^1QnMCF+8kd&yw7L+GSL0N}M%m}zMnqbebm2LtlQ3I72yszPk)^fnb&qJPaDw~Wz zQy16+fad~Dsp`rPcGT-%=#VrV_qi!iW5A1^?Oe2s84i8Xm+~WJ%l?l!&uX3Aw!v5#bY&Brh$8 zQxS^1p1hu;^;2IA6zJTjF;eym+DKU*3l)#KPmDi7Em9r_TF_-R>!%K?nV@D#TtFla zE4#dn(64yDcxTEH6v==dZvInF@lOc6UzT;9!|{~UzWCT6x`Uf!+Y997V~R}s4(xKVw?LL@5ZeO?fL)d#bBzCD z@>Je^lqWLxmVgRI=yyt{t%cvYXPRZ&#Zso74w?34aZg@qGwpm0{ttPHHv;AR4e5H` zTKM|0u67!x)H*FbDUwDlR<*VU_dFA@X%ZzJCssn*YGQ zI~RHa`(|oEcvc~d&Pao9R%$qL+cHJF?@PJ3NV^q1uf|JYAMA{B5vx^P+Ci(hygQb9 zd3$^!T!*;8z6Dy49w7h=)jGm7*hU!A#u0v8W+>8vOI2jLT^SQmS*ms)zxk(IY1{uH zD^ufN)(88yR`uP8%!^Tbb@F>b+$R?3qBAmzJVx2^+!NcPbxa(EZ|{QReHA?sX+ zVjb*a`4zYDz%LIr*X#4k_W0LDF3ErToP4d~wZPtU{M#bu0c00|jN~BD6#;5uNxMi- zL_nfBBB$g;k-sj`bPn9FL3vG=hTV`5*NP0!SOI5fagTap>0D0;tL@=~T&0gj&R zf2x_>#o4;`Q>RwZJ+QAIFXHbDL@)AZ8m7{T=G7K=TYMd=tL_jvH)liSERKsWahV%` zPHv;WOV*-SQ3aH|9*A|j8r9<;MP4ia2d2PFk?>tVC-R(#O$76GvBP}-uHWg%n>hbU zc>#GE`dtY~sN0%e+$5i@Tesq#{GTW`hQX163w{VNjq*u_*z zfqx1LXr)gf#xTF6yf-WZ1tbS*6)DWpRja^eYJgVyYa)=h-Z0+<8veHlib4kUKv`z% z?d@DR3JOVGS<9>4|mJN>5^p*2+6VM5v{H>cv&ai}QUSX8?V(eU)JG3M#v z-I%9`Mm^*g)CK)<0Sf}!iwsCBXXW@&My_Ba=8jwLp?alxJr^ss#`%^Izz`S|i_{J2K^Q_T{Hm7CZ>s@+lEV@7EItgYF}nCRVz$=h$3@B1HDJ|W@4m5Sr?tLHcIQj|b&W+JV zNvH@U-uQ)GISj|IflkB`sR%Sp@K0L9i7E2v8j8TkLu)uE!uO7{Ld2OL7ew$#fGd;# z63-(m*F}4gC*=PZ7-5Onj{;z%C1j)@fQi6s{}nl(&PHxoa|`l?yK{HmG&q5_1RZn zQU5$`7`p`b(_ozos$6rWBr$h5f#FEO4GyUb;f4DRXnVK}e+b}Qea}V| zDn}t+dg#?$Zlo$#9{Dj2I2RNA#Ln1i&pqEhlCeu&nPkDo}23J``X~Pw_L0B?N`m=HrMqNgm=%x*lU1 z*Ts6H`*m}5CLgv}RUJl2p3ps5#QocA9-yU9;J}W#Cy++sLrC<<$%yDRuN%z4E-Qo5 z-*P__$@E%9@Qd*=WZpLMhxr8Ut~Ua&V8~3yQKKImuwN_vJzAk-mfN%5^D{hF>dBa{GcYRj zz^9GUo})<17zzg%ClqPj;RvI<2K$suL^K^PDaLzs8GR{#hu zq78W+#SLo&irY6-g3AHd2-M|!Ky%iF-Z_&+Lur3tRe>suAxV6J6TC>lE-izm6RQU?>X(-juDX&CTHTvbmk*Uy$>dCg zpK^xDVvc$0>b8@9yp(IE$)$3)*Ux>z(L-;Py9P#9Mp3-khN)-vs-NU;Z3@! zk{1%6$@Lr{V4<`G>Nu`tu2i_)<_ftT)s0=wb9|#Y z(x_g3hDK@UdY|iD?J~WN2pllwzV;`H)3R09+BjAGv?WeE8zoN5#79WV*(CKvaGe%k zCPU2_kv+ViDz?B`CZ0xK(sd%5i18@tc>`<(sYyJD%RE=$z`}Vwq%{h6w_C&*z>t2O zTrj7D)?wax(x;9}9E8MS=FULlmEB5!I&NiP+ebHRlb9P47rD_|+uuQ#*0~F0?rUW3 z42O1aBQi_JfC~Ob2KNDc=D=RnYa26`X_$I-vsYc}W>83Wqv}l?}wE zS}FQi-ws}_0GYd@rCiWf;u%{{$N68{KMa(+8=U6jR3SA>v2@Bp_-)VKvXuN;SicHW zj_mJwv&cSO;hhNL6N~Fz;>pdDed@zAAvj!h$QNVju36febUUW(rMSvsURt2KA#y%r z{v?$cX^i=Mqz7Z3S25bXy8tFoz0PGqY!zTY^Z>8|XZ6-p#58MPx)gV`JY5c5)%EFIw)wP_pSvPPs}-3pX>e1G3u$ZtA6#$@p@+l@J+fwd>pkC{W5DH7f5Wd6P$82mH#KW>S9jjxjfYI^AkIpxB5B#9ZD0x>C z{B!|ii7=WWO-X_@PC>efkG2k zMCcB%ncslFgcMq-z^hgLIjq%^7BgbF3KJ>uBNZmCM1K{|XV}i)m*HNBkJh-NuMb|D ziFfV3zeBAHU?ic~JC%e9rX!4%e-$5aY@*)eAPxl`>aBqfW$7epSju)&^SOkOJNnOv zQfn|m5&u+K2tx=}NpC`cLoIMw!lHtU$MI@a(IEbYoDn$NP578h(#n$b6K(}s5+F~7 zB>`xA4y^K-=WG?01n8;4%NXC8;UjME8&jIw`z^zv+)2yuNNDd`l|{Cp4+CX6)wM9-MUy z)CWIR!kT`d!*j7#aYZ27#kVP6tB3}o-Td!q6;O3|@xKI0L#pnIRF}K5t6b5lHJ6|a z-EBaw^?cz0jLQ|EGhRiN>IWTsXM0C@4YFOzF~%YLW6b`66!=mg%w}|4j!og4DLv60 zTp)~-kaEXiUKESski2DaFk?ypV?J}WEmR;1m`YJ_q7nsn;5E{P^heo{zl`GhLV{MG zsS*V$%$mh86=r+HAcSGS!Yy5Iyi=2w-Grz8YUMurJ0SV~WHOR$Za#Cxn>$FBu{akV z995@xbxva}}xAc1zCT8Ln2piUz-bfRa1lT6s57hc~ zl-cd5Zp5~KGqxEh*^F&E-%QKF$3Y3pRASpxVatQ9$SLvl4)B#wLMsWH_|{I62(Xy= zOofSz*o-h(d7zg*x)yS3jPtbCEU&)@e*XH`pg|*OKz`n-C`jRD^Yej;Ha{~C{Jfdj zyAg5K!S#%ecW@QoOnEo_AS6S7R7yy>|3yeo0=x~WF$vN}1xd~W2PHmJN&Mc5`0Mc+ zIW2MggZ>gwXeFVO{=-?JJ(=9D!o)}1s={ogxE^8H)C}^N!sypY-Nn>`1+d``yYL61 zGW8Ec+o2D3H)uhgmn+YtgIY~C>az-vznK)mw#H&UJOA?u5|MEXZ&hJA#NI+U;!nuU z@gSa8IV5X8#T;_lvf)W)TB>qLX8IL#$;4&9@><`rN=c%pe^= z1JM(IlH_U9`W@c{w9nU|T4<0be9+B`Oh71E(BRNYzXD;TgB$;exYwVW1rE2SXQfAa z(H53IJ>;uV2di4-goMTIz2y7mXo3;ysE6{!)uFow_SHksstz8J={p6R0B8)ag~M=1 zq)+qs;1``j`32F2XF32NJ#!C$hwz+r!{F@v9C;DGF#FC!M-+w6WcM$Ms7bedW)W&A$e2-O(OMGd5rUa-Z#+^Rv zt^%=Qoa(L3cw%|rmg%+W$UdKSJfxDjCl9}ia9ke6>-!RWhbdB);205_qZjZOAA!_j%R(_mDKw2{`OHSnpOH#Wo9TP4Kq1{m4Z#C2Dme(3>>Jz*GSaOEI@?FF!EkFy%O-2kCF+Mo} zzrGS;0vm@5+1RK!Mb&tZT_YRXD3kVx)0l)~xVS+~_2VDAL4*O(tfs@;~~ufL5!RF znOq0s3E;!x)jM#QhAZy)?CS?muKGU?PeU<@V(2!E`mc@n^_!xVgYFp?_Ii-r;f?%>Qb99vtR0sX-kI761)@|*ZQNhyOSo{pLi!lzT>^0rg{0Kk#6-r}F2+GN(lH#rsC z#m4WU_zh%+jV#<{s3Pc#62t6dm^VrU;V+~&yQZ_~g?c1gn&-n0VFr9Iyl_*(jz4^o z9Boo19r-b6ord>V{Vm5U1SWl5ctf{gAl`<7ctFw)J`zIkF9FXjaxl)lF_GLJYkIoV zSpO|p^m9dO+&YKE%C0lA--pWvqxuU)<`2bCqMH51HCEPFUh_5*xt>JU;e;U!X#*lR z#>RJigcz%15FiDV^`&|0Tv#Yo#bfwax?KW484ds|-4^M)?WqDKb! z`iS@-+O~v0lC7hik`JHK!151%Dr$=hJlQ+jA|m5ySG4v|(IK<8yF^HXY zU``CUuJt_Lf6E9k&^XnLi)Jn3qvFC^Hncv+%dYyO`F$H9n|`**KDrXlP9=K7ZY)8Vs4^)i za8P1A6VpyY?Po|QcWJtH={q@9MqU%n_?jctA*4QyXNMheQ6skhGor)cGHsLZMx0g* zJ^2^DdU1oOY7i8BdcPC(MSHnA@INX)fC|l7WSP`jChW(O z_L~KUiR(Y#dP9Y1IW96g-}T~X4GN(QqcW*sa25Djnqi%>0R|)9yf@|Xsso0ixuSy7NNugARTFi z?)i*cZm61|NQJ-0RKr=3yf$_s|)lR0iWKlzDGnYh|tVo$A5%Sh>qo z>eU)!+9v2$&&cxRy{whq3xeUkjZPPm(`pUr)-;X}9GtGB0l2x@=yz!rt}G?swCA&C z9dRoC(>Y(#N}nY80SX1b)SYkNgX4~!`ko!lIc;q+F;i5k)u(M9G&1FkwUPNA^W{kK zvs5EL!$0tvqpynTk`)QCCM7_rOFjTlwH{}!*UH)@Q(M$xcY>b%vaZ^@i$@&T{=$qn zJ!wAF~K_U_nDeyJN(=dsq<$0<>mEAZ@C|Z>yBK5+>h(*@bf2~ zovUl@RH{D%v+21?d9k!QJUD2$6BpxtuH7vU6y*1rCxClC! zA1LJ*l%Xfu`j?rBN`q!~m-L{Kpz$gp!==%65ZwDM?pv`ak5{-Q0PzzR2&{{*iLFF;)+-OY#12GBX(Q&s??a~2y`*D zR`5#CYLp80QmSfjPyyvZ86A&fzmo?&d^%B;`qphwmq>jpzQKo&I;d|EUjwDXTID-|K8@;$~W1o*xQ^Qv>p4Y@P`l=Ru1PZV4U!nDc@P*>G+Q5M4F-cR3 z0SWAZz|E`Ce*P!9r;}g9gDsv!*z}iRkaqAmUzU!Bhra9S=fxGd;k{v5R|!IJlT-yc z4gq>Hlq(-F%4@zV%7^m_i+u^kk*_^ai~DuB*{I!*J(GJG6js#CK(Px2tn~1V3nd}> zfevGJO!66fKH+&zbvO<7|60WxXm*M2Y+y8`A#65k;jXxYz6X~y;RJaE?w7owXXAej z911LhoyijFTb`HOH3#rPy-Pr2oWO`Z`~X+925v6`3(9d!IhM>RufNP#;ej*m1bOWl zJfl(z_L2-JuhYTd7W%Vr8S*XX2T-#&ChJ}~m~h}ih2Q}w1SKQj!?ZxloBgfV+^%%4 zTX^#jUr@Y+gv$P!ynrv*!diQVRCWV6Dv|Yte=lje9jZj5`kOfaHO3YES#B^S?ntbP zX$keS*JB7k+25nln+IFmSA6F*k1qqhy3I?W%zHr^;CS=C^>1f$*emP}XqAD%7=FvZ zYknf}05>XBd?$&=hOuKmX@)12gKiub&RBs1b1*TUprlluVf^Aoq9!l2AQFms^ou%j zh}%2jQytXL!`A^PEvciID!%*CMG;)#ua$HL^zd$E@a8r8ih*7UKs69lx$56cpoJFT zoB=0n2gD=zI-HIRs9Ndk$p4k@SG3fsU)3}pOR!4weq_z@={r{48;*d zvkW!Pe!(_kitD$HtJon@hJc&LU2Rcz?vKgNb2+{f<)?jK1re#vs}3SRUyq^XJBc!M zql^6u8F~+7C~T2CF+}4uuZd^$6?lAr_>5qptQ9XIZ)7$(sK>qR!YdMvfjWW#W5+<( z@EB;gJO*M{8P01mzxy}{A8qpxm%s~&H$+h_2C1(nyg)a3vM~q48?IE<_Dw2xA`)o-|GHjnUl@1tya*1JVELz zCIPN}C7j5aA&h*=(q9rxosI=@15TC&7+fSKk?0H3%8SUYS9DpoI;(^G7i%?_>c}dcM=G zZdcFeTRJY9;wP^liYq0=v=!`wkaX&(o1IX_JB+Y;?#u-Aw~&VvSLtFti`e16ARH#H zC^B1hcGW6u<>jDx#6pdfBr-v8zT9_rqk= z06Zh70-taQ^$;)ge55M^ks|e0CHw$OQ@^wA;-uYp#6<=&nsr;1mi$bQI9Ec9itA+l+^S*}Q?|-1Bl^qa9il)!w~6I=Cd!NE?{f#Xv8EUam<-)m96!!edmIaK*wu+^{;h_63ce>49r z+CBwhT3P_O%*~7T!`5?Q@d)d#G%+94!pM-Tt-m3U%RD11P?JiF@IW0NSk3PeW0A>K zn|cO1un{7kuo6T*WN%+k&7#Ymbz@u!UR4@)>4U&Vq1++JYYW~g3`I!W-Tz7(1#SP|Cmn--dh=A^_+J)px*)@hKVzLb$2<+B6c_%Ny`6|m3u$1@+d#B zt8N5V99#X6_xVhs_&G~S**j8V5tqHgm|&$@6lEOUxit(~JzqJE5nIG&q_cJegA&FT z@f4mBY}4z)L4d|HGL<>(Yc$czSa(!BW)~#kB8a2Zt)tXsPTBak5DTeWB3rHc)|6jb z#OzrmNv8a~KQ19|6PslI+^c7zn3B5EwzpCy?-1|FXH;B_ik1E+E>Gm3?Uo8QJ(M_s z^CY+n&)OgGLa{%!qs8nh_)(Qe1 zkPQR~UJ1!Uq9H^QkhbDxlWfRpl3n-UP|+x$#56Xw7ZtVXVN0#r)K*JdkD#rh_G?qW zep_m-#(UFvP^*Ym<@fo_JhOTC-6cjufB$rnd1pQ|^E~s+@y_+m&g7OCj)rsWE#5cv z^M&oxxvgZ-z3$!Y*eNnX9aFq({s9@W199_=O8em99kbc)#Lqwrg#;G2Ejl2heBI^v zx$*j6BVJv(vyr;8hb^}HXxt}I9%o};(OHXm4tD-vHd@w!^(9`{i8?(1QnqdShRt8& zrg0r&8B+K6C@u#D35uLS?@J2$)uEud40;MbjIsq{&~K=q+~~?*LC0ms z!I?K~PX`58EMkLbQ?%%6W9*gSJ_L1#m(<@ZADE9ucxe7}?ShmE@fTqt3_g32>fW+nH>~kE&OW6KG)5saoI0MEcQeFdb-96uOB`bk2jS zH&YWMHm5Q%V)qIXc4sTu{UvwKIQoU1;KI%zR#|T+nVk7zdgYTqgI@V32xRY-_3a+} zwR1k=BqkVr%r$u`<=1#==+60g6hQn16+rbkOijb7rqy_g1gcA%gYmBnZOzYlPgUGT z-OM?b>K6Z~W?SQ5I-CwT`Bf1=i}mA8NIe$+(YnSP=-8oeguM>-fvX`vFhQJmH6@NWa!z@3!s-lUkPpc2Q~h^8`F??$DoVt7}HUdJ2=(dyYAi5u`iZk@AtYj zxfVY6b)1Wa_lfAZE`HtO@h=;mh`lv~VcE|fZKv~Cou?rATd#tce3+rWZkc{|>2btX>x4h%|oO897Wbn|nre1UCTWBW}U z4Y8-s9eds*=e4_mY>o(EOKn zM5aV%;G~XBPvKiQSEG3Byx+G!fOCJABApw0S0Cdkd^vK$hThAMz>kyc<>M**Fme!n z@WFmGcIV)MSU>0B;Ko5T`zjW0n4K)K;P~F?#BK4+(!&1ONu}-2ga0nPryF_)aq;@# z;IS1QO47mcrG>l29y?&LS**y1Jc=!g8Q1Sr>pn%wso+N!@U6jZ(wNL~kbx8ORT7_x zKczZJT*t8|{=MBG@6cS(nA8EX@=k0Q#)Ltag8rU>+e0eaZ_#h+p7@_nRt;+< z1M79BUM6S%O?URhADGA*jE1KGaiN1b@5?lFi;B6r761Aq<)0Rw7}=+ zaDxW{vkd>vZ(VyY!wXgLXX8f*Su4l}7n2v0dNu?bMENFuxX8rCXHwh_dub#}BB{+h z7~v?wTot}R{qD`yW*(`$--s8|8(?hFz;am(ni`)M4nGsATFm3skZKA9HN4 zmF(qs?^FbER5>)5F$CTY0|`Ka$?4AwigG_&U_zIoEHNp%of?_kx^8G^z(+;CIiLARp!h>;!Pc)ld)B zE(cy5hxU=FCI3H-Lp+$_Ve=6xQ69+Gf*b?JZK!_aoUVN{RqwZGQHQO19;7C<>irC4 zQuWwlq71jfa8$iFPgGSe$grPE^Y%*oh2tnb-ub173svu}B{X!^D`M5V)1@3t)tiBu zsH@&jNg&I^orh%c4NR_jyH&$DDo_WXj(giwD!Gi_MTgGuKRp24uTxA|_2?gW6N>#S zu&1kfw}WkJ)%y-3>ri6@$;Xv`-b5a=bs08$9cl(k zqe=_oJRLk~a1?vRJ~+Atb)Owq@HOY)=w5Wi(y?Ck#;_ghI1U#QgCkaxbd84@9IaJ@ ziM{q)AI5Xo@H_jhNv$CJ=)uvi(5s;1ax?I!(t7NP-+~oc)p|@oTzIwLIhTg5^@tv= z9CYjPVf^i5P3v(H2@->&KVa7GXgzqFQ(5PzlhO8}MR2Ja$JT?tNJi^%(I~VYRfr{-D*pXQ5l-$QL871hJ4Y7D{bb*f;eF+} ztQ_Y<@O#D46L&p`Zzen^_|JobxS~Y^Qh;8^K`m)X< z>_uIWi_=4~mOT#4D~{fS`zT^r+$q-nR4LAa?K~Y@%U)&&qgJ5D{DTWjZHPeae<^EU zH37>&iS=?|mmQn^I%Rw_xvGc#I#q11vGY%T*BST$&=9=|KfxB>l@valHhg^P5dWR* zFi;)JlISW(my*9GzAZNT9-+@kqCYq-eQ~0Ek%1ok!k25sI06|>c?4e<-iiN}c3#we z2ZjMMu88Jh^(C>?QKF+!mF*{pTB_*K{vzJ!G)3R&gw|m@>UR7&WIr|;ZZGe|>U-ys zek7L*om`);=)f^gyP^xx%xz~WsoNO7N(=j=4p`dO?y#aKly_c{7ymqjD(|?0%T6f% zjs-(f-403E7mSBFxC|SY`|(jMhYZUf9;1x*Mc8vQr>p}@P6yyT77UA`SZM>|@F^#L z!C@$cJvdUv$bnRqG323BF|q?+ddNUi_qY)>a);V zi`j8lF@8uslpi-Su8!j*@qAs}#cfw$0Ts8VqjdXT+DqyBLC4DYKWMsHAI1RN-k+iM z&vmcP!B)^dwMXTB4!p3?id~)ftx2S;qYx5d#2j5*-2R7l&#$;$rMSa81?N|68^jXc zU}<}N>^z)iw8~Z19^1l&@3mXGvAq3{aTg-Q9$xH+#L#$3ap6D4uKN&~hvD%T2Hu8+ zL5n-in}TyA3j4r&?7F|g6}vfm7Z#q5AKK%hQJk~S3dB|7&vTKueaUvUKN6#!4r~=c zlY{kQx*}I??N?dHGOQP8VF@q#mel;xj`}IlLau$5b_8;m3{T-prS1J#p2!zfc6F@C;btOy@9hWwtz8@y>LplwpB2Fd z*RbZn7wg|c`4fAq?6l?EqiV* zg)ljTGfPj4Oo>cmouZC(ReDD0H=dF-F6 z&?y|d{&7`raGFR*e#g8VY>vk4sNM6V(j@mvTs-Q3WinrH5qcJV_qiVMZV9iBLxrhWGy zs}=p|j+Jv|M+VtXTNvuE?C&r3m*Hn<^RfB;Aw92s4B1qQP1BzCSJiTV$C)_UrlLKD zCVV-nq;tPg;vGr1{?A$GlFzA3`k3?E>v;;)a%^cwdEq3ALi7V2=S+#7vTXn@$8&i3 zkblMP|D$UcoBY?ut7vlh;vI@C95a|xT=+i`Y<>GTm*X8-k=kC5yuW%6_t$=`{wmPF zxBlvbBXob|hq+Jv)g1?+_4suAtN+87%whVg3XByT{Z%=-uzl;VUSnK)@2_0X?xnxF zOTM-q1C#yLc`zOQl`3D{c82PXuhL7;=H`a8@Y|JsOfYtoA{PsDc;f%4Cuzs&jeE8| zVEYcm=03v$?W>#vYv}(p_2G4Y$}8G0pqhbE6?;&U+iG4tW%{5rARmS4^^ zC5=x3kW#`&k-M#T65f`s+>5eZ1J8Ve8Zw_&eR_Bsi?{lHS!{tKl&uafy;6Lbt zeIX9bn)b*g$2MZS9|HqzkKn$dQNJxF+wu3p7{ow|Y)0Lr-EN@Up};@Y_-8OY>-S(K zpijkvwE-l2y%J&Ubw5PR74;Yo7vo2H5V&+y4}STACGQ>42A%{sbw>r=+)pgT7-QY@ zAJSv~*`1~15#!olRG|NWqhtJeE$*vWwP)Rjr^K=!TCiuDy1MU_Sk^;hrlGgU#5q16 z#-6Tdf1K693?l~S{MC7nA(grJ#;=^2n)SMJPI(x^8q2kA(<))eLfy!xNJ;W{4_?6*aBLJ9Ucm)&j&nP z3!svzC!uu|Bk?^?&*3^o-9s9kWF!@_^7jTMNHz{h>=<>O;%H0uBZn~Ad*biFM6w$t zMhdY*dA$>Vk6toU)iIAo%paM4CC9MoS8*k$Uq=-WXlYbCYSJ&#G%FMHAI@9UWPCMT zlHX^O7u{@oRUvcET@-&B-{4G2mJei;PUW8oA994hO^1&^l|+}55?@8f1$h-6mCF_u z{w*@5qWywp3)}xz+TOdaf5O=HKSCW{_bz@uvu-!gw}CwFC$JKD*1C5yW8-(tFUr7O zXr1$m@Nz6{f3$q+1A~(oJXE}^Hz#)3!uF>sPF^}?a2)(#sT#y_aZ4w_mRp|j#OiYt zIljVGf_xiCIF(iEJ;xZQ@3K=%+qbQI4x{lW#;(5|@gmYOW$P}VU_}oH^W3rPH^Ffs zepj>MYp`HX`Dz$6Lt-|GSu5r;F|mrI!l7|gW|5e4#LN?OikL1jCy0qxU(w}gQ%$7H z9=@gx5Q9=QSJ*@cVaH-4Y;HwHA2!yZS*UbT=;%S^^$(O~&7T6ty#LQ4SG0eJA`kGI zR%iVy<^=ISWjt8-TU`j`eq>LTOOG4bO4;Uz>>sg>5X%LNmho2KF=g!wmSN?0E3;zP zg4!I+tvRDDd^~bUS;u*3%DC0=aTYc};hT{xoT;uBn}*sW@~h}LZ&`Wa1DansrWjlo z1Bv2`);e`%Y|x zN_KT)Z&T{`I;_#?n}R&<7jY{P)>_m_iXE3?+H_G~#mPLRv}6uWmXD4r>#W9#%B9P2 z#ZK+OX5>-vJu1m1wWyj;10y7gnZH{uL56tHXI@%_dHQy2(#gOV&HFG9K$x}Lca6!2 zVw(^4>%Pn}6D~IS3u+eTEL+Q`Vm^%t-qeRNf!&_6YFSc-;eHk4SF&X6ENhP-#*#S; z>t8F+c)OzgqCEaWzx~o><()Bf=$Jtl^8VGnva$2tE9=1bxw*SCP(Hg#@Dk%KJjc9+ z=Twzv{Hd({94rl8iUPaT#ROw*Ad=_V7_)E$^UIiUpaq+fG!xB2@6m+S$6dOKvU%?5 zXE(S7sfzy;k3n1!owPm*vBrLLKAM+c2AVXb68>lta@*ESzz#B=g{gM0bzni_QT)Cg zs|TmIU4r)DsKJ?u{!BK%MW@pzHua(62^nRDyT^XBXu?DDloi)C#%>)LMP`NW=o~I8 z{Ej67utaU6>&P!_zZi4BUD2Gf_DU2uHq5op(`I2#w4kiLDrYditYchRM;Ia8dku+F zM@YONk75Ya4koyR@m%nkmrGF|!iH;gEIM}X!4rwWUQg^&yevoI4iqy20ID9+(s zhXAmYDQ0waa>MpHh=o}9$_|TrXXgxJIR~szCCYO7GD9WuJ2Bp^LIZ#vxQK&_z-VO9 z!zHQ#?I@|;k`tYcf5!{AXk4H?zCq^crgH(gP~ixMveMfvS0 zylL_(l;dVw{fmQ=vI@KkxPlBPksz8p=qVNLkvY3cYO|sTme)V54i15PqT9vG--cpO zjPK3)lyk5|iRC-Ce%S25W!m+Kv2ATHcFzBX^`s-KqN6rm-f`K{Q?~ZNq4Ig+4znA?8?sU6XtcSKY{HgMz1mC=-RD(?JDqNb^InbzAc+<3T`+Z2AtzRQy4{8 zK1U6T@v`js^G46lmFGmnKK4G(&*!ykj$C%Cz>%~IGd?UGdmolK@WUcp0Q;}_Hz*vI zSdN5*9LHhJKdU2}wKw`Z{3zDLe-6z$!?*kG>dny{b(7{`qWvVkk< zt%oz%9at7YGmD8w`!;o{?AQ&=e5{dNz6?3O6;}@7#DlfHTz)wp>tee+y=d_GC&pmOb_ zK3l$S&l_W}{-!F3cjBKzh=CgcK=ip)V{u34#Nv(o0SbnAywDY=sg|#MX(zHN{s@BN z7y{t`$ynGv4d;pAJXb6<7qWF#7rK^r9)Uf|@1Y~z3XZ(h6=!NZ-#>Q!9gM)->^kp|=wqmLd$bs54T*6aw$LY}C~-=0Iiz@D?D`WDQdDF-hm`~f zaSQlSi1)M*?6%80FT)+fyVyyn8`RlSP=xg&!oAuYTnc#xOK@;TE`9-wqbkf*voG_i z*`fARuA5DF+w6U2?H^JS^6ie-~87piBodbX-(NIk>q8CB1f>bY7yFHz6S)bn!nY*Wvx)N{RhUag)R)$>~Q{Hl6h zr=DHvdA)jmQ$4?}o}1M32KBsAJ#SXeZuR_udj3c~f2^Kc)bm#LyiGmtP|qIqyi+}Y zrJi@I=T`Ont$N<0p7*I|uX;Y9p1)VmhtzYsdOoV2e^k%M)w54MpHR;y)$=dvxkEjl zQqQN=^BMK*SI_6w^F{T1Sv}+G`A_wHRXtx<&z!wZJPycP&JZzl4O4}yduA=Q#+E&wc7Mjq3R@%Nn8@~}W zy+qrWX`79%X`qU>4%+w|tERuxb~X}g>@ZX9oVoVH_W8$TMhBWOF9wgYLq zjy6vDnx3R>7Z!4wj>K$m;8ohHX?vcwuhX`Jwm;GKIBl=e_Iuh+!H9U^x3n#yt%tTS zZ9k@suGy|Htq#&`VVcF({?mw6a!J(X3=&bZI!gu(smJTOKH1?whG#Q zNZUNxenZOX|%ma+eF&lqU|W!4#1wCfn3^-p=~s6vuJxCJ2aZ+)AlB9OK6MJ zR!`eAw1sJVlC~>pdz7}X(bh}bO|;!j+s|mbjkc|{{eZTIXxl{FleAq&+Y7X5+CE2HBW+V?JD;{<+7{DRMOztdUfRy2t(CT!v|UcyNwj^JHWzKbqV03E zJwe;Sw7o`KCT%%bUK!YpT_8=9XnUQuQrcdmt&z5;Xj?^FA8psr_7H71(#GG&Hr-C! zowVIU+ZNg$qwQwe{z2O}Y5Rb-YhlB?xVg{Ds>B;-)j7XVnq> z2O4R&RuGKA<7${nCF0~aaiwTE5xSCLC*pCYa>irN=J8pF;HBri#1@Ls%3u(2$4jZ) z4~6-W?#!oB1f)zGp{*)tZ1&P>&*q(07IV%zSzMH5JU}aBEP_59Izmtn&Bb8lLtYfD z3qBctgas?d+UGs-*+d`CU^#wKicFY>{~vL_gEEXU`g}g9Xkn`B2v$KeIVz!7!NUCd zIdlIy=sTeQh8EhYMG~0pDj07!W9BFyo+!!8`9IR!18^#fk1A2_f6~~pXkjHk6v3=P z=-JRp?b&?il@Ro&87!p`^p|t+$U-=@A67MLSq4ve+irYH@tRNsHk}#Y2VfEv&18s6 zny=8O1Ar-1K8Hgv`qb0sI)FcePWfDhnnj-oeRcq_iYuQ3AO?LdrO)92A&O3=%|sd> z)~-141{UUF2Lt>sGzZB_CBhztc$K1sc~?w_6Yxlsk*+K3p6Sn@_-FhCmgAvE6MO&* zGhF#(!iCFKN=*P@-pz)o8WQYH(P}PSNV5QD##wme8XpE_dEJ(Q5}+0139V=$x2s85 z1bw0oi@6Xi%-S31^ACVdm`YtJsk($dmje7=JS+|XS^<7RpW6Y7jL&Q0^9TBT1!YrW zd~OCH&C~Qb7>`$sk8bPA0DlI}ttZyMp>1{Qs&%MS?`BSiE3+|%aex(oCi7_ozlCP) zKZc-RzyyNB!H!M0^5IWfPX#!OKHmjk{ZKyqEi>PX4)|ouMOsgVgYwyo6p{57m{t!S z6JV-Hw+q-rZaXE|7YW$%F}Ib^i2wnhV6^~bJ%eDa&?uj8+iAE;Kn6E5SijH| z6R;XE9_5n<7; z=PD;WXt^Hx^UNPs+8r>DB{&Y*NP$j)Y0bogiBQ2R1WaMDkOX^|!8-9^ij+^E_?*CC zuZfRh@HPNTRjI`Lc)W3;h2JvNEBiPs(~OS_>jF9!dKXTKiY#d!p-(3s)y5~Oj(mmQRJ1UC_oMQvaS*}7 z1h2t|t?Zu&-UV0&^S1=&B1wnC9K#&tEQB=5X9cPQQ~o4_{Stt|{zmWt0Q;q92tJPo ze{HOkZ4A^RP8Ka=q4OB%GUyG^N^wv^A1<(1xpX`y1C)8_>`Jb*_5U8!tsxL><~3>IcWGjrr80xl+C$3dT!1a}Cy zl9_NfzzHy~CU_2jDN#PhB1@Tz-=q(ldgkJH37!F9nXtvSj+gxXA;HZ6^w~miE5M(@ zQK>zfAG#8i?!k;2xEuzjR*J&Dg>fjk?gU^Qm(pi~6lfbk8340e(VQou{FFYAORzf# z-V`4dY?R3L7=11WVEX$ACPKJ`1hW7r!E5xn3V;&4N$?>6Y2G0ijR#wNrF0orz|L~M zif$al^JP}bR>nRgS8`{!RS&AQ>m>0WZlnTkK#db4q`C6sMa2Kq~-25yaVh7tUvNWMGI-)B6tRx zvrsXd#&hcdj8?$)=pleRE@YznO>p~>h=1Tzqjg2xCrs$u%p5%AkyB7N6M zFm;C+n|`KmBZJXpDNLn~fD2ilP9OF(l<@)ry4(p!>Kn@t>)J3IVk5(8H_I6!>p7& zFMnqoX<_QwYN?Kt4bEKzufT`x#cv53z=$%wO7KGf%J?sWOgtF*E`lTRpp4mkZO#Np zWchLl*2!R(;K4`_U@*Eo4^t^yAFU?rbfkrGb3xAf4m9KbA;B(a#;uxP0M zYb`(`K2}!-`y+$>1`ozJn!)JO4O1z5d2DA;Dq0v^<@)mgERR1h)7}DLdAvh#F}P7i zH*>HDfHJaCx5mPok)K8|5r8t56PyE(knutZb^}c78axeMmr;ZkS5h+X{{-m7;}_w-Rxn zz{n#6=RsdZ3)Ls1{XrYb{wOxUoDY8wLS=Yh;rLD|ZSL8u!-e6-K`wjpj7_kxHCD=m zTbmW*%#>NfW-X&0mLs6mjFuD2iO`4A=XbDhAg+7{V5xvsio;H(wUkWHz=NVG#X0UM z*f^}nsK6s-t}E+ciB^ghW}+(Edttd4TB*7~tFyTrJt1;97K+l#JvEUoS9Oyw>~C;Y1nQE>^QT(#1I_+q#~Evs$TDlHwIt#XyGnwsje!-e(m>d+vK66pXoQ(P)hcUgNET(z zRExf)LqOL|CGMeJM zP4=OvU5oufhn&+nGa%E<(8#)Cq^b$I=L6$azKF}$9QOMf*0`E|D4wQ3>k5WL z_Er0%QJ~1)B1Ud5UF?diiA4P^u1Hf%g?2RrSGAG>adNX0)?J8#ioiP` z`N*O`MGP|%*UB&obS0!}L?x|5-Chw^m6AdtIP$Zm$?ppLFOK;UUjs71)R;g7pg!1w zybdrkR|QafNFa)^B@~PV@V>cxsNN1IkcDHdtvb2+D2tjV#mUB&rSDsbj5dW7iw2ql z(KXDu<^ZY$-XE11lu|-|B^b-XuirO!J_@Kb9AMh!OQGfSMH4sX!a1!f)AIR}l`Sk) zl{Vo9(QH90g1!cpdww1w6?dc~8ffvmAb&6xbp;z;4XCaRgQ&^RlyIQc6^r;?bx6Tb z9WW_jcvPEG|H=T~L-1nq>+zb@g>~i6=X)pKCF0H&L}i=2clqkQLzE5vD2f`A2AS|B z)$>kq)j_s}LDWMO2zfW^RwqACSEOoP{;HyyjGDoW!u!?=UVKYX-z3;j2;`ZxN99!| zuIeb0?qGr}v;`>{suzxM$WmLlg|VoAwUZTc)D~n&3gn!PZ=)_~NE}GCHLfW$b!rl| zawt?|02Q=!ncM9`%i6FCtt&$#Wj3Cy`)KIY>xlA2FXCzpgj-bLSV))n%)F#VrG6;q z7S+d^V-eS4sVZppC=4ryDh6FT^}beBGQp6)6(y)D0$ycPEo~uViH1vFNxW^UEoN}Y z;9%Su#G8)pufZM+x$Ouh8KPOmQ0-W~>YM!a7qLZQW9T4|NTXd+A|a;fq*S#5zL zE$H`DFqD^r*HDsJX09)@cOyeodPm4mIEaR(B{J01AoqPLFngWkJRK%5>ix(AqdgsQ zVD?fY4=jz2EywmQvpcDNscKst_4`^-&uwE0v?Q!uOIj~d4V$!tlN#7z@Rd_T5pQL% z)t}@b;gj4L+-o1OpuL>WhGY0pGH^)^WX4^k6%~8u#6iq3zIrsX_W+5p%5XtcgP91K zDkugodnbnvGe!n6sl-(n!Yr0y#Bf|n)Jx0IsXQu!7{R3Xa{T~Y%f`NgIWuL&;EJvc}rsX8JSl&d`db@< z;p&jTKF}Db_v*<)O;GZxCaC*#sRhGPqJ&hN>BSorU4+hEkK#r|Vq&G77<%g#14R*z zj)=T6SgksKO*bME9aI-YwGZvUni38HJ_ao&9`gb#J|00ehXx}eF*(9o#8JYCh?w(> zG0if?zSJL%;I$eNt%iCSt1)i5C`htycZtDb4c1Xj4tTIdV3)-;71tWdOx6I*Y@A8o}liMKUmp{eBb zNPDPheX|;vVzuS?1FcCu*Q7evqz2cdFS#a_&7HJx?xgBzlP2ZOirKux9bv3V5!b0M zi+UPI%qzo|HbUr6BhyxfX|G}QjTnDWP3}U0jQ6)VEN0{5{szi6F+9; zTyGGrE;S*S#Q+k<{L?JY>UzJQGg}NJ>o2MZv|tF1=_*sblp&@}on}?9X^r|;>xuPT zO?Zl7L!K1b!;8Hz5Q%WEKY8wCm#-1|VF+9NEp7a3qm8oJ#9z5^D|A zv+N@=tX8bx)H&n}KmwhM%rLW3aDEI_7hzrq+B#HJSg^(t@uPk>VAk5)$QR4!O3zS9 zY`pd=`CQIL!>)$FiU1agh6<9&9RYEZe>K)d>H}!VH4ht$3chEP8cuPQ1e;?mt*}}y zmvxd0i(G!Z!d!I1`-oZlv;!?)1Z`~8bzuaP&qg(ow~*Si0q4$Db#d-oG%4uHS;?nN zoeQ4IikUepJSs4#)hg6UUEbQ@ zUyVpO&sNiaRfm)uDPq}Zu?&R@qe+#CrJUAQth!)1v(=B1#)8yv^tQNB!jb661VB3< zY+mVK>~HjkS!btQ}&3*DAI0s3u8p90P(6GW%zwTZpZ^2KY#tDT-vLrgEx`K#3{ zqXMz4^ss`J7~Q>E)|GDIT{f&Xu4!&rxS8&}?Rw7uTLMj~J zS7#Z2B)1VtIcd_gNewHkN?)bLoUl&CWGlb{lXa@we{vy|m2fc*Q8tT>s$D$Ln(MNb z)Xblw(_-lwc^+EpA;-B^9VXk&e!8-gnrnrzp6o-bYFU-l(HUMZmU`=a5sXi{XpPk3 zi3Nf3`pRl}vGMU@`4=yAdA-L2w?fJHV3-abeiqsng{}Hm2wfZOR9C1c9)@4#Oun>* z>{>!>5S?*pe|Nr&pw)209!C80Fb@vYr}(C%Kln-0Z}PK1=ci_e3i)yJ5?`;>?j(LH z+(?&^fq!2{R>twz(*rl+b74Ps+(FsY^kcYlmtoUV9zM*uK->g} z<9Fi$Ma(ag_k4hljo7}D`ysX&o{T+CFneYrKA5gK*zN?gXf8fV()~>A8-dveGY2KK z6Q&DhZwYpn!K^LCwk($1e0O?5)I46k&$&0lOO#=X&`87}$pm z0oa<vHgcX|*99m|YuS9g|`8UyaYmFuOLwo#wSjXAa`;0zJ&CZ(G)G$WioNY;D1}$*F*L1pA(UjtZ=ab+QMv#rcfwlz9$lr_3&w3X2}#>#f(Seb3( ztT8*sSqHWqZe`~lVU2DZZ;dLNU}dyTuny{m?uG83U}g1x-a4T7D9{~cjp{qv%IrD@ zypFX-_Z?@A4jpeDSUcIu>6(J{=7WBQW$m1aUj)puMpey09CNG#`cY?!PD8k2gqw$a zE=Rqn0A6T~X{)rddKO#Rc{SFU-Wrt6640M#<@BLG)S@o*)LLU|>#UsG29yi7?YctP zL3uIcjaWH75i6@GhVZK)*IKw=i8!yevTLugM)kL&PJZ1QQ*^zR*>k;>(RV%kQKntr zu`=^ESs6Pwf!}5;v*<>o7a#6>Znm;&zh`9>btBvlk$))Xwk>eK6>;89 z`zz4G%)84vpzki&@3J!c?gsv~m6eCOkoz0NeJ}FtKFjL8-^%LRX5|z;Xl2$uXl3_3 zh&cX$@PDu}`X9D3bGJjT?cn<;@MBh1-ye}Ts28<=vPM}SLsiYxh2G0g;ZS*ky9G~~ zrQQ3v^9QO*+!Yw+QS+YmygW~G?R#H&lj^%%#fIu zh`C%`n7<`2ZYP0YK+>=pA-F`pFk88PExzA5JWVva_CLX|7#QDROMbDEfQ#GEH) zg_ujltQGS@F{5H$F6KrtuNU)1F@G#(kC?eR*qEe^7_-6*Gn3tHST~6rUuAB8PvM19MDbS4O_xy~t+|`(OKibKt)@ z@ZTKxZw~x72mYG_|ILB_=0Iu=j62?SUTN*b(%OP~HN~Oan$qfd=baOpP*Yq}ym;Q? z5`}WBVGHHpFZbMWMczg8&c^18isI^O??i89^*puKYn^*>-Zm#5h zRNOl=)5ZM}l*7e6wCanf_qyuqnHgErTF=C9Ocs5Fc)q&yiR`7C@*LwY?`_03jW?B)<>PRR?4(Cvs z3H!pLFwzuUh0XeFR5A6XO;AC76ki7M1tdSvfc)?Nw}jGVT2pRbuMxcrV9=Y>o2k>A zLOXnw1ns8GRN4_19jT4T)zLz~`O<>Ca9h${XEK^yB_mElsVZ zinL~*c%^%N_rhuTT-Q=b6S8j{(#g``tHMjz^^Qqww`pOenQLfb&@w6dWO|&_lrSMP7UvuJ^V?R&b+})z;J{T^xIdp=v!;HSw`=ukB>IFOBD3 z+;gxl{lxqA$v$1SZB5jxU!`ZvYOoLAMB92Zg<-X+?fahWwk^7=s!8zrgsF}vQmqs1 zz4sh;>tP=sAI4M2S5M9U}U9En2q(k`{EI25$w}pAzwV zT3VRaE&GAtEH7Gr{3rljuHxCVpLr^#TlXW=mUG3jKvegCpl3Gdr4 zJh6Fhg&Gu5%pLoKC4Ml1%}|~eNqYbO;EC-=_)(`vmrr~@aGVW}{8^euW#!KOz_BnC zi!|ZItiQ;kihTEe;926vc)q&8%d%<9{N&R!!>^?UY-cLA8}|cSHS2?jUHgHTuX-rS zo09pBXjq6j2Yyq%hAFL{;jLrNb?*b4(tO>nZrKOgaKy71BP8qMp0vcn4?|FIj}vMc4)LR>}0k?@~>~7s7>5ElBlJhG>Pg@@=SD#Gq7_F^G>{p4R!d1 z8Gay)ez`Rgz^K$4_N%U47i~N}{Y>3usSbZ<`XB}M*eDnFT*%VdofO23zk=8lhk~wb8PKZvTjxGn27njW&@;mXxav* zy+Z-iHeWA(=Um^!=(Z2}pwAj|?;CP&4Ez1b>~;)!swsijSFiT5l3~Bo&ulG(Uwp_< zih~q8hg?+=(QS7YryfgMS7A!wUF?rw?>U{@vek^F?h=1ENW4*Fm2mv7HxQ*`mv#(9 z)V4|d2nueSwA;{BhI@eN(M^wr=KAI!c0U4d(U^Pw341h*tkL5QqQ*qnUIiQR6I`8@ z3L45jg|O@pA)g%zapOBtzaSN3T!Dz+e-XWQDirl&<0sH=h14+ugl(e`KZbtzSpwlk zfuVrn+9i-b8xJ-%_|`DYCOWDmAv)8gn=UQB`X-Kb^-n398|kq{dvFIWVUL3TmiiXV z^3W6+7*c$D1-9U);Pl>3Y<`@94Z_}f@W!v#;MM2!YQSbw?X|=1)xw`qwp1v2lsDQGu4gdBMuv#AhA;t) zs$A<*4nug8!uY}Z#PZ5TrJh+cN!6_#!;Pj8wul2J8uaf`a80B>s)~Ip;Yxcfy`#-c z+85(buheecsvyn}398cBzE^);IWbGh@M2?G=F-L1I83~GCRVoBDs!Grf+O5YYzLEA zFJva2Nn*u8hTj}n(Q+IFRgL2zcrrxdCzgNBkX^UjRBYXfu;nPP8veonr~EANxBA0@ zdKH>;9UOaX`{i(P#QJ$=wVGJZ4~FrxA+cO7ZOfX8s^F&4j=j>!zy%koL z)wdXr-fC=lOmLRpVPStb-i*zeV217892{8PnIfV5(g>}?Er_A520VKB=w5KW z|C)_-n$+ArYTr|H`{;d6&G$#|V`_dfIy<|2fa&PM4Jp~#J+C1(R6P~By%~Mkp`yG{ zZ$?)pegj_wRkbsxFQ+>r)Ronhu`{zbqb)lZ%H?vkW%g&}wq^HbbZ2yDb!Y87s3)`Q z@b1i>tgg(y?7Z6k?CyhmGP@7y8Qqo%*PJ%c_h#(O?$7Evs1KpqvfB>oJ-9D3gg_Z> z`0L8(8Pl8DgVkKPBy3%oZKHOM4doTNy2o@QBqZ87sc>MGx`xFN)&m3?Y9ZV zL-_1?IdCKPX3uzM=6MXn-EY(I;2v`-Y+Y6dd>gzQcs)HtG5kbmvu}vF5)V5jzarts zbDbvIFszEc7bX=k>3a#Fh)K`A?NrNPC%wU!!JbZ@DkdC?LCMdK$**dv^0r=uo%{@j zRml_5-U)g;CVj8a^KdlMC$P{LIq2ShQ3$%4&|R6lb*jVpyDxpjNf2G&u#8hG#I}flRk8c^0r!p z-e87jeX^&Q^ma`8ZlUL)hK%3fk<#}G{m+Ho;E~dsb9A>0y}^dQNGC6memkc8MSKyV zo)&t8M@ru&^t_yd={IkLG0QH{s9xGk6?!|F5^v(`zDhmADbJ zKHKqd@-%{9gV56W7BJ=cU{`W`T{TSy`ZxS3kHM2ir#?s{aF<}x50~D<#w4eg$IPb7|6Kg0iRxDPQ$B+q0$#7Z z)YHh@EpEije>)ydo)dDC<*5dyJQE!Cfxoe$x(oi4$KZ#6)5+7UgD2iEgL%;m-zWZF zi;D6NC*L%LZ%`ri;{ssHXF2+F{`QON9{5u}gAYA0y?kAa7>Wk-%Z^z;dJ2`d{2%UxYB_)J20t+E6*N;Z?N%u7MSJv{y(N9 zm1k~|4s^yio&N?e1x}a${lb&+vwqp}aPs^V{Os~P2~2r19PRJUA|1gr&r2^1quAL(yP;uw#{f^Od*tCD4-}e)OOHK7vp*Q%K4td7m5(B$@ z_?>SOHu3GmxQ~jM@!2uuo;+HhXpp}hlRtk8PIbYN zn!mxX0NeSKp8UEn4xuvq?3nzjmTCVpCTM;Je-AhvKNlH68Gd$5e*BF()e)c9{0#mY za5{cH4t{n_elDyEQe_^c`583J3cRlU#~Z0Pf7fuccrJ0?BPP@wvg&>PI~ zOnT&t9N<3@Sq(venm0INCAkd6ov% zMxi&@(D%~zRTKhOT4 zx(oEG{}OEIt7w6uLHX^N^gJ_!>aF87y}^flF}*xJWCTTn{OnlCvr&0l5zs4n1T#F- zV;^sk-i{UhwG3ogzc%!OpWBN(ZI1l0WAfwKCsfrZXn71a@)SAR2RkM`&rG4ZO6U## z0N7r>hMzrunLaxvzwYm7ej#KA^T%LAAJX25{Iz41o=rNyJwl%=*wE+E0!4%I+cD{R z_6t?kBptuO4A1iEhNd#~-3n<;dh@${uh1K8=-X`J8NVHq-u&+WmqKswNa@Xa0DDaQ zH|Piry}f;5{C3RvdFBmO^@%$D1{-=_Xh=m&dOIe)>wC)Ex>@KAHuOcbK+zz*9h1Jc zo4z<-N9YY^c;>&oyhv}yr0@DZsc~-5WG%nJhTa}uy7>Ekpy@k=-e5y-k1t*P){iv( zKZM?3L*MPlKRc%U-9ORv`BSv~1{?a1lD~h8roUF`4L0;2C4cU%n*K$hH`vgBRQy#x z)AVOd)$$u`=szm{w%auQcZJ?yL!V0v6b?o+m~1lwh83MfI9so^z$t$(o+$T~Qq_ znCD(mohX>+Ur`kb<~dkY6@qyl7L`{p&&8q&3+DM)R2u}VbFzRp3FdiOR6i5UbF--K z6U_6osQzri3w}{B&(orMM=;OTqB`&toj#tcMRkl|b-os`TQJYrqVfn<=WPLh3D`vs zQ9p9vHyn8GsmbBH9e5C!>jzaMTrc<#;TufkFi)MP=P#dktmpG=FsiS@pZ%A?uL7@E zKKel~)<=8)#rkZ=tdHhAnyTrVpTUMcPk0iO-i}G%E%G!8y}^dQ$U$$%r0*B{Hla7z z(7PP;c1(Jnkw$f+&>Q?HaJu}kw}(uR9jo-*qxqeNgsSm@;DkK1K+zz*%Z5qcd$01g z&KG)v*8-=NM+Z;v>$YL?tG!P8 zH+ZD+^UOM`sX}kCq2K9fFYTD}=RTn6mkGVWhQ3yNC(>`nqz?)G?Lu#`p)YdK+cD{T zgnpaQ8~iumbmf`nNRJ(pU;poQg!A)tc^GWu>2b(o$E5H2gAVXzp*Psj=Q`-^nDpI3 z-zxM58~Qc}y&aR@^^gv*Ug!-r^i>XeJ0?BPETsCe&>L*%KWe_;{fMT2z{oGy(1)~l zqCVI$84L0<-4thIQ=@ z+1j6&@!K)!dA23h2SRVKp|{6JdOIe4+f$nUsF}Jv3^w#d+B;F7?3nbuLhlxOgAIM2 zgWirwzfZM{uLi8*J$9@-qE)%=l}C{=Ws?W71ns>j2XW zbp9D^=0Lq}5qg8a2AuAFu;)MJv17_(&WC$d_!(^Ev4>Ab z-zM^mo+b53u%R!~*_FsoJ7)a768?)qZ}3Rz&3%}s3%$XHzSa@H9W(ygf9L=&3BAFF zUI~sM#7w^(EBa?N{Ts7&`g!Iom7(ufXo%j9NniA=4zPQUrZ?EocRSh>J0^YqbDI8N zg__=AL+_#miU#GkW71nM(ATnlK3CHlOs|R1_W2;`?U?krFOu4_)|{s44L0;DV)zr2 z-i{UhOK^j_>U5zOZ0P%y?-0Gg*Pfy0KkD3IgtN&=D<%oFjLu}ld2NL zYTcldrk-yjyd6(0Nojg6Dp`t;4c1(Vu0p)G|tXRuqFvC+Gm-bH3 z+cD|Q`I`?3y}^b)(wlQR51XgsH`vg(Iq2<}^yb{pMxi%&r1a)I&^t~1gE~S( z-{pwkj#c_4{OA%bf0u(k&p~g;q&Me$RtmkrCjKG^y&bFkdsPScw$NLG4Sg;vJ``~! z9(GLn+}D-2^`6ihZ0POslHQIwMggP-;kkaQ&bvpr9|~6I-UHt)nCIV9Jt~;z;8Q&V>{2%U zm|B*MLk|2q2OeFX9KP9sf9=2@IxwZM_ZObCu}6uHleIhngRu@swNbFyZ+(wovtK$c z*z8ZvK1cI2`-8^|Hv4f`7=MhbsO}YP_QM`tA@mscP_+s+`&Iv-a9d)(=|9B34gECL zTY|d;AF)vL>lS>9;2yzC6mCoGXZ)IAv;Xiu;6sr=Wy)ckh}o-Ekx zSG&Mqv^!K60+XNFPj-v=oBdi(nDD6ARHGJ&{HQlnrvQ`Q>~FeL{LOx()2bN0EwR7o zCc$Pu(1dffzuC{zDA?@JsadS!Gy7Qrg3W%EKM6MbOWqZ1_KSS3TGN~TA6E%B`#EkC zZ1!h7X~Ktf`m7qEk7#^~V6z{hMzGo65EX3pE8GFh{4x6v9yj!tYJR6J(frN+fUsbz zP5b{;u=ySz2PQxBJ$>|2k#D08f40HbY8(}8zEA&9VU)+Wwg0i_k-jbQz4$`G=KJq2 z1e@=Ojfwfa*2P5V6*wUpy{&eJp+TYBFW(qd*nMDe>CFU!e1)KTC8-mUJ;k1iHzCj)T*94pK{a*!} z@%nMi68=>kew|=5o*ocv#>a&%I=mV0whK1n*&Tw-cywZ`4sXVn*9tb{$3ekn{O1h{ z|F^X~w*nuE@fq)lqPj=0`TgGGg3a&u`URWcBfTlu{61w=Nb@tlPnjUt{9fQ>!RGe@ zX9_mI7dTh2*$>_z*z9jzDcJ09-6*)oLM4E@L9p51dYfRgzx95>W`FAwg3b5+7X_Q| z`|k)g-}eu^Sf|f?-#&hu@_j!8;|P|&`M!UIVDo){vS9Olf39HjeZNw$`MzH# z*nHo|g{z9cSs!Z`Y}Uta6l~VVelFOok3AsRtdISlV6#3pAlR&reIVGZkB!5)i0L!y zW0M4%^|3<1W_@g-VBXh7dlL9q z;8z8|DtM>hgQMDix8PF*TXG-ALc!+#ng)g2EOVdA6@tzEDVvB7!96E4bozcS*xbAF z5b?M+%iJ$DE~c@$hw6O6=ANnt1oz5)H2)AB7raZbxi4niO5sb>bZ|=cr0Y3Dwq2Cj)6KsA@e1l-~d*V9pZUFNkzn(C z)v)oG{Ux1(&F@ui5Nv+0(j(aHM|lvKzj0Y6^e+gm6}(4qli;J*=9^=qRh_Nt1Y3fCAh=ENF9r7s{-eQDHT{c%&G`>+3pT%(KlBnEpZWcL zf#A?7n!ZY~Isd^Y*qm1o7Hpj)@(MQR5!@o!oG);fU~^u>qr~IdEOT$pxJxxQ_bZ(* z*xdi~6XG##mbu^Nb;0KTqr%Iyzqy}hJutFUS6+ztEeF2MfgjWuEs$3Kt8tdWhp$!4 z61c{JFLmJWI`9h)oOgLLzsnu?5eFWBMRNE$2fo9B|Kq^(+mh+O?!eDD@Z>9#!>@AS zdmMPwRmtH!4t$9N|J;FJbl{`bCG-1|1AohbA9dh84m@*xGQU;_zRQ7kI`Fg&$@I+* z{4)psrvo2OWI{I&zKd2)YXTT<99;^P!hRd!cKg zeb9B#_0SE_e&|MM?&G=`It(3wjzO=2UJbnl`V#0%p)Z483q2b;3cV8g3g|ZIb`a95@p>Kq~3HoN} z??HD%e;@h>&_9I!5%ew4KZgDZ^cLu!LT`fpF7&O?P({qE3$(orIIX@M{#Qa@1$_hb zf6M8!D<_vVeF=`dj!dtM1)3Y`f>CXWH2YTir%#(UeOi4z&I9#NkG6!STRgyYW!UQr z1*QQ{i$rnQ@5=D0ICJvUU}W{FiiJNsZFWJy?80e*z;LXE7H97^dqJyXogN9-i_M5b z&uI!wU#yR|oNkjsdn~HE5XbgMPHhc_TYSyaSI?Q{oi)=QENFR`F81PZ%AqqShe`F` zMH`CQ&b>YqQvAt0ak?WfILcoc&Yy{hD}ufT95h+I2Ao?=2+vAudT}V!9Kddj&GQHHl(%+0o!_#YUo@afN4~MAhaHal6U#vMgZ8fed5TEI> zNO(H#*1age>maN{4f)Mceo6V4@XVi;>S^-QW1-Dh=?k-- z4%=$v&zb4|gpG!2A({hqE5rKwj%mIrL-9wZ1*bCK^7By(J*_JP;b3bE-n6B@aDc_k zy9xHGVbF0+H<3=aN6F@)sfAbK1jCVGb6|FXJ1_53$%3KyB?D%w3{Z#Hro2n6D(-xb z?Jf1}pIjM|LN%G*FS`rbCYRz+Ut479qDPs1IsaqI?3sbff>_!kjz&{J%22Z}+87KE zTUhSGIqsRCR$++%EnXZRy%J|-n|kZ6f@G>$F7?;NR#f|OPe%|Ze(#q`JCyLDcv(>B zfg1zO{<`q+y?%b7JAYcsC+qdozraHRG^{XL;m$+VksE#XQ~Hym!F@N*ULX%Abwr!k zkbUHPoImH&$%-KX^ov}`)A?Rvaa#3j_wb}pIy$k`d1+hyfd(M1umaxZuTZ_wn%w1-R@MU*;b^<7xp(` zFc2NKCC@MXlm;F{@vA07zp?I_)k>_2K%JTx?6)z8BQ|;W^4&wxp~ajZYpv&WqiQAN zRdssEe+lkF@HODdKz;keM~>Ls?%8uboi1=l05fE(bkC~hbhAcXOi{xOb?298w2-$$ zsQX{`OFw9jTyim8>;)2g1us>tiiUA?zjwB{c|4zvI87|Fj}!(&@A76Xf!DjBV$r+AyOq|SQ^XQjM*g|jJVMLy<1QbL%yYFl}!<;7&7 zBo@|~s5ODAV-enuRuYWiLI(H<*0;PMqc5^}OGYdj_=q0307L15Pi1g66u-RAbMRIz zU0e}dQ3J{JSh{ZijK_weVl7-5ZVs*(wjD#7XMZ}=2OYOgaOJELmE8ST!8LdDrV0B( zl?d0z`1bnamU_-32Hn z_Wp|@89mfoYZ2ZqwJ6dUSV2!NLhXI|Z|@6X&iSrG22++PLgW{yx5X|O2PL?Y)(=rs z+m<5tjCou?n;#CgFzCKY9Bm4O8$wuySTp@XTxkml6N_ZT(|O$ymM)tRS{0}z%;d9?8&xuun5C~nWzXi`w^>Cc?h`Dp zp5^sGVN5%d+zW8|4z46u1E0@o7_SrZ+2wYNza zYoXlX77XJmaVSjM@Q<9VF7$#~p4XHZvfQ5apUPXV2P1mYY2w{4HN|!d=Vvz0QOPJq()7;!6o{$2mvO2t zTcifeba7suea&b89 zTQht(cYcGPUn(nOEp`6z$inJr(ePna{5m1(p7XuQ>2@fMZ#dbiie z(qyx(=IxcNG#EqkmXzamvd^qrji9Z?s?BHDuW_#P*+v+Qe1@qDMjBT&q?CHTypu~> z1AH}0psVmnAevnMtkyHVi!U4^uW%PIyb4d0awdTdemrtWAkV0 z7Dc4@MCyGZe>KM;?0W5u!Q!MOoMUI=p0mOq+C%p%A|CBKT)lHeP*~u3u$u zl5F_}kPRO>TX18nUpM^=@#W69!XJ?aOt&7h5v)1T>Q8@3GzUG7;Xhw#x8wfv8gES= z#ypr1DBt918-_cWFVwghVAf|i+SD(le2+D4rMVRwo>)!MK}MQ%wfZzPPA^cy){iw} zorP;(+1}d+z@g@m#?L{pW7eiJUS(|+2lN=#7pgv_W@VnYHGd|?nYxSEkI8m_B3^mA z^6gjogr}rcilr)P-k)5L_4L7A==Gx8#=N8cB7Ex!`RW7FHA(M=duH+iMtRk+TxW7p zQka-+c^0ANQ!l0z!ai_w=P7oL*fSFSxcvAk+Fo7=^NGYu%PvVi)V`zy@52kSFJ+Q6 z_T2lF@na|dU*P#UH0aeJsXFGVh17n}gR0Jz#4?QuDSil>jdaK7dF3 z-e}NEer)$f{^;J~|iu-Kk%*+^OHZ+^Lgzcd8KisZKNUQevEu`t5qgjMPwRRs>Ron2{Re%+wfX zrY3u4YO-ghNj4TCQZj5tsu=E>1uXcQ#LecPq@PlCsAlQ@=sq>8n*GPBWWTV=Q)^I; zaU9ne^!rnjxD@^qXCr31ktq7uQhx~BhF0hmCAG3O?26Kiy!=nPpF91|F14Vf_1%L3A>1TW zBzMor0v{e&Q%8JC`pS&P%S41#>sKt)lh>rtZFelSUIBY!^ zO~%k!*{MNLJw%J!=#kJ!<1h6S{FX4W%c$ZJmo)Xfp7l!nfK0NN7*^bkYQG!3iKNSu74#^K`PBRG(0yLq@4Ohxuu6 z1hm02P=LTW(6@!8D3c-?`PSAa#8`0sG{m^zWB-r^;Fc~q=a-oXBVRbyMWa{PaY4$FV$#0;E*`HiNB>8q$z=0iqTdf!8 zB=1Y~P9FNQzNL9^_ayY_CAOqb|AH;aHxxbYNY}=WWD8bKU6IV0E8aPGJF7)Cz|rwS*tAD(UM$8ukABAnc!?1 zRaqSJ@IhnUR3ohTC^-+U>Gaf|iz-RJmuWiQ;1s*e%1YcKMd~bDLVmGj1zPu6P+OE0 zor%K~U#{qGUQ8ilUV;A`_fyMgJqG|a1zy(F2)7;K(Sp>>X_VzsfYNcsF3Wq_JeJ2W zxxt0xMy3%g7~>?2QrIs_2JmXn9Un;Guf+fMF+rzT#zJy#gB3{pBlv2q7GM;BPhN!t zlZ;|&Y$ZWB{&xVZ3g*4WpU?{p;1vM3j6We*I%?426~y)}qFES$;VIWE)U}H+(H%*O zcn7!4Y)$=~sYBg}f7A@M!pEre5dYh88Hu^NckWB>&28klke#>}t>EOG z+T|$WTJ5~`6{lk#>kE-2BlTGwT4d|;I*_t;dF@CUx;!F5@5CNmUb|Yv#443&+l`QC zLunT~k$KYD5tiaUw=0x=po0$@ghM=t40d_XAUcLS2_*FFSb?hO-wOg!J^Cb|W$bqo zK;z>vw?}d-vv`#A*1Jb zAdf+-_u*a)PeJ(&*i3r+_Zl{Z)DS+%pUe91nQCZah_|i!Xcec7rW#ts(bx&;nQj+m zCmv0<;2hAe+rPa)#oE-S#rh_KCByY{A)4GYK{$numSfs zktu2y61$U8s@|WZT!~evM_BPb{PPi3yky|)_y{Ym2jW0Rf>m_o8))=@7Q~|ZE#!e zf*jpauI-E8ORC)fx16uXZkvwIVHV_GA8sW3cMfCE(NAXUWOv_P{)b_FS&{M68&1g! zPiHSVUu{%zEA1kqYi(3Qa4fr<5o@ew5gxT8Rd@Rmz)Qrwz!l2WodB^=evlGm()z5yo4DP5J!m?;pYs*Y78j@E2eK ze}x4gSy@@hynfM=KjshQM1#YGQOjzcYj6T*G=iwGeuUGJqA2HA!kG-^2{&^g0ubH7 z9bQ5adTWPLypBjJuG@niOyHai#71j)&`jZZUb^HSWHUYuByXs!*UsZNp;T0?SsqSZqm zIrNFb3U_K4`yUz?z4Ws7pxu4&FX(Jo-kaXIE&tjL*S+SWw|l#QM*%j?w8d@p4%LK; z!p6F_>!mH^ZPh5a-*b9rdm;60Hsf2fx$WvFgKrwH1Qo*W4L$*Gg8|`&`;a9vvqfNjn({O#tQfRR11g&!T+YWF)jyIcV zn%xI_!s*}1vZOEZCJLpu$|Tf>mva!bIs-e*&rK1gb&k*%tC$@9hzHE;2lePl}RUrn3l` z1;K04?{{!28h?|)uCa^cDW&Ad$7fQ+1=>iT3lzd<0S7Mc!gBh*IE>a{KzY<|5o7$e z#FO3((SDIrRCg0h)jPPS6tT&}@5y5rqc1BE)zfC6tEUwdww(P`mS{-*C@0g<+i7S& zhQxesjhO9DD&h>0rx}NWNXMp18}hrbnlG@8tuQu~`U1y2zg*pX{y07#B6+n;c{uS6 fOfpg)t9XU^xL0LokNFG_BDnYzEI0zo%D;aAEq|q> literal 0 HcmV?d00001 diff --git a/examples/ThirdPartyLibs/openvr/lib/win32/openvr_api.lib b/examples/ThirdPartyLibs/openvr/lib/win32/openvr_api.lib new file mode 100644 index 0000000000000000000000000000000000000000..45a41aeb07a98a65318c590415e53340e9d80cff GIT binary patch literal 4864 zcmcIn&2HO95FSZ!9Ltt1E9osoRn%yH3ON3e)C33$yOx_MksX0j)Z7?KVk{yODUfsv zAA-I>kW-%_=&|RZhn#W_j2?RFt*1OgkaULRl3Xq+S#i9;aJe(X{dQ+(W`|$jR?Key zhwP0a-_}c&a%ppIy;9=&Yu@nIM#X!3oCScd0A}9+%)JMguK?sBu_vPw#Ya8UYB-gCF!(PKwEmgO17Hv3^ zMYf|S9qP6=RBO6rD}#aBb6nKAquOn$rfc@DX&UCX)jS$@j6vvw zB!!r7clCpTX7#J8)it$|tr_~5dE%7aIq#^tYHHn@ZmZ@KrK|Fjh*JEjX8GD})wB?~ ztqe5YNC_G)CRw0mJXIqr4zURZm7H00C2S#{je5=gq1`in)njx;QCr$EblWrr4MkT& z)AHQ5R8_2g$571Po}w!Usu@^Cl(eOmsdS&Jy&Yw!nu@rN1hH$2rfq8a!B2*XzUg>H z07dR1il>h3%^|%0+G|ZN~di ztPv^hqp_A8Be5}yGYG!OXBg5*3Kd5-Ig_B8=)_{`J5hS{GahevmIp=0W|9Q|Wnwa< zcobo2=s?13(YO62p6GDGbHyH!ufQKvz)rdl60%q5L-FW*A(!-hu5gUwZmZxTTkQ=7 zH;R*P@A6s@|sbO}3 zXGeuSt!o;V@x(4(m97=*wf*~!H1Z&2`j937%scc(YnXA~cpzL!*BFj)$;SjD5p`*JgwM06ark{t z_L`0IreE{bQ)$O*{&H4G>x5XZ={cg{5%QW%#wD-$gAKf%yymRD;Uwq#C9Wf}aLi6^ zxtpwvew=0T_75VsryXy(G4WPr#v-4jcnh~syp^h?PA7XxDjA} zI62zOx8nDD1#vSjZtP9Y<9vdRH{x-Nh3KZwy_w(4oA=&4pTDWv zt@djATAqIvizTVJTv#kE^85nr-dMRozkW*tz&U`a7XZ`m0MefUa?gC4GXXsMh%M6W zOG;<4MasPPDfbEWk+N5P%At(VyzJA=LjaH7V~dno^(lLR`Ui?q-KyP_8%kxPzAjg5 zjeD|U^>p)hTTy!kD9ZNz&CR3^JPnn6mByX>+jo`9T4N2GvQl;KbhVnTJG$xOBu2NV z#JOHy-ZNdJt5;3ORXZJBi|Qt1ID+zOs@o1#qfFGft-DRRY8vi_ZCm!5Q{V6ISe;P4 zk6bWv!`$r{PP?KzE!*h1hGq7jMWE}?cw0Ah+h|oySGOOjEuEVpA;d9NC(v!`wu7im zwPSFm5i9t3Waka*vCgkG;Uskb`MB19Na1reFppAPtjn3NkPTse$rwjJaXP?q^fqY9dEOb8&7X zG@n153%I_az-iI2#PM;*!2n)FyA<4nz%2`6R(v9mHMams}8 zqr&hAqTHk(N2Q#h1;^1>H=ZlGqX|ZF2NdCo(^5nsaae&Yn!^KT;@}3|I^l)1pmjRe z^22UnsZa`TVeR=i{PpU=uk&MovFASvn!dBQd$CTtP{EHsS%fr8l;<^XycLpl0*Jgu^F_fs;x)^RNxbH7)}bx&nv?Q|QO@@}Tu0vmFwJ|+@OWEV zS&CTBkGKC2!9Q)WA1+!fO9_WBXc#_N#adYyy(CC zaq&tl>Br9ZXS8gZ;fd?U7&PA3Q`{B2yrwZ3zI)O{2hswx-mGu WJHj3%@g7MvmGRLMH8hU_>Hh(1a`IUK literal 0 HcmV?d00001 diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/Matrices.cpp b/examples/ThirdPartyLibs/openvr/samples/shared/Matrices.cpp new file mode 100644 index 000000000..582b2854e --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/samples/shared/Matrices.cpp @@ -0,0 +1,581 @@ +/////////////////////////////////////////////////////////////////////////////// +// Matrice.cpp +// =========== +// NxN Matrix Math classes +// +// The elements of the matrix are stored as column major order. +// | 0 2 | | 0 3 6 | | 0 4 8 12 | +// | 1 3 | | 1 4 7 | | 1 5 9 13 | +// | 2 5 8 | | 2 6 10 14 | +// | 3 7 11 15 | +// +// AUTHOR: Song Ho Ahn (song.ahn@gmail.com) +// CREATED: 2005-06-24 +// UPDATED: 2014-09-21 +// +// Copyright (C) 2005 Song Ho Ahn +/////////////////////////////////////////////////////////////////////////////// + +#include +#include +#include "Matrices.h" + +const float DEG2RAD = 3.141593f / 180; +const float EPSILON = 0.00001f; + + + +/////////////////////////////////////////////////////////////////////////////// +// transpose 2x2 matrix +/////////////////////////////////////////////////////////////////////////////// +Matrix2& Matrix2::transpose() +{ + std::swap(m[1], m[2]); + return *this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// return the determinant of 2x2 matrix +/////////////////////////////////////////////////////////////////////////////// +float Matrix2::getDeterminant() +{ + return m[0] * m[3] - m[1] * m[2]; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// inverse of 2x2 matrix +// If cannot find inverse, set identity matrix +/////////////////////////////////////////////////////////////////////////////// +Matrix2& Matrix2::invert() +{ + float determinant = getDeterminant(); + if(fabs(determinant) <= EPSILON) + { + return identity(); + } + + float tmp = m[0]; // copy the first element + float invDeterminant = 1.0f / determinant; + m[0] = invDeterminant * m[3]; + m[1] = -invDeterminant * m[1]; + m[2] = -invDeterminant * m[2]; + m[3] = invDeterminant * tmp; + + return *this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// transpose 3x3 matrix +/////////////////////////////////////////////////////////////////////////////// +Matrix3& Matrix3::transpose() +{ + std::swap(m[1], m[3]); + std::swap(m[2], m[6]); + std::swap(m[5], m[7]); + + return *this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// return determinant of 3x3 matrix +/////////////////////////////////////////////////////////////////////////////// +float Matrix3::getDeterminant() +{ + return m[0] * (m[4] * m[8] - m[5] * m[7]) - + m[1] * (m[3] * m[8] - m[5] * m[6]) + + m[2] * (m[3] * m[7] - m[4] * m[6]); +} + + + +/////////////////////////////////////////////////////////////////////////////// +// inverse 3x3 matrix +// If cannot find inverse, set identity matrix +/////////////////////////////////////////////////////////////////////////////// +Matrix3& Matrix3::invert() +{ + float determinant, invDeterminant; + float tmp[9]; + + tmp[0] = m[4] * m[8] - m[5] * m[7]; + tmp[1] = m[2] * m[7] - m[1] * m[8]; + tmp[2] = m[1] * m[5] - m[2] * m[4]; + tmp[3] = m[5] * m[6] - m[3] * m[8]; + tmp[4] = m[0] * m[8] - m[2] * m[6]; + tmp[5] = m[2] * m[3] - m[0] * m[5]; + tmp[6] = m[3] * m[7] - m[4] * m[6]; + tmp[7] = m[1] * m[6] - m[0] * m[7]; + tmp[8] = m[0] * m[4] - m[1] * m[3]; + + // check determinant if it is 0 + determinant = m[0] * tmp[0] + m[1] * tmp[3] + m[2] * tmp[6]; + if(fabs(determinant) <= EPSILON) + { + return identity(); // cannot inverse, make it idenety matrix + } + + // divide by the determinant + invDeterminant = 1.0f / determinant; + m[0] = invDeterminant * tmp[0]; + m[1] = invDeterminant * tmp[1]; + m[2] = invDeterminant * tmp[2]; + m[3] = invDeterminant * tmp[3]; + m[4] = invDeterminant * tmp[4]; + m[5] = invDeterminant * tmp[5]; + m[6] = invDeterminant * tmp[6]; + m[7] = invDeterminant * tmp[7]; + m[8] = invDeterminant * tmp[8]; + + return *this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// transpose 4x4 matrix +/////////////////////////////////////////////////////////////////////////////// +Matrix4& Matrix4::transpose() +{ + std::swap(m[1], m[4]); + std::swap(m[2], m[8]); + std::swap(m[3], m[12]); + std::swap(m[6], m[9]); + std::swap(m[7], m[13]); + std::swap(m[11], m[14]); + + return *this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// inverse 4x4 matrix +/////////////////////////////////////////////////////////////////////////////// +Matrix4& Matrix4::invert() +{ + // If the 4th row is [0,0,0,1] then it is affine matrix and + // it has no projective transformation. + if(m[3] == 0 && m[7] == 0 && m[11] == 0 && m[15] == 1) + this->invertAffine(); + else + { + this->invertGeneral(); + /*@@ invertProjective() is not optimized (slower than generic one) + if(fabs(m[0]*m[5] - m[1]*m[4]) > EPSILON) + this->invertProjective(); // inverse using matrix partition + else + this->invertGeneral(); // generalized inverse + */ + } + + return *this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// compute the inverse of 4x4 Euclidean transformation matrix +// +// Euclidean transformation is translation, rotation, and reflection. +// With Euclidean transform, only the position and orientation of the object +// will be changed. Euclidean transform does not change the shape of an object +// (no scaling). Length and angle are reserved. +// +// Use inverseAffine() if the matrix has scale and shear transformation. +// +// M = [ R | T ] +// [ --+-- ] (R denotes 3x3 rotation/reflection matrix) +// [ 0 | 1 ] (T denotes 1x3 translation matrix) +// +// y = M*x -> y = R*x + T -> x = R^-1*(y - T) -> x = R^T*y - R^T*T +// (R is orthogonal, R^-1 = R^T) +// +// [ R | T ]-1 [ R^T | -R^T * T ] (R denotes 3x3 rotation matrix) +// [ --+-- ] = [ ----+--------- ] (T denotes 1x3 translation) +// [ 0 | 1 ] [ 0 | 1 ] (R^T denotes R-transpose) +/////////////////////////////////////////////////////////////////////////////// +Matrix4& Matrix4::invertEuclidean() +{ + // transpose 3x3 rotation matrix part + // | R^T | 0 | + // | ----+-- | + // | 0 | 1 | + float tmp; + tmp = m[1]; m[1] = m[4]; m[4] = tmp; + tmp = m[2]; m[2] = m[8]; m[8] = tmp; + tmp = m[6]; m[6] = m[9]; m[9] = tmp; + + // compute translation part -R^T * T + // | 0 | -R^T x | + // | --+------- | + // | 0 | 0 | + float x = m[12]; + float y = m[13]; + float z = m[14]; + m[12] = -(m[0] * x + m[4] * y + m[8] * z); + m[13] = -(m[1] * x + m[5] * y + m[9] * z); + m[14] = -(m[2] * x + m[6] * y + m[10]* z); + + // last row should be unchanged (0,0,0,1) + + return *this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// compute the inverse of a 4x4 affine transformation matrix +// +// Affine transformations are generalizations of Euclidean transformations. +// Affine transformation includes translation, rotation, reflection, scaling, +// and shearing. Length and angle are NOT preserved. +// M = [ R | T ] +// [ --+-- ] (R denotes 3x3 rotation/scale/shear matrix) +// [ 0 | 1 ] (T denotes 1x3 translation matrix) +// +// y = M*x -> y = R*x + T -> x = R^-1*(y - T) -> x = R^-1*y - R^-1*T +// +// [ R | T ]-1 [ R^-1 | -R^-1 * T ] +// [ --+-- ] = [ -----+---------- ] +// [ 0 | 1 ] [ 0 + 1 ] +/////////////////////////////////////////////////////////////////////////////// +Matrix4& Matrix4::invertAffine() +{ + // R^-1 + Matrix3 r(m[0],m[1],m[2], m[4],m[5],m[6], m[8],m[9],m[10]); + r.invert(); + m[0] = r[0]; m[1] = r[1]; m[2] = r[2]; + m[4] = r[3]; m[5] = r[4]; m[6] = r[5]; + m[8] = r[6]; m[9] = r[7]; m[10]= r[8]; + + // -R^-1 * T + float x = m[12]; + float y = m[13]; + float z = m[14]; + m[12] = -(r[0] * x + r[3] * y + r[6] * z); + m[13] = -(r[1] * x + r[4] * y + r[7] * z); + m[14] = -(r[2] * x + r[5] * y + r[8] * z); + + // last row should be unchanged (0,0,0,1) + //m[3] = m[7] = m[11] = 0.0f; + //m[15] = 1.0f; + + return * this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// inverse matrix using matrix partitioning (blockwise inverse) +// It devides a 4x4 matrix into 4 of 2x2 matrices. It works in case of where +// det(A) != 0. If not, use the generic inverse method +// inverse formula. +// M = [ A | B ] A, B, C, D are 2x2 matrix blocks +// [ --+-- ] det(M) = |A| * |D - ((C * A^-1) * B)| +// [ C | D ] +// +// M^-1 = [ A' | B' ] A' = A^-1 - (A^-1 * B) * C' +// [ ---+--- ] B' = (A^-1 * B) * -D' +// [ C' | D' ] C' = -D' * (C * A^-1) +// D' = (D - ((C * A^-1) * B))^-1 +// +// NOTE: I wrap with () if it it used more than once. +// The matrix is invertable even if det(A)=0, so must check det(A) before +// calling this function, and use invertGeneric() instead. +/////////////////////////////////////////////////////////////////////////////// +Matrix4& Matrix4::invertProjective() +{ + // partition + Matrix2 a(m[0], m[1], m[4], m[5]); + Matrix2 b(m[8], m[9], m[12], m[13]); + Matrix2 c(m[2], m[3], m[6], m[7]); + Matrix2 d(m[10], m[11], m[14], m[15]); + + // pre-compute repeated parts + a.invert(); // A^-1 + Matrix2 ab = a * b; // A^-1 * B + Matrix2 ca = c * a; // C * A^-1 + Matrix2 cab = ca * b; // C * A^-1 * B + Matrix2 dcab = d - cab; // D - C * A^-1 * B + + // check determinant if |D - C * A^-1 * B| = 0 + //NOTE: this function assumes det(A) is already checked. if |A|=0 then, + // cannot use this function. + float determinant = dcab[0] * dcab[3] - dcab[1] * dcab[2]; + if(fabs(determinant) <= EPSILON) + { + return identity(); + } + + // compute D' and -D' + Matrix2 d1 = dcab; // (D - C * A^-1 * B) + d1.invert(); // (D - C * A^-1 * B)^-1 + Matrix2 d2 = -d1; // -(D - C * A^-1 * B)^-1 + + // compute C' + Matrix2 c1 = d2 * ca; // -D' * (C * A^-1) + + // compute B' + Matrix2 b1 = ab * d2; // (A^-1 * B) * -D' + + // compute A' + Matrix2 a1 = a - (ab * c1); // A^-1 - (A^-1 * B) * C' + + // assemble inverse matrix + m[0] = a1[0]; m[4] = a1[2]; /*|*/ m[8] = b1[0]; m[12]= b1[2]; + m[1] = a1[1]; m[5] = a1[3]; /*|*/ m[9] = b1[1]; m[13]= b1[3]; + /*-----------------------------+-----------------------------*/ + m[2] = c1[0]; m[6] = c1[2]; /*|*/ m[10]= d1[0]; m[14]= d1[2]; + m[3] = c1[1]; m[7] = c1[3]; /*|*/ m[11]= d1[1]; m[15]= d1[3]; + + return *this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// compute the inverse of a general 4x4 matrix using Cramer's Rule +// If cannot find inverse, return indentity matrix +// M^-1 = adj(M) / det(M) +/////////////////////////////////////////////////////////////////////////////// +Matrix4& Matrix4::invertGeneral() +{ + // get cofactors of minor matrices + float cofactor0 = getCofactor(m[5],m[6],m[7], m[9],m[10],m[11], m[13],m[14],m[15]); + float cofactor1 = getCofactor(m[4],m[6],m[7], m[8],m[10],m[11], m[12],m[14],m[15]); + float cofactor2 = getCofactor(m[4],m[5],m[7], m[8],m[9], m[11], m[12],m[13],m[15]); + float cofactor3 = getCofactor(m[4],m[5],m[6], m[8],m[9], m[10], m[12],m[13],m[14]); + + // get determinant + float determinant = m[0] * cofactor0 - m[1] * cofactor1 + m[2] * cofactor2 - m[3] * cofactor3; + if(fabs(determinant) <= EPSILON) + { + return identity(); + } + + // get rest of cofactors for adj(M) + float cofactor4 = getCofactor(m[1],m[2],m[3], m[9],m[10],m[11], m[13],m[14],m[15]); + float cofactor5 = getCofactor(m[0],m[2],m[3], m[8],m[10],m[11], m[12],m[14],m[15]); + float cofactor6 = getCofactor(m[0],m[1],m[3], m[8],m[9], m[11], m[12],m[13],m[15]); + float cofactor7 = getCofactor(m[0],m[1],m[2], m[8],m[9], m[10], m[12],m[13],m[14]); + + float cofactor8 = getCofactor(m[1],m[2],m[3], m[5],m[6], m[7], m[13],m[14],m[15]); + float cofactor9 = getCofactor(m[0],m[2],m[3], m[4],m[6], m[7], m[12],m[14],m[15]); + float cofactor10= getCofactor(m[0],m[1],m[3], m[4],m[5], m[7], m[12],m[13],m[15]); + float cofactor11= getCofactor(m[0],m[1],m[2], m[4],m[5], m[6], m[12],m[13],m[14]); + + float cofactor12= getCofactor(m[1],m[2],m[3], m[5],m[6], m[7], m[9], m[10],m[11]); + float cofactor13= getCofactor(m[0],m[2],m[3], m[4],m[6], m[7], m[8], m[10],m[11]); + float cofactor14= getCofactor(m[0],m[1],m[3], m[4],m[5], m[7], m[8], m[9], m[11]); + float cofactor15= getCofactor(m[0],m[1],m[2], m[4],m[5], m[6], m[8], m[9], m[10]); + + // build inverse matrix = adj(M) / det(M) + // adjugate of M is the transpose of the cofactor matrix of M + float invDeterminant = 1.0f / determinant; + m[0] = invDeterminant * cofactor0; + m[1] = -invDeterminant * cofactor4; + m[2] = invDeterminant * cofactor8; + m[3] = -invDeterminant * cofactor12; + + m[4] = -invDeterminant * cofactor1; + m[5] = invDeterminant * cofactor5; + m[6] = -invDeterminant * cofactor9; + m[7] = invDeterminant * cofactor13; + + m[8] = invDeterminant * cofactor2; + m[9] = -invDeterminant * cofactor6; + m[10]= invDeterminant * cofactor10; + m[11]= -invDeterminant * cofactor14; + + m[12]= -invDeterminant * cofactor3; + m[13]= invDeterminant * cofactor7; + m[14]= -invDeterminant * cofactor11; + m[15]= invDeterminant * cofactor15; + + return *this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// return determinant of 4x4 matrix +/////////////////////////////////////////////////////////////////////////////// +float Matrix4::getDeterminant() +{ + return m[0] * getCofactor(m[5],m[6],m[7], m[9],m[10],m[11], m[13],m[14],m[15]) - + m[1] * getCofactor(m[4],m[6],m[7], m[8],m[10],m[11], m[12],m[14],m[15]) + + m[2] * getCofactor(m[4],m[5],m[7], m[8],m[9], m[11], m[12],m[13],m[15]) - + m[3] * getCofactor(m[4],m[5],m[6], m[8],m[9], m[10], m[12],m[13],m[14]); +} + + + +/////////////////////////////////////////////////////////////////////////////// +// compute cofactor of 3x3 minor matrix without sign +// input params are 9 elements of the minor matrix +// NOTE: The caller must know its sign. +/////////////////////////////////////////////////////////////////////////////// +float Matrix4::getCofactor(float m0, float m1, float m2, + float m3, float m4, float m5, + float m6, float m7, float m8) +{ + return m0 * (m4 * m8 - m5 * m7) - + m1 * (m3 * m8 - m5 * m6) + + m2 * (m3 * m7 - m4 * m6); +} + + + +/////////////////////////////////////////////////////////////////////////////// +// translate this matrix by (x, y, z) +/////////////////////////////////////////////////////////////////////////////// +Matrix4& Matrix4::translate(const Vector3& v) +{ + return translate(v.x, v.y, v.z); +} + +Matrix4& Matrix4::translate(float x, float y, float z) +{ + m[0] += m[3] * x; m[4] += m[7] * x; m[8] += m[11]* x; m[12]+= m[15]* x; + m[1] += m[3] * y; m[5] += m[7] * y; m[9] += m[11]* y; m[13]+= m[15]* y; + m[2] += m[3] * z; m[6] += m[7] * z; m[10]+= m[11]* z; m[14]+= m[15]* z; + + return *this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// uniform scale +/////////////////////////////////////////////////////////////////////////////// +Matrix4& Matrix4::scale(float s) +{ + return scale(s, s, s); +} + +Matrix4& Matrix4::scale(float x, float y, float z) +{ + m[0] *= x; m[4] *= x; m[8] *= x; m[12] *= x; + m[1] *= y; m[5] *= y; m[9] *= y; m[13] *= y; + m[2] *= z; m[6] *= z; m[10]*= z; m[14] *= z; + return *this; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// build a rotation matrix with given angle(degree) and rotation axis, then +// multiply it with this object +/////////////////////////////////////////////////////////////////////////////// +Matrix4& Matrix4::rotate(float angle, const Vector3& axis) +{ + return rotate(angle, axis.x, axis.y, axis.z); +} + +Matrix4& Matrix4::rotate(float angle, float x, float y, float z) +{ + float c = cosf(angle * DEG2RAD); // cosine + float s = sinf(angle * DEG2RAD); // sine + float c1 = 1.0f - c; // 1 - c + float m0 = m[0], m4 = m[4], m8 = m[8], m12= m[12], + m1 = m[1], m5 = m[5], m9 = m[9], m13= m[13], + m2 = m[2], m6 = m[6], m10= m[10], m14= m[14]; + + // build rotation matrix + float r0 = x * x * c1 + c; + float r1 = x * y * c1 + z * s; + float r2 = x * z * c1 - y * s; + float r4 = x * y * c1 - z * s; + float r5 = y * y * c1 + c; + float r6 = y * z * c1 + x * s; + float r8 = x * z * c1 + y * s; + float r9 = y * z * c1 - x * s; + float r10= z * z * c1 + c; + + // multiply rotation matrix + m[0] = r0 * m0 + r4 * m1 + r8 * m2; + m[1] = r1 * m0 + r5 * m1 + r9 * m2; + m[2] = r2 * m0 + r6 * m1 + r10* m2; + m[4] = r0 * m4 + r4 * m5 + r8 * m6; + m[5] = r1 * m4 + r5 * m5 + r9 * m6; + m[6] = r2 * m4 + r6 * m5 + r10* m6; + m[8] = r0 * m8 + r4 * m9 + r8 * m10; + m[9] = r1 * m8 + r5 * m9 + r9 * m10; + m[10]= r2 * m8 + r6 * m9 + r10* m10; + m[12]= r0 * m12+ r4 * m13+ r8 * m14; + m[13]= r1 * m12+ r5 * m13+ r9 * m14; + m[14]= r2 * m12+ r6 * m13+ r10* m14; + + return *this; +} + +Matrix4& Matrix4::rotateX(float angle) +{ + float c = cosf(angle * DEG2RAD); + float s = sinf(angle * DEG2RAD); + float m1 = m[1], m2 = m[2], + m5 = m[5], m6 = m[6], + m9 = m[9], m10= m[10], + m13= m[13], m14= m[14]; + + m[1] = m1 * c + m2 *-s; + m[2] = m1 * s + m2 * c; + m[5] = m5 * c + m6 *-s; + m[6] = m5 * s + m6 * c; + m[9] = m9 * c + m10*-s; + m[10]= m9 * s + m10* c; + m[13]= m13* c + m14*-s; + m[14]= m13* s + m14* c; + + return *this; +} + +Matrix4& Matrix4::rotateY(float angle) +{ + float c = cosf(angle * DEG2RAD); + float s = sinf(angle * DEG2RAD); + float m0 = m[0], m2 = m[2], + m4 = m[4], m6 = m[6], + m8 = m[8], m10= m[10], + m12= m[12], m14= m[14]; + + m[0] = m0 * c + m2 * s; + m[2] = m0 *-s + m2 * c; + m[4] = m4 * c + m6 * s; + m[6] = m4 *-s + m6 * c; + m[8] = m8 * c + m10* s; + m[10]= m8 *-s + m10* c; + m[12]= m12* c + m14* s; + m[14]= m12*-s + m14* c; + + return *this; +} + +Matrix4& Matrix4::rotateZ(float angle) +{ + float c = cosf(angle * DEG2RAD); + float s = sinf(angle * DEG2RAD); + float m0 = m[0], m1 = m[1], + m4 = m[4], m5 = m[5], + m8 = m[8], m9 = m[9], + m12= m[12], m13= m[13]; + + m[0] = m0 * c + m1 *-s; + m[1] = m0 * s + m1 * c; + m[4] = m4 * c + m5 *-s; + m[5] = m4 * s + m5 * c; + m[8] = m8 * c + m9 *-s; + m[9] = m8 * s + m9 * c; + m[12]= m12* c + m13*-s; + m[13]= m12* s + m13* c; + + return *this; +} diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/Matrices.h b/examples/ThirdPartyLibs/openvr/samples/shared/Matrices.h new file mode 100644 index 000000000..3515f546d --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/samples/shared/Matrices.h @@ -0,0 +1,909 @@ +/////////////////////////////////////////////////////////////////////////////// +// Matrice.h +// ========= +// NxN Matrix Math classes +// +// The elements of the matrix are stored as column major order. +// | 0 2 | | 0 3 6 | | 0 4 8 12 | +// | 1 3 | | 1 4 7 | | 1 5 9 13 | +// | 2 5 8 | | 2 6 10 14 | +// | 3 7 11 15 | +// +// AUTHOR: Song Ho Ahn (song.ahn@gmail.com) +// CREATED: 2005-06-24 +// UPDATED: 2013-09-30 +// +// Copyright (C) 2005 Song Ho Ahn +/////////////////////////////////////////////////////////////////////////////// + +#ifndef MATH_MATRICES_H +#define MATH_MATRICES_H + +#include +#include +#include "Vectors.h" + +/////////////////////////////////////////////////////////////////////////// +// 2x2 matrix +/////////////////////////////////////////////////////////////////////////// +class Matrix2 +{ +public: + // constructors + Matrix2(); // init with identity + Matrix2(const float src[4]); + Matrix2(float m0, float m1, float m2, float m3); + + void set(const float src[4]); + void set(float m0, float m1, float m2, float m3); + void setRow(int index, const float row[2]); + void setRow(int index, const Vector2& v); + void setColumn(int index, const float col[2]); + void setColumn(int index, const Vector2& v); + + const float* get() const; + float getDeterminant(); + + Matrix2& identity(); + Matrix2& transpose(); // transpose itself and return reference + Matrix2& invert(); + + // operators + Matrix2 operator+(const Matrix2& rhs) const; // add rhs + Matrix2 operator-(const Matrix2& rhs) const; // subtract rhs + Matrix2& operator+=(const Matrix2& rhs); // add rhs and update this object + Matrix2& operator-=(const Matrix2& rhs); // subtract rhs and update this object + Vector2 operator*(const Vector2& rhs) const; // multiplication: v' = M * v + Matrix2 operator*(const Matrix2& rhs) const; // multiplication: M3 = M1 * M2 + Matrix2& operator*=(const Matrix2& rhs); // multiplication: M1' = M1 * M2 + bool operator==(const Matrix2& rhs) const; // exact compare, no epsilon + bool operator!=(const Matrix2& rhs) const; // exact compare, no epsilon + float operator[](int index) const; // subscript operator v[0], v[1] + float& operator[](int index); // subscript operator v[0], v[1] + + friend Matrix2 operator-(const Matrix2& m); // unary operator (-) + friend Matrix2 operator*(float scalar, const Matrix2& m); // pre-multiplication + friend Vector2 operator*(const Vector2& vec, const Matrix2& m); // pre-multiplication + friend std::ostream& operator<<(std::ostream& os, const Matrix2& m); + +protected: + +private: + float m[4]; + +}; + + + +/////////////////////////////////////////////////////////////////////////// +// 3x3 matrix +/////////////////////////////////////////////////////////////////////////// +class Matrix3 +{ +public: + // constructors + Matrix3(); // init with identity + Matrix3(const float src[9]); + Matrix3(float m0, float m1, float m2, // 1st column + float m3, float m4, float m5, // 2nd column + float m6, float m7, float m8); // 3rd column + + void set(const float src[9]); + void set(float m0, float m1, float m2, // 1st column + float m3, float m4, float m5, // 2nd column + float m6, float m7, float m8); // 3rd column + void setRow(int index, const float row[3]); + void setRow(int index, const Vector3& v); + void setColumn(int index, const float col[3]); + void setColumn(int index, const Vector3& v); + + const float* get() const; + float getDeterminant(); + + Matrix3& identity(); + Matrix3& transpose(); // transpose itself and return reference + Matrix3& invert(); + + // operators + Matrix3 operator+(const Matrix3& rhs) const; // add rhs + Matrix3 operator-(const Matrix3& rhs) const; // subtract rhs + Matrix3& operator+=(const Matrix3& rhs); // add rhs and update this object + Matrix3& operator-=(const Matrix3& rhs); // subtract rhs and update this object + Vector3 operator*(const Vector3& rhs) const; // multiplication: v' = M * v + Matrix3 operator*(const Matrix3& rhs) const; // multiplication: M3 = M1 * M2 + Matrix3& operator*=(const Matrix3& rhs); // multiplication: M1' = M1 * M2 + bool operator==(const Matrix3& rhs) const; // exact compare, no epsilon + bool operator!=(const Matrix3& rhs) const; // exact compare, no epsilon + float operator[](int index) const; // subscript operator v[0], v[1] + float& operator[](int index); // subscript operator v[0], v[1] + + friend Matrix3 operator-(const Matrix3& m); // unary operator (-) + friend Matrix3 operator*(float scalar, const Matrix3& m); // pre-multiplication + friend Vector3 operator*(const Vector3& vec, const Matrix3& m); // pre-multiplication + friend std::ostream& operator<<(std::ostream& os, const Matrix3& m); + +protected: + +private: + float m[9]; + +}; + + + +/////////////////////////////////////////////////////////////////////////// +// 4x4 matrix +/////////////////////////////////////////////////////////////////////////// +class Matrix4 +{ +public: + // constructors + Matrix4(); // init with identity + Matrix4(const float src[16]); + Matrix4(float m00, float m01, float m02, float m03, // 1st column + float m04, float m05, float m06, float m07, // 2nd column + float m08, float m09, float m10, float m11, // 3rd column + float m12, float m13, float m14, float m15);// 4th column + + void set(const float src[16]); + void set(float m00, float m01, float m02, float m03, // 1st column + float m04, float m05, float m06, float m07, // 2nd column + float m08, float m09, float m10, float m11, // 3rd column + float m12, float m13, float m14, float m15);// 4th column + void setRow(int index, const float row[4]); + void setRow(int index, const Vector4& v); + void setRow(int index, const Vector3& v); + void setColumn(int index, const float col[4]); + void setColumn(int index, const Vector4& v); + void setColumn(int index, const Vector3& v); + + const float* get() const; + const float* getTranspose(); // return transposed matrix + float getDeterminant(); + + Matrix4& identity(); + Matrix4& transpose(); // transpose itself and return reference + Matrix4& invert(); // check best inverse method before inverse + Matrix4& invertEuclidean(); // inverse of Euclidean transform matrix + Matrix4& invertAffine(); // inverse of affine transform matrix + Matrix4& invertProjective(); // inverse of projective matrix using partitioning + Matrix4& invertGeneral(); // inverse of generic matrix + + // transform matrix + Matrix4& translate(float x, float y, float z); // translation by (x,y,z) + Matrix4& translate(const Vector3& v); // + Matrix4& rotate(float angle, const Vector3& axis); // rotate angle(degree) along the given axix + Matrix4& rotate(float angle, float x, float y, float z); + Matrix4& rotateX(float angle); // rotate on X-axis with degree + Matrix4& rotateY(float angle); // rotate on Y-axis with degree + Matrix4& rotateZ(float angle); // rotate on Z-axis with degree + Matrix4& scale(float scale); // uniform scale + Matrix4& scale(float sx, float sy, float sz); // scale by (sx, sy, sz) on each axis + + // operators + Matrix4 operator+(const Matrix4& rhs) const; // add rhs + Matrix4 operator-(const Matrix4& rhs) const; // subtract rhs + Matrix4& operator+=(const Matrix4& rhs); // add rhs and update this object + Matrix4& operator-=(const Matrix4& rhs); // subtract rhs and update this object + Vector4 operator*(const Vector4& rhs) const; // multiplication: v' = M * v + Vector3 operator*(const Vector3& rhs) const; // multiplication: v' = M * v + Matrix4 operator*(const Matrix4& rhs) const; // multiplication: M3 = M1 * M2 + Matrix4& operator*=(const Matrix4& rhs); // multiplication: M1' = M1 * M2 + bool operator==(const Matrix4& rhs) const; // exact compare, no epsilon + bool operator!=(const Matrix4& rhs) const; // exact compare, no epsilon + float operator[](int index) const; // subscript operator v[0], v[1] + float& operator[](int index); // subscript operator v[0], v[1] + + friend Matrix4 operator-(const Matrix4& m); // unary operator (-) + friend Matrix4 operator*(float scalar, const Matrix4& m); // pre-multiplication + friend Vector3 operator*(const Vector3& vec, const Matrix4& m); // pre-multiplication + friend Vector4 operator*(const Vector4& vec, const Matrix4& m); // pre-multiplication + friend std::ostream& operator<<(std::ostream& os, const Matrix4& m); + +protected: + +private: + float getCofactor(float m0, float m1, float m2, + float m3, float m4, float m5, + float m6, float m7, float m8); + + float m[16]; + float tm[16]; // transpose m + +}; + + + +/////////////////////////////////////////////////////////////////////////// +// inline functions for Matrix2 +/////////////////////////////////////////////////////////////////////////// +inline Matrix2::Matrix2() +{ + // initially identity matrix + identity(); +} + + + +inline Matrix2::Matrix2(const float src[4]) +{ + set(src); +} + + + +inline Matrix2::Matrix2(float m0, float m1, float m2, float m3) +{ + set(m0, m1, m2, m3); +} + + + +inline void Matrix2::set(const float src[4]) +{ + m[0] = src[0]; m[1] = src[1]; m[2] = src[2]; m[3] = src[3]; +} + + + +inline void Matrix2::set(float m0, float m1, float m2, float m3) +{ + m[0]= m0; m[1] = m1; m[2] = m2; m[3]= m3; +} + + + +inline void Matrix2::setRow(int index, const float row[2]) +{ + m[index] = row[0]; m[index + 2] = row[1]; +} + + + +inline void Matrix2::setRow(int index, const Vector2& v) +{ + m[index] = v.x; m[index + 2] = v.y; +} + + + +inline void Matrix2::setColumn(int index, const float col[2]) +{ + m[index*2] = col[0]; m[index*2 + 1] = col[1]; +} + + + +inline void Matrix2::setColumn(int index, const Vector2& v) +{ + m[index*2] = v.x; m[index*2 + 1] = v.y; +} + + + +inline const float* Matrix2::get() const +{ + return m; +} + + + +inline Matrix2& Matrix2::identity() +{ + m[0] = m[3] = 1.0f; + m[1] = m[2] = 0.0f; + return *this; +} + + + +inline Matrix2 Matrix2::operator+(const Matrix2& rhs) const +{ + return Matrix2(m[0]+rhs[0], m[1]+rhs[1], m[2]+rhs[2], m[3]+rhs[3]); +} + + + +inline Matrix2 Matrix2::operator-(const Matrix2& rhs) const +{ + return Matrix2(m[0]-rhs[0], m[1]-rhs[1], m[2]-rhs[2], m[3]-rhs[3]); +} + + + +inline Matrix2& Matrix2::operator+=(const Matrix2& rhs) +{ + m[0] += rhs[0]; m[1] += rhs[1]; m[2] += rhs[2]; m[3] += rhs[3]; + return *this; +} + + + +inline Matrix2& Matrix2::operator-=(const Matrix2& rhs) +{ + m[0] -= rhs[0]; m[1] -= rhs[1]; m[2] -= rhs[2]; m[3] -= rhs[3]; + return *this; +} + + + +inline Vector2 Matrix2::operator*(const Vector2& rhs) const +{ + return Vector2(m[0]*rhs.x + m[2]*rhs.y, m[1]*rhs.x + m[3]*rhs.y); +} + + + +inline Matrix2 Matrix2::operator*(const Matrix2& rhs) const +{ + return Matrix2(m[0]*rhs[0] + m[2]*rhs[1], m[1]*rhs[0] + m[3]*rhs[1], + m[0]*rhs[2] + m[2]*rhs[3], m[1]*rhs[2] + m[3]*rhs[3]); +} + + + +inline Matrix2& Matrix2::operator*=(const Matrix2& rhs) +{ + *this = *this * rhs; + return *this; +} + + + +inline bool Matrix2::operator==(const Matrix2& rhs) const +{ + return (m[0] == rhs[0]) && (m[1] == rhs[1]) && (m[2] == rhs[2]) && (m[3] == rhs[3]); +} + + + +inline bool Matrix2::operator!=(const Matrix2& rhs) const +{ + return (m[0] != rhs[0]) || (m[1] != rhs[1]) || (m[2] != rhs[2]) || (m[3] != rhs[3]); +} + + + +inline float Matrix2::operator[](int index) const +{ + return m[index]; +} + + + +inline float& Matrix2::operator[](int index) +{ + return m[index]; +} + + + +inline Matrix2 operator-(const Matrix2& rhs) +{ + return Matrix2(-rhs[0], -rhs[1], -rhs[2], -rhs[3]); +} + + + +inline Matrix2 operator*(float s, const Matrix2& rhs) +{ + return Matrix2(s*rhs[0], s*rhs[1], s*rhs[2], s*rhs[3]); +} + + + +inline Vector2 operator*(const Vector2& v, const Matrix2& rhs) +{ + return Vector2(v.x*rhs[0] + v.y*rhs[1], v.x*rhs[2] + v.y*rhs[3]); +} + + + +inline std::ostream& operator<<(std::ostream& os, const Matrix2& m) +{ + os << std::fixed << std::setprecision(5); + os << "[" << std::setw(10) << m[0] << " " << std::setw(10) << m[2] << "]\n" + << "[" << std::setw(10) << m[1] << " " << std::setw(10) << m[3] << "]\n"; + os << std::resetiosflags(std::ios_base::fixed | std::ios_base::floatfield); + return os; +} +// END OF MATRIX2 INLINE ////////////////////////////////////////////////////// + + + + +/////////////////////////////////////////////////////////////////////////// +// inline functions for Matrix3 +/////////////////////////////////////////////////////////////////////////// +inline Matrix3::Matrix3() +{ + // initially identity matrix + identity(); +} + + + +inline Matrix3::Matrix3(const float src[9]) +{ + set(src); +} + + + +inline Matrix3::Matrix3(float m0, float m1, float m2, + float m3, float m4, float m5, + float m6, float m7, float m8) +{ + set(m0, m1, m2, m3, m4, m5, m6, m7, m8); +} + + + +inline void Matrix3::set(const float src[9]) +{ + m[0] = src[0]; m[1] = src[1]; m[2] = src[2]; + m[3] = src[3]; m[4] = src[4]; m[5] = src[5]; + m[6] = src[6]; m[7] = src[7]; m[8] = src[8]; +} + + + +inline void Matrix3::set(float m0, float m1, float m2, + float m3, float m4, float m5, + float m6, float m7, float m8) +{ + m[0] = m0; m[1] = m1; m[2] = m2; + m[3] = m3; m[4] = m4; m[5] = m5; + m[6] = m6; m[7] = m7; m[8] = m8; +} + + + +inline void Matrix3::setRow(int index, const float row[3]) +{ + m[index] = row[0]; m[index + 3] = row[1]; m[index + 6] = row[2]; +} + + + +inline void Matrix3::setRow(int index, const Vector3& v) +{ + m[index] = v.x; m[index + 3] = v.y; m[index + 6] = v.z; +} + + + +inline void Matrix3::setColumn(int index, const float col[3]) +{ + m[index*3] = col[0]; m[index*3 + 1] = col[1]; m[index*3 + 2] = col[2]; +} + + + +inline void Matrix3::setColumn(int index, const Vector3& v) +{ + m[index*3] = v.x; m[index*3 + 1] = v.y; m[index*3 + 2] = v.z; +} + + + +inline const float* Matrix3::get() const +{ + return m; +} + + + +inline Matrix3& Matrix3::identity() +{ + m[0] = m[4] = m[8] = 1.0f; + m[1] = m[2] = m[3] = m[5] = m[6] = m[7] = 0.0f; + return *this; +} + + + +inline Matrix3 Matrix3::operator+(const Matrix3& rhs) const +{ + return Matrix3(m[0]+rhs[0], m[1]+rhs[1], m[2]+rhs[2], + m[3]+rhs[3], m[4]+rhs[4], m[5]+rhs[5], + m[6]+rhs[6], m[7]+rhs[7], m[8]+rhs[8]); +} + + + +inline Matrix3 Matrix3::operator-(const Matrix3& rhs) const +{ + return Matrix3(m[0]-rhs[0], m[1]-rhs[1], m[2]-rhs[2], + m[3]-rhs[3], m[4]-rhs[4], m[5]-rhs[5], + m[6]-rhs[6], m[7]-rhs[7], m[8]-rhs[8]); +} + + + +inline Matrix3& Matrix3::operator+=(const Matrix3& rhs) +{ + m[0] += rhs[0]; m[1] += rhs[1]; m[2] += rhs[2]; + m[3] += rhs[3]; m[4] += rhs[4]; m[5] += rhs[5]; + m[6] += rhs[6]; m[7] += rhs[7]; m[8] += rhs[8]; + return *this; +} + + + +inline Matrix3& Matrix3::operator-=(const Matrix3& rhs) +{ + m[0] -= rhs[0]; m[1] -= rhs[1]; m[2] -= rhs[2]; + m[3] -= rhs[3]; m[4] -= rhs[4]; m[5] -= rhs[5]; + m[6] -= rhs[6]; m[7] -= rhs[7]; m[8] -= rhs[8]; + return *this; +} + + + +inline Vector3 Matrix3::operator*(const Vector3& rhs) const +{ + return Vector3(m[0]*rhs.x + m[3]*rhs.y + m[6]*rhs.z, + m[1]*rhs.x + m[4]*rhs.y + m[7]*rhs.z, + m[2]*rhs.x + m[5]*rhs.y + m[8]*rhs.z); +} + + + +inline Matrix3 Matrix3::operator*(const Matrix3& rhs) const +{ + return Matrix3(m[0]*rhs[0] + m[3]*rhs[1] + m[6]*rhs[2], m[1]*rhs[0] + m[4]*rhs[1] + m[7]*rhs[2], m[2]*rhs[0] + m[5]*rhs[1] + m[8]*rhs[2], + m[0]*rhs[3] + m[3]*rhs[4] + m[6]*rhs[5], m[1]*rhs[3] + m[4]*rhs[4] + m[7]*rhs[5], m[2]*rhs[3] + m[5]*rhs[4] + m[8]*rhs[5], + m[0]*rhs[6] + m[3]*rhs[7] + m[6]*rhs[8], m[1]*rhs[6] + m[4]*rhs[7] + m[7]*rhs[8], m[2]*rhs[6] + m[5]*rhs[7] + m[8]*rhs[8]); +} + + + +inline Matrix3& Matrix3::operator*=(const Matrix3& rhs) +{ + *this = *this * rhs; + return *this; +} + + + +inline bool Matrix3::operator==(const Matrix3& rhs) const +{ + return (m[0] == rhs[0]) && (m[1] == rhs[1]) && (m[2] == rhs[2]) && + (m[3] == rhs[3]) && (m[4] == rhs[4]) && (m[5] == rhs[5]) && + (m[6] == rhs[6]) && (m[7] == rhs[7]) && (m[8] == rhs[8]); +} + + + +inline bool Matrix3::operator!=(const Matrix3& rhs) const +{ + return (m[0] != rhs[0]) || (m[1] != rhs[1]) || (m[2] != rhs[2]) || + (m[3] != rhs[3]) || (m[4] != rhs[4]) || (m[5] != rhs[5]) || + (m[6] != rhs[6]) || (m[7] != rhs[7]) || (m[8] != rhs[8]); +} + + + +inline float Matrix3::operator[](int index) const +{ + return m[index]; +} + + + +inline float& Matrix3::operator[](int index) +{ + return m[index]; +} + + + +inline Matrix3 operator-(const Matrix3& rhs) +{ + return Matrix3(-rhs[0], -rhs[1], -rhs[2], -rhs[3], -rhs[4], -rhs[5], -rhs[6], -rhs[7], -rhs[8]); +} + + + +inline Matrix3 operator*(float s, const Matrix3& rhs) +{ + return Matrix3(s*rhs[0], s*rhs[1], s*rhs[2], s*rhs[3], s*rhs[4], s*rhs[5], s*rhs[6], s*rhs[7], s*rhs[8]); +} + + + +inline Vector3 operator*(const Vector3& v, const Matrix3& m) +{ + return Vector3(v.x*m[0] + v.y*m[1] + v.z*m[2], v.x*m[3] + v.y*m[4] + v.z*m[5], v.x*m[6] + v.y*m[7] + v.z*m[8]); +} + + + +inline std::ostream& operator<<(std::ostream& os, const Matrix3& m) +{ + os << std::fixed << std::setprecision(5); + os << "[" << std::setw(10) << m[0] << " " << std::setw(10) << m[3] << " " << std::setw(10) << m[6] << "]\n" + << "[" << std::setw(10) << m[1] << " " << std::setw(10) << m[4] << " " << std::setw(10) << m[7] << "]\n" + << "[" << std::setw(10) << m[2] << " " << std::setw(10) << m[5] << " " << std::setw(10) << m[8] << "]\n"; + os << std::resetiosflags(std::ios_base::fixed | std::ios_base::floatfield); + return os; +} +// END OF MATRIX3 INLINE ////////////////////////////////////////////////////// + + + + +/////////////////////////////////////////////////////////////////////////// +// inline functions for Matrix4 +/////////////////////////////////////////////////////////////////////////// +inline Matrix4::Matrix4() +{ + // initially identity matrix + identity(); +} + + + +inline Matrix4::Matrix4(const float src[16]) +{ + set(src); +} + + + +inline Matrix4::Matrix4(float m00, float m01, float m02, float m03, + float m04, float m05, float m06, float m07, + float m08, float m09, float m10, float m11, + float m12, float m13, float m14, float m15) +{ + set(m00, m01, m02, m03, m04, m05, m06, m07, m08, m09, m10, m11, m12, m13, m14, m15); +} + + + +inline void Matrix4::set(const float src[16]) +{ + m[0] = src[0]; m[1] = src[1]; m[2] = src[2]; m[3] = src[3]; + m[4] = src[4]; m[5] = src[5]; m[6] = src[6]; m[7] = src[7]; + m[8] = src[8]; m[9] = src[9]; m[10]= src[10]; m[11]= src[11]; + m[12]= src[12]; m[13]= src[13]; m[14]= src[14]; m[15]= src[15]; +} + + + +inline void Matrix4::set(float m00, float m01, float m02, float m03, + float m04, float m05, float m06, float m07, + float m08, float m09, float m10, float m11, + float m12, float m13, float m14, float m15) +{ + m[0] = m00; m[1] = m01; m[2] = m02; m[3] = m03; + m[4] = m04; m[5] = m05; m[6] = m06; m[7] = m07; + m[8] = m08; m[9] = m09; m[10]= m10; m[11]= m11; + m[12]= m12; m[13]= m13; m[14]= m14; m[15]= m15; +} + + + +inline void Matrix4::setRow(int index, const float row[4]) +{ + m[index] = row[0]; m[index + 4] = row[1]; m[index + 8] = row[2]; m[index + 12] = row[3]; +} + + + +inline void Matrix4::setRow(int index, const Vector4& v) +{ + m[index] = v.x; m[index + 4] = v.y; m[index + 8] = v.z; m[index + 12] = v.w; +} + + + +inline void Matrix4::setRow(int index, const Vector3& v) +{ + m[index] = v.x; m[index + 4] = v.y; m[index + 8] = v.z; +} + + + +inline void Matrix4::setColumn(int index, const float col[4]) +{ + m[index*4] = col[0]; m[index*4 + 1] = col[1]; m[index*4 + 2] = col[2]; m[index*4 + 3] = col[3]; +} + + + +inline void Matrix4::setColumn(int index, const Vector4& v) +{ + m[index*4] = v.x; m[index*4 + 1] = v.y; m[index*4 + 2] = v.z; m[index*4 + 3] = v.w; +} + + + +inline void Matrix4::setColumn(int index, const Vector3& v) +{ + m[index*4] = v.x; m[index*4 + 1] = v.y; m[index*4 + 2] = v.z; +} + + + +inline const float* Matrix4::get() const +{ + return m; +} + + + +inline const float* Matrix4::getTranspose() +{ + tm[0] = m[0]; tm[1] = m[4]; tm[2] = m[8]; tm[3] = m[12]; + tm[4] = m[1]; tm[5] = m[5]; tm[6] = m[9]; tm[7] = m[13]; + tm[8] = m[2]; tm[9] = m[6]; tm[10]= m[10]; tm[11]= m[14]; + tm[12]= m[3]; tm[13]= m[7]; tm[14]= m[11]; tm[15]= m[15]; + return tm; +} + + + +inline Matrix4& Matrix4::identity() +{ + m[0] = m[5] = m[10] = m[15] = 1.0f; + m[1] = m[2] = m[3] = m[4] = m[6] = m[7] = m[8] = m[9] = m[11] = m[12] = m[13] = m[14] = 0.0f; + return *this; +} + + + +inline Matrix4 Matrix4::operator+(const Matrix4& rhs) const +{ + return Matrix4(m[0]+rhs[0], m[1]+rhs[1], m[2]+rhs[2], m[3]+rhs[3], + m[4]+rhs[4], m[5]+rhs[5], m[6]+rhs[6], m[7]+rhs[7], + m[8]+rhs[8], m[9]+rhs[9], m[10]+rhs[10], m[11]+rhs[11], + m[12]+rhs[12], m[13]+rhs[13], m[14]+rhs[14], m[15]+rhs[15]); +} + + + +inline Matrix4 Matrix4::operator-(const Matrix4& rhs) const +{ + return Matrix4(m[0]-rhs[0], m[1]-rhs[1], m[2]-rhs[2], m[3]-rhs[3], + m[4]-rhs[4], m[5]-rhs[5], m[6]-rhs[6], m[7]-rhs[7], + m[8]-rhs[8], m[9]-rhs[9], m[10]-rhs[10], m[11]-rhs[11], + m[12]-rhs[12], m[13]-rhs[13], m[14]-rhs[14], m[15]-rhs[15]); +} + + + +inline Matrix4& Matrix4::operator+=(const Matrix4& rhs) +{ + m[0] += rhs[0]; m[1] += rhs[1]; m[2] += rhs[2]; m[3] += rhs[3]; + m[4] += rhs[4]; m[5] += rhs[5]; m[6] += rhs[6]; m[7] += rhs[7]; + m[8] += rhs[8]; m[9] += rhs[9]; m[10]+= rhs[10]; m[11]+= rhs[11]; + m[12]+= rhs[12]; m[13]+= rhs[13]; m[14]+= rhs[14]; m[15]+= rhs[15]; + return *this; +} + + + +inline Matrix4& Matrix4::operator-=(const Matrix4& rhs) +{ + m[0] -= rhs[0]; m[1] -= rhs[1]; m[2] -= rhs[2]; m[3] -= rhs[3]; + m[4] -= rhs[4]; m[5] -= rhs[5]; m[6] -= rhs[6]; m[7] -= rhs[7]; + m[8] -= rhs[8]; m[9] -= rhs[9]; m[10]-= rhs[10]; m[11]-= rhs[11]; + m[12]-= rhs[12]; m[13]-= rhs[13]; m[14]-= rhs[14]; m[15]-= rhs[15]; + return *this; +} + + + +inline Vector4 Matrix4::operator*(const Vector4& rhs) const +{ + return Vector4(m[0]*rhs.x + m[4]*rhs.y + m[8]*rhs.z + m[12]*rhs.w, + m[1]*rhs.x + m[5]*rhs.y + m[9]*rhs.z + m[13]*rhs.w, + m[2]*rhs.x + m[6]*rhs.y + m[10]*rhs.z + m[14]*rhs.w, + m[3]*rhs.x + m[7]*rhs.y + m[11]*rhs.z + m[15]*rhs.w); +} + + + +inline Vector3 Matrix4::operator*(const Vector3& rhs) const +{ + return Vector3(m[0]*rhs.x + m[4]*rhs.y + m[8]*rhs.z, + m[1]*rhs.x + m[5]*rhs.y + m[9]*rhs.z, + m[2]*rhs.x + m[6]*rhs.y + m[10]*rhs.z); +} + + + +inline Matrix4 Matrix4::operator*(const Matrix4& n) const +{ + return Matrix4(m[0]*n[0] + m[4]*n[1] + m[8]*n[2] + m[12]*n[3], m[1]*n[0] + m[5]*n[1] + m[9]*n[2] + m[13]*n[3], m[2]*n[0] + m[6]*n[1] + m[10]*n[2] + m[14]*n[3], m[3]*n[0] + m[7]*n[1] + m[11]*n[2] + m[15]*n[3], + m[0]*n[4] + m[4]*n[5] + m[8]*n[6] + m[12]*n[7], m[1]*n[4] + m[5]*n[5] + m[9]*n[6] + m[13]*n[7], m[2]*n[4] + m[6]*n[5] + m[10]*n[6] + m[14]*n[7], m[3]*n[4] + m[7]*n[5] + m[11]*n[6] + m[15]*n[7], + m[0]*n[8] + m[4]*n[9] + m[8]*n[10] + m[12]*n[11], m[1]*n[8] + m[5]*n[9] + m[9]*n[10] + m[13]*n[11], m[2]*n[8] + m[6]*n[9] + m[10]*n[10] + m[14]*n[11], m[3]*n[8] + m[7]*n[9] + m[11]*n[10] + m[15]*n[11], + m[0]*n[12] + m[4]*n[13] + m[8]*n[14] + m[12]*n[15], m[1]*n[12] + m[5]*n[13] + m[9]*n[14] + m[13]*n[15], m[2]*n[12] + m[6]*n[13] + m[10]*n[14] + m[14]*n[15], m[3]*n[12] + m[7]*n[13] + m[11]*n[14] + m[15]*n[15]); +} + + + +inline Matrix4& Matrix4::operator*=(const Matrix4& rhs) +{ + *this = *this * rhs; + return *this; +} + + + +inline bool Matrix4::operator==(const Matrix4& n) const +{ + return (m[0] == n[0]) && (m[1] == n[1]) && (m[2] == n[2]) && (m[3] == n[3]) && + (m[4] == n[4]) && (m[5] == n[5]) && (m[6] == n[6]) && (m[7] == n[7]) && + (m[8] == n[8]) && (m[9] == n[9]) && (m[10]== n[10]) && (m[11]== n[11]) && + (m[12]== n[12]) && (m[13]== n[13]) && (m[14]== n[14]) && (m[15]== n[15]); +} + + + +inline bool Matrix4::operator!=(const Matrix4& n) const +{ + return (m[0] != n[0]) || (m[1] != n[1]) || (m[2] != n[2]) || (m[3] != n[3]) || + (m[4] != n[4]) || (m[5] != n[5]) || (m[6] != n[6]) || (m[7] != n[7]) || + (m[8] != n[8]) || (m[9] != n[9]) || (m[10]!= n[10]) || (m[11]!= n[11]) || + (m[12]!= n[12]) || (m[13]!= n[13]) || (m[14]!= n[14]) || (m[15]!= n[15]); +} + + + +inline float Matrix4::operator[](int index) const +{ + return m[index]; +} + + + +inline float& Matrix4::operator[](int index) +{ + return m[index]; +} + + + +inline Matrix4 operator-(const Matrix4& rhs) +{ + return Matrix4(-rhs[0], -rhs[1], -rhs[2], -rhs[3], -rhs[4], -rhs[5], -rhs[6], -rhs[7], -rhs[8], -rhs[9], -rhs[10], -rhs[11], -rhs[12], -rhs[13], -rhs[14], -rhs[15]); +} + + + +inline Matrix4 operator*(float s, const Matrix4& rhs) +{ + return Matrix4(s*rhs[0], s*rhs[1], s*rhs[2], s*rhs[3], s*rhs[4], s*rhs[5], s*rhs[6], s*rhs[7], s*rhs[8], s*rhs[9], s*rhs[10], s*rhs[11], s*rhs[12], s*rhs[13], s*rhs[14], s*rhs[15]); +} + + + +inline Vector4 operator*(const Vector4& v, const Matrix4& m) +{ + return Vector4(v.x*m[0] + v.y*m[1] + v.z*m[2] + v.w*m[3], v.x*m[4] + v.y*m[5] + v.z*m[6] + v.w*m[7], v.x*m[8] + v.y*m[9] + v.z*m[10] + v.w*m[11], v.x*m[12] + v.y*m[13] + v.z*m[14] + v.w*m[15]); +} + + + +inline Vector3 operator*(const Vector3& v, const Matrix4& m) +{ + return Vector3(v.x*m[0] + v.y*m[1] + v.z*m[2], v.x*m[4] + v.y*m[5] + v.z*m[6], v.x*m[8] + v.y*m[9] + v.z*m[10]); +} + + + +inline std::ostream& operator<<(std::ostream& os, const Matrix4& m) +{ + os << std::fixed << std::setprecision(5); + os << "[" << std::setw(10) << m[0] << " " << std::setw(10) << m[4] << " " << std::setw(10) << m[8] << " " << std::setw(10) << m[12] << "]\n" + << "[" << std::setw(10) << m[1] << " " << std::setw(10) << m[5] << " " << std::setw(10) << m[9] << " " << std::setw(10) << m[13] << "]\n" + << "[" << std::setw(10) << m[2] << " " << std::setw(10) << m[6] << " " << std::setw(10) << m[10] << " " << std::setw(10) << m[14] << "]\n" + << "[" << std::setw(10) << m[3] << " " << std::setw(10) << m[7] << " " << std::setw(10) << m[11] << " " << std::setw(10) << m[15] << "]\n"; + os << std::resetiosflags(std::ios_base::fixed | std::ios_base::floatfield); + return os; +} +// END OF MATRIX4 INLINE ////////////////////////////////////////////////////// +#endif diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/Vectors.h b/examples/ThirdPartyLibs/openvr/samples/shared/Vectors.h new file mode 100644 index 000000000..2e08103c4 --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/samples/shared/Vectors.h @@ -0,0 +1,530 @@ +/////////////////////////////////////////////////////////////////////////////// +// Vectors.h +// ========= +// 2D/3D/4D vectors +// +// AUTHOR: Song Ho Ahn (song.ahn@gmail.com) +// CREATED: 2007-02-14 +// UPDATED: 2013-01-20 +// +// Copyright (C) 2007-2013 Song Ho Ahn +/////////////////////////////////////////////////////////////////////////////// + + +#ifndef VECTORS_H_DEF +#define VECTORS_H_DEF + +#include +#include + +/////////////////////////////////////////////////////////////////////////////// +// 2D vector +/////////////////////////////////////////////////////////////////////////////// +struct Vector2 +{ + float x; + float y; + + // ctors + Vector2() : x(0), y(0) {}; + Vector2(float x, float y) : x(x), y(y) {}; + + // utils functions + void set(float x, float y); + float length() const; // + float distance(const Vector2& vec) const; // distance between two vectors + Vector2& normalize(); // + float dot(const Vector2& vec) const; // dot product + bool equal(const Vector2& vec, float e) const; // compare with epsilon + + // operators + Vector2 operator-() const; // unary operator (negate) + Vector2 operator+(const Vector2& rhs) const; // add rhs + Vector2 operator-(const Vector2& rhs) const; // subtract rhs + Vector2& operator+=(const Vector2& rhs); // add rhs and update this object + Vector2& operator-=(const Vector2& rhs); // subtract rhs and update this object + Vector2 operator*(const float scale) const; // scale + Vector2 operator*(const Vector2& rhs) const; // multiply each element + Vector2& operator*=(const float scale); // scale and update this object + Vector2& operator*=(const Vector2& rhs); // multiply each element and update this object + Vector2 operator/(const float scale) const; // inverse scale + Vector2& operator/=(const float scale); // scale and update this object + bool operator==(const Vector2& rhs) const; // exact compare, no epsilon + bool operator!=(const Vector2& rhs) const; // exact compare, no epsilon + bool operator<(const Vector2& rhs) const; // comparison for sort + float operator[](int index) const; // subscript operator v[0], v[1] + float& operator[](int index); // subscript operator v[0], v[1] + + friend Vector2 operator*(const float a, const Vector2 vec); + friend std::ostream& operator<<(std::ostream& os, const Vector2& vec); +}; + + + +/////////////////////////////////////////////////////////////////////////////// +// 3D vector +/////////////////////////////////////////////////////////////////////////////// +struct Vector3 +{ + float x; + float y; + float z; + + // ctors + Vector3() : x(0), y(0), z(0) {}; + Vector3(float x, float y, float z) : x(x), y(y), z(z) {}; + + // utils functions + void set(float x, float y, float z); + float length() const; // + float distance(const Vector3& vec) const; // distance between two vectors + Vector3& normalize(); // + float dot(const Vector3& vec) const; // dot product + Vector3 cross(const Vector3& vec) const; // cross product + bool equal(const Vector3& vec, float e) const; // compare with epsilon + + // operators + Vector3 operator-() const; // unary operator (negate) + Vector3 operator+(const Vector3& rhs) const; // add rhs + Vector3 operator-(const Vector3& rhs) const; // subtract rhs + Vector3& operator+=(const Vector3& rhs); // add rhs and update this object + Vector3& operator-=(const Vector3& rhs); // subtract rhs and update this object + Vector3 operator*(const float scale) const; // scale + Vector3 operator*(const Vector3& rhs) const; // multiplay each element + Vector3& operator*=(const float scale); // scale and update this object + Vector3& operator*=(const Vector3& rhs); // product each element and update this object + Vector3 operator/(const float scale) const; // inverse scale + Vector3& operator/=(const float scale); // scale and update this object + bool operator==(const Vector3& rhs) const; // exact compare, no epsilon + bool operator!=(const Vector3& rhs) const; // exact compare, no epsilon + bool operator<(const Vector3& rhs) const; // comparison for sort + float operator[](int index) const; // subscript operator v[0], v[1] + float& operator[](int index); // subscript operator v[0], v[1] + + friend Vector3 operator*(const float a, const Vector3 vec); + friend std::ostream& operator<<(std::ostream& os, const Vector3& vec); +}; + + + +/////////////////////////////////////////////////////////////////////////////// +// 4D vector +/////////////////////////////////////////////////////////////////////////////// +struct Vector4 +{ + float x; + float y; + float z; + float w; + + // ctors + Vector4() : x(0), y(0), z(0), w(0) {}; + Vector4(float x, float y, float z, float w) : x(x), y(y), z(z), w(w) {}; + + // utils functions + void set(float x, float y, float z, float w); + float length() const; // + float distance(const Vector4& vec) const; // distance between two vectors + Vector4& normalize(); // + float dot(const Vector4& vec) const; // dot product + bool equal(const Vector4& vec, float e) const; // compare with epsilon + + // operators + Vector4 operator-() const; // unary operator (negate) + Vector4 operator+(const Vector4& rhs) const; // add rhs + Vector4 operator-(const Vector4& rhs) const; // subtract rhs + Vector4& operator+=(const Vector4& rhs); // add rhs and update this object + Vector4& operator-=(const Vector4& rhs); // subtract rhs and update this object + Vector4 operator*(const float scale) const; // scale + Vector4 operator*(const Vector4& rhs) const; // multiply each element + Vector4& operator*=(const float scale); // scale and update this object + Vector4& operator*=(const Vector4& rhs); // multiply each element and update this object + Vector4 operator/(const float scale) const; // inverse scale + Vector4& operator/=(const float scale); // scale and update this object + bool operator==(const Vector4& rhs) const; // exact compare, no epsilon + bool operator!=(const Vector4& rhs) const; // exact compare, no epsilon + bool operator<(const Vector4& rhs) const; // comparison for sort + float operator[](int index) const; // subscript operator v[0], v[1] + float& operator[](int index); // subscript operator v[0], v[1] + + friend Vector4 operator*(const float a, const Vector4 vec); + friend std::ostream& operator<<(std::ostream& os, const Vector4& vec); +}; + + + +// fast math routines from Doom3 SDK +inline float invSqrt(float x) +{ + float xhalf = 0.5f * x; + int i = *(int*)&x; // get bits for floating value + i = 0x5f3759df - (i>>1); // gives initial guess + x = *(float*)&i; // convert bits back to float + x = x * (1.5f - xhalf*x*x); // Newton step + return x; +} + + + +/////////////////////////////////////////////////////////////////////////////// +// inline functions for Vector2 +/////////////////////////////////////////////////////////////////////////////// +inline Vector2 Vector2::operator-() const { + return Vector2(-x, -y); +} + +inline Vector2 Vector2::operator+(const Vector2& rhs) const { + return Vector2(x+rhs.x, y+rhs.y); +} + +inline Vector2 Vector2::operator-(const Vector2& rhs) const { + return Vector2(x-rhs.x, y-rhs.y); +} + +inline Vector2& Vector2::operator+=(const Vector2& rhs) { + x += rhs.x; y += rhs.y; return *this; +} + +inline Vector2& Vector2::operator-=(const Vector2& rhs) { + x -= rhs.x; y -= rhs.y; return *this; +} + +inline Vector2 Vector2::operator*(const float a) const { + return Vector2(x*a, y*a); +} + +inline Vector2 Vector2::operator*(const Vector2& rhs) const { + return Vector2(x*rhs.x, y*rhs.y); +} + +inline Vector2& Vector2::operator*=(const float a) { + x *= a; y *= a; return *this; +} + +inline Vector2& Vector2::operator*=(const Vector2& rhs) { + x *= rhs.x; y *= rhs.y; return *this; +} + +inline Vector2 Vector2::operator/(const float a) const { + return Vector2(x/a, y/a); +} + +inline Vector2& Vector2::operator/=(const float a) { + x /= a; y /= a; return *this; +} + +inline bool Vector2::operator==(const Vector2& rhs) const { + return (x == rhs.x) && (y == rhs.y); +} + +inline bool Vector2::operator!=(const Vector2& rhs) const { + return (x != rhs.x) || (y != rhs.y); +} + +inline bool Vector2::operator<(const Vector2& rhs) const { + if(x < rhs.x) return true; + if(x > rhs.x) return false; + if(y < rhs.y) return true; + if(y > rhs.y) return false; + return false; +} + +inline float Vector2::operator[](int index) const { + return (&x)[index]; +} + +inline float& Vector2::operator[](int index) { + return (&x)[index]; +} + +inline void Vector2::set(float x, float y) { + this->x = x; this->y = y; +} + +inline float Vector2::length() const { + return sqrtf(x*x + y*y); +} + +inline float Vector2::distance(const Vector2& vec) const { + return sqrtf((vec.x-x)*(vec.x-x) + (vec.y-y)*(vec.y-y)); +} + +inline Vector2& Vector2::normalize() { + //@@const float EPSILON = 0.000001f; + float xxyy = x*x + y*y; + //@@if(xxyy < EPSILON) + //@@ return *this; + + //float invLength = invSqrt(xxyy); + float invLength = 1.0f / sqrtf(xxyy); + x *= invLength; + y *= invLength; + return *this; +} + +inline float Vector2::dot(const Vector2& rhs) const { + return (x*rhs.x + y*rhs.y); +} + +inline bool Vector2::equal(const Vector2& rhs, float epsilon) const { + return fabs(x - rhs.x) < epsilon && fabs(y - rhs.y) < epsilon; +} + +inline Vector2 operator*(const float a, const Vector2 vec) { + return Vector2(a*vec.x, a*vec.y); +} + +inline std::ostream& operator<<(std::ostream& os, const Vector2& vec) { + os << "(" << vec.x << ", " << vec.y << ")"; + return os; +} +// END OF VECTOR2 ///////////////////////////////////////////////////////////// + + + + +/////////////////////////////////////////////////////////////////////////////// +// inline functions for Vector3 +/////////////////////////////////////////////////////////////////////////////// +inline Vector3 Vector3::operator-() const { + return Vector3(-x, -y, -z); +} + +inline Vector3 Vector3::operator+(const Vector3& rhs) const { + return Vector3(x+rhs.x, y+rhs.y, z+rhs.z); +} + +inline Vector3 Vector3::operator-(const Vector3& rhs) const { + return Vector3(x-rhs.x, y-rhs.y, z-rhs.z); +} + +inline Vector3& Vector3::operator+=(const Vector3& rhs) { + x += rhs.x; y += rhs.y; z += rhs.z; return *this; +} + +inline Vector3& Vector3::operator-=(const Vector3& rhs) { + x -= rhs.x; y -= rhs.y; z -= rhs.z; return *this; +} + +inline Vector3 Vector3::operator*(const float a) const { + return Vector3(x*a, y*a, z*a); +} + +inline Vector3 Vector3::operator*(const Vector3& rhs) const { + return Vector3(x*rhs.x, y*rhs.y, z*rhs.z); +} + +inline Vector3& Vector3::operator*=(const float a) { + x *= a; y *= a; z *= a; return *this; +} + +inline Vector3& Vector3::operator*=(const Vector3& rhs) { + x *= rhs.x; y *= rhs.y; z *= rhs.z; return *this; +} + +inline Vector3 Vector3::operator/(const float a) const { + return Vector3(x/a, y/a, z/a); +} + +inline Vector3& Vector3::operator/=(const float a) { + x /= a; y /= a; z /= a; return *this; +} + +inline bool Vector3::operator==(const Vector3& rhs) const { + return (x == rhs.x) && (y == rhs.y) && (z == rhs.z); +} + +inline bool Vector3::operator!=(const Vector3& rhs) const { + return (x != rhs.x) || (y != rhs.y) || (z != rhs.z); +} + +inline bool Vector3::operator<(const Vector3& rhs) const { + if(x < rhs.x) return true; + if(x > rhs.x) return false; + if(y < rhs.y) return true; + if(y > rhs.y) return false; + if(z < rhs.z) return true; + if(z > rhs.z) return false; + return false; +} + +inline float Vector3::operator[](int index) const { + return (&x)[index]; +} + +inline float& Vector3::operator[](int index) { + return (&x)[index]; +} + +inline void Vector3::set(float x, float y, float z) { + this->x = x; this->y = y; this->z = z; +} + +inline float Vector3::length() const { + return sqrtf(x*x + y*y + z*z); +} + +inline float Vector3::distance(const Vector3& vec) const { + return sqrtf((vec.x-x)*(vec.x-x) + (vec.y-y)*(vec.y-y) + (vec.z-z)*(vec.z-z)); +} + +inline Vector3& Vector3::normalize() { + //@@const float EPSILON = 0.000001f; + float xxyyzz = x*x + y*y + z*z; + //@@if(xxyyzz < EPSILON) + //@@ return *this; // do nothing if it is ~zero vector + + //float invLength = invSqrt(xxyyzz); + float invLength = 1.0f / sqrtf(xxyyzz); + x *= invLength; + y *= invLength; + z *= invLength; + return *this; +} + +inline float Vector3::dot(const Vector3& rhs) const { + return (x*rhs.x + y*rhs.y + z*rhs.z); +} + +inline Vector3 Vector3::cross(const Vector3& rhs) const { + return Vector3(y*rhs.z - z*rhs.y, z*rhs.x - x*rhs.z, x*rhs.y - y*rhs.x); +} + +inline bool Vector3::equal(const Vector3& rhs, float epsilon) const { + return fabs(x - rhs.x) < epsilon && fabs(y - rhs.y) < epsilon && fabs(z - rhs.z) < epsilon; +} + +inline Vector3 operator*(const float a, const Vector3 vec) { + return Vector3(a*vec.x, a*vec.y, a*vec.z); +} + +inline std::ostream& operator<<(std::ostream& os, const Vector3& vec) { + os << "(" << vec.x << ", " << vec.y << ", " << vec.z << ")"; + return os; +} +// END OF VECTOR3 ///////////////////////////////////////////////////////////// + + + +/////////////////////////////////////////////////////////////////////////////// +// inline functions for Vector4 +/////////////////////////////////////////////////////////////////////////////// +inline Vector4 Vector4::operator-() const { + return Vector4(-x, -y, -z, -w); +} + +inline Vector4 Vector4::operator+(const Vector4& rhs) const { + return Vector4(x+rhs.x, y+rhs.y, z+rhs.z, w+rhs.w); +} + +inline Vector4 Vector4::operator-(const Vector4& rhs) const { + return Vector4(x-rhs.x, y-rhs.y, z-rhs.z, w-rhs.w); +} + +inline Vector4& Vector4::operator+=(const Vector4& rhs) { + x += rhs.x; y += rhs.y; z += rhs.z; w += rhs.w; return *this; +} + +inline Vector4& Vector4::operator-=(const Vector4& rhs) { + x -= rhs.x; y -= rhs.y; z -= rhs.z; w -= rhs.w; return *this; +} + +inline Vector4 Vector4::operator*(const float a) const { + return Vector4(x*a, y*a, z*a, w*a); +} + +inline Vector4 Vector4::operator*(const Vector4& rhs) const { + return Vector4(x*rhs.x, y*rhs.y, z*rhs.z, w*rhs.w); +} + +inline Vector4& Vector4::operator*=(const float a) { + x *= a; y *= a; z *= a; w *= a; return *this; +} + +inline Vector4& Vector4::operator*=(const Vector4& rhs) { + x *= rhs.x; y *= rhs.y; z *= rhs.z; w *= rhs.w; return *this; +} + +inline Vector4 Vector4::operator/(const float a) const { + return Vector4(x/a, y/a, z/a, w/a); +} + +inline Vector4& Vector4::operator/=(const float a) { + x /= a; y /= a; z /= a; w /= a; return *this; +} + +inline bool Vector4::operator==(const Vector4& rhs) const { + return (x == rhs.x) && (y == rhs.y) && (z == rhs.z) && (w == rhs.w); +} + +inline bool Vector4::operator!=(const Vector4& rhs) const { + return (x != rhs.x) || (y != rhs.y) || (z != rhs.z) || (w != rhs.w); +} + +inline bool Vector4::operator<(const Vector4& rhs) const { + if(x < rhs.x) return true; + if(x > rhs.x) return false; + if(y < rhs.y) return true; + if(y > rhs.y) return false; + if(z < rhs.z) return true; + if(z > rhs.z) return false; + if(w < rhs.w) return true; + if(w > rhs.w) return false; + return false; +} + +inline float Vector4::operator[](int index) const { + return (&x)[index]; +} + +inline float& Vector4::operator[](int index) { + return (&x)[index]; +} + +inline void Vector4::set(float x, float y, float z, float w) { + this->x = x; this->y = y; this->z = z; this->w = w; +} + +inline float Vector4::length() const { + return sqrtf(x*x + y*y + z*z + w*w); +} + +inline float Vector4::distance(const Vector4& vec) const { + return sqrtf((vec.x-x)*(vec.x-x) + (vec.y-y)*(vec.y-y) + (vec.z-z)*(vec.z-z) + (vec.w-w)*(vec.w-w)); +} + +inline Vector4& Vector4::normalize() { + //NOTE: leave w-component untouched + //@@const float EPSILON = 0.000001f; + float xxyyzz = x*x + y*y + z*z; + //@@if(xxyyzz < EPSILON) + //@@ return *this; // do nothing if it is zero vector + + //float invLength = invSqrt(xxyyzz); + float invLength = 1.0f / sqrtf(xxyyzz); + x *= invLength; + y *= invLength; + z *= invLength; + return *this; +} + +inline float Vector4::dot(const Vector4& rhs) const { + return (x*rhs.x + y*rhs.y + z*rhs.z + w*rhs.w); +} + +inline bool Vector4::equal(const Vector4& rhs, float epsilon) const { + return fabs(x - rhs.x) < epsilon && fabs(y - rhs.y) < epsilon && + fabs(z - rhs.z) < epsilon && fabs(w - rhs.w) < epsilon; +} + +inline Vector4 operator*(const float a, const Vector4 vec) { + return Vector4(a*vec.x, a*vec.y, a*vec.z, a*vec.w); +} + +inline std::ostream& operator<<(std::ostream& os, const Vector4& vec) { + os << "(" << vec.x << ", " << vec.y << ", " << vec.z << ", " << vec.w << ")"; + return os; +} +// END OF VECTOR4 ///////////////////////////////////////////////////////////// + +#endif diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/lodepng.cpp b/examples/ThirdPartyLibs/openvr/samples/shared/lodepng.cpp new file mode 100644 index 000000000..d57a9d945 --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/samples/shared/lodepng.cpp @@ -0,0 +1,6104 @@ +/* +LodePNG version 20140823 + +Copyright (c) 2005-2014 Lode Vandevenne + +This software is provided 'as-is', without any express or implied +warranty. In no event will the authors be held liable for any damages +arising from the use of this software. + +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it +freely, subject to the following restrictions: + + 1. The origin of this software must not be misrepresented; you must not + claim that you wrote the original software. If you use this software + in a product, an acknowledgment in the product documentation would be + appreciated but is not required. + + 2. Altered source versions must be plainly marked as such, and must not be + misrepresented as being the original software. + + 3. This notice may not be removed or altered from any source + distribution. +*/ + +/* +The manual and changelog are in the header file "lodepng.h" +Rename this file to lodepng.cpp to use it for C++, or to lodepng.c to use it for C. +*/ + +#include "lodepng.h" + +#include +#include + +#ifdef LODEPNG_COMPILE_CPP +#include +#endif /*LODEPNG_COMPILE_CPP*/ + +#define VERSION_STRING "20140823" + +#if defined(_MSC_VER) && (_MSC_VER >= 1310) /*Visual Studio: A few warning types are not desired here.*/ +#pragma warning( disable : 4244 ) /*implicit conversions: not warned by gcc -Wall -Wextra and requires too much casts*/ +#pragma warning( disable : 4996 ) /*VS does not like fopen, but fopen_s is not standard C so unusable here*/ +#endif /*_MSC_VER */ + +/* +This source file is built up in the following large parts. The code sections +with the "LODEPNG_COMPILE_" #defines divide this up further in an intermixed way. +-Tools for C and common code for PNG and Zlib +-C Code for Zlib (huffman, deflate, ...) +-C Code for PNG (file format chunks, adam7, PNG filters, color conversions, ...) +-The C++ wrapper around all of the above +*/ + +/*The malloc, realloc and free functions defined here with "lodepng_" in front +of the name, so that you can easily change them to others related to your +platform if needed. Everything else in the code calls these. Pass +-DLODEPNG_NO_COMPILE_ALLOCATORS to the compiler, or comment out +#define LODEPNG_COMPILE_ALLOCATORS in the header, to disable the ones here and +define them in your own project's source files without needing to change +lodepng source code. Don't forget to remove "static" if you copypaste them +from here.*/ + +#ifdef LODEPNG_COMPILE_ALLOCATORS +static void* lodepng_malloc(size_t size) +{ + return malloc(size); +} + +static void* lodepng_realloc(void* ptr, size_t new_size) +{ + return realloc(ptr, new_size); +} + +static void lodepng_free(void* ptr) +{ + free(ptr); +} +#else /*LODEPNG_COMPILE_ALLOCATORS*/ +void* lodepng_malloc(size_t size); +void* lodepng_realloc(void* ptr, size_t new_size); +void lodepng_free(void* ptr); +#endif /*LODEPNG_COMPILE_ALLOCATORS*/ + +/* ////////////////////////////////////////////////////////////////////////// */ +/* ////////////////////////////////////////////////////////////////////////// */ +/* // Tools for C, and common code for PNG and Zlib. // */ +/* ////////////////////////////////////////////////////////////////////////// */ +/* ////////////////////////////////////////////////////////////////////////// */ + +/* +Often in case of an error a value is assigned to a variable and then it breaks +out of a loop (to go to the cleanup phase of a function). This macro does that. +It makes the error handling code shorter and more readable. + +Example: if(!uivector_resizev(&frequencies_ll, 286, 0)) ERROR_BREAK(83); +*/ +#define CERROR_BREAK(errorvar, code)\ +{\ + errorvar = code;\ + break;\ +} + +/*version of CERROR_BREAK that assumes the common case where the error variable is named "error"*/ +#define ERROR_BREAK(code) CERROR_BREAK(error, code) + +/*Set error var to the error code, and return it.*/ +#define CERROR_RETURN_ERROR(errorvar, code)\ +{\ + errorvar = code;\ + return code;\ +} + +/*Try the code, if it returns error, also return the error.*/ +#define CERROR_TRY_RETURN(call)\ +{\ + unsigned error = call;\ + if(error) return error;\ +} + +/* +About uivector, ucvector and string: +-All of them wrap dynamic arrays or text strings in a similar way. +-LodePNG was originally written in C++. The vectors replace the std::vectors that were used in the C++ version. +-The string tools are made to avoid problems with compilers that declare things like strncat as deprecated. +-They're not used in the interface, only internally in this file as static functions. +-As with many other structs in this file, the init and cleanup functions serve as ctor and dtor. +*/ + +#ifdef LODEPNG_COMPILE_ZLIB +/*dynamic vector of unsigned ints*/ +typedef struct uivector +{ + unsigned* data; + size_t size; /*size in number of unsigned longs*/ + size_t allocsize; /*allocated size in bytes*/ +} uivector; + +static void uivector_cleanup(void* p) +{ + ((uivector*)p)->size = ((uivector*)p)->allocsize = 0; + lodepng_free(((uivector*)p)->data); + ((uivector*)p)->data = NULL; +} + +/*returns 1 if success, 0 if failure ==> nothing done*/ +static unsigned uivector_reserve(uivector* p, size_t allocsize) +{ + if(allocsize > p->allocsize) + { + size_t newsize = (allocsize > p->allocsize * 2) ? allocsize : (allocsize * 3 / 2); + void* data = lodepng_realloc(p->data, newsize); + if(data) + { + p->allocsize = newsize; + p->data = (unsigned*)data; + } + else return 0; /*error: not enough memory*/ + } + return 1; +} + +/*returns 1 if success, 0 if failure ==> nothing done*/ +static unsigned uivector_resize(uivector* p, size_t size) +{ + if(!uivector_reserve(p, size * sizeof(unsigned))) return 0; + p->size = size; + return 1; /*success*/ +} + +/*resize and give all new elements the value*/ +static unsigned uivector_resizev(uivector* p, size_t size, unsigned value) +{ + size_t oldsize = p->size, i; + if(!uivector_resize(p, size)) return 0; + for(i = oldsize; i < size; i++) p->data[i] = value; + return 1; +} + +static void uivector_init(uivector* p) +{ + p->data = NULL; + p->size = p->allocsize = 0; +} + +#ifdef LODEPNG_COMPILE_ENCODER +/*returns 1 if success, 0 if failure ==> nothing done*/ +static unsigned uivector_push_back(uivector* p, unsigned c) +{ + if(!uivector_resize(p, p->size + 1)) return 0; + p->data[p->size - 1] = c; + return 1; +} + +/*copy q to p, returns 1 if success, 0 if failure ==> nothing done*/ +static unsigned uivector_copy(uivector* p, const uivector* q) +{ + size_t i; + if(!uivector_resize(p, q->size)) return 0; + for(i = 0; i < q->size; i++) p->data[i] = q->data[i]; + return 1; +} +#endif /*LODEPNG_COMPILE_ENCODER*/ +#endif /*LODEPNG_COMPILE_ZLIB*/ + +/* /////////////////////////////////////////////////////////////////////////// */ + +/*dynamic vector of unsigned chars*/ +typedef struct ucvector +{ + unsigned char* data; + size_t size; /*used size*/ + size_t allocsize; /*allocated size*/ +} ucvector; + +/*returns 1 if success, 0 if failure ==> nothing done*/ +static unsigned ucvector_reserve(ucvector* p, size_t allocsize) +{ + if(allocsize > p->allocsize) + { + size_t newsize = (allocsize > p->allocsize * 2) ? allocsize : (allocsize * 3 / 2); + void* data = lodepng_realloc(p->data, newsize); + if(data) + { + p->allocsize = newsize; + p->data = (unsigned char*)data; + } + else return 0; /*error: not enough memory*/ + } + return 1; +} + +/*returns 1 if success, 0 if failure ==> nothing done*/ +static unsigned ucvector_resize(ucvector* p, size_t size) +{ + if(!ucvector_reserve(p, size * sizeof(unsigned char))) return 0; + p->size = size; + return 1; /*success*/ +} + +#ifdef LODEPNG_COMPILE_PNG + +static void ucvector_cleanup(void* p) +{ + ((ucvector*)p)->size = ((ucvector*)p)->allocsize = 0; + lodepng_free(((ucvector*)p)->data); + ((ucvector*)p)->data = NULL; +} + +static void ucvector_init(ucvector* p) +{ + p->data = NULL; + p->size = p->allocsize = 0; +} + +#ifdef LODEPNG_COMPILE_DECODER +/*resize and give all new elements the value*/ +static unsigned ucvector_resizev(ucvector* p, size_t size, unsigned char value) +{ + size_t oldsize = p->size, i; + if(!ucvector_resize(p, size)) return 0; + for(i = oldsize; i < size; i++) p->data[i] = value; + return 1; +} +#endif /*LODEPNG_COMPILE_DECODER*/ +#endif /*LODEPNG_COMPILE_PNG*/ + +#ifdef LODEPNG_COMPILE_ZLIB +/*you can both convert from vector to buffer&size and vica versa. If you use +init_buffer to take over a buffer and size, it is not needed to use cleanup*/ +static void ucvector_init_buffer(ucvector* p, unsigned char* buffer, size_t size) +{ + p->data = buffer; + p->allocsize = p->size = size; +} +#endif /*LODEPNG_COMPILE_ZLIB*/ + +#if (defined(LODEPNG_COMPILE_PNG) && defined(LODEPNG_COMPILE_ANCILLARY_CHUNKS)) || defined(LODEPNG_COMPILE_ENCODER) +/*returns 1 if success, 0 if failure ==> nothing done*/ +static unsigned ucvector_push_back(ucvector* p, unsigned char c) +{ + if(!ucvector_resize(p, p->size + 1)) return 0; + p->data[p->size - 1] = c; + return 1; +} +#endif /*defined(LODEPNG_COMPILE_PNG) || defined(LODEPNG_COMPILE_ENCODER)*/ + + +/* ////////////////////////////////////////////////////////////////////////// */ + +#ifdef LODEPNG_COMPILE_PNG +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS +/*returns 1 if success, 0 if failure ==> nothing done*/ +static unsigned string_resize(char** out, size_t size) +{ + char* data = (char*)lodepng_realloc(*out, size + 1); + if(data) + { + data[size] = 0; /*null termination char*/ + *out = data; + } + return data != 0; +} + +/*init a {char*, size_t} pair for use as string*/ +static void string_init(char** out) +{ + *out = NULL; + string_resize(out, 0); +} + +/*free the above pair again*/ +static void string_cleanup(char** out) +{ + lodepng_free(*out); + *out = NULL; +} + +static void string_set(char** out, const char* in) +{ + size_t insize = strlen(in), i = 0; + if(string_resize(out, insize)) + { + for(i = 0; i < insize; i++) + { + (*out)[i] = in[i]; + } + } +} +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ +#endif /*LODEPNG_COMPILE_PNG*/ + +/* ////////////////////////////////////////////////////////////////////////// */ + +unsigned lodepng_read32bitInt(const unsigned char* buffer) +{ + return (unsigned)((buffer[0] << 24) | (buffer[1] << 16) | (buffer[2] << 8) | buffer[3]); +} + +#if defined(LODEPNG_COMPILE_PNG) || defined(LODEPNG_COMPILE_ENCODER) +/*buffer must have at least 4 allocated bytes available*/ +static void lodepng_set32bitInt(unsigned char* buffer, unsigned value) +{ + buffer[0] = (unsigned char)((value >> 24) & 0xff); + buffer[1] = (unsigned char)((value >> 16) & 0xff); + buffer[2] = (unsigned char)((value >> 8) & 0xff); + buffer[3] = (unsigned char)((value ) & 0xff); +} +#endif /*defined(LODEPNG_COMPILE_PNG) || defined(LODEPNG_COMPILE_ENCODER)*/ + +#ifdef LODEPNG_COMPILE_ENCODER +static void lodepng_add32bitInt(ucvector* buffer, unsigned value) +{ + ucvector_resize(buffer, buffer->size + 4); /*todo: give error if resize failed*/ + lodepng_set32bitInt(&buffer->data[buffer->size - 4], value); +} +#endif /*LODEPNG_COMPILE_ENCODER*/ + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / File IO / */ +/* ////////////////////////////////////////////////////////////////////////// */ + +#ifdef LODEPNG_COMPILE_DISK + +unsigned lodepng_load_file(unsigned char** out, size_t* outsize, const char* filename) +{ + FILE* file; + long size; + + /*provide some proper output values if error will happen*/ + *out = 0; + *outsize = 0; + + file = fopen(filename, "rb"); + if(!file) return 78; + + /*get filesize:*/ + fseek(file , 0 , SEEK_END); + size = ftell(file); + rewind(file); + + /*read contents of the file into the vector*/ + *outsize = 0; + *out = (unsigned char*)lodepng_malloc((size_t)size); + if(size && (*out)) (*outsize) = fread(*out, 1, (size_t)size, file); + + fclose(file); + if(!(*out) && size) return 83; /*the above malloc failed*/ + return 0; +} + +/*write given buffer to the file, overwriting the file, it doesn't append to it.*/ +unsigned lodepng_save_file(const unsigned char* buffer, size_t buffersize, const char* filename) +{ + FILE* file; + file = fopen(filename, "wb" ); + if(!file) return 79; + fwrite((char*)buffer , 1 , buffersize, file); + fclose(file); + return 0; +} + +#endif /*LODEPNG_COMPILE_DISK*/ + +/* ////////////////////////////////////////////////////////////////////////// */ +/* ////////////////////////////////////////////////////////////////////////// */ +/* // End of common code and tools. Begin of Zlib related code. // */ +/* ////////////////////////////////////////////////////////////////////////// */ +/* ////////////////////////////////////////////////////////////////////////// */ + +#ifdef LODEPNG_COMPILE_ZLIB +#ifdef LODEPNG_COMPILE_ENCODER +/*TODO: this ignores potential out of memory errors*/ +#define addBitToStream(/*size_t**/ bitpointer, /*ucvector**/ bitstream, /*unsigned char*/ bit)\ +{\ + /*add a new byte at the end*/\ + if(((*bitpointer) & 7) == 0) ucvector_push_back(bitstream, (unsigned char)0);\ + /*earlier bit of huffman code is in a lesser significant bit of an earlier byte*/\ + (bitstream->data[bitstream->size - 1]) |= (bit << ((*bitpointer) & 0x7));\ + (*bitpointer)++;\ +} + +static void addBitsToStream(size_t* bitpointer, ucvector* bitstream, unsigned value, size_t nbits) +{ + size_t i; + for(i = 0; i < nbits; i++) addBitToStream(bitpointer, bitstream, (unsigned char)((value >> i) & 1)); +} + +static void addBitsToStreamReversed(size_t* bitpointer, ucvector* bitstream, unsigned value, size_t nbits) +{ + size_t i; + for(i = 0; i < nbits; i++) addBitToStream(bitpointer, bitstream, (unsigned char)((value >> (nbits - 1 - i)) & 1)); +} +#endif /*LODEPNG_COMPILE_ENCODER*/ + +#ifdef LODEPNG_COMPILE_DECODER + +#define READBIT(bitpointer, bitstream) ((bitstream[bitpointer >> 3] >> (bitpointer & 0x7)) & (unsigned char)1) + +static unsigned char readBitFromStream(size_t* bitpointer, const unsigned char* bitstream) +{ + unsigned char result = (unsigned char)(READBIT(*bitpointer, bitstream)); + (*bitpointer)++; + return result; +} + +static unsigned readBitsFromStream(size_t* bitpointer, const unsigned char* bitstream, size_t nbits) +{ + unsigned result = 0, i; + for(i = 0; i < nbits; i++) + { + result += ((unsigned)READBIT(*bitpointer, bitstream)) << i; + (*bitpointer)++; + } + return result; +} +#endif /*LODEPNG_COMPILE_DECODER*/ + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / Deflate - Huffman / */ +/* ////////////////////////////////////////////////////////////////////////// */ + +#define FIRST_LENGTH_CODE_INDEX 257 +#define LAST_LENGTH_CODE_INDEX 285 +/*256 literals, the end code, some length codes, and 2 unused codes*/ +#define NUM_DEFLATE_CODE_SYMBOLS 288 +/*the distance codes have their own symbols, 30 used, 2 unused*/ +#define NUM_DISTANCE_SYMBOLS 32 +/*the code length codes. 0-15: code lengths, 16: copy previous 3-6 times, 17: 3-10 zeros, 18: 11-138 zeros*/ +#define NUM_CODE_LENGTH_CODES 19 + +/*the base lengths represented by codes 257-285*/ +static const unsigned LENGTHBASE[29] + = {3, 4, 5, 6, 7, 8, 9, 10, 11, 13, 15, 17, 19, 23, 27, 31, 35, 43, 51, 59, + 67, 83, 99, 115, 131, 163, 195, 227, 258}; + +/*the extra bits used by codes 257-285 (added to base length)*/ +static const unsigned LENGTHEXTRA[29] + = {0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 2, 2, 2, 2, 3, 3, 3, 3, + 4, 4, 4, 4, 5, 5, 5, 5, 0}; + +/*the base backwards distances (the bits of distance codes appear after length codes and use their own huffman tree)*/ +static const unsigned DISTANCEBASE[30] + = {1, 2, 3, 4, 5, 7, 9, 13, 17, 25, 33, 49, 65, 97, 129, 193, 257, 385, 513, + 769, 1025, 1537, 2049, 3073, 4097, 6145, 8193, 12289, 16385, 24577}; + +/*the extra bits of backwards distances (added to base)*/ +static const unsigned DISTANCEEXTRA[30] + = {0, 0, 0, 0, 1, 1, 2, 2, 3, 3, 4, 4, 5, 5, 6, 6, 7, 7, 8, + 8, 9, 9, 10, 10, 11, 11, 12, 12, 13, 13}; + +/*the order in which "code length alphabet code lengths" are stored, out of this +the huffman tree of the dynamic huffman tree lengths is generated*/ +static const unsigned CLCL_ORDER[NUM_CODE_LENGTH_CODES] + = {16, 17, 18, 0, 8, 7, 9, 6, 10, 5, 11, 4, 12, 3, 13, 2, 14, 1, 15}; + +/* ////////////////////////////////////////////////////////////////////////// */ + +/* +Huffman tree struct, containing multiple representations of the tree +*/ +typedef struct HuffmanTree +{ + unsigned* tree2d; + unsigned* tree1d; + unsigned* lengths; /*the lengths of the codes of the 1d-tree*/ + unsigned maxbitlen; /*maximum number of bits a single code can get*/ + unsigned numcodes; /*number of symbols in the alphabet = number of codes*/ +} HuffmanTree; + +/*function used for debug purposes to draw the tree in ascii art with C++*/ +/* +static void HuffmanTree_draw(HuffmanTree* tree) +{ + std::cout << "tree. length: " << tree->numcodes << " maxbitlen: " << tree->maxbitlen << std::endl; + for(size_t i = 0; i < tree->tree1d.size; i++) + { + if(tree->lengths.data[i]) + std::cout << i << " " << tree->tree1d.data[i] << " " << tree->lengths.data[i] << std::endl; + } + std::cout << std::endl; +}*/ + +static void HuffmanTree_init(HuffmanTree* tree) +{ + tree->tree2d = 0; + tree->tree1d = 0; + tree->lengths = 0; +} + +static void HuffmanTree_cleanup(HuffmanTree* tree) +{ + lodepng_free(tree->tree2d); + lodepng_free(tree->tree1d); + lodepng_free(tree->lengths); +} + +/*the tree representation used by the decoder. return value is error*/ +static unsigned HuffmanTree_make2DTree(HuffmanTree* tree) +{ + unsigned nodefilled = 0; /*up to which node it is filled*/ + unsigned treepos = 0; /*position in the tree (1 of the numcodes columns)*/ + unsigned n, i; + + tree->tree2d = (unsigned*)lodepng_malloc(tree->numcodes * 2 * sizeof(unsigned)); + if(!tree->tree2d) return 83; /*alloc fail*/ + + /* + convert tree1d[] to tree2d[][]. In the 2D array, a value of 32767 means + uninited, a value >= numcodes is an address to another bit, a value < numcodes + is a code. The 2 rows are the 2 possible bit values (0 or 1), there are as + many columns as codes - 1. + A good huffmann tree has N * 2 - 1 nodes, of which N - 1 are internal nodes. + Here, the internal nodes are stored (what their 0 and 1 option point to). + There is only memory for such good tree currently, if there are more nodes + (due to too long length codes), error 55 will happen + */ + for(n = 0; n < tree->numcodes * 2; n++) + { + tree->tree2d[n] = 32767; /*32767 here means the tree2d isn't filled there yet*/ + } + + for(n = 0; n < tree->numcodes; n++) /*the codes*/ + { + for(i = 0; i < tree->lengths[n]; i++) /*the bits for this code*/ + { + unsigned char bit = (unsigned char)((tree->tree1d[n] >> (tree->lengths[n] - i - 1)) & 1); + if(treepos > tree->numcodes - 2) return 55; /*oversubscribed, see comment in lodepng_error_text*/ + if(tree->tree2d[2 * treepos + bit] == 32767) /*not yet filled in*/ + { + if(i + 1 == tree->lengths[n]) /*last bit*/ + { + tree->tree2d[2 * treepos + bit] = n; /*put the current code in it*/ + treepos = 0; + } + else + { + /*put address of the next step in here, first that address has to be found of course + (it's just nodefilled + 1)...*/ + nodefilled++; + /*addresses encoded with numcodes added to it*/ + tree->tree2d[2 * treepos + bit] = nodefilled + tree->numcodes; + treepos = nodefilled; + } + } + else treepos = tree->tree2d[2 * treepos + bit] - tree->numcodes; + } + } + + for(n = 0; n < tree->numcodes * 2; n++) + { + if(tree->tree2d[n] == 32767) tree->tree2d[n] = 0; /*remove possible remaining 32767's*/ + } + + return 0; +} + +/* +Second step for the ...makeFromLengths and ...makeFromFrequencies functions. +numcodes, lengths and maxbitlen must already be filled in correctly. return +value is error. +*/ +static unsigned HuffmanTree_makeFromLengths2(HuffmanTree* tree) +{ + uivector blcount; + uivector nextcode; + unsigned bits, n, error = 0; + + uivector_init(&blcount); + uivector_init(&nextcode); + + tree->tree1d = (unsigned*)lodepng_malloc(tree->numcodes * sizeof(unsigned)); + if(!tree->tree1d) error = 83; /*alloc fail*/ + + if(!uivector_resizev(&blcount, tree->maxbitlen + 1, 0) + || !uivector_resizev(&nextcode, tree->maxbitlen + 1, 0)) + error = 83; /*alloc fail*/ + + if(!error) + { + /*step 1: count number of instances of each code length*/ + for(bits = 0; bits < tree->numcodes; bits++) blcount.data[tree->lengths[bits]]++; + /*step 2: generate the nextcode values*/ + for(bits = 1; bits <= tree->maxbitlen; bits++) + { + nextcode.data[bits] = (nextcode.data[bits - 1] + blcount.data[bits - 1]) << 1; + } + /*step 3: generate all the codes*/ + for(n = 0; n < tree->numcodes; n++) + { + if(tree->lengths[n] != 0) tree->tree1d[n] = nextcode.data[tree->lengths[n]]++; + } + } + + uivector_cleanup(&blcount); + uivector_cleanup(&nextcode); + + if(!error) return HuffmanTree_make2DTree(tree); + else return error; +} + +/* +given the code lengths (as stored in the PNG file), generate the tree as defined +by Deflate. maxbitlen is the maximum bits that a code in the tree can have. +return value is error. +*/ +static unsigned HuffmanTree_makeFromLengths(HuffmanTree* tree, const unsigned* bitlen, + size_t numcodes, unsigned maxbitlen) +{ + unsigned i; + tree->lengths = (unsigned*)lodepng_malloc(numcodes * sizeof(unsigned)); + if(!tree->lengths) return 83; /*alloc fail*/ + for(i = 0; i < numcodes; i++) tree->lengths[i] = bitlen[i]; + tree->numcodes = (unsigned)numcodes; /*number of symbols*/ + tree->maxbitlen = maxbitlen; + return HuffmanTree_makeFromLengths2(tree); +} + +#ifdef LODEPNG_COMPILE_ENCODER + +/* +A coin, this is the terminology used for the package-merge algorithm and the +coin collector's problem. This is used to generate the huffman tree. +A coin can be multiple coins (when they're merged) +*/ +typedef struct Coin +{ + uivector symbols; + float weight; /*the sum of all weights in this coin*/ +} Coin; + +static void coin_init(Coin* c) +{ + uivector_init(&c->symbols); +} + +/*argument c is void* so that this dtor can be given as function pointer to the vector resize function*/ +static void coin_cleanup(void* c) +{ + uivector_cleanup(&((Coin*)c)->symbols); +} + +static void coin_copy(Coin* c1, const Coin* c2) +{ + c1->weight = c2->weight; + uivector_copy(&c1->symbols, &c2->symbols); +} + +static void add_coins(Coin* c1, const Coin* c2) +{ + size_t i; + for(i = 0; i < c2->symbols.size; i++) uivector_push_back(&c1->symbols, c2->symbols.data[i]); + c1->weight += c2->weight; +} + +static void init_coins(Coin* coins, size_t num) +{ + size_t i; + for(i = 0; i < num; i++) coin_init(&coins[i]); +} + +static void cleanup_coins(Coin* coins, size_t num) +{ + size_t i; + for(i = 0; i < num; i++) coin_cleanup(&coins[i]); +} + +static int coin_compare(const void* a, const void* b) { + float wa = ((const Coin*)a)->weight; + float wb = ((const Coin*)b)->weight; + return wa > wb ? 1 : wa < wb ? -1 : 0; +} + +static unsigned append_symbol_coins(Coin* coins, const unsigned* frequencies, unsigned numcodes, size_t sum) +{ + unsigned i; + unsigned j = 0; /*index of present symbols*/ + for(i = 0; i < numcodes; i++) + { + if(frequencies[i] != 0) /*only include symbols that are present*/ + { + coins[j].weight = frequencies[i] / (float)sum; + uivector_push_back(&coins[j].symbols, i); + j++; + } + } + return 0; +} + +unsigned lodepng_huffman_code_lengths(unsigned* lengths, const unsigned* frequencies, + size_t numcodes, unsigned maxbitlen) +{ + unsigned i, j; + size_t sum = 0, numpresent = 0; + unsigned error = 0; + Coin* coins; /*the coins of the currently calculated row*/ + Coin* prev_row; /*the previous row of coins*/ + size_t numcoins; + size_t coinmem; + + if(numcodes == 0) return 80; /*error: a tree of 0 symbols is not supposed to be made*/ + + for(i = 0; i < numcodes; i++) + { + if(frequencies[i] > 0) + { + numpresent++; + sum += frequencies[i]; + } + } + + for(i = 0; i < numcodes; i++) lengths[i] = 0; + + /*ensure at least two present symbols. There should be at least one symbol + according to RFC 1951 section 3.2.7. To decoders incorrectly require two. To + make these work as well ensure there are at least two symbols. The + Package-Merge code below also doesn't work correctly if there's only one + symbol, it'd give it the theoritical 0 bits but in practice zlib wants 1 bit*/ + if(numpresent == 0) + { + lengths[0] = lengths[1] = 1; /*note that for RFC 1951 section 3.2.7, only lengths[0] = 1 is needed*/ + } + else if(numpresent == 1) + { + for(i = 0; i < numcodes; i++) + { + if(frequencies[i]) + { + lengths[i] = 1; + lengths[i == 0 ? 1 : 0] = 1; + break; + } + } + } + else + { + /*Package-Merge algorithm represented by coin collector's problem + For every symbol, maxbitlen coins will be created*/ + + coinmem = numpresent * 2; /*max amount of coins needed with the current algo*/ + coins = (Coin*)lodepng_malloc(sizeof(Coin) * coinmem); + prev_row = (Coin*)lodepng_malloc(sizeof(Coin) * coinmem); + if(!coins || !prev_row) + { + lodepng_free(coins); + lodepng_free(prev_row); + return 83; /*alloc fail*/ + } + init_coins(coins, coinmem); + init_coins(prev_row, coinmem); + + /*first row, lowest denominator*/ + error = append_symbol_coins(coins, frequencies, numcodes, sum); + numcoins = numpresent; + qsort(coins, numcoins, sizeof(Coin), coin_compare); + if(!error) + { + unsigned numprev = 0; + for(j = 1; j <= maxbitlen && !error; j++) /*each of the remaining rows*/ + { + unsigned tempnum; + Coin* tempcoins; + /*swap prev_row and coins, and their amounts*/ + tempcoins = prev_row; prev_row = coins; coins = tempcoins; + tempnum = numprev; numprev = numcoins; numcoins = tempnum; + + cleanup_coins(coins, numcoins); + init_coins(coins, numcoins); + + numcoins = 0; + + /*fill in the merged coins of the previous row*/ + for(i = 0; i + 1 < numprev; i += 2) + { + /*merge prev_row[i] and prev_row[i + 1] into new coin*/ + Coin* coin = &coins[numcoins++]; + coin_copy(coin, &prev_row[i]); + add_coins(coin, &prev_row[i + 1]); + } + /*fill in all the original symbols again*/ + if(j < maxbitlen) + { + error = append_symbol_coins(coins + numcoins, frequencies, numcodes, sum); + numcoins += numpresent; + } + qsort(coins, numcoins, sizeof(Coin), coin_compare); + } + } + + if(!error) + { + /*calculate the lenghts of each symbol, as the amount of times a coin of each symbol is used*/ + for(i = 0; i < numpresent - 1; i++) + { + Coin* coin = &coins[i]; + for(j = 0; j < coin->symbols.size; j++) lengths[coin->symbols.data[j]]++; + } + } + + cleanup_coins(coins, coinmem); + lodepng_free(coins); + cleanup_coins(prev_row, coinmem); + lodepng_free(prev_row); + } + + return error; +} + +/*Create the Huffman tree given the symbol frequencies*/ +static unsigned HuffmanTree_makeFromFrequencies(HuffmanTree* tree, const unsigned* frequencies, + size_t mincodes, size_t numcodes, unsigned maxbitlen) +{ + unsigned error = 0; + while(!frequencies[numcodes - 1] && numcodes > mincodes) numcodes--; /*trim zeroes*/ + tree->maxbitlen = maxbitlen; + tree->numcodes = (unsigned)numcodes; /*number of symbols*/ + tree->lengths = (unsigned*)lodepng_realloc(tree->lengths, numcodes * sizeof(unsigned)); + if(!tree->lengths) return 83; /*alloc fail*/ + /*initialize all lengths to 0*/ + memset(tree->lengths, 0, numcodes * sizeof(unsigned)); + + error = lodepng_huffman_code_lengths(tree->lengths, frequencies, numcodes, maxbitlen); + if(!error) error = HuffmanTree_makeFromLengths2(tree); + return error; +} + +static unsigned HuffmanTree_getCode(const HuffmanTree* tree, unsigned index) +{ + return tree->tree1d[index]; +} + +static unsigned HuffmanTree_getLength(const HuffmanTree* tree, unsigned index) +{ + return tree->lengths[index]; +} +#endif /*LODEPNG_COMPILE_ENCODER*/ + +/*get the literal and length code tree of a deflated block with fixed tree, as per the deflate specification*/ +static unsigned generateFixedLitLenTree(HuffmanTree* tree) +{ + unsigned i, error = 0; + unsigned* bitlen = (unsigned*)lodepng_malloc(NUM_DEFLATE_CODE_SYMBOLS * sizeof(unsigned)); + if(!bitlen) return 83; /*alloc fail*/ + + /*288 possible codes: 0-255=literals, 256=endcode, 257-285=lengthcodes, 286-287=unused*/ + for(i = 0; i <= 143; i++) bitlen[i] = 8; + for(i = 144; i <= 255; i++) bitlen[i] = 9; + for(i = 256; i <= 279; i++) bitlen[i] = 7; + for(i = 280; i <= 287; i++) bitlen[i] = 8; + + error = HuffmanTree_makeFromLengths(tree, bitlen, NUM_DEFLATE_CODE_SYMBOLS, 15); + + lodepng_free(bitlen); + return error; +} + +/*get the distance code tree of a deflated block with fixed tree, as specified in the deflate specification*/ +static unsigned generateFixedDistanceTree(HuffmanTree* tree) +{ + unsigned i, error = 0; + unsigned* bitlen = (unsigned*)lodepng_malloc(NUM_DISTANCE_SYMBOLS * sizeof(unsigned)); + if(!bitlen) return 83; /*alloc fail*/ + + /*there are 32 distance codes, but 30-31 are unused*/ + for(i = 0; i < NUM_DISTANCE_SYMBOLS; i++) bitlen[i] = 5; + error = HuffmanTree_makeFromLengths(tree, bitlen, NUM_DISTANCE_SYMBOLS, 15); + + lodepng_free(bitlen); + return error; +} + +#ifdef LODEPNG_COMPILE_DECODER + +/* +returns the code, or (unsigned)(-1) if error happened +inbitlength is the length of the complete buffer, in bits (so its byte length times 8) +*/ +static unsigned huffmanDecodeSymbol(const unsigned char* in, size_t* bp, + const HuffmanTree* codetree, size_t inbitlength) +{ + unsigned treepos = 0, ct; + for(;;) + { + if(*bp >= inbitlength) return (unsigned)(-1); /*error: end of input memory reached without endcode*/ + /* + decode the symbol from the tree. The "readBitFromStream" code is inlined in + the expression below because this is the biggest bottleneck while decoding + */ + ct = codetree->tree2d[(treepos << 1) + READBIT(*bp, in)]; + (*bp)++; + if(ct < codetree->numcodes) return ct; /*the symbol is decoded, return it*/ + else treepos = ct - codetree->numcodes; /*symbol not yet decoded, instead move tree position*/ + + if(treepos >= codetree->numcodes) return (unsigned)(-1); /*error: it appeared outside the codetree*/ + } +} +#endif /*LODEPNG_COMPILE_DECODER*/ + +#ifdef LODEPNG_COMPILE_DECODER + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / Inflator (Decompressor) / */ +/* ////////////////////////////////////////////////////////////////////////// */ + +/*get the tree of a deflated block with fixed tree, as specified in the deflate specification*/ +static void getTreeInflateFixed(HuffmanTree* tree_ll, HuffmanTree* tree_d) +{ + /*TODO: check for out of memory errors*/ + generateFixedLitLenTree(tree_ll); + generateFixedDistanceTree(tree_d); +} + +/*get the tree of a deflated block with dynamic tree, the tree itself is also Huffman compressed with a known tree*/ +static unsigned getTreeInflateDynamic(HuffmanTree* tree_ll, HuffmanTree* tree_d, + const unsigned char* in, size_t* bp, size_t inlength) +{ + /*make sure that length values that aren't filled in will be 0, or a wrong tree will be generated*/ + unsigned error = 0; + unsigned n, HLIT, HDIST, HCLEN, i; + size_t inbitlength = inlength * 8; + + /*see comments in deflateDynamic for explanation of the context and these variables, it is analogous*/ + unsigned* bitlen_ll = 0; /*lit,len code lengths*/ + unsigned* bitlen_d = 0; /*dist code lengths*/ + /*code length code lengths ("clcl"), the bit lengths of the huffman tree used to compress bitlen_ll and bitlen_d*/ + unsigned* bitlen_cl = 0; + HuffmanTree tree_cl; /*the code tree for code length codes (the huffman tree for compressed huffman trees)*/ + + if((*bp) >> 3 >= inlength - 2) return 49; /*error: the bit pointer is or will go past the memory*/ + + /*number of literal/length codes + 257. Unlike the spec, the value 257 is added to it here already*/ + HLIT = readBitsFromStream(bp, in, 5) + 257; + /*number of distance codes. Unlike the spec, the value 1 is added to it here already*/ + HDIST = readBitsFromStream(bp, in, 5) + 1; + /*number of code length codes. Unlike the spec, the value 4 is added to it here already*/ + HCLEN = readBitsFromStream(bp, in, 4) + 4; + + HuffmanTree_init(&tree_cl); + + while(!error) + { + /*read the code length codes out of 3 * (amount of code length codes) bits*/ + + bitlen_cl = (unsigned*)lodepng_malloc(NUM_CODE_LENGTH_CODES * sizeof(unsigned)); + if(!bitlen_cl) ERROR_BREAK(83 /*alloc fail*/); + + for(i = 0; i < NUM_CODE_LENGTH_CODES; i++) + { + if(i < HCLEN) bitlen_cl[CLCL_ORDER[i]] = readBitsFromStream(bp, in, 3); + else bitlen_cl[CLCL_ORDER[i]] = 0; /*if not, it must stay 0*/ + } + + error = HuffmanTree_makeFromLengths(&tree_cl, bitlen_cl, NUM_CODE_LENGTH_CODES, 7); + if(error) break; + + /*now we can use this tree to read the lengths for the tree that this function will return*/ + bitlen_ll = (unsigned*)lodepng_malloc(NUM_DEFLATE_CODE_SYMBOLS * sizeof(unsigned)); + bitlen_d = (unsigned*)lodepng_malloc(NUM_DISTANCE_SYMBOLS * sizeof(unsigned)); + if(!bitlen_ll || !bitlen_d) ERROR_BREAK(83 /*alloc fail*/); + for(i = 0; i < NUM_DEFLATE_CODE_SYMBOLS; i++) bitlen_ll[i] = 0; + for(i = 0; i < NUM_DISTANCE_SYMBOLS; i++) bitlen_d[i] = 0; + + /*i is the current symbol we're reading in the part that contains the code lengths of lit/len and dist codes*/ + i = 0; + while(i < HLIT + HDIST) + { + unsigned code = huffmanDecodeSymbol(in, bp, &tree_cl, inbitlength); + if(code <= 15) /*a length code*/ + { + if(i < HLIT) bitlen_ll[i] = code; + else bitlen_d[i - HLIT] = code; + i++; + } + else if(code == 16) /*repeat previous*/ + { + unsigned replength = 3; /*read in the 2 bits that indicate repeat length (3-6)*/ + unsigned value; /*set value to the previous code*/ + + if(*bp >= inbitlength) ERROR_BREAK(50); /*error, bit pointer jumps past memory*/ + if (i == 0) ERROR_BREAK(54); /*can't repeat previous if i is 0*/ + + replength += readBitsFromStream(bp, in, 2); + + if(i < HLIT + 1) value = bitlen_ll[i - 1]; + else value = bitlen_d[i - HLIT - 1]; + /*repeat this value in the next lengths*/ + for(n = 0; n < replength; n++) + { + if(i >= HLIT + HDIST) ERROR_BREAK(13); /*error: i is larger than the amount of codes*/ + if(i < HLIT) bitlen_ll[i] = value; + else bitlen_d[i - HLIT] = value; + i++; + } + } + else if(code == 17) /*repeat "0" 3-10 times*/ + { + unsigned replength = 3; /*read in the bits that indicate repeat length*/ + if(*bp >= inbitlength) ERROR_BREAK(50); /*error, bit pointer jumps past memory*/ + + replength += readBitsFromStream(bp, in, 3); + + /*repeat this value in the next lengths*/ + for(n = 0; n < replength; n++) + { + if(i >= HLIT + HDIST) ERROR_BREAK(14); /*error: i is larger than the amount of codes*/ + + if(i < HLIT) bitlen_ll[i] = 0; + else bitlen_d[i - HLIT] = 0; + i++; + } + } + else if(code == 18) /*repeat "0" 11-138 times*/ + { + unsigned replength = 11; /*read in the bits that indicate repeat length*/ + if(*bp >= inbitlength) ERROR_BREAK(50); /*error, bit pointer jumps past memory*/ + + replength += readBitsFromStream(bp, in, 7); + + /*repeat this value in the next lengths*/ + for(n = 0; n < replength; n++) + { + if(i >= HLIT + HDIST) ERROR_BREAK(15); /*error: i is larger than the amount of codes*/ + + if(i < HLIT) bitlen_ll[i] = 0; + else bitlen_d[i - HLIT] = 0; + i++; + } + } + else /*if(code == (unsigned)(-1))*/ /*huffmanDecodeSymbol returns (unsigned)(-1) in case of error*/ + { + if(code == (unsigned)(-1)) + { + /*return error code 10 or 11 depending on the situation that happened in huffmanDecodeSymbol + (10=no endcode, 11=wrong jump outside of tree)*/ + error = (*bp) > inbitlength ? 10 : 11; + } + else error = 16; /*unexisting code, this can never happen*/ + break; + } + } + if(error) break; + + if(bitlen_ll[256] == 0) ERROR_BREAK(64); /*the length of the end code 256 must be larger than 0*/ + + /*now we've finally got HLIT and HDIST, so generate the code trees, and the function is done*/ + error = HuffmanTree_makeFromLengths(tree_ll, bitlen_ll, NUM_DEFLATE_CODE_SYMBOLS, 15); + if(error) break; + error = HuffmanTree_makeFromLengths(tree_d, bitlen_d, NUM_DISTANCE_SYMBOLS, 15); + + break; /*end of error-while*/ + } + + lodepng_free(bitlen_cl); + lodepng_free(bitlen_ll); + lodepng_free(bitlen_d); + HuffmanTree_cleanup(&tree_cl); + + return error; +} + +/*inflate a block with dynamic of fixed Huffman tree*/ +static unsigned inflateHuffmanBlock(ucvector* out, const unsigned char* in, size_t* bp, + size_t* pos, size_t inlength, unsigned btype) +{ + unsigned error = 0; + HuffmanTree tree_ll; /*the huffman tree for literal and length codes*/ + HuffmanTree tree_d; /*the huffman tree for distance codes*/ + size_t inbitlength = inlength * 8; + + HuffmanTree_init(&tree_ll); + HuffmanTree_init(&tree_d); + + if(btype == 1) getTreeInflateFixed(&tree_ll, &tree_d); + else if(btype == 2) error = getTreeInflateDynamic(&tree_ll, &tree_d, in, bp, inlength); + + while(!error) /*decode all symbols until end reached, breaks at end code*/ + { + /*code_ll is literal, length or end code*/ + unsigned code_ll = huffmanDecodeSymbol(in, bp, &tree_ll, inbitlength); + if(code_ll <= 255) /*literal symbol*/ + { + /*ucvector_push_back would do the same, but for some reason the two lines below run 10% faster*/ + if(!ucvector_resize(out, (*pos) + 1)) ERROR_BREAK(83 /*alloc fail*/); + out->data[*pos] = (unsigned char)code_ll; + (*pos)++; + } + else if(code_ll >= FIRST_LENGTH_CODE_INDEX && code_ll <= LAST_LENGTH_CODE_INDEX) /*length code*/ + { + unsigned code_d, distance; + unsigned numextrabits_l, numextrabits_d; /*extra bits for length and distance*/ + size_t start, forward, backward, length; + + /*part 1: get length base*/ + length = LENGTHBASE[code_ll - FIRST_LENGTH_CODE_INDEX]; + + /*part 2: get extra bits and add the value of that to length*/ + numextrabits_l = LENGTHEXTRA[code_ll - FIRST_LENGTH_CODE_INDEX]; + if(*bp >= inbitlength) ERROR_BREAK(51); /*error, bit pointer will jump past memory*/ + length += readBitsFromStream(bp, in, numextrabits_l); + + /*part 3: get distance code*/ + code_d = huffmanDecodeSymbol(in, bp, &tree_d, inbitlength); + if(code_d > 29) + { + if(code_ll == (unsigned)(-1)) /*huffmanDecodeSymbol returns (unsigned)(-1) in case of error*/ + { + /*return error code 10 or 11 depending on the situation that happened in huffmanDecodeSymbol + (10=no endcode, 11=wrong jump outside of tree)*/ + error = (*bp) > inlength * 8 ? 10 : 11; + } + else error = 18; /*error: invalid distance code (30-31 are never used)*/ + break; + } + distance = DISTANCEBASE[code_d]; + + /*part 4: get extra bits from distance*/ + numextrabits_d = DISTANCEEXTRA[code_d]; + if(*bp >= inbitlength) ERROR_BREAK(51); /*error, bit pointer will jump past memory*/ + + distance += readBitsFromStream(bp, in, numextrabits_d); + + /*part 5: fill in all the out[n] values based on the length and dist*/ + start = (*pos); + if(distance > start) ERROR_BREAK(52); /*too long backward distance*/ + backward = start - distance; + + if(!ucvector_resize(out, (*pos) + length)) ERROR_BREAK(83 /*alloc fail*/); + for(forward = 0; forward < length; forward++) + { + out->data[(*pos)] = out->data[backward]; + (*pos)++; + backward++; + if(backward >= start) backward = start - distance; + } + } + else if(code_ll == 256) + { + break; /*end code, break the loop*/ + } + else /*if(code == (unsigned)(-1))*/ /*huffmanDecodeSymbol returns (unsigned)(-1) in case of error*/ + { + /*return error code 10 or 11 depending on the situation that happened in huffmanDecodeSymbol + (10=no endcode, 11=wrong jump outside of tree)*/ + error = (*bp) > inlength * 8 ? 10 : 11; + break; + } + } + + HuffmanTree_cleanup(&tree_ll); + HuffmanTree_cleanup(&tree_d); + + return error; +} + +static unsigned inflateNoCompression(ucvector* out, const unsigned char* in, size_t* bp, size_t* pos, size_t inlength) +{ + /*go to first boundary of byte*/ + size_t p; + unsigned LEN, NLEN, n, error = 0; + while(((*bp) & 0x7) != 0) (*bp)++; + p = (*bp) / 8; /*byte position*/ + + /*read LEN (2 bytes) and NLEN (2 bytes)*/ + if(p >= inlength - 4) return 52; /*error, bit pointer will jump past memory*/ + LEN = in[p] + 256u * in[p + 1]; p += 2; + NLEN = in[p] + 256u * in[p + 1]; p += 2; + + /*check if 16-bit NLEN is really the one's complement of LEN*/ + if(LEN + NLEN != 65535) return 21; /*error: NLEN is not one's complement of LEN*/ + + if(!ucvector_resize(out, (*pos) + LEN)) return 83; /*alloc fail*/ + + /*read the literal data: LEN bytes are now stored in the out buffer*/ + if(p + LEN > inlength) return 23; /*error: reading outside of in buffer*/ + for(n = 0; n < LEN; n++) out->data[(*pos)++] = in[p++]; + + (*bp) = p * 8; + + return error; +} + +static unsigned lodepng_inflatev(ucvector* out, + const unsigned char* in, size_t insize, + const LodePNGDecompressSettings* settings) +{ + /*bit pointer in the "in" data, current byte is bp >> 3, current bit is bp & 0x7 (from lsb to msb of the byte)*/ + size_t bp = 0; + unsigned BFINAL = 0; + size_t pos = 0; /*byte position in the out buffer*/ + unsigned error = 0; + + (void)settings; + + while(!BFINAL) + { + unsigned BTYPE; + if(bp + 2 >= insize * 8) return 52; /*error, bit pointer will jump past memory*/ + BFINAL = readBitFromStream(&bp, in); + BTYPE = 1u * readBitFromStream(&bp, in); + BTYPE += 2u * readBitFromStream(&bp, in); + + if(BTYPE == 3) return 20; /*error: invalid BTYPE*/ + else if(BTYPE == 0) error = inflateNoCompression(out, in, &bp, &pos, insize); /*no compression*/ + else error = inflateHuffmanBlock(out, in, &bp, &pos, insize, BTYPE); /*compression, BTYPE 01 or 10*/ + + if(error) return error; + } + + return error; +} + +unsigned lodepng_inflate(unsigned char** out, size_t* outsize, + const unsigned char* in, size_t insize, + const LodePNGDecompressSettings* settings) +{ + unsigned error; + ucvector v; + ucvector_init_buffer(&v, *out, *outsize); + error = lodepng_inflatev(&v, in, insize, settings); + *out = v.data; + *outsize = v.size; + return error; +} + +static unsigned inflate(unsigned char** out, size_t* outsize, + const unsigned char* in, size_t insize, + const LodePNGDecompressSettings* settings) +{ + if(settings->custom_inflate) + { + return settings->custom_inflate(out, outsize, in, insize, settings); + } + else + { + return lodepng_inflate(out, outsize, in, insize, settings); + } +} + +#endif /*LODEPNG_COMPILE_DECODER*/ + +#ifdef LODEPNG_COMPILE_ENCODER + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / Deflator (Compressor) / */ +/* ////////////////////////////////////////////////////////////////////////// */ + +static const size_t MAX_SUPPORTED_DEFLATE_LENGTH = 258; + +/*bitlen is the size in bits of the code*/ +static void addHuffmanSymbol(size_t* bp, ucvector* compressed, unsigned code, unsigned bitlen) +{ + addBitsToStreamReversed(bp, compressed, code, bitlen); +} + +/*search the index in the array, that has the largest value smaller than or equal to the given value, +given array must be sorted (if no value is smaller, it returns the size of the given array)*/ +static size_t searchCodeIndex(const unsigned* array, size_t array_size, size_t value) +{ + /*linear search implementation*/ + /*for(size_t i = 1; i < array_size; i++) if(array[i] > value) return i - 1; + return array_size - 1;*/ + + /*binary search implementation (not that much faster) (precondition: array_size > 0)*/ + size_t left = 1; + size_t right = array_size - 1; + while(left <= right) + { + size_t mid = (left + right) / 2; + if(array[mid] <= value) left = mid + 1; /*the value to find is more to the right*/ + else if(array[mid - 1] > value) right = mid - 1; /*the value to find is more to the left*/ + else return mid - 1; + } + return array_size - 1; +} + +static void addLengthDistance(uivector* values, size_t length, size_t distance) +{ + /*values in encoded vector are those used by deflate: + 0-255: literal bytes + 256: end + 257-285: length/distance pair (length code, followed by extra length bits, distance code, extra distance bits) + 286-287: invalid*/ + + unsigned length_code = (unsigned)searchCodeIndex(LENGTHBASE, 29, length); + unsigned extra_length = (unsigned)(length - LENGTHBASE[length_code]); + unsigned dist_code = (unsigned)searchCodeIndex(DISTANCEBASE, 30, distance); + unsigned extra_distance = (unsigned)(distance - DISTANCEBASE[dist_code]); + + uivector_push_back(values, length_code + FIRST_LENGTH_CODE_INDEX); + uivector_push_back(values, extra_length); + uivector_push_back(values, dist_code); + uivector_push_back(values, extra_distance); +} + +/*3 bytes of data get encoded into two bytes. The hash cannot use more than 3 +bytes as input because 3 is the minimum match length for deflate*/ +static const unsigned HASH_NUM_VALUES = 65536; +static const unsigned HASH_BIT_MASK = 65535; /*HASH_NUM_VALUES - 1, but C90 does not like that as initializer*/ + +typedef struct Hash +{ + int* head; /*hash value to head circular pos - can be outdated if went around window*/ + /*circular pos to prev circular pos*/ + unsigned short* chain; + int* val; /*circular pos to hash value*/ + + /*TODO: do this not only for zeros but for any repeated byte. However for PNG + it's always going to be the zeros that dominate, so not important for PNG*/ + int* headz; /*similar to head, but for chainz*/ + unsigned short* chainz; /*those with same amount of zeros*/ + unsigned short* zeros; /*length of zeros streak, used as a second hash chain*/ +} Hash; + +static unsigned hash_init(Hash* hash, unsigned windowsize) +{ + unsigned i; + hash->head = (int*)lodepng_malloc(sizeof(int) * HASH_NUM_VALUES); + hash->val = (int*)lodepng_malloc(sizeof(int) * windowsize); + hash->chain = (unsigned short*)lodepng_malloc(sizeof(unsigned short) * windowsize); + + hash->zeros = (unsigned short*)lodepng_malloc(sizeof(unsigned short) * windowsize); + hash->headz = (int*)lodepng_malloc(sizeof(int) * (MAX_SUPPORTED_DEFLATE_LENGTH + 1)); + hash->chainz = (unsigned short*)lodepng_malloc(sizeof(unsigned short) * windowsize); + + if(!hash->head || !hash->chain || !hash->val || !hash->headz|| !hash->chainz || !hash->zeros) + { + return 83; /*alloc fail*/ + } + + /*initialize hash table*/ + for(i = 0; i < HASH_NUM_VALUES; i++) hash->head[i] = -1; + for(i = 0; i < windowsize; i++) hash->val[i] = -1; + for(i = 0; i < windowsize; i++) hash->chain[i] = i; /*same value as index indicates uninitialized*/ + + for(i = 0; i <= MAX_SUPPORTED_DEFLATE_LENGTH; i++) hash->headz[i] = -1; + for(i = 0; i < windowsize; i++) hash->chainz[i] = i; /*same value as index indicates uninitialized*/ + + return 0; +} + +static void hash_cleanup(Hash* hash) +{ + lodepng_free(hash->head); + lodepng_free(hash->val); + lodepng_free(hash->chain); + + lodepng_free(hash->zeros); + lodepng_free(hash->headz); + lodepng_free(hash->chainz); +} + + + +static unsigned getHash(const unsigned char* data, size_t size, size_t pos) +{ + unsigned result = 0; + if (pos + 2 < size) + { + /*A simple shift and xor hash is used. Since the data of PNGs is dominated + by zeroes due to the filters, a better hash does not have a significant + effect on speed in traversing the chain, and causes more time spend on + calculating the hash.*/ + result ^= (unsigned)(data[pos + 0] << 0u); + result ^= (unsigned)(data[pos + 1] << 4u); + result ^= (unsigned)(data[pos + 2] << 8u); + } else { + size_t amount, i; + if(pos >= size) return 0; + amount = size - pos; + for(i = 0; i < amount; i++) result ^= (unsigned)(data[pos + i] << (i * 8u)); + } + return result & HASH_BIT_MASK; +} + +static unsigned countZeros(const unsigned char* data, size_t size, size_t pos) +{ + const unsigned char* start = data + pos; + const unsigned char* end = start + MAX_SUPPORTED_DEFLATE_LENGTH; + if(end > data + size) end = data + size; + data = start; + while (data != end && *data == 0) data++; + /*subtracting two addresses returned as 32-bit number (max value is MAX_SUPPORTED_DEFLATE_LENGTH)*/ + return (unsigned)(data - start); +} + +/*wpos = pos & (windowsize - 1)*/ +static void updateHashChain(Hash* hash, size_t wpos, unsigned hashval, unsigned short numzeros) +{ + hash->val[wpos] = (int)hashval; + if(hash->head[hashval] != -1) hash->chain[wpos] = hash->head[hashval]; + hash->head[hashval] = wpos; + + hash->zeros[wpos] = numzeros; + if(hash->headz[numzeros] != -1) hash->chainz[wpos] = hash->headz[numzeros]; + hash->headz[numzeros] = wpos; +} + +/* +LZ77-encode the data. Return value is error code. The input are raw bytes, the output +is in the form of unsigned integers with codes representing for example literal bytes, or +length/distance pairs. +It uses a hash table technique to let it encode faster. When doing LZ77 encoding, a +sliding window (of windowsize) is used, and all past bytes in that window can be used as +the "dictionary". A brute force search through all possible distances would be slow, and +this hash technique is one out of several ways to speed this up. +*/ +static unsigned encodeLZ77(uivector* out, Hash* hash, + const unsigned char* in, size_t inpos, size_t insize, unsigned windowsize, + unsigned minmatch, unsigned nicematch, unsigned lazymatching) +{ + size_t pos; + unsigned i, error = 0; + /*for large window lengths, assume the user wants no compression loss. Otherwise, max hash chain length speedup.*/ + unsigned maxchainlength = windowsize >= 8192 ? windowsize : windowsize / 8; + unsigned maxlazymatch = windowsize >= 8192 ? MAX_SUPPORTED_DEFLATE_LENGTH : 64; + + unsigned usezeros = 1; /*not sure if setting it to false for windowsize < 8192 is better or worse*/ + unsigned numzeros = 0; + + unsigned offset; /*the offset represents the distance in LZ77 terminology*/ + unsigned length; + unsigned lazy = 0; + unsigned lazylength = 0, lazyoffset = 0; + unsigned hashval; + unsigned current_offset, current_length; + unsigned prev_offset; + const unsigned char *lastptr, *foreptr, *backptr; + unsigned hashpos; + + if(windowsize <= 0 || windowsize > 32768) return 60; /*error: windowsize smaller/larger than allowed*/ + if((windowsize & (windowsize - 1)) != 0) return 90; /*error: must be power of two*/ + + if(nicematch > MAX_SUPPORTED_DEFLATE_LENGTH) nicematch = MAX_SUPPORTED_DEFLATE_LENGTH; + + for(pos = inpos; pos < insize; pos++) + { + size_t wpos = pos & (windowsize - 1); /*position for in 'circular' hash buffers*/ + unsigned chainlength = 0; + + hashval = getHash(in, insize, pos); + + if(usezeros && hashval == 0) + { + if (numzeros == 0) numzeros = countZeros(in, insize, pos); + else if (pos + numzeros > insize || in[pos + numzeros - 1] != 0) numzeros--; + } + else + { + numzeros = 0; + } + + updateHashChain(hash, wpos, hashval, numzeros); + + /*the length and offset found for the current position*/ + length = 0; + offset = 0; + + hashpos = hash->chain[wpos]; + + lastptr = &in[insize < pos + MAX_SUPPORTED_DEFLATE_LENGTH ? insize : pos + MAX_SUPPORTED_DEFLATE_LENGTH]; + + /*search for the longest string*/ + prev_offset = 0; + for(;;) + { + if(chainlength++ >= maxchainlength) break; + current_offset = hashpos <= wpos ? wpos - hashpos : wpos - hashpos + windowsize; + + if(current_offset < prev_offset) break; /*stop when went completely around the circular buffer*/ + prev_offset = current_offset; + if(current_offset > 0) + { + /*test the next characters*/ + foreptr = &in[pos]; + backptr = &in[pos - current_offset]; + + /*common case in PNGs is lots of zeros. Quickly skip over them as a speedup*/ + if(numzeros >= 3) + { + unsigned skip = hash->zeros[hashpos]; + if(skip > numzeros) skip = numzeros; + backptr += skip; + foreptr += skip; + } + + while(foreptr != lastptr && *backptr == *foreptr) /*maximum supported length by deflate is max length*/ + { + ++backptr; + ++foreptr; + } + current_length = (unsigned)(foreptr - &in[pos]); + + if(current_length > length) + { + length = current_length; /*the longest length*/ + offset = current_offset; /*the offset that is related to this longest length*/ + /*jump out once a length of max length is found (speed gain). This also jumps + out if length is MAX_SUPPORTED_DEFLATE_LENGTH*/ + if(current_length >= nicematch) break; + } + } + + if(hashpos == hash->chain[hashpos]) break; + + if(numzeros >= 3 && length > numzeros) { + hashpos = hash->chainz[hashpos]; + if(hash->zeros[hashpos] != numzeros) break; + } else { + hashpos = hash->chain[hashpos]; + /*outdated hash value, happens if particular value was not encountered in whole last window*/ + if(hash->val[hashpos] != (int)hashval) break; + } + } + + if(lazymatching) + { + if(!lazy && length >= 3 && length <= maxlazymatch && length < MAX_SUPPORTED_DEFLATE_LENGTH) + { + lazy = 1; + lazylength = length; + lazyoffset = offset; + continue; /*try the next byte*/ + } + if(lazy) + { + lazy = 0; + if(pos == 0) ERROR_BREAK(81); + if(length > lazylength + 1) + { + /*push the previous character as literal*/ + if(!uivector_push_back(out, in[pos - 1])) ERROR_BREAK(83 /*alloc fail*/); + } + else + { + length = lazylength; + offset = lazyoffset; + hash->head[hashval] = -1; /*the same hashchain update will be done, this ensures no wrong alteration*/ + hash->headz[numzeros] = -1; /*idem*/ + pos--; + } + } + } + if(length >= 3 && offset > windowsize) ERROR_BREAK(86 /*too big (or overflown negative) offset*/); + + /*encode it as length/distance pair or literal value*/ + if(length < 3) /*only lengths of 3 or higher are supported as length/distance pair*/ + { + if(!uivector_push_back(out, in[pos])) ERROR_BREAK(83 /*alloc fail*/); + } + else if(length < minmatch || (length == 3 && offset > 4096)) + { + /*compensate for the fact that longer offsets have more extra bits, a + length of only 3 may be not worth it then*/ + if(!uivector_push_back(out, in[pos])) ERROR_BREAK(83 /*alloc fail*/); + } + else + { + addLengthDistance(out, length, offset); + for(i = 1; i < length; i++) + { + pos++; + wpos = pos & (windowsize - 1); + hashval = getHash(in, insize, pos); + if(usezeros && hashval == 0) + { + if (numzeros == 0) numzeros = countZeros(in, insize, pos); + else if (pos + numzeros > insize || in[pos + numzeros - 1] != 0) numzeros--; + } + else + { + numzeros = 0; + } + updateHashChain(hash, wpos, hashval, numzeros); + } + } + } /*end of the loop through each character of input*/ + + return error; +} + +/* /////////////////////////////////////////////////////////////////////////// */ + +static unsigned deflateNoCompression(ucvector* out, const unsigned char* data, size_t datasize) +{ + /*non compressed deflate block data: 1 bit BFINAL,2 bits BTYPE,(5 bits): it jumps to start of next byte, + 2 bytes LEN, 2 bytes NLEN, LEN bytes literal DATA*/ + + size_t i, j, numdeflateblocks = (datasize + 65534) / 65535; + unsigned datapos = 0; + for(i = 0; i < numdeflateblocks; i++) + { + unsigned BFINAL, BTYPE, LEN, NLEN; + unsigned char firstbyte; + + BFINAL = (i == numdeflateblocks - 1); + BTYPE = 0; + + firstbyte = (unsigned char)(BFINAL + ((BTYPE & 1) << 1) + ((BTYPE & 2) << 1)); + ucvector_push_back(out, firstbyte); + + LEN = 65535; + if(datasize - datapos < 65535) LEN = (unsigned)datasize - datapos; + NLEN = 65535 - LEN; + + ucvector_push_back(out, (unsigned char)(LEN % 256)); + ucvector_push_back(out, (unsigned char)(LEN / 256)); + ucvector_push_back(out, (unsigned char)(NLEN % 256)); + ucvector_push_back(out, (unsigned char)(NLEN / 256)); + + /*Decompressed data*/ + for(j = 0; j < 65535 && datapos < datasize; j++) + { + ucvector_push_back(out, data[datapos++]); + } + } + + return 0; +} + +/* +write the lz77-encoded data, which has lit, len and dist codes, to compressed stream using huffman trees. +tree_ll: the tree for lit and len codes. +tree_d: the tree for distance codes. +*/ +static void writeLZ77data(size_t* bp, ucvector* out, const uivector* lz77_encoded, + const HuffmanTree* tree_ll, const HuffmanTree* tree_d) +{ + size_t i = 0; + for(i = 0; i < lz77_encoded->size; i++) + { + unsigned val = lz77_encoded->data[i]; + addHuffmanSymbol(bp, out, HuffmanTree_getCode(tree_ll, val), HuffmanTree_getLength(tree_ll, val)); + if(val > 256) /*for a length code, 3 more things have to be added*/ + { + unsigned length_index = val - FIRST_LENGTH_CODE_INDEX; + unsigned n_length_extra_bits = LENGTHEXTRA[length_index]; + unsigned length_extra_bits = lz77_encoded->data[++i]; + + unsigned distance_code = lz77_encoded->data[++i]; + + unsigned distance_index = distance_code; + unsigned n_distance_extra_bits = DISTANCEEXTRA[distance_index]; + unsigned distance_extra_bits = lz77_encoded->data[++i]; + + addBitsToStream(bp, out, length_extra_bits, n_length_extra_bits); + addHuffmanSymbol(bp, out, HuffmanTree_getCode(tree_d, distance_code), + HuffmanTree_getLength(tree_d, distance_code)); + addBitsToStream(bp, out, distance_extra_bits, n_distance_extra_bits); + } + } +} + +/*Deflate for a block of type "dynamic", that is, with freely, optimally, created huffman trees*/ +static unsigned deflateDynamic(ucvector* out, size_t* bp, Hash* hash, + const unsigned char* data, size_t datapos, size_t dataend, + const LodePNGCompressSettings* settings, unsigned final) +{ + unsigned error = 0; + + /* + A block is compressed as follows: The PNG data is lz77 encoded, resulting in + literal bytes and length/distance pairs. This is then huffman compressed with + two huffman trees. One huffman tree is used for the lit and len values ("ll"), + another huffman tree is used for the dist values ("d"). These two trees are + stored using their code lengths, and to compress even more these code lengths + are also run-length encoded and huffman compressed. This gives a huffman tree + of code lengths "cl". The code lenghts used to describe this third tree are + the code length code lengths ("clcl"). + */ + + /*The lz77 encoded data, represented with integers since there will also be length and distance codes in it*/ + uivector lz77_encoded; + HuffmanTree tree_ll; /*tree for lit,len values*/ + HuffmanTree tree_d; /*tree for distance codes*/ + HuffmanTree tree_cl; /*tree for encoding the code lengths representing tree_ll and tree_d*/ + uivector frequencies_ll; /*frequency of lit,len codes*/ + uivector frequencies_d; /*frequency of dist codes*/ + uivector frequencies_cl; /*frequency of code length codes*/ + uivector bitlen_lld; /*lit,len,dist code lenghts (int bits), literally (without repeat codes).*/ + uivector bitlen_lld_e; /*bitlen_lld encoded with repeat codes (this is a rudemtary run length compression)*/ + /*bitlen_cl is the code length code lengths ("clcl"). The bit lengths of codes to represent tree_cl + (these are written as is in the file, it would be crazy to compress these using yet another huffman + tree that needs to be represented by yet another set of code lengths)*/ + uivector bitlen_cl; + size_t datasize = dataend - datapos; + + /* + Due to the huffman compression of huffman tree representations ("two levels"), there are some anologies: + bitlen_lld is to tree_cl what data is to tree_ll and tree_d. + bitlen_lld_e is to bitlen_lld what lz77_encoded is to data. + bitlen_cl is to bitlen_lld_e what bitlen_lld is to lz77_encoded. + */ + + unsigned BFINAL = final; + size_t numcodes_ll, numcodes_d, i; + unsigned HLIT, HDIST, HCLEN; + + uivector_init(&lz77_encoded); + HuffmanTree_init(&tree_ll); + HuffmanTree_init(&tree_d); + HuffmanTree_init(&tree_cl); + uivector_init(&frequencies_ll); + uivector_init(&frequencies_d); + uivector_init(&frequencies_cl); + uivector_init(&bitlen_lld); + uivector_init(&bitlen_lld_e); + uivector_init(&bitlen_cl); + + /*This while loop never loops due to a break at the end, it is here to + allow breaking out of it to the cleanup phase on error conditions.*/ + while(!error) + { + if(settings->use_lz77) + { + error = encodeLZ77(&lz77_encoded, hash, data, datapos, dataend, settings->windowsize, + settings->minmatch, settings->nicematch, settings->lazymatching); + if(error) break; + } + else + { + if(!uivector_resize(&lz77_encoded, datasize)) ERROR_BREAK(83 /*alloc fail*/); + for(i = datapos; i < dataend; i++) lz77_encoded.data[i] = data[i]; /*no LZ77, but still will be Huffman compressed*/ + } + + if(!uivector_resizev(&frequencies_ll, 286, 0)) ERROR_BREAK(83 /*alloc fail*/); + if(!uivector_resizev(&frequencies_d, 30, 0)) ERROR_BREAK(83 /*alloc fail*/); + + /*Count the frequencies of lit, len and dist codes*/ + for(i = 0; i < lz77_encoded.size; i++) + { + unsigned symbol = lz77_encoded.data[i]; + frequencies_ll.data[symbol]++; + if(symbol > 256) + { + unsigned dist = lz77_encoded.data[i + 2]; + frequencies_d.data[dist]++; + i += 3; + } + } + frequencies_ll.data[256] = 1; /*there will be exactly 1 end code, at the end of the block*/ + + /*Make both huffman trees, one for the lit and len codes, one for the dist codes*/ + error = HuffmanTree_makeFromFrequencies(&tree_ll, frequencies_ll.data, 257, frequencies_ll.size, 15); + if(error) break; + /*2, not 1, is chosen for mincodes: some buggy PNG decoders require at least 2 symbols in the dist tree*/ + error = HuffmanTree_makeFromFrequencies(&tree_d, frequencies_d.data, 2, frequencies_d.size, 15); + if(error) break; + + numcodes_ll = tree_ll.numcodes; if(numcodes_ll > 286) numcodes_ll = 286; + numcodes_d = tree_d.numcodes; if(numcodes_d > 30) numcodes_d = 30; + /*store the code lengths of both generated trees in bitlen_lld*/ + for(i = 0; i < numcodes_ll; i++) uivector_push_back(&bitlen_lld, HuffmanTree_getLength(&tree_ll, (unsigned)i)); + for(i = 0; i < numcodes_d; i++) uivector_push_back(&bitlen_lld, HuffmanTree_getLength(&tree_d, (unsigned)i)); + + /*run-length compress bitlen_ldd into bitlen_lld_e by using repeat codes 16 (copy length 3-6 times), + 17 (3-10 zeroes), 18 (11-138 zeroes)*/ + for(i = 0; i < (unsigned)bitlen_lld.size; i++) + { + unsigned j = 0; /*amount of repititions*/ + while(i + j + 1 < (unsigned)bitlen_lld.size && bitlen_lld.data[i + j + 1] == bitlen_lld.data[i]) j++; + + if(bitlen_lld.data[i] == 0 && j >= 2) /*repeat code for zeroes*/ + { + j++; /*include the first zero*/ + if(j <= 10) /*repeat code 17 supports max 10 zeroes*/ + { + uivector_push_back(&bitlen_lld_e, 17); + uivector_push_back(&bitlen_lld_e, j - 3); + } + else /*repeat code 18 supports max 138 zeroes*/ + { + if(j > 138) j = 138; + uivector_push_back(&bitlen_lld_e, 18); + uivector_push_back(&bitlen_lld_e, j - 11); + } + i += (j - 1); + } + else if(j >= 3) /*repeat code for value other than zero*/ + { + size_t k; + unsigned num = j / 6, rest = j % 6; + uivector_push_back(&bitlen_lld_e, bitlen_lld.data[i]); + for(k = 0; k < num; k++) + { + uivector_push_back(&bitlen_lld_e, 16); + uivector_push_back(&bitlen_lld_e, 6 - 3); + } + if(rest >= 3) + { + uivector_push_back(&bitlen_lld_e, 16); + uivector_push_back(&bitlen_lld_e, rest - 3); + } + else j -= rest; + i += j; + } + else /*too short to benefit from repeat code*/ + { + uivector_push_back(&bitlen_lld_e, bitlen_lld.data[i]); + } + } + + /*generate tree_cl, the huffmantree of huffmantrees*/ + + if(!uivector_resizev(&frequencies_cl, NUM_CODE_LENGTH_CODES, 0)) ERROR_BREAK(83 /*alloc fail*/); + for(i = 0; i < bitlen_lld_e.size; i++) + { + frequencies_cl.data[bitlen_lld_e.data[i]]++; + /*after a repeat code come the bits that specify the number of repetitions, + those don't need to be in the frequencies_cl calculation*/ + if(bitlen_lld_e.data[i] >= 16) i++; + } + + error = HuffmanTree_makeFromFrequencies(&tree_cl, frequencies_cl.data, + frequencies_cl.size, frequencies_cl.size, 7); + if(error) break; + + if(!uivector_resize(&bitlen_cl, tree_cl.numcodes)) ERROR_BREAK(83 /*alloc fail*/); + for(i = 0; i < tree_cl.numcodes; i++) + { + /*lenghts of code length tree is in the order as specified by deflate*/ + bitlen_cl.data[i] = HuffmanTree_getLength(&tree_cl, CLCL_ORDER[i]); + } + while(bitlen_cl.data[bitlen_cl.size - 1] == 0 && bitlen_cl.size > 4) + { + /*remove zeros at the end, but minimum size must be 4*/ + if(!uivector_resize(&bitlen_cl, bitlen_cl.size - 1)) ERROR_BREAK(83 /*alloc fail*/); + } + if(error) break; + + /* + Write everything into the output + + After the BFINAL and BTYPE, the dynamic block consists out of the following: + - 5 bits HLIT, 5 bits HDIST, 4 bits HCLEN + - (HCLEN+4)*3 bits code lengths of code length alphabet + - HLIT + 257 code lenghts of lit/length alphabet (encoded using the code length + alphabet, + possible repetition codes 16, 17, 18) + - HDIST + 1 code lengths of distance alphabet (encoded using the code length + alphabet, + possible repetition codes 16, 17, 18) + - compressed data + - 256 (end code) + */ + + /*Write block type*/ + addBitToStream(bp, out, BFINAL); + addBitToStream(bp, out, 0); /*first bit of BTYPE "dynamic"*/ + addBitToStream(bp, out, 1); /*second bit of BTYPE "dynamic"*/ + + /*write the HLIT, HDIST and HCLEN values*/ + HLIT = (unsigned)(numcodes_ll - 257); + HDIST = (unsigned)(numcodes_d - 1); + HCLEN = (unsigned)bitlen_cl.size - 4; + /*trim zeroes for HCLEN. HLIT and HDIST were already trimmed at tree creation*/ + while(!bitlen_cl.data[HCLEN + 4 - 1] && HCLEN > 0) HCLEN--; + addBitsToStream(bp, out, HLIT, 5); + addBitsToStream(bp, out, HDIST, 5); + addBitsToStream(bp, out, HCLEN, 4); + + /*write the code lenghts of the code length alphabet*/ + for(i = 0; i < HCLEN + 4; i++) addBitsToStream(bp, out, bitlen_cl.data[i], 3); + + /*write the lenghts of the lit/len AND the dist alphabet*/ + for(i = 0; i < bitlen_lld_e.size; i++) + { + addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_cl, bitlen_lld_e.data[i]), + HuffmanTree_getLength(&tree_cl, bitlen_lld_e.data[i])); + /*extra bits of repeat codes*/ + if(bitlen_lld_e.data[i] == 16) addBitsToStream(bp, out, bitlen_lld_e.data[++i], 2); + else if(bitlen_lld_e.data[i] == 17) addBitsToStream(bp, out, bitlen_lld_e.data[++i], 3); + else if(bitlen_lld_e.data[i] == 18) addBitsToStream(bp, out, bitlen_lld_e.data[++i], 7); + } + + /*write the compressed data symbols*/ + writeLZ77data(bp, out, &lz77_encoded, &tree_ll, &tree_d); + /*error: the length of the end code 256 must be larger than 0*/ + if(HuffmanTree_getLength(&tree_ll, 256) == 0) ERROR_BREAK(64); + + /*write the end code*/ + addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_ll, 256), HuffmanTree_getLength(&tree_ll, 256)); + + break; /*end of error-while*/ + } + + /*cleanup*/ + uivector_cleanup(&lz77_encoded); + HuffmanTree_cleanup(&tree_ll); + HuffmanTree_cleanup(&tree_d); + HuffmanTree_cleanup(&tree_cl); + uivector_cleanup(&frequencies_ll); + uivector_cleanup(&frequencies_d); + uivector_cleanup(&frequencies_cl); + uivector_cleanup(&bitlen_lld_e); + uivector_cleanup(&bitlen_lld); + uivector_cleanup(&bitlen_cl); + + return error; +} + +static unsigned deflateFixed(ucvector* out, size_t* bp, Hash* hash, + const unsigned char* data, + size_t datapos, size_t dataend, + const LodePNGCompressSettings* settings, unsigned final) +{ + HuffmanTree tree_ll; /*tree for literal values and length codes*/ + HuffmanTree tree_d; /*tree for distance codes*/ + + unsigned BFINAL = final; + unsigned error = 0; + size_t i; + + HuffmanTree_init(&tree_ll); + HuffmanTree_init(&tree_d); + + generateFixedLitLenTree(&tree_ll); + generateFixedDistanceTree(&tree_d); + + addBitToStream(bp, out, BFINAL); + addBitToStream(bp, out, 1); /*first bit of BTYPE*/ + addBitToStream(bp, out, 0); /*second bit of BTYPE*/ + + if(settings->use_lz77) /*LZ77 encoded*/ + { + uivector lz77_encoded; + uivector_init(&lz77_encoded); + error = encodeLZ77(&lz77_encoded, hash, data, datapos, dataend, settings->windowsize, + settings->minmatch, settings->nicematch, settings->lazymatching); + if(!error) writeLZ77data(bp, out, &lz77_encoded, &tree_ll, &tree_d); + uivector_cleanup(&lz77_encoded); + } + else /*no LZ77, but still will be Huffman compressed*/ + { + for(i = datapos; i < dataend; i++) + { + addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_ll, data[i]), HuffmanTree_getLength(&tree_ll, data[i])); + } + } + /*add END code*/ + if(!error) addHuffmanSymbol(bp, out, HuffmanTree_getCode(&tree_ll, 256), HuffmanTree_getLength(&tree_ll, 256)); + + /*cleanup*/ + HuffmanTree_cleanup(&tree_ll); + HuffmanTree_cleanup(&tree_d); + + return error; +} + +static unsigned lodepng_deflatev(ucvector* out, const unsigned char* in, size_t insize, + const LodePNGCompressSettings* settings) +{ + unsigned error = 0; + size_t i, blocksize, numdeflateblocks; + size_t bp = 0; /*the bit pointer*/ + Hash hash; + + if(settings->btype > 2) return 61; + else if(settings->btype == 0) return deflateNoCompression(out, in, insize); + else if(settings->btype == 1) blocksize = insize; + else /*if(settings->btype == 2)*/ + { + blocksize = insize / 8 + 8; + if(blocksize < 65535) blocksize = 65535; + } + + numdeflateblocks = (insize + blocksize - 1) / blocksize; + if(numdeflateblocks == 0) numdeflateblocks = 1; + + error = hash_init(&hash, settings->windowsize); + if(error) return error; + + for(i = 0; i < numdeflateblocks && !error; i++) + { + unsigned final = (i == numdeflateblocks - 1); + size_t start = i * blocksize; + size_t end = start + blocksize; + if(end > insize) end = insize; + + if(settings->btype == 1) error = deflateFixed(out, &bp, &hash, in, start, end, settings, final); + else if(settings->btype == 2) error = deflateDynamic(out, &bp, &hash, in, start, end, settings, final); + } + + hash_cleanup(&hash); + + return error; +} + +unsigned lodepng_deflate(unsigned char** out, size_t* outsize, + const unsigned char* in, size_t insize, + const LodePNGCompressSettings* settings) +{ + unsigned error; + ucvector v; + ucvector_init_buffer(&v, *out, *outsize); + error = lodepng_deflatev(&v, in, insize, settings); + *out = v.data; + *outsize = v.size; + return error; +} + +static unsigned deflate(unsigned char** out, size_t* outsize, + const unsigned char* in, size_t insize, + const LodePNGCompressSettings* settings) +{ + if(settings->custom_deflate) + { + return settings->custom_deflate(out, outsize, in, insize, settings); + } + else + { + return lodepng_deflate(out, outsize, in, insize, settings); + } +} + +#endif /*LODEPNG_COMPILE_DECODER*/ + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / Adler32 */ +/* ////////////////////////////////////////////////////////////////////////// */ + +static unsigned update_adler32(unsigned adler, const unsigned char* data, unsigned len) +{ + unsigned s1 = adler & 0xffff; + unsigned s2 = (adler >> 16) & 0xffff; + + while(len > 0) + { + /*at least 5550 sums can be done before the sums overflow, saving a lot of module divisions*/ + unsigned amount = len > 5550 ? 5550 : len; + len -= amount; + while(amount > 0) + { + s1 += (*data++); + s2 += s1; + amount--; + } + s1 %= 65521; + s2 %= 65521; + } + + return (s2 << 16) | s1; +} + +/*Return the adler32 of the bytes data[0..len-1]*/ +static unsigned adler32(const unsigned char* data, unsigned len) +{ + return update_adler32(1L, data, len); +} + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / Zlib / */ +/* ////////////////////////////////////////////////////////////////////////// */ + +#ifdef LODEPNG_COMPILE_DECODER + +unsigned lodepng_zlib_decompress(unsigned char** out, size_t* outsize, const unsigned char* in, + size_t insize, const LodePNGDecompressSettings* settings) +{ + unsigned error = 0; + unsigned CM, CINFO, FDICT; + + if(insize < 2) return 53; /*error, size of zlib data too small*/ + /*read information from zlib header*/ + if((in[0] * 256 + in[1]) % 31 != 0) + { + /*error: 256 * in[0] + in[1] must be a multiple of 31, the FCHECK value is supposed to be made that way*/ + return 24; + } + + CM = in[0] & 15; + CINFO = (in[0] >> 4) & 15; + /*FCHECK = in[1] & 31;*/ /*FCHECK is already tested above*/ + FDICT = (in[1] >> 5) & 1; + /*FLEVEL = (in[1] >> 6) & 3;*/ /*FLEVEL is not used here*/ + + if(CM != 8 || CINFO > 7) + { + /*error: only compression method 8: inflate with sliding window of 32k is supported by the PNG spec*/ + return 25; + } + if(FDICT != 0) + { + /*error: the specification of PNG says about the zlib stream: + "The additional flags shall not specify a preset dictionary."*/ + return 26; + } + + error = inflate(out, outsize, in + 2, insize - 2, settings); + if(error) return error; + + if(!settings->ignore_adler32) + { + unsigned ADLER32 = lodepng_read32bitInt(&in[insize - 4]); + unsigned checksum = adler32(*out, (unsigned)(*outsize)); + if(checksum != ADLER32) return 58; /*error, adler checksum not correct, data must be corrupted*/ + } + + return 0; /*no error*/ +} + +static unsigned zlib_decompress(unsigned char** out, size_t* outsize, const unsigned char* in, + size_t insize, const LodePNGDecompressSettings* settings) +{ + if(settings->custom_zlib) + { + return settings->custom_zlib(out, outsize, in, insize, settings); + } + else + { + return lodepng_zlib_decompress(out, outsize, in, insize, settings); + } +} + +#endif /*LODEPNG_COMPILE_DECODER*/ + +#ifdef LODEPNG_COMPILE_ENCODER + +unsigned lodepng_zlib_compress(unsigned char** out, size_t* outsize, const unsigned char* in, + size_t insize, const LodePNGCompressSettings* settings) +{ + /*initially, *out must be NULL and outsize 0, if you just give some random *out + that's pointing to a non allocated buffer, this'll crash*/ + ucvector outv; + size_t i; + unsigned error; + unsigned char* deflatedata = 0; + size_t deflatesize = 0; + + unsigned ADLER32; + /*zlib data: 1 byte CMF (CM+CINFO), 1 byte FLG, deflate data, 4 byte ADLER32 checksum of the Decompressed data*/ + unsigned CMF = 120; /*0b01111000: CM 8, CINFO 7. With CINFO 7, any window size up to 32768 can be used.*/ + unsigned FLEVEL = 0; + unsigned FDICT = 0; + unsigned CMFFLG = 256 * CMF + FDICT * 32 + FLEVEL * 64; + unsigned FCHECK = 31 - CMFFLG % 31; + CMFFLG += FCHECK; + + /*ucvector-controlled version of the output buffer, for dynamic array*/ + ucvector_init_buffer(&outv, *out, *outsize); + + ucvector_push_back(&outv, (unsigned char)(CMFFLG / 256)); + ucvector_push_back(&outv, (unsigned char)(CMFFLG % 256)); + + error = deflate(&deflatedata, &deflatesize, in, insize, settings); + + if(!error) + { + ADLER32 = adler32(in, (unsigned)insize); + for(i = 0; i < deflatesize; i++) ucvector_push_back(&outv, deflatedata[i]); + lodepng_free(deflatedata); + lodepng_add32bitInt(&outv, ADLER32); + } + + *out = outv.data; + *outsize = outv.size; + + return error; +} + +/* compress using the default or custom zlib function */ +static unsigned zlib_compress(unsigned char** out, size_t* outsize, const unsigned char* in, + size_t insize, const LodePNGCompressSettings* settings) +{ + if(settings->custom_zlib) + { + return settings->custom_zlib(out, outsize, in, insize, settings); + } + else + { + return lodepng_zlib_compress(out, outsize, in, insize, settings); + } +} + +#endif /*LODEPNG_COMPILE_ENCODER*/ + +#else /*no LODEPNG_COMPILE_ZLIB*/ + +#ifdef LODEPNG_COMPILE_DECODER +static unsigned zlib_decompress(unsigned char** out, size_t* outsize, const unsigned char* in, + size_t insize, const LodePNGDecompressSettings* settings) +{ + if (!settings->custom_zlib) return 87; /*no custom zlib function provided */ + return settings->custom_zlib(out, outsize, in, insize, settings); +} +#endif /*LODEPNG_COMPILE_DECODER*/ +#ifdef LODEPNG_COMPILE_ENCODER +static unsigned zlib_compress(unsigned char** out, size_t* outsize, const unsigned char* in, + size_t insize, const LodePNGCompressSettings* settings) +{ + if (!settings->custom_zlib) return 87; /*no custom zlib function provided */ + return settings->custom_zlib(out, outsize, in, insize, settings); +} +#endif /*LODEPNG_COMPILE_ENCODER*/ + +#endif /*LODEPNG_COMPILE_ZLIB*/ + +/* ////////////////////////////////////////////////////////////////////////// */ + +#ifdef LODEPNG_COMPILE_ENCODER + +/*this is a good tradeoff between speed and compression ratio*/ +#define DEFAULT_WINDOWSIZE 2048 + +void lodepng_compress_settings_init(LodePNGCompressSettings* settings) +{ + /*compress with dynamic huffman tree (not in the mathematical sense, just not the predefined one)*/ + settings->btype = 2; + settings->use_lz77 = 1; + settings->windowsize = DEFAULT_WINDOWSIZE; + settings->minmatch = 3; + settings->nicematch = 128; + settings->lazymatching = 1; + + settings->custom_zlib = 0; + settings->custom_deflate = 0; + settings->custom_context = 0; +} + +const LodePNGCompressSettings lodepng_default_compress_settings = {2, 1, DEFAULT_WINDOWSIZE, 3, 128, 1, 0, 0, 0}; + + +#endif /*LODEPNG_COMPILE_ENCODER*/ + +#ifdef LODEPNG_COMPILE_DECODER + +void lodepng_decompress_settings_init(LodePNGDecompressSettings* settings) +{ + settings->ignore_adler32 = 0; + + settings->custom_zlib = 0; + settings->custom_inflate = 0; + settings->custom_context = 0; +} + +const LodePNGDecompressSettings lodepng_default_decompress_settings = {0, 0, 0, 0}; + +#endif /*LODEPNG_COMPILE_DECODER*/ + +/* ////////////////////////////////////////////////////////////////////////// */ +/* ////////////////////////////////////////////////////////////////////////// */ +/* // End of Zlib related code. Begin of PNG related code. // */ +/* ////////////////////////////////////////////////////////////////////////// */ +/* ////////////////////////////////////////////////////////////////////////// */ + +#ifdef LODEPNG_COMPILE_PNG + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / CRC32 / */ +/* ////////////////////////////////////////////////////////////////////////// */ + +/* CRC polynomial: 0xedb88320 */ +static unsigned lodepng_crc32_table[256] = { + 0u, 1996959894u, 3993919788u, 2567524794u, 124634137u, 1886057615u, 3915621685u, 2657392035u, + 249268274u, 2044508324u, 3772115230u, 2547177864u, 162941995u, 2125561021u, 3887607047u, 2428444049u, + 498536548u, 1789927666u, 4089016648u, 2227061214u, 450548861u, 1843258603u, 4107580753u, 2211677639u, + 325883990u, 1684777152u, 4251122042u, 2321926636u, 335633487u, 1661365465u, 4195302755u, 2366115317u, + 997073096u, 1281953886u, 3579855332u, 2724688242u, 1006888145u, 1258607687u, 3524101629u, 2768942443u, + 901097722u, 1119000684u, 3686517206u, 2898065728u, 853044451u, 1172266101u, 3705015759u, 2882616665u, + 651767980u, 1373503546u, 3369554304u, 3218104598u, 565507253u, 1454621731u, 3485111705u, 3099436303u, + 671266974u, 1594198024u, 3322730930u, 2970347812u, 795835527u, 1483230225u, 3244367275u, 3060149565u, + 1994146192u, 31158534u, 2563907772u, 4023717930u, 1907459465u, 112637215u, 2680153253u, 3904427059u, + 2013776290u, 251722036u, 2517215374u, 3775830040u, 2137656763u, 141376813u, 2439277719u, 3865271297u, + 1802195444u, 476864866u, 2238001368u, 4066508878u, 1812370925u, 453092731u, 2181625025u, 4111451223u, + 1706088902u, 314042704u, 2344532202u, 4240017532u, 1658658271u, 366619977u, 2362670323u, 4224994405u, + 1303535960u, 984961486u, 2747007092u, 3569037538u, 1256170817u, 1037604311u, 2765210733u, 3554079995u, + 1131014506u, 879679996u, 2909243462u, 3663771856u, 1141124467u, 855842277u, 2852801631u, 3708648649u, + 1342533948u, 654459306u, 3188396048u, 3373015174u, 1466479909u, 544179635u, 3110523913u, 3462522015u, + 1591671054u, 702138776u, 2966460450u, 3352799412u, 1504918807u, 783551873u, 3082640443u, 3233442989u, + 3988292384u, 2596254646u, 62317068u, 1957810842u, 3939845945u, 2647816111u, 81470997u, 1943803523u, + 3814918930u, 2489596804u, 225274430u, 2053790376u, 3826175755u, 2466906013u, 167816743u, 2097651377u, + 4027552580u, 2265490386u, 503444072u, 1762050814u, 4150417245u, 2154129355u, 426522225u, 1852507879u, + 4275313526u, 2312317920u, 282753626u, 1742555852u, 4189708143u, 2394877945u, 397917763u, 1622183637u, + 3604390888u, 2714866558u, 953729732u, 1340076626u, 3518719985u, 2797360999u, 1068828381u, 1219638859u, + 3624741850u, 2936675148u, 906185462u, 1090812512u, 3747672003u, 2825379669u, 829329135u, 1181335161u, + 3412177804u, 3160834842u, 628085408u, 1382605366u, 3423369109u, 3138078467u, 570562233u, 1426400815u, + 3317316542u, 2998733608u, 733239954u, 1555261956u, 3268935591u, 3050360625u, 752459403u, 1541320221u, + 2607071920u, 3965973030u, 1969922972u, 40735498u, 2617837225u, 3943577151u, 1913087877u, 83908371u, + 2512341634u, 3803740692u, 2075208622u, 213261112u, 2463272603u, 3855990285u, 2094854071u, 198958881u, + 2262029012u, 4057260610u, 1759359992u, 534414190u, 2176718541u, 4139329115u, 1873836001u, 414664567u, + 2282248934u, 4279200368u, 1711684554u, 285281116u, 2405801727u, 4167216745u, 1634467795u, 376229701u, + 2685067896u, 3608007406u, 1308918612u, 956543938u, 2808555105u, 3495958263u, 1231636301u, 1047427035u, + 2932959818u, 3654703836u, 1088359270u, 936918000u, 2847714899u, 3736837829u, 1202900863u, 817233897u, + 3183342108u, 3401237130u, 1404277552u, 615818150u, 3134207493u, 3453421203u, 1423857449u, 601450431u, + 3009837614u, 3294710456u, 1567103746u, 711928724u, 3020668471u, 3272380065u, 1510334235u, 755167117u +}; + +/*Return the CRC of the bytes buf[0..len-1].*/ +unsigned lodepng_crc32(const unsigned char* buf, size_t len) +{ + unsigned c = 0xffffffffL; + size_t n; + + for(n = 0; n < len; n++) + { + c = lodepng_crc32_table[(c ^ buf[n]) & 0xff] ^ (c >> 8); + } + return c ^ 0xffffffffL; +} + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / Reading and writing single bits and bytes from/to stream for LodePNG / */ +/* ////////////////////////////////////////////////////////////////////////// */ + +static unsigned char readBitFromReversedStream(size_t* bitpointer, const unsigned char* bitstream) +{ + unsigned char result = (unsigned char)((bitstream[(*bitpointer) >> 3] >> (7 - ((*bitpointer) & 0x7))) & 1); + (*bitpointer)++; + return result; +} + +static unsigned readBitsFromReversedStream(size_t* bitpointer, const unsigned char* bitstream, size_t nbits) +{ + unsigned result = 0; + size_t i; + for ( i = 1; i <= nbits; i++ ) + { + result += (unsigned)readBitFromReversedStream( bitpointer, bitstream ) << (nbits - i); + } + return result; +} + +#ifdef LODEPNG_COMPILE_DECODER +static void setBitOfReversedStream0(size_t* bitpointer, unsigned char* bitstream, unsigned char bit) +{ + /*the current bit in bitstream must be 0 for this to work*/ + if(bit) + { + /*earlier bit of huffman code is in a lesser significant bit of an earlier byte*/ + bitstream[(*bitpointer) >> 3] |= (bit << (7 - ((*bitpointer) & 0x7))); + } + (*bitpointer)++; +} +#endif /*LODEPNG_COMPILE_DECODER*/ + +static void setBitOfReversedStream(size_t* bitpointer, unsigned char* bitstream, unsigned char bit) +{ + /*the current bit in bitstream may be 0 or 1 for this to work*/ + if(bit == 0) bitstream[(*bitpointer) >> 3] &= (unsigned char)(~(1 << (7 - ((*bitpointer) & 0x7)))); + else bitstream[(*bitpointer) >> 3] |= (1 << (7 - ((*bitpointer) & 0x7))); + (*bitpointer)++; +} + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / PNG chunks / */ +/* ////////////////////////////////////////////////////////////////////////// */ + +unsigned lodepng_chunk_length(const unsigned char* chunk) +{ + return lodepng_read32bitInt(&chunk[0]); +} + +void lodepng_chunk_type(char type[5], const unsigned char* chunk) +{ + unsigned i; + for(i = 0; i < 4; i++) type[i] = (char)chunk[4 + i]; + type[4] = 0; /*null termination char*/ +} + +unsigned char lodepng_chunk_type_equals(const unsigned char* chunk, const char* type) +{ + if(strlen(type) != 4) return 0; + return (chunk[4] == type[0] && chunk[5] == type[1] && chunk[6] == type[2] && chunk[7] == type[3]); +} + +unsigned char lodepng_chunk_ancillary(const unsigned char* chunk) +{ + return((chunk[4] & 32) != 0); +} + +unsigned char lodepng_chunk_private(const unsigned char* chunk) +{ + return((chunk[6] & 32) != 0); +} + +unsigned char lodepng_chunk_safetocopy(const unsigned char* chunk) +{ + return((chunk[7] & 32) != 0); +} + +unsigned char* lodepng_chunk_data(unsigned char* chunk) +{ + return &chunk[8]; +} + +const unsigned char* lodepng_chunk_data_const(const unsigned char* chunk) +{ + return &chunk[8]; +} + +unsigned lodepng_chunk_check_crc(const unsigned char* chunk) +{ + unsigned length = lodepng_chunk_length(chunk); + unsigned CRC = lodepng_read32bitInt(&chunk[length + 8]); + /*the CRC is taken of the data and the 4 chunk type letters, not the length*/ + unsigned checksum = lodepng_crc32(&chunk[4], length + 4); + if(CRC != checksum) return 1; + else return 0; +} + +void lodepng_chunk_generate_crc(unsigned char* chunk) +{ + unsigned length = lodepng_chunk_length(chunk); + unsigned CRC = lodepng_crc32(&chunk[4], length + 4); + lodepng_set32bitInt(chunk + 8 + length, CRC); +} + +unsigned char* lodepng_chunk_next(unsigned char* chunk) +{ + unsigned total_chunk_length = lodepng_chunk_length(chunk) + 12; + return &chunk[total_chunk_length]; +} + +const unsigned char* lodepng_chunk_next_const(const unsigned char* chunk) +{ + unsigned total_chunk_length = lodepng_chunk_length(chunk) + 12; + return &chunk[total_chunk_length]; +} + +unsigned lodepng_chunk_append(unsigned char** out, size_t* outlength, const unsigned char* chunk) +{ + unsigned i; + unsigned total_chunk_length = lodepng_chunk_length(chunk) + 12; + unsigned char *chunk_start, *new_buffer; + size_t new_length = (*outlength) + total_chunk_length; + if(new_length < total_chunk_length || new_length < (*outlength)) return 77; /*integer overflow happened*/ + + new_buffer = (unsigned char*)lodepng_realloc(*out, new_length); + if(!new_buffer) return 83; /*alloc fail*/ + (*out) = new_buffer; + (*outlength) = new_length; + chunk_start = &(*out)[new_length - total_chunk_length]; + + for(i = 0; i < total_chunk_length; i++) chunk_start[i] = chunk[i]; + + return 0; +} + +unsigned lodepng_chunk_create(unsigned char** out, size_t* outlength, unsigned length, + const char* type, const unsigned char* data) +{ + unsigned i; + unsigned char *chunk, *new_buffer; + size_t new_length = (*outlength) + length + 12; + if(new_length < length + 12 || new_length < (*outlength)) return 77; /*integer overflow happened*/ + new_buffer = (unsigned char*)lodepng_realloc(*out, new_length); + if(!new_buffer) return 83; /*alloc fail*/ + (*out) = new_buffer; + (*outlength) = new_length; + chunk = &(*out)[(*outlength) - length - 12]; + + /*1: length*/ + lodepng_set32bitInt(chunk, (unsigned)length); + + /*2: chunk name (4 letters)*/ + chunk[4] = (unsigned char)type[0]; + chunk[5] = (unsigned char)type[1]; + chunk[6] = (unsigned char)type[2]; + chunk[7] = (unsigned char)type[3]; + + /*3: the data*/ + for(i = 0; i < length; i++) chunk[8 + i] = data[i]; + + /*4: CRC (of the chunkname characters and the data)*/ + lodepng_chunk_generate_crc(chunk); + + return 0; +} + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / Color types and such / */ +/* ////////////////////////////////////////////////////////////////////////// */ + +/*return type is a LodePNG error code*/ +static unsigned checkColorValidity(LodePNGColorType colortype, unsigned bd) /*bd = bitdepth*/ +{ + switch(colortype) + { + case 0: if(!(bd == 1 || bd == 2 || bd == 4 || bd == 8 || bd == 16)) return 37; break; /*grey*/ + case 2: if(!( bd == 8 || bd == 16)) return 37; break; /*RGB*/ + case 3: if(!(bd == 1 || bd == 2 || bd == 4 || bd == 8 )) return 37; break; /*palette*/ + case 4: if(!( bd == 8 || bd == 16)) return 37; break; /*grey + alpha*/ + case 6: if(!( bd == 8 || bd == 16)) return 37; break; /*RGBA*/ + default: return 31; + } + return 0; /*allowed color type / bits combination*/ +} + +static unsigned getNumColorChannels(LodePNGColorType colortype) +{ + switch(colortype) + { + case 0: return 1; /*grey*/ + case 2: return 3; /*RGB*/ + case 3: return 1; /*palette*/ + case 4: return 2; /*grey + alpha*/ + case 6: return 4; /*RGBA*/ + } + return 0; /*unexisting color type*/ +} + +static unsigned lodepng_get_bpp_lct(LodePNGColorType colortype, unsigned bitdepth) +{ + /*bits per pixel is amount of channels * bits per channel*/ + return getNumColorChannels(colortype) * bitdepth; +} + +/* ////////////////////////////////////////////////////////////////////////// */ + +void lodepng_color_mode_init(LodePNGColorMode* info) +{ + info->key_defined = 0; + info->key_r = info->key_g = info->key_b = 0; + info->colortype = LCT_RGBA; + info->bitdepth = 8; + info->palette = 0; + info->palettesize = 0; +} + +void lodepng_color_mode_cleanup(LodePNGColorMode* info) +{ + lodepng_palette_clear(info); +} + +unsigned lodepng_color_mode_copy(LodePNGColorMode* dest, const LodePNGColorMode* source) +{ + size_t i; + lodepng_color_mode_cleanup(dest); + *dest = *source; + if(source->palette) + { + dest->palette = (unsigned char*)lodepng_malloc(1024); + if(!dest->palette && source->palettesize) return 83; /*alloc fail*/ + for(i = 0; i < source->palettesize * 4; i++) dest->palette[i] = source->palette[i]; + } + return 0; +} + +static int lodepng_color_mode_equal(const LodePNGColorMode* a, const LodePNGColorMode* b) +{ + size_t i; + if(a->colortype != b->colortype) return 0; + if(a->bitdepth != b->bitdepth) return 0; + if(a->key_defined != b->key_defined) return 0; + if(a->key_defined) + { + if(a->key_r != b->key_r) return 0; + if(a->key_g != b->key_g) return 0; + if(a->key_b != b->key_b) return 0; + } + if(a->palettesize != b->palettesize) return 0; + for(i = 0; i < a->palettesize * 4; i++) + { + if(a->palette[i] != b->palette[i]) return 0; + } + return 1; +} + +void lodepng_palette_clear(LodePNGColorMode* info) +{ + if(info->palette) lodepng_free(info->palette); + info->palette = 0; + info->palettesize = 0; +} + +unsigned lodepng_palette_add(LodePNGColorMode* info, + unsigned char r, unsigned char g, unsigned char b, unsigned char a) +{ + unsigned char* data; + /*the same resize technique as C++ std::vectors is used, and here it's made so that for a palette with + the max of 256 colors, it'll have the exact alloc size*/ + if(!info->palette) /*allocate palette if empty*/ + { + /*room for 256 colors with 4 bytes each*/ + data = (unsigned char*)lodepng_realloc(info->palette, 1024); + if(!data) return 83; /*alloc fail*/ + else info->palette = data; + } + info->palette[4 * info->palettesize + 0] = r; + info->palette[4 * info->palettesize + 1] = g; + info->palette[4 * info->palettesize + 2] = b; + info->palette[4 * info->palettesize + 3] = a; + info->palettesize++; + return 0; +} + +unsigned lodepng_get_bpp(const LodePNGColorMode* info) +{ + /*calculate bits per pixel out of colortype and bitdepth*/ + return lodepng_get_bpp_lct(info->colortype, info->bitdepth); +} + +unsigned lodepng_get_channels(const LodePNGColorMode* info) +{ + return getNumColorChannels(info->colortype); +} + +unsigned lodepng_is_greyscale_type(const LodePNGColorMode* info) +{ + return info->colortype == LCT_GREY || info->colortype == LCT_GREY_ALPHA; +} + +unsigned lodepng_is_alpha_type(const LodePNGColorMode* info) +{ + return (info->colortype & 4) != 0; /*4 or 6*/ +} + +unsigned lodepng_is_palette_type(const LodePNGColorMode* info) +{ + return info->colortype == LCT_PALETTE; +} + +unsigned lodepng_has_palette_alpha(const LodePNGColorMode* info) +{ + size_t i; + for(i = 0; i < info->palettesize; i++) + { + if(info->palette[i * 4 + 3] < 255) return 1; + } + return 0; +} + +unsigned lodepng_can_have_alpha(const LodePNGColorMode* info) +{ + return info->key_defined + || lodepng_is_alpha_type(info) + || lodepng_has_palette_alpha(info); +} + +size_t lodepng_get_raw_size(unsigned w, unsigned h, const LodePNGColorMode* color) +{ + return (w * h * lodepng_get_bpp(color) + 7) / 8; +} + +size_t lodepng_get_raw_size_lct(unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) +{ + return (w * h * lodepng_get_bpp_lct(colortype, bitdepth) + 7) / 8; +} + + +#ifdef LODEPNG_COMPILE_PNG +#ifdef LODEPNG_COMPILE_DECODER +/*in an idat chunk, each scanline is a multiple of 8 bits, unlike the lodepng output buffer*/ +static size_t lodepng_get_raw_size_idat(unsigned w, unsigned h, const LodePNGColorMode* color) +{ + return h * ((w * lodepng_get_bpp(color) + 7) / 8); +} +#endif /*LODEPNG_COMPILE_DECODER*/ +#endif /*LODEPNG_COMPILE_PNG*/ + +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + +static void LodePNGUnknownChunks_init(LodePNGInfo* info) +{ + unsigned i; + for(i = 0; i < 3; i++) info->unknown_chunks_data[i] = 0; + for(i = 0; i < 3; i++) info->unknown_chunks_size[i] = 0; +} + +static void LodePNGUnknownChunks_cleanup(LodePNGInfo* info) +{ + unsigned i; + for(i = 0; i < 3; i++) lodepng_free(info->unknown_chunks_data[i]); +} + +static unsigned LodePNGUnknownChunks_copy(LodePNGInfo* dest, const LodePNGInfo* src) +{ + unsigned i; + + LodePNGUnknownChunks_cleanup(dest); + + for(i = 0; i < 3; i++) + { + size_t j; + dest->unknown_chunks_size[i] = src->unknown_chunks_size[i]; + dest->unknown_chunks_data[i] = (unsigned char*)lodepng_malloc(src->unknown_chunks_size[i]); + if(!dest->unknown_chunks_data[i] && dest->unknown_chunks_size[i]) return 83; /*alloc fail*/ + for(j = 0; j < src->unknown_chunks_size[i]; j++) + { + dest->unknown_chunks_data[i][j] = src->unknown_chunks_data[i][j]; + } + } + + return 0; +} + +/******************************************************************************/ + +static void LodePNGText_init(LodePNGInfo* info) +{ + info->text_num = 0; + info->text_keys = NULL; + info->text_strings = NULL; +} + +static void LodePNGText_cleanup(LodePNGInfo* info) +{ + size_t i; + for(i = 0; i < info->text_num; i++) + { + string_cleanup(&info->text_keys[i]); + string_cleanup(&info->text_strings[i]); + } + lodepng_free(info->text_keys); + lodepng_free(info->text_strings); +} + +static unsigned LodePNGText_copy(LodePNGInfo* dest, const LodePNGInfo* source) +{ + size_t i = 0; + dest->text_keys = 0; + dest->text_strings = 0; + dest->text_num = 0; + for(i = 0; i < source->text_num; i++) + { + CERROR_TRY_RETURN(lodepng_add_text(dest, source->text_keys[i], source->text_strings[i])); + } + return 0; +} + +void lodepng_clear_text(LodePNGInfo* info) +{ + LodePNGText_cleanup(info); +} + +unsigned lodepng_add_text(LodePNGInfo* info, const char* key, const char* str) +{ + char** new_keys = (char**)(lodepng_realloc(info->text_keys, sizeof(char*) * (info->text_num + 1))); + char** new_strings = (char**)(lodepng_realloc(info->text_strings, sizeof(char*) * (info->text_num + 1))); + if(!new_keys || !new_strings) + { + lodepng_free(new_keys); + lodepng_free(new_strings); + return 83; /*alloc fail*/ + } + + info->text_num++; + info->text_keys = new_keys; + info->text_strings = new_strings; + + string_init(&info->text_keys[info->text_num - 1]); + string_set(&info->text_keys[info->text_num - 1], key); + + string_init(&info->text_strings[info->text_num - 1]); + string_set(&info->text_strings[info->text_num - 1], str); + + return 0; +} + +/******************************************************************************/ + +static void LodePNGIText_init(LodePNGInfo* info) +{ + info->itext_num = 0; + info->itext_keys = NULL; + info->itext_langtags = NULL; + info->itext_transkeys = NULL; + info->itext_strings = NULL; +} + +static void LodePNGIText_cleanup(LodePNGInfo* info) +{ + size_t i; + for(i = 0; i < info->itext_num; i++) + { + string_cleanup(&info->itext_keys[i]); + string_cleanup(&info->itext_langtags[i]); + string_cleanup(&info->itext_transkeys[i]); + string_cleanup(&info->itext_strings[i]); + } + lodepng_free(info->itext_keys); + lodepng_free(info->itext_langtags); + lodepng_free(info->itext_transkeys); + lodepng_free(info->itext_strings); +} + +static unsigned LodePNGIText_copy(LodePNGInfo* dest, const LodePNGInfo* source) +{ + size_t i = 0; + dest->itext_keys = 0; + dest->itext_langtags = 0; + dest->itext_transkeys = 0; + dest->itext_strings = 0; + dest->itext_num = 0; + for(i = 0; i < source->itext_num; i++) + { + CERROR_TRY_RETURN(lodepng_add_itext(dest, source->itext_keys[i], source->itext_langtags[i], + source->itext_transkeys[i], source->itext_strings[i])); + } + return 0; +} + +void lodepng_clear_itext(LodePNGInfo* info) +{ + LodePNGIText_cleanup(info); +} + +unsigned lodepng_add_itext(LodePNGInfo* info, const char* key, const char* langtag, + const char* transkey, const char* str) +{ + char** new_keys = (char**)(lodepng_realloc(info->itext_keys, sizeof(char*) * (info->itext_num + 1))); + char** new_langtags = (char**)(lodepng_realloc(info->itext_langtags, sizeof(char*) * (info->itext_num + 1))); + char** new_transkeys = (char**)(lodepng_realloc(info->itext_transkeys, sizeof(char*) * (info->itext_num + 1))); + char** new_strings = (char**)(lodepng_realloc(info->itext_strings, sizeof(char*) * (info->itext_num + 1))); + if(!new_keys || !new_langtags || !new_transkeys || !new_strings) + { + lodepng_free(new_keys); + lodepng_free(new_langtags); + lodepng_free(new_transkeys); + lodepng_free(new_strings); + return 83; /*alloc fail*/ + } + + info->itext_num++; + info->itext_keys = new_keys; + info->itext_langtags = new_langtags; + info->itext_transkeys = new_transkeys; + info->itext_strings = new_strings; + + string_init(&info->itext_keys[info->itext_num - 1]); + string_set(&info->itext_keys[info->itext_num - 1], key); + + string_init(&info->itext_langtags[info->itext_num - 1]); + string_set(&info->itext_langtags[info->itext_num - 1], langtag); + + string_init(&info->itext_transkeys[info->itext_num - 1]); + string_set(&info->itext_transkeys[info->itext_num - 1], transkey); + + string_init(&info->itext_strings[info->itext_num - 1]); + string_set(&info->itext_strings[info->itext_num - 1], str); + + return 0; +} +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + +void lodepng_info_init(LodePNGInfo* info) +{ + lodepng_color_mode_init(&info->color); + info->interlace_method = 0; + info->compression_method = 0; + info->filter_method = 0; +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + info->background_defined = 0; + info->background_r = info->background_g = info->background_b = 0; + + LodePNGText_init(info); + LodePNGIText_init(info); + + info->time_defined = 0; + info->phys_defined = 0; + + LodePNGUnknownChunks_init(info); +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ +} + +void lodepng_info_cleanup(LodePNGInfo* info) +{ + lodepng_color_mode_cleanup(&info->color); +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + LodePNGText_cleanup(info); + LodePNGIText_cleanup(info); + + LodePNGUnknownChunks_cleanup(info); +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ +} + +unsigned lodepng_info_copy(LodePNGInfo* dest, const LodePNGInfo* source) +{ + lodepng_info_cleanup(dest); + *dest = *source; + lodepng_color_mode_init(&dest->color); + CERROR_TRY_RETURN(lodepng_color_mode_copy(&dest->color, &source->color)); + +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + CERROR_TRY_RETURN(LodePNGText_copy(dest, source)); + CERROR_TRY_RETURN(LodePNGIText_copy(dest, source)); + + LodePNGUnknownChunks_init(dest); + CERROR_TRY_RETURN(LodePNGUnknownChunks_copy(dest, source)); +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + return 0; +} + +void lodepng_info_swap(LodePNGInfo* a, LodePNGInfo* b) +{ + LodePNGInfo temp = *a; + *a = *b; + *b = temp; +} + +/* ////////////////////////////////////////////////////////////////////////// */ + +/*index: bitgroup index, bits: bitgroup size(1, 2 or 4), in: bitgroup value, out: octet array to add bits to*/ +static void addColorBits(unsigned char* out, size_t index, unsigned bits, unsigned in) +{ + unsigned m = bits == 1 ? 7 : bits == 2 ? 3 : 1; /*8 / bits - 1*/ + /*p = the partial index in the byte, e.g. with 4 palettebits it is 0 for first half or 1 for second half*/ + unsigned p = index & m; + in &= (1u << bits) - 1u; /*filter out any other bits of the input value*/ + in = in << (bits * (m - p)); + if(p == 0) out[index * bits / 8] = in; + else out[index * bits / 8] |= in; +} + +typedef struct ColorTree ColorTree; + +/* +One node of a color tree +This is the data structure used to count the number of unique colors and to get a palette +index for a color. It's like an octree, but because the alpha channel is used too, each +node has 16 instead of 8 children. +*/ +struct ColorTree +{ + ColorTree* children[16]; /*up to 16 pointers to ColorTree of next level*/ + int index; /*the payload. Only has a meaningful value if this is in the last level*/ +}; + +static void color_tree_init(ColorTree* tree) +{ + int i; + for(i = 0; i < 16; i++) tree->children[i] = 0; + tree->index = -1; +} + +static void color_tree_cleanup(ColorTree* tree) +{ + int i; + for(i = 0; i < 16; i++) + { + if(tree->children[i]) + { + color_tree_cleanup(tree->children[i]); + lodepng_free(tree->children[i]); + } + } +} + +/*returns -1 if color not present, its index otherwise*/ +static int color_tree_get(ColorTree* tree, unsigned char r, unsigned char g, unsigned char b, unsigned char a) +{ + int bit = 0; + for(bit = 0; bit < 8; bit++) + { + int i = 8 * ((r >> bit) & 1) + 4 * ((g >> bit) & 1) + 2 * ((b >> bit) & 1) + 1 * ((a >> bit) & 1); + if(!tree->children[i]) return -1; + else tree = tree->children[i]; + } + return tree ? tree->index : -1; +} + +#ifdef LODEPNG_COMPILE_ENCODER +static int color_tree_has(ColorTree* tree, unsigned char r, unsigned char g, unsigned char b, unsigned char a) +{ + return color_tree_get(tree, r, g, b, a) >= 0; +} +#endif /*LODEPNG_COMPILE_ENCODER*/ + +/*color is not allowed to already exist. +Index should be >= 0 (it's signed to be compatible with using -1 for "doesn't exist")*/ +static void color_tree_add(ColorTree* tree, + unsigned char r, unsigned char g, unsigned char b, unsigned char a, unsigned index) +{ + int bit; + for(bit = 0; bit < 8; bit++) + { + int i = 8 * ((r >> bit) & 1) + 4 * ((g >> bit) & 1) + 2 * ((b >> bit) & 1) + 1 * ((a >> bit) & 1); + if(!tree->children[i]) + { + tree->children[i] = (ColorTree*)lodepng_malloc(sizeof(ColorTree)); + color_tree_init(tree->children[i]); + } + tree = tree->children[i]; + } + tree->index = (int)index; +} + +/*put a pixel, given its RGBA color, into image of any color type*/ +static unsigned rgba8ToPixel(unsigned char* out, size_t i, + const LodePNGColorMode* mode, ColorTree* tree /*for palette*/, + unsigned char r, unsigned char g, unsigned char b, unsigned char a) +{ + if(mode->colortype == LCT_GREY) + { + unsigned char grey = r; /*((unsigned short)r + g + b) / 3*/; + if(mode->bitdepth == 8) out[i] = grey; + else if(mode->bitdepth == 16) out[i * 2 + 0] = out[i * 2 + 1] = grey; + else + { + /*take the most significant bits of grey*/ + grey = (grey >> (8 - mode->bitdepth)) & ((1 << mode->bitdepth) - 1); + addColorBits(out, i, mode->bitdepth, grey); + } + } + else if(mode->colortype == LCT_RGB) + { + if(mode->bitdepth == 8) + { + out[i * 3 + 0] = r; + out[i * 3 + 1] = g; + out[i * 3 + 2] = b; + } + else + { + out[i * 6 + 0] = out[i * 6 + 1] = r; + out[i * 6 + 2] = out[i * 6 + 3] = g; + out[i * 6 + 4] = out[i * 6 + 5] = b; + } + } + else if(mode->colortype == LCT_PALETTE) + { + int index = color_tree_get(tree, r, g, b, a); + if(index < 0) return 82; /*color not in palette*/ + if(mode->bitdepth == 8) out[i] = index; + else addColorBits(out, i, mode->bitdepth, (unsigned)index); + } + else if(mode->colortype == LCT_GREY_ALPHA) + { + unsigned char grey = r; /*((unsigned short)r + g + b) / 3*/; + if(mode->bitdepth == 8) + { + out[i * 2 + 0] = grey; + out[i * 2 + 1] = a; + } + else if(mode->bitdepth == 16) + { + out[i * 4 + 0] = out[i * 4 + 1] = grey; + out[i * 4 + 2] = out[i * 4 + 3] = a; + } + } + else if(mode->colortype == LCT_RGBA) + { + if(mode->bitdepth == 8) + { + out[i * 4 + 0] = r; + out[i * 4 + 1] = g; + out[i * 4 + 2] = b; + out[i * 4 + 3] = a; + } + else + { + out[i * 8 + 0] = out[i * 8 + 1] = r; + out[i * 8 + 2] = out[i * 8 + 3] = g; + out[i * 8 + 4] = out[i * 8 + 5] = b; + out[i * 8 + 6] = out[i * 8 + 7] = a; + } + } + + return 0; /*no error*/ +} + +/*put a pixel, given its RGBA16 color, into image of any color 16-bitdepth type*/ +static void rgba16ToPixel(unsigned char* out, size_t i, + const LodePNGColorMode* mode, + unsigned short r, unsigned short g, unsigned short b, unsigned short a) +{ + if(mode->colortype == LCT_GREY) + { + unsigned short grey = r; /*((unsigned)r + g + b) / 3*/; + out[i * 2 + 0] = (grey >> 8) & 255; + out[i * 2 + 1] = grey & 255; + } + else if(mode->colortype == LCT_RGB) + { + out[i * 6 + 0] = (r >> 8) & 255; + out[i * 6 + 1] = r & 255; + out[i * 6 + 2] = (g >> 8) & 255; + out[i * 6 + 3] = g & 255; + out[i * 6 + 4] = (b >> 8) & 255; + out[i * 6 + 5] = b & 255; + } + else if(mode->colortype == LCT_GREY_ALPHA) + { + unsigned short grey = r; /*((unsigned)r + g + b) / 3*/; + out[i * 4 + 0] = (grey >> 8) & 255; + out[i * 4 + 1] = grey & 255; + out[i * 4 + 2] = (a >> 8) & 255; + out[i * 4 + 3] = a & 255; + } + else if(mode->colortype == LCT_RGBA) + { + out[i * 8 + 0] = (r >> 8) & 255; + out[i * 8 + 1] = r & 255; + out[i * 8 + 2] = (g >> 8) & 255; + out[i * 8 + 3] = g & 255; + out[i * 8 + 4] = (b >> 8) & 255; + out[i * 8 + 5] = b & 255; + out[i * 8 + 6] = (a >> 8) & 255; + out[i * 8 + 7] = a & 255; + } +} + +/*Get RGBA8 color of pixel with index i (y * width + x) from the raw image with given color type.*/ +static void getPixelColorRGBA8(unsigned char* r, unsigned char* g, + unsigned char* b, unsigned char* a, + const unsigned char* in, size_t i, + const LodePNGColorMode* mode) +{ + if(mode->colortype == LCT_GREY) + { + if(mode->bitdepth == 8) + { + *r = *g = *b = in[i]; + if(mode->key_defined && *r == mode->key_r) *a = 0; + else *a = 255; + } + else if(mode->bitdepth == 16) + { + *r = *g = *b = in[i * 2 + 0]; + if(mode->key_defined && 256U * in[i * 2 + 0] + in[i * 2 + 1] == mode->key_r) *a = 0; + else *a = 255; + } + else + { + unsigned highest = ((1U << mode->bitdepth) - 1U); /*highest possible value for this bit depth*/ + size_t j = i * mode->bitdepth; + unsigned value = readBitsFromReversedStream(&j, in, mode->bitdepth); + *r = *g = *b = (value * 255) / highest; + if(mode->key_defined && value == mode->key_r) *a = 0; + else *a = 255; + } + } + else if(mode->colortype == LCT_RGB) + { + if(mode->bitdepth == 8) + { + *r = in[i * 3 + 0]; *g = in[i * 3 + 1]; *b = in[i * 3 + 2]; + if(mode->key_defined && *r == mode->key_r && *g == mode->key_g && *b == mode->key_b) *a = 0; + else *a = 255; + } + else + { + *r = in[i * 6 + 0]; + *g = in[i * 6 + 2]; + *b = in[i * 6 + 4]; + if(mode->key_defined && 256U * in[i * 6 + 0] + in[i * 6 + 1] == mode->key_r + && 256U * in[i * 6 + 2] + in[i * 6 + 3] == mode->key_g + && 256U * in[i * 6 + 4] + in[i * 6 + 5] == mode->key_b) *a = 0; + else *a = 255; + } + } + else if(mode->colortype == LCT_PALETTE) + { + unsigned index; + if(mode->bitdepth == 8) index = in[i]; + else + { + size_t j = i * mode->bitdepth; + index = readBitsFromReversedStream(&j, in, mode->bitdepth); + } + + if(index >= mode->palettesize) + { + /*This is an error according to the PNG spec, but common PNG decoders make it black instead. + Done here too, slightly faster due to no error handling needed.*/ + *r = *g = *b = 0; + *a = 255; + } + else + { + *r = mode->palette[index * 4 + 0]; + *g = mode->palette[index * 4 + 1]; + *b = mode->palette[index * 4 + 2]; + *a = mode->palette[index * 4 + 3]; + } + } + else if(mode->colortype == LCT_GREY_ALPHA) + { + if(mode->bitdepth == 8) + { + *r = *g = *b = in[i * 2 + 0]; + *a = in[i * 2 + 1]; + } + else + { + *r = *g = *b = in[i * 4 + 0]; + *a = in[i * 4 + 2]; + } + } + else if(mode->colortype == LCT_RGBA) + { + if(mode->bitdepth == 8) + { + *r = in[i * 4 + 0]; + *g = in[i * 4 + 1]; + *b = in[i * 4 + 2]; + *a = in[i * 4 + 3]; + } + else + { + *r = in[i * 8 + 0]; + *g = in[i * 8 + 2]; + *b = in[i * 8 + 4]; + *a = in[i * 8 + 6]; + } + } +} + +/*Similar to getPixelColorRGBA8, but with all the for loops inside of the color +mode test cases, optimized to convert the colors much faster, when converting +to RGBA or RGB with 8 bit per cannel. buffer must be RGBA or RGB output with +enough memory, if has_alpha is true the output is RGBA. mode has the color mode +of the input buffer.*/ +static void getPixelColorsRGBA8(unsigned char* buffer, size_t numpixels, + unsigned has_alpha, const unsigned char* in, + const LodePNGColorMode* mode) +{ + unsigned num_channels = has_alpha ? 4 : 3; + size_t i; + if(mode->colortype == LCT_GREY) + { + if(mode->bitdepth == 8) + { + for(i = 0; i < numpixels; i++, buffer += num_channels) + { + buffer[0] = buffer[1] = buffer[2] = in[i]; + if(has_alpha) buffer[3] = mode->key_defined && in[i] == mode->key_r ? 0 : 255; + } + } + else if(mode->bitdepth == 16) + { + for(i = 0; i < numpixels; i++, buffer += num_channels) + { + buffer[0] = buffer[1] = buffer[2] = in[i * 2]; + if(has_alpha) buffer[3] = mode->key_defined && 256U * in[i * 2 + 0] + in[i * 2 + 1] == mode->key_r ? 0 : 255; + } + } + else + { + unsigned highest = ((1U << mode->bitdepth) - 1U); /*highest possible value for this bit depth*/ + size_t j = 0; + for(i = 0; i < numpixels; i++, buffer += num_channels) + { + unsigned value = readBitsFromReversedStream(&j, in, mode->bitdepth); + buffer[0] = buffer[1] = buffer[2] = (value * 255) / highest; + if(has_alpha) buffer[3] = mode->key_defined && value == mode->key_r ? 0 : 255; + } + } + } + else if(mode->colortype == LCT_RGB) + { + if(mode->bitdepth == 8) + { + for(i = 0; i < numpixels; i++, buffer += num_channels) + { + buffer[0] = in[i * 3 + 0]; + buffer[1] = in[i * 3 + 1]; + buffer[2] = in[i * 3 + 2]; + if(has_alpha) buffer[3] = mode->key_defined && buffer[0] == mode->key_r + && buffer[1]== mode->key_g && buffer[2] == mode->key_b ? 0 : 255; + } + } + else + { + for(i = 0; i < numpixels; i++, buffer += num_channels) + { + buffer[0] = in[i * 6 + 0]; + buffer[1] = in[i * 6 + 2]; + buffer[2] = in[i * 6 + 4]; + if(has_alpha) buffer[3] = mode->key_defined + && 256U * in[i * 6 + 0] + in[i * 6 + 1] == mode->key_r + && 256U * in[i * 6 + 2] + in[i * 6 + 3] == mode->key_g + && 256U * in[i * 6 + 4] + in[i * 6 + 5] == mode->key_b ? 0 : 255; + } + } + } + else if(mode->colortype == LCT_PALETTE) + { + unsigned index; + size_t j = 0; + for(i = 0; i < numpixels; i++, buffer += num_channels) + { + if(mode->bitdepth == 8) index = in[i]; + else index = readBitsFromReversedStream(&j, in, mode->bitdepth); + + if(index >= mode->palettesize) + { + /*This is an error according to the PNG spec, but most PNG decoders make it black instead. + Done here too, slightly faster due to no error handling needed.*/ + buffer[0] = buffer[1] = buffer[2] = 0; + if(has_alpha) buffer[3] = 255; + } + else + { + buffer[0] = mode->palette[index * 4 + 0]; + buffer[1] = mode->palette[index * 4 + 1]; + buffer[2] = mode->palette[index * 4 + 2]; + if(has_alpha) buffer[3] = mode->palette[index * 4 + 3]; + } + } + } + else if(mode->colortype == LCT_GREY_ALPHA) + { + if(mode->bitdepth == 8) + { + for(i = 0; i < numpixels; i++, buffer += num_channels) + { + buffer[0] = buffer[1] = buffer[2] = in[i * 2 + 0]; + if(has_alpha) buffer[3] = in[i * 2 + 1]; + } + } + else + { + for(i = 0; i < numpixels; i++, buffer += num_channels) + { + buffer[0] = buffer[1] = buffer[2] = in[i * 4 + 0]; + if(has_alpha) buffer[3] = in[i * 4 + 2]; + } + } + } + else if(mode->colortype == LCT_RGBA) + { + if(mode->bitdepth == 8) + { + for(i = 0; i < numpixels; i++, buffer += num_channels) + { + buffer[0] = in[i * 4 + 0]; + buffer[1] = in[i * 4 + 1]; + buffer[2] = in[i * 4 + 2]; + if(has_alpha) buffer[3] = in[i * 4 + 3]; + } + } + else + { + for(i = 0; i < numpixels; i++, buffer += num_channels) + { + buffer[0] = in[i * 8 + 0]; + buffer[1] = in[i * 8 + 2]; + buffer[2] = in[i * 8 + 4]; + if(has_alpha) buffer[3] = in[i * 8 + 6]; + } + } + } +} + +/*Get RGBA16 color of pixel with index i (y * width + x) from the raw image with +given color type, but the given color type must be 16-bit itself.*/ +static void getPixelColorRGBA16(unsigned short* r, unsigned short* g, unsigned short* b, unsigned short* a, + const unsigned char* in, size_t i, const LodePNGColorMode* mode) +{ + if(mode->colortype == LCT_GREY) + { + *r = *g = *b = 256 * in[i * 2 + 0] + in[i * 2 + 1]; + if(mode->key_defined && 256U * in[i * 2 + 0] + in[i * 2 + 1] == mode->key_r) *a = 0; + else *a = 65535; + } + else if(mode->colortype == LCT_RGB) + { + *r = 256 * in[i * 6 + 0] + in[i * 6 + 1]; + *g = 256 * in[i * 6 + 2] + in[i * 6 + 3]; + *b = 256 * in[i * 6 + 4] + in[i * 6 + 5]; + if(mode->key_defined && 256U * in[i * 6 + 0] + in[i * 6 + 1] == mode->key_r + && 256U * in[i * 6 + 2] + in[i * 6 + 3] == mode->key_g + && 256U * in[i * 6 + 4] + in[i * 6 + 5] == mode->key_b) *a = 0; + else *a = 65535; + } + else if(mode->colortype == LCT_GREY_ALPHA) + { + *r = *g = *b = 256 * in[i * 4 + 0] + in[i * 4 + 1]; + *a = 256 * in[i * 4 + 2] + in[i * 4 + 3]; + } + else if(mode->colortype == LCT_RGBA) + { + *r = 256 * in[i * 8 + 0] + in[i * 8 + 1]; + *g = 256 * in[i * 8 + 2] + in[i * 8 + 3]; + *b = 256 * in[i * 8 + 4] + in[i * 8 + 5]; + *a = 256 * in[i * 8 + 6] + in[i * 8 + 7]; + } +} + +unsigned lodepng_convert(unsigned char* out, const unsigned char* in, + LodePNGColorMode* mode_out, const LodePNGColorMode* mode_in, + unsigned w, unsigned h) +{ + size_t i; + ColorTree tree; + size_t numpixels = w * h; + + if(lodepng_color_mode_equal(mode_out, mode_in)) + { + size_t numbytes = lodepng_get_raw_size(w, h, mode_in); + for(i = 0; i < numbytes; i++) out[i] = in[i]; + return 0; + } + + if(mode_out->colortype == LCT_PALETTE) + { + size_t palsize = 1u << mode_out->bitdepth; + if(mode_out->palettesize < palsize) palsize = mode_out->palettesize; + color_tree_init(&tree); + for(i = 0; i < palsize; i++) + { + unsigned char* p = &mode_out->palette[i * 4]; + color_tree_add(&tree, p[0], p[1], p[2], p[3], i); + } + } + + if(mode_in->bitdepth == 16 && mode_out->bitdepth == 16) + { + for(i = 0; i < numpixels; i++) + { + unsigned short r = 0, g = 0, b = 0, a = 0; + getPixelColorRGBA16(&r, &g, &b, &a, in, i, mode_in); + rgba16ToPixel(out, i, mode_out, r, g, b, a); + } + } + else if(mode_out->bitdepth == 8 && mode_out->colortype == LCT_RGBA) + { + getPixelColorsRGBA8(out, numpixels, 1, in, mode_in); + } + else if(mode_out->bitdepth == 8 && mode_out->colortype == LCT_RGB) + { + getPixelColorsRGBA8(out, numpixels, 0, in, mode_in); + } + else + { + unsigned char r = 0, g = 0, b = 0, a = 0; + for(i = 0; i < numpixels; i++) + { + getPixelColorRGBA8(&r, &g, &b, &a, in, i, mode_in); + rgba8ToPixel(out, i, mode_out, &tree, r, g, b, a); + } + } + + if(mode_out->colortype == LCT_PALETTE) + { + color_tree_cleanup(&tree); + } + + return 0; /*no error (this function currently never has one, but maybe OOM detection added later.)*/ +} + +#ifdef LODEPNG_COMPILE_ENCODER + +void lodepng_color_profile_init(LodePNGColorProfile* profile) +{ + profile->colored = 0; + profile->key = 0; + profile->alpha = 0; + profile->key_r = profile->key_g = profile->key_b = 0; + profile->numcolors = 0; + profile->bits = 1; +} + +/*function used for debug purposes with C++*/ +/*void printColorProfile(LodePNGColorProfile* p) +{ + std::cout << "colored: " << (int)p->colored << ", "; + std::cout << "key: " << (int)p->key << ", "; + std::cout << "key_r: " << (int)p->key_r << ", "; + std::cout << "key_g: " << (int)p->key_g << ", "; + std::cout << "key_b: " << (int)p->key_b << ", "; + std::cout << "alpha: " << (int)p->alpha << ", "; + std::cout << "numcolors: " << (int)p->numcolors << ", "; + std::cout << "bits: " << (int)p->bits << std::endl; +}*/ + +/*Returns how many bits needed to represent given value (max 8 bit)*/ +unsigned getValueRequiredBits(unsigned char value) +{ + if(value == 0 || value == 255) return 1; + /*The scaling of 2-bit and 4-bit values uses multiples of 85 and 17*/ + if(value % 17 == 0) return value % 85 == 0 ? 2 : 4; + return 8; +} + +/*profile must already have been inited with mode. +It's ok to set some parameters of profile to done already.*/ +unsigned get_color_profile(LodePNGColorProfile* profile, + const unsigned char* in, unsigned w, unsigned h, + const LodePNGColorMode* mode) +{ + unsigned error = 0; + size_t i; + ColorTree tree; + size_t numpixels = w * h; + + unsigned colored_done = lodepng_is_greyscale_type(mode) ? 1 : 0; + unsigned alpha_done = lodepng_can_have_alpha(mode) ? 0 : 1; + unsigned numcolors_done = 0; + unsigned bpp = lodepng_get_bpp(mode); + unsigned bits_done = bpp == 1 ? 1 : 0; + unsigned maxnumcolors = 257; + unsigned sixteen = 0; + if(bpp <= 8) maxnumcolors = bpp == 1 ? 2 : (bpp == 2 ? 4 : (bpp == 4 ? 16 : 256)); + + color_tree_init(&tree); + + /*Check if the 16-bit input is truly 16-bit*/ + if(mode->bitdepth == 16) + { + unsigned short r, g, b, a; + for(i = 0; i < numpixels; i++) + { + getPixelColorRGBA16(&r, &g, &b, &a, in, i, mode); + if(r % 257u != 0 || g % 257u != 0 || b % 257u != 0 || a % 257u != 0) /*first and second byte differ*/ + { + sixteen = 1; + break; + } + } + } + + if(sixteen) + { + unsigned short r = 0, g = 0, b = 0, a = 0; + profile->bits = 16; + bits_done = numcolors_done = 1; /*counting colors no longer useful, palette doesn't support 16-bit*/ + + for(i = 0; i < numpixels; i++) + { + getPixelColorRGBA16(&r, &g, &b, &a, in, i, mode); + + if(!colored_done && (r != g || r != b)) + { + profile->colored = 1; + colored_done = 1; + } + + if(!alpha_done) + { + unsigned matchkey = (r == profile->key_r && g == profile->key_g && b == profile->key_b); + if(a != 65535 && (a != 0 || (profile->key && !matchkey))) + { + profile->alpha = 1; + alpha_done = 1; + if(profile->bits < 8) profile->bits = 8; /*PNG has no alphachannel modes with less than 8-bit per channel*/ + } + else if(a == 0 && !profile->alpha && !profile->key) + { + profile->key = 1; + profile->key_r = r; + profile->key_g = g; + profile->key_b = b; + } + else if(a == 65535 && profile->key && matchkey) + { + /* Color key cannot be used if an opaque pixel also has that RGB color. */ + profile->alpha = 1; + alpha_done = 1; + } + } + + if(alpha_done && numcolors_done && colored_done && bits_done) break; + } + } + else /* < 16-bit */ + { + for(i = 0; i < numpixels; i++) + { + unsigned char r = 0, g = 0, b = 0, a = 0; + getPixelColorRGBA8(&r, &g, &b, &a, in, i, mode); + + if(!bits_done && profile->bits < 8) + { + /*only r is checked, < 8 bits is only relevant for greyscale*/ + unsigned bits = getValueRequiredBits(r); + if(bits > profile->bits) profile->bits = bits; + } + bits_done = (profile->bits >= bpp); + + if(!colored_done && (r != g || r != b)) + { + profile->colored = 1; + colored_done = 1; + if(profile->bits < 8) profile->bits = 8; /*PNG has no colored modes with less than 8-bit per channel*/ + } + + if(!alpha_done) + { + unsigned matchkey = (r == profile->key_r && g == profile->key_g && b == profile->key_b); + if(a != 255 && (a != 0 || (profile->key && !matchkey))) + { + profile->alpha = 1; + alpha_done = 1; + if(profile->bits < 8) profile->bits = 8; /*PNG has no alphachannel modes with less than 8-bit per channel*/ + } + else if(a == 0 && !profile->alpha && !profile->key) + { + profile->key = 1; + profile->key_r = r; + profile->key_g = g; + profile->key_b = b; + } + else if(a == 255 && profile->key && matchkey) + { + /* Color key cannot be used if an opaque pixel also has that RGB color. */ + profile->alpha = 1; + alpha_done = 1; + if(profile->bits < 8) profile->bits = 8; /*PNG has no alphachannel modes with less than 8-bit per channel*/ + } + } + + if(!numcolors_done) + { + if(!color_tree_has(&tree, r, g, b, a)) + { + color_tree_add(&tree, r, g, b, a, profile->numcolors); + if(profile->numcolors < 256) + { + unsigned char* p = profile->palette; + unsigned n = profile->numcolors; + p[n * 4 + 0] = r; + p[n * 4 + 1] = g; + p[n * 4 + 2] = b; + p[n * 4 + 3] = a; + } + profile->numcolors++; + numcolors_done = profile->numcolors >= maxnumcolors; + } + } + + if(alpha_done && numcolors_done && colored_done && bits_done) break; + } + + /*make the profile's key always 16-bit for consistency - repeat each byte twice*/ + profile->key_r *= 257; + profile->key_g *= 257; + profile->key_b *= 257; + } + + color_tree_cleanup(&tree); + return error; +} + +/*Automatically chooses color type that gives smallest amount of bits in the +output image, e.g. grey if there are only greyscale pixels, palette if there +are less than 256 colors, ... +Updates values of mode with a potentially smaller color model. mode_out should +contain the user chosen color model, but will be overwritten with the new chosen one.*/ +unsigned lodepng_auto_choose_color(LodePNGColorMode* mode_out, + const unsigned char* image, unsigned w, unsigned h, + const LodePNGColorMode* mode_in) +{ + LodePNGColorProfile prof; + unsigned error = 0; + unsigned i, n, palettebits, grey_ok, palette_ok; + + lodepng_color_profile_init(&prof); + error = get_color_profile(&prof, image, w, h, mode_in); + if(error) return error; + mode_out->key_defined = 0; + + if(prof.key && w * h <= 16) prof.alpha = 1; /*too few pixels to justify tRNS chunk overhead*/ + grey_ok = !prof.colored && !prof.alpha; /*grey without alpha, with potentially low bits*/ + n = prof.numcolors; + palettebits = n <= 2 ? 1 : (n <= 4 ? 2 : (n <= 16 ? 4 : 8)); + palette_ok = n <= 256 && (n * 2 < w * h) && prof.bits <= 8; + if(w * h < n * 2) palette_ok = 0; /*don't add palette overhead if image has only a few pixels*/ + if(grey_ok && prof.bits <= palettebits) palette_ok = 0; /*grey is less overhead*/ + + if(palette_ok) + { + unsigned char* p = prof.palette; + lodepng_palette_clear(mode_out); /*remove potential earlier palette*/ + for(i = 0; i < prof.numcolors; i++) + { + error = lodepng_palette_add(mode_out, p[i * 4 + 0], p[i * 4 + 1], p[i * 4 + 2], p[i * 4 + 3]); + if(error) break; + } + + mode_out->colortype = LCT_PALETTE; + mode_out->bitdepth = palettebits; + + if(mode_in->colortype == LCT_PALETTE && mode_in->palettesize >= mode_out->palettesize + && mode_in->bitdepth == mode_out->bitdepth) + { + /*If input should have same palette colors, keep original to preserve its order and prevent conversion*/ + lodepng_color_mode_cleanup(mode_out); + lodepng_color_mode_copy(mode_out, mode_in); + } + } + else /*8-bit or 16-bit per channel*/ + { + mode_out->bitdepth = prof.bits; + mode_out->colortype = prof.alpha ? (prof.colored ? LCT_RGBA : LCT_GREY_ALPHA) + : (prof.colored ? LCT_RGB : LCT_GREY); + + if(prof.key && !prof.alpha) + { + unsigned mask = (1u << mode_out->bitdepth) - 1u; /*profile always uses 16-bit, mask converts it*/ + mode_out->key_r = prof.key_r & mask; + mode_out->key_g = prof.key_g & mask; + mode_out->key_b = prof.key_b & mask; + mode_out->key_defined = 1; + } + } + + return error; +} + +#endif /* #ifdef LODEPNG_COMPILE_ENCODER */ + +/* +Paeth predicter, used by PNG filter type 4 +The parameters are of type short, but should come from unsigned chars, the shorts +are only needed to make the paeth calculation correct. +*/ +static unsigned char paethPredictor(short a, short b, short c) +{ + short pa = abs(b - c); + short pb = abs(a - c); + short pc = abs(a + b - c - c); + + if(pc < pa && pc < pb) return (unsigned char)c; + else if(pb < pa) return (unsigned char)b; + else return (unsigned char)a; +} + +/*shared values used by multiple Adam7 related functions*/ + +static const unsigned ADAM7_IX[7] = { 0, 4, 0, 2, 0, 1, 0 }; /*x start values*/ +static const unsigned ADAM7_IY[7] = { 0, 0, 4, 0, 2, 0, 1 }; /*y start values*/ +static const unsigned ADAM7_DX[7] = { 8, 8, 4, 4, 2, 2, 1 }; /*x delta values*/ +static const unsigned ADAM7_DY[7] = { 8, 8, 8, 4, 4, 2, 2 }; /*y delta values*/ + +/* +Outputs various dimensions and positions in the image related to the Adam7 reduced images. +passw: output containing the width of the 7 passes +passh: output containing the height of the 7 passes +filter_passstart: output containing the index of the start and end of each + reduced image with filter bytes +padded_passstart output containing the index of the start and end of each + reduced image when without filter bytes but with padded scanlines +passstart: output containing the index of the start and end of each reduced + image without padding between scanlines, but still padding between the images +w, h: width and height of non-interlaced image +bpp: bits per pixel +"padded" is only relevant if bpp is less than 8 and a scanline or image does not + end at a full byte +*/ +static void Adam7_getpassvalues(unsigned passw[7], unsigned passh[7], size_t filter_passstart[8], + size_t padded_passstart[8], size_t passstart[8], unsigned w, unsigned h, unsigned bpp) +{ + /*the passstart values have 8 values: the 8th one indicates the byte after the end of the 7th (= last) pass*/ + unsigned i; + + /*calculate width and height in pixels of each pass*/ + for(i = 0; i < 7; i++) + { + passw[i] = (w + ADAM7_DX[i] - ADAM7_IX[i] - 1) / ADAM7_DX[i]; + passh[i] = (h + ADAM7_DY[i] - ADAM7_IY[i] - 1) / ADAM7_DY[i]; + if(passw[i] == 0) passh[i] = 0; + if(passh[i] == 0) passw[i] = 0; + } + + filter_passstart[0] = padded_passstart[0] = passstart[0] = 0; + for(i = 0; i < 7; i++) + { + /*if passw[i] is 0, it's 0 bytes, not 1 (no filtertype-byte)*/ + filter_passstart[i + 1] = filter_passstart[i] + + ((passw[i] && passh[i]) ? passh[i] * (1 + (passw[i] * bpp + 7) / 8) : 0); + /*bits padded if needed to fill full byte at end of each scanline*/ + padded_passstart[i + 1] = padded_passstart[i] + passh[i] * ((passw[i] * bpp + 7) / 8); + /*only padded at end of reduced image*/ + passstart[i + 1] = passstart[i] + (passh[i] * passw[i] * bpp + 7) / 8; + } +} + +#ifdef LODEPNG_COMPILE_DECODER + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / PNG Decoder / */ +/* ////////////////////////////////////////////////////////////////////////// */ + +/*read the information from the header and store it in the LodePNGInfo. return value is error*/ +unsigned lodepng_inspect(unsigned* w, unsigned* h, LodePNGState* state, + const unsigned char* in, size_t insize) +{ + LodePNGInfo* info = &state->info_png; + if(insize == 0 || in == 0) + { + CERROR_RETURN_ERROR(state->error, 48); /*error: the given data is empty*/ + } + if(insize < 29) + { + CERROR_RETURN_ERROR(state->error, 27); /*error: the data length is smaller than the length of a PNG header*/ + } + + /*when decoding a new PNG image, make sure all parameters created after previous decoding are reset*/ + lodepng_info_cleanup(info); + lodepng_info_init(info); + + if(in[0] != 137 || in[1] != 80 || in[2] != 78 || in[3] != 71 + || in[4] != 13 || in[5] != 10 || in[6] != 26 || in[7] != 10) + { + CERROR_RETURN_ERROR(state->error, 28); /*error: the first 8 bytes are not the correct PNG signature*/ + } + if(in[12] != 'I' || in[13] != 'H' || in[14] != 'D' || in[15] != 'R') + { + CERROR_RETURN_ERROR(state->error, 29); /*error: it doesn't start with a IHDR chunk!*/ + } + + /*read the values given in the header*/ + *w = lodepng_read32bitInt(&in[16]); + *h = lodepng_read32bitInt(&in[20]); + info->color.bitdepth = in[24]; + info->color.colortype = (LodePNGColorType)in[25]; + info->compression_method = in[26]; + info->filter_method = in[27]; + info->interlace_method = in[28]; + + if(!state->decoder.ignore_crc) + { + unsigned CRC = lodepng_read32bitInt(&in[29]); + unsigned checksum = lodepng_crc32(&in[12], 17); + if(CRC != checksum) + { + CERROR_RETURN_ERROR(state->error, 57); /*invalid CRC*/ + } + } + + /*error: only compression method 0 is allowed in the specification*/ + if(info->compression_method != 0) CERROR_RETURN_ERROR(state->error, 32); + /*error: only filter method 0 is allowed in the specification*/ + if(info->filter_method != 0) CERROR_RETURN_ERROR(state->error, 33); + /*error: only interlace methods 0 and 1 exist in the specification*/ + if(info->interlace_method > 1) CERROR_RETURN_ERROR(state->error, 34); + + state->error = checkColorValidity(info->color.colortype, info->color.bitdepth); + return state->error; +} + +static unsigned unfilterScanline(unsigned char* recon, const unsigned char* scanline, const unsigned char* precon, + size_t bytewidth, unsigned char filterType, size_t length) +{ + /* + For PNG filter method 0 + unfilter a PNG image scanline by scanline. when the pixels are smaller than 1 byte, + the filter works byte per byte (bytewidth = 1) + precon is the previous unfiltered scanline, recon the result, scanline the current one + the incoming scanlines do NOT include the filtertype byte, that one is given in the parameter filterType instead + recon and scanline MAY be the same memory address! precon must be disjoint. + */ + + size_t i; + switch(filterType) + { + case 0: + for(i = 0; i < length; i++) recon[i] = scanline[i]; + break; + case 1: + for(i = 0; i < bytewidth; i++) recon[i] = scanline[i]; + for(i = bytewidth; i < length; i++) recon[i] = scanline[i] + recon[i - bytewidth]; + break; + case 2: + if(precon) + { + for(i = 0; i < length; i++) recon[i] = scanline[i] + precon[i]; + } + else + { + for(i = 0; i < length; i++) recon[i] = scanline[i]; + } + break; + case 3: + if(precon) + { + for(i = 0; i < bytewidth; i++) recon[i] = scanline[i] + precon[i] / 2; + for(i = bytewidth; i < length; i++) recon[i] = scanline[i] + ((recon[i - bytewidth] + precon[i]) / 2); + } + else + { + for(i = 0; i < bytewidth; i++) recon[i] = scanline[i]; + for(i = bytewidth; i < length; i++) recon[i] = scanline[i] + recon[i - bytewidth] / 2; + } + break; + case 4: + if(precon) + { + for(i = 0; i < bytewidth; i++) + { + recon[i] = (scanline[i] + precon[i]); /*paethPredictor(0, precon[i], 0) is always precon[i]*/ + } + for(i = bytewidth; i < length; i++) + { + recon[i] = (scanline[i] + paethPredictor(recon[i - bytewidth], precon[i], precon[i - bytewidth])); + } + } + else + { + for(i = 0; i < bytewidth; i++) + { + recon[i] = scanline[i]; + } + for(i = bytewidth; i < length; i++) + { + /*paethPredictor(recon[i - bytewidth], 0, 0) is always recon[i - bytewidth]*/ + recon[i] = (scanline[i] + recon[i - bytewidth]); + } + } + break; + default: return 36; /*error: unexisting filter type given*/ + } + return 0; +} + +static unsigned unfilter(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, unsigned bpp) +{ + /* + For PNG filter method 0 + this function unfilters a single image (e.g. without interlacing this is called once, with Adam7 seven times) + out must have enough bytes allocated already, in must have the scanlines + 1 filtertype byte per scanline + w and h are image dimensions or dimensions of reduced image, bpp is bits per pixel + in and out are allowed to be the same memory address (but aren't the same size since in has the extra filter bytes) + */ + + unsigned y; + unsigned char* prevline = 0; + + /*bytewidth is used for filtering, is 1 when bpp < 8, number of bytes per pixel otherwise*/ + size_t bytewidth = (bpp + 7) / 8; + size_t linebytes = (w * bpp + 7) / 8; + + for(y = 0; y < h; y++) + { + size_t outindex = linebytes * y; + size_t inindex = (1 + linebytes) * y; /*the extra filterbyte added to each row*/ + unsigned char filterType = in[inindex]; + + CERROR_TRY_RETURN(unfilterScanline(&out[outindex], &in[inindex + 1], prevline, bytewidth, filterType, linebytes)); + + prevline = &out[outindex]; + } + + return 0; +} + +/* +in: Adam7 interlaced image, with no padding bits between scanlines, but between + reduced images so that each reduced image starts at a byte. +out: the same pixels, but re-ordered so that they're now a non-interlaced image with size w*h +bpp: bits per pixel +out has the following size in bits: w * h * bpp. +in is possibly bigger due to padding bits between reduced images. +out must be big enough AND must be 0 everywhere if bpp < 8 in the current implementation +(because that's likely a little bit faster) +NOTE: comments about padding bits are only relevant if bpp < 8 +*/ +static void Adam7_deinterlace(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, unsigned bpp) +{ + unsigned passw[7], passh[7]; + size_t filter_passstart[8], padded_passstart[8], passstart[8]; + unsigned i; + + Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); + + if(bpp >= 8) + { + for(i = 0; i < 7; i++) + { + unsigned x, y, b; + size_t bytewidth = bpp / 8; + for(y = 0; y < passh[i]; y++) + for(x = 0; x < passw[i]; x++) + { + size_t pixelinstart = passstart[i] + (y * passw[i] + x) * bytewidth; + size_t pixeloutstart = ((ADAM7_IY[i] + y * ADAM7_DY[i]) * w + ADAM7_IX[i] + x * ADAM7_DX[i]) * bytewidth; + for(b = 0; b < bytewidth; b++) + { + out[pixeloutstart + b] = in[pixelinstart + b]; + } + } + } + } + else /*bpp < 8: Adam7 with pixels < 8 bit is a bit trickier: with bit pointers*/ + { + for(i = 0; i < 7; i++) + { + unsigned x, y, b; + unsigned ilinebits = bpp * passw[i]; + unsigned olinebits = bpp * w; + size_t obp, ibp; /*bit pointers (for out and in buffer)*/ + for(y = 0; y < passh[i]; y++) + for(x = 0; x < passw[i]; x++) + { + ibp = (8 * passstart[i]) + (y * ilinebits + x * bpp); + obp = (ADAM7_IY[i] + y * ADAM7_DY[i]) * olinebits + (ADAM7_IX[i] + x * ADAM7_DX[i]) * bpp; + for(b = 0; b < bpp; b++) + { + unsigned char bit = readBitFromReversedStream(&ibp, in); + /*note that this function assumes the out buffer is completely 0, use setBitOfReversedStream otherwise*/ + setBitOfReversedStream0(&obp, out, bit); + } + } + } + } +} + +static void removePaddingBits(unsigned char* out, const unsigned char* in, + size_t olinebits, size_t ilinebits, unsigned h) +{ + /* + After filtering there are still padding bits if scanlines have non multiple of 8 bit amounts. They need + to be removed (except at last scanline of (Adam7-reduced) image) before working with pure image buffers + for the Adam7 code, the color convert code and the output to the user. + in and out are allowed to be the same buffer, in may also be higher but still overlapping; in must + have >= ilinebits*h bits, out must have >= olinebits*h bits, olinebits must be <= ilinebits + also used to move bits after earlier such operations happened, e.g. in a sequence of reduced images from Adam7 + only useful if (ilinebits - olinebits) is a value in the range 1..7 + */ + unsigned y; + size_t diff = ilinebits - olinebits; + size_t ibp = 0, obp = 0; /*input and output bit pointers*/ + for(y = 0; y < h; y++) + { + size_t x; + for(x = 0; x < olinebits; x++) + { + unsigned char bit = readBitFromReversedStream(&ibp, in); + setBitOfReversedStream(&obp, out, bit); + } + ibp += diff; + } +} + +/*out must be buffer big enough to contain full image, and in must contain the full decompressed data from +the IDAT chunks (with filter index bytes and possible padding bits) +return value is error*/ +static unsigned postProcessScanlines(unsigned char* out, unsigned char* in, + unsigned w, unsigned h, const LodePNGInfo* info_png) +{ + /* + This function converts the filtered-padded-interlaced data into pure 2D image buffer with the PNG's colortype. + Steps: + *) if no Adam7: 1) unfilter 2) remove padding bits (= posible extra bits per scanline if bpp < 8) + *) if adam7: 1) 7x unfilter 2) 7x remove padding bits 3) Adam7_deinterlace + NOTE: the in buffer will be overwritten with intermediate data! + */ + unsigned bpp = lodepng_get_bpp(&info_png->color); + if(bpp == 0) return 31; /*error: invalid colortype*/ + + if(info_png->interlace_method == 0) + { + if(bpp < 8 && w * bpp != ((w * bpp + 7) / 8) * 8) + { + CERROR_TRY_RETURN(unfilter(in, in, w, h, bpp)); + removePaddingBits(out, in, w * bpp, ((w * bpp + 7) / 8) * 8, h); + } + /*we can immediatly filter into the out buffer, no other steps needed*/ + else CERROR_TRY_RETURN(unfilter(out, in, w, h, bpp)); + } + else /*interlace_method is 1 (Adam7)*/ + { + unsigned passw[7], passh[7]; size_t filter_passstart[8], padded_passstart[8], passstart[8]; + unsigned i; + + Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); + + for(i = 0; i < 7; i++) + { + CERROR_TRY_RETURN(unfilter(&in[padded_passstart[i]], &in[filter_passstart[i]], passw[i], passh[i], bpp)); + /*TODO: possible efficiency improvement: if in this reduced image the bits fit nicely in 1 scanline, + move bytes instead of bits or move not at all*/ + if(bpp < 8) + { + /*remove padding bits in scanlines; after this there still may be padding + bits between the different reduced images: each reduced image still starts nicely at a byte*/ + removePaddingBits(&in[passstart[i]], &in[padded_passstart[i]], passw[i] * bpp, + ((passw[i] * bpp + 7) / 8) * 8, passh[i]); + } + } + + Adam7_deinterlace(out, in, w, h, bpp); + } + + return 0; +} + +static unsigned readChunk_PLTE(LodePNGColorMode* color, const unsigned char* data, size_t chunkLength) +{ + unsigned pos = 0, i; + if(color->palette) lodepng_free(color->palette); + color->palettesize = chunkLength / 3; + color->palette = (unsigned char*)lodepng_malloc(4 * color->palettesize); + if(!color->palette && color->palettesize) + { + color->palettesize = 0; + return 83; /*alloc fail*/ + } + if(color->palettesize > 256) return 38; /*error: palette too big*/ + + for(i = 0; i < color->palettesize; i++) + { + color->palette[4 * i + 0] = data[pos++]; /*R*/ + color->palette[4 * i + 1] = data[pos++]; /*G*/ + color->palette[4 * i + 2] = data[pos++]; /*B*/ + color->palette[4 * i + 3] = 255; /*alpha*/ + } + + return 0; /* OK */ +} + +static unsigned readChunk_tRNS(LodePNGColorMode* color, const unsigned char* data, size_t chunkLength) +{ + unsigned i; + if(color->colortype == LCT_PALETTE) + { + /*error: more alpha values given than there are palette entries*/ + if(chunkLength > color->palettesize) return 38; + + for(i = 0; i < chunkLength; i++) color->palette[4 * i + 3] = data[i]; + } + else if(color->colortype == LCT_GREY) + { + /*error: this chunk must be 2 bytes for greyscale image*/ + if(chunkLength != 2) return 30; + + color->key_defined = 1; + color->key_r = color->key_g = color->key_b = 256u * data[0] + data[1]; + } + else if(color->colortype == LCT_RGB) + { + /*error: this chunk must be 6 bytes for RGB image*/ + if(chunkLength != 6) return 41; + + color->key_defined = 1; + color->key_r = 256u * data[0] + data[1]; + color->key_g = 256u * data[2] + data[3]; + color->key_b = 256u * data[4] + data[5]; + } + else return 42; /*error: tRNS chunk not allowed for other color models*/ + + return 0; /* OK */ +} + + +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS +/*background color chunk (bKGD)*/ +static unsigned readChunk_bKGD(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) +{ + if(info->color.colortype == LCT_PALETTE) + { + /*error: this chunk must be 1 byte for indexed color image*/ + if(chunkLength != 1) return 43; + + info->background_defined = 1; + info->background_r = info->background_g = info->background_b = data[0]; + } + else if(info->color.colortype == LCT_GREY || info->color.colortype == LCT_GREY_ALPHA) + { + /*error: this chunk must be 2 bytes for greyscale image*/ + if(chunkLength != 2) return 44; + + info->background_defined = 1; + info->background_r = info->background_g = info->background_b = 256u * data[0] + data[1]; + } + else if(info->color.colortype == LCT_RGB || info->color.colortype == LCT_RGBA) + { + /*error: this chunk must be 6 bytes for greyscale image*/ + if(chunkLength != 6) return 45; + + info->background_defined = 1; + info->background_r = 256u * data[0] + data[1]; + info->background_g = 256u * data[2] + data[3]; + info->background_b = 256u * data[4] + data[5]; + } + + return 0; /* OK */ +} + +/*text chunk (tEXt)*/ +static unsigned readChunk_tEXt(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) +{ + unsigned error = 0; + char *key = 0, *str = 0; + unsigned i; + + while(!error) /*not really a while loop, only used to break on error*/ + { + unsigned length, string2_begin; + + length = 0; + while(length < chunkLength && data[length] != 0) length++; + /*even though it's not allowed by the standard, no error is thrown if + there's no null termination char, if the text is empty*/ + if(length < 1 || length > 79) CERROR_BREAK(error, 89); /*keyword too short or long*/ + + key = (char*)lodepng_malloc(length + 1); + if(!key) CERROR_BREAK(error, 83); /*alloc fail*/ + + key[length] = 0; + for(i = 0; i < length; i++) key[i] = (char)data[i]; + + string2_begin = length + 1; /*skip keyword null terminator*/ + + length = chunkLength < string2_begin ? 0 : chunkLength - string2_begin; + str = (char*)lodepng_malloc(length + 1); + if(!str) CERROR_BREAK(error, 83); /*alloc fail*/ + + str[length] = 0; + for(i = 0; i < length; i++) str[i] = (char)data[string2_begin + i]; + + error = lodepng_add_text(info, key, str); + + break; + } + + lodepng_free(key); + lodepng_free(str); + + return error; +} + +/*compressed text chunk (zTXt)*/ +static unsigned readChunk_zTXt(LodePNGInfo* info, const LodePNGDecompressSettings* zlibsettings, + const unsigned char* data, size_t chunkLength) +{ + unsigned error = 0; + unsigned i; + + unsigned length, string2_begin; + char *key = 0; + ucvector decoded; + + ucvector_init(&decoded); + + while(!error) /*not really a while loop, only used to break on error*/ + { + for(length = 0; length < chunkLength && data[length] != 0; length++) ; + if(length + 2 >= chunkLength) CERROR_BREAK(error, 75); /*no null termination, corrupt?*/ + if(length < 1 || length > 79) CERROR_BREAK(error, 89); /*keyword too short or long*/ + + key = (char*)lodepng_malloc(length + 1); + if(!key) CERROR_BREAK(error, 83); /*alloc fail*/ + + key[length] = 0; + for(i = 0; i < length; i++) key[i] = (char)data[i]; + + if(data[length + 1] != 0) CERROR_BREAK(error, 72); /*the 0 byte indicating compression must be 0*/ + + string2_begin = length + 2; + if(string2_begin > chunkLength) CERROR_BREAK(error, 75); /*no null termination, corrupt?*/ + + length = chunkLength - string2_begin; + /*will fail if zlib error, e.g. if length is too small*/ + error = zlib_decompress(&decoded.data, &decoded.size, + (unsigned char*)(&data[string2_begin]), + length, zlibsettings); + if(error) break; + ucvector_push_back(&decoded, 0); + + error = lodepng_add_text(info, key, (char*)decoded.data); + + break; + } + + lodepng_free(key); + ucvector_cleanup(&decoded); + + return error; +} + +/*international text chunk (iTXt)*/ +static unsigned readChunk_iTXt(LodePNGInfo* info, const LodePNGDecompressSettings* zlibsettings, + const unsigned char* data, size_t chunkLength) +{ + unsigned error = 0; + unsigned i; + + unsigned length, begin, compressed; + char *key = 0, *langtag = 0, *transkey = 0; + ucvector decoded; + ucvector_init(&decoded); + + while(!error) /*not really a while loop, only used to break on error*/ + { + /*Quick check if the chunk length isn't too small. Even without check + it'd still fail with other error checks below if it's too short. This just gives a different error code.*/ + if(chunkLength < 5) CERROR_BREAK(error, 30); /*iTXt chunk too short*/ + + /*read the key*/ + for(length = 0; length < chunkLength && data[length] != 0; length++) ; + if(length + 3 >= chunkLength) CERROR_BREAK(error, 75); /*no null termination char, corrupt?*/ + if(length < 1 || length > 79) CERROR_BREAK(error, 89); /*keyword too short or long*/ + + key = (char*)lodepng_malloc(length + 1); + if(!key) CERROR_BREAK(error, 83); /*alloc fail*/ + + key[length] = 0; + for(i = 0; i < length; i++) key[i] = (char)data[i]; + + /*read the compression method*/ + compressed = data[length + 1]; + if(data[length + 2] != 0) CERROR_BREAK(error, 72); /*the 0 byte indicating compression must be 0*/ + + /*even though it's not allowed by the standard, no error is thrown if + there's no null termination char, if the text is empty for the next 3 texts*/ + + /*read the langtag*/ + begin = length + 3; + length = 0; + for(i = begin; i < chunkLength && data[i] != 0; i++) length++; + + langtag = (char*)lodepng_malloc(length + 1); + if(!langtag) CERROR_BREAK(error, 83); /*alloc fail*/ + + langtag[length] = 0; + for(i = 0; i < length; i++) langtag[i] = (char)data[begin + i]; + + /*read the transkey*/ + begin += length + 1; + length = 0; + for(i = begin; i < chunkLength && data[i] != 0; i++) length++; + + transkey = (char*)lodepng_malloc(length + 1); + if(!transkey) CERROR_BREAK(error, 83); /*alloc fail*/ + + transkey[length] = 0; + for(i = 0; i < length; i++) transkey[i] = (char)data[begin + i]; + + /*read the actual text*/ + begin += length + 1; + + length = chunkLength < begin ? 0 : chunkLength - begin; + + if(compressed) + { + /*will fail if zlib error, e.g. if length is too small*/ + error = zlib_decompress(&decoded.data, &decoded.size, + (unsigned char*)(&data[begin]), + length, zlibsettings); + if(error) break; + if(decoded.allocsize < decoded.size) decoded.allocsize = decoded.size; + ucvector_push_back(&decoded, 0); + } + else + { + if(!ucvector_resize(&decoded, length + 1)) CERROR_BREAK(error, 83 /*alloc fail*/); + + decoded.data[length] = 0; + for(i = 0; i < length; i++) decoded.data[i] = data[begin + i]; + } + + error = lodepng_add_itext(info, key, langtag, transkey, (char*)decoded.data); + + break; + } + + lodepng_free(key); + lodepng_free(langtag); + lodepng_free(transkey); + ucvector_cleanup(&decoded); + + return error; +} + +static unsigned readChunk_tIME(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) +{ + if(chunkLength != 7) return 73; /*invalid tIME chunk size*/ + + info->time_defined = 1; + info->time.year = 256u * data[0] + data[1]; + info->time.month = data[2]; + info->time.day = data[3]; + info->time.hour = data[4]; + info->time.minute = data[5]; + info->time.second = data[6]; + + return 0; /* OK */ +} + +static unsigned readChunk_pHYs(LodePNGInfo* info, const unsigned char* data, size_t chunkLength) +{ + if(chunkLength != 9) return 74; /*invalid pHYs chunk size*/ + + info->phys_defined = 1; + info->phys_x = 16777216u * data[0] + 65536u * data[1] + 256u * data[2] + data[3]; + info->phys_y = 16777216u * data[4] + 65536u * data[5] + 256u * data[6] + data[7]; + info->phys_unit = data[8]; + + return 0; /* OK */ +} +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + +/*read a PNG, the result will be in the same color type as the PNG (hence "generic")*/ +static void decodeGeneric(unsigned char** out, unsigned* w, unsigned* h, + LodePNGState* state, + const unsigned char* in, size_t insize) +{ + unsigned char IEND = 0; + const unsigned char* chunk; + size_t i; + ucvector idat; /*the data from idat chunks*/ + ucvector scanlines; + size_t predict; + + /*for unknown chunk order*/ + unsigned unknown = 0; +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + unsigned critical_pos = 1; /*1 = after IHDR, 2 = after PLTE, 3 = after IDAT*/ +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + + /*provide some proper output values if error will happen*/ + *out = 0; + + state->error = lodepng_inspect(w, h, state, in, insize); /*reads header and resets other parameters in state->info_png*/ + if(state->error) return; + + ucvector_init(&idat); + chunk = &in[33]; /*first byte of the first chunk after the header*/ + + /*loop through the chunks, ignoring unknown chunks and stopping at IEND chunk. + IDAT data is put at the start of the in buffer*/ + while(!IEND && !state->error) + { + unsigned chunkLength; + const unsigned char* data; /*the data in the chunk*/ + + /*error: size of the in buffer too small to contain next chunk*/ + if((size_t)((chunk - in) + 12) > insize || chunk < in) CERROR_BREAK(state->error, 30); + + /*length of the data of the chunk, excluding the length bytes, chunk type and CRC bytes*/ + chunkLength = lodepng_chunk_length(chunk); + /*error: chunk length larger than the max PNG chunk size*/ + if(chunkLength > 2147483647) CERROR_BREAK(state->error, 63); + + if((size_t)((chunk - in) + chunkLength + 12) > insize || (chunk + chunkLength + 12) < in) + { + CERROR_BREAK(state->error, 64); /*error: size of the in buffer too small to contain next chunk*/ + } + + data = lodepng_chunk_data_const(chunk); + + /*IDAT chunk, containing compressed image data*/ + if(lodepng_chunk_type_equals(chunk, "IDAT")) + { + size_t oldsize = idat.size; + if(!ucvector_resize(&idat, oldsize + chunkLength)) CERROR_BREAK(state->error, 83 /*alloc fail*/); + for(i = 0; i < chunkLength; i++) idat.data[oldsize + i] = data[i]; +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + critical_pos = 3; +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + } + /*IEND chunk*/ + else if(lodepng_chunk_type_equals(chunk, "IEND")) + { + IEND = 1; + } + /*palette chunk (PLTE)*/ + else if(lodepng_chunk_type_equals(chunk, "PLTE")) + { + state->error = readChunk_PLTE(&state->info_png.color, data, chunkLength); + if(state->error) break; +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + critical_pos = 2; +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + } + /*palette transparency chunk (tRNS)*/ + else if(lodepng_chunk_type_equals(chunk, "tRNS")) + { + state->error = readChunk_tRNS(&state->info_png.color, data, chunkLength); + if(state->error) break; + } +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + /*background color chunk (bKGD)*/ + else if(lodepng_chunk_type_equals(chunk, "bKGD")) + { + state->error = readChunk_bKGD(&state->info_png, data, chunkLength); + if(state->error) break; + } + /*text chunk (tEXt)*/ + else if(lodepng_chunk_type_equals(chunk, "tEXt")) + { + if(state->decoder.read_text_chunks) + { + state->error = readChunk_tEXt(&state->info_png, data, chunkLength); + if(state->error) break; + } + } + /*compressed text chunk (zTXt)*/ + else if(lodepng_chunk_type_equals(chunk, "zTXt")) + { + if(state->decoder.read_text_chunks) + { + state->error = readChunk_zTXt(&state->info_png, &state->decoder.zlibsettings, data, chunkLength); + if(state->error) break; + } + } + /*international text chunk (iTXt)*/ + else if(lodepng_chunk_type_equals(chunk, "iTXt")) + { + if(state->decoder.read_text_chunks) + { + state->error = readChunk_iTXt(&state->info_png, &state->decoder.zlibsettings, data, chunkLength); + if(state->error) break; + } + } + else if(lodepng_chunk_type_equals(chunk, "tIME")) + { + state->error = readChunk_tIME(&state->info_png, data, chunkLength); + if(state->error) break; + } + else if(lodepng_chunk_type_equals(chunk, "pHYs")) + { + state->error = readChunk_pHYs(&state->info_png, data, chunkLength); + if(state->error) break; + } +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + else /*it's not an implemented chunk type, so ignore it: skip over the data*/ + { + /*error: unknown critical chunk (5th bit of first byte of chunk type is 0)*/ + if(!lodepng_chunk_ancillary(chunk)) CERROR_BREAK(state->error, 69); + + unknown = 1; +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + if(state->decoder.remember_unknown_chunks) + { + state->error = lodepng_chunk_append(&state->info_png.unknown_chunks_data[critical_pos - 1], + &state->info_png.unknown_chunks_size[critical_pos - 1], chunk); + if(state->error) break; + } +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + } + + if(!state->decoder.ignore_crc && !unknown) /*check CRC if wanted, only on known chunk types*/ + { + if(lodepng_chunk_check_crc(chunk)) CERROR_BREAK(state->error, 57); /*invalid CRC*/ + } + + if(!IEND) chunk = lodepng_chunk_next_const(chunk); + } + + ucvector_init(&scanlines); + /*predict output size, to allocate exact size for output buffer to avoid more dynamic allocation. + The prediction is currently not correct for interlaced PNG images.*/ + predict = lodepng_get_raw_size_idat(*w, *h, &state->info_png.color) + *h; + if(!state->error && !ucvector_reserve(&scanlines, predict)) state->error = 83; /*alloc fail*/ + if(!state->error) + { + state->error = zlib_decompress(&scanlines.data, &scanlines.size, idat.data, + idat.size, &state->decoder.zlibsettings); + } + ucvector_cleanup(&idat); + + if(!state->error) + { + ucvector outv; + ucvector_init(&outv); + if(!ucvector_resizev(&outv, + lodepng_get_raw_size(*w, *h, &state->info_png.color), 0)) state->error = 83; /*alloc fail*/ + if(!state->error) state->error = postProcessScanlines(outv.data, scanlines.data, *w, *h, &state->info_png); + *out = outv.data; + } + ucvector_cleanup(&scanlines); +} + +unsigned lodepng_decode(unsigned char** out, unsigned* w, unsigned* h, + LodePNGState* state, + const unsigned char* in, size_t insize) +{ + *out = 0; + decodeGeneric(out, w, h, state, in, insize); + if(state->error) return state->error; + if(!state->decoder.color_convert || lodepng_color_mode_equal(&state->info_raw, &state->info_png.color)) + { + /*same color type, no copying or converting of data needed*/ + /*store the info_png color settings on the info_raw so that the info_raw still reflects what colortype + the raw image has to the end user*/ + if(!state->decoder.color_convert) + { + state->error = lodepng_color_mode_copy(&state->info_raw, &state->info_png.color); + if(state->error) return state->error; + } + } + else + { + /*color conversion needed; sort of copy of the data*/ + unsigned char* data = *out; + size_t outsize; + + /*TODO: check if this works according to the statement in the documentation: "The converter can convert + from greyscale input color type, to 8-bit greyscale or greyscale with alpha"*/ + if(!(state->info_raw.colortype == LCT_RGB || state->info_raw.colortype == LCT_RGBA) + && !(state->info_raw.bitdepth == 8)) + { + return 56; /*unsupported color mode conversion*/ + } + + outsize = lodepng_get_raw_size(*w, *h, &state->info_raw); + *out = (unsigned char*)lodepng_malloc(outsize); + if(!(*out)) + { + state->error = 83; /*alloc fail*/ + } + else state->error = lodepng_convert(*out, data, &state->info_raw, + &state->info_png.color, *w, *h); + lodepng_free(data); + } + return state->error; +} + +unsigned lodepng_decode_memory(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, + size_t insize, LodePNGColorType colortype, unsigned bitdepth) +{ + unsigned error; + LodePNGState state; + lodepng_state_init(&state); + state.info_raw.colortype = colortype; + state.info_raw.bitdepth = bitdepth; + error = lodepng_decode(out, w, h, &state, in, insize); + lodepng_state_cleanup(&state); + return error; +} + +unsigned lodepng_decode32(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize) +{ + return lodepng_decode_memory(out, w, h, in, insize, LCT_RGBA, 8); +} + +unsigned lodepng_decode24(unsigned char** out, unsigned* w, unsigned* h, const unsigned char* in, size_t insize) +{ + return lodepng_decode_memory(out, w, h, in, insize, LCT_RGB, 8); +} + +#ifdef LODEPNG_COMPILE_DISK +unsigned lodepng_decode_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename, + LodePNGColorType colortype, unsigned bitdepth) +{ + unsigned char* buffer; + size_t buffersize; + unsigned error; + error = lodepng_load_file(&buffer, &buffersize, filename); + if(!error) error = lodepng_decode_memory(out, w, h, buffer, buffersize, colortype, bitdepth); + lodepng_free(buffer); + return error; +} + +unsigned lodepng_decode32_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename) +{ + return lodepng_decode_file(out, w, h, filename, LCT_RGBA, 8); +} + +unsigned lodepng_decode24_file(unsigned char** out, unsigned* w, unsigned* h, const char* filename) +{ + return lodepng_decode_file(out, w, h, filename, LCT_RGB, 8); +} +#endif /*LODEPNG_COMPILE_DISK*/ + +void lodepng_decoder_settings_init(LodePNGDecoderSettings* settings) +{ + settings->color_convert = 1; +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + settings->read_text_chunks = 1; + settings->remember_unknown_chunks = 0; +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + settings->ignore_crc = 0; + lodepng_decompress_settings_init(&settings->zlibsettings); +} + +#endif /*LODEPNG_COMPILE_DECODER*/ + +#if defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) + +void lodepng_state_init(LodePNGState* state) +{ +#ifdef LODEPNG_COMPILE_DECODER + lodepng_decoder_settings_init(&state->decoder); +#endif /*LODEPNG_COMPILE_DECODER*/ +#ifdef LODEPNG_COMPILE_ENCODER + lodepng_encoder_settings_init(&state->encoder); +#endif /*LODEPNG_COMPILE_ENCODER*/ + lodepng_color_mode_init(&state->info_raw); + lodepng_info_init(&state->info_png); + state->error = 1; +} + +void lodepng_state_cleanup(LodePNGState* state) +{ + lodepng_color_mode_cleanup(&state->info_raw); + lodepng_info_cleanup(&state->info_png); +} + +void lodepng_state_copy(LodePNGState* dest, const LodePNGState* source) +{ + lodepng_state_cleanup(dest); + *dest = *source; + lodepng_color_mode_init(&dest->info_raw); + lodepng_info_init(&dest->info_png); + dest->error = lodepng_color_mode_copy(&dest->info_raw, &source->info_raw); if(dest->error) return; + dest->error = lodepng_info_copy(&dest->info_png, &source->info_png); if(dest->error) return; +} + +#endif /* defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) */ + +#ifdef LODEPNG_COMPILE_ENCODER + +/* ////////////////////////////////////////////////////////////////////////// */ +/* / PNG Encoder / */ +/* ////////////////////////////////////////////////////////////////////////// */ + +/*chunkName must be string of 4 characters*/ +static unsigned addChunk(ucvector* out, const char* chunkName, const unsigned char* data, size_t length) +{ + CERROR_TRY_RETURN(lodepng_chunk_create(&out->data, &out->size, (unsigned)length, chunkName, data)); + out->allocsize = out->size; /*fix the allocsize again*/ + return 0; +} + +static void writeSignature(ucvector* out) +{ + /*8 bytes PNG signature, aka the magic bytes*/ + ucvector_push_back(out, 137); + ucvector_push_back(out, 80); + ucvector_push_back(out, 78); + ucvector_push_back(out, 71); + ucvector_push_back(out, 13); + ucvector_push_back(out, 10); + ucvector_push_back(out, 26); + ucvector_push_back(out, 10); +} + +static unsigned addChunk_IHDR(ucvector* out, unsigned w, unsigned h, + LodePNGColorType colortype, unsigned bitdepth, unsigned interlace_method) +{ + unsigned error = 0; + ucvector header; + ucvector_init(&header); + + lodepng_add32bitInt(&header, w); /*width*/ + lodepng_add32bitInt(&header, h); /*height*/ + ucvector_push_back(&header, (unsigned char)bitdepth); /*bit depth*/ + ucvector_push_back(&header, (unsigned char)colortype); /*color type*/ + ucvector_push_back(&header, 0); /*compression method*/ + ucvector_push_back(&header, 0); /*filter method*/ + ucvector_push_back(&header, interlace_method); /*interlace method*/ + + error = addChunk(out, "IHDR", header.data, header.size); + ucvector_cleanup(&header); + + return error; +} + +static unsigned addChunk_PLTE(ucvector* out, const LodePNGColorMode* info) +{ + unsigned error = 0; + size_t i; + ucvector PLTE; + ucvector_init(&PLTE); + for(i = 0; i < info->palettesize * 4; i++) + { + /*add all channels except alpha channel*/ + if(i % 4 != 3) ucvector_push_back(&PLTE, info->palette[i]); + } + error = addChunk(out, "PLTE", PLTE.data, PLTE.size); + ucvector_cleanup(&PLTE); + + return error; +} + +static unsigned addChunk_tRNS(ucvector* out, const LodePNGColorMode* info) +{ + unsigned error = 0; + size_t i; + ucvector tRNS; + ucvector_init(&tRNS); + if(info->colortype == LCT_PALETTE) + { + size_t amount = info->palettesize; + /*the tail of palette values that all have 255 as alpha, does not have to be encoded*/ + for(i = info->palettesize; i > 0; i--) + { + if(info->palette[4 * (i - 1) + 3] == 255) amount--; + else break; + } + /*add only alpha channel*/ + for(i = 0; i < amount; i++) ucvector_push_back(&tRNS, info->palette[4 * i + 3]); + } + else if(info->colortype == LCT_GREY) + { + if(info->key_defined) + { + ucvector_push_back(&tRNS, (unsigned char)(info->key_r / 256)); + ucvector_push_back(&tRNS, (unsigned char)(info->key_r % 256)); + } + } + else if(info->colortype == LCT_RGB) + { + if(info->key_defined) + { + ucvector_push_back(&tRNS, (unsigned char)(info->key_r / 256)); + ucvector_push_back(&tRNS, (unsigned char)(info->key_r % 256)); + ucvector_push_back(&tRNS, (unsigned char)(info->key_g / 256)); + ucvector_push_back(&tRNS, (unsigned char)(info->key_g % 256)); + ucvector_push_back(&tRNS, (unsigned char)(info->key_b / 256)); + ucvector_push_back(&tRNS, (unsigned char)(info->key_b % 256)); + } + } + + error = addChunk(out, "tRNS", tRNS.data, tRNS.size); + ucvector_cleanup(&tRNS); + + return error; +} + +static unsigned addChunk_IDAT(ucvector* out, const unsigned char* data, size_t datasize, + LodePNGCompressSettings* zlibsettings) +{ + ucvector zlibdata; + unsigned error = 0; + + /*compress with the Zlib compressor*/ + ucvector_init(&zlibdata); + error = zlib_compress(&zlibdata.data, &zlibdata.size, data, datasize, zlibsettings); + if(!error) error = addChunk(out, "IDAT", zlibdata.data, zlibdata.size); + ucvector_cleanup(&zlibdata); + + return error; +} + +static unsigned addChunk_IEND(ucvector* out) +{ + unsigned error = 0; + error = addChunk(out, "IEND", 0, 0); + return error; +} + +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + +static unsigned addChunk_tEXt(ucvector* out, const char* keyword, const char* textstring) +{ + unsigned error = 0; + size_t i; + ucvector text; + ucvector_init(&text); + for(i = 0; keyword[i] != 0; i++) ucvector_push_back(&text, (unsigned char)keyword[i]); + if(i < 1 || i > 79) return 89; /*error: invalid keyword size*/ + ucvector_push_back(&text, 0); /*0 termination char*/ + for(i = 0; textstring[i] != 0; i++) ucvector_push_back(&text, (unsigned char)textstring[i]); + error = addChunk(out, "tEXt", text.data, text.size); + ucvector_cleanup(&text); + + return error; +} + +static unsigned addChunk_zTXt(ucvector* out, const char* keyword, const char* textstring, + LodePNGCompressSettings* zlibsettings) +{ + unsigned error = 0; + ucvector data, compressed; + size_t i, textsize = strlen(textstring); + + ucvector_init(&data); + ucvector_init(&compressed); + for(i = 0; keyword[i] != 0; i++) ucvector_push_back(&data, (unsigned char)keyword[i]); + if(i < 1 || i > 79) return 89; /*error: invalid keyword size*/ + ucvector_push_back(&data, 0); /*0 termination char*/ + ucvector_push_back(&data, 0); /*compression method: 0*/ + + error = zlib_compress(&compressed.data, &compressed.size, + (unsigned char*)textstring, textsize, zlibsettings); + if(!error) + { + for(i = 0; i < compressed.size; i++) ucvector_push_back(&data, compressed.data[i]); + error = addChunk(out, "zTXt", data.data, data.size); + } + + ucvector_cleanup(&compressed); + ucvector_cleanup(&data); + return error; +} + +static unsigned addChunk_iTXt(ucvector* out, unsigned compressed, const char* keyword, const char* langtag, + const char* transkey, const char* textstring, LodePNGCompressSettings* zlibsettings) +{ + unsigned error = 0; + ucvector data; + size_t i, textsize = strlen(textstring); + + ucvector_init(&data); + + for(i = 0; keyword[i] != 0; i++) ucvector_push_back(&data, (unsigned char)keyword[i]); + if(i < 1 || i > 79) return 89; /*error: invalid keyword size*/ + ucvector_push_back(&data, 0); /*null termination char*/ + ucvector_push_back(&data, compressed ? 1 : 0); /*compression flag*/ + ucvector_push_back(&data, 0); /*compression method*/ + for(i = 0; langtag[i] != 0; i++) ucvector_push_back(&data, (unsigned char)langtag[i]); + ucvector_push_back(&data, 0); /*null termination char*/ + for(i = 0; transkey[i] != 0; i++) ucvector_push_back(&data, (unsigned char)transkey[i]); + ucvector_push_back(&data, 0); /*null termination char*/ + + if(compressed) + { + ucvector compressed_data; + ucvector_init(&compressed_data); + error = zlib_compress(&compressed_data.data, &compressed_data.size, + (unsigned char*)textstring, textsize, zlibsettings); + if(!error) + { + for(i = 0; i < compressed_data.size; i++) ucvector_push_back(&data, compressed_data.data[i]); + } + ucvector_cleanup(&compressed_data); + } + else /*not compressed*/ + { + for(i = 0; textstring[i] != 0; i++) ucvector_push_back(&data, (unsigned char)textstring[i]); + } + + if(!error) error = addChunk(out, "iTXt", data.data, data.size); + ucvector_cleanup(&data); + return error; +} + +static unsigned addChunk_bKGD(ucvector* out, const LodePNGInfo* info) +{ + unsigned error = 0; + ucvector bKGD; + ucvector_init(&bKGD); + if(info->color.colortype == LCT_GREY || info->color.colortype == LCT_GREY_ALPHA) + { + ucvector_push_back(&bKGD, (unsigned char)(info->background_r / 256)); + ucvector_push_back(&bKGD, (unsigned char)(info->background_r % 256)); + } + else if(info->color.colortype == LCT_RGB || info->color.colortype == LCT_RGBA) + { + ucvector_push_back(&bKGD, (unsigned char)(info->background_r / 256)); + ucvector_push_back(&bKGD, (unsigned char)(info->background_r % 256)); + ucvector_push_back(&bKGD, (unsigned char)(info->background_g / 256)); + ucvector_push_back(&bKGD, (unsigned char)(info->background_g % 256)); + ucvector_push_back(&bKGD, (unsigned char)(info->background_b / 256)); + ucvector_push_back(&bKGD, (unsigned char)(info->background_b % 256)); + } + else if(info->color.colortype == LCT_PALETTE) + { + ucvector_push_back(&bKGD, (unsigned char)(info->background_r % 256)); /*palette index*/ + } + + error = addChunk(out, "bKGD", bKGD.data, bKGD.size); + ucvector_cleanup(&bKGD); + + return error; +} + +static unsigned addChunk_tIME(ucvector* out, const LodePNGTime* time) +{ + unsigned error = 0; + unsigned char* data = (unsigned char*)lodepng_malloc(7); + if(!data) return 83; /*alloc fail*/ + data[0] = (unsigned char)(time->year / 256); + data[1] = (unsigned char)(time->year % 256); + data[2] = (unsigned char)time->month; + data[3] = (unsigned char)time->day; + data[4] = (unsigned char)time->hour; + data[5] = (unsigned char)time->minute; + data[6] = (unsigned char)time->second; + error = addChunk(out, "tIME", data, 7); + lodepng_free(data); + return error; +} + +static unsigned addChunk_pHYs(ucvector* out, const LodePNGInfo* info) +{ + unsigned error = 0; + ucvector data; + ucvector_init(&data); + + lodepng_add32bitInt(&data, info->phys_x); + lodepng_add32bitInt(&data, info->phys_y); + ucvector_push_back(&data, info->phys_unit); + + error = addChunk(out, "pHYs", data.data, data.size); + ucvector_cleanup(&data); + + return error; +} + +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + +static void filterScanline(unsigned char* out, const unsigned char* scanline, const unsigned char* prevline, + size_t length, size_t bytewidth, unsigned char filterType) +{ + size_t i; + switch(filterType) + { + case 0: /*None*/ + for(i = 0; i < length; i++) out[i] = scanline[i]; + break; + case 1: /*Sub*/ + if(prevline) + { + for(i = 0; i < bytewidth; i++) out[i] = scanline[i]; + for(i = bytewidth; i < length; i++) out[i] = scanline[i] - scanline[i - bytewidth]; + } + else + { + for(i = 0; i < bytewidth; i++) out[i] = scanline[i]; + for(i = bytewidth; i < length; i++) out[i] = scanline[i] - scanline[i - bytewidth]; + } + break; + case 2: /*Up*/ + if(prevline) + { + for(i = 0; i < length; i++) out[i] = scanline[i] - prevline[i]; + } + else + { + for(i = 0; i < length; i++) out[i] = scanline[i]; + } + break; + case 3: /*Average*/ + if(prevline) + { + for(i = 0; i < bytewidth; i++) out[i] = scanline[i] - prevline[i] / 2; + for(i = bytewidth; i < length; i++) out[i] = scanline[i] - ((scanline[i - bytewidth] + prevline[i]) / 2); + } + else + { + for(i = 0; i < bytewidth; i++) out[i] = scanline[i]; + for(i = bytewidth; i < length; i++) out[i] = scanline[i] - scanline[i - bytewidth] / 2; + } + break; + case 4: /*Paeth*/ + if(prevline) + { + /*paethPredictor(0, prevline[i], 0) is always prevline[i]*/ + for(i = 0; i < bytewidth; i++) out[i] = (scanline[i] - prevline[i]); + for(i = bytewidth; i < length; i++) + { + out[i] = (scanline[i] - paethPredictor(scanline[i - bytewidth], prevline[i], prevline[i - bytewidth])); + } + } + else + { + for(i = 0; i < bytewidth; i++) out[i] = scanline[i]; + /*paethPredictor(scanline[i - bytewidth], 0, 0) is always scanline[i - bytewidth]*/ + for(i = bytewidth; i < length; i++) out[i] = (scanline[i] - scanline[i - bytewidth]); + } + break; + default: return; /*unexisting filter type given*/ + } +} + +/* log2 approximation. A slight bit faster than std::log. */ +static float flog2(float f) +{ + float result = 0; + while(f > 32) { result += 4; f /= 16; } + while(f > 2) { result++; f /= 2; } + return result + 1.442695f * (f * f * f / 3 - 3 * f * f / 2 + 3 * f - 1.83333f); +} + +static unsigned filter(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, + const LodePNGColorMode* info, const LodePNGEncoderSettings* settings) +{ + /* + For PNG filter method 0 + out must be a buffer with as size: h + (w * h * bpp + 7) / 8, because there are + the scanlines with 1 extra byte per scanline + */ + + unsigned bpp = lodepng_get_bpp(info); + /*the width of a scanline in bytes, not including the filter type*/ + size_t linebytes = (w * bpp + 7) / 8; + /*bytewidth is used for filtering, is 1 when bpp < 8, number of bytes per pixel otherwise*/ + size_t bytewidth = (bpp + 7) / 8; + const unsigned char* prevline = 0; + unsigned x, y; + unsigned error = 0; + LodePNGFilterStrategy strategy = settings->filter_strategy; + + /* + There is a heuristic called the minimum sum of absolute differences heuristic, suggested by the PNG standard: + * If the image type is Palette, or the bit depth is smaller than 8, then do not filter the image (i.e. + use fixed filtering, with the filter None). + * (The other case) If the image type is Grayscale or RGB (with or without Alpha), and the bit depth is + not smaller than 8, then use adaptive filtering heuristic as follows: independently for each row, apply + all five filters and select the filter that produces the smallest sum of absolute values per row. + This heuristic is used if filter strategy is LFS_MINSUM and filter_palette_zero is true. + + If filter_palette_zero is true and filter_strategy is not LFS_MINSUM, the above heuristic is followed, + but for "the other case", whatever strategy filter_strategy is set to instead of the minimum sum + heuristic is used. + */ + if(settings->filter_palette_zero && + (info->colortype == LCT_PALETTE || info->bitdepth < 8)) strategy = LFS_ZERO; + + if(bpp == 0) return 31; /*error: invalid color type*/ + + if(strategy == LFS_ZERO) + { + for(y = 0; y < h; y++) + { + size_t outindex = (1 + linebytes) * y; /*the extra filterbyte added to each row*/ + size_t inindex = linebytes * y; + out[outindex] = 0; /*filter type byte*/ + filterScanline(&out[outindex + 1], &in[inindex], prevline, linebytes, bytewidth, 0); + prevline = &in[inindex]; + } + } + else if(strategy == LFS_MINSUM) + { + /*adaptive filtering*/ + size_t sum[5]; + ucvector attempt[5]; /*five filtering attempts, one for each filter type*/ + size_t smallest = 0; + unsigned char type, bestType = 0; + + for(type = 0; type < 5; type++) + { + ucvector_init(&attempt[type]); + if(!ucvector_resize(&attempt[type], linebytes)) return 83; /*alloc fail*/ + } + + if(!error) + { + for(y = 0; y < h; y++) + { + /*try the 5 filter types*/ + for(type = 0; type < 5; type++) + { + filterScanline(attempt[type].data, &in[y * linebytes], prevline, linebytes, bytewidth, type); + + /*calculate the sum of the result*/ + sum[type] = 0; + if(type == 0) + { + for(x = 0; x < linebytes; x++) sum[type] += (unsigned char)(attempt[type].data[x]); + } + else + { + for(x = 0; x < linebytes; x++) + { + /*For differences, each byte should be treated as signed, values above 127 are negative + (converted to signed char). Filtertype 0 isn't a difference though, so use unsigned there. + This means filtertype 0 is almost never chosen, but that is justified.*/ + unsigned char s = attempt[type].data[x]; + sum[type] += s < 128 ? s : (255U - s); + } + } + + /*check if this is smallest sum (or if type == 0 it's the first case so always store the values)*/ + if(type == 0 || sum[type] < smallest) + { + bestType = type; + smallest = sum[type]; + } + } + + prevline = &in[y * linebytes]; + + /*now fill the out values*/ + out[y * (linebytes + 1)] = bestType; /*the first byte of a scanline will be the filter type*/ + for(x = 0; x < linebytes; x++) out[y * (linebytes + 1) + 1 + x] = attempt[bestType].data[x]; + } + } + + for(type = 0; type < 5; type++) ucvector_cleanup(&attempt[type]); + } + else if(strategy == LFS_ENTROPY) + { + float sum[5]; + ucvector attempt[5]; /*five filtering attempts, one for each filter type*/ + float smallest = 0; + unsigned type, bestType = 0; + unsigned count[256]; + + for(type = 0; type < 5; type++) + { + ucvector_init(&attempt[type]); + if(!ucvector_resize(&attempt[type], linebytes)) return 83; /*alloc fail*/ + } + + for(y = 0; y < h; y++) + { + /*try the 5 filter types*/ + for(type = 0; type < 5; type++) + { + filterScanline(attempt[type].data, &in[y * linebytes], prevline, linebytes, bytewidth, type); + for(x = 0; x < 256; x++) count[x] = 0; + for(x = 0; x < linebytes; x++) count[attempt[type].data[x]]++; + count[type]++; /*the filter type itself is part of the scanline*/ + sum[type] = 0; + for(x = 0; x < 256; x++) + { + float p = count[x] / (float)(linebytes + 1); + sum[type] += count[x] == 0 ? 0 : flog2(1 / p) * p; + } + /*check if this is smallest sum (or if type == 0 it's the first case so always store the values)*/ + if(type == 0 || sum[type] < smallest) + { + bestType = type; + smallest = sum[type]; + } + } + + prevline = &in[y * linebytes]; + + /*now fill the out values*/ + out[y * (linebytes + 1)] = bestType; /*the first byte of a scanline will be the filter type*/ + for(x = 0; x < linebytes; x++) out[y * (linebytes + 1) + 1 + x] = attempt[bestType].data[x]; + } + + for(type = 0; type < 5; type++) ucvector_cleanup(&attempt[type]); + } + else if(strategy == LFS_PREDEFINED) + { + for(y = 0; y < h; y++) + { + size_t outindex = (1 + linebytes) * y; /*the extra filterbyte added to each row*/ + size_t inindex = linebytes * y; + unsigned char type = settings->predefined_filters[y]; + out[outindex] = type; /*filter type byte*/ + filterScanline(&out[outindex + 1], &in[inindex], prevline, linebytes, bytewidth, type); + prevline = &in[inindex]; + } + } + else if(strategy == LFS_BRUTE_FORCE) + { + /*brute force filter chooser. + deflate the scanline after every filter attempt to see which one deflates best. + This is very slow and gives only slightly smaller, sometimes even larger, result*/ + size_t size[5]; + ucvector attempt[5]; /*five filtering attempts, one for each filter type*/ + size_t smallest = 0; + unsigned type = 0, bestType = 0; + unsigned char* dummy; + LodePNGCompressSettings zlibsettings = settings->zlibsettings; + /*use fixed tree on the attempts so that the tree is not adapted to the filtertype on purpose, + to simulate the true case where the tree is the same for the whole image. Sometimes it gives + better result with dynamic tree anyway. Using the fixed tree sometimes gives worse, but in rare + cases better compression. It does make this a bit less slow, so it's worth doing this.*/ + zlibsettings.btype = 1; + /*a custom encoder likely doesn't read the btype setting and is optimized for complete PNG + images only, so disable it*/ + zlibsettings.custom_zlib = 0; + zlibsettings.custom_deflate = 0; + for(type = 0; type < 5; type++) + { + ucvector_init(&attempt[type]); + ucvector_resize(&attempt[type], linebytes); /*todo: give error if resize failed*/ + } + for(y = 0; y < h; y++) /*try the 5 filter types*/ + { + for(type = 0; type < 5; type++) + { + unsigned testsize = attempt[type].size; + /*if(testsize > 8) testsize /= 8;*/ /*it already works good enough by testing a part of the row*/ + + filterScanline(attempt[type].data, &in[y * linebytes], prevline, linebytes, bytewidth, type); + size[type] = 0; + dummy = 0; + zlib_compress(&dummy, &size[type], attempt[type].data, testsize, &zlibsettings); + lodepng_free(dummy); + /*check if this is smallest size (or if type == 0 it's the first case so always store the values)*/ + if(type == 0 || size[type] < smallest) + { + bestType = type; + smallest = size[type]; + } + } + prevline = &in[y * linebytes]; + out[y * (linebytes + 1)] = bestType; /*the first byte of a scanline will be the filter type*/ + for(x = 0; x < linebytes; x++) out[y * (linebytes + 1) + 1 + x] = attempt[bestType].data[x]; + } + for(type = 0; type < 5; type++) ucvector_cleanup(&attempt[type]); + } + else return 88; /* unknown filter strategy */ + + return error; +} + +static void addPaddingBits(unsigned char* out, const unsigned char* in, + size_t olinebits, size_t ilinebits, unsigned h) +{ + /*The opposite of the removePaddingBits function + olinebits must be >= ilinebits*/ + unsigned y; + size_t diff = olinebits - ilinebits; + size_t obp = 0, ibp = 0; /*bit pointers*/ + for(y = 0; y < h; y++) + { + size_t x; + for(x = 0; x < ilinebits; x++) + { + unsigned char bit = readBitFromReversedStream(&ibp, in); + setBitOfReversedStream(&obp, out, bit); + } + /*obp += diff; --> no, fill in some value in the padding bits too, to avoid + "Use of uninitialised value of size ###" warning from valgrind*/ + for(x = 0; x < diff; x++) setBitOfReversedStream(&obp, out, 0); + } +} + +/* +in: non-interlaced image with size w*h +out: the same pixels, but re-ordered according to PNG's Adam7 interlacing, with + no padding bits between scanlines, but between reduced images so that each + reduced image starts at a byte. +bpp: bits per pixel +there are no padding bits, not between scanlines, not between reduced images +in has the following size in bits: w * h * bpp. +out is possibly bigger due to padding bits between reduced images +NOTE: comments about padding bits are only relevant if bpp < 8 +*/ +static void Adam7_interlace(unsigned char* out, const unsigned char* in, unsigned w, unsigned h, unsigned bpp) +{ + unsigned passw[7], passh[7]; + size_t filter_passstart[8], padded_passstart[8], passstart[8]; + unsigned i; + + Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); + + if(bpp >= 8) + { + for(i = 0; i < 7; i++) + { + unsigned x, y, b; + size_t bytewidth = bpp / 8; + for(y = 0; y < passh[i]; y++) + for(x = 0; x < passw[i]; x++) + { + size_t pixelinstart = ((ADAM7_IY[i] + y * ADAM7_DY[i]) * w + ADAM7_IX[i] + x * ADAM7_DX[i]) * bytewidth; + size_t pixeloutstart = passstart[i] + (y * passw[i] + x) * bytewidth; + for(b = 0; b < bytewidth; b++) + { + out[pixeloutstart + b] = in[pixelinstart + b]; + } + } + } + } + else /*bpp < 8: Adam7 with pixels < 8 bit is a bit trickier: with bit pointers*/ + { + for(i = 0; i < 7; i++) + { + unsigned x, y, b; + unsigned ilinebits = bpp * passw[i]; + unsigned olinebits = bpp * w; + size_t obp, ibp; /*bit pointers (for out and in buffer)*/ + for(y = 0; y < passh[i]; y++) + for(x = 0; x < passw[i]; x++) + { + ibp = (ADAM7_IY[i] + y * ADAM7_DY[i]) * olinebits + (ADAM7_IX[i] + x * ADAM7_DX[i]) * bpp; + obp = (8 * passstart[i]) + (y * ilinebits + x * bpp); + for(b = 0; b < bpp; b++) + { + unsigned char bit = readBitFromReversedStream(&ibp, in); + setBitOfReversedStream(&obp, out, bit); + } + } + } + } +} + +/*out must be buffer big enough to contain uncompressed IDAT chunk data, and in must contain the full image. +return value is error**/ +static unsigned preProcessScanlines(unsigned char** out, size_t* outsize, const unsigned char* in, + unsigned w, unsigned h, + const LodePNGInfo* info_png, const LodePNGEncoderSettings* settings) +{ + /* + This function converts the pure 2D image with the PNG's colortype, into filtered-padded-interlaced data. Steps: + *) if no Adam7: 1) add padding bits (= posible extra bits per scanline if bpp < 8) 2) filter + *) if adam7: 1) Adam7_interlace 2) 7x add padding bits 3) 7x filter + */ + unsigned bpp = lodepng_get_bpp(&info_png->color); + unsigned error = 0; + + if(info_png->interlace_method == 0) + { + *outsize = h + (h * ((w * bpp + 7) / 8)); /*image size plus an extra byte per scanline + possible padding bits*/ + *out = (unsigned char*)lodepng_malloc(*outsize); + if(!(*out) && (*outsize)) error = 83; /*alloc fail*/ + + if(!error) + { + /*non multiple of 8 bits per scanline, padding bits needed per scanline*/ + if(bpp < 8 && w * bpp != ((w * bpp + 7) / 8) * 8) + { + unsigned char* padded = (unsigned char*)lodepng_malloc(h * ((w * bpp + 7) / 8)); + if(!padded) error = 83; /*alloc fail*/ + if(!error) + { + addPaddingBits(padded, in, ((w * bpp + 7) / 8) * 8, w * bpp, h); + error = filter(*out, padded, w, h, &info_png->color, settings); + } + lodepng_free(padded); + } + else + { + /*we can immediatly filter into the out buffer, no other steps needed*/ + error = filter(*out, in, w, h, &info_png->color, settings); + } + } + } + else /*interlace_method is 1 (Adam7)*/ + { + unsigned passw[7], passh[7]; + size_t filter_passstart[8], padded_passstart[8], passstart[8]; + unsigned char* adam7; + + Adam7_getpassvalues(passw, passh, filter_passstart, padded_passstart, passstart, w, h, bpp); + + *outsize = filter_passstart[7]; /*image size plus an extra byte per scanline + possible padding bits*/ + *out = (unsigned char*)lodepng_malloc(*outsize); + if(!(*out)) error = 83; /*alloc fail*/ + + adam7 = (unsigned char*)lodepng_malloc(passstart[7]); + if(!adam7 && passstart[7]) error = 83; /*alloc fail*/ + + if(!error) + { + unsigned i; + + Adam7_interlace(adam7, in, w, h, bpp); + for(i = 0; i < 7; i++) + { + if(bpp < 8) + { + unsigned char* padded = (unsigned char*)lodepng_malloc(padded_passstart[i + 1] - padded_passstart[i]); + if(!padded) ERROR_BREAK(83); /*alloc fail*/ + addPaddingBits(padded, &adam7[passstart[i]], + ((passw[i] * bpp + 7) / 8) * 8, passw[i] * bpp, passh[i]); + error = filter(&(*out)[filter_passstart[i]], padded, + passw[i], passh[i], &info_png->color, settings); + lodepng_free(padded); + } + else + { + error = filter(&(*out)[filter_passstart[i]], &adam7[padded_passstart[i]], + passw[i], passh[i], &info_png->color, settings); + } + + if(error) break; + } + } + + lodepng_free(adam7); + } + + return error; +} + +/* +palette must have 4 * palettesize bytes allocated, and given in format RGBARGBARGBARGBA... +returns 0 if the palette is opaque, +returns 1 if the palette has a single color with alpha 0 ==> color key +returns 2 if the palette is semi-translucent. +*/ +static unsigned getPaletteTranslucency(const unsigned char* palette, size_t palettesize) +{ + size_t i; + unsigned key = 0; + unsigned r = 0, g = 0, b = 0; /*the value of the color with alpha 0, so long as color keying is possible*/ + for(i = 0; i < palettesize; i++) + { + if(!key && palette[4 * i + 3] == 0) + { + r = palette[4 * i + 0]; g = palette[4 * i + 1]; b = palette[4 * i + 2]; + key = 1; + i = (size_t)(-1); /*restart from beginning, to detect earlier opaque colors with key's value*/ + } + else if(palette[4 * i + 3] != 255) return 2; + /*when key, no opaque RGB may have key's RGB*/ + else if(key && r == palette[i * 4 + 0] && g == palette[i * 4 + 1] && b == palette[i * 4 + 2]) return 2; + } + return key; +} + +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS +static unsigned addUnknownChunks(ucvector* out, unsigned char* data, size_t datasize) +{ + unsigned char* inchunk = data; + while((size_t)(inchunk - data) < datasize) + { + CERROR_TRY_RETURN(lodepng_chunk_append(&out->data, &out->size, inchunk)); + out->allocsize = out->size; /*fix the allocsize again*/ + inchunk = lodepng_chunk_next(inchunk); + } + return 0; +} +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + +unsigned lodepng_encode(unsigned char** out, size_t* outsize, + const unsigned char* image, unsigned w, unsigned h, + LodePNGState* state) +{ + LodePNGInfo info; + ucvector outv; + unsigned char* data = 0; /*uncompressed version of the IDAT chunk data*/ + size_t datasize = 0; + + /*provide some proper output values if error will happen*/ + *out = 0; + *outsize = 0; + state->error = 0; + + lodepng_info_init(&info); + lodepng_info_copy(&info, &state->info_png); + + if((info.color.colortype == LCT_PALETTE || state->encoder.force_palette) + && (info.color.palettesize == 0 || info.color.palettesize > 256)) + { + state->error = 68; /*invalid palette size, it is only allowed to be 1-256*/ + return state->error; + } + + if(state->encoder.auto_convert) + { + state->error = lodepng_auto_choose_color(&info.color, image, w, h, &state->info_raw); + } + if(state->error) return state->error; + + if(state->encoder.zlibsettings.btype > 2) + { + CERROR_RETURN_ERROR(state->error, 61); /*error: unexisting btype*/ + } + if(state->info_png.interlace_method > 1) + { + CERROR_RETURN_ERROR(state->error, 71); /*error: unexisting interlace mode*/ + } + + state->error = checkColorValidity(info.color.colortype, info.color.bitdepth); + if(state->error) return state->error; /*error: unexisting color type given*/ + state->error = checkColorValidity(state->info_raw.colortype, state->info_raw.bitdepth); + if(state->error) return state->error; /*error: unexisting color type given*/ + + if(!lodepng_color_mode_equal(&state->info_raw, &info.color)) + { + unsigned char* converted; + size_t size = (w * h * lodepng_get_bpp(&info.color) + 7) / 8; + + converted = (unsigned char*)lodepng_malloc(size); + if(!converted && size) state->error = 83; /*alloc fail*/ + if(!state->error) + { + state->error = lodepng_convert(converted, image, &info.color, &state->info_raw, w, h); + } + if(!state->error) preProcessScanlines(&data, &datasize, converted, w, h, &info, &state->encoder); + lodepng_free(converted); + } + else preProcessScanlines(&data, &datasize, image, w, h, &info, &state->encoder); + + ucvector_init(&outv); + while(!state->error) /*while only executed once, to break on error*/ + { +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + size_t i; +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + /*write signature and chunks*/ + writeSignature(&outv); + /*IHDR*/ + addChunk_IHDR(&outv, w, h, info.color.colortype, info.color.bitdepth, info.interlace_method); +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + /*unknown chunks between IHDR and PLTE*/ + if(info.unknown_chunks_data[0]) + { + state->error = addUnknownChunks(&outv, info.unknown_chunks_data[0], info.unknown_chunks_size[0]); + if(state->error) break; + } +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + /*PLTE*/ + if(info.color.colortype == LCT_PALETTE) + { + addChunk_PLTE(&outv, &info.color); + } + if(state->encoder.force_palette && (info.color.colortype == LCT_RGB || info.color.colortype == LCT_RGBA)) + { + addChunk_PLTE(&outv, &info.color); + } + /*tRNS*/ + if(info.color.colortype == LCT_PALETTE && getPaletteTranslucency(info.color.palette, info.color.palettesize) != 0) + { + addChunk_tRNS(&outv, &info.color); + } + if((info.color.colortype == LCT_GREY || info.color.colortype == LCT_RGB) && info.color.key_defined) + { + addChunk_tRNS(&outv, &info.color); + } +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + /*bKGD (must come between PLTE and the IDAt chunks*/ + if(info.background_defined) addChunk_bKGD(&outv, &info); + /*pHYs (must come before the IDAT chunks)*/ + if(info.phys_defined) addChunk_pHYs(&outv, &info); + + /*unknown chunks between PLTE and IDAT*/ + if(info.unknown_chunks_data[1]) + { + state->error = addUnknownChunks(&outv, info.unknown_chunks_data[1], info.unknown_chunks_size[1]); + if(state->error) break; + } +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + /*IDAT (multiple IDAT chunks must be consecutive)*/ + state->error = addChunk_IDAT(&outv, data, datasize, &state->encoder.zlibsettings); + if(state->error) break; +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + /*tIME*/ + if(info.time_defined) addChunk_tIME(&outv, &info.time); + /*tEXt and/or zTXt*/ + for(i = 0; i < info.text_num; i++) + { + if(strlen(info.text_keys[i]) > 79) + { + state->error = 66; /*text chunk too large*/ + break; + } + if(strlen(info.text_keys[i]) < 1) + { + state->error = 67; /*text chunk too small*/ + break; + } + if(state->encoder.text_compression) + { + addChunk_zTXt(&outv, info.text_keys[i], info.text_strings[i], &state->encoder.zlibsettings); + } + else + { + addChunk_tEXt(&outv, info.text_keys[i], info.text_strings[i]); + } + } + /*LodePNG version id in text chunk*/ + if(state->encoder.add_id) + { + unsigned alread_added_id_text = 0; + for(i = 0; i < info.text_num; i++) + { + if(!strcmp(info.text_keys[i], "LodePNG")) + { + alread_added_id_text = 1; + break; + } + } + if(alread_added_id_text == 0) + { + addChunk_tEXt(&outv, "LodePNG", VERSION_STRING); /*it's shorter as tEXt than as zTXt chunk*/ + } + } + /*iTXt*/ + for(i = 0; i < info.itext_num; i++) + { + if(strlen(info.itext_keys[i]) > 79) + { + state->error = 66; /*text chunk too large*/ + break; + } + if(strlen(info.itext_keys[i]) < 1) + { + state->error = 67; /*text chunk too small*/ + break; + } + addChunk_iTXt(&outv, state->encoder.text_compression, + info.itext_keys[i], info.itext_langtags[i], info.itext_transkeys[i], info.itext_strings[i], + &state->encoder.zlibsettings); + } + + /*unknown chunks between IDAT and IEND*/ + if(info.unknown_chunks_data[2]) + { + state->error = addUnknownChunks(&outv, info.unknown_chunks_data[2], info.unknown_chunks_size[2]); + if(state->error) break; + } +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + addChunk_IEND(&outv); + + break; /*this isn't really a while loop; no error happened so break out now!*/ + } + + lodepng_info_cleanup(&info); + lodepng_free(data); + /*instead of cleaning the vector up, give it to the output*/ + *out = outv.data; + *outsize = outv.size; + + return state->error; +} + +unsigned lodepng_encode_memory(unsigned char** out, size_t* outsize, const unsigned char* image, + unsigned w, unsigned h, LodePNGColorType colortype, unsigned bitdepth) +{ + unsigned error; + LodePNGState state; + lodepng_state_init(&state); + state.info_raw.colortype = colortype; + state.info_raw.bitdepth = bitdepth; + state.info_png.color.colortype = colortype; + state.info_png.color.bitdepth = bitdepth; + lodepng_encode(out, outsize, image, w, h, &state); + error = state.error; + lodepng_state_cleanup(&state); + return error; +} + +unsigned lodepng_encode32(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h) +{ + return lodepng_encode_memory(out, outsize, image, w, h, LCT_RGBA, 8); +} + +unsigned lodepng_encode24(unsigned char** out, size_t* outsize, const unsigned char* image, unsigned w, unsigned h) +{ + return lodepng_encode_memory(out, outsize, image, w, h, LCT_RGB, 8); +} + +#ifdef LODEPNG_COMPILE_DISK +unsigned lodepng_encode_file(const char* filename, const unsigned char* image, unsigned w, unsigned h, + LodePNGColorType colortype, unsigned bitdepth) +{ + unsigned char* buffer; + size_t buffersize; + unsigned error = lodepng_encode_memory(&buffer, &buffersize, image, w, h, colortype, bitdepth); + if(!error) error = lodepng_save_file(buffer, buffersize, filename); + lodepng_free(buffer); + return error; +} + +unsigned lodepng_encode32_file(const char* filename, const unsigned char* image, unsigned w, unsigned h) +{ + return lodepng_encode_file(filename, image, w, h, LCT_RGBA, 8); +} + +unsigned lodepng_encode24_file(const char* filename, const unsigned char* image, unsigned w, unsigned h) +{ + return lodepng_encode_file(filename, image, w, h, LCT_RGB, 8); +} +#endif /*LODEPNG_COMPILE_DISK*/ + +void lodepng_encoder_settings_init(LodePNGEncoderSettings* settings) +{ + lodepng_compress_settings_init(&settings->zlibsettings); + settings->filter_palette_zero = 1; + settings->filter_strategy = LFS_MINSUM; + settings->auto_convert = 1; + settings->force_palette = 0; + settings->predefined_filters = 0; +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + settings->add_id = 0; + settings->text_compression = 1; +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ +} + +#endif /*LODEPNG_COMPILE_ENCODER*/ +#endif /*LODEPNG_COMPILE_PNG*/ + +#ifdef LODEPNG_COMPILE_ERROR_TEXT +/* +This returns the description of a numerical error code in English. This is also +the documentation of all the error codes. +*/ +const char* lodepng_error_text(unsigned code) +{ + switch(code) + { + case 0: return "no error, everything went ok"; + case 1: return "nothing done yet"; /*the Encoder/Decoder has done nothing yet, error checking makes no sense yet*/ + case 10: return "end of input memory reached without huffman end code"; /*while huffman decoding*/ + case 11: return "error in code tree made it jump outside of huffman tree"; /*while huffman decoding*/ + case 13: return "problem while processing dynamic deflate block"; + case 14: return "problem while processing dynamic deflate block"; + case 15: return "problem while processing dynamic deflate block"; + case 16: return "unexisting code while processing dynamic deflate block"; + case 17: return "end of out buffer memory reached while inflating"; + case 18: return "invalid distance code while inflating"; + case 19: return "end of out buffer memory reached while inflating"; + case 20: return "invalid deflate block BTYPE encountered while decoding"; + case 21: return "NLEN is not ones complement of LEN in a deflate block"; + /*end of out buffer memory reached while inflating: + This can happen if the inflated deflate data is longer than the amount of bytes required to fill up + all the pixels of the image, given the color depth and image dimensions. Something that doesn't + happen in a normal, well encoded, PNG image.*/ + case 22: return "end of out buffer memory reached while inflating"; + case 23: return "end of in buffer memory reached while inflating"; + case 24: return "invalid FCHECK in zlib header"; + case 25: return "invalid compression method in zlib header"; + case 26: return "FDICT encountered in zlib header while it's not used for PNG"; + case 27: return "PNG file is smaller than a PNG header"; + /*Checks the magic file header, the first 8 bytes of the PNG file*/ + case 28: return "incorrect PNG signature, it's no PNG or corrupted"; + case 29: return "first chunk is not the header chunk"; + case 30: return "chunk length too large, chunk broken off at end of file"; + case 31: return "illegal PNG color type or bpp"; + case 32: return "illegal PNG compression method"; + case 33: return "illegal PNG filter method"; + case 34: return "illegal PNG interlace method"; + case 35: return "chunk length of a chunk is too large or the chunk too small"; + case 36: return "illegal PNG filter type encountered"; + case 37: return "illegal bit depth for this color type given"; + case 38: return "the palette is too big"; /*more than 256 colors*/ + case 39: return "more palette alpha values given in tRNS chunk than there are colors in the palette"; + case 40: return "tRNS chunk has wrong size for greyscale image"; + case 41: return "tRNS chunk has wrong size for RGB image"; + case 42: return "tRNS chunk appeared while it was not allowed for this color type"; + case 43: return "bKGD chunk has wrong size for palette image"; + case 44: return "bKGD chunk has wrong size for greyscale image"; + case 45: return "bKGD chunk has wrong size for RGB image"; + /*the input data is empty, maybe a PNG file doesn't exist or is in the wrong path*/ + case 48: return "empty input or file doesn't exist"; + case 49: return "jumped past memory while generating dynamic huffman tree"; + case 50: return "jumped past memory while generating dynamic huffman tree"; + case 51: return "jumped past memory while inflating huffman block"; + case 52: return "jumped past memory while inflating"; + case 53: return "size of zlib data too small"; + case 54: return "repeat symbol in tree while there was no value symbol yet"; + /*jumped past tree while generating huffman tree, this could be when the + tree will have more leaves than symbols after generating it out of the + given lenghts. They call this an oversubscribed dynamic bit lengths tree in zlib.*/ + case 55: return "jumped past tree while generating huffman tree"; + case 56: return "given output image colortype or bitdepth not supported for color conversion"; + case 57: return "invalid CRC encountered (checking CRC can be disabled)"; + case 58: return "invalid ADLER32 encountered (checking ADLER32 can be disabled)"; + case 59: return "requested color conversion not supported"; + case 60: return "invalid window size given in the settings of the encoder (must be 0-32768)"; + case 61: return "invalid BTYPE given in the settings of the encoder (only 0, 1 and 2 are allowed)"; + /*LodePNG leaves the choice of RGB to greyscale conversion formula to the user.*/ + case 62: return "conversion from color to greyscale not supported"; + case 63: return "length of a chunk too long, max allowed for PNG is 2147483647 bytes per chunk"; /*(2^31-1)*/ + /*this would result in the inability of a deflated block to ever contain an end code. It must be at least 1.*/ + case 64: return "the length of the END symbol 256 in the Huffman tree is 0"; + case 66: return "the length of a text chunk keyword given to the encoder is longer than the maximum of 79 bytes"; + case 67: return "the length of a text chunk keyword given to the encoder is smaller than the minimum of 1 byte"; + case 68: return "tried to encode a PLTE chunk with a palette that has less than 1 or more than 256 colors"; + case 69: return "unknown chunk type with 'critical' flag encountered by the decoder"; + case 71: return "unexisting interlace mode given to encoder (must be 0 or 1)"; + case 72: return "while decoding, unexisting compression method encountering in zTXt or iTXt chunk (it must be 0)"; + case 73: return "invalid tIME chunk size"; + case 74: return "invalid pHYs chunk size"; + /*length could be wrong, or data chopped off*/ + case 75: return "no null termination char found while decoding text chunk"; + case 76: return "iTXt chunk too short to contain required bytes"; + case 77: return "integer overflow in buffer size"; + case 78: return "failed to open file for reading"; /*file doesn't exist or couldn't be opened for reading*/ + case 79: return "failed to open file for writing"; + case 80: return "tried creating a tree of 0 symbols"; + case 81: return "lazy matching at pos 0 is impossible"; + case 82: return "color conversion to palette requested while a color isn't in palette"; + case 83: return "memory allocation failed"; + case 84: return "given image too small to contain all pixels to be encoded"; + case 86: return "impossible offset in lz77 encoding (internal bug)"; + case 87: return "must provide custom zlib function pointer if LODEPNG_COMPILE_ZLIB is not defined"; + case 88: return "invalid filter strategy given for LodePNGEncoderSettings.filter_strategy"; + case 89: return "text chunk keyword too short or long: must have size 1-79"; + /*the windowsize in the LodePNGCompressSettings. Requiring POT(==> & instead of %) makes encoding 12% faster.*/ + case 90: return "windowsize must be a power of two"; + } + return "unknown error code"; +} +#endif /*LODEPNG_COMPILE_ERROR_TEXT*/ + +/* ////////////////////////////////////////////////////////////////////////// */ +/* ////////////////////////////////////////////////////////////////////////// */ +/* // C++ Wrapper // */ +/* ////////////////////////////////////////////////////////////////////////// */ +/* ////////////////////////////////////////////////////////////////////////// */ + +#ifdef LODEPNG_COMPILE_CPP +namespace lodepng +{ + +#ifdef LODEPNG_COMPILE_DISK +void load_file(std::vector& buffer, const std::string& filename) +{ + std::ifstream file(filename.c_str(), std::ios::in|std::ios::binary|std::ios::ate); + + /*get filesize*/ + std::streamsize size = 0; + if(file.seekg(0, std::ios::end).good()) size = file.tellg(); + if(file.seekg(0, std::ios::beg).good()) size -= file.tellg(); + + /*read contents of the file into the vector*/ + buffer.resize(size_t(size)); + if(size > 0) file.read((char*)(&buffer[0]), size); +} + +/*write given buffer to the file, overwriting the file, it doesn't append to it.*/ +void save_file(const std::vector& buffer, const std::string& filename) +{ + std::ofstream file(filename.c_str(), std::ios::out|std::ios::binary); + file.write(buffer.empty() ? 0 : (char*)&buffer[0], std::streamsize(buffer.size())); +} +#endif //LODEPNG_COMPILE_DISK + +#ifdef LODEPNG_COMPILE_ZLIB +#ifdef LODEPNG_COMPILE_DECODER +unsigned decompress(std::vector& out, const unsigned char* in, size_t insize, + const LodePNGDecompressSettings& settings) +{ + unsigned char* buffer = 0; + size_t buffersize = 0; + unsigned error = zlib_decompress(&buffer, &buffersize, in, insize, &settings); + if(buffer) + { + out.insert(out.end(), &buffer[0], &buffer[buffersize]); + lodepng_free(buffer); + } + return error; +} + +unsigned decompress(std::vector& out, const std::vector& in, + const LodePNGDecompressSettings& settings) +{ + return decompress(out, in.empty() ? 0 : &in[0], in.size(), settings); +} +#endif //LODEPNG_COMPILE_DECODER + +#ifdef LODEPNG_COMPILE_ENCODER +unsigned compress(std::vector& out, const unsigned char* in, size_t insize, + const LodePNGCompressSettings& settings) +{ + unsigned char* buffer = 0; + size_t buffersize = 0; + unsigned error = zlib_compress(&buffer, &buffersize, in, insize, &settings); + if(buffer) + { + out.insert(out.end(), &buffer[0], &buffer[buffersize]); + lodepng_free(buffer); + } + return error; +} + +unsigned compress(std::vector& out, const std::vector& in, + const LodePNGCompressSettings& settings) +{ + return compress(out, in.empty() ? 0 : &in[0], in.size(), settings); +} +#endif //LODEPNG_COMPILE_ENCODER +#endif //LODEPNG_COMPILE_ZLIB + + +#ifdef LODEPNG_COMPILE_PNG + +State::State() +{ + lodepng_state_init(this); +} + +State::State(const State& other) +{ + lodepng_state_init(this); + lodepng_state_copy(this, &other); +} + +State::~State() +{ + lodepng_state_cleanup(this); +} + +State& State::operator=(const State& other) +{ + lodepng_state_copy(this, &other); + return *this; +} + +#ifdef LODEPNG_COMPILE_DECODER + +unsigned decode(std::vector& out, unsigned& w, unsigned& h, const unsigned char* in, + size_t insize, LodePNGColorType colortype, unsigned bitdepth) +{ + unsigned char* buffer; + unsigned error = lodepng_decode_memory(&buffer, &w, &h, in, insize, colortype, bitdepth); + if(buffer && !error) + { + State state; + state.info_raw.colortype = colortype; + state.info_raw.bitdepth = bitdepth; + size_t buffersize = lodepng_get_raw_size(w, h, &state.info_raw); + out.insert(out.end(), &buffer[0], &buffer[buffersize]); + lodepng_free(buffer); + } + return error; +} + +unsigned decode(std::vector& out, unsigned& w, unsigned& h, + const std::vector& in, LodePNGColorType colortype, unsigned bitdepth) +{ + return decode(out, w, h, in.empty() ? 0 : &in[0], (unsigned)in.size(), colortype, bitdepth); +} + +unsigned decode(std::vector& out, unsigned& w, unsigned& h, + State& state, + const unsigned char* in, size_t insize) +{ + unsigned char* buffer = NULL; + unsigned error = lodepng_decode(&buffer, &w, &h, &state, in, insize); + if(buffer && !error) + { + size_t buffersize = lodepng_get_raw_size(w, h, &state.info_raw); + out.insert(out.end(), &buffer[0], &buffer[buffersize]); + } + lodepng_free(buffer); + return error; +} + +unsigned decode(std::vector& out, unsigned& w, unsigned& h, + State& state, + const std::vector& in) +{ + return decode(out, w, h, state, in.empty() ? 0 : &in[0], in.size()); +} + +#ifdef LODEPNG_COMPILE_DISK +unsigned decode(std::vector& out, unsigned& w, unsigned& h, const std::string& filename, + LodePNGColorType colortype, unsigned bitdepth) +{ + std::vector buffer; + load_file(buffer, filename); + return decode(out, w, h, buffer, colortype, bitdepth); +} +#endif //LODEPNG_COMPILE_DECODER +#endif //LODEPNG_COMPILE_DISK + +#ifdef LODEPNG_COMPILE_ENCODER +unsigned encode(std::vector& out, const unsigned char* in, unsigned w, unsigned h, + LodePNGColorType colortype, unsigned bitdepth) +{ + unsigned char* buffer; + size_t buffersize; + unsigned error = lodepng_encode_memory(&buffer, &buffersize, in, w, h, colortype, bitdepth); + if(buffer) + { + out.insert(out.end(), &buffer[0], &buffer[buffersize]); + lodepng_free(buffer); + } + return error; +} + +unsigned encode(std::vector& out, + const std::vector& in, unsigned w, unsigned h, + LodePNGColorType colortype, unsigned bitdepth) +{ + if(lodepng_get_raw_size_lct(w, h, colortype, bitdepth) > in.size()) return 84; + return encode(out, in.empty() ? 0 : &in[0], w, h, colortype, bitdepth); +} + +unsigned encode(std::vector& out, + const unsigned char* in, unsigned w, unsigned h, + State& state) +{ + unsigned char* buffer; + size_t buffersize; + unsigned error = lodepng_encode(&buffer, &buffersize, in, w, h, &state); + if(buffer) + { + out.insert(out.end(), &buffer[0], &buffer[buffersize]); + lodepng_free(buffer); + } + return error; +} + +unsigned encode(std::vector& out, + const std::vector& in, unsigned w, unsigned h, + State& state) +{ + if(lodepng_get_raw_size(w, h, &state.info_raw) > in.size()) return 84; + return encode(out, in.empty() ? 0 : &in[0], w, h, state); +} + +#ifdef LODEPNG_COMPILE_DISK +unsigned encode(const std::string& filename, + const unsigned char* in, unsigned w, unsigned h, + LodePNGColorType colortype, unsigned bitdepth) +{ + std::vector buffer; + unsigned error = encode(buffer, in, w, h, colortype, bitdepth); + if(!error) save_file(buffer, filename); + return error; +} + +unsigned encode(const std::string& filename, + const std::vector& in, unsigned w, unsigned h, + LodePNGColorType colortype, unsigned bitdepth) +{ + if(lodepng_get_raw_size_lct(w, h, colortype, bitdepth) > in.size()) return 84; + return encode(filename, in.empty() ? 0 : &in[0], w, h, colortype, bitdepth); +} +#endif //LODEPNG_COMPILE_DISK +#endif //LODEPNG_COMPILE_ENCODER +#endif //LODEPNG_COMPILE_PNG +} //namespace lodepng +#endif /*LODEPNG_COMPILE_CPP*/ diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/lodepng.h b/examples/ThirdPartyLibs/openvr/samples/shared/lodepng.h new file mode 100644 index 000000000..ef2c82067 --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/samples/shared/lodepng.h @@ -0,0 +1,1702 @@ +/* +LodePNG version 20140823 + +Copyright (c) 2005-2014 Lode Vandevenne + +This software is provided 'as-is', without any express or implied +warranty. In no event will the authors be held liable for any damages +arising from the use of this software. + +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it +freely, subject to the following restrictions: + + 1. The origin of this software must not be misrepresented; you must not + claim that you wrote the original software. If you use this software + in a product, an acknowledgment in the product documentation would be + appreciated but is not required. + + 2. Altered source versions must be plainly marked as such, and must not be + misrepresented as being the original software. + + 3. This notice may not be removed or altered from any source + distribution. +*/ + +#ifndef LODEPNG_H +#define LODEPNG_H + +#include /*for size_t*/ + +#ifdef __cplusplus +#include +#include +#endif /*__cplusplus*/ + +/* +The following #defines are used to create code sections. They can be disabled +to disable code sections, which can give faster compile time and smaller binary. +The "NO_COMPILE" defines are designed to be used to pass as defines to the +compiler command to disable them without modifying this header, e.g. +-DLODEPNG_NO_COMPILE_ZLIB for gcc. +*/ +/*deflate & zlib. If disabled, you must specify alternative zlib functions in +the custom_zlib field of the compress and decompress settings*/ +#ifndef LODEPNG_NO_COMPILE_ZLIB +#define LODEPNG_COMPILE_ZLIB +#endif +/*png encoder and png decoder*/ +#ifndef LODEPNG_NO_COMPILE_PNG +#define LODEPNG_COMPILE_PNG +#endif +/*deflate&zlib decoder and png decoder*/ +#ifndef LODEPNG_NO_COMPILE_DECODER +#define LODEPNG_COMPILE_DECODER +#endif +/*deflate&zlib encoder and png encoder*/ +#ifndef LODEPNG_NO_COMPILE_ENCODER +#define LODEPNG_COMPILE_ENCODER +#endif +/*the optional built in harddisk file loading and saving functions*/ +#ifndef LODEPNG_NO_COMPILE_DISK +#define LODEPNG_COMPILE_DISK +#endif +/*support for chunks other than IHDR, IDAT, PLTE, tRNS, IEND: ancillary and unknown chunks*/ +#ifndef LODEPNG_NO_COMPILE_ANCILLARY_CHUNKS +#define LODEPNG_COMPILE_ANCILLARY_CHUNKS +#endif +/*ability to convert error numerical codes to English text string*/ +#ifndef LODEPNG_NO_COMPILE_ERROR_TEXT +#define LODEPNG_COMPILE_ERROR_TEXT +#endif +/*Compile the default allocators (C's free, malloc and realloc). If you disable this, +you can define the functions lodepng_free, lodepng_malloc and lodepng_realloc in your +source files with custom allocators.*/ +#ifndef LODEPNG_NO_COMPILE_ALLOCATORS +#define LODEPNG_COMPILE_ALLOCATORS +#endif +/*compile the C++ version (you can disable the C++ wrapper here even when compiling for C++)*/ +#ifdef __cplusplus +#ifndef LODEPNG_NO_COMPILE_CPP +#define LODEPNG_COMPILE_CPP +#endif +#endif + +#ifdef LODEPNG_COMPILE_PNG +/*The PNG color types (also used for raw).*/ +typedef enum LodePNGColorType +{ + LCT_GREY = 0, /*greyscale: 1,2,4,8,16 bit*/ + LCT_RGB = 2, /*RGB: 8,16 bit*/ + LCT_PALETTE = 3, /*palette: 1,2,4,8 bit*/ + LCT_GREY_ALPHA = 4, /*greyscale with alpha: 8,16 bit*/ + LCT_RGBA = 6 /*RGB with alpha: 8,16 bit*/ +} LodePNGColorType; + +#ifdef LODEPNG_COMPILE_DECODER +/* +Converts PNG data in memory to raw pixel data. +out: Output parameter. Pointer to buffer that will contain the raw pixel data. + After decoding, its size is w * h * (bytes per pixel) bytes larger than + initially. Bytes per pixel depends on colortype and bitdepth. + Must be freed after usage with free(*out). + Note: for 16-bit per channel colors, uses big endian format like PNG does. +w: Output parameter. Pointer to width of pixel data. +h: Output parameter. Pointer to height of pixel data. +in: Memory buffer with the PNG file. +insize: size of the in buffer. +colortype: the desired color type for the raw output image. See explanation on PNG color types. +bitdepth: the desired bit depth for the raw output image. See explanation on PNG color types. +Return value: LodePNG error code (0 means no error). +*/ +unsigned lodepng_decode_memory(unsigned char** out, unsigned* w, unsigned* h, + const unsigned char* in, size_t insize, + LodePNGColorType colortype, unsigned bitdepth); + +/*Same as lodepng_decode_memory, but always decodes to 32-bit RGBA raw image*/ +unsigned lodepng_decode32(unsigned char** out, unsigned* w, unsigned* h, + const unsigned char* in, size_t insize); + +/*Same as lodepng_decode_memory, but always decodes to 24-bit RGB raw image*/ +unsigned lodepng_decode24(unsigned char** out, unsigned* w, unsigned* h, + const unsigned char* in, size_t insize); + +#ifdef LODEPNG_COMPILE_DISK +/* +Load PNG from disk, from file with given name. +Same as the other decode functions, but instead takes a filename as input. +*/ +unsigned lodepng_decode_file(unsigned char** out, unsigned* w, unsigned* h, + const char* filename, + LodePNGColorType colortype, unsigned bitdepth); + +/*Same as lodepng_decode_file, but always decodes to 32-bit RGBA raw image.*/ +unsigned lodepng_decode32_file(unsigned char** out, unsigned* w, unsigned* h, + const char* filename); + +/*Same as lodepng_decode_file, but always decodes to 24-bit RGB raw image.*/ +unsigned lodepng_decode24_file(unsigned char** out, unsigned* w, unsigned* h, + const char* filename); +#endif /*LODEPNG_COMPILE_DISK*/ +#endif /*LODEPNG_COMPILE_DECODER*/ + + +#ifdef LODEPNG_COMPILE_ENCODER +/* +Converts raw pixel data into a PNG image in memory. The colortype and bitdepth + of the output PNG image cannot be chosen, they are automatically determined + by the colortype, bitdepth and content of the input pixel data. + Note: for 16-bit per channel colors, needs big endian format like PNG does. +out: Output parameter. Pointer to buffer that will contain the PNG image data. + Must be freed after usage with free(*out). +outsize: Output parameter. Pointer to the size in bytes of the out buffer. +image: The raw pixel data to encode. The size of this buffer should be + w * h * (bytes per pixel), bytes per pixel depends on colortype and bitdepth. +w: width of the raw pixel data in pixels. +h: height of the raw pixel data in pixels. +colortype: the color type of the raw input image. See explanation on PNG color types. +bitdepth: the bit depth of the raw input image. See explanation on PNG color types. +Return value: LodePNG error code (0 means no error). +*/ +unsigned lodepng_encode_memory(unsigned char** out, size_t* outsize, + const unsigned char* image, unsigned w, unsigned h, + LodePNGColorType colortype, unsigned bitdepth); + +/*Same as lodepng_encode_memory, but always encodes from 32-bit RGBA raw image.*/ +unsigned lodepng_encode32(unsigned char** out, size_t* outsize, + const unsigned char* image, unsigned w, unsigned h); + +/*Same as lodepng_encode_memory, but always encodes from 24-bit RGB raw image.*/ +unsigned lodepng_encode24(unsigned char** out, size_t* outsize, + const unsigned char* image, unsigned w, unsigned h); + +#ifdef LODEPNG_COMPILE_DISK +/* +Converts raw pixel data into a PNG file on disk. +Same as the other encode functions, but instead takes a filename as output. +NOTE: This overwrites existing files without warning! +*/ +unsigned lodepng_encode_file(const char* filename, + const unsigned char* image, unsigned w, unsigned h, + LodePNGColorType colortype, unsigned bitdepth); + +/*Same as lodepng_encode_file, but always encodes from 32-bit RGBA raw image.*/ +unsigned lodepng_encode32_file(const char* filename, + const unsigned char* image, unsigned w, unsigned h); + +/*Same as lodepng_encode_file, but always encodes from 24-bit RGB raw image.*/ +unsigned lodepng_encode24_file(const char* filename, + const unsigned char* image, unsigned w, unsigned h); +#endif /*LODEPNG_COMPILE_DISK*/ +#endif /*LODEPNG_COMPILE_ENCODER*/ + + +#ifdef LODEPNG_COMPILE_CPP +namespace lodepng +{ +#ifdef LODEPNG_COMPILE_DECODER +/*Same as lodepng_decode_memory, but decodes to an std::vector. The colortype +is the format to output the pixels to. Default is RGBA 8-bit per channel.*/ +unsigned decode(std::vector& out, unsigned& w, unsigned& h, + const unsigned char* in, size_t insize, + LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); +unsigned decode(std::vector& out, unsigned& w, unsigned& h, + const std::vector& in, + LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); +#ifdef LODEPNG_COMPILE_DISK +/* +Converts PNG file from disk to raw pixel data in memory. +Same as the other decode functions, but instead takes a filename as input. +*/ +unsigned decode(std::vector& out, unsigned& w, unsigned& h, + const std::string& filename, + LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); +#endif //LODEPNG_COMPILE_DISK +#endif //LODEPNG_COMPILE_DECODER + +#ifdef LODEPNG_COMPILE_ENCODER +/*Same as lodepng_encode_memory, but encodes to an std::vector. colortype +is that of the raw input data. The output PNG color type will be auto chosen.*/ +unsigned encode(std::vector& out, + const unsigned char* in, unsigned w, unsigned h, + LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); +unsigned encode(std::vector& out, + const std::vector& in, unsigned w, unsigned h, + LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); +#ifdef LODEPNG_COMPILE_DISK +/* +Converts 32-bit RGBA raw pixel data into a PNG file on disk. +Same as the other encode functions, but instead takes a filename as output. +NOTE: This overwrites existing files without warning! +*/ +unsigned encode(const std::string& filename, + const unsigned char* in, unsigned w, unsigned h, + LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); +unsigned encode(const std::string& filename, + const std::vector& in, unsigned w, unsigned h, + LodePNGColorType colortype = LCT_RGBA, unsigned bitdepth = 8); +#endif //LODEPNG_COMPILE_DISK +#endif //LODEPNG_COMPILE_ENCODER +} //namespace lodepng +#endif /*LODEPNG_COMPILE_CPP*/ +#endif /*LODEPNG_COMPILE_PNG*/ + +#ifdef LODEPNG_COMPILE_ERROR_TEXT +/*Returns an English description of the numerical error code.*/ +const char* lodepng_error_text(unsigned code); +#endif /*LODEPNG_COMPILE_ERROR_TEXT*/ + +#ifdef LODEPNG_COMPILE_DECODER +/*Settings for zlib decompression*/ +typedef struct LodePNGDecompressSettings LodePNGDecompressSettings; +struct LodePNGDecompressSettings +{ + unsigned ignore_adler32; /*if 1, continue and don't give an error message if the Adler32 checksum is corrupted*/ + + /*use custom zlib decoder instead of built in one (default: null)*/ + unsigned (*custom_zlib)(unsigned char**, size_t*, + const unsigned char*, size_t, + const LodePNGDecompressSettings*); + /*use custom deflate decoder instead of built in one (default: null) + if custom_zlib is used, custom_deflate is ignored since only the built in + zlib function will call custom_deflate*/ + unsigned (*custom_inflate)(unsigned char**, size_t*, + const unsigned char*, size_t, + const LodePNGDecompressSettings*); + + const void* custom_context; /*optional custom settings for custom functions*/ +}; + +extern const LodePNGDecompressSettings lodepng_default_decompress_settings; +void lodepng_decompress_settings_init(LodePNGDecompressSettings* settings); +#endif /*LODEPNG_COMPILE_DECODER*/ + +#ifdef LODEPNG_COMPILE_ENCODER +/* +Settings for zlib compression. Tweaking these settings tweaks the balance +between speed and compression ratio. +*/ +typedef struct LodePNGCompressSettings LodePNGCompressSettings; +struct LodePNGCompressSettings /*deflate = compress*/ +{ + /*LZ77 related settings*/ + unsigned btype; /*the block type for LZ (0, 1, 2 or 3, see zlib standard). Should be 2 for proper compression.*/ + unsigned use_lz77; /*whether or not to use LZ77. Should be 1 for proper compression.*/ + unsigned windowsize; /*must be a power of two <= 32768. higher compresses more but is slower. Default value: 2048.*/ + unsigned minmatch; /*mininum lz77 length. 3 is normally best, 6 can be better for some PNGs. Default: 0*/ + unsigned nicematch; /*stop searching if >= this length found. Set to 258 for best compression. Default: 128*/ + unsigned lazymatching; /*use lazy matching: better compression but a bit slower. Default: true*/ + + /*use custom zlib encoder instead of built in one (default: null)*/ + unsigned (*custom_zlib)(unsigned char**, size_t*, + const unsigned char*, size_t, + const LodePNGCompressSettings*); + /*use custom deflate encoder instead of built in one (default: null) + if custom_zlib is used, custom_deflate is ignored since only the built in + zlib function will call custom_deflate*/ + unsigned (*custom_deflate)(unsigned char**, size_t*, + const unsigned char*, size_t, + const LodePNGCompressSettings*); + + const void* custom_context; /*optional custom settings for custom functions*/ +}; + +extern const LodePNGCompressSettings lodepng_default_compress_settings; +void lodepng_compress_settings_init(LodePNGCompressSettings* settings); +#endif /*LODEPNG_COMPILE_ENCODER*/ + +#ifdef LODEPNG_COMPILE_PNG +/* +Color mode of an image. Contains all information required to decode the pixel +bits to RGBA colors. This information is the same as used in the PNG file +format, and is used both for PNG and raw image data in LodePNG. +*/ +typedef struct LodePNGColorMode +{ + /*header (IHDR)*/ + LodePNGColorType colortype; /*color type, see PNG standard or documentation further in this header file*/ + unsigned bitdepth; /*bits per sample, see PNG standard or documentation further in this header file*/ + + /* + palette (PLTE and tRNS) + + Dynamically allocated with the colors of the palette, including alpha. + When encoding a PNG, to store your colors in the palette of the LodePNGColorMode, first use + lodepng_palette_clear, then for each color use lodepng_palette_add. + If you encode an image without alpha with palette, don't forget to put value 255 in each A byte of the palette. + + When decoding, by default you can ignore this palette, since LodePNG already + fills the palette colors in the pixels of the raw RGBA output. + + The palette is only supported for color type 3. + */ + unsigned char* palette; /*palette in RGBARGBA... order. When allocated, must be either 0, or have size 1024*/ + size_t palettesize; /*palette size in number of colors (amount of bytes is 4 * palettesize)*/ + + /* + transparent color key (tRNS) + + This color uses the same bit depth as the bitdepth value in this struct, which can be 1-bit to 16-bit. + For greyscale PNGs, r, g and b will all 3 be set to the same. + + When decoding, by default you can ignore this information, since LodePNG sets + pixels with this key to transparent already in the raw RGBA output. + + The color key is only supported for color types 0 and 2. + */ + unsigned key_defined; /*is a transparent color key given? 0 = false, 1 = true*/ + unsigned key_r; /*red/greyscale component of color key*/ + unsigned key_g; /*green component of color key*/ + unsigned key_b; /*blue component of color key*/ +} LodePNGColorMode; + +/*init, cleanup and copy functions to use with this struct*/ +void lodepng_color_mode_init(LodePNGColorMode* info); +void lodepng_color_mode_cleanup(LodePNGColorMode* info); +/*return value is error code (0 means no error)*/ +unsigned lodepng_color_mode_copy(LodePNGColorMode* dest, const LodePNGColorMode* source); + +void lodepng_palette_clear(LodePNGColorMode* info); +/*add 1 color to the palette*/ +unsigned lodepng_palette_add(LodePNGColorMode* info, + unsigned char r, unsigned char g, unsigned char b, unsigned char a); + +/*get the total amount of bits per pixel, based on colortype and bitdepth in the struct*/ +unsigned lodepng_get_bpp(const LodePNGColorMode* info); +/*get the amount of color channels used, based on colortype in the struct. +If a palette is used, it counts as 1 channel.*/ +unsigned lodepng_get_channels(const LodePNGColorMode* info); +/*is it a greyscale type? (only colortype 0 or 4)*/ +unsigned lodepng_is_greyscale_type(const LodePNGColorMode* info); +/*has it got an alpha channel? (only colortype 2 or 6)*/ +unsigned lodepng_is_alpha_type(const LodePNGColorMode* info); +/*has it got a palette? (only colortype 3)*/ +unsigned lodepng_is_palette_type(const LodePNGColorMode* info); +/*only returns true if there is a palette and there is a value in the palette with alpha < 255. +Loops through the palette to check this.*/ +unsigned lodepng_has_palette_alpha(const LodePNGColorMode* info); +/* +Check if the given color info indicates the possibility of having non-opaque pixels in the PNG image. +Returns true if the image can have translucent or invisible pixels (it still be opaque if it doesn't use such pixels). +Returns false if the image can only have opaque pixels. +In detail, it returns true only if it's a color type with alpha, or has a palette with non-opaque values, +or if "key_defined" is true. +*/ +unsigned lodepng_can_have_alpha(const LodePNGColorMode* info); +/*Returns the byte size of a raw image buffer with given width, height and color mode*/ +size_t lodepng_get_raw_size(unsigned w, unsigned h, const LodePNGColorMode* color); + +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS +/*The information of a Time chunk in PNG.*/ +typedef struct LodePNGTime +{ + unsigned year; /*2 bytes used (0-65535)*/ + unsigned month; /*1-12*/ + unsigned day; /*1-31*/ + unsigned hour; /*0-23*/ + unsigned minute; /*0-59*/ + unsigned second; /*0-60 (to allow for leap seconds)*/ +} LodePNGTime; +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + +/*Information about the PNG image, except pixels, width and height.*/ +typedef struct LodePNGInfo +{ + /*header (IHDR), palette (PLTE) and transparency (tRNS) chunks*/ + unsigned compression_method;/*compression method of the original file. Always 0.*/ + unsigned filter_method; /*filter method of the original file*/ + unsigned interlace_method; /*interlace method of the original file*/ + LodePNGColorMode color; /*color type and bits, palette and transparency of the PNG file*/ + +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + /* + suggested background color chunk (bKGD) + This color uses the same color mode as the PNG (except alpha channel), which can be 1-bit to 16-bit. + + For greyscale PNGs, r, g and b will all 3 be set to the same. When encoding + the encoder writes the red one. For palette PNGs: When decoding, the RGB value + will be stored, not a palette index. But when encoding, specify the index of + the palette in background_r, the other two are then ignored. + + The decoder does not use this background color to edit the color of pixels. + */ + unsigned background_defined; /*is a suggested background color given?*/ + unsigned background_r; /*red component of suggested background color*/ + unsigned background_g; /*green component of suggested background color*/ + unsigned background_b; /*blue component of suggested background color*/ + + /* + non-international text chunks (tEXt and zTXt) + + The char** arrays each contain num strings. The actual messages are in + text_strings, while text_keys are keywords that give a short description what + the actual text represents, e.g. Title, Author, Description, or anything else. + + A keyword is minimum 1 character and maximum 79 characters long. It's + discouraged to use a single line length longer than 79 characters for texts. + + Don't allocate these text buffers yourself. Use the init/cleanup functions + correctly and use lodepng_add_text and lodepng_clear_text. + */ + size_t text_num; /*the amount of texts in these char** buffers (there may be more texts in itext)*/ + char** text_keys; /*the keyword of a text chunk (e.g. "Comment")*/ + char** text_strings; /*the actual text*/ + + /* + international text chunks (iTXt) + Similar to the non-international text chunks, but with additional strings + "langtags" and "transkeys". + */ + size_t itext_num; /*the amount of international texts in this PNG*/ + char** itext_keys; /*the English keyword of the text chunk (e.g. "Comment")*/ + char** itext_langtags; /*language tag for this text's language, ISO/IEC 646 string, e.g. ISO 639 language tag*/ + char** itext_transkeys; /*keyword translated to the international language - UTF-8 string*/ + char** itext_strings; /*the actual international text - UTF-8 string*/ + + /*time chunk (tIME)*/ + unsigned time_defined; /*set to 1 to make the encoder generate a tIME chunk*/ + LodePNGTime time; + + /*phys chunk (pHYs)*/ + unsigned phys_defined; /*if 0, there is no pHYs chunk and the values below are undefined, if 1 else there is one*/ + unsigned phys_x; /*pixels per unit in x direction*/ + unsigned phys_y; /*pixels per unit in y direction*/ + unsigned phys_unit; /*may be 0 (unknown unit) or 1 (metre)*/ + + /* + unknown chunks + There are 3 buffers, one for each position in the PNG where unknown chunks can appear + each buffer contains all unknown chunks for that position consecutively + The 3 buffers are the unknown chunks between certain critical chunks: + 0: IHDR-PLTE, 1: PLTE-IDAT, 2: IDAT-IEND + Do not allocate or traverse this data yourself. Use the chunk traversing functions declared + later, such as lodepng_chunk_next and lodepng_chunk_append, to read/write this struct. + */ + unsigned char* unknown_chunks_data[3]; + size_t unknown_chunks_size[3]; /*size in bytes of the unknown chunks, given for protection*/ +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ +} LodePNGInfo; + +/*init, cleanup and copy functions to use with this struct*/ +void lodepng_info_init(LodePNGInfo* info); +void lodepng_info_cleanup(LodePNGInfo* info); +/*return value is error code (0 means no error)*/ +unsigned lodepng_info_copy(LodePNGInfo* dest, const LodePNGInfo* source); + +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS +void lodepng_clear_text(LodePNGInfo* info); /*use this to clear the texts again after you filled them in*/ +unsigned lodepng_add_text(LodePNGInfo* info, const char* key, const char* str); /*push back both texts at once*/ + +void lodepng_clear_itext(LodePNGInfo* info); /*use this to clear the itexts again after you filled them in*/ +unsigned lodepng_add_itext(LodePNGInfo* info, const char* key, const char* langtag, + const char* transkey, const char* str); /*push back the 4 texts of 1 chunk at once*/ +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ + +/* +Converts raw buffer from one color type to another color type, based on +LodePNGColorMode structs to describe the input and output color type. +See the reference manual at the end of this header file to see which color conversions are supported. +return value = LodePNG error code (0 if all went ok, an error if the conversion isn't supported) +The out buffer must have size (w * h * bpp + 7) / 8, where bpp is the bits per pixel +of the output color type (lodepng_get_bpp). +For < 8 bpp images, there should not be padding bits at the end of scanlines. +For 16-bit per channel colors, uses big endian format like PNG does. +Return value is LodePNG error code +*/ +unsigned lodepng_convert(unsigned char* out, const unsigned char* in, + LodePNGColorMode* mode_out, const LodePNGColorMode* mode_in, + unsigned w, unsigned h); + +#ifdef LODEPNG_COMPILE_DECODER +/* +Settings for the decoder. This contains settings for the PNG and the Zlib +decoder, but not the Info settings from the Info structs. +*/ +typedef struct LodePNGDecoderSettings +{ + LodePNGDecompressSettings zlibsettings; /*in here is the setting to ignore Adler32 checksums*/ + + unsigned ignore_crc; /*ignore CRC checksums*/ + + unsigned color_convert; /*whether to convert the PNG to the color type you want. Default: yes*/ + +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + unsigned read_text_chunks; /*if false but remember_unknown_chunks is true, they're stored in the unknown chunks*/ + /*store all bytes from unknown chunks in the LodePNGInfo (off by default, useful for a png editor)*/ + unsigned remember_unknown_chunks; +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ +} LodePNGDecoderSettings; + +void lodepng_decoder_settings_init(LodePNGDecoderSettings* settings); +#endif /*LODEPNG_COMPILE_DECODER*/ + +#ifdef LODEPNG_COMPILE_ENCODER +/*automatically use color type with less bits per pixel if losslessly possible. Default: AUTO*/ +typedef enum LodePNGFilterStrategy +{ + /*every filter at zero*/ + LFS_ZERO, + /*Use filter that gives minumum sum, as described in the official PNG filter heuristic.*/ + LFS_MINSUM, + /*Use the filter type that gives smallest Shannon entropy for this scanline. Depending + on the image, this is better or worse than minsum.*/ + LFS_ENTROPY, + /* + Brute-force-search PNG filters by compressing each filter for each scanline. + Experimental, very slow, and only rarely gives better compression than MINSUM. + */ + LFS_BRUTE_FORCE, + /*use predefined_filters buffer: you specify the filter type for each scanline*/ + LFS_PREDEFINED +} LodePNGFilterStrategy; + +/*Gives characteristics about the colors of the image, which helps decide which color model to use for encoding. +Used internally by default if "auto_convert" is enabled. Public because it's useful for custom algorithms.*/ +typedef struct LodePNGColorProfile +{ + unsigned colored; /*not greyscale*/ + unsigned key; /*if true, image is not opaque. Only if true and alpha is false, color key is possible.*/ + unsigned short key_r; /*these values are always in 16-bit bitdepth in the profile*/ + unsigned short key_g; + unsigned short key_b; + unsigned alpha; /*alpha channel or alpha palette required*/ + unsigned numcolors; /*amount of colors, up to 257. Not valid if bits == 16.*/ + unsigned char palette[1024]; /*Remembers up to the first 256 RGBA colors, in no particular order*/ + unsigned bits; /*bits per channel (not for palette). 1,2 or 4 for greyscale only. 16 if 16-bit per channel required.*/ +} LodePNGColorProfile; + +void lodepng_color_profile_init(LodePNGColorProfile* profile); + +/*Get a LodePNGColorProfile of the image.*/ +unsigned get_color_profile(LodePNGColorProfile* profile, + const unsigned char* image, unsigned w, unsigned h, + const LodePNGColorMode* mode_in); +/*The function LodePNG uses internally to decide the PNG color with auto_convert. +Chooses an optimal color model, e.g. grey if only grey pixels, palette if < 256 colors, ...*/ +unsigned lodepng_auto_choose_color(LodePNGColorMode* mode_out, + const unsigned char* image, unsigned w, unsigned h, + const LodePNGColorMode* mode_in); + +/*Settings for the encoder.*/ +typedef struct LodePNGEncoderSettings +{ + LodePNGCompressSettings zlibsettings; /*settings for the zlib encoder, such as window size, ...*/ + + unsigned auto_convert; /*automatically choose output PNG color type. Default: true*/ + + /*If true, follows the official PNG heuristic: if the PNG uses a palette or lower than + 8 bit depth, set all filters to zero. Otherwise use the filter_strategy. Note that to + completely follow the official PNG heuristic, filter_palette_zero must be true and + filter_strategy must be LFS_MINSUM*/ + unsigned filter_palette_zero; + /*Which filter strategy to use when not using zeroes due to filter_palette_zero. + Set filter_palette_zero to 0 to ensure always using your chosen strategy. Default: LFS_MINSUM*/ + LodePNGFilterStrategy filter_strategy; + /*used if filter_strategy is LFS_PREDEFINED. In that case, this must point to a buffer with + the same length as the amount of scanlines in the image, and each value must <= 5. You + have to cleanup this buffer, LodePNG will never free it. Don't forget that filter_palette_zero + must be set to 0 to ensure this is also used on palette or low bitdepth images.*/ + const unsigned char* predefined_filters; + + /*force creating a PLTE chunk if colortype is 2 or 6 (= a suggested palette). + If colortype is 3, PLTE is _always_ created.*/ + unsigned force_palette; +#ifdef LODEPNG_COMPILE_ANCILLARY_CHUNKS + /*add LodePNG identifier and version as a text chunk, for debugging*/ + unsigned add_id; + /*encode text chunks as zTXt chunks instead of tEXt chunks, and use compression in iTXt chunks*/ + unsigned text_compression; +#endif /*LODEPNG_COMPILE_ANCILLARY_CHUNKS*/ +} LodePNGEncoderSettings; + +void lodepng_encoder_settings_init(LodePNGEncoderSettings* settings); +#endif /*LODEPNG_COMPILE_ENCODER*/ + + +#if defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) +/*The settings, state and information for extended encoding and decoding.*/ +typedef struct LodePNGState +{ +#ifdef LODEPNG_COMPILE_DECODER + LodePNGDecoderSettings decoder; /*the decoding settings*/ +#endif /*LODEPNG_COMPILE_DECODER*/ +#ifdef LODEPNG_COMPILE_ENCODER + LodePNGEncoderSettings encoder; /*the encoding settings*/ +#endif /*LODEPNG_COMPILE_ENCODER*/ + LodePNGColorMode info_raw; /*specifies the format in which you would like to get the raw pixel buffer*/ + LodePNGInfo info_png; /*info of the PNG image obtained after decoding*/ + unsigned error; +#ifdef LODEPNG_COMPILE_CPP + //For the lodepng::State subclass. + virtual ~LodePNGState(){} +#endif +} LodePNGState; + +/*init, cleanup and copy functions to use with this struct*/ +void lodepng_state_init(LodePNGState* state); +void lodepng_state_cleanup(LodePNGState* state); +void lodepng_state_copy(LodePNGState* dest, const LodePNGState* source); +#endif /* defined(LODEPNG_COMPILE_DECODER) || defined(LODEPNG_COMPILE_ENCODER) */ + +#ifdef LODEPNG_COMPILE_DECODER +/* +Same as lodepng_decode_memory, but uses a LodePNGState to allow custom settings and +getting much more information about the PNG image and color mode. +*/ +unsigned lodepng_decode(unsigned char** out, unsigned* w, unsigned* h, + LodePNGState* state, + const unsigned char* in, size_t insize); + +/* +Read the PNG header, but not the actual data. This returns only the information +that is in the header chunk of the PNG, such as width, height and color type. The +information is placed in the info_png field of the LodePNGState. +*/ +unsigned lodepng_inspect(unsigned* w, unsigned* h, + LodePNGState* state, + const unsigned char* in, size_t insize); +#endif /*LODEPNG_COMPILE_DECODER*/ + + +#ifdef LODEPNG_COMPILE_ENCODER +/*This function allocates the out buffer with standard malloc and stores the size in *outsize.*/ +unsigned lodepng_encode(unsigned char** out, size_t* outsize, + const unsigned char* image, unsigned w, unsigned h, + LodePNGState* state); +#endif /*LODEPNG_COMPILE_ENCODER*/ + +/* +The lodepng_chunk functions are normally not needed, except to traverse the +unknown chunks stored in the LodePNGInfo struct, or add new ones to it. +It also allows traversing the chunks of an encoded PNG file yourself. + +PNG standard chunk naming conventions: +First byte: uppercase = critical, lowercase = ancillary +Second byte: uppercase = public, lowercase = private +Third byte: must be uppercase +Fourth byte: uppercase = unsafe to copy, lowercase = safe to copy +*/ + +/*get the length of the data of the chunk. Total chunk length has 12 bytes more.*/ +unsigned lodepng_chunk_length(const unsigned char* chunk); + +/*puts the 4-byte type in null terminated string*/ +void lodepng_chunk_type(char type[5], const unsigned char* chunk); + +/*check if the type is the given type*/ +unsigned char lodepng_chunk_type_equals(const unsigned char* chunk, const char* type); + +/*0: it's one of the critical chunk types, 1: it's an ancillary chunk (see PNG standard)*/ +unsigned char lodepng_chunk_ancillary(const unsigned char* chunk); + +/*0: public, 1: private (see PNG standard)*/ +unsigned char lodepng_chunk_private(const unsigned char* chunk); + +/*0: the chunk is unsafe to copy, 1: the chunk is safe to copy (see PNG standard)*/ +unsigned char lodepng_chunk_safetocopy(const unsigned char* chunk); + +/*get pointer to the data of the chunk, where the input points to the header of the chunk*/ +unsigned char* lodepng_chunk_data(unsigned char* chunk); +const unsigned char* lodepng_chunk_data_const(const unsigned char* chunk); + +/*returns 0 if the crc is correct, 1 if it's incorrect (0 for OK as usual!)*/ +unsigned lodepng_chunk_check_crc(const unsigned char* chunk); + +/*generates the correct CRC from the data and puts it in the last 4 bytes of the chunk*/ +void lodepng_chunk_generate_crc(unsigned char* chunk); + +/*iterate to next chunks. don't use on IEND chunk, as there is no next chunk then*/ +unsigned char* lodepng_chunk_next(unsigned char* chunk); +const unsigned char* lodepng_chunk_next_const(const unsigned char* chunk); + +/* +Appends chunk to the data in out. The given chunk should already have its chunk header. +The out variable and outlength are updated to reflect the new reallocated buffer. +Returns error code (0 if it went ok) +*/ +unsigned lodepng_chunk_append(unsigned char** out, size_t* outlength, const unsigned char* chunk); + +/* +Appends new chunk to out. The chunk to append is given by giving its length, type +and data separately. The type is a 4-letter string. +The out variable and outlength are updated to reflect the new reallocated buffer. +Returne error code (0 if it went ok) +*/ +unsigned lodepng_chunk_create(unsigned char** out, size_t* outlength, unsigned length, + const char* type, const unsigned char* data); + + +/*Calculate CRC32 of buffer*/ +unsigned lodepng_crc32(const unsigned char* buf, size_t len); +#endif /*LODEPNG_COMPILE_PNG*/ + + +#ifdef LODEPNG_COMPILE_ZLIB +/* +This zlib part can be used independently to zlib compress and decompress a +buffer. It cannot be used to create gzip files however, and it only supports the +part of zlib that is required for PNG, it does not support dictionaries. +*/ + +#ifdef LODEPNG_COMPILE_DECODER +/*Inflate a buffer. Inflate is the decompression step of deflate. Out buffer must be freed after use.*/ +unsigned lodepng_inflate(unsigned char** out, size_t* outsize, + const unsigned char* in, size_t insize, + const LodePNGDecompressSettings* settings); + +/* +Decompresses Zlib data. Reallocates the out buffer and appends the data. The +data must be according to the zlib specification. +Either, *out must be NULL and *outsize must be 0, or, *out must be a valid +buffer and *outsize its size in bytes. out must be freed by user after usage. +*/ +unsigned lodepng_zlib_decompress(unsigned char** out, size_t* outsize, + const unsigned char* in, size_t insize, + const LodePNGDecompressSettings* settings); +#endif /*LODEPNG_COMPILE_DECODER*/ + +#ifdef LODEPNG_COMPILE_ENCODER +/* +Compresses data with Zlib. Reallocates the out buffer and appends the data. +Zlib adds a small header and trailer around the deflate data. +The data is output in the format of the zlib specification. +Either, *out must be NULL and *outsize must be 0, or, *out must be a valid +buffer and *outsize its size in bytes. out must be freed by user after usage. +*/ +unsigned lodepng_zlib_compress(unsigned char** out, size_t* outsize, + const unsigned char* in, size_t insize, + const LodePNGCompressSettings* settings); + +/* +Find length-limited Huffman code for given frequencies. This function is in the +public interface only for tests, it's used internally by lodepng_deflate. +*/ +unsigned lodepng_huffman_code_lengths(unsigned* lengths, const unsigned* frequencies, + size_t numcodes, unsigned maxbitlen); + +/*Compress a buffer with deflate. See RFC 1951. Out buffer must be freed after use.*/ +unsigned lodepng_deflate(unsigned char** out, size_t* outsize, + const unsigned char* in, size_t insize, + const LodePNGCompressSettings* settings); + +#endif /*LODEPNG_COMPILE_ENCODER*/ +#endif /*LODEPNG_COMPILE_ZLIB*/ + +#ifdef LODEPNG_COMPILE_DISK +/* +Load a file from disk into buffer. The function allocates the out buffer, and +after usage you should free it. +out: output parameter, contains pointer to loaded buffer. +outsize: output parameter, size of the allocated out buffer +filename: the path to the file to load +return value: error code (0 means ok) +*/ +unsigned lodepng_load_file(unsigned char** out, size_t* outsize, const char* filename); + +/* +Save a file from buffer to disk. Warning, if it exists, this function overwrites +the file without warning! +buffer: the buffer to write +buffersize: size of the buffer to write +filename: the path to the file to save to +return value: error code (0 means ok) +*/ +unsigned lodepng_save_file(const unsigned char* buffer, size_t buffersize, const char* filename); +#endif /*LODEPNG_COMPILE_DISK*/ + +#ifdef LODEPNG_COMPILE_CPP +//The LodePNG C++ wrapper uses std::vectors instead of manually allocated memory buffers. +namespace lodepng +{ +#ifdef LODEPNG_COMPILE_PNG +class State : public LodePNGState +{ + public: + State(); + State(const State& other); + virtual ~State(); + State& operator=(const State& other); +}; + +#ifdef LODEPNG_COMPILE_DECODER +//Same as other lodepng::decode, but using a State for more settings and information. +unsigned decode(std::vector& out, unsigned& w, unsigned& h, + State& state, + const unsigned char* in, size_t insize); +unsigned decode(std::vector& out, unsigned& w, unsigned& h, + State& state, + const std::vector& in); +#endif /*LODEPNG_COMPILE_DECODER*/ + +#ifdef LODEPNG_COMPILE_ENCODER +//Same as other lodepng::encode, but using a State for more settings and information. +unsigned encode(std::vector& out, + const unsigned char* in, unsigned w, unsigned h, + State& state); +unsigned encode(std::vector& out, + const std::vector& in, unsigned w, unsigned h, + State& state); +#endif /*LODEPNG_COMPILE_ENCODER*/ + +#ifdef LODEPNG_COMPILE_DISK +/* +Load a file from disk into an std::vector. If the vector is empty, then either +the file doesn't exist or is an empty file. +*/ +void load_file(std::vector& buffer, const std::string& filename); + +/* +Save the binary data in an std::vector to a file on disk. The file is overwritten +without warning. +*/ +void save_file(const std::vector& buffer, const std::string& filename); +#endif //LODEPNG_COMPILE_DISK +#endif //LODEPNG_COMPILE_PNG + +#ifdef LODEPNG_COMPILE_ZLIB +#ifdef LODEPNG_COMPILE_DECODER +//Zlib-decompress an unsigned char buffer +unsigned decompress(std::vector& out, const unsigned char* in, size_t insize, + const LodePNGDecompressSettings& settings = lodepng_default_decompress_settings); + +//Zlib-decompress an std::vector +unsigned decompress(std::vector& out, const std::vector& in, + const LodePNGDecompressSettings& settings = lodepng_default_decompress_settings); +#endif //LODEPNG_COMPILE_DECODER + +#ifdef LODEPNG_COMPILE_ENCODER +//Zlib-compress an unsigned char buffer +unsigned compress(std::vector& out, const unsigned char* in, size_t insize, + const LodePNGCompressSettings& settings = lodepng_default_compress_settings); + +//Zlib-compress an std::vector +unsigned compress(std::vector& out, const std::vector& in, + const LodePNGCompressSettings& settings = lodepng_default_compress_settings); +#endif //LODEPNG_COMPILE_ENCODER +#endif //LODEPNG_COMPILE_ZLIB +} //namespace lodepng +#endif /*LODEPNG_COMPILE_CPP*/ + +/* +TODO: +[.] test if there are no memory leaks or security exploits - done a lot but needs to be checked often +[.] check compatibility with vareous compilers - done but needs to be redone for every newer version +[X] converting color to 16-bit per channel types +[ ] read all public PNG chunk types (but never let the color profile and gamma ones touch RGB values) +[ ] make sure encoder generates no chunks with size > (2^31)-1 +[ ] partial decoding (stream processing) +[X] let the "isFullyOpaque" function check color keys and transparent palettes too +[X] better name for the variables "codes", "codesD", "codelengthcodes", "clcl" and "lldl" +[ ] don't stop decoding on errors like 69, 57, 58 (make warnings) +[ ] make option to choose if the raw image with non multiple of 8 bits per scanline should have padding bits or not +[ ] let the C++ wrapper catch exceptions coming from the standard library and return LodePNG error codes +*/ + +#endif /*LODEPNG_H inclusion guard*/ + +/* +LodePNG Documentation +--------------------- + +0. table of contents +-------------------- + + 1. about + 1.1. supported features + 1.2. features not supported + 2. C and C++ version + 3. security + 4. decoding + 5. encoding + 6. color conversions + 6.1. PNG color types + 6.2. color conversions + 6.3. padding bits + 6.4. A note about 16-bits per channel and endianness + 7. error values + 8. chunks and PNG editing + 9. compiler support + 10. examples + 10.1. decoder C++ example + 10.2. decoder C example + 11. changes + 12. contact information + + +1. about +-------- + +PNG is a file format to store raster images losslessly with good compression, +supporting different color types and alpha channel. + +LodePNG is a PNG codec according to the Portable Network Graphics (PNG) +Specification (Second Edition) - W3C Recommendation 10 November 2003. + +The specifications used are: + +*) Portable Network Graphics (PNG) Specification (Second Edition): + http://www.w3.org/TR/2003/REC-PNG-20031110 +*) RFC 1950 ZLIB Compressed Data Format version 3.3: + http://www.gzip.org/zlib/rfc-zlib.html +*) RFC 1951 DEFLATE Compressed Data Format Specification ver 1.3: + http://www.gzip.org/zlib/rfc-deflate.html + +The most recent version of LodePNG can currently be found at +http://lodev.org/lodepng/ + +LodePNG works both in C (ISO C90) and C++, with a C++ wrapper that adds +extra functionality. + +LodePNG exists out of two files: +-lodepng.h: the header file for both C and C++ +-lodepng.c(pp): give it the name lodepng.c or lodepng.cpp (or .cc) depending on your usage + +If you want to start using LodePNG right away without reading this doc, get the +examples from the LodePNG website to see how to use it in code, or check the +smaller examples in chapter 13 here. + +LodePNG is simple but only supports the basic requirements. To achieve +simplicity, the following design choices were made: There are no dependencies +on any external library. There are functions to decode and encode a PNG with +a single function call, and extended versions of these functions taking a +LodePNGState struct allowing to specify or get more information. By default +the colors of the raw image are always RGB or RGBA, no matter what color type +the PNG file uses. To read and write files, there are simple functions to +convert the files to/from buffers in memory. + +This all makes LodePNG suitable for loading textures in games, demos and small +programs, ... It's less suitable for full fledged image editors, loading PNGs +over network (it requires all the image data to be available before decoding can +begin), life-critical systems, ... + +1.1. supported features +----------------------- + +The following features are supported by the decoder: + +*) decoding of PNGs with any color type, bit depth and interlace mode, to a 24- or 32-bit color raw image, + or the same color type as the PNG +*) encoding of PNGs, from any raw image to 24- or 32-bit color, or the same color type as the raw image +*) Adam7 interlace and deinterlace for any color type +*) loading the image from harddisk or decoding it from a buffer from other sources than harddisk +*) support for alpha channels, including RGBA color model, translucent palettes and color keying +*) zlib decompression (inflate) +*) zlib compression (deflate) +*) CRC32 and ADLER32 checksums +*) handling of unknown chunks, allowing making a PNG editor that stores custom and unknown chunks. +*) the following chunks are supported (generated/interpreted) by both encoder and decoder: + IHDR: header information + PLTE: color palette + IDAT: pixel data + IEND: the final chunk + tRNS: transparency for palettized images + tEXt: textual information + zTXt: compressed textual information + iTXt: international textual information + bKGD: suggested background color + pHYs: physical dimensions + tIME: modification time + +1.2. features not supported +--------------------------- + +The following features are _not_ supported: + +*) some features needed to make a conformant PNG-Editor might be still missing. +*) partial loading/stream processing. All data must be available and is processed in one call. +*) The following public chunks are not supported but treated as unknown chunks by LodePNG + cHRM, gAMA, iCCP, sRGB, sBIT, hIST, sPLT + Some of these are not supported on purpose: LodePNG wants to provide the RGB values + stored in the pixels, not values modified by system dependent gamma or color models. + + +2. C and C++ version +-------------------- + +The C version uses buffers allocated with alloc that you need to free() +yourself. You need to use init and cleanup functions for each struct whenever +using a struct from the C version to avoid exploits and memory leaks. + +The C++ version has extra functions with std::vectors in the interface and the +lodepng::State class which is a LodePNGState with constructor and destructor. + +These files work without modification for both C and C++ compilers because all +the additional C++ code is in "#ifdef __cplusplus" blocks that make C-compilers +ignore it, and the C code is made to compile both with strict ISO C90 and C++. + +To use the C++ version, you need to rename the source file to lodepng.cpp +(instead of lodepng.c), and compile it with a C++ compiler. + +To use the C version, you need to rename the source file to lodepng.c (instead +of lodepng.cpp), and compile it with a C compiler. + + +3. Security +----------- + +Even if carefully designed, it's always possible that LodePNG contains possible +exploits. If you discover one, please let me know, and it will be fixed. + +When using LodePNG, care has to be taken with the C version of LodePNG, as well +as the C-style structs when working with C++. The following conventions are used +for all C-style structs: + +-if a struct has a corresponding init function, always call the init function when making a new one +-if a struct has a corresponding cleanup function, call it before the struct disappears to avoid memory leaks +-if a struct has a corresponding copy function, use the copy function instead of "=". + The destination must also be inited already. + + +4. Decoding +----------- + +Decoding converts a PNG compressed image to a raw pixel buffer. + +Most documentation on using the decoder is at its declarations in the header +above. For C, simple decoding can be done with functions such as +lodepng_decode32, and more advanced decoding can be done with the struct +LodePNGState and lodepng_decode. For C++, all decoding can be done with the +various lodepng::decode functions, and lodepng::State can be used for advanced +features. + +When using the LodePNGState, it uses the following fields for decoding: +*) LodePNGInfo info_png: it stores extra information about the PNG (the input) in here +*) LodePNGColorMode info_raw: here you can say what color mode of the raw image (the output) you want to get +*) LodePNGDecoderSettings decoder: you can specify a few extra settings for the decoder to use + +LodePNGInfo info_png +-------------------- + +After decoding, this contains extra information of the PNG image, except the actual +pixels, width and height because these are already gotten directly from the decoder +functions. + +It contains for example the original color type of the PNG image, text comments, +suggested background color, etc... More details about the LodePNGInfo struct are +at its declaration documentation. + +LodePNGColorMode info_raw +------------------------- + +When decoding, here you can specify which color type you want +the resulting raw image to be. If this is different from the colortype of the +PNG, then the decoder will automatically convert the result. This conversion +always works, except if you want it to convert a color PNG to greyscale or to +a palette with missing colors. + +By default, 32-bit color is used for the result. + +LodePNGDecoderSettings decoder +------------------------------ + +The settings can be used to ignore the errors created by invalid CRC and Adler32 +chunks, and to disable the decoding of tEXt chunks. + +There's also a setting color_convert, true by default. If false, no conversion +is done, the resulting data will be as it was in the PNG (after decompression) +and you'll have to puzzle the colors of the pixels together yourself using the +color type information in the LodePNGInfo. + + +5. Encoding +----------- + +Encoding converts a raw pixel buffer to a PNG compressed image. + +Most documentation on using the encoder is at its declarations in the header +above. For C, simple encoding can be done with functions such as +lodepng_encode32, and more advanced decoding can be done with the struct +LodePNGState and lodepng_encode. For C++, all encoding can be done with the +various lodepng::encode functions, and lodepng::State can be used for advanced +features. + +Like the decoder, the encoder can also give errors. However it gives less errors +since the encoder input is trusted, the decoder input (a PNG image that could +be forged by anyone) is not trusted. + +When using the LodePNGState, it uses the following fields for encoding: +*) LodePNGInfo info_png: here you specify how you want the PNG (the output) to be. +*) LodePNGColorMode info_raw: here you say what color type of the raw image (the input) has +*) LodePNGEncoderSettings encoder: you can specify a few settings for the encoder to use + +LodePNGInfo info_png +-------------------- + +When encoding, you use this the opposite way as when decoding: for encoding, +you fill in the values you want the PNG to have before encoding. By default it's +not needed to specify a color type for the PNG since it's automatically chosen, +but it's possible to choose it yourself given the right settings. + +The encoder will not always exactly match the LodePNGInfo struct you give, +it tries as close as possible. Some things are ignored by the encoder. The +encoder uses, for example, the following settings from it when applicable: +colortype and bitdepth, text chunks, time chunk, the color key, the palette, the +background color, the interlace method, unknown chunks, ... + +When encoding to a PNG with colortype 3, the encoder will generate a PLTE chunk. +If the palette contains any colors for which the alpha channel is not 255 (so +there are translucent colors in the palette), it'll add a tRNS chunk. + +LodePNGColorMode info_raw +------------------------- + +You specify the color type of the raw image that you give to the input here, +including a possible transparent color key and palette you happen to be using in +your raw image data. + +By default, 32-bit color is assumed, meaning your input has to be in RGBA +format with 4 bytes (unsigned chars) per pixel. + +LodePNGEncoderSettings encoder +------------------------------ + +The following settings are supported (some are in sub-structs): +*) auto_convert: when this option is enabled, the encoder will +automatically choose the smallest possible color mode (including color key) that +can encode the colors of all pixels without information loss. +*) btype: the block type for LZ77. 0 = uncompressed, 1 = fixed huffman tree, + 2 = dynamic huffman tree (best compression). Should be 2 for proper + compression. +*) use_lz77: whether or not to use LZ77 for compressed block types. Should be + true for proper compression. +*) windowsize: the window size used by the LZ77 encoder (1 - 32768). Has value + 2048 by default, but can be set to 32768 for better, but slow, compression. +*) force_palette: if colortype is 2 or 6, you can make the encoder write a PLTE + chunk if force_palette is true. This can used as suggested palette to convert + to by viewers that don't support more than 256 colors (if those still exist) +*) add_id: add text chunk "Encoder: LodePNG " to the image. +*) text_compression: default 1. If 1, it'll store texts as zTXt instead of tEXt chunks. + zTXt chunks use zlib compression on the text. This gives a smaller result on + large texts but a larger result on small texts (such as a single program name). + It's all tEXt or all zTXt though, there's no separate setting per text yet. + + +6. color conversions +-------------------- + +An important thing to note about LodePNG, is that the color type of the PNG, and +the color type of the raw image, are completely independent. By default, when +you decode a PNG, you get the result as a raw image in the color type you want, +no matter whether the PNG was encoded with a palette, greyscale or RGBA color. +And if you encode an image, by default LodePNG will automatically choose the PNG +color type that gives good compression based on the values of colors and amount +of colors in the image. It can be configured to let you control it instead as +well, though. + +To be able to do this, LodePNG does conversions from one color mode to another. +It can convert from almost any color type to any other color type, except the +following conversions: RGB to greyscale is not supported, and converting to a +palette when the palette doesn't have a required color is not supported. This is +not supported on purpose: this is information loss which requires a color +reduction algorithm that is beyong the scope of a PNG encoder (yes, RGB to grey +is easy, but there are multiple ways if you want to give some channels more +weight). + +By default, when decoding, you get the raw image in 32-bit RGBA or 24-bit RGB +color, no matter what color type the PNG has. And by default when encoding, +LodePNG automatically picks the best color model for the output PNG, and expects +the input image to be 32-bit RGBA or 24-bit RGB. So, unless you want to control +the color format of the images yourself, you can skip this chapter. + +6.1. PNG color types +-------------------- + +A PNG image can have many color types, ranging from 1-bit color to 64-bit color, +as well as palettized color modes. After the zlib decompression and unfiltering +in the PNG image is done, the raw pixel data will have that color type and thus +a certain amount of bits per pixel. If you want the output raw image after +decoding to have another color type, a conversion is done by LodePNG. + +The PNG specification gives the following color types: + +0: greyscale, bit depths 1, 2, 4, 8, 16 +2: RGB, bit depths 8 and 16 +3: palette, bit depths 1, 2, 4 and 8 +4: greyscale with alpha, bit depths 8 and 16 +6: RGBA, bit depths 8 and 16 + +Bit depth is the amount of bits per pixel per color channel. So the total amount +of bits per pixel is: amount of channels * bitdepth. + +6.2. color conversions +---------------------- + +As explained in the sections about the encoder and decoder, you can specify +color types and bit depths in info_png and info_raw to change the default +behaviour. + +If, when decoding, you want the raw image to be something else than the default, +you need to set the color type and bit depth you want in the LodePNGColorMode, +or the parameters colortype and bitdepth of the simple decoding function. + +If, when encoding, you use another color type than the default in the raw input +image, you need to specify its color type and bit depth in the LodePNGColorMode +of the raw image, or use the parameters colortype and bitdepth of the simple +encoding function. + +If, when encoding, you don't want LodePNG to choose the output PNG color type +but control it yourself, you need to set auto_convert in the encoder settings +to false, and specify the color type you want in the LodePNGInfo of the +encoder (including palette: it can generate a palette if auto_convert is true, +otherwise not). + +If the input and output color type differ (whether user chosen or auto chosen), +LodePNG will do a color conversion, which follows the rules below, and may +sometimes result in an error. + +To avoid some confusion: +-the decoder converts from PNG to raw image +-the encoder converts from raw image to PNG +-the colortype and bitdepth in LodePNGColorMode info_raw, are those of the raw image +-the colortype and bitdepth in the color field of LodePNGInfo info_png, are those of the PNG +-when encoding, the color type in LodePNGInfo is ignored if auto_convert + is enabled, it is automatically generated instead +-when decoding, the color type in LodePNGInfo is set by the decoder to that of the original + PNG image, but it can be ignored since the raw image has the color type you requested instead +-if the color type of the LodePNGColorMode and PNG image aren't the same, a conversion + between the color types is done if the color types are supported. If it is not + supported, an error is returned. If the types are the same, no conversion is done. +-even though some conversions aren't supported, LodePNG supports loading PNGs from any + colortype and saving PNGs to any colortype, sometimes it just requires preparing + the raw image correctly before encoding. +-both encoder and decoder use the same color converter. + +Non supported color conversions: +-color to greyscale: no error is thrown, but the result will look ugly because +only the red channel is taken +-anything to palette when that palette does not have that color in it: in this +case an error is thrown + +Supported color conversions: +-anything to 8-bit RGB, 8-bit RGBA, 16-bit RGB, 16-bit RGBA +-any grey or grey+alpha, to grey or grey+alpha +-anything to a palette, as long as the palette has the requested colors in it +-removing alpha channel +-higher to smaller bitdepth, and vice versa + +If you want no color conversion to be done (e.g. for speed or control): +-In the encoder, you can make it save a PNG with any color type by giving the +raw color mode and LodePNGInfo the same color mode, and setting auto_convert to +false. +-In the decoder, you can make it store the pixel data in the same color type +as the PNG has, by setting the color_convert setting to false. Settings in +info_raw are then ignored. + +The function lodepng_convert does the color conversion. It is available in the +interface but normally isn't needed since the encoder and decoder already call +it. + +6.3. padding bits +----------------- + +In the PNG file format, if a less than 8-bit per pixel color type is used and the scanlines +have a bit amount that isn't a multiple of 8, then padding bits are used so that each +scanline starts at a fresh byte. But that is NOT true for the LodePNG raw input and output. +The raw input image you give to the encoder, and the raw output image you get from the decoder +will NOT have these padding bits, e.g. in the case of a 1-bit image with a width +of 7 pixels, the first pixel of the second scanline will the the 8th bit of the first byte, +not the first bit of a new byte. + +6.4. A note about 16-bits per channel and endianness +---------------------------------------------------- + +LodePNG uses unsigned char arrays for 16-bit per channel colors too, just like +for any other color format. The 16-bit values are stored in big endian (most +significant byte first) in these arrays. This is the opposite order of the +little endian used by x86 CPU's. + +LodePNG always uses big endian because the PNG file format does so internally. +Conversions to other formats than PNG uses internally are not supported by +LodePNG on purpose, there are myriads of formats, including endianness of 16-bit +colors, the order in which you store R, G, B and A, and so on. Supporting and +converting to/from all that is outside the scope of LodePNG. + +This may mean that, depending on your use case, you may want to convert the big +endian output of LodePNG to little endian with a for loop. This is certainly not +always needed, many applications and libraries support big endian 16-bit colors +anyway, but it means you cannot simply cast the unsigned char* buffer to an +unsigned short* buffer on x86 CPUs. + + +7. error values +--------------- + +All functions in LodePNG that return an error code, return 0 if everything went +OK, or a non-zero code if there was an error. + +The meaning of the LodePNG error values can be retrieved with the function +lodepng_error_text: given the numerical error code, it returns a description +of the error in English as a string. + +Check the implementation of lodepng_error_text to see the meaning of each code. + + +8. chunks and PNG editing +------------------------- + +If you want to add extra chunks to a PNG you encode, or use LodePNG for a PNG +editor that should follow the rules about handling of unknown chunks, or if your +program is able to read other types of chunks than the ones handled by LodePNG, +then that's possible with the chunk functions of LodePNG. + +A PNG chunk has the following layout: + +4 bytes length +4 bytes type name +length bytes data +4 bytes CRC + +8.1. iterating through chunks +----------------------------- + +If you have a buffer containing the PNG image data, then the first chunk (the +IHDR chunk) starts at byte number 8 of that buffer. The first 8 bytes are the +signature of the PNG and are not part of a chunk. But if you start at byte 8 +then you have a chunk, and can check the following things of it. + +NOTE: none of these functions check for memory buffer boundaries. To avoid +exploits, always make sure the buffer contains all the data of the chunks. +When using lodepng_chunk_next, make sure the returned value is within the +allocated memory. + +unsigned lodepng_chunk_length(const unsigned char* chunk): + +Get the length of the chunk's data. The total chunk length is this length + 12. + +void lodepng_chunk_type(char type[5], const unsigned char* chunk): +unsigned char lodepng_chunk_type_equals(const unsigned char* chunk, const char* type): + +Get the type of the chunk or compare if it's a certain type + +unsigned char lodepng_chunk_critical(const unsigned char* chunk): +unsigned char lodepng_chunk_private(const unsigned char* chunk): +unsigned char lodepng_chunk_safetocopy(const unsigned char* chunk): + +Check if the chunk is critical in the PNG standard (only IHDR, PLTE, IDAT and IEND are). +Check if the chunk is private (public chunks are part of the standard, private ones not). +Check if the chunk is safe to copy. If it's not, then, when modifying data in a critical +chunk, unsafe to copy chunks of the old image may NOT be saved in the new one if your +program doesn't handle that type of unknown chunk. + +unsigned char* lodepng_chunk_data(unsigned char* chunk): +const unsigned char* lodepng_chunk_data_const(const unsigned char* chunk): + +Get a pointer to the start of the data of the chunk. + +unsigned lodepng_chunk_check_crc(const unsigned char* chunk): +void lodepng_chunk_generate_crc(unsigned char* chunk): + +Check if the crc is correct or generate a correct one. + +unsigned char* lodepng_chunk_next(unsigned char* chunk): +const unsigned char* lodepng_chunk_next_const(const unsigned char* chunk): + +Iterate to the next chunk. This works if you have a buffer with consecutive chunks. Note that these +functions do no boundary checking of the allocated data whatsoever, so make sure there is enough +data available in the buffer to be able to go to the next chunk. + +unsigned lodepng_chunk_append(unsigned char** out, size_t* outlength, const unsigned char* chunk): +unsigned lodepng_chunk_create(unsigned char** out, size_t* outlength, unsigned length, + const char* type, const unsigned char* data): + +These functions are used to create new chunks that are appended to the data in *out that has +length *outlength. The append function appends an existing chunk to the new data. The create +function creates a new chunk with the given parameters and appends it. Type is the 4-letter +name of the chunk. + +8.2. chunks in info_png +----------------------- + +The LodePNGInfo struct contains fields with the unknown chunk in it. It has 3 +buffers (each with size) to contain 3 types of unknown chunks: +the ones that come before the PLTE chunk, the ones that come between the PLTE +and the IDAT chunks, and the ones that come after the IDAT chunks. +It's necessary to make the distionction between these 3 cases because the PNG +standard forces to keep the ordering of unknown chunks compared to the critical +chunks, but does not force any other ordering rules. + +info_png.unknown_chunks_data[0] is the chunks before PLTE +info_png.unknown_chunks_data[1] is the chunks after PLTE, before IDAT +info_png.unknown_chunks_data[2] is the chunks after IDAT + +The chunks in these 3 buffers can be iterated through and read by using the same +way described in the previous subchapter. + +When using the decoder to decode a PNG, you can make it store all unknown chunks +if you set the option settings.remember_unknown_chunks to 1. By default, this +option is off (0). + +The encoder will always encode unknown chunks that are stored in the info_png. +If you need it to add a particular chunk that isn't known by LodePNG, you can +use lodepng_chunk_append or lodepng_chunk_create to the chunk data in +info_png.unknown_chunks_data[x]. + +Chunks that are known by LodePNG should not be added in that way. E.g. to make +LodePNG add a bKGD chunk, set background_defined to true and add the correct +parameters there instead. + + +9. compiler support +------------------- + +No libraries other than the current standard C library are needed to compile +LodePNG. For the C++ version, only the standard C++ library is needed on top. +Add the files lodepng.c(pp) and lodepng.h to your project, include +lodepng.h where needed, and your program can read/write PNG files. + +It is compatible with C90 and up, and C++03 and up. + +If performance is important, use optimization when compiling! For both the +encoder and decoder, this makes a large difference. + +Make sure that LodePNG is compiled with the same compiler of the same version +and with the same settings as the rest of the program, or the interfaces with +std::vectors and std::strings in C++ can be incompatible. + +CHAR_BITS must be 8 or higher, because LodePNG uses unsigned chars for octets. + +*) gcc and g++ + +LodePNG is developed in gcc so this compiler is natively supported. It gives no +warnings with compiler options "-Wall -Wextra -pedantic -ansi", with gcc and g++ +version 4.7.1 on Linux, 32-bit and 64-bit. + +*) Clang + +Fully supported and warning-free. + +*) Mingw + +The Mingw compiler (a port of gcc for Windows) should be fully supported by +LodePNG. + +*) Visual Studio and Visual C++ Express Edition + +LodePNG should be warning-free with warning level W4. Two warnings were disabled +with pragmas though: warning 4244 about implicit conversions, and warning 4996 +where it wants to use a non-standard function fopen_s instead of the standard C +fopen. + +Visual Studio may want "stdafx.h" files to be included in each source file and +give an error "unexpected end of file while looking for precompiled header". +This is not standard C++ and will not be added to the stock LodePNG. You can +disable it for lodepng.cpp only by right clicking it, Properties, C/C++, +Precompiled Headers, and set it to Not Using Precompiled Headers there. + +NOTE: Modern versions of VS should be fully supported, but old versions, e.g. +VS6, are not guaranteed to work. + +*) Compilers on Macintosh + +LodePNG has been reported to work both with gcc and LLVM for Macintosh, both for +C and C++. + +*) Other Compilers + +If you encounter problems on any compilers, feel free to let me know and I may +try to fix it if the compiler is modern and standards complient. + + +10. examples +------------ + +This decoder example shows the most basic usage of LodePNG. More complex +examples can be found on the LodePNG website. + +10.1. decoder C++ example +------------------------- + +#include "lodepng.h" +#include + +int main(int argc, char *argv[]) +{ + const char* filename = argc > 1 ? argv[1] : "test.png"; + + //load and decode + std::vector image; + unsigned width, height; + unsigned error = lodepng::decode(image, width, height, filename); + + //if there's an error, display it + if(error) std::cout << "decoder error " << error << ": " << lodepng_error_text(error) << std::endl; + + //the pixels are now in the vector "image", 4 bytes per pixel, ordered RGBARGBA..., use it as texture, draw it, ... +} + +10.2. decoder C example +----------------------- + +#include "lodepng.h" + +int main(int argc, char *argv[]) +{ + unsigned error; + unsigned char* image; + size_t width, height; + const char* filename = argc > 1 ? argv[1] : "test.png"; + + error = lodepng_decode32_file(&image, &width, &height, filename); + + if(error) printf("decoder error %u: %s\n", error, lodepng_error_text(error)); + + / * use image here * / + + free(image); + return 0; +} + + +11. changes +----------- + +The version number of LodePNG is the date of the change given in the format +yyyymmdd. + +Some changes aren't backwards compatible. Those are indicated with a (!) +symbol. + +*) 23 aug 2014: Reduced needless memory usage of decoder. +*) 28 jun 2014: Removed fix_png setting, always support palette OOB for + simplicity. Made ColorProfile public. +*) 09 jun 2014: Faster encoder by fixing hash bug and more zeros optimization. +*) 22 dec 2013: Power of two windowsize required for optimization. +*) 15 apr 2013: Fixed bug with LAC_ALPHA and color key. +*) 25 mar 2013: Added an optional feature to ignore some PNG errors (fix_png). +*) 11 mar 2013 (!): Bugfix with custom free. Changed from "my" to "lodepng_" + prefix for the custom allocators and made it possible with a new #define to + use custom ones in your project without needing to change lodepng's code. +*) 28 jan 2013: Bugfix with color key. +*) 27 okt 2012: Tweaks in text chunk keyword length error handling. +*) 8 okt 2012 (!): Added new filter strategy (entropy) and new auto color mode. + (no palette). Better deflate tree encoding. New compression tweak settings. + Faster color conversions while decoding. Some internal cleanups. +*) 23 sep 2012: Reduced warnings in Visual Studio a little bit. +*) 1 sep 2012 (!): Removed #define's for giving custom (de)compression functions + and made it work with function pointers instead. +*) 23 jun 2012: Added more filter strategies. Made it easier to use custom alloc + and free functions and toggle #defines from compiler flags. Small fixes. +*) 6 may 2012 (!): Made plugging in custom zlib/deflate functions more flexible. +*) 22 apr 2012 (!): Made interface more consistent, renaming a lot. Removed + redundant C++ codec classes. Reduced amount of structs. Everything changed, + but it is cleaner now imho and functionality remains the same. Also fixed + several bugs and shrinked the implementation code. Made new samples. +*) 6 nov 2011 (!): By default, the encoder now automatically chooses the best + PNG color model and bit depth, based on the amount and type of colors of the + raw image. For this, autoLeaveOutAlphaChannel replaced by auto_choose_color. +*) 9 okt 2011: simpler hash chain implementation for the encoder. +*) 8 sep 2011: lz77 encoder lazy matching instead of greedy matching. +*) 23 aug 2011: tweaked the zlib compression parameters after benchmarking. + A bug with the PNG filtertype heuristic was fixed, so that it chooses much + better ones (it's quite significant). A setting to do an experimental, slow, + brute force search for PNG filter types is added. +*) 17 aug 2011 (!): changed some C zlib related function names. +*) 16 aug 2011: made the code less wide (max 120 characters per line). +*) 17 apr 2011: code cleanup. Bugfixes. Convert low to 16-bit per sample colors. +*) 21 feb 2011: fixed compiling for C90. Fixed compiling with sections disabled. +*) 11 dec 2010: encoding is made faster, based on suggestion by Peter Eastman + to optimize long sequences of zeros. +*) 13 nov 2010: added LodePNG_InfoColor_hasPaletteAlpha and + LodePNG_InfoColor_canHaveAlpha functions for convenience. +*) 7 nov 2010: added LodePNG_error_text function to get error code description. +*) 30 okt 2010: made decoding slightly faster +*) 26 okt 2010: (!) changed some C function and struct names (more consistent). + Reorganized the documentation and the declaration order in the header. +*) 08 aug 2010: only changed some comments and external samples. +*) 05 jul 2010: fixed bug thanks to warnings in the new gcc version. +*) 14 mar 2010: fixed bug where too much memory was allocated for char buffers. +*) 02 sep 2008: fixed bug where it could create empty tree that linux apps could + read by ignoring the problem but windows apps couldn't. +*) 06 jun 2008: added more error checks for out of memory cases. +*) 26 apr 2008: added a few more checks here and there to ensure more safety. +*) 06 mar 2008: crash with encoding of strings fixed +*) 02 feb 2008: support for international text chunks added (iTXt) +*) 23 jan 2008: small cleanups, and #defines to divide code in sections +*) 20 jan 2008: support for unknown chunks allowing using LodePNG for an editor. +*) 18 jan 2008: support for tIME and pHYs chunks added to encoder and decoder. +*) 17 jan 2008: ability to encode and decode compressed zTXt chunks added + Also vareous fixes, such as in the deflate and the padding bits code. +*) 13 jan 2008: Added ability to encode Adam7-interlaced images. Improved + filtering code of encoder. +*) 07 jan 2008: (!) changed LodePNG to use ISO C90 instead of C++. A + C++ wrapper around this provides an interface almost identical to before. + Having LodePNG be pure ISO C90 makes it more portable. The C and C++ code + are together in these files but it works both for C and C++ compilers. +*) 29 dec 2007: (!) changed most integer types to unsigned int + other tweaks +*) 30 aug 2007: bug fixed which makes this Borland C++ compatible +*) 09 aug 2007: some VS2005 warnings removed again +*) 21 jul 2007: deflate code placed in new namespace separate from zlib code +*) 08 jun 2007: fixed bug with 2- and 4-bit color, and small interlaced images +*) 04 jun 2007: improved support for Visual Studio 2005: crash with accessing + invalid std::vector element [0] fixed, and level 3 and 4 warnings removed +*) 02 jun 2007: made the encoder add a tag with version by default +*) 27 may 2007: zlib and png code separated (but still in the same file), + simple encoder/decoder functions added for more simple usage cases +*) 19 may 2007: minor fixes, some code cleaning, new error added (error 69), + moved some examples from here to lodepng_examples.cpp +*) 12 may 2007: palette decoding bug fixed +*) 24 apr 2007: changed the license from BSD to the zlib license +*) 11 mar 2007: very simple addition: ability to encode bKGD chunks. +*) 04 mar 2007: (!) tEXt chunk related fixes, and support for encoding + palettized PNG images. Plus little interface change with palette and texts. +*) 03 mar 2007: Made it encode dynamic Huffman shorter with repeat codes. + Fixed a bug where the end code of a block had length 0 in the Huffman tree. +*) 26 feb 2007: Huffman compression with dynamic trees (BTYPE 2) now implemented + and supported by the encoder, resulting in smaller PNGs at the output. +*) 27 jan 2007: Made the Adler-32 test faster so that a timewaste is gone. +*) 24 jan 2007: gave encoder an error interface. Added color conversion from any + greyscale type to 8-bit greyscale with or without alpha. +*) 21 jan 2007: (!) Totally changed the interface. It allows more color types + to convert to and is more uniform. See the manual for how it works now. +*) 07 jan 2007: Some cleanup & fixes, and a few changes over the last days: + encode/decode custom tEXt chunks, separate classes for zlib & deflate, and + at last made the decoder give errors for incorrect Adler32 or Crc. +*) 01 jan 2007: Fixed bug with encoding PNGs with less than 8 bits per channel. +*) 29 dec 2006: Added support for encoding images without alpha channel, and + cleaned out code as well as making certain parts faster. +*) 28 dec 2006: Added "Settings" to the encoder. +*) 26 dec 2006: The encoder now does LZ77 encoding and produces much smaller files now. + Removed some code duplication in the decoder. Fixed little bug in an example. +*) 09 dec 2006: (!) Placed output parameters of public functions as first parameter. + Fixed a bug of the decoder with 16-bit per color. +*) 15 okt 2006: Changed documentation structure +*) 09 okt 2006: Encoder class added. It encodes a valid PNG image from the + given image buffer, however for now it's not compressed. +*) 08 sep 2006: (!) Changed to interface with a Decoder class +*) 30 jul 2006: (!) LodePNG_InfoPng , width and height are now retrieved in different + way. Renamed decodePNG to decodePNGGeneric. +*) 29 jul 2006: (!) Changed the interface: image info is now returned as a + struct of type LodePNG::LodePNG_Info, instead of a vector, which was a bit clumsy. +*) 28 jul 2006: Cleaned the code and added new error checks. + Corrected terminology "deflate" into "inflate". +*) 23 jun 2006: Added SDL example in the documentation in the header, this + example allows easy debugging by displaying the PNG and its transparency. +*) 22 jun 2006: (!) Changed way to obtain error value. Added + loadFile function for convenience. Made decodePNG32 faster. +*) 21 jun 2006: (!) Changed type of info vector to unsigned. + Changed position of palette in info vector. Fixed an important bug that + happened on PNGs with an uncompressed block. +*) 16 jun 2006: Internally changed unsigned into unsigned where + needed, and performed some optimizations. +*) 07 jun 2006: (!) Renamed functions to decodePNG and placed them + in LodePNG namespace. Changed the order of the parameters. Rewrote the + documentation in the header. Renamed files to lodepng.cpp and lodepng.h +*) 22 apr 2006: Optimized and improved some code +*) 07 sep 2005: (!) Changed to std::vector interface +*) 12 aug 2005: Initial release (C++, decoder only) + + +12. contact information +----------------------- + +Feel free to contact me with suggestions, problems, comments, ... concerning +LodePNG. If you encounter a PNG image that doesn't work properly with this +decoder, feel free to send it and I'll use it to find and fix the problem. + +My email address is (puzzle the account and domain together with an @ symbol): +Domain: gmail dot com. +Account: lode dot vandevenne. + + +Copyright (c) 2005-2014 Lode Vandevenne +*/ diff --git a/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp b/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp new file mode 100644 index 000000000..d148a5d84 --- /dev/null +++ b/examples/ThirdPartyLibs/openvr/samples/shared/pathtools.cpp @@ -0,0 +1,560 @@ +//========= Copyright Valve Corporation ============// +#include "pathtools.h" +//#include "hmdplatform_private.h" +//#include "vrcommon/strtools.h" + +#if defined( _WIN32) +#include +#include +#include +#include +#elif defined OSX +#include +#include +#include "osxfilebridge.h" +#define _S_IFDIR S_IFDIR // really from tier0/platform.h which we dont have yet +#define _MAX_PATH MAX_PATH // yet another form of _PATH define we use +#elif defined(LINUX) +#include +#include +#endif + +#include + +#include + +/** Returns the path (including filename) to the current executable */ +std::string Path_GetExecutablePath() +{ + bool bSuccess = false; + char rchPath[ 1024 ]; + size_t nBuff = sizeof(rchPath); +#if defined( _WIN32 ) + bSuccess = ::GetModuleFileNameA(NULL, rchPath, (DWORD)nBuff) > 0; +#elif defined OSX + uint32_t _nBuff = nBuff; + bSuccess = _NSGetExecutablePath(rchPath, &_nBuff) == 0; + rchPath[nBuff-1] = '\0'; +#elif defined LINUX + ssize_t nRead = readlink("/proc/self/exe", rchPath, nBuff-1 ); + if ( nRead != -1 ) + { + rchPath[ nRead ] = 0; + bSuccess = true; + } + else + { + rchPath[ 0 ] = '\0'; + } +#else + AssertMsg( false, "Implement Plat_GetExecutablePath" ); +#endif + + if( bSuccess ) + return rchPath; + else + return ""; +} + +/** Returns the path of the current working directory */ +std::string Path_GetWorkingDirectory() +{ + std::string sPath; + char buf[ 1024 ]; +#if defined( _WIN32 ) + sPath = _getcwd( buf, sizeof( buf ) ); +#else + sPath = getcwd( buf, sizeof( buf ) ); +#endif + return sPath; +} + +/** Sets the path of the current working directory. Returns true if this was successful. */ +bool Path_SetWorkingDirectory( const std::string & sPath ) +{ + bool bSuccess; +#if defined( _WIN32 ) + bSuccess = 0 == _chdir( sPath.c_str() ); +#else + bSuccess = 0 == chdir( sPath.c_str() ); +#endif + return bSuccess; +} + +std::string Path_GetModulePath() +{ +#if defined( _WIN32 ) + char path[32768]; + HMODULE hm = NULL; + + if (!GetModuleHandleExA(GET_MODULE_HANDLE_EX_FLAG_FROM_ADDRESS, + (LPCSTR) &Path_GetModulePath, + &hm)) + { + int ret = GetLastError(); + fprintf(stderr, "GetModuleHandle returned %d\n", ret); + return ""; + } + GetModuleFileNameA(hm, path, sizeof(path)); + FreeLibrary( hm ); + return path; +#else + Dl_info dl_info; + dladdr((void *)Path_GetModulePath, &dl_info); + return dl_info.dli_fname; +#endif +} + +/** Returns the specified path without its filename */ +std::string Path_StripFilename( const std::string & sPath, char slash ) +{ + if( slash == 0 ) + slash = Path_GetSlash(); + + std::string::size_type n = sPath.find_last_of( slash ); + if( n == std::string::npos ) + return sPath; + else + return std::string( sPath.begin(), sPath.begin() + n ); +} + +/** returns just the filename from the provided full or relative path. */ +std::string Path_StripDirectory( const std::string & sPath, char slash ) +{ + if( slash == 0 ) + slash = Path_GetSlash(); + + std::string::size_type n = sPath.find_last_of( slash ); + if( n == std::string::npos ) + return sPath; + else + return std::string( sPath.begin() + n + 1, sPath.end() ); +} + +/** returns just the filename with no extension of the provided filename. +* If there is a path the path is left intact. */ +std::string Path_StripExtension( const std::string & sPath ) +{ + for( std::string::const_reverse_iterator i = sPath.rbegin(); i != sPath.rend(); i++ ) + { + if( *i == '.' ) + { + return std::string( sPath.begin(), i.base() - 1 ); + } + + // if we find a slash there is no extension + if( *i == '\\' || *i == '/' ) + break; + } + + // we didn't find an extension + return sPath; +} + + +bool Path_IsAbsolute( const std::string & sPath ) +{ + if( sPath.empty() ) + return false; + + if( sPath.find( ':' ) != std::string::npos ) + return true; + + if( sPath[0] == '\\' || sPath[0] == '/' ) + return true; + + return false; +} + + +/** Makes an absolute path from a relative path and a base path */ +std::string Path_MakeAbsolute( const std::string & sRelativePath, const std::string & sBasePath, char slash ) +{ + if( slash == 0 ) + slash = Path_GetSlash(); + + if( Path_IsAbsolute( sRelativePath ) ) + return sRelativePath; + else + { + if( !Path_IsAbsolute( sBasePath ) ) + return ""; + + std::string sCompacted = Path_Compact( Path_Join( sBasePath, sRelativePath, slash ), slash ); + if( Path_IsAbsolute( sCompacted ) ) + return sCompacted; + else + return ""; + } +} + + +/** Fixes the directory separators for the current platform */ +std::string Path_FixSlashes( const std::string & sPath, char slash ) +{ + if( slash == 0 ) + slash = Path_GetSlash(); + + std::string sFixed = sPath; + for( std::string::iterator i = sFixed.begin(); i != sFixed.end(); i++ ) + { + if( *i == '/' || *i == '\\' ) + *i = slash; + } + + return sFixed; +} + + +char Path_GetSlash() +{ +#if defined(_WIN32) + return '\\'; +#else + return '/'; +#endif +} + +/** Jams two paths together with the right kind of slash */ +std::string Path_Join( const std::string & first, const std::string & second, char slash ) +{ + if( slash == 0 ) + slash = Path_GetSlash(); + + // only insert a slash if we don't already have one + std::string::size_type nLen = first.length(); +#if defined(_WIN32) + if( first.back() == '\\' || first.back() == '/' ) + nLen--; +#else + char last_char = first[first.length()-1]; + if (last_char == '\\' || last_char == '/') + nLen--; +#endif + + return first.substr( 0, nLen ) + std::string( 1, slash ) + second; +} + + +std::string Path_Join( const std::string & first, const std::string & second, const std::string & third, char slash ) +{ + return Path_Join( Path_Join( first, second, slash ), third, slash ); +} + +std::string Path_Join( const std::string & first, const std::string & second, const std::string & third, const std::string &fourth, char slash ) +{ + return Path_Join( Path_Join( Path_Join( first, second, slash ), third, slash ), fourth, slash ); +} + +std::string Path_Join( + const std::string & first, + const std::string & second, + const std::string & third, + const std::string & fourth, + const std::string & fifth, + char slash ) +{ + return Path_Join( Path_Join( Path_Join( Path_Join( first, second, slash ), third, slash ), fourth, slash ), fifth, slash ); +} + +/** Removes redundant

M%^DnC5Vp1g6eMEX>y0fJttoi;Om1TtIcC{_Vwcg~qHBoK=?|-`)<>10rQcjHT3=ZbvLSSBSwz(gdLU0` zS5?V?AZZO==0mj0Xmd+^WuT&()uUcVKeM8$IFJOhe$?yeFLFyQjbe`>2=%xa9GdPZ z!SxfHaqpU4zC8S1om*jJEyb2ew$8*unurd z#4?17`%qg+m8ZgCtK@ckxzkor#o~wDXHTBYy)^%5tlY5L2Gr#4UE$VsU?tK}p!Ekf zca?3ej8VFNwQ~iXs=m;`tvwafR!+BOTdgnP@P)O8Qey#O@?=SA8pd+NW-CT_ZE=mQ zxPrRpSZ~w&e9Az~C#``(ixn12APVye5wEwo^;I2P)$)~OTn#}?ksP49+iGOWD#5O) zW*J159ZFf$Sx%R;qFP(T5kt_Ie8?|z+NuLHevA*S)0EfnMQ(6e0HRa0tt}_(Nd?&- zSkkgFm5RKCw`xyirJklK0!>oDQd(tf%%>Ngfw0nmy6B9OH7Tr~+iT1YW8y znoUWOvNHw}NpomLNT1%=#$PFmN<07?S`K11K@uZYjL1^6PG~fWR3!IIVdXFxSQn`x zbu(1QOY{{Hv2H<$r@~WX%QG@v*8HSyNt(3;>FF#fuGG@VbfS{HkmU}k$a*>=bUneQ zWK=flk=9VfgQO`!zp{#2%#y6btS1#BLeFSudSD((Q3|W1%vrKZOqr}zp-4YQ%x+rJ za=Hq!K<|$t!ZzvE$W&g_r20gL7fPGf_HUH#Py&^z6shZ~uAT$8APNn)v z`ck95O86{qeiePAKaI$f*!EA>s_&_%ce0eax&D=w)154GJBwG-^U#F_)}Cb*R`1)* z>z~@vrg@DzH?YL1FrtZ6zY91?&seRNxKGjxtox^DXPbgMSrwSo1#F7FnCkGsdJ)RDwnQlaj54+O>BSL;vfj%DKt0qbr1qMlzapri9C1a!OTHtXnC{3pu z4YSSAA=W?_&#h;KU4~9Tfo{bptmt~IGaI)ovC4o|Wql98WOzhavhu9=*;>~hrf5#1 z=!H7|FtxCBik{Z-n^er$Jp@li{&Q}v2k}n{7m7UB2$5Zp8>*}?85o;js^>bv@ z2+O}%_Ue9_iOnuQsXhrFa7QBE=`83Po^A{-g}Fl@ntjbFs6!h6;R2egknX zqHai|rtuUTMe&vVbAJ)({a^K;%W~MM`8Dk2CbOC);5^yWIMqB07_0SO5&5hQO3Spr zQAZqxjo_p>(EG_WS)V!wa$m|WQZK!V?jnmV6>XP5w>45HVo^}D?IfKV!qN5>=rseg z-6-)Hx4QFc7E~@_ZDK{Bl}5A8&?RGP3My+nE*A?)PFi{OYVIDz!Ro+T#eb zFG4p%Hp)%mMrL&6ZcT7)CBMwGdif%@h2$te~uRY2~ZiO4{^;4$={171uCxWR_Q!*OZySdnLVkaHUB-O6@|Y2hS%v3{A|S-rZv zMtbISXJt8wjgTAFB)fbyld5$kPN&qu2pz2zFD|bsU#{IlOJtHp!>isIX*yb_u?(s-))V0VkwAx>kVIh-Kj&`EL% zMYlJwEtsY+lLYoyOeLo4aRF6Bi>2`zw>DoqNiVm`bV;uRrVD`%Tf4cRM@wIaJtxVH z;x%2@>XPYu(5685YZ%7#NtQzfjyJdv8ZB-k-%W8vk6WK(8x!^@X)py~*rrur-MA?F zdU*5L)UR40<7qV87F3wmbEPxUHYlVHnxfP5Ce&`j+T%%jvpuB@2*C}ss9|A~wuvFb z9_zMIb&N6#sLH*jexxSMwi?YieH$q=o*cC-LU~d##OnGFi zV2AB!1=qbvhsYy0ugs&1*re%5#~d|ZFvZZ3xlY(tRxl!C*F!&%5!!W%ke{?G6(Oha zOvmG79o?8V(}9(+OE0s9fGww@8w}pC|71VXf2OmV$tWfp8KaJaOB#cbcA{5df3r)L!n3aL%y7H_|bF+3t!)R3u)>#yZZF>gNNb4TXmpp)+83_F_+s(`0I_ z{EXBK1{!Rm;Wi-mtd0mcT0WhmX9_r)KK079p&h*}!*m7@kHJB}^?~|1;;^0FU~GZB2!$24 z$2)-D$#I61Bhw&p=akEN)FrIdR;`Ve28lPi4kcsi>1BN}6jQ+d=-b05>*YCDSFLfH zf(uTdbem(!gF)$f`Z#S0Cqgc*DRe_^>^u*sLuHZUXY(9Etw7qC?#uk!6dtD~D~jdV zhraY=l=WbGp@8)?V5529*Y>z0b>>9b?2gnS9Ag)ouD-a!;|%R&2itj2hr*Oy>yS#& z7Cj8)+>c&4C8Q8F3~g(A5FLFt+N|W>|4+36w++{VYr}Qmx^O+Xi~fh*QNp*p{!cXt zmyC1pJ^77)s=wv)U~VdU>9~BH1Lwvy;I`pfaBa8_To;H`aZ}|p*ZO%W z)hD<=H82qf8O~|^$6~dxPaa}eEt=#9ru*!dO-gF3V)96 zKg4arc}?lKgU>a%GThC$JltH|EZk(=#kg~ER@_kBmv8=4{TuH8m304KwX=sjeDB}+ z_o1Psxv*+bzq)SH3otHaTStdvBt5);w0(PCr=Sgl(#6(=; zA=@?OJTR-tvc<%4j)^v&8}Y2J^$idus zrMzXJx>%`p${K6BN49GN-sI3(afP=2Q$r16x4gt1H0e^CVzY4^-U(SVlY`a-H)*7z z@70w`{z=w4tED^zRI~?|782twYDj@T$!R^xwfh6v>}^eyF}{Q=!O02t_A=5?x_9LZ0JGn zfT7!Fe3tKnxfa9E|7KdZ88$SWf-QxE=uC|vx5T(E={{oKnX25!6Y)La94|7tq(qxc;g<=SB3k2d`DM@eg>->yM)cEyl4#JDcuyA7EG zZu@S(dddA?&E@|Ke!glP|K0jYF>LO7AUy5cBECo3ksl#XGQM|gqdk$2>AX(*-RHiV zv-}HwzG@u*-TECbL{DQw#P#%u?~!&`BIF%=^l;s<<@tW~+wb?QwSS6s};DU&vi~cM%(9e3oe__T{w|1FRtO3xIV1T zn6YfpGG=~!^OU$5S$RIDk_Vo&V^oZfGA4T}%S&Wd6?1H!A&(O=yqB*i=Lt6FIwl32 zL!2bz>nZv#bFO0=P*TqGIeIYWP>LN6?J;#^HRbDgEQph9L{J@yN*;F7rvL$4*;wbe zlbp$M6_+zr(2Zh}6MUYm(1S0TFW`5%9K6(?fva(n84g=naYd;-omL!7e0YFL2B$06 z$IcPOArlxfH)mO;bL}#Yj%t&%WyS7g^8B8nKQg}&}`HnR17oHtcwzH8cN{-YO_dcSLNkv%Xkj6#w9P3 z(hZouXhE)SIkhHDuYES{qJv|#l6SV%o*L~@Q72C@Vq{=qucfdu5TTa%NlNb2`88FQ zlds`aYjvJB!JO?Wm+5atK$H>^U1K~36qH@Lz*8L(2QQnvWJvb#@7SF>`vO#XO%M;| z+g1|2@${&YU0l6_Cz07l4LtKGA36NWsdhtF5LM`?^2no=#)Fa}PbXc!dTMxZrqHyI zW5#8Yh6g&JAQ&BehLbx4d85EhlpAL!NGA2ESRR|CSp`4Wl<5!qIyqV_kNawOE?N&k zU6!JnF+;1(GiKB{1Gf+3C(PisN58qz3!f%H)@o0%ULpA&>DLjM-!Ibc7>xEYBk(>h z43c=|L1W{dLa%W=>?sEo2M8~%(!m~oY5BT{fQ|c$z!Qjai^J_3diq(+nD)gAPe1c1 zIX9r8k>PThTQ^LyOrFc+X1c~mqLv9!@=A_fN-^DZ^LXt&C)$bG3EDtl3PbBU0zsUV z-=;9isnMJzaju&n4|>+PXXxK}D7R8Z6Nycqp9YU z=$(mXhO~AWqk=Z+R|Ag#S5;EM^aq`#`tfQ&sV4*JEa&utC=H~eH;qX#8f&mM3>XHs zTs@VD28yRt9{e9fM;fNsdvd2Dl2fxq*PNtiN7|!j9n*p6b+|;%KZVsZ7BpNHJe0gf z#+{Su2sN>)VvRHSY)G)2V-&EIS7iM@DU7e+*HlMM^*nkNkBrykw>((C2dLSR{;`|) z8-`_8Sc5uQUrs~iXoGN=FH-}EmOm?aCynMwUUF13e!@hfUki+wX74M~j;n2k>w-sc z4xBsS=5uYH?t1vV4R;i0G2AwOQKJRdfg5|varLpAj;mW?O9^2ZZY#XEn0Vy-isNbn zZX2!*cdrw_&{2V(Rb0pI!97-fT&?9=`mM*+e4GQkfa+3m=1yKoQl%RKp9tGMg9+O-keaY=lhirdELZ4KD82^(+?n+Xe-j+@B$d~rYH z`_GT7$+#q33*Wcl+=k;Nv*v%sxUbZiFY-C^x_qybvWxalpRG)nsh)O9IXL5(Vmz~{ zEtdtartr>-@)F}(czE3}D@r@jf0(8y-SBTv{&gE~Q|+FkfA52J%kgaJN z)NL?{9~9h!%bsvTZQxo9&X|=>VX)?GxAwlQ>XRm)VbWlkPdEFCn9E+RhZNLJ$>ar9 z5!VQn(sKl^D#kQ;%9Rq9UbGH#6d8)XnJ~_A1+y;Rt*1Ts$75yXjv2DRJ+4Mq2&j29 zHKkxtMxJtolZ9}W!CeZEZOcuRyG(9Zw0FF42gjs?cMD!PQpwjYk55@Q&UHoL&$V>}*Em;SE_WkDuZJPa(Y#E8!Ch9t^@r(glUb`DNInI5?&Pbr2S0T^ z9!jaGxn_?3B`}#cHw5kTcTN9xXZi;|ClMPucSR z=`Fhttv~5mG5qq~|Ml(jUTSh!pE>VSTkFcKTc7>=2Wc-h zZ0P#^IlVo9SiSJ6uA}=l{kDGb_KL5y?_A}$?Th8dkG$@@XF*|H(t8!dN=mLx{PG{C zB{c50RnEM{TAtmLR`k2-TUR{tR!{t_xm}j)k8e8d?Nv{WeDuqmPhC~9{fXJ{y#D z2cCN~@zED{KfHU$_=GJ(mp$>`=)K8@M?HRbZPgWLWS1@d#d*aqUwe7!(@klI)(pG# z{kT20x3^zv{oUWZn;yUQf~TGy_Gr&bKfJPQxBrpXhp(IZg_3yh&Jo`ov;FixK7ZQE zJ1@U>b;9>59N&&BEcx@%g{xLAFRmDSFvYnkS6Tk)Umh4%ar>ij=e~S2;jSeeiT~L9 zUaQl7_?a_5-u$Ru-Vb-lf?LSW&a*5SC>c!2r(XWqts%*)Vo2qOhx=Nq@VNdaIPXFSATeiRc-h^*% z?`&<``R=}NT>In=8&7MSG_&x9Xa1w&xprIq?!P?!%)KK|v} zw;%fY#qV3{&pK3d=BSeYY?$fT_N|qxPuqFp%G*Z0d3w)7>WKR(v!!|JSfpm21xJI?;XEZ@o9(_IvAr`F~hZ z_2IK$eDSvz@167FGvD~#y{$$5AHVa?9rwTWqmEY&PRslB!v&wLc>b*wOZNQa55u0i z?)s~r$olyu+o{-Lb0 z{`VLB`m7f>-gNP^pZ#%dYt`Dh&y4x=jR{*^D-+c>W)3SY92Iwl`mpo9^2e4R`>ndF zIOENVv(|kyviYxXpZ0Eky(RaRC*!9VU%cX{pPyCKnKQS1-ur7Szcqj5TaO*O@tyZd zM}3&uH}l{%iyqtav)3Me{)0Q;d}8ile#dz1r!Ty4&nwTpk#hf&i+=Lsw&bB#cRqLj zuy=nwVaW&iFRgg*qDi-vKDm2-amSEz%WmFwS=FW2yf~`uNB53?_1q7K-q`rJA(x-j z85kGF-EjH1)t9pmH?G(=ZaEurwsAMu#%0YImosDBqDkY%rCjYXiHz&$1j2jZos0dW zCY|xE@7{Srt;Bh8^7$cLON6_P@Au*Y@`DX0)L9!(sO7l3agX9&!F`Og-E~48ikpdZ z;C_gE4cCvmp#Fq91vek(#C-?XiR;6iNthY9-~JD|RfKyl?nk&k-g`p*6YgW&UvXdJ zcHO5tmCqxL&!@q!;m*cgU|gFFFU4Jly9hT8mx=pl6Y2i;33W2A7WV+|A3IK{zsC7- z^0^-u|4_Jlk86K1$>YwApV@q#qC6ST%xHPPx`)q2tNYdc-&B-lSe8!-R`#p?K1E4^ zuE!MRb$Ik8zPtKW<$Oi4d03Z)O>6p92ehy4SGT}sxLf4w`qggOy`DAN3-EUvYrL=y zx?wBa4m;s)XuG{%^+OjNV`F9qv!J!MUtI@_;7-^I4?<-_znX9%@xp1a8J595xE;>8 zgY>{ucnEew3+c1p$+|Lh!E{M4EQ9TE3+#kDVK?+crH*(m!XKOnn_xEVgf6ITWK9~T zz&2=yUC;%O!X}uMjNNc5?1uSJxr=;&DR4V1f_q>SJOo=|KkSBM$Dv=}ug-!tSO`;L zEi8gNU=!Q}+u7|4PDT}OtKj!!)}-k zt(z%tm;xK19kxIh?0`+M2ev}Xc*2Lt(0VuiVG49WJ8Xb1*aDki2W*EuP}zcio-a*- z$*>5f!#XI>oi@V;*bZA@AMAiOFaBXFv|Nfmm<*d>I&6gw*a;h;^&b4gRM-Jsum?6n z%VmTQlVKlBhgKi{VG3-3cGv=4umd*19@q{oOxU|&vP|5!;vc3!2P}dOunxAsX4nDS zVGrzv7J6oDBmQ9uOov6#0h?e0Y=teb6Lvu5Ui`xpXkqch4wIn^ro$#EyA`dl0d~U{ zXuS{rFctPd7qqbQ*aVYdD@=#o&;hMY_=l;m1s1^$SO;<}^9qxe5umkqNBQS+M$fT)+4`;zv z=zx82D@^$w@rWEA5;?S7g&aEs`r3Y%de?1K$3<%h%rUGM;Gf=6H{OqxOdHj{7A4!P}8T(AK)!4}vD z55S@ykq>emCe6f7I2Croe3umvhR@efmA4=jR~RP2YzuorvpWz?cVGFE-9k3bpz;kZoxX}hRREfSMnVmfUb^y^%(4gwsg|@ z8uJF&3D-gUUg{mJgPpJsS~9R_A9lcYxD=+mL3u;vSLn(21L$QE&acsfDR0xxpskDe zVe9W`FVOW4dUHv~yVOJ235%fhJ<kJ8YhK zT&;tB`~Y(sv`%Nu7S=%}A33zaZkP^jGmfic3a}Su!B*&keKSe#V*JlKu8xN(FbmpY z8El44un%^?)@zTe$Dr~p^p~Iq3t`=Lgj#ctRRm8D#tO+LU*=zz)`*1Vw&?t<;` zAhf4r#|`8Y91mMz7F05@6WU=5v}U3Yi(tZy=)qaAdoJtD!Yt|sOr1x5z-E|m6W_Cs ztJ7c;tbpxs8|;Q{ur7!4ht^!muaNj)3ao?quxKH6!=`-l0V)N@)h#!Zt{Yi{hssU( zm+wX7_bq%cJ+7{UeXtKUmyw^#2zMoGs72UafgRAw8vQ}o%sTz(V&tsNw?f;7<7)PD z?7V~ghuwD)uY6}6{uopmNOuY4<)a?J)~%#NzTbab^~2O{v=;~AY$yL<%J<1X*!Lje zI!RXx^$d2x@uk#@pI{Gc`YHJ*-+xB_!PZ|;Z&nch6O=P7YQrAbv>Q2WewO?#L%s(& z?0W$@Y<-FRF2|17$tTzZZ7Z?o0Qm{~x@Zqj`GEQY?LFk%D#H0Q`3CKOk-ZJR|DF7U z&0mmj739~Kvj4$#*hIZn{z-mG{f3>;4v)e*xRd&=C@0i|QtvG%)MJ!eCrp-d8hS#_ zheg9!Z>D^TSfk!0<;9wHGUZffJ)!P^t}{-k2Vm2gCsd^fe_vy*0b0L)LQSQdtgK(V zU>$4NeknKBw#QIDR@S!tlJDo9P{&F>k3FGwK-c-KdBdU$SQjUs>TD;}1oFrB%@b-X zY`^G)+AaB&d_uL7ZWn9c+evR7+zs2|A((nG>*K4r4m)59>*hzHUDnSl@du~EI+zbz zVJ+;2Eije!^-k!5$6ym2Q$_f28tj8b(8?No9ZZ4Eun2a*I@kl7p~Zzim<;=17PMY^ zLM?+XxE;2_c9BCrv|mR0Zp9y*3R5PYP?y4HSPNU>4%iLbp?wnRgD#jp>5u!)EA!eOHlgm~svE2U@35f7TGrbnJ#rFdw!T}!=%)^DK?>!58NdN2#N!!oF(o=|tnb$AH&!G35>!~XT8 zdp5sY2%F(L*bR3;>m2rCU=i$rP0(^1dN3Kb!gQFDPPxG*xC<&7=tCDAdpmkC8+JlB zv}RHdp$&Gx6xah(p{17i;Z&G1m%Sob1Z!a(+yRv=>MyjyK4^p14d}xZmI`xt?^uROop7Ho^U{8}`9=))IGmkw1XlFy(vX<2}Ut zAnnRWxU3(#VG-O0>tGvfhF!1^j;24evi3Mp`Zwr?F1Q1>!Xok~P?r9F`T=AY2sVAD@YuYCU*6Pzo^b^qfH1&Eb@xxir4hx|R*1~4k3_D>5RGy)ILOUGOh#gS57yF*2zQUB}@DGb% z9c+RvF!g!z1J=P~uoK$uBmO;%KhOq?U<#~*sjwL~!**Eo0_7p!;g}}kf01?wo1hD( zwiAzhe+B!X^;OFK+oS{9VJEDGN(bS>RM-KVUc(;wzK`&ss~^* zv}{K&QB|{G${DJ<9d;+F>LJ+tbyXexeXgISs_C%#Jmj$G0#)@x`$eic@j=2%R@Fk- zbg8PQQtsBvRMiDjE?3oN*bX~k_Z6x-9=lyB*aNMTRkaC!F4zuRVGp!TQPnX&AbdCr zHp2?o37cT|mFUAh*bSAbs;cZDJZOU{Fcmhz3fK;tpmLR}w!u_*P=J_~(VbS>reBd%XZzQI0N2$fV- zt%X*&1KQvoxt^w~{m>4_K7#!)3)an6)pf8rlXSrLxs*3l=8<1NhSyVm&<58*7u*56 zVJ9rgCS0iGs%lCL;lT>1EKt>*uo?PcC$v5a?Su!Fg@gy~d8)b}Ho-pF3avjOJ#Z?t zEutPmJKO{7U^i^fSJkASA}^pkVJobFop3AcgS()znEDT`@CZzSqjwS>oCu3xHmrjc zuo-TJeXtFtE}?zMb!hn+>4p=bZK=xnAi{yQuodoA7dVIQ>q9Dg@bJ}~7bRdv9k zLh22y zxZV!;KavCk^XA(##?-b((!>)|%|4moQKeRf#p_s1ik{tzNjdl z!$Mg1F!8|$;Q_c8T3%9=9X}-9@KIO+-+|j<5>-I{#od;t#MLImojclM*%C)P;M!Q+ zo^;mjM)KkGgv`@N&rclXwyaaGJ7?ylQ}0eJ^Tl0?fZo6E+Q*ecI3k^+T839lzN!WaG%wEc^Dpns&P7wTw~P*|Tl<=~>*b zR$@m`KeK-5!p)XBcgGJ&4|&KOWkaO{m%OxJCAlH}wEFlVyI)NsIj>FRvLDxujy*!B zdZey1Z&dE9X|JJ;Tx=dg+}-G}iO_c#`g2Fo7a_BtH|>Ug^=W8X^CKhvxu*@q-kT(S z*N3dV9zSA>8{Li@`_;^duvZyjXN}4Z+9LWb==YqWz772@vE``&ZE4iN5PA=pRJC=_}|b z#M1|U1^sF0cYX!^GW7etg8p{&t%awapZn2I`3m~S(6^tWzLh#Ko`$g!eQ6)^Puj>V zz7%q8yIcsgYucU1s3V!wcj+S>=yjo2EP8>uHY8h`rY3Jdo_uq^dbU}fu89>J*IEqu zMItxFW3JEp(MchUX!Tia@Eh_GVPWWTh&*8^eIEXSDUOhQJc6eA>~V-ZkOrf@i2p3) zeWcMQ@_>zndWRy{$_#m$S)Q{wzEV{7>iM)4ow3+(wOOY+6vi&(vyjg)%L!wJ5r&QH zo#-q@NBWJR9rHKGYo-|S97V^0&V^>3oAr1kElI=ZqmX~iEME|kPc`J{nB|K@^87*k zyAAodX8%h<{?;2L%$uUVUskhE5Y<#L|&`7(1MC z6P;Lg%tF2kd8~XWH00yWb~r-ms71bK0RKA%k?$EqerOPRzafuh-`E62Ie>k!t4MrX_|(c6T`+mTO09;*zx4SB4(uFxT5;XhUx+mJ7f z5x%4$)sPR=-W=#S2qPK&V4Exo)q@7)Zsb$Ua;;;~`-K+d+mMIFQ5N#wfxHFzd1n7N zgycPg$Sut8#J|>e2KuhNkpJXC$Fe{Kw= z&%!u0Q2fb;e3IG!%8>tb2b9>Og)Jd8|6vfZVbyw!8&-67pDeykih~k0FoM zpIb)j;g2_`&(u#PBTpv&Sn_n_QwOlmF^IgukjKiO7Ubyzgx@iUyvLBoDj&;fl+gg` zOGfSB|kJFWr#GvfqKcZJ_iU@>uC>G32rO=nmu^gda=ZgS=~i{IewL@>uhcWJ9jaPXqm< zHkr`-=X66J%YKI;kCi_S$a@CJpB6(N%YO&*qxg>{??G-Uirs%$nBWg2Pd4PS!cRw@ zMEJ4f4&=!L#NRN8yk!u1#~|_^LmtaM%Ng`v1K6L8JbeIpI`aGhxr5<}U0czsMK9Vo zE_UrQg5DAI3eg)ZUy{B-e|idfv(Vdm3h_G7YdHnIt?2DJ1-&-( zx=umw5PC;WLC-RV`d%`4zDz`K>?!Ewqc`;w^lH(|J_WrN^c<(4cL2Rw^ag8>N6~9R zZ?OJkECcqgQ_xFCuMNE^=Jux5`&+{5eFb_4(91RJY5mIDFuiT)9YrtoB)#%5y*=oS zcJ!;$&3anA&M>_m^pa0OZ!{gxtW(gNieCOH=oO+@f!<*0Xh5&w6vEqu-VXEz%4g|E zyU=SxkLGUbzxDZq^p8gk`9R@_-dJu34iL^!Tt*LMmq;DuWjfh zqc@m+d(fMO-eC2q2R+9i@k+jp=1*;8yry-iiO6>#kCm_4hI}x)-RQLqVvpqi4)hKT zqKAso!Ji)V&NG*jdHu_f$FkdkNAbVd?0>;#3ww=ed(-x5tNdcmMD)g%@|?oSdJ6)2 zVoyGL4)nxNaQZO9w&KTx?#IET>Ng`SPiK|4(Iu6{#K za|p>z>-b|?Fcbf==GC*1??E2Rf1x3dHm?)=YLOqnKhx7t{HA?|9fmws_C4sXRl2#pG@zG{UaWMs z7;?JtP(GQ~A36r{-($#A%>FAv_g5Ah^_BQz$&-=0k;lrXbmR>K$Q{VH4Ipno-ZFr^ z1$i6tYZd+l)?e0#?C(I{HGuyf4V4}hJ1qAerKru zHX!dH{8;(hg1ifPtoqY2fLzktW5_csdFhIjwx)>?Lc>GHP16z_!5ymSA=dKy8GAktCz)v>n_?HUv5%WB;2v%7@yYi zJSd;d;gY^Pg1YIWG~Fz8~`fxhL)?dI~6b7afz)=W0M%o(NF&>MXTb58tRYL0{REDqz`l$1vbIy=#+ z4C?jKRU0S|@iQJjJ@|Q=&z1_4EpzIJYO{gu9GD4A2(U%^wC(tD z-PNzMb!phnnKI+NNh+6Wk;}V0oI?on(m6HB(em{ue#UPikEpwrk8cah*F4?NosoXVQ+bj% zQ+DF#*Cs!K^gm}Z)v&D)Kk}}QWz;px(p96xJqijPznfF;#Md(x4NrF9C)5Vr{bj#4a z8vBE`5VlsYJ}~7ghp{B=KJ?e|&WqBBuytFq!onU)Lzwjgp2s%pW^)Kr%g!4@cF!KA zOhYFd{jG%kW3zssjOB1+sE(KFU-bT7{BDs(_nm%qb2PvCVSYJyC;{nyB@g6%D*5=m zH|UpkFrV_%%iJC^G*c_Tqv*HA)}I&B*XxKM{UqMsadSL%Wc|8OK2xu>e7?_Q-+aAo zjlGPsA>Zv+pA|p1NAc5S@-t6w^IP##`(X4lXg1Qe3wZ@{5VC>($!YXYqSJ|R9XgVo z!TMn8!$jvOIt}Pt6rmG1PbY2Z5IRlhY~i!z?~D$CaWzn$6(;+QdY(;TjDE3SEjQQ2 zfWA484E~(l4EBioAeo+Bjr0H)B)sVl~QELYl8mu@r5y%@nvsN;K z>CZ&J9sTWJLBCJ*U(v_nlj`(RQ~jWh&LVspH@)Lue;3tVZu!*0)oBX6p z@0387(}ka<`})-@qvYq1K-$Evd85od47sC4r?|!c{(kjalGc|@aR&OC zUznm~ZZ3B2c4>Ilxi;C;vL)o+6Nc#>gx!T>1wai@9a!Ch<9#9^-7b%->TD z`Bi55LhZgTeUz~VD|%(<)e%mbS&#mVdxskWU7*C*gx*f{!q!HO_(a}1h`e(Ud7mL? z>+_`aNch$(_4sK9hMfM;bj~{k`F8A!CATBrGJxELd|eE=jVPOtOMZvt6XW;o#u%T9 z&N_6qq4PZ%=gz4Pr6VvOnQv+Xb4SIW9;gyVdzXIc7-96iX`VNl>W~ufAhlq&HinI# zil?`@A0f_QJ;*Zpm-w}256pm=H{uHMbLegQrC>d!@1JY<8FIj6Wag;rP4$%Nq}FbW z@W1D`{pwqi&VpM*@doPZ?@d9_CrRDz#825fk>iJUf3}Ktq>r`6b4L9VKDsOLr>BXs zp1V1I!^pi_iD!<=;ge+A>`_uT97*Mt%f&lrcNBwlFU=W=lEL z;b$7}a$5BNarfroQ50SKa8-BLWRjUA69^Cj$Os_>Az>9!Q38Y{>;c0fpnya+5fBl< z2Q}=AY|1L2g0d;7sE7!t$gZHGBBG+;BPuE?3L%R z#W!uL5YBmzL%oV3^$lEiX?hSW4QzT{;&;Yo=&R4c^MT1n9+$#Uy*CGjp-i0-S$#)@ zWxP+uc` zyjX-CT3sBv-_qne?dnWqyCQru;DgTq1ARVgn%Qou)elg0v#-6cgR{aU zo>SmS0nc`%t@rN^>yJL9_MgUvI}z%O?9=mlj8))igS1=Ttf}Tm+oRp3~rI;Q9iTMfzkawc^3f&%^SB+!*HA#CHyS zC%-QW9oKbhPk9-)x{Nu#|G0ei+_c^eSbv==3f-#n!FF)z1u=VDs|?%ux{$t<9oeBD zc(#D&6<0@;izZ!auSk2Bv%MT=<^iAkW2x~^mgx>xwU)kiPVr>l*bSZn@L*~mwsluI z2WjuiB282qI}O}0;AG#IeHZrXrYeE_n*T;cU!u!Vc4^~gjy)RL{((IKS+jI3+CyJe zt{(2x5Omr8fzSM@)IADqUNar^exQffS+JA6&Z73c&Zhrc`#uERbjTsUa;5EiKX_Jw zN49TvSJ;M^Y2VG7qd(!Be^=VR2Lqo6d|0o4Z{N$oGYmZcOZ%pJJPf{qpYfeT*9OQ7 zbA7b$#dy&Q_E=B;Yb@yp%%?Ojykl?}=gvoK=?hP}7AL-q;5&E@@BGo)aYtEv{V(E^ z{vUk1|11i@^D`@BNH{;Wc*MRkO)cG}pqz*HY=N~dzM0n@JZ?Fic`IJ;b{rVB4f>Ai zDqzp+ShdgEP5NY4xVk4a7WmQY@SQv0trxU%pugIFwMSSXwQs+H^g$Wk5#X7o@i=4r zIKAkteL={snhBp+Tf$~zXHow+&&z0lIa_|&J;TwU-&nnb-!hKG=Ptno`I6H*H2Iw^l&c1ca#WIXD+L{I9G3A>Jp4}VleCuD#V_reNvmm2E zw4HDDi)EC~m+GMiJjXT`hrU7jqBcq|`a6vjJ&5|j8Q_<{gt;?E*$!aUB*)P3y3u&{ zVxE*%7?1FcNV-2^y;TN}vuj2!0Qpcq?FpX5nBq`Z>ff(8JkEGQQ`oEZ3U~WAec!ja zzc|#3_!gAKSLY%=D%XDSrMzP6c)!D^m8+DF#8U*G266a?CFOOO!vh`BzGR!skIagA z8nnjzDNr0*Nw&z-c%1h2pwpg|F{qB{8^rse+uumL_Ex?Dw>R{UXJpI$wL`!!!M8Yv zB9Dve^aHJaTKkNpt7wB`!Ll%M}p^Ia&c%O+3)*E9_5N}53^+Z zj1OaW?cJwti__9pw&6{Xkyf=hRE}i4rpd7Dz*wQ_ivCIUb_zU+`0no)#Pe7gJdPo$ z+OW{b1W#2=jCNdwZAngw*44(kj&#q{WXQDz`jT;2E3opNN5OM0tvEE!1DgJ*J+;?S$4dwGq=-5-u@S8(A@yFv?5cJ}9B zJ&g8WnPhx(XSn=MUG36}k6uH4W;}TOn~Ov9!QQ-2pr+po{F=KSlCfY2Tg)8AbTswCvm4G#QRf%jnzmP4rXv zCbjI_i^||BqiH-`?)q`I-#3 ztw;9lOw`9F@a*qU97?xPH`hBn=-YO_W^bq6kTc8m8B?@Qh8qavQ!YTpraZfk)pulQ z&i-&AWRB0b^*B2q+|Jzc zN9rNV51yX*Mz`$iM>L-Qp|4+njLGP?vahezWH@zKMqeM?9`kSXp)2j{O9c73%F#%>%}QXLtYN&;c)a9?*E4w$xYWK^q>gH6Hk0YQx(hgTA@$jfRXJ znha-6ag#oO%kpJ{=L~r2-CG=LNY|L zo2J0LQ9b0l z05S?@7l(!*9d1){ZJUF6VQY6e3^M6C9r#ti??u|$qUniefb#8aO_vAtUlq6u;5meL zPVLamL%T1LgpH~lpi>)n>Dqk>(z7`*$AB59V`#9NYTY``q$fGUdjgc_Fv8<|n-&99&V1mTppBQ)@tp{v=%a0Vd7a)lOkZHrV|BV+H>CF_&{H74 zflgP?VD{C^cMQ0C|AI?{46BRM7tuxKGjhVqV9J~RyJIk9rs~+va<93QuMKr{RmPsc zjRdZuj_VpO<5-(slju%c(8@^v2~r4t($BSdFZ+4voNzunfSV57rEGn|rk7>wAj$5k z_#?`LJ)U0bmYJ;26krxyrYu=D{Zcv<*z`;3FxjSGPKR~C(0@vlWlw6Ovut`k($=oq z!!}dx{tk3Tb?+CAl5mD*>Bg;$^MT@ z$jASFBp=J~${F|8-23cQ@ARKId60*taJbBPcMA`#xr?J9NSVNm1@3Ac z*M6$m#qK|ZDF9~jWiVO5Ob2EjFe{LD>k4xbd5_+pHy&&gXZ!NhG^#b8_HX0MmrGGf zt7m%-LC&etddug)#<;gW$WP;zCMyEg|7LOIH%@5{GtI;dTDzy|WJ50)fRF09S$Eh6 zyk(7_MDGcDCg?FpyXDdDcZ~(T0q7BJQ==~dJqUVy8T>tQZ42lD&`;^~4)QqM0Gs}Uw*YAkVU#D_P~4svK#5Lhlks56VP{qo}tr+Dmt~D ze9#Yr-cqOENe^4d+k)=*D#im>^e;HlXBBWM_}`qe@}vGT9rPxkx2FEmzE{}ZYM=0) z$a@HCPPrXCc{_?jHxUp0QIfMp5AQ9~`yXzeXN4~78xYYOV!uH<;dK1vE0oK)fVA%eLLC*sH zZk?{)=k4iiX;VEF0XGY{4myt3fz!;fq!LwB5VREB9NYxl)jAGiWH)V$r2nMa0Sx&X zSEquo&VxZe1iD|R+wGlrrrZ3qE>-+kSCB69Gs*Nem2D#XS@A8v=j|!hp4)}Lv)|pN zx>|12Uq;$`9R+pk*Z%Hu@32V6A5irigUr$33G3kac}<5b-%x!i*97of@CNr5hcM$0 z=S5?Q?O$_!x5ey|_u_MWZEa6Wbx;Vtp5TjU+dbs_V0ip0Y`=BD^#iUff6yFqW`Uju zdJAf2U!$RF<-JXIy>NN46eYJ{Zw;&aV+Vnh2%Zc3izC0YtmZiG zdsRW;jsh3Ne`}Q<@0@3*sGk)9(;S$Hd6)fOC*@VO52mJ|w?x`4pUMj#m{1;;kC@IOfMow;&%ITz0IWy`kG70rtb-`p;Tc7>hAMs^@FY(=C z^&DYo{Tx0=zwEGng9tJ)LkPX210bZ^j9eg{x+}Wxe zRPMvTzJKtBdLmBG!|ex`={Uy)6}U#F`z0KI77 zOd;I&GDuE?zL;knC^c_sr)*F3JkXOaLmvsc7xYWbo92Oj0XmmOC!I%wehTy_$Y->{ zvH7%QA|CZ2?lORQGN9TwkNRn=vbxO zD7TH}`now&&ea==syl>;^9dQQ~8~kL4evrNV^WxBBWQT`!+43GS*}-Fk?U3U$UJDD%b=FC= zXvvXl#M6*>`gn0D8nRuR+J2nMatQQepkGI2iOA2f)0LK`e^?LfrBYeyVPdr7o8r)K zRF*+ymL*bnWSy3T1-A5&yz!7X@(28vst59(EK^=7+dLH(QHE{21(+}VTDEOyj603| z0-*0E+eG9i_d7eHE|Rpmpxd#m4?+s$t~-mlGqt^qj-E8Pm3$pA|JPoC&GOmz2xvju zUO#E=GcD{`JI#fL3faFVLw;_R61j%83LN>E3)}mX?oDxW7nr!!1K&CDWSuV#tw!2y z2M+!g&41!q1;W$+brv8Gvb#lp;_LKBH70d;`!VinWCD|PC&nFYqt!Si>8*cTzw!T6M4#hwNI1b?B7?`_wQT!nt|^ic$)uN9Qi#4+|QjPdQP>p zH@R^~Br}|)dZvtc&sTI`?hC3lB*R2$Jo5Y90MFWsd5ljrTjJhfbLcn{ zJh^|Xd&90B9oxh4xX&En7GSo0N+UYmXb*yaBls_XzXj4RKc4d*uI;zb|I;S^gY|GJ z%qSZ}KKueOnZWeZF>3D~%fIoib4>v~We~<)U{S(wp2~-haK?=WAaww41OC7DD;+1F zAEq}-)Z@{3>}G~@ONe-~z|%8W61s})zO1t@pY~y}YBgr*E{^JX6L_+&E{S}f+_B*Z z&4$Qqu(GI}6j56~1KtbZ6{s`Ue&IF${BT}v<#Ti=f!_~%*QPqIsp;pm!+qNLzP)L~X~MdN)Uut~fm^Z@d*W@z%&z8ZalK-kv+c!p>^@E2vRJ*gby!IN2|By=C~bkun8t|83Rd#V-j+Mx7fr@=D|JUhXo z*&UnH@WS-Mk<&=g*~r(?{|%3aUJI#h{(+l;j^A_Insd*P%nPTIul3iKKF5(#(^L0t z8w`byGDFrR!QU@1AK=3MEhQ~=jXi(z6BWSBW^kE|5%_ln+Ez0&~tUVYO~l6R&&fu z&=P?=1>6Z5@9Js#IW}vh*}09+T;?=4G85+Oxt#rfGbtk5C;>4VST_9NX4`XI}09o6kE5-mJ7M z^Ld#l)=}U``|-cAWQ!;NXXg4v*5PB0X;f2}b=dQ6^q)Ftb9x;*Z9wP8taXOg zZ!qPMd-F@c-yk0UeX8@TITP-I4+&R#E1&jKd`syA4}*7ipd?g*>d2{kZ7+@f51i=L zbh`H4Kl-2WOVOz>(Eo=My_L?d_D!(|rS?s$g4PGPqObo^-vx8_MeO-D(dmE3Ps2u4 zNRC6--o;z~FZAt~p$8%Im`$%s@*O*1Pf~wZkBz{10Ua)fNdd;X=F*sY5bpSeAVKaVuMXKavmop48j1qt6?f zK3FlNLH<18bL*CbR+iF7j!}<=ho~Uv+krg@Y=(~2{5oMy0CNY|j5-QJJiJ zFh&5gTE{p(%vco86!ahh{V#n%y^_f9?n0*gq$0)>>Lc`@^@YH6LfWkd)Gxk&<&GEB z2MU2(2V7&qIekF8Z?FRN{h<4a?zEF!^4n_M+5!5O%g|5Q@-M~DMxniczl)x~p}wg? zwh4lM6!a~6{^;wdLTumR2`6`~ZRw+O=K()By(Dt4NwsTy1YC`i4S;J7Tp@7lk+y!# z4wp^M1@H(>2QLUI0u|MoH)ev^VQnO|ISMhG|WX7Ll0{ zwI4hS@ElAhv}tR)#-sXKCzSK0a5=GH!*gBELX;*ZG$+r!7k#y1iQ1!f>PhkEPBZ(5 z*|U82y3F9CHa{7>C&AkjX}4T>o&{zzvK*t?*p0v@HL~l=$wxi=Vq|LAAn?b4?Eq{# z(ymzRP^BUXr zaF@nIHodhJCemN#E%pyY~Z+|2q7iJGILm8jtFK zFr#+66?+fV4iAAR>H7cOhUAOPWRos`}8@XJFo8mzRVj-)H`HL-6oC27?@WQ8W07( z**c%f3t!<2kEytyP34&mo_;;bEI;{Q`5}GzAHl#<-H!);2k_5CBaaCe=V7+=XqjZo z@|*@w^Zq5FDd2Z)to&^FGpKERcvHfD9t4x|Oh8Y8Zvpszr}DgYabCugT2^f%7QS*H zv;$-e#sn^JNJ(f1+Nztk<3CI7ptb~<|F?p32lXKT>Ggt8uk#4g{AFBpZ=URz9cj|0x!q;OWH3F*umgC z3BF-uzm2WJc{zS=jizhl#tXjo^^Id3s(H6PUVuzC8S}cb>{-cSp~jPYMfUWM$KLLg zlF)Z#&qpuT(cGcSM62GXRg!JbS&&h6MoH)m-9F*H$tAiyrT+(h1Mm-ekY|pTC-#D* zPn%>#7>4}J8SsonV5T+($pFn(a#BJJuL@q9pU_xXSz zAP0f32Yh`U51B(WnP-4$28>xoy&Fq4b74MF6>@?PVLq{>M0<`e{LLexXM*m%480%d z7my!@+i)4QJ%B>cPk~;M=+64brqf()g-!24bZ2}=ACu1xj0(4iAjk)StqNUg>R6QD z`K~2l&H$4J%*~}R&U}|Ji4SAH2$<$B2KTEVXS8icy50RWQxzO4^ zbvhu~Z7leMkC$!NAm~d#4}e}xmk%9!Xmz7R2QZg{Wg-Xe`n(!!>;l0doo%tl}atMy3JKJn^YG1k>r|(hyBu#(~ zfVot=Z3cP(bWA@q8RS5e?RtXFKu?XJPcrfGS_ul``gmacz+9@mlHFGTlLSn@E(gA) z>r@ke9u{6t?*}dqILg*7lbUPN%c}~Q<9pbd+5`bB0(b*>F4e}!4#A1=f53Q=cIDd7 zEs}njpf3TvrA}A*y3dFOK^qL*j?3gl?Q<3|+kpv}RrR}D?e?7O8|przO)|Fwe;Rli z3tZjMK7n#=d;*vYz+B3IHv_9R3GD%MX+XnroUs*Kt?pzZ+n23(5^6u0;2jKJKi7EW zv;4*;$w`{Pms0tL0o!3Y*7=5pb>@H#oe2gpsD0e!z>j~j^gRh#H0hhSgFXxNc!+b$ zZ`Tdg-7%a0Qf;^h^kLw~^xozV`}XFzRCO}egPF{yx{6<@2;65X6J33n;w0xEN z^#Oko_;YlAqqQ7d$#&yGuZO+FemY&vKQVuL$aU^yyLG_!1NPmEv28Hd(r&1$?~EP= zo~A98nW$JlD}HrZ!fJMUO8^#+=|2S5jmX&Z&idX;9s%U-aB{7*F&0?1wlV* z)7v5K%17TY>>+{rOc5{#Ap_gwVGQ~%_9*EcM8{{i-?FDVYcLh#{koD6mPBD5d;f`U zOev-;dG9y~Y#(4(z$R9e>%(}b9wzH^LiG&8Jn-y)w$%QGyBB+VL}$cv#EzNd-p4`k z`kyN)_3dD}SBcNGX%FzW^4;UMRuqHk!#fTB6TD0Ga=H2HyEAPr`c`EMcyhtN5&RK* z(f#E!c3D380x0Gbz%>DG3vfk9TNU7aoVrs!Bh&R6c>Y1T9@Qx6IcoJSO6422K+eeZ zC6Ujh+t2QHfb8X<7lPi3Y`+cO&&kK}YrC{Ii9Jcpu5#XfB=TA3 z0_Ry+)$XWW<^i_^xJpQ?JmFL9cmIO8G}5NumiX zd`hz=?tlitGa5Xrp4Z1YWdoy=5=?TJ0CNJEh%rgEk(N>-`I21U2&Yw0nGb@e`3oi5 zdsnc%{d_0UPyY+uKU49?0_&F7es+TR>w#Vm@*~C@O@0T^tAbum=hxo*9A?ui==3h( z@obh&zf}GkK=)rp{z02wmV9c%r)_$Uoi%-*C-=>jT^^ zx;*>|hW-4I`<_n$a0`Hon5Sb87g-O`^PL6U2H+a&^5pk8@LH=rI)cuPr z@D_k~fy;~bte%H0)E<12_c}%bdlcAJ7h@lCv9`}y4s4%|CGtCGZhOS~*XRNyH5+>$ zYd3JaflEan)NuB?=1#2xw((^Ga*psXVed@GtM`NYxH{zGF<9q8Exe|#9_%GQ*HS(c z)C`+AD_$-Md2|_=AK(>1W1uS}OJWOvo%~9P_WW3`^9{`Q(@a^nvL2|9%>#BFuv91R zdU%NHBUGmwLEjJhokVwhy1E~LM};1y`j@g~{R8XYr0z+FvGV>4T4^sAOKsje2V*<1 zHC(xvdv}uly^T-v0S$m_23)|!p|0&YXLDT313eA&{Vp9o$nk~F142}sYtomtE0 zIc535zXkk0mp?3@=o>*_2YQ5$(Vo9Q^e^-?Hob}~ANpzkIT)C$#l!-ScV)|v* zej9l&_87?rzKM=kYcuy51G1?#4}Ai-XdP$o!31$F1@x1k*N&i1GW%=eaV{`tfRXz+ zPP?>yew4Bw!ZblZCCB@;aLXbl+wR7-nwh&!;C9pJrRVA4UpmAQfkf%e}F&V zlpTcH{2^ery!B7$airZg@3g!M3C=3;ofZck3S^Y)$VCIv!cd-wxhk z;H~5G!mf~i`!4k|6xrYeFk^wiE$pza?i$wUP}*jJ`S7p6|5wL%bnjWu3END)-)aFr zeVf{Mu~s5Sr|q`~kNOsHZkR{i>uUy{li+zCd068#9@RJHpP4ByuAZq_1$@EwQhT=Q zyTrdc3m|Iy2Z76cqa+lkk4bVIHW_z-z)>Au05;`KeGY+kEB68mTqNOw7}V2T^qp8G#fI$3irDp$fJP`ymjezL49TkFg1WFMA{t(?Y^0X zOItvn2>L@7PNdDDmy_Ry469{^w|$1cWk#S=1~Y5&j2*l`68(*^CTJHVdm&`)DhX{c z9XT{!$#12j1_x(YSsC7}41fEKKrZ;}8d5SYWMu@}XR!as)9eg?>x@9x3}y^+@G9dD z8o5IT>#k)UM0Vqm_o=<=y#m)}Ip|0BUS%dQD}V{?D+&FKw2MI>CcBQ#@aJR%+9BTu zWk#)}9#Bi0p-~x6LdNTm@u|>c$p2x;!}lB?=USOiNMp7vM9U0+D@c;G)>1HN{pBf0 zC@=Eqqfv2cGE*xd)>p``9|pI?_ew%fx_e%*uWV<%Cy9}=0H`4&TS|fN)4u!C1Z-)G8G8vbBIfX_ohU27D9|0s<~ZF#zW>q>e6N7-4L5K2 zD8*;A%&@XEyvQ1ituqo^WhAxCsM;zc*fxXpa0={_T1iry3^v4-p9`5gAU|-ZB=X%# zC7(9+kp+4J>JRNzWs&2^!5u7DlG;=9FJY`NWR*4dB41Ds^md?k*UOSC|6?JSgpuo~ zzMBu+*h|PE`e@JxfF3bd(7uhc0Q6fykJIzf=6IVx&$*2J!=N|11f9l&bD&oPy^$^- z{d|&%j-4kfu>;NYcY#j&reHEr{Sxwso&|c$CFo?g0?_|J8+aROxBX#ofM;CoQ~}AE z1>79Sp>FE-b=&6+#-$CQ-wQguFYeOeU;6@?~%8>}pls%wRs{ zzlLV85v5A+swn46{$-5y{>YvWI^%dJhox0U0KL!N%9DGB&4JGWzECeyZib&~7N+ka z9TmDCiUPld0U+FUsza29ezUHG|-;(~I$rG5{ z9xl<|F(N+le(G7!e9$|BPVaQNxy;Bc){IK}LJX2}6^-sYI(p#|6?PO^HFyeb|BI4PiJq^V&){Q&#<~oDt{gu)If=fqw8#XeNA8#< zkqdU4KsL@Fk<%%f1+|t{)kd;_GE5S3GMMs>#5=^%P|iPLNSd4?jY1l)Ii-@$hG^{^ z$#*%K-|FaVy0sNc5pA1=U zowSiY#O?dK{~QnelfYlAt>hqlLg@03ce#cpRMO$$C?kx zDgtAHa|M6=6}E3x@NR&d+!JN*)6g31Am|N2Z>ZEpF_hqhMWoT5o!$i@pbj;75ZF8^u9-h1I6_0B*R?u_>e2;)B1 zI^Mi*v?t&(?i(A3GVU91%me9d$+?IA3W>C4p%Aa%_txj4*-l%!*kiGET)b_uce$8j;l)Hs|7_69Y>*h&9H?8x8qQv^`O1@|?qZq2?iFV_d&E%U zDmOr!C;m3rNO9g^v$@!1uYH!h#%%lMxjw!jppJnSt~Abr>r?|axUGQHIUw9G%@ z>bg|mF|0qXOtP&|`(~W<7hhX!Ef>#QY!?^jEOv^Erv&?(iz$MAYMfFgye3JTx^bJpYYsAW7!*?s<^T!*F=BTtI}_6g=@)(CjRdyD zUmNLvVwKpyNW@FIct)@v_(AMJP`$UpwQk~X&Q|ad@=E+oZ6xX&&d%8NP}Zg9Eo7TI z%GtLzs(KnkH4qam_6YCF*f(4pH`%Xd5BLg;lE^K16Ck&Uw*(tbb%@ruOt5WSd}6U_ z#ulZ~8+@pkQjYyfQvc%OYyz8U)MD&yL;RXRmVPsVtuw{mB(~EOJCoS=rg$@nJ!XkV zlh~KYry~2)5{D|X`9d75$X*j-RYmrrsP}9Iw%#MYEXVeF#AD^zZyr%xj;)HSwzoX{ zHcEiHI9jZaWv@hwwXy8eXz@%e`!!m8;%Cpr5cQK7aXgm&5+fdoV@rJEbS&HBtF|wW z75a(#mY?!{GWIXH6_nDOCR(s|P#0VoE+`Cj4Zv%_fpZ z&4kY^R0NWbS_%6swwfCDPC6W>!*_JJK!=&siI>yi1v>1Y!$)*LK~~yY{pM&j-{WdE z!Q*Q6Ygnr<1=~le{9q&;5Uh~$f7(oVUBKrc`GuLVR;NrHV% z%9PMy9_9Wt9X8QnFCC83;YT_Y(P0kt%@uTjmj1?~BfC-D#(Jvr=;Yo3 z56)2(`qu5`{5rz1>0o z-%0ASl8eWq*++(W#>>ta;)!Us1#UH(y=RKAqFIS)mPF%Sar3{?>`jZ(pHrFVdqhz* zTL<41&89|)i7{*{X|~Z;uY66Mv~9GHvsqO16SDlv8uHYSc{=(wit9xy0p$f#yc)$n ziV|nM>`^Z+{7nbt=#;PX_1wnaH`t>luESUUzmQRjCtn9?gTxljKjY#nZca1AEQ2i~ zjgYroRUj|m$o~%#A9H?=i@&(}v?10S?4?Lth*!7^upRKP7W>8&J1n-%sw7*3L)a_{ z`!RqJfy!~^vWG)9#vP17Q!R1cV!zq41GQhpF5?A5Of%VXvJP6`le`HMd*JwdG?2{o zvn2+lUogaberj4s|6_=SvFv4&()&&EZY&GQ^g>H4jAQS>gZbETOS~ILZ6E11LM)7D zpUU*lLcAN#p7hZ5O&+l@z`m8~e>~#d0DB>duAhyrv@n4!jj8lq0^1r>0qFxiC^geh zDlV(WE9Afg^SIc{`7soWv!AGSxMN$O4mRAL_T#}7K5n)VIP=cnuR`2`G@%R>7&q>xmX#8QT74G4w&Ne zSX9_2aQ^RjpW~}z*`gRgUx^W0W7$gIPjuzg*c&8sg(g)`8ThjK0fYK4lE_&SdQd|- z&Bb~@d)ySu{Om(h{NrOkm}06AeTX{q3znGZV;@_h1f4~QzhlUwY>r_Qqr|)z_I4Cu z4n>L6G3=;JuOKa;aQRw@o85h$v*)SUlk6N@t~b6#{Vx^bxhOcOk?@-yfp<>ijOHDW zSQ5oflTSj`ydT9@(^TU%I=n-NFX(V-*?~Gk7<+?1!55lrwX`bQYn4YS`&YU6g7YJk zoMH(4kHG@c$LX;DzpdYiftNPkY$s7B(R_3Q;1|X!o@c^E~Vks=g=a@S;7qT%svlR9(`) zTv2_6cx`H4*&p-m7TW>uX0a~}@r%Vus9G0eE{W@}*i(ji|Y7tfc-_LSnTb%BEY860I@o{(VtV5`VM?DTbfJ%K$RK=Lg*91FltOiVy(0Ug%RVJ{ufZm07b#JV_EaGbvtV4oW` z{u{?;nBtQFd)BOkE63r`5?G-n7RR$^Ekgck32d;>7Gg#`J1fQjGdW7Um%u)a5`V|C zAH3~x<>P2^Jf5A47SG4C)jokM@A$-<@$9fqydTfr_gBM}6R`q$orxvtGjU3pDt%r; z;u(*);AJmSQ4dB5yr?(D9t-2Lufj$h#v1a=Qv3hG z7Jtjnp2AFz{V6&=?`L0;#fv;0KlZcFqwvhZ)80HdqGGb`I&!{S>2Qz^C!{Y9@jI^* z&-&Qy@9=3p_NGzedmok%Vup{+HY?%EE>p~kLAw@5{cMIs$PX;>r=R_7iJ#!A#6)64 zHDi>S8zmO_*+<@Hxbl0nfS`#n0_nB34-52p7TGTIh@Yd_-*(4{X;t%C&Nh=xs7k%{ z#m%fUPAFYhbYL`0xM?gGk@mL*y^H9MA^9R&y%%ivw3V}c{AxzS${DT}u1^@r@ReH) z@s`0(*#0ws<$(jja!bm)`bA2-&69!qiVG}2CL55n&JfQ_b_K#hieb%={JKHQ_Afar zq3qPuV3RF9zCJMXxxfp2pE$xX=%5AjeCh?foamd%%#56r-1yw5+0 zi|L#eZ8Fn}7|j_w%agYmY#s)1gKc&=GO!skAbCA!gmSq2gx6J@=FGriaDjh zHrO2HlOd|HC^nSz+4itGk)tja#IWz>_QM2Itd3@TO_~oLHO09Ynub0RMJpVJ-js|f z<18W0df9t49Xu|QUyY&J@Oxgi1!GSPd)FgYqES&@V>nwH!_HE2iZ^+63>v0b>t*|C zruPdS7En)_Yd4iln5oFaj-!xKv=uNXitRJS-yU`ZYc3B~5#l4k{;|Yk9$GE@h%2PP zbdOlhjGYtc{JPZnWvTNDsq?fbD)-+4{*^}imxWjt z#THX{-{GMhjTN@evI;lJDm*Ba-Xp8<4OxW?`lfpX=b#T zi?s-4b%YLY+WBQ;Q{(w)_FwF2dD%o$VCM-dr!8LgnJE@{vBaZ6d873qXS4)AA?HXh zMYE@;!b?yy{rYuLLlUgJ0mi(x} zMv0#|+ev+I7IiZ@$H!V_6~7VI&RPO zg)8~uTZ0b~J56&X&sb^lLPP8@Id%q%4HLsIu3+N-g`D^wGR@6q%#SAfmOAn|IzXPi zh6(Y8BWZZXKH@fu?YFMREY%X51)E59zCa}ZBG^kp?8m+uUHE|x_{sH2W2A?PA2^@D zMG41OQ^j0^Jx-<239_i}wV%<|0APe6dBV zZ>0aSYQkJNdt2*sA3=(SuTV!R*y_9za z?W1fF>=mKLQD5&Z#uAh5ruHG%VTn|~1F3#dvn6(!P;B}kpBtC)s(S_dlP7NSu-^=^ z(Zi-HpNm8b>;5`c|lyCV+mlM65-dr)$FIak1_%k0r9zSeE%0sPK6 zCVP@JLWaS#6l!meS_}&fw2wW!8)It?f%bFA_!x=-6JHCPowND1s|~iys4g#6t{X(r zt6(km6wj1~dBj9@VNfLejn`lb&9BAq{fvzdwnjEHxp=~&HDa-e3c($Y=M3?=$$m5& zOSb;$P^m@26qDTw<2{&wy~72x>9v_Byk|mfB!A@z+f39RlIx5FY;3mSU}L>G##K@>7AmggR#$mc0@Z2OJD&5t6=dDr>d6ttZNeS&{^Vd zUN-6@J}H`=MW6A~MiDlLu#NIwGIq)Ojd)D)`FA{0D{%|5~`8`>l%@xb}r1I<+ zkNCbE{=ZthQI4&Q5+7jC**nt&c0J8gclkwe0z2=geb;4i;@d>_e4O~T9NQQ#0GSl1 z012-IXeII~EgNPe^k(eCaspS8X@0O9o;(w;#j$_*k7z^ltyLWRsQZL?HWrhH?nwVP z3Qxv7=@pCOSdkZXxGY*sjl(h^LC#5L#In;dF#JrPI3LUY_I;!p;(Y~a#qn5qi1qR8 z5sNm4H(AU1sRY^>n;2lLJz`gY?e&O%;@OW;zZk%-_lf-p>0p^;b$+A-XBDZZ~WM-LdJVz#Qa#gdGQ)F_KBC{*%^OZsgJGqQdjRUJ<$7Y zY#YrHVuy!a5WOU>kO!~FjGQ*}9fLn7^y6 zftvbBHqGxn&~Q0rahPd`V7mK3VkJyxphGV5P z_Bf}<(3A>k41P1QNo`UZx6l^((CaCU{m278+8sdpJskbiZjjy;Rq22q?Y`0p=;^J1 z^hBCpy-f$1XUwe+!0|7$9brt5uHSJCG@wGCn4z6F8te^np*UZ5HLo;*n@<>g6EBZ7 z%o4i3(Gb}BM5*KtJQY{-6l|`pHc%PAnca~5#NM*--X=z%|0~JaVg|=(AkRXfk@rCo zLSPJTh#-81K)(=vDs}ne=n|880r?6umlW*F($7NN052gHB5WMTCH*hZogd)>rokE@ z=)Xc-KZB3-_A7OLG~vBi^5Oc5dWMu&;k?NRPkGlvn&Mf|MgL6){ZP8W@-hs3cP^aQ zZd?yy@XSP@>%{vccnMFxlN1w8qi?e5gdNRPzK_}QI>cwdL$p2iwZn-0f2wPzv^3)u zyI|)-^x&IVj3em3L|k9d$Yhz6AHG#9dxNuqPk(|buAOPR5ZumOo zlL^@yOUWl)`{7z)sq469hi9~5e}o2~DZ8A3zW??+2EL6$O*Zl_dcKnwer(h1^2R?r&W3h;*V{$>7(ED4|DNf_X6c6Hh0L38Q z2Rt6vVF3ivU>I%!lH~>i40plc^%!O`>~w)jZ|{fao^aj(Ldzqjy2BGpBkJ{)ZGS`* z&d=a{6UNcM5##dz>6fXs$y_Z>!kXFVnMGk64=aUnG93&Xr(m#iersTt%?NuDjv#!8 za2~;P7h@F>QW2UWWFvG(7>FGs2x|~FBkV;ug76)} zc?1t`-d99OMQDnUjnExoAi@}gsR)Y@)*x&~*o$xk;X8!$2p-%$uZWO}&=esXp*zAr zgfR$H5f&k=LD-D27vTuPcL?VZJh+8W5g`?!DMB_vcZ7imV-ThyEJ9d=uo+=5!V!e; z5Y8ib?g2kSDne6)Y=rIz0};j`Ohs6Pum)i>!d`?U2;U)`NAQdSKSC-(Q-o}U?g#@B z#vn{ZScI?!VKc&Bgd+&wA)H6>+zWn$RD`Ao*$CYc1|p0>n2N9nVGY7&guMty5WYh= zkKh>%euPwnrU=;x-4O;Nj6s-+un1ud!e)fM2uBdULpYD%!B|oeAr+x1LN-EognR9C?Zg921 z&d~K527{?tW=#WI>)=aK^ukm{A6Z+`=cOrngKHH1P+fzeG0F+lCx|a)7Yi~CR&Br6 zwhK*=M%@nvOopmc{&t*+7~4*Al0zMZmkXf6hae_P52BOM#B3aB z^eaN3i5IF=PSz&KtLX8NPm{4AuG23U;mma=n~AuvnaLibi}(@FX(x1k5O}A3lx_!? z(o^-18u<(**93M$lup$)Z79VaK#M zcpT@K*P|b{5~#7Gp1>DNvnczg^k`B)&Zh6U53i1CdMNt!jU4*!F(!+dnt>{Xf z4Y<;Z^f4OX>3FL(DPk02oUpP;1LMEhNVcV{jWoh`q&$uKgzZF`84nY-Gv#7@P1t-A zZ?tTWWN#_=@l+)HOJS8dB6){QwjGaTfs~s`*uhfn62cCb!YUGWgiPiV_8uvB?mi?R zk`hLGkena^OVW^hL<(C>$=QSzV@5HNFenCdif6vy>QP?O4vvAXjd50mRpO|+# z8scf@ZP^7kX@Eq@eqmnv{PVBO`(+Pwe$e8uDreq`(BpUJy%$o>B5(ASbBz9ni~Yg8 zRVHH&#k_-2<@Ek68TDGsf|KO>lKRkLOF%k@#pf36JM^f)`kM z65xIm1i4dgJQYUtQw}V^H=?+_g1UaQc71$(T)$df@9tht;I~s*(zw(k<|LgY@NX%q z&j-GQDCS0L&)jx$-2C zxH1zb^W@3H6<&lN6v^D?s#q<6(#smQt3;oi@?6b-pMfO0PuueXl6yF;KuCub9hC9FCK6 z_Q^Z2h`)k7305k&2PXsU%*Q;7h8U-0{kRh8c$Mz?JkkM`e&!ma6I8lcI@0A-`T!J< zT_e-w)1PB3u7%72Mfze2&U#2nxh-=Ti%(LDBqgE><1-X{3YmG%gvTd4F+XiD*IRJt+A$yVvr zFhqQgO8<%ZM|`eI_e(~)ol5T+h;)0E?lTJM4mN%S(j8U$cbGT6lS(g4M7py|w}Wel z&$F+i`r_>-au`h~zN@-E8ZJ0qRYuY&Dtk|L-HVYW{#KR#syWiVRGL1v8sA%`GsymZ zRC@R@q;FH{6?KumU8Q%TtH$?L>Avfb?x)gg(Np64tMv3SNZ+B-@76?mfJ)aw*N-2h z(%skr&fZ85Q|X(i?(SCU<7k%g_oy@{`J+_23A$+f7?r+ZBGUJ(^mLLxR;3%= zj`TQ{UOX7-2UL3L!$|)}rMr`DA6Du6uZ6?3ZNBq*?7K};*Yi=o<$@|bz9m+aqg8tJ zT=eEj($gnRNTZ(p=BqeXzPT+O>!Q@si}K3fUxf?Fvpm>VAXmmK&$}5>m4OM2N&m?! zx9EclRhyx+Nax8bFD3U{E&WCeb&6#gDwSX5hfwJ@dF5b#T&NxeJ4>I*D<@{*La@b1 z49be-_-tIbx@HG-P4alW@-Q?!UZXR*o^+MG@;{KzYYs?;Tx$P28qvTGe}Y#Qsu~Es*Bvg(PReip}tR3^NW?W30kcRWV$9=Jx=>bB5Z4 zX9C(Ozxq5_>og2jYV`r!MzGTCkusY5xs2xhE~7^SsHDx;_WmeDgw&^TCW)wMEO z(?dqjj+4=b6*78Zr;Iipm(j~bGJ54IwEkeFO*hEs)$TIdJW58d&5_ZT=VbKy#Oj3H zx>QEnw#jJwF&Vv4ETcEC2@>S3Y#F^hL`J)&%4qjG8SQyjMte`oXkYBr#IV1XjNZwS z(Yr%rbl?#g9eiF!@9mY*`^RPUK}bf2g77E7N*`v*=%fCKYE+8h(`4-9t7Powdu5!= zNuL^(s&O(-jY>gIW~ouBCMSc`s8rkLOSAdvNIuVjOjNn?<~5vEShk!YyQG%z1BhB- z3V^6J+zFzr-ZILjO@d%j4&7J?Cgo!H2~k_xAqXb5hx zj6`INUx((sJRfvVzs1zBXAZzISoyk{y8Z`>k_S$zL(!nuWOP^6Yv^nk zJp~d>zWWv#4Zll9BPPk{o)={_`k;))oRrZxx=|iXe&8w@{U=jK58ff8ho;D=aK4Nt ztd-HkcVsl_M;T3~|2PRIPpv7VX>DZm{!db+59z7qVDjO*GWz5WN&EC+86EvhMxQN~ z(dS!a^u-@CI;q%CDTbdE!)b;5Ss{N_>}M3iS(VWrGNUTDPfkL%RrhC z84W0wQ9*?aqTQJ;qk&m68q`NdgCCaBkd-pJ`%M`Q|5ipL=~?4om3!*QXjB&&jUFPS z`zFX}%p4irzeYw6Y?aaY4`uY=DH%OvVHgfpDNK^lgoZMj+*3wV?v&Bg@iLnJIHH<~ zjnN3M!myXJ4?fH?eB7+H4KplwTAn(G5&=F6E)nOoIYEqA&VLWUvw|n>RfynzqWiZY z$L$ey_=B2v>FMETisnyt?Z4k@9TNEEx@@&tnI#y6Y`OG0!XnTg?k- z!hAq^Y>sw;V1M=YwQicG%+~Nj^vUX-x~kKL`_b>JcUEUs!$p{WRL@gq-bS2wt9Rv< zAt#8C<|BofeZ4zxh-p%p?JOv2{$4t6puL!lk%9i@jGUmblLA70QhYt0E>8e%m-XRI0qN$rTbGeEc@OuU*nZ{(jWfIh>XXvJ7< zQs5Q<`i4PLybT)p^k^G27J$iNkd)Mj4_pOF_w$7yJna(g2GpFtFvw&TADC2tJYEBJ zmy7UIzEETys^=LhYccMO1U2&C+C6K@6;E6#obO)s4ky%46cn=P7O-fa0nXhF$L ztCEv!StFay)l~&+Otg2&`c_oVJkkHqcb^CsdaccXjSQaJ}CAyz6D9U*?N+)B2x8_kw@zI?`hDi^tYNb znfBbrl5?M6?Q6*O1#8!R5oZc5YT<=i6%R+^NRSU25#yqsGp? zGEzFLRq+MpF-)e@1ObhbN$%k;@X}Pz<@wC~B!lbqP z1yVRSmSr0(tvz9GTE{aTAf6ml101eHNFy%X;w1M(!0f(#$0&ba#wFBZ0pKmp zLVV5<%C$yr^)2v&b(+zXB)87>$8eDupR8raCmeOfQI?l_#L z@VRhgM$HDPKdr!NDqkp1o1{KM)HJ(9%~F4)64kR$o2RA>!f6KYhL&&C%uM}Y3Qikw zI76IfrS3vgsN0xhOu%V&>if6gvk_*f~bAaz0=+!4;Rbsn7h za!X{?mA@qO9mb3lsC7+Cs!QY7>6k>M4Ma`0vu>J$dPQYN&%mHpt3RiX-`<;^e_JEQ zb_3DDO7F22amQL+;iYaRaz|PgrQbFQ`Lc%dx*^@oZV3&SA(Qmmrvs1K4>S5gNP6G# zblRViLrG$QAE=A;1WvOEPK#aDdjfoDBCdaD$m=mxaGefltJLNKd=61fvk|UwI{4** za&~ada20-S**yfGf!R&^IVFr1&wipRWPo=>VbfzwV&>!Mx;)s~J&X%22p!;qDg&2m zNF1%XCBLI?qxB$mRzzBfDcQwkj5pY#B1pll(0D8c9e zAtMpBP?9E~rKc}cl9s!YWJ=GLLw9z1mVEXlTT)$P> zg?1j4u2Q&Ty1YJsOjHosl~A?gPz`kR^m3+bCA3-Lr91I6l^(Xbzc*mW z|2Wml3kpHI8y6#fAq|Hs1g-E(Y3K;*Oj>SLFxnUiYv~~FY!1W_g`h10g|PLgvK++C ziby*t5yV|^gXtqwHPHTwS{2C_EGyo}H?{y`iR=ut^P+Sl6X90Vg3h3=kd2nMW5SAo z)&Tw>{S8T@J(>vG0_wfLoZ)x>ExN8=0d7Po?yZ%X2aE~8tee!7Nc z_9>zk$8hL8`fgS)V+w5tHEe{bdd4);2b0u>4ba~*rmHin;nlTqHbb3x8x9(bvzhA5 z-|%!zoIRq>0u3)r!`Uo#me_DV2I`F2>MW_@0L&gT=BTr(4XfOXv$^Ul*l^}DoIOVK zA){tW!wLbM&0iwV($G{)>V8#KEzqWwEHrG`lU(64X(!sm3foC`O#s>r0N@$Qgwys` z*jNtW5$b01r3BjeDlH+v$59n7Q(313fso5$nUZ$3yFXR9k59zVlU^*%pG{c0s&ozT zCt!>8w>a&0@&PW9Qm7G9Ai!4!Q6r+39gTeKxMQ zQrBtoFI;wI>Hu%{C=l7I0JJZ7vFz~=0?}R}Xv^?oL>+42ofU$16BR;sM_a$ffQV$viz9x6`uK#Ii1YWp~g`8A$-`REA5(@^}+0 z0@A;yqomUoW`qEN*-?5Nr$_>5b5j%0g%3xkNxxo35C?LM)F96O@m4Qgcn;(qV|7m9m`e0*B_v-&l(-Grq zw3+(9P#5aT&!Lj*pPPbe;;HENe!}|qnJ5l<*l1S2XnB@R zE{G&|;kz&$s?T_Fdpy}q8qOrZ$HXrWw0J>PY=<|lZ}CO{A8Y>sUPbZ!0ps`VZW>%d z;1YyLNGO5O0-=R+NiMx3O+b2)BE3lyAqXNMy(nOzNE1*|tRRRed{xAPqJ9+>d;MCm zxA*fovv>Cf@b^6b|NHW=lQVNZbLPyMc6MfWZ(}@XKy7zLQQ);i_o|yHP2t`!i@X@+ z1qn53^pLrjyXpqzj!t;SfT$mcB2}cEYAu0Ek?CM6svH5Apwt>=>)D?!K*AikWY7uZja_OnS05| zNuvUFt4ZZDZsy+d(=cSIDaRZ)#UOEm%7P=#OOQ}NGGEDjH~AALvv}J|IX0G#Tgv&AnE`` z2dNis#uU`^h3m14L(mZf&-)-gsszwCsVJv!|2nRu4*~d*AXPF5LkEJtqRxS^ESwDF zu%|KGNFwr<$K|4Q`X?0fI-omNANlPZO#Kie^?~9sw$Thy?xbPHl^h6OH>3}_NQ!C| zmcTrqX7D?wG98G*q9}7C$&skHk0j8P{1ed)fPCj4s2p+jAzJ~-eCN?9nRah7gjN~Y zw>s`9$ivDm+K5$#Xd@=WAXP?a)AHTED%Vn_`tnsH(Bs5Hwj^BH%+E&D^a+xNXf-cA zI0z(|4Pmk>(C zZpEHuGwo$?O1{LnuV?yP6(_gpEr_)=yu{oSeGzMKV!_-zxG(iOm{>|~KT7FnVr6na zrIb!4RxY;@rF1s23b~sFu`VW-nY(!uVqHzFYVNH&5bMTTSXHufS21>#iPgxxdpBY| zOsr;ZPwLXk#A@YkNB^jIwTacveXRjveNC)R?wy!u>J2uroZPE0e(Mb}vAVgNDRa1q z)ywThnb(?FZtmTbIm*Q9=e|stV@#|;?ncU-WMU0-J5%Ol6Kez)C8iT zSYp7+1FFHCUdks>!v04&~k6%EN`fE>;6r(cRp zKtF77g>m|LzGf_qvlpgUFy0am+@k3-nO@1ba6EyFrnkVd-QY)yyA#4AIbR3$4ovVf z^bTC3dvFa(*|e(g+|D#HwTGY3cQgd$S=#TJ24-a)0{Nh@b zl6GzEK!dr)V*O?O3}l!m!t+I)xY4se?~Jsa>R&&@WL1F_nuGN%Ex$7J=&)+=J;T(Cl@j+K1md)b%Z2uIN$08z|o}| zb8^Q)Y^~#F{3oLQx*$E@;htG6t^4BK&(nQz^4cPzsXWQm)an6i1=OfHiR$*3dj^2c zv*kQuK?cagoz~(Kya^ojbA>0qhM6KyVBW3S)U+FqfTQWv_9DHxN#~icNiQyZqrT>k z)LeK*9ECrHd9h}B({Xrc98LcVja&0dBW89qJxB_Qu@Whgek~x=&5-2@v*}wbAu8k> zG+xb8S|{P*vuP~$e`GJ#49w%!EOu%hNnbp^)CeiEh_EY+3?5ngGNPrF#7%k4FHIGA znyu+(o^U6Za!rBAG?i)RAxNPzUGS&C)aZ-#ze2U_;sWk~OA3y;rLd9>-&8OYdOGx9h+I?R8BM^^KoCi8eb ziayGwengXb-0oWd(rdK@?}8;ffH!LOmsS|kHM@%NG~O74(+o_0WEU7c%v{AYdY@_L zVzvdA+m$w8&(i)l-E6)Zkuy3k^B~{U3eA#)c2M6dXS~K239*eG`HS<%FYoNR}hsQkDqNfE1k%t4>Bj=!}W=qgC(y-Rj2nhy^DO;FJ~ zc@^duDL{I=Sl(Y@@LniB3A_PFAMNqX`qf<4VQIGhTN&cD7Zd_;iwA;Yw=M?%U3`AQ z@VA2ZpvTt-HO$i*JtVs|EKtSzWHlyHYW5~z=Jtj+E(R5rb8OttcSEXt4ZyEOWd(-F zU$8{uqjGc>5Xq=n8ZJ{+Bci$deGNqX^(;o7s@wp8W*#UoRH{ycgelgO_@jXC9@FSc zb#Ox{r(t_5L+(RK#MyEqfQtxDQ_H%DD)RG&C}In^`-tG#ym?p!f~sJdv8u~SI4rEW zEhhmv9V=)Vo1u<0hnXv&*=_k8+;3wM$EyI5D;7GKK@@9C+MKJ)nQv(h1xFUVhUMIyu*o*&HryB!socmZ`ujxd^8Xrr=?c z3zXGGcCL&Hz6aokFOvaE3>^q;Z~1Mm>BhFa4BR_DRz(h%Dwx)+LGmL++VVHpW^p0c zbj#r~dki3>BxgM#l`vgg3i*BoAd{rg2twL;5Y?S`9)aPKi9TZ8Bn?*)GTMXa0WpIp zWU-9hO2{$~!WkvVAPQL~S7Hp1mIwE`KB8vf2!CQOQ_F(s0EXAmF0vS>v!msjP-TM0}L?eHT?=S?INj z>JP*yAEh;OQJt;UxNTKbArQ-b6l;hQo3e8KtglCz$w|A{eI6fvYTQ6EiXS;x2VD^s%a0AhL)%v}S3z!b( z4L)Fq{El|E-nT|U6#$h54_b?;}0+`^h39%Lu5R2r`l`Nkh>fhRmt?#fc$<#fwoJHU{n0YWvxpu==W~{{ZmXC8BP}FFaTy?Xy6ssQ&?R!4n0Q6)?g63N52zlEZi~ z4wt9$_gE~g>+MH-x)SPw*_eRnAW*=K_IKl43Ejc$>q{_-uCP~NjZqaQgE!X`5Uuky zQ&7yE_7%~2=r$m>`zUv|Qq)d+JK9I*jwgY5&PVCGH%b(BzkO(%i~10VZ+w(HTPf!b5yZy?4NMa8U5qeSuV z+Rtxtr7i+?gOB%?9W;@1{%ZlYd?h!c7~$=D)d{x z{wNBC{S-CPxdSFsR4V-IYPj6W#M)1xH#-|jyU++=U3{qan<3I|f*r7Ka~7aj84m6& zAECaWFVV$5=*;Q?>`LIaT!eMIqKbUhsWjOw_zA#X@S!TvwYoyzc5)O2o*hhT4TF~u=YhVtmb=)3|Q`P!qz|Q+nmC68GD707H8BEVA^>@JHk*;4%KxQe)IQ(bQW_KttU z7ik;KxhHP$8aL-7$o0zQa>h20W;z@f!F`?<_a!m}T6y*L)ng{uNAYL)gI)%o25h6t z;Wejgf6er9++Elw&_b?4hLL_IZ7L1iuBrH+R_;^zaq`EvM6YEnGD2OJD7x`#Hrxi93sShS>W@gr)vnYtmv zb(hPe)rmFqHSvQxxtSIs!`+w5`R?de$8E@AdOiD=xy>0No3N%?$K$t`i^7gv1~y9gD1&t-ehD;JC-qIB z{znzm_cCqfX%9z^kJ4M`;)macN!M3+M!9k66GxDA4*PzBp9-gO2k!FsH@>_$-GNpYRx_P*r+4nA<&o+2{0? z9;MHISfPXp$u9m$U{CvaZ=HnpD!Nj_`79Uu8DPKqP`@EuX#Ir$T;)Pbx5G^^F4uJ0 z7}Nq%BUHE`p=sEKwg9Y~4~0GsDSJq5JIqoM~SOo2b4w%7>ly_dm9 zq2m*tLeEj?Gl0GBLt_=b3UjkHJK<~Fg?Dnmnf|G z4GGEDxcH91_P-1s3M+I^!prDbDtbC#H~Y|7g-hKCg&$40zP}6I0@wi`8mq8EPbB0= z&F}(X=Y8lU3M>9h!k#Lw=-+`Y-r>>;LScn|l5lT%7n%iFV;>r;aKTn6{9{6gs2REg zHq3{{Dy&c|vHxAJ)EfX><3le|Sn(-|gRpCb{eFL!1d}yq~ zs}rGcPU1u?@G4a>!IZ}3wsWk)3e8V!mf}Kd1J=riUZSw#J14$@QKF&;0z2U{cqpvU zfr;-#hyE>qZS5EtOIgLC7*fTyfc7ovJW!8;}6`GhWKY16hFMKHL zhO!lPN8+UJF3QG2R34XW0Z(AmZ&Ccg#C#0R-Vh)SfbI2f_#%Fb<~)(uc)FW&0&>mv zbJBoOea90tIZwd?yojE1>Q39TW0wC*qi}MU)v)rU@H!K~2o7)3ys5WKA8sGSiUC=Z!*v zc}@Bwiyl1jL9@IDd`2nnH7JgJTaTIY8Zplp*@@XJFKo*`FrUPgO{wB94|pm` zArUzZ?&}@`hbi2<$!k;5!S@Z3EdN7rf&9*t06zEG@;dCpOt6yt5=btC%jI9EyJ&e` zwq?8gI^Z?*`3;7&Rij4#!am&~Cg14+OaaNXzVNoC{$oQDYX?Sw4kJFF{qzy76|NMU=l8;ZQND_gx5k}-ySkeFg){@TL@4!Bpe;(wmH*4R6(HS2pq8 z2=XR&UXHZHck|I}5Y2ZM0B(JTMrm4XjV3&eguZ-g<}3))F-QT*0h`$@k>9+?Y?j2Y ziDfn`#t&7b@onXl^!^7iW#;}|36BvBX^s?hOY1Nuob-Xp=#G(_KC~Dxc+w&FH_XK8 z!%QqOHw?cfeYlAQtw)$?&=Wv*m%I9c9+|oouizmrBM}5iMOoupqC*ytRY(>ouy$o4 z*R;Doyc;ngIT zY>fgEi$i-!EQZiZoQOVVCm!zsD<|HJ4Y9by+Sj595?`8)Pbmdz_Jlp0@HM&2d{&rw z$p&U_4i&A$PT<;sVtX-nORdsyBxM%v1SgJ;2QGZtUIwW($6?lW!Y@ytgmrx=;jzY) zaHIw#1O_MEM)qg+UEojRrd#-P_7cachz6Kcdn^*Z(1eO?k-%gp{6G6SV6FJ7U>#t2 zT|XEB@|#^q?OG9DL-<=37RZ}>59qHsb8w28!V=JSc736K;n(GRB>aUd`w^H)g3ONz zM44wL8EZmSTrQJR%!J-82KI(D0;Hu6I}Axt8E;8XFb4a~lZH8prN1p)bmn?Y@8MUz zK^uPO!3=!5jaqF0Vw;Bwwq)VWHp(MKY;q%k_xSoAg@M^{Kx#J!FpdZ?jjU;Wr z>m1A9gRT+&usvEumADqXaXx>l-hG5W$ps2$z+{-VVBK*-kUN^4qlsnPXy$60YeH7O zJ_v#atuEw-n_BV&@*QK|cUgTf>XFgRk~2tr-($EYo-Wx7zz$o>n*sg3$2OD2EVMIz zA!k@FdvGVqwkEXz`2K|`f5t;~L3XxEfVMU)2K~S$CO^pJE>>02E$4ymYH==|aV=)Q za5szfp3$9VyvnHF8%2bF>R$@U$=Hetceg&$+G>w(kw!aesm&LyWJ#q4p~V-BVk!%5 ze)A5drZDxU`;j`cBgJOXF2z!iF14x;Mwozv zSyByT{x*3R^5i!J*-2YLxn>HCy8(?VvxL7&k$+aRNCxs{&p?mzP=Usr8l3R-9bn}( z*oFGs7#(r5g%d+~hR6UgM>8)`X1zw=;)@sIS-)UEoH?Wryjuv`OHiPN-gk!Q)C5ZT zclta`b)4GrodXC949TH^=U|F2-E=F*kCdHX=_{QjRu5_}&K~x9vwAk^W>gljAll zVBw=Cq74+@bBLgU5u_ihr66tO@P4*;+g(>9{n>gZa}N%$lP02V9^S|1Z@Ucj2|vg4 zcRa*%g5AA`#WBK(4$B7OJ*}6q7&wXL@JNk4=gp-^>SeKKIC2G(1`WZO4qt6?%ve=| z_Monrh+m_RjagMv>_OM>K)k;jFJoITv_yR8P;^^$Ns)WN;kN-@$+X2b{$|mor9`TT5gkI6Hi9Fh+8Y$fMvK_qpv1xB87}ta>7^ zgY$vMEpj9tZYaS<*s*6D{Q*bFG7rx_ISlU+)UCi5wIV~NFc@&#plKaw>-L(wUBBUGP*)626L?k2x@Id$?+v9 zC|~;ER#j2^fq489)O}Q^K;CZZqRs&E-X*B_*8>%iJ_#=BS0J2zQI(=4>gw52Ixcik z6@jRE32MYJ$ii0;umq@HZGh;035qv=;nuQhh-y;&fTH2S#w=Xe)$O6Qd!~)h~y$kn|Cl+v;jl76CUQHI)AATM#&kh%G#}OVNk4hSI6~el;R15NY!nOF&js{aX^3S*CGerhKCytDWB^9W=NR}3m<;C3SitW6 z0F09U=qw6Y1Lnq9z~YSnjFICZ7w{06M?HX9Xt33fJN@uD`3W{rpY|;v-uF=G`+Pbf zJV`pi>{`xmUS$dU&}KAF1OVN&F?8R2>I z7@A#rgTW{B+=*3hG0bxf;l(mxx;y>O0b=pxQ7ff?6txwI{XPm-;y~t;6ybH!Dh~aY zQ|d_|&Jd*&thuRiQ5z*EiuxLeUwxFy8ZDzoP7j3dlFFO0SJn%%N@E09!4)GbIz3ie zk7Bn-;yl+xEdc9S6bj{d#2&s!O5E*MbOaESh%%mmJGpBW_DHW{E@~+d8+??m#cmb$ z$)cKWMIQj-Fj1zWv8emyH#l8fqvR|QANaC#;dNy_B#+$T%K8I{gu$MySkzN88Pku- zssuzGqKx*s#Jfg&UK-AJjn*EBe!eW~WsK%RPfPY(7djQNB^N<2!M`dKqxkK>9`x~4 zGuj?J<-kqlW&|d*d!qVhcD;9c93ZS1#uT8GP zRRF776pB_>)R!`NsEg_d#MM5^wWgx}Cu=b*bWrh!lnQ;67CQo}M+IJxW6}9;Ghq9C zsMb3c`m=np#g%#juy=f@SDB!T|9%f@^p|WH>EeF^HXe${4A3aFGe$*NtZHx%RN+j( zY7<(d!zs$Ko}BNZ+5yqiN4b?(RJ_$5i>k^R55$c=%2N}SpG&{HlvOw#FRfmUmb@LX zyFDo87rlK=v;M|(Di4Ekf=tsTRSq|LqOc0q0Zgj$4j|uO1e>KDGX`7H;!c?)!0P32 zxgt#`BW#q^f==NKYg}!&7F>|>2{jhcf=5ZchCo%aicN9dlzu>5dkN}ot_D@CzLQ+k zJRolNP$-NWvf(W2I^5jUrX99`xyuKb#}>oYtfrW~6~ONDA0OaK$hKBxV)mwl55WAK z05em&5^7kZrnvxXI7R|47cfLV9}gYsSglZD$pE94$24zw4UrzRfXK0iO$4GPxLq$o zjFKPeNY%CGw81SmOfI8=m`Icw4HX@73jp=3ob4`P37D&VKpmOJvE9JhJe8XyyTEyj zT+`xos)OuOcm(`Q%wpk2R^OIpzOv;EaPRq8_Kv^}2G-b`2#1B!nk_#Sg_t{=Kmljx zh*KJ20apW!7tm2FpfgrLx3Pe(VFBI00=jtl4uKK9E04G|Q}UgDQ7QQ7@s2gNsb=Tjz8@e)5>! z#+!NT9II(yIhc|RPbdvnb{<6s(-^xofxrS5x(BESh*ZtIx6T)1W)l{A_97{& zRrIa%nI(bx5{RFRqRh+Yqe|f&Kz_%J1e%S1@|{%ZQb01I2@y@mcdmyr5vM+xB=emX zQL^!PfTha7_mGf99=0XKd&_(bQYYccCOhUW^Fl9s$vim<+fwXxl;`2oik@YQ=L4BLcYvWMFS0DFrXUn1BPQjH;m;_fL z)WBGrrK;&kz?jRxE}%{k-Mnf%$&8O0Q0LO|p{Ztk)CIsBAFm<*+qkmZAvI=ve1)`M zy!2ofaQ*R-h#5B(m&tU|_$UkQ_9Lg{0MU%7z7!p7MiJ5R@yqR)qX_B+zz`o4F(5NO zmSSF1NwWZ0N{}jfneowlA4J^^!~;HxH7+_n_EpACISYLbsF#UU&Ajn3p>M*2?| zNl~q$<6}>Kpo&3wSzNA0EX%YFJC!z)_Ab0gig>=$2>b$)5lx6_LcX&B%0!%=WRlEx z21Uun?4=kV?;;_KydvXc2~t<#$|gHzd~8K@zn32T2&6wgjv)4e$8;M_dp#BN2xu`J zD9pJC3rOPIld3uUTf_-mhvX|u<78qPQp=@xkuz8v2Ni&s{)!L@Rjt~3F4j|dR_#Z~ z>?LmjXeGTo1(80&PMpMVC#Lrm4!b12LYO{4J_ji22~0id1BGTyI!Jnuu-7K><-_!$ z!a!!fq>RN6h2nAn!{p($08EyL zyW^e?088qF+mr}XMjffJ6Nu@uwko;Z!5QdrgW8Mg$kL90Y?EPFi!GT3_WX+=!({Lb zK<<^Rsz=M&49G4YMq^>QUzP^g>v9X+_qgel_B0^Rd9WzrEm>FyuU!@X2;47;Fm)a# zH&UB((ri~$MjYm>ATGB`F5;mPO-ZueLjiuhc5caF*! z2kulNqB0sMLdMrJb49euE5Kb(gfZ8kwY|d1h5u%>JrToHZLhQ*s~gq!!x*NXOJ`U^+u^guTF-xC%2Z|*>upS!rrT7Q z;A^`p6WUg{_?zA)XHzoWdMdM))&Hhw&OTmFys8PmG(FL|Z-}XLkFFt2M*- z04Ge0_CixWn>w1IGNy|3LC%Y#qa{=ZxCt|8r!>N;O_2-}oae8Ome32}>zG0N`Nbtv z7k<1jeT*eH0CSTk7<>Q97;DLTB<}PW=0oJgG1#M!iIzMD_A@@DYz%jmEoZ^`z~@#n z+^1RYJWGBACjc9p3c0I>c{442x4nHI%0UK61EiV<3)Z2KQF3kzgeFSm%he2gO0%#k(Ps*;Xz3fRzxKEi?g4YJ zFTn-eX$?YsRKl}hp7JG_H`CJZv0layxsyeF0_NAg1Q)Q|8W6&dsS*&6o>u~wR|~$G zmcGwgl;BFJ4rUGk(S=0;4_G(Exe_{nc~z_g?l-0%v=+{D9l`6soE!__j%E5|)~Ry1 zna5%&%fRF_`koGaZ7lt;wYIqn*azlAKEOQ0n|{c75Q9^m1LJivO)q5&;tki%Lm}c+ zTtm$MwtNNlFFu4TYZUU|xPvnZNyb8+fy_Ngw4aH^dbCL)_;{ zQ0xpKANepo9T8-J-I0Dnp$Ux?xKpt zzg^4idl4YI5M>6ttNL0@2I*zvzrw1d6&wY`)JsqS%$VuT?YDQkB`ybIBT=Re8<-KN zr~>qr?8bpG}JjGq;wfB63s7(VWIUFqq*htl-%sDcjYw-M(f z#3K&f-F*B$C&K^?T|hG8aCM6~rIFyd73c?MxZW{EgW$qWP6m=AW8i}ZW)2JGI58IXxpNr92vm+TJL0o9LS9li!O6y5G!w;?1|LDthIiXBQk{b zF4hiyqv!#A9>7PIbMn*M!pI8tGW`liWEE#T{WeErHRrZ@GGW-{KxCtQ2_?SA zl}#ljFyEwa6S1$ysShs0Fw4zxV4_*~OBT4fKH_u?^D$`!MmL}NRt)om3<2YMpIHd2 z#}r_G6(I80!6w+UqE;&b-R#4)AhR+>f>H*iP}IXf9P?3HqKm2|_jGVkZv*kEk7Cgn z<@EO>wPfafm~mhX{CG9o0bJQ1vwQ%!JVhEwEi}w_0xFTo%b3jtk9wz_(!j91GwvROE={;g0lM_J9;9 zQvsJd7=B`JHb+O1Q}P_{GZobsh*mx-Fc&C&)i?5?oUY-51^_VH2dO9n`byr-zzGC$ zNg)8s3DW)-bj#x#gONDv3}%DH=(n;9h=+VprC6SMb25@<{eYQ7o&)!FAK~_Pm6Ktji~8Efbd;=S24~A?$RE4 z)=Iq%h}Xe=$3vj`=(I*oTNBp9oa`n)f%zu^(Lvw3F92t)V{4%S0cGc4)xzZg=o~~o zvBs@)bI5QtTmpt$TuO5&IB z+!F5v;t`^Xl&GkRc4(Vh;>$q1bBQc2`;lzBOjP@yfDqWNs4PX*w=*$3bYi;_i0VWY z>6%>jBW>+sxvq225(qwUQB;{Q9?AA{Dolo6}l~s4a zcJaaN+?JKmOWxkK2;Pe2 zUyosyerOl`uveJld+>fG-;~~5l>hYKSW5aLS>Jt12hi|?y)nA5#d|vodH#JZU=yXZRldAY0NIOk?34)(4O@$~<4a%ldMFt6v27cU^F0Q>+AgA_R(+ z2=B4_#JQ+ZKuo;^)p|Wpd#!mL@a-`$WjTV47okSWILw~m1J+;Hxd-hJ0r7-~LSgze z_d$zA^BGfl4a~P=0q601py9`@`nb=~N60RK`9~~ZFg)$>QELN?z~e$mh1*a8m#Gwr zP{46(>0TGm7|d24K%X(g&f_OnG6;}sJs55_zb=D<{$t&YB?$W; z;M_#+Aes)`Nn^l$-a0af+)dzY^|`~O+YE3|S@~UzwJbRd?th4gG5s)kmO@Tj4`AM8 z2eRZtK)$&MR!3i$4Zm#l7)(eU6exwuXkr?%y6^$&@P93-0!~ej8z>aRdD{|c<|PM5 zfMgHsioXTyD-ow3$ut-`-!Tc-F@b$R~J6r9sbIaLx??%E1NR-0K783w&XP=zV9)DzkwZCAcpQO!pcLmGMlXN&Mp)(cl+rGyxX0MW%q^#%wiP8Z=n ztU0KIqDBER_3|jO_W`9PE(c6Vb!?6I)jp5?<>PEQhr8X~td6s}w z)*vucC&zFJ`w%AZ)dYOyGtnwEXvFykX$5?)IpR>+h?9cM+JyPel_Uw9OF&|{wEgVD zOIobF&F*emEY0Q-y=k#4?M!5^F8eWAgwt&qkJvO^*_0uHk%mzbEwUJ?Yducz1@NQ! zGVl{$;2iL|uaJudRk2lVWIqAst3E)xqT8U=>?TnB9TxZ%5Wo1S4=BcM&}_TzP~63V zDW#B{j>{-%rf#=EbL?SYC@K#`>&v4W+84mk5(j~})MS-xr>0W5qJ$6vDeqd1Vq4-J`)W}d*j|-!#BVwFbPyS;(W#glK7Z9o19Z! z+VxjJNd3G{i}(x6j1XE?t_=iQHd1mmI%&(p zBOx~58Hcc-0D$5$><%O!;D8bSqNDj)9sb}Wcz;#_?>+v|j__w54X?l9{Y~CGjL1{u zZDgUvWdz0TXMTCZOHRANRIkR(UiIA1XTFE2ynb^x@_$!P-y8kJHZPC{(iRwzbA6E{ zJ&U=K|661$sH_$vffIQIjc=jc>W%p`kC&cx^K(mz{RB07GzVX);}O)_n@fY$PBJh-yUDr)cx@lhL#8gP5rAA*cX=&OYc$ zmJ|I20%_<$ zjgMe{l_~>&M?w~PT+P%At};wpjtg6r5!$ro7YL}5_iV@_L~g~E&HOQE-*+Oq$4d|L zVPs@-pAC5e41NIAWO5s^&#IwRWXxw^xX*_0Cs1=bWCF|@>6thwk3c;Li8%2PUqCY7 zIgRSz_aB)M4q=jb2Jv7<`;Xwi=JHfLV=WP=q;Aq>3}mk6QXA`7#*jC#xksS%NA_X3 zvcF&~${(>K9=-;WWe$P`q#C&OeMHSJY&NbaDRHjJaQcn*Lx__v%^w28K6zP)0Aak-r)oM{-2rgFva5!^W#r8 zDuO>WF8@|~X`tAHe)e?WB#X!D5j8uN9hV8+Ac*P%BP z!G_jN+Ki{zb@Wazk5ave!Nu8{Gc5hz%x^1j^f0NI__`4`GSQGh;km{z0vLY$B!u7{x$__SS5iYlyNDes7d~PI$+fbwn zID>rdq>wMZOl8z^kjNyk=XwyYubf?v<$T+uYIvChB4q;*+dNdT3yU%SOvd$63@y@^ zsKY?~$499$E^3(!>*u0A0OEf>ib`R-h@UabxKm0eLXN#0``@_SD${OinkejP`Fsjs zH34bt!&H#j4bFI34h+ZY3-d~MAo_YJXwCiPjJKpWR_!hXOaXHi0fSfv>>Bb*of#j< zKJ-VGuolcsz62NWrL@PyqY@5+dB~Swc7rp1l-t_krkh2)4(2<)1Q+n9yxa-85%3e3 zf5uASZg57N6~4=rP!{G%$L03GQKEok>vwckm5>K!J^`i{qlDYV8Re`#O)ph}Yf$6ODYGK~u$mnXlSO&S%z^F#1jzTkGxrkxb5=?y( z2DfWbM6~1ZL!224tiO5yHUf~b9t>TAAL7hdW;LATs<8;nTM397ll$Ho>#TD(x!VUj z!QAfy!uqAoR;|{<<&&q8eww@(HO+=~#$(o(_u%nmn&LAc`1$9{piWwR7p^f;C05}} zD7cIwrpk4M8{HW%T0OEbaY;R}!xuqxQ#<2*s|ALMmUcA&!w8De$$-AMT4AQs!sY<5 z_##Q>i<}vMT92YHtEjC&?Dj;#c>H8%hGUPjTrp3B`J5*P0Dh4(BWT~6iz4l}bVVz0!pfMuXKfkDz?=g^M7ZUr7D=U2r%>UD1ARZqn14hJ~6#fX$xi- zUxN95WJWXld>oj=!IXt_^2dbVE0i9D6j>_;Lpw+soF(D~v9RNFu zf>ce|gy#Smf7rd@3CkfsPWmt|2|)B43agcLYD1Wu1NS2jfeoe~wt_j_>4mOg$?xD4 zU+Wpd*Sd~$+ymTrr;6e#1Cvt}haYIqhF{a_xjjNjZNR;{D8g93j`SM?7#8q0#El2$ zCLgD*6kBZDmH?lXuB`~(1mI2|OdPh@YW0L>Z#w1RTXBlBghv*y5~g#9@!j-}u#Thv zknxEVho#Aq&w;r>oEehr*O&2;F5@-jJH;U<;$*?T1+$c_N0Og}3UX*PJ6y64>Xc`Fyfbtkax3s!s5+zD)Z$_j(7E_31$Ic>?~ zh&_cXo1(avq>NXvCwT^`?|GcyVOz-&o?(ZK8^wf)MP+6ABcp@acoj`jetJ4tQ7 zv+kMVidg^zzb@m6;of1}U#y?+bH!{2^L`Hy6~lAewtreTcX#Xa91yP)rS%EEY-)WC zN@*Lgw_@p1oxcI%cVCu^Dn;8kb`E-{DqaSeGjSD_m4aQBwu$zKOQZD%q8(9M|7eNa z({CHJpTvMySwn#se~GM>w@aXHiv0t+6Wd1?BUs^~{2r4N!fL6vtL%*0nW8Be87v^; z{IHOtVNn9I*-veQ+^N)qjK+Sg+`-S_MKPM3g8(N6a#()~_X=XQMm z3RgBo73p;Ck=o1S1nYqBce)@3vJIw8Kro%CCYs;tbaz~ZhYtu?iC{x4!0mMJ^}==| z^E?3NqXZZYyiRuy0DN>+UIFu*2Z;6-?Ni@baoGD%F+T(GmxrQPF%8Z3i?wdHE9Q!g z*s#E5%880`JKezA3CC z!#*n|K&Wg$a3`+p8h}awz&*_+(603i%$WSlmst3PVgipMI8g-nQx8aN``@viL`#96 z0rU-l{M4A>GdO(zwOu4!@VIjzXC`-yP<*^_}j_(1x>&@JQV@#H{F958>uO{vZ+;! zsLU5w{v-I(^bdAZj7RT| z(LBg_pnyNsyj=Kmz;+rE>U$t9_%`&%VSy?Wm>ekJF9I)@^C`f#L&A6ut7YFV>AZa^ zAzURkYDPo|!cWyfl}*AQP_mcH==%6`3)0tl0!YDD{B5u0!f#63yODCxgi z_HiV?bP20Fg};mBFFY10Nad}-a^VNB?Z1$cv^8o6BQ@XQr_q+nX9(?zU^emqq>9>< znU@O>n(U4shk8&_MWH;8SuQ-zu&0B0s|O`j6v|_e&C(%++qcg4Hn1P}z@&;N8frm%e>?Ye&F(>C+%eL)tTx_T^>3H^hLIz5~yT>Uqyf`Iwn%ZI3Cz z)7UNQwwT;X2MG@pu%zYE5{9=6kkA=dj2Xe=Cb-=n$x}QQsiFVY&VmpnVRg3%HDOI;hwd!vfalOg7{2 zPC1APFER^uxDjdiw|ie8aF>v}TduoKu=CAZaC^=9d3Q^#>;3q5i1%CI#|!6gk@v)Ko{yPN!IGRZgjSI@s&ZXbqt2NOR4{3nAD@4|I!BJf+}R}5R}^(-_xsPXd65$Cso z0-xd9Djev1WOfxUsrlJG*di8=atGRN*)Dl8Z0jMpM|vP(hj4nz&>9&D%)LP+WbYuK z61stJ1Vp(P30M*%fSEU{fN>BIRRIPt5~6HR!ZuaGSpx)ib!0cJ&tE~zM4e>B^qtg! zO?oei*d?6j$UT6|Dr=ok6*#Ahj{1*pxSw#r!uT?@=sTy~EBQfW9HH*A6KQ5p5k7SPawxPKN3L%a%zF$B3! z<3eR#QYB~zvW+1;_T>!mEb?uHWX}+#;-ZG=3d$IQ&#yjCkZXt;ilHGkf-;8a2FyU# zuSY~xq#;fz?jl3P--!JvT>oZ>DBl?3JVfX}V~7`_?kkAPh{e03hPVKTF$B41aG^49 zsuDB=*~Sna`*Maji+tZfvS)~D@liuu4ayk8K?PILjiQE_rx+SyD=1@#Qoxi~Lv&OX zX^7Vpcab6Z<_25+-wYAu8$)~!5&F*;GLAgU?F5c9OF~pmSp&@<)|7B=I`Nj|}AtJ^Q+n_F|9qF*~-l!q22E-VG+#SXcU#Jo^1lh(A9{X~J z*o%AzVhynm`OF+4Nl`=8f!?pg7@{UPJA{Vl0?HVoF)(ddza9frMH*tB;x018EP$30 z_%DWt@{J+ZK}3upD$l`3d}xRf+xA8cu^SL$2y(M=ZNCivNndO1IiepDKPDE**&gR6={fGio3`V>>0k zzA?mjh|qs~bk&%Q66!${8DUn8La>by$eD%kw;%9mr>l za1xX;!aRV6#u(va#jrQTWBE2lxD}X9xa=O+?V|)87T{hoEYe^A`WyddgeZT%t{B#2 z*i8TBJ3IimQ(i_`5Bcw&ht&oJB<;tdXztNQ^BxT+T=&UWg)r3Ur`UtnICse`D1X0< z#Cw=>9dGqEAm0{wek?!>>9PET3!fX2uONFXpE<~Jk_d@I5j%jZ4N|T{Y1<@Z z%Go9vN;vl_Zay$;ammRY%2*Hl4#n;PMcpqzJ|$Hv#QUsB+XrcT<-D8XYIu$s2H<^f zkwLp5?L0NCNN*ex1nXZtOhaG3-lp^O$*y3OMblV6W-!x>!-JC&0K^1mH87I#v!M^D)*TPF}m8D$vDh zfD+7rA^TBW7%c3c9WcYe!nC3;))UBgp7oEeBd>#L28>-YI$$!;IsvqG zbk?X1j+r&OfieT8HZXa(>>is{2M(A*#c|fy0Lpc-_*65S+wS#{x>)nKseffpox5eP zM49ernQBIhvBD9kS`J#k3U5CUwZgLyY^*@`F$%YRF+$q%nivYqW(!U3+jt@(Xf#Id;z-mAa;%ZqM zUn22gl|0x3(g(0(fV_cgHemVAwMcnD#v(kAw3-VsST%i?rq4rI4{397Nr?F6n!Xlc zA=3C@d=E|Es_DBB@^SdIMW~dfKdkA85N0B6EUxc0{W(p43E^a<9m3VJ4CSBG^bZjp zLt3$$vCXRK-)Z{K2vd;OAJ+$(?!e=IK#Cz8inP7Ba#Ja%oTgVqcmQd?<65BUwKcsy z!oXr2Bj9=!=?}|~4N&`gm)1c&(WQTPApfaP47P{B}EGOo#V&lc*8)Tb?9|)oOeogj1=$(W1f(* ztB`t1cg>gl)jUcH$fNQ_1;n;6R(ME8Y(`|CvYf-R^Gd`@3ZpyvNZ?61fOWm2 zW2yAhFTQy6N%^iFQsPVs?Dy1@QmztG;=PoDwNktrYQ2VMlxyYLZP+X+#_iO#(j2OG zE^cW4+NHKrX@h9_`)Wn}-lBZ#74X@I0fQI~) zkYh3p;Zd27Fd)Zd1^yn9O$breF8nzr4{3N*!xuDsL&Fa>{6@pyHH^m%#W5+ZVMPsV zYS>uARvLEGu)l_*G@Pp8JPns=c$A7!!yh#KTf<^-vX4nw z4J&JyqhT`*+iBQS!@(Mk)o=#Fr{yMuadzQf4#poJ2zgpoYRY7!JT04*9;);{rMoNr zq|yGzb*RQg+`Q&2$M*`nCc`efjln%T!F=>2YS*o5~_j83f-a*|7JZanTRHL##0*q{4@W!EbW3R zAET(+2{{MygBduElM_-G)5F=e@Jd6+r6wk@p(D|akIT0p>tVdke?}VJjOT{>QtG@D z(h8CDDE*)Lfjub63jB_F!;#!Hgzv%uSs%vz@nUn0F986)kTG$3z;+V&cpLt-=O0Pj zcs2f530*O`ZHeEkvAD|DBbFG49Y6d@Xr&qA1~4Y^+W>K#S%~mkV}bZzOQOmRYm+?I z3}o{`AQNUx4Opc(Qz!n?4}~v%7o=n+y>&Yx%QO-wOdMSgv6Uv4*kUvyt2B~QY+D48 z)f$;!oWB@hrHPv>n4W^@&6Y;vN-T$MtS7A{C^R^S^*m}N$Dyo1a(ATJm83jlCGW_E z)|Hh`JTU^gXKVh#l6~ePvfF@G4=CPOIf;+2MD@!VMM{>*LL|pzuZq?P)-`n84$$=s-KhoWTtmNm zBk1~uPM8k5fuWzlf)Q+J=u~v2U?W4{jm8c(Hgq8ztYDs@pWY0*iJ>{|1)CcB-5}^@ zhJJei=;nqVun~0F(5KN@!4`&YS`Bo*q2tkd!2(0KXac&ep&L+6J45e;A%g7<{mUlM z9Sl7bV*ZaE76q!Q~6iH1rb6pJnL!gF(+W^zCCn&oT7o`Jitw zbRXJwzM*F}!mY8fIVL5iH-2u!PIOxEk66!Cz}SRw0x5SP$Sj5S!R(jvIRB)aU{LxD z!uh4%XG&qpHwfe6{zRCPD5TNQflyhHp(+Sc>LMr%;q|FNr~`xE42B{|8IPbaWwwTk z5oU(gAq;J0u%E%>44!4cZM4ui1f@Pl0N?g!{7JDaiY|#TbR~o83>q*fV9=RCUj`!> zOk!{YgIgG^W3Yw6J_e65c!t5t4Blbz8G|1g{KKF)x@71I22~i;Wzd{Kdj`E23}G;i z!Au4V8LVP(2ZP-Vcw7{Eioq!cZ!-9Z!M6gCZThu=!~i;WAiiH$^o)kJEDS^be zCMytgPNgH*vH|u@Schd+0!f-2*KsD2ie>diw$3E+#FJfIm^ZE~UfF#Ic|XGyoDH6o zAR>?~4%Yj)tNvKdHS;e@M=vo5Fzq^EcAveB%rr16`OK2?1eA~K*&damC>tLl#}$#Wq!-fq`x)Kz{xS|}GrjZ@%czgb93)G?Sno6M058fMCOg4+&}VLD&QiiR zdg8|4)e85wRNw^w-ta*x-UUtGKHUX<3&0;fNF}Ans2z|rQ-Tmv9+xpk5Q{FVRa&12 zkDIgbTEud|ZRR0Luv{o|h||HM-kG@DM}qW1(4Qbr{6%3E6xG| z--^zWvu-I;Rz8K4ROf$8cfF;fc$+2Rb#~CQtZb@N44u3z5pnR7l1e>-1*80w2O%M8 zGIwFpQZOh2X{C@NX@?(xpg_W5B*~RK5pj|l$zY^}wB?6}U2cHTmyY%gFy7 z3I@_vL@4D9)*&mcOBfw0tqJC0Cs2WoS<=#x$zW%u(=kh0rjbBl1v+L)D^08d9kZlW z8cC_R4bqZUYh-=~9kZk~adTzTF-yAH(r8>II%Y{vS|g!DCLOb+qtZXgX%ey$nsqtmHwHnT}aXNt3z4O%o9* z?MCRBrKD;kvoamClo4*>bj(U68(DPBN|iJ;9kWs?hNfdys+6JWn3XDRXgX%4b}5}s z$E6nF@8Jdn+sJWr(n1#ZI zrehXrVQ4yLp?pKrF$)zKnvPkht)c0dh1waKj#;R^q3M`~IvARcS*Vkt>6nE&8=8(; zsEdoA1iGuC>6nGO8Jdn+=qf|gF$;Bf)6sk(w~Np*3-vVVbj(7gF{;op3-vSUbj(86 z7@Ce*sK246nFv8Jdn+Xt<&2 zn1x0dnvPj$w4v#kg~k|~j#+5Dq3M`~CK#HIS!jx(>6nG48k&w-XojKbn1yBxR&9W%=~W>q;wr6kpn5{WphD}De& zyRL8w!@8K2gL%k{I$2X0t>m=@ZQ!BgC+F7-*+m~8Z$`zxM z^|HR&ifA>dsL_U5{0v%Zwp*hnSzoe7wcThqt14PBHAi013P!SC#$ZXUFI}|yZL*%p zMzn#{&}h4?mwF-EP^zlr_E}xwl%_V3h8pdV)wCx}*HX@@s4iKz;%{mvF}_OgthJ1G zcBB2WHZj`8jSkG}gEmO*>PClVaji}5CKvDrU%tp%P{RtOc6W6ill4$b6x36iX}RMA z)gMFePkl7IaWdxW)F*>Tu2K7bsCI-TTCoOyxHI)=X^lBG#$j?uJ#Jb!5$oVtw0o+< zeiTdBM^pjM^?$57X^@%2j4uH2#wDQ411O{6Oq8U) z$+rOfK~O_2OC^Qm*ndS6@CLpa`Q26tty!{^4~zLetC^m4b*%FLw7rX zYHfVHsX2;}@p1@BISZ6l@pY#{75h1)eu1kVA9f}oIqyxhVcyBmAb0$vnJyV9ODorJ zN;M<}>rBp6iu#J8az?{Uh72@d$=s*<99N~XcncTUhW8^8hZv2>+yuq}Tr$3Kl*}U^ z|C&f`RxJD-*gbB+YdXlk8u^>Xvw$!w1}ROGV`3>y)fQp3#hOfrc%C9!4@LIbxbA|8 z$0$OL)LMjAd{Su16q%zX90j8z?j%3A=I0S78S#|MO3a-;gSe z*z{3e*_!$9BD&`16F==*`^bIE=Qm^*h__e&?I`vJSNv zy@k>CtZ!{bmmu15KckH}65{Nk*r6?pNhi>nK5%9mJ_8;oY`v3zT0ev^r7iDx=eK#$ zFy6tRxUyd$Z2c2c$~p+!*|=A2mx7>m1q6ldYB1i2K}!Z*5wyMrL1F7r8uHFJvt1#= zb}JZcVz86JgA9%^cpgEUvj_sx?j!tZ{VjsRcF;G_E)m{TyD|(i8Stp7T@wav7<6Ya zkO5Cm+D&Ir$Y41GKHS!B2ZI9)o@DSGgV!0HXYe(HUl};@2zXG^t^$K>1`QcR7<6IK zkHNJJCNr4JU! zWiXz>EC!1htY&a0gFOfW{HU%K*pq_07PG(ob8*rA?eA{ExgdrY{g(f4_O~4;&Y6ZH z-F@!(75{L_1Aak3M zEL;V$eoK|} z^?ozi+;0Y-XF(-yEzR8X__%8FsyC1?dEyWF8hIf3&}mFaf#f^i#`(G=U-J*%q(os& zzDDii*PSK2>X$6+_cP2?34ANrdKTQ|J;1;bFY(gH#BRAj>~qf(d+=RiUqitb-g*BP zkrJD>K)5!N-LUI~x^L;|{J@4Qlzl7u) zA^*q!hpq1pjG}no-`U$-Hp#IUAV5M$NXS9pF7%dA14s)U>C!vWiy#OR6p$cDM-Y&p zA|gc)X-Wwo2&f1M3Mc|9Qlv^(k>B&ab31qU`TqWx*?D)~d7gLb&d%)Jgj=g&*Zpwo zEWjRwTf_I^ABV%OX~_DcaO(mLd>n3#x=J4tT0K$ke}`ME4&b>TZdC;4zv0&MNTEFq zw@gU?gP~TvP5ZYz8Rp?KAyW+O`q2*n1Th~sb$lX>pY`NyPZeoe+y4%`v1x4<* z(qa4!m=rFwn{KNk772Us^XRjqW6khOHeEC7q@=ckB#i&RtXTTE^b{#fqYop`Y%jqbB|%0 z4UOy()ZNn&Fq{d3)+4Q-f1|cD0II?|fe77Ng4%FcJ79@n)kX6Rv+|*6oYvnc`*5oz zYRBRY9Y=#Y-<1FTGfD>BarV1>$QXXl%5Soz$!cpv=)%3L)3% zD+`~Z>@@2hs^yAiMWV2;YSy-kC_BySbq&o`vl^oQ|J1CVXhrB%jZv;ggw+b|?WnM{ zyPEd3u-c+N*6Y?e)c6M7>VbT1)U7U-&_2Ijri) z-D8K<0@eA%VSRrOt=(b$hu;5>!+IH({p+wAp2aV-9M&~7k^dalAtZR_uzH~NWgFH! zpqw$Rw^3zh4eQi#v`oWVio*ZNu>KbKCLzq)53t=~){1{n|6x`VdfwhJD+iq{*J%oNdB#9{fCabDZ(0p zOmB{`#vP;=0IMwqjYW~x>lil|M_RisA!CtNX;k==NNWhjo1desr6_{)QC3wz{}N?g zL4pfW)^=25p35o)lzlGCfgZcxWfj11NX>3D#*~%Ih32k`qA{GGiZj#<2BRz{TL)0p zn$-b~S6Fk=k96w|)Sg3gS3{N!=Wfv=9PxQT(ySWjk;3W%^K~l&zQZaBI}K|!8bO%# z2O6i-%0Nd8x6Z(hB`JCi z;2Ml3CR_(lgu)exRv=uhkV3d(Y1nm@L@@~0H)s#Ik6}`{l3=%RjYNS6S0~hla22Hc z(Zbb`uFgwn1J2psBMXu3zeBKto?8fH6|N!Dy$=1+aE{jhpnN*eEYUTPbzz0;WZ6A5 zKZoXuM2{4%*U(&r`yhIb;oPT>GNHQ#)u&nIeg?MH57AN9LkylSs~kF6KI<_`#g-y+HRzH?xVvElG~y1E-gQ_9y<8|jZx6~FgF?c8JSZ$jzAz}Hp{g(_ zcrjpLP()UzYeq75tjIQMKk=$zKOupk`!yyzmr zH51KBlavTXs%~yD8g9?JnA`( ztK16%s8yZ^nqj#$7ZlHYLF$812Etl(hRhs+7KOs>j^<~$i~30E6fDuK;#>wl;(4H3 ze`Bn0SUb^`k(Z&UUy;AtOkhO54l3so{ZU~I2Mf}1C;z;m8+)T!3~`!b@|S>{!}K311_XXeY&NBg3?l z67jqY(@sj{7MYlKQli{4ae>!{K`7uCXeTAA5DQ5~`i_Lq$4^c>DK1N5U0;Q;TZU;T z#T6~Xw3Fh>FT=Ex;wm7+w3Ficki!LOCnaB9WM6r(&{M2lGE6%uR&N=mofNB&4AV}EH9&@G zC&d~l!?crP4Uu8mNwJ2?FzuvRBW0L&Qmj!jOgkyoSQ)0B6l+Aj7niV!a~69jI(4%P{Sv6p&@E#ofagQNfw|J34jIp_;P{1+YS^h5wBJIbL4S z*~d39a^oeACK#E{w4(WCs&W)isp!WcQs18{?itiw&WcS*eXQoJOaZ0d*;dDCDXWr>{=|m42zMFSIyJR<&qn)(@nJrHkf-2gRZTRM;rmTZPS{y;Rtx z#oi2`=Ew74S7)6R=q@xA|qYKIY0HGbSFNFAkQYH&%Q{-NZn7|-S;=LCjZ6pXirFr}~Jn5XDN~r}_q4*Q1V)P0d?JO&@3gW*!X~WG~UigbT zfi~QfXe7{vo3nyH)=Z!cHzm5XV)UkAIM0azgtQJd;QU#9FSDu@dmfQ4=XLQeA`@TM zoHuNe#PI>akjZZPlbKqv&YbM7I7^u67eRQ>PMA=Ta%YQ1!p@x#?+23hK+;&}--15i zPv}5Np9-0IEurFJh?*|*X(Y73ywU0Ki)O-tI}i=O=t>xe8JIKNFGeSv`x&vOUyRX; z^NQ&J_JuirkDI?JQ~IYQ-iYGTK>2o;-6L z{nzQ!G2~NQO8AosEzJ)Eme(1myzVOmptmurbXN4|6#oN}!$4K^jud$bQz>UP+k}Kc ze?zPu0Gh+PHTBm?w<}FyYAfCTB-RP&E@IMp{8pE+5pxe`17&^jWr&P*Hqjd)QOm-b zmed~~pE;Yd5lJT~t64g=-K1p9#huM`YJEwC|HJ*}IyJVWUEd(wf~zO#{BDF>>eM8X zBJh^xY{gZPG&>ELt+{NIUc>U0vkezz@}Lo@qPAReN$+1q+UL1sl6p|Rw&TntEkB5G zd!1USR%`{V^*B58zx5^1UWxMsJ1Yq>_aS!G--inNd%}q85WD$H*G!;)6Lt2`>9c%2 z1-*&B%r~8b^e>U;gw`}t4CXM^TGHnbhuBR8i@`^s6hQ-3F?tO)os)QCO8soIU47Kg zvi$-+(76GkE|=D^!R|MMPbHl;^`p3*L!ntWu|B9xLN1r-7ywuc1RkHKo>~r^Lpm9*2}A4NKDE=$)>w%h!lNo}q?ZW$njKL$rBU zIVn|$-*ygC`F_yWQ+jG~BM?Y(Rh~r2CZO0|RfD-*)ohcOV32cFm(NC+JQm4JSIy5T z+3v3pRT~2{5ViPWrvj25KN+(IR~=GA&p~_t9H9vGWi4(Z5Mo@73ls&yhnOiJyh`;jSvB*!W4i zAXSr6vG{L~K}wfWQvA8okZMTD6CeHvQcWq9j-OAq)Rw(3E&e}}>Po3f{BM|UxHEs@ z%+`u8jTYjrFP~A*#ZTT2sex=EP2!v40p@N>_)bqmB2%Ij z?XpGBz^W4lkdr8tly2w?qSZRWpQoh^e1f@JD~iBRvr~qlXl=>#JV8}==Ni6QUcxmB~ZG5d!+IgK;ppZ-fq=o{3CJ%gb5vH}~Uz)FcJXQ4NaGM$Zh`rdZ~ z0KZXy<7|6!5H(Lhj1PjCdJ+&52_hHqU%*`kL_%>pOA~FI24g^#ie%GTDDG5%uPVS2 z!b2IHl83n4a5Q`_RA5tVFnSJ&Df}ElFYQBhH$}D_Gv#eOUc?kiq@yEU{fi_XXXZtF zjsWteqJ3S_h8gr^EFtzhg7)+~&~VH|p9T3@MLyjwj3)Myl#hA~@$Q0cXz(p$vyN0c6Y z;lBb-X8diH@i2olN{OLAL;D@tG0cV5=WtaqM3zamv;U55z$?#4QNp4vKyinHU9MnD zh?+D&t;|E*Rk)!5o3FrD+F)TcIIfiSZKOQ<4A3h{jdBxDxmme_C70(2K>kofs}vDx z9~u$V1dtU9QXP~M$(RX=56H|rNEP`eHfUkO6DY`s#s{_uIv#@J1Nu&Y+V&GDn^2a; z^r50DB`RHl-dfV5(@eZ@=K+{i!UkMx1E$|0MZ19FpjaAC0$<+(5S@@N`yw~ z84r-faFXnEMHXhzmlLJLX-d1BhJ##a9fsQt%5N0q?sdVGyF(~c|KHRUxko;6+-q^2-#OQSp+~z!AY_sL1cqyUi1z1gbIj%5w0J|+$HUt zeIv;X*|xrsWTvdSZzP#Z*4#IeEIM_d8n=!~BCfB9lgQNx9=Aa9A>0ZOEm1@#LUMH? zBv&WwTy=a(AVayZT`65?GQ^Pjyl82}328)(XFLc#fRj1?J}Af4sd#_L1;!@CABCf% zF0Lsg zQBsirUh@S|z6@UX2;B^V;pF3Z-r*tz^ySgF4xLsu( z2kC7p7&^}91Gt+2JEXvF+tyV*Ns4y6n*KXUq(-HmgJkc)Nn7tKTf>a%E-L+*^o+Pq zB%7f1D`{fJ(73c+1ov$cF8%v<=`-bhyU#G?eM#vr{rh(5?*!yUWxzvaKnZ*wkHUI# z2XV#T!i*oZn-uL6o0f^5*m>Lg3#@(OZ&@i{P|JBz57kG*>JtFb(Lyq(|0tqTB54=& z{-bJ6LVRtwMIh75*m?ZVCcAls6zN+Ls^&6KtO-|!UlTN;5WV74`YyyF2r?5I-Qd0j zWJf^y_`SF*1yJ|scPT#ZW1^d0^g z<`fY_S# zL9>F$M(hf>g8(d%W@oB`0^CHSTLppV3HOg2s4i20m4X4MP!(1cxrjXm_Y{D+3b3jT zSa!s)PNe34(Sz7IAeug2%BU*jT87KVYZ04MnG>S+<7pyEoT>P(@>_SHj`&ORA(sYW&vog*#0L#TXIvK3yqKA3SqvxMuE0e zpj)vC0o7c8BU}pAj}&O@V9*XU>_5*V&?aacfNKHJn+o)K8`QHCar+cX`(Tu7G=6vD z{2qtKW4LKR=~>>+ZzmhYmk%p_P?e7-!*_vR#yj~3F4H&cD2p=I)0-(PKqCw8 z0VqpXuyfg4QE~A8hy#KZofVkCby1$FN|IDfeOcNKTjw4LT5Q z1vsizv`b^8;$YB`%J8*N-2o?ycyuu6sVx8<%bI!6I0ttcp!ADIIcFHFKzV*Xmh(sx zkt0w&11CXW4hB7V2%xX9r5B-5cs{1+7@vz(vO!-_plsoaC{39r*2}}^R*3ftvZW1WX$~NV+ zP|9hcl+!{frzy(L02-?(-w3As2*o32ay4Z`<2|^opd6woXNFSFRFv~?aY}p8%|Xgs z#W5?GqZED2IEPDe6Eu#(-2}%z#W5$8V~)+?*$LId3UppD=(~GBzmN?-4vo8TB}>6o zvCC?q0_8z$p?^d%GojH1 z?puHss%mHdeFZvxB&$*`s3$gsY9|G{IvDgIO?f`zis}iC(QsjS2YW$*eq@7s1|e>w zLisotWnUinHVFEFHyaxB;c5eAl|tE|P;wAASD}0&NXP%AZpBaPEBGE$e99K(LT?}3 zOTdb%W@qzL8_RbWd$dsX?+W-H2aBd>EmH1POrHgqykaXosDNVde?|S$zMCdpcV(Jdqj}+`K8`kp#@dEL(@$3oU zq=|(W5VcQ4BepJF0^Tm4D1?1Bf{zwNp+;X)kzsLAt*rnL1Or|;2hBqw6S2eL+5>Q0 zb-OeVDZp_%SdF3p=qr7QMf6&TrZ4vni~fxw-!a;5J0zrXw5KU>hbs2N0roJ14D^bD zw~_p7F7Xl2dmU~z>^Pw8_}aF^GahkM6xO!^tTZu2^+z+X%j* zRD#EujEZI{RM#rNlL0`l`0^WQo@UKW&^QA36rh6?=xGJ|2aP_b1$}=`pgW=Zl>+@y zP!fMTZjW}HCbnON{yA|RI={hHErXwrDA;p0tmiD^E-9R!12|qWlzPGiHtr5I@-IRe z1Eo-go#P8OitGs&LVJQOVh0te-AFAP+ofQRxl{nZGe;6M=n%)%;CNAS{H{2-C;Tq# zo=^s==?e6ZV9;hX{9R+vOlb6iI}gxf3iO%+oj_G}%?9Fvs*?!Eui{a-s1#Tnli# zp*Zd-j;P;Qm7=J1tcB_h1^OTW8fMVau2+=)8v2hJIuCm1;HClkR|Wl8LGQvBB~Z1Y zk3jW|g8n-IohF`r4$!CKB4Wj2%)S9wzouOtPZeOoc~+BM+3=+Vi>BuqQa@Ap&w}wI zw<4jgM+3Ve+ymghr|@-s9S;?nkLy&|{SC!ep6XQBzn24vCk`pg!^y^I=&IwS@#3op z*E12@1+FYs2kt5SaE0H2+Dy1E_m}W=gK8%Q7!eFufu0C1y(eNP!1V**bG7UOaVfyU zTL9=%fPR1^D96eEAs31SdjzOB?_=$0MIKc(3Gk$ zfBlyWjnCmu1N6EAEv!Jfi51rEcCZ$zI}~Va05naU+yT&dJrA*$;PR#6)u^_e?RW)P z@(HU^6b<7L25egQ?`f_0Vc1wbr_l@nIj1r_24FfBess6o05uyTV2V}R_FgX5(@-n zkg~4gNDb!ri>5$c=4cI#k#JkVF;Q`NLpi*PgGVc`%139U9IiOh0vu_gC%!cl<@IdD zE`_@Z{BIS0d4*qpm3tUO8e8knY zi>HbW?OBVs&2X}is|B#UV(u3}$>;AY|B0 z#@9uPGS=l=LTjFOEY>`MdsA6ZGuVPPR0Va|f;-SCz69M079?ca`KS|WK^;BBf;yoV z*s*>K?AU0}6JRF*Tb4m)um#QUA}0;lf+T3Pg8LR0tW*{>P!{mgTLay{^yZ5^!zoFV z=1CnNu=p{HE+79jT8~|&3TxyiGo@|nniqY3~){K z)=1L_E)1(cj}R+gN1NC-c{(Gmm%_~o;HHUgRJJYj5r};qt~L-d>e&b_6vBAKO;HG~ z0tjC5Rvv6<%N=AcG&aM%1e6sDrLB$Pt9zYQDT;=aXaBHh5B*D#@)O0;F2E6H(1)d7 zG4CGqJMzb?dC>bFZUdOEDW;A#ljjKHPAII-0jxB!gK754xD-=xAWW-o=eVnl z;2ZoC$hyieWnt^j)BFW2yr77 z%G>}-nz;NBwk*)I5xW4c1rXLLgaryA2XXTh!lGb=-Y0>uM9)R+7Px6ZxTz49D1^0$ z+pG}Y2_Sey?>#_R!8yr;#`kc$fl|4VT^=hG$`Qn!P$(+{C~0CajYse47ZH08?g0>9 zQV8!UglmYqs}Md2Ab7>LXFyn^{}ry`fr_16xU!Wr?W{ssW25*=?_peQ#h%BeJ++pLqp^p?~EsxK+f zEy19}FGF)1gJwhH6SzwN)tlJ)*cJ-9O@YpV>S_hLBN#ONcYuDunwy|;0Ip<-;b65oHP^5!dw+mE%%GO!6%(!@=|MSYfWI%?D%g0wc%i> z4H8J%a8TK>L)q|Ezy_~aKu^D;Tsb4a`~}=)u>YvokA|`zRqX%L#{x(7!NDbPl(RwX zyS`#v`Cbs?8+s~8j7>eRjQJ+mm|djx9k<&&7;+A-OchL>vh1SxP8q`+6yLGk)cok| z>ocUzUrL+^2CYpq*;A}ZC+{S#!1M~B%M|D-1r@e!a4M%{R$<>Nb~yrDRr z1an-v1a}M0CPoH@>+dm1F#J)qPnL2qUfBVbWTNA{Rd9TKNiNvVsnskJ)CT9W-!OR$Iy&ojyz~Qglhqg z`mO8|j0)w5QXJKYBg#RV^g-HpNO?nXjtLVim7-gQ*p&~`*ThymxWxuljm8K>z~o7FRMnE93b_IUH?GK zBdci@x)j_h&~9kb1@O@1RvqRvxH!!sN|&zasuO;?${o|C zJBCU+Uq^b&OLu(FVod5C#a<(r{dua&+RWY>%#-0BfPJcBuN}%>+h+Ilfa*(dvR~H? z2ED!;hSir928~bPGHT#;NP*T51+A|@=RkF}0(~wRblgsWHg?dgW)n1ig_{J>a_#JL zY8(pMSb^?^>KO&vG#IoeeHGQ5ExiMcI`89s0HB)`X!B6e<~FF0duwxt-CJ+%g>}sx z{4-q4aT`*xHutx*SkE(HR{^#xtCqnQG^1>_;cR6>BO5NPCKgBA+u3RpYC)TT1)p+C z`IWiL#~-%0@z-~Bs_C@po)4yrIf_IbWYvIbCtOp|y{_mwgwl0TbdRoZO48(k5Gg-_ zlUeE%;0QBb;(_oNVtRp@@}TzwZZ?>1DyA1gnO;y#kBR982f+~2cSw0#F?9S7F5D$>+*cf9LOI6R93D4R zOT$UfvB9AA&jEBiYi2^D16;}4*yiqJ7uhwBEE zISS=f8^zb{GOOAv9K)eH15TQj9Sr*KerUeVpt;bv0=EjFdS~0T*A?h^szb(VkBLbY4+T3#P2~FA~mR$~&a-A)d~l?5`+igi_83rJUjC zFg?$Zx;RqHY|RYjSo9Davzem;GzO7Y9ee?%IA$vjesi8}SEJlWneAAaDZ4{mr0k(M z<^*%(oCe2y<`@Bu_uz(tqj(p)=;nuV%(po_lcBmqfi4UN{q%Q$zRjSUpz$BvW`M3& zpl^qQzHNj0cv0hR$6$V*x_tEi1^|+eSA1=KDoBj+Ew~&c#-^q_?NVGCY>Yt<@a1fb zwg$r&+yfXB{eqpt<)OwbSH_e*z$tU3F&;NkmWPuy^=>f7>0hC_ia9c&F$ylDE?T$Z zSfx04X>yfAf*L+vDzrt@m;WCI@-G$oI?~J4Du)#DX%KKnC=1>XwqPV}&wnU~HE1k` z8wm@}C<{KcE%4+ZZlOZ?C>Z4@YSrr)B^Mee;no7BY*)Li*4ZfXWp15aR-R9wdRT#O z2nJ352B4d`a4te4?jt;(06I^BZVCn6WP|$n^W9DU>UVi=Beff;Wd(d1%#pJj99x+q z2^yW@DrTah701?4j;)HL*-xBOE|j@E<&m-Fn!CeN0)uj|_m z702-a2ljmOp!vNc7qQ#mW&?kv!vEgJ_pC+SXA0qTFv7e`Kse*bL+tNx2Z8WRA)K)h zTz}_P z{bf`C!T;Cd-2(Hc)YeYBgf9fJy~0hl|H@U93GAM5_3Gp6Q-%Ml!k@p7RdY20G<;(Z zu}GR!!cCE~JDjY=-yL7`edvZ62N4W2_QsJv+NI&!fd8mDUvUuI1i0~FEYZu((G|rw zjwr4;C_Sxu4}$8;isD*;!Ydq)p?O1&$Iw^>w;7<*73d8GTKF!j@_*?d8xdz%Bu&aj z4pOdE9Jc}-Va6<|gcx~-T>OQ_T?eJ44D5vJVFi9K z0PYnlwgd1XxAf!Ccnp`^0MowScBwp6pzUboRH{-vaJ4-2H+<7~DL59tdI8WwMfo_G zvhjIP{=<~oI&1>Nbq3{fMfs0S>4`vGemGgVPlHiTp9G4=e`u2gjT&(CfO1!%Xa;T} z`=GjdtP&pmNJ9ZrJkhH5chag-Lh<-g=)LSs1G5rB^FW0yu)C}@}s>id~qQe{dS zWO@AnJB&=}@^!neaIt#fX$oBW3l(WWc(4V@G{Qz2G{TO6#ymLj95#xS1(Bf^L@EoI z(iSoDAmtpz;R@zhdk~;*F1lQ3d+% zeyc3VA8f(ppP?DUyDG<_@eFPxEci)T5EE)aOsEC6X!`gE$uR~cq?ffUdWVfM{$MfM za~8Nyl?8pb|m9j1Dv0=viLz_i>mM$0lj((Fx$zK8K%}^s@^kF4UyBP?KyC z+s;T?98Okle1Oy|o_qn0M1%g_yaF_4z+D2zGsTgpIHn$EReKSg{yY&W<%8GdYm9?> zAufobY{&Tc8IHz2?OnnRS#va9?EWurZ4A51_@!W?k@#=eFxl@iajI1?iCRXrtcTDYCjP5Va|UoWkF})PEr=s30ROOE`E!I^^9!9 zegZcL>B|*nhZkOQ0(;-dk%0nz{%2Y5Maj)hQ^vk25qBlf(HGy z@hZx{vY=6@1&u;2utn2%jwVbJNLkQGS+Enh=amIb0v4o+tMtm-%(#eH_eS}JOu~zH z{+oreHw$IAMbq~-o}vJ;cLTZfn<@5dz|IG3ng15S?1dkJy|odI*cNd48)F4jv9}Io zZym~Ri}?1F<}TE62!|(b{iYtS1hv&6I6zgKf*YhlK5o)`*=9 z*A%u@A8eOQ`%v53huUU~e%ox(-!9v$lIaZGNs7H=fZZ#uKLC3d9vQNsu@r6!ESRM% z=%OshpepRbe@jJ!P7YMxR-j!CO5z{O=zu-1c%7hoFmx{T4#VvPbl4C(b3H<#d)Uyv zOMi08q1?_*pYI%tvZP&}wE#M#h^T!`K6kmzg6Q8t=fJ z0LK%>@p34~%QlB62dYaH=!9U+N!o%_3A<&52gm*qrk}PZWjZn%rY)a1)sGCriO(iD)8fFwj>WHD37I}q_re(7@ zOLUf7MYzqtpQi9sDk5=vb>^uD?sNJjSoO`9&=x;!uvoHiu_CRA<1+ za#|7$x`8_QG6tOsjgR3v19ZU%8+2JH=rRSm6sjM=NzfI+pw)i^XfA_pg2o?k^8o4@ zX@lm5g67(wzBANna{UiFyt@R8F5iJ&9BY3Qbu3tn@$3Z6@5-R}f(?3^9)qjdpgYhg zyBU*L81$twXmzMTtCc|+RI#g-L6!Cgi7sCl?WWqX(Z1vhL9sEuTVJwBEc(1y&l52F zz$^=FO~Ae|gZ|&uE50SJkJ-u!(CY*zn&A_NQFgI?9BSpq%F2oKQuncc)HZ#EuLX%N zPX>TGz)9lu0b;LcaS)oHFlA3@%z(=PNhswfit@$doKilUOkb-VL88ku2td;n z<>mlonkYkK;b+EN#J&$V5_Eqly3cGn&r-y#QV83E5hCfAgFB5)h&=$e76?^F+hw#< zA?!rlK85f_0KqFN(%Z%!&h~L=Jb}9elr;)vkB#EHNiSwnl@?US-{h2}iSFvVLoI!e zv4KS_r~v4ZqRb0Wh8c_TcndRD!S{;!pCQ!&rq@12FNTY2ju)OWb|wxe`U%8$fKwCw zUE({yFf>|3AZ2klS+fTNd}(4cP1+6{6%d;R*9Q0l75-s`&wz*hfcP^ts5Vi6M}qe@jL@#U(6)UbD+Z<%3Q{F1(6y2v#fwuUsW~*%j-O+>E@AauP}Kf$SX%)4e}b1 z*Ot8QZ$E;2M5j$8a77L=>ru#4J!tk z!wlJ?w6JHlK-IP`B>dZn3kM-Ok&5(1qft5;c0cZ~4nb0OprPR)&U#|*De zcgn1XSD)-=UJ8n|;mn1yrw z8u;OSI;~^Dp8_)~KAqP5`y}q0d^)Ykr_-AL(`h64G*3qx@s|V2$@m?fW)Aoj&tAny0z#BIZMyDNpk>zUinx|PDvOtY_FEa+nEtkzV95 z7J zvSB!Oivb220H4rl@(G=07nr1*d_t$mCv=*8LZ|u1O*BT6Pv|uHgie!B=rs9+PLogQ zH2H*1lTYY0`GiiBPv|uLCv--vJ58jcbvjAhbUZ*qH~F|slaI?Z<#Cx2d_<;WpPnxa z@mo+Pn#o6GntVj2`S4SGk#F)5nI<2RY4Q=7<~X#KXtVbjER>jhM5f6{WSX~eKgQ%E zGEF`r)8r#EO+F&iSDUZN3TVX=_2OebS zCR28v>POL=&0i~%p@%ST3A0Qpcc^#zaEJP*C#jn&hH;0=?1UFH&Aft6j1Cn!3rnV& zIixFIwl#AGhS?jMS+5N?_BAsTu(xos3C7jint8q>hGE26SRByI!nH8*(#+97xd(2P z=Y7rW3kx1-X8cra3~A=TNK9umv&BN}Ica7VP@ZUJcbN3IX8zL+=i6##dNvj~gn9NI z%&3J)e~EEanEgv|2Y#b5{uEG{7hwFi!W;vJW5Vq2#b$;uxA()}*b0+22G{H6nPjZs z>1LS(?&CdQ##*6nem4daQQho}!FIE58nMW9xY?yTH}{+(05i?oQ27oQ7ebIr`D!9=q*kA!8Gqy#BL4JEx=b9rrG#atjn2Z z42t!*TjK){9lP}RQ54}D^H4uVT+wh;OciuZ&6G!GnhVhzFw)5*GtJa*xnfrD+HRUmA(bND5$7XLA);d~%zSmqJ3rFj}fGSHWoAl&4NcJwjPIa#o?-MUsn7a&*jOLCcOBfXANW zEh$CONsf*=EJWv9l?h=k3zMx++CwNR{Hfdt(GaKUEQYx!|fL}PW5kesrlJfT*389bRG%h+f(X7ic_`;vgO*A`7G&%}0 zth5A(?l2L;8X2(z?Zg@DkDvn;o#i+pnhsQSmY3nM4-l>(!}K2z&WbWj2P!%%$uJ$L z=&UTm2hiM{Rb;r(bcCzQFdeAqtR}&kHLbc7qqaAm@2B*S!|qO-9K(}9Z4CNfM1 zDmt@dm=08QHj`mGP|?}kuRk2&7BWl+Dmq)rFdeAqY$d~VprW(2|Nbh3+sH5-sOW4f z!*rmcQ`S;69jNH+B=6IKiq6h5Ob04DyT~vdsOWq_hUq{>XIB{>HU!~rGMwu}xVsF~ zfr`!^GE4_5I(y169jNH+CBt-}qO-RQA5B5Hj||g+ip~KtOb04D2g)!VsOTIb!*rmc zbEpi{u7h)=4AX&%&QUU41wF+%R)*<7MdvsfrUMn7FUv3;sOTIo!*rmcbAk-Ng9nH6 z6&a=j6`hkgtQA-$uy5%|T@{5*`=Oen304vr-fSg~^ zVH&luU0PrZ^i4-*55InW3Mk;=w!Y8`?1W;HqanRN796KJ8WR>23%;zvX2J0)99?jN z3dd@N4gcYRcnMjB@g!{Yn7;U93OW|9NT(L~c~+IPKy!9M5JzA~rJp41uM;p*uB?sc zj&ngrL^$u%A%6<$M8rKr4J22Lb=CJ4Lw;Sezs6HI)-|UpOLOVagIL$R!F-wj4qp~* z=gYzid|C7_UltbyNv!MbbiOQU&6lO!`SQ+mzAW3om*vO#vf?RU-YuF)>2fRa<-PWN zd4DutKA6jw4?pG0+EaX4{|{d_CKRW1n`-do(~f-EGM+D=(Z6!Xy0&iS%QpH$?O50L zYkb)emPFFd^L+XI0bjl-oJ==&Rp-m@PJG!jjW2sw@nzqad^vE5FJC&)&SPB%sXN8G z4mIY>R|ENSIGZm=-s8*BFZuHIAAI@7M01XHeVfdeV>S5lT^GI_e}yk6mht7}E?kPb zBE_$KjS|oJ>JrHwx?fa~Jw;s!f(oaoD@jnX6m_KtDv+YCRDZhC{&ZzHo%8EVRJpzf zzYvdHwp@cL`Rd^TflK}Bd}+{>FVA5#z|BVZ^bD8Av3zMlf3FgouW32HG~3E5&GY!u z;%mON{DCj6UtyIt{rK`c9)U>LZZcomW1<78!~1;cl));UpW{oHR(yG(3tzfjVwLVU z_|oGMUwY!#%1GXOI$!#Xz(t>kF)(s@JH$JCzD*5#W*_*mR`st-L)S_#?WIe`b98a{ z|Aj9D3iwDGJdQ6z7V~B3M!pO?#Fyc}@MUCV8flJ6<;&Q*d>P-BFB8V|<&|Z8nY5cP zuU_O!_AS0l(aTcu*F1cAy&+$w_UFs=SNZZrE?3li8o8x{w$Cooz z%2C|ezgRj~kfonm^W}G${Hjdwr%Z4|YTlHZw`KA>GQmAb^ni(?yI+U{baanm<>}HZ zl`p;P@ug2EzVsczmwq$&(tjmi25jfcz;k>V^e27Gz72Vb&B^JU5`zD(W1muY!?nf@bR zX57amJ_c_jqHY2F?aNnq_8SGGgd?Fa8U#jKk@yy-6$PWkf+8#z7o<`UuS5l*?}1B- zu7uRd6rWreL7a$m2r5EUP?1U0;L!ZElt)7lNO|-k`5%4=Ul(}N=dYKHgyD-FATQAA zC8RUkR)M@eFph+b)c=L71%B+<2j97CVDZ)E3iY{ZAqdLnR^`1p6=p~h3`FP zjY8B;@dvEJL6XJA+3yhd1@aH%qHsyKfhjb9M4k|7xXDL-azye2L?{0PujJ*bKx!qn zV@~D3DG=9yUf?V7@I8p47ZME&prw8UB{Ht`Wz6HB zbAKNB^vB&IWl2{Gzl9M_#KyGiggIVpO#2pm>A=scnC`<^8ZeVDFMi0E!Mkxud4Ca- z#Xm-u5mRHZ-rNSju0qWcYJ!X!gO~pDzEI27QuH21ofm2)CBwTIqi&(rQZjvl(iUnf zY5+$bWSRq1&40gxXp8%U;F2QfezF_B9@hX#njQx_8c}P?lz2(01R7D7sfbBAHIV#L zE8#mUyUB02p8RPT3`Ck}gTgNC%We+gFfhvYXg5NmR+e0l;LC~MM`Ie$P5d4bN9u@M zJOy#Dh%hv=)W0&YGK|~F%7en)nNV0Psst+p7?fsm>T2MX&qR}rZFYmK6I%Hzg|Q8A z>XDS3bxqvWD$v}+h-#XQ0@7gpaCX z=1$@%?isLJ^4j;ih(frRtnMdQLMl75o2Z0{I)TWGWUL>tmuQ8E7Xp#>DP>i0dLir? zvZ6lrCdhy>P{N=u=zI-tZzKG7fDIcl8PhKK_y(%*opiH!psTGWKs z`-0;PVt-c}$;1moJ}-vkQ`;r^d)`wh7>MzgOLdVB6QgFYK+|hUhQU~4I|wS)-2J8WO-MrwWGK{sq~HT#&c2Qqb6ZgDT5ZE>ElrEMbj}3XnH4f>Y}r! zK-po0(S$>%bN7nAH5hl&jjc$}6P5T=%Mlkt@@I(gPvbKPE#25lR1_7~v~>fmSomYe z&Qlv;f33RE5Vh$GY@<$L^L!@s&1SQ3&pclT(471`s2BMj)+J1=Pme#>-@l^27j-%O zvnE5(Y%4a=OM_-?qHiynRZ7>l0pk3MhUQrJ`|_!~O+Iz^$*1mq`P4lipSlO-Q}+-( zb?b;;y+>>A4HuAiDg;3f-((6Qs_&q&ntRL3z3_Vwj7Z``J4(iOP@4SY>U4kQBJ$}Mc_Iacj0a;%IJV!)ccfg< z_o>MXR>7k})#@%?i>OSF@>0|R6_xq(8;EMbQ9-vghs#LED^LcF=>_h>6G=^WB5A$P zk(s2drU(k5FKeW0NzF*7swe}4l3Ltpjx&uY@=bX2;gTqokOLbj*6-0{tb9`NNECXD z>L2PEE#WnIM69t*itNA$nw(CPndg!-X!A|ePp`qyTk$$>H9Udf!j$}CT|6Fwu?Y?> zrGTJJ)8n#LCMvgxe@#zXXo z>u5_jfj;riT!^K_9Tux3zDcpA{W(fcyiPev^NY0-Jp&+?6Jycn^_0xS@95!JNnjX- z_*~)vG?$dh0`oA4jS`PN53!1P$jFToTdWs2J5M;vQ*4vOjJ7DcdSV7cHBWpK-6LGuqmugS^Wd$PofF}VMS&iDJ#ee%#&sm*1HwGEYSj)Eg9*c#Nrg)XU|V}4mUDLJ4;X(E7?S6J$hT` z^tQQ`)*-T$jHGvX8A(XZkn|#~DEYFCrC0mV*uj*UE7Cf82lEV4;!C(1mTDm2h zWJshbXz3*vNu);#i9^A(1f3;jQV~Cp#?oR$ND+TA43YoHNLr%cNF=)59rruSa-lT~ zX)A-wsEVO}Ik(HlIHCj>$SZQnYs|AfgQiB#3q=w&)_~nS) zCL?JLCM1&nO1|W9Sq-!@lg#f^+=98{)5NB_&{)Eqf!1uKjZ{SVtbSoD#N~3MrG=b; zVTh}MDPYOn97n4=A#n?-_s(TZTJj0OjKU~h@(ERw2ulh{mnG_UMqE1wN2XCE_e@o# z$#f6RtP(C6)#0@mGgM0}HSIit-b$F{mwJQj!IQ*W0sXDi3@I7jW+lv1?!@f(n4Nh!vA7!T@Fv!xX4?UM%SEh!cA#*c4?G@3~bT5SBk8fB<~w~`vP4kXeCn`Pq11mv8n^&9eiO0TH_4lPHQQu z;Ps*874kWr7C%D(!Z153X$iWp0xgRM0kjgs&}m9$@P!p<1|L9>O*Km_Y6-2wf@b+V zx0f3Jx?e$&7X?qqX~G|fv>%f9MnU6>*oZud2LB(80`x7ENc}UR6#8IgO!rc6@(au* zw3*af)PP!x`?C?gKMmC+rVs?_Ca1u|)W6?IE%ov4T>raSE=5y}9X(`>miq7V=ls!o zL!(=X1F=BX#M5T@y9~1MGAWd!^z6~g3#wvQb!Zu4aW!nVlC`3wUjcFT(7aMjk%8$A zB@wB1Tr#OjGg^s>7`swkg8p)`3Td?^84=G{D2JL6iPdi55unrhTVe*~POo1ZuOBse^>I78PGYT{7$1DX zhvH9cDCkqFm2gRaBN;7O@cqVO6YlL&_mj2KCU2i|P{ zMRANoq__v~8EHi!u}CJn@G{0qZI8aBX%k5)7I!^xex>_T=~f}|bnH^rk3@$FwIn4r zG8qM}B|neUS~cXk};@0B+=l_GkR#g+)tI!&|@Lgzq2aTUXwd9K=^+bMsqyVatE;V@RAl>K!?iz*@ zrIA6wbR)kVEO68f(73Lj;zk0+;mIzz661PsC0ZzuxISF9CI$PFNj~vsRfGqNZb;S_ zE{W1pCG!2D;w6Yv)cxcg2qLlyiY#ulm=9^Ciu6}v>KP2aWU~suOj^mVVeEmQLBR(2 z_yfkCY&QaW>7}dDmWQ`%E|ywra4W;4OG>fcs)W)^O2xeI2uRJPl;nM)6!?W1&iDW!S8uMDZ9l*)RSW1uPBT}tJ=tmIqTS^tYEeW%)lq!1PCCvU(s^tBSFb7JhvUdq#4wq6DZ!^LiA*HIAqC|9o zJc;roXg7(U4*WKwwHF_aLtJ(n+!lBjL7nL5FfA*?l~|w(jRW55TM=9DLlbpVgVwTy zsQ1gq5Ni5`wtXPfm8&K7UYiafQ^urTcF3V!1@Lz3>$3#Sj<&PBuj6^|>q}!l8fn2% z{f273ep15g>r!a>`V%$M3@%v{OEf+^%@8?h^rsmrC8Q|@E#I(flqT9YuG$QZm!u@m z%c$4@&v+@BnqD1Rz6lAyjtpCc;2(N7gwu^a@H>z-wAaRCgd8Zc#H686bIMu89Ev0l zDHh?%cM$!FZa<+6R=>9mmpDd?vw0CFg*WQTx_jFpF5VV;W zuz_a>(rbeRS|?tE^W}F?sS4WhlT}RCV;0nL0D!9NT>rEWXcJ7uG}l+qLB%R)V=$S@ zkv$~(0e!^RRlcOtb|ELSrzO8q-3*ZL9JGljr)2arur-bX)Yn5Mr~SqM)#xl{)`7+o zUC_2;GG+3AbJbildd{KwCdv})EQX9l0-T3OJCi(cqh()hhI^}dew|3S*#ruqIw-$s z;vs45;Q29aVg@w0h@h}Whr+JT)UIiJ^M4hx#D@7$_*Pao?R>HZO6VSD3ceR*A<$N+ zd`qCooLvaNz7CB({z6b1JjKisuT$yAIe5*K)?bsUMY0F%&FH~Cub^9kR%In;nz;2I z?w{n_v`YKG#-@q>IZ*f!Ek_fye*1qFZc}+|;MWaW*$pV5C`u9fCZ22#35{#)N-L5B zgBRhp_r)nF*jTw9r+LR=m`{tNwIyD4nhCA6qLjSL_PSUi+t!Xg-FKzz`h}9FZNz%q zZVJ*1=b7iBu;+J{4DVpTrtFvf-$eb<9$LCVYi7Y=UQws@JYG?!xLoM*UD^ZYyQ%mf z8)lRkPUdzN?_P%^ZR@-r0E6=_m{nWm|JX z+K9Ki`8~|YN^IfVv@vgM@1d&R%C~8wK2QQc_tit(eO=Jjy)>({sE;mPqJ@ zh8Yz3?hg^sMvhgqyB~;T3*?Z{UcBXi+Lv5wX`<#_2q$@5rcVH5u23xzxc!AJ68a`U z0&tzBiRqEZ9&JnFyGl%<7bEzhnBoQ7-^96X{qx*JX73y$&O0slgS zs`zRkR?uxBx+c8{shFU&=#vipB{YhHqiJ@g(^RqG*lHA{sbax#^(Z(G<59s0w9TVW z-3QQ#>nYd{!+F6;^x=Zug@Ug(M6lazG<8?OIgX!TlXquz+@D8>R#4~f0>XmxrDS+d zr9xUjJ2ZNVsdcNip3*IL?5=`Y?E5l>sMqlSk@g}@P*Am|N_Y0^?r>!CoiwaR4q@F?wefRp+0mDFWlDXj3uAK6(iB4EWDy z*#a&;EcoZZ5p${?#u$1OR{rw@S9ZG&WN#K64cYVXKjzBR{FO$lF*V10oB;LG3O)t! zr3)cpOBO)>+3G^J{4dBNQ6wq?dBj6K=h2QTG(rg^>X*@^BxN;#smq&kdW4Ql25~>658Oed(LX();`RyjJW2900Bc-G>rdszL&I48 z5DWqKx$p30y6Y6_o=h5yM(c zAG!&Z2K9hgO)e}Ib=m-$G89NIRehL|>Gwo_UJ7J1r43|clZ!~&`N{)Y0%#*KbExKW zMvl3N+#u$YgDjw7n;E(6B0QqR^T|Q-s1*7D-aJDEspN8-Q3IwO(K7mq7)fyv$&qAw zAiV}0ZKBV-LsOd@&n`o1trGp@yioe93Quk78yr>SqN}|=rFhw9y?eG@CXzA2fkmq64hbtaL0&#g@iKP z1g(NvJmw@?@lTR5kW|bs4au9$og=CZrt5#>@|es%{Z|3g(K(Jr4QI+cdF zqKnu&5xMd-OH3KP$&+}u3p%M0kajK>FQsWy<@LsWZ0ddx4|tTcB%7+H58r1~%Ry}L zC~5mPRbSW9Y9+?!Kpgcb$(c>H(i`EjRj5xvT=6K*p_WUToVo7$bu9aNa3aDWZsD*; z9~&5`e}l<(4g(1gR%Ad8fJ12Ts6krHaQz4PiH1h7v}8byUp6pNFO1}hhCvVxXFzGl zC0{twFjJouKvU-^=0o_9r@;mm=_vq~GO!cE{h=Ci_CUi*{hzY7hSwo{Cscy~kLtNa zYz$Fc!}s$DGnDVPlpDdg9NGKO741c6H2K`jII%@FaxKg#x^R z81tU~XJZ>U3*mhhU}~TFnyusC$19 zrHmwu@3aQejV=NGTNXf=XbdZEuc@Ag@Gt{Ti~5A?qK5J9TuiiFlK+A5D;H34Pp_~cmAO`h zz)0g7YDU!D58)VB4S=7q{)lO&v+VCLYEp#F~>*} z&Or7bSAmnz9%B*BMx%HidsO%t#BGnVM=POr7+X<4GIkWlsyh*fT{8A)CDfC~%Uf)! zE{GN$Wsg=uy<$v7%M)D#L5%h&dmL(?jdYzf-a*?JYB7j49%ZLXs1J+>obmA~5GV6f zl2IqO!hdG)|0{~ti(vUhkC1%iLoXXUQG;W_wg<`H8~$=9*|5-2iNthuY=WcBG-jtTksNS~?8r z`yL@{K~G~p6833xatE;Ag8TCh)^3V|oiO9a*bx^+(=3l8WLR)!bwNKdt2*UbA6U7FTVO)(^qn`fq%` zx{;8(!}_kYLl$X-T}vFHbuZC{R*(dGC9FZB9jFNc^!jgsP(H$+3%jM;`~zTD+>4i( z?DCgDUxz*RkR9j=1bEF0BvmCRdq5EWR@k1dHvb9OU+=}=m6L+u9k9TVg5y7{Esw*_ zz847xa&i&~ui}h4^}+VM7k^hy8ixPy@WWmJuSt6)mqQU-5o%?4BK)`z40;M7-n>^RuTlrn3+S>j zd&0*&?re4Zj1a2TbK6pvIRj}u=Cqh&;ag)JEVk+0ST6CS3^C`z7a`@cNUZ^?ISzY0 zBz5Md9t%Z&2tVdR_<*$-bo+uE#;jU#avo6N*TSLkoA6ov@dY9@E1Cyl2~*B$?%g&3 zehR;^#RhgjxGxmgh6rPR3onSIbw#V9QxLu#3h=WWG2y-!Foa5?uRwU)1=K#Lm*`x1 z_9G_7SGusx7jK4L9~^cj-FXtJ7uE5;FUs3!Ltvde)T;;^t>JsUosEtJHp4@uGB_2` z+JF;W-p?x^nN8;kXXl*LW3W^*@hF7Kct ze6OPA2wE0cs)vRqxE;pkm?^&NhK;rW*3&~n6D;T=Ut^TNXq^Bo&qLh=I0+VhjjwPI zo8J!hxqI+Pu%NqrXIt6mSzupyXlR1(dk_hJ-uFOH8~qblL3Dw8RI#8Zef6ATC=aZ* zhu)Q7;m`SYC)%pJfX%%Jj|2;P*|(>Jjm`qL(nCWNTz@kXeACz5DTckk4tZ#32@8sk z>pW&_{Ser754|hF!WXgl|AD1O!ZBbL$6=R+%Ok;p##?{1wbAOp8hU7Gf>&5ba8+v* zCV0`>8`ww>4Nb71^(_8km7oiOJ?5cq0-Poxd@Jii^b+A;0Q<&0cqCZR-qxp1*Z&gO zO%DxC@Zek|c(}E@8^%2zMhc-BmBnEfL+Aj(kC(+fXqCnVa%Xf{$^h2bLpg7VTc{1z z==L_%7sLdQauqu37U2(C_0Tm%>oTxU{x@EY;P!YSAx~PhCfFh0K&TJAkX(RHdM;Sc zSGTDjK$uACof(t?(cyo!29&k=vS2g+8?Wjn`8SN2T&T%Y7vmY6a`q!Se9Py5h_p8Kvs)U zZl>_wO={z^CO%*T&D0#Sb}ZkC6W;~meYVu*dok92%W{4!cC;tIUv|+_TW>)ziF^@c z%RPCOeodrM9TVlV2Wm3RePA-#8vP7fBvl$@qGM*?s);*dLqeaR8D>90b740m!)?jt z95_aVJWj)R?vwes8n)m)S*5bu|BFg~d_q*RMT5S45}>o@>qnH|s! z_&?6&uG}!Y&19Hwv5cFKeg#EaEdm3E7F*roZ(77wFTkHui>)5PAEJonw~>oP_k0$U zbERAH@aWeYK4?7pD;O4{dyAkw`d4)Sf?)7GLZv@2UPk9AmsP0_Rv*y=lq*tyjsx|1 z8Dv{}3(ar!ujUO=84z-a*5^A^-O)ZAJ zNhlQpt$|-_&M;pCnaS4T$M6k-8WU16miQj&rE6xeZ6ORrR#YQIU=>8_$%?>Pw??5Q z7}l{47!IuY*b)r0Di6Z#FzcNu2&(xyqCCuCj~X2KJaOPfYdCOiBvH3oLW(z%p1=r8 z<)X3NqbZ%RM>QlIT<~pUNk`}yj@icyo*l&+R^yUHvtGcy2w8_KLW9=Fht;7Oyka~K z`N+a`@Ve_&u1ixdiwYQ7c^Evt6_2u9Bibl4_`Pu&tR9X5CU}73YjJ5HtUv66Z;P^+ z+k-!HWLov<+hD)W{hJ4Z(HsNn&PX9nU+@FE0gr!h1fEARQ9Or7Hy7b~ib9E$$6*Uu ziyC&@g<~0LIzFOK5cKneuPb3L$NmY8f#5+`7+@KX7W{^6@Kb)p<864+ zS`b@ZD!w5{oa?FjUz)hOjL8(M=L>BJ$YOM6&gn@ z4QA@}GQu6@u%C1GA*jZJES=tm=NGQPF5+=iVK&5dbiU6(H(aqA>(?Wf*qhI(&Mmm5 zZs?=y0)CSJRCdBMsj#-v3&XCjSpfS}kFxjE?A=-~&-UyYu(#29#G5b(s)B8G&i91& zT#W5h(mNM}{nu&H@Ggu^xL|wzYssy&=$a+D93|Eo^Okc=_w~VlP0r3`UyiiK{2lCD zgnj2c3Eu}=jGCa;cz{*tKU9P7MAi_#uNQI`9@7oy#K{OjiACT~<&yj2Y=NFgNwB7E zq0d?RCr*K;=rCj#lU8RMDwQVER2XUJC5XrZ2X}-}S~VUT%;1C_P+2{=6Zv`2>2Z^Y z2ZrE8JPiWjP#giK)U1lO^)E(`;N;)1Yb|YSHe`z!+RKoZE?0-asg*#9{4r04p^k^P z4D)H6GnJLQMwWSuJ(SfuXP6&5-WetjN*QK<5^0)G`w_uhIKEqZ#_wgUh z4#9)5$}xglz;pcQ6eQKr=YlWTj$bOn@lt|Fq#A;I4nS}AS1sUwC|QMAi`}Q-5#^8y z3hsV|q23MP{~8arc=nJhIk=DOJ9}prSWi?}fje;bI;9*^=fS;P{n>dq1>dM8Q16r6 z+&k#pM|hx{jOy2d9rbrH8JJcq9(*w-|7S70I_capOe)S^z5Ah02fOIpXY|BKqj#GC z+&$#sEpO^C;=fJ`W>HBD1l$fN7sN=WI&r+X(2%LDE+wJM$PBR%LVgBI0r8UCTspQ05!Iuv zxS$kjKZuv^qV{ug>eDBgHuXM;i+52M9|qNcy83MD4-jGK*7;+U*)yA3%(baF5Gi+2 z19PCOAq~P5An9rXqQhMjU!nyY(ei%w#nf;RlkTEwa0hEbGsoKF-AWMaTna_?@@fE0 zsplBPfo@38K=@K95LX63OB#q}oTTP`2)}lLczNTOPtbKa94J08m5IMQ8Q@Q#Gz$d^^O)9&8u>MiyCUU4I5ZUa z8A%Ivp=KpCjptOF1L5LOU^V8uU{`u+HkM)xY=iKLP@oqVe>ZBkOkKCo2?)=G0&UP> zg57BxnlN{Gx(wm3xJOrQ@y)e=Sk|C@b3Ut^Epf@!_ zIY^;5hmarJb2Us40_a0emb8KUAsiD5+$sy8FBPj|19=dx3G<*-?FQLG&4FCp^j$SE1;of-Y8Hbw-jeFog z`n-@0q(WFL6xhcT=pd@O-3IuD?{1+$)xrP<(^V|iC5o{SP7Vcj?E{cYJu&(SunNNU zp}>N50EW`B7#lbU;j1p7CK_zW<9a+eoPI@_$eQ+J5MQ_ynl?W}5FAY{QS1`WpAZrn ztDD!$s{xFopU^f0CXg8D3!*$#suKS2?kK`)@%sS5--u25ZK zsHYEt3uxp7d-$COV&T21Wz^H5wt(30Q79$u$owQja5XgyL%Zc6^>q;MGbICTz8Ke0 zRfqZ>#2+3dx`xn@!4tILW0deHzC#QziopW09F7oO&VU^MFrwW=)(pFd>H%w+A4TH$ zMtE==6?)vx=pYbdm{KbPdvKR5?50i;HkAirtw+gRY-e;Y&8uW*^Ze-vGM)P1dl7t58IPM!obPvl zUGz}VY8O$PRzN?eS01s^KY&H_ce53W_9z1M8|t*)PH;J3)$*gLWud;Kz7R;WX$ebL zkFrZssPAbNx`lMAF(77plteoSNp}?fLa#aF-3DO$JXG=>ir%8jn{2J8fL-uVH#6}z z|MPC-=r*kxZ1cCk`Vfy@r#xUdXe)GqAn8e18%cuWfmLBNUxO3M)DO+Hsb(NLd6b=b zp~CfMm{djANDwnT%1tIRKYcr*y-%Mt0lPR@l+rq2n_Lv*i(I~z)c?V7O3y)XiiN64 ziXPtRaj??*0Su~i0mzLzu=Ua~L)fzVd0eHEH2^PP;;>b!M#fk!r65hgIDL3!I~PG< z^%+$qA`$0OwVI&f^$4tEWSPi z4B;*hP!AUdlk`kXV*(t7@C^^JHB``-2QYfGhA$!fmH{ z@yek0!CmxNZXMbbh1JqWVZp+~nnAbnBkIaV%jA(U%Z$M}le@LJGkKww$&0Z}UN&a( z(lC>kf0?|*!)sLlv*fBg%eJ!*-v4&AWQalsWN!slJApMa-VK-kNxkdcaPd{|hVvh$ zy6=WRi}0`D2qeQd>Jc{iLbs5Un6b~VzH$<{3K$P$kXb0QLxWd>Qu)(o?rW39FnFkTkF2#+!>!?pyu z?}FbC-!V7>EDm`WocFkvy8iK(VMV3c?}9%L*Irj>S6b)CTXQ@^--19dvK-^q{i_jk za`OPLm|;=xh;z#2WpO)GjX-Ca*Kp2cYxH_fY_0M9DbD1bN!ZTCV3)klvAi`@4R-%S zq(yHM6<6m&MVX(Vlk=NK?+?ck`P$bQdSuMcfpi>>0Am!t0%tj?66aW@=-Gn8PO$|M&pmKgAJf2H%kWaUFiYyZ-TQAoco30pz$C z4i)H*{!t9$&3=TWR1me9>dva;YqJWcfBg0c#wdn51L*HT*$PtqV==}>(Zp|smNtpI^zoMN|RR433Dw-1%DqGV=m5_Y{j=F zCFR`SvP>EV?>aGfOJy&7W20Ns`xCGMP@ntByTl}ts+X7hVjV@MmzVopo#xAZ0ef)BT8q&LSrt;t2f8 zE(aJw9iPO%ogg;)2}1r#ao{f-;75s~htuV{m?Ys(_o4g7;;?}ndUh3nG4w3*mIFYi zAf#DLs5p|S^bQacXjM6uc7UXhD~*>{lthbL0NFx0#Tc0Y@vJ+L9O^p}$R28!?8LJH z$Sx1#!oqZ)hYf}34`?B-UBVw=ZO4F|b}@(ei0011s$CNNHKf;=P-3!yrmNr#T#D4~?2;~bJ8 zU!D#;Fo#8Q^uNS+Q@Thju_H0gNP!QeF<2f)8+ySw^iT8_ozg;tol8UL)7xVery55` z7IN>=29gL1>fgB$k7gnF7zhJv5Hd=?T*(RfP)JA-#^@K&hg7!rgoKpT7T2p|O{-FS zDnux$Ev54t;wrUYg$U)obe!J5DIV^Zd}>(0I;j<5qW%d6Ox0}4u+UEJ&Hz%ItOqik zkXa!iMVO-Zoa2P-=7z)zl~|WXTju_LDxU_8gK#bm)z+kxonEqR4A{!%l+nCCeH6@2 zkCTp+L$_xGscZIFffr|y1%r+P`A>dK)Tv3<4$#K*p(s~MfE$1<#GqQTil3|636St4 zV(4SOg}PQTBm&Ol0Mg%;a!yUY03*%QU7Q#?10MEYV~C?;We~$qou-4C>ng_HzX*ou zv<99#U4i=0cqBTzgN)MYMTk#$NbwNqa)UmE*aZI{g9(p{P}c>{&zI z9*Ev$Y~8DA6%c?*0ZDeT_^PZVmo99Ak_CE?nz-sf5m7dX=1e&QDqq1x=jjj5Rpmzm zAiUpI0}TSK)X$+|aE-{PlJYza>H;l#oql__tzkQadp!*{uu<=W{D_8=5WeMUQ16dL zZ`04Bi#*0rd;{V4o(3D(rT4-lvWEd5Ca}Ud++5`BK`!>{^L)033J|6;;7lw6Jf%+y zvo*AUuzjco-fxUPsL!2YF9e4{I5rgE9n0t!^fOrE@i*vc352Uc0e-nF`W1auZ5!AJ z;Xw~jkJ?7RY(9<7Nv9z=&qCEoxd!oSX{-KFaVD&$wEXK3|L!3?vpUGfVFxF1Z;BcR z4SXmqjKmA49^a4tMW1`0T`O6@n&wAQx%?_X^gsHAA~w|@#0Zb#ncbnj37Y^)vc3Ss zDv#ok%c1WS1S|QV{EzQl(#0^*EvG8ymLUF&+f*s;A4Q%JZ<*$oK*?wiMRK zATHmfOQ>eXQQUlyp7Sq=f|!u()Z4n=N9T^7X+D#L**FHJR31circ}D@>JjR3GXcw< z4NSEH(T%BmCBc7TA6-7YeIL6Uj0G{-rL<)JJf2*8eSn1xFB+3eZbeV>!}2(qfn1;Q z$G>=e_5F z%Pix`6rs)>B+JZVVO?<5_`#0Y^zMhTX*-Rlzx0{R8P!)Kd+Bppfx{Bo(0QSp-i!0A ze_8?7-n>yF9|ceE!;h$mmrNMFHY+jJV4Ge%2aN7s;u8#n@-NYWlu{#%GltUUcVlt4{4$H6#3 z_fZn0H9X>-5aA2d2!eK=@Z%8SN$L;5L{GQ{r5+N2dhjXzHoww+kyEuC=mrm$h}6uK z9!W*9c_GwuAdY&J#As9Tw5_>KeG1}=M{(5X<-FccPoYWsG2);wh%oM1I0BbBegHf@ zrKeF!Cr#VNKmvpn8BoP$1NG=>D0-5CMi932G^pt*y%~*p#MUqf!r=@k4K~o89*Va$ z%!lwH2Ankb!jXm^^h6a*@*KrZ2={v$)cln`fF@y8f0lvQA$%uP15Z!s!>R2|TfD>3u2r{*_jkw8}wg`*}5JA z@t8-2&hPwEQTogJ+I7h3K_IVs7>@|{)SiAq_pb$U9?}agfmHLNHT`XU5h+;voI9K76&E)(i+6Ga!B1sWzd0(I+mnyF_0Q z!(25E#fyV<%{YUmDWx+H#EQEpp7ztD@K1Mkj8A}go~e8>3RTvK*<#1|E{F?v>EdZW zy@FBHN&PJlI?64-E}?1|0Spr|u$2bEcP;ZbO`i7Cn-~$*?ZrVu5N+?$B~*7~Q+IoD zFciduJ9N3zxoocSO!z;h{QtpV2Ct7w%Q8bEd%+sZS-cj zfAKe#lhHfMfJvc67|*fAGXaiiI0CGXv`NZ;KhaWnu6G6MsyK~&=)BQSrx(IH2{L*H zrElrO1L(5RFYm-U>^%-~1F}C@u3}FkkstjBQ%QGt zQ#7EmIFwvI7ltj~M>vwxe=W6@qywnuLXQ01G{{9sH^>IMaz_b2T^0RNy;yrRpAKLV zLz0vD|G)}O19JdfIDs{k4EbB&yZ;VI+5#_^Tnm~27crjy2b#&&ERz$GWq!sUY@K?p z6K4A0CcW8g>}?jnEFV0l^9;`mv);u_xId7`cKK=Xh^^?H!EN%{w1{&U#)8}RFQF+{ zJzu?3|E`yvzHH2}ZEyrwEyZ`l85CzCxLfavt3%1f5D??Gy$#gIq(0K!j0fiLiXpTQUP8o17o zd$Yen_;)DKmsi?H^ff31zFkPgpsEZGl_^9az%hOC6E=_zVIvoiXUwqkc)1H6`#Y&$ zMuQuJ`BbOAKnA-QE;g?hMMSUb^DzTs{{xb_EbYTZ2kGdcke=2L_hIRykZkd!In)+w zx!@VSUTalaIvs-a4JJa0K8H@QlDGAzFm7_u>+}_nAMe1Dh+k_Bp4B__Wh5L4h{mB( zqAD?t_yOwR$2ygRB*m3#GnC*H9pBDzed7nh$_=m$%uH@7Xn<@jg>ud?mB;<;!A))| zKRRm#ztC@BkT1hRG(w8t5hQp;ABM7vXjm8at2*BWo@L(vwBV(|ju_8^==5cD?hVTOhigFIL{xUQM3mGqCs93?kcb*WH!sVG| z{sX^EeyTakP=D`Qg`u!7OXv3Yk@SP6q0yQ;8~2H&7p6;{fKL-07_ zXYzw(3>psCI2-}iLE2y?D2p1I58supB>oM^op5mmZG+?~Px=l^XR5&E41_)o*;!8> zTAxWqMn}vB9N)Jfe)Xt}ti`U+3Px&w3}O&c6ukM*<5e2fxNX;GRU-$4P-!5t?@iS- zegP#h_5v}$rJTqzjRI&T0!)W+ZYUu2Sb^B9EN8Tbw-w>}#f52qr22441r zs825LEU7ch|Bz%V4^DEHd6_-fnxSf($GPZtF%{vH)XnEZ-%blNdKO#VPg2{C|NTko z9#E9b@6fSD%jC13I0*5iiFF0qXvQl8p*F+3ALq>e04h_?26!Cc{zCkBjq0Co_}?5M z`#TY`&-uS_i2uV;$@mW+A^V4ApR$Aaj~&%h8yk0`a_kyWL!nr*?Sd{ zyVn&R=W)Vv7t{dI6 zTEkb}=;luZxHq~FBkB`40&xfya-;h^{4Tlv@#P`)Zgk&(;9pmG$BphYNX%LYDRv zl_eEh&}Z1ll6Q17%$bNg%S=JAOt#|ww_~mLc?^`6=>0o9%CL;*GFbwb$dQ`kX|2RS zsan1vTw)L>$$cOlNRH%&INMwc^1(=!X<})b$<_?>2V^J9^s`5wqGQYSX);bTS^m8(=Y1*v zkjazqS0F53htnocolEpKw)n$n&FsMyEjzUSSGnoPWuE_7FT^6>G4>zN zWh+0q;6HH{qnPZ?`cM79R(@8&|2qHUu6)PX|3)5Ld3^JqmjBO?7IcP_oI*)s4bA^C ztwQmx#}VKZ@YSLCUn1HI&lg-ld>M!x>GwpZAvy0!?K+mQf6zA&{GDGIUjgBjk~kGb zF`~i`;h#TosJP>U9EB}S!v7yblHp0~g-C1S{Vzy*dD0a{J@rKsPz-&DMnXK*MclS> z9*Q!zj84Li3T(6*#3q-DZ^_Z9^{M{>ia=3yVd^CiCp}6MV^evQ)7_>ng1F{UoG9!S z@t4N@8!6g?9)dj@hn;0EHz^tiJ4#ovXHOM?)bub>q_%?nXX(HIJQ0iHrM4itxD-;& zo5}uKycO)Pub-)G1AjrNFL!gH zUg7Y!(ceNNp;!pYu~2%U8nA34M_+`YkFp?bm7j1L4u31tKU=@u0ay-@p)Q6d!QaaC z=jk;^+sT*%A^*drTbR7G@UPY{%(3?lwn6xW2h@^}X=XNj7)w5S75-;f7LrW0TkU^A z|85)ZTyRlb2J!Q~sZ;vz-O#d`D!2mAzu`~`QCUu+hLe$+xAYF>QCL(J;;cIm+0pi2 z)a#;~NNk+|^kXO_O$z#1Z-}LbL^c_~ygM|hk7oM+)}KdP7FCaf*x{-|;qg~B{iZQo zx7EA~;VD-QfS+q3xsk?_0=9-PAiNT)L4cyhaE#275L$@~I~;EDzuN{H5)Hi>9@1)! zVo89oA_HnX&Xt$r{VB$1tciIwN{t|F>1j}(c=Tr(UxY!}AA%8XXs3Z(=TtT`2yK<- zK)TE$axgGp>^WZsL=R)adJx+o-RlxqOYp9K=7<%jQ5iE%Kz81h$MYnlB2wS`^FL%n z*0RwbfoZFp%qY~3k(K%%GkTXsjKzQ?-+|d1d=>7f7c&FmC`&lbZ#Z3!lRn zDCrylbaH+inc=$tnX9{CkQQhqfUWrUrXtTl>Nty z#oCI8IGv6FIm?&~#A@yKQgN_JR0PW!|79}_Q~F9BJQaRwH;`)2v_PNxQCD%}SE?y=MIzL)s6TRk;jlKWf%G==@2u z+Q9V&S+mQNcABgg5$;X0{0MM{tO^M57FjPL+IPsB5ArNot4omfE?MXNq`gPhD3JSf z>oB6-uUp?mllG);y?|(+(ygb8k+#CHUWVsN!-__JRvFg&NcC#N+6yh)4QmZjy~D81 zK+8_Unul<^3@ZgG+ih4=%8|Cmu%1AGClC%P+iO_+;knPSvXQd=hLs1;ClLUiPZ`z? zo~q5Q;M_`hLwuMpERt=aGf%&Wte-!QDk zi0`yv#UM$)7}j8v*{_Cm5ymaUS_fsnA)Sc!Ps4ft7W4 zBGY;Z0X{OV+aNzSt*MCUP?*&N#^Eq)8nhe$5E6_B)>y3*?&5S_|a5&w39j``%~$1T8=Ktd&51 z^jUu*_Md##IOzP@XCx#=nhopn<90deKiVJ-kz@W9Dn># zE{N(p&;J3Kd<8=%`?(e^daHzgWt|)TRWJN&JXWdjM}Kj`v!8^Qfov*&bknSRM8Etf z?%E9BqG@%H>Jki>WpbCM?rD7xl*{IM-8c2AZ0FR~J)@6?J&vYgX<7Geovy)k14n>W z@&2m_-o-Y47-re~a41RqHOR4)@a;pm3;Hu@*k?yDN&!)Wsh=f$uIw(?{X(B!0$=T6 zpf!a2(xeOUZh76W^>SEI{LNuTLdY|^odUJ}TKAeht~K5)Vhzh6eAER(w_of2q;DH* zt9cg0D=x*WqVb65H~rRrTg`b0FS&rDhM!@m`?o&7y`7)GK=_a>mE3q8>q+S1uXoqg zjLlf@Nt)w9RAEX=&7tn&vN4USm}Dg3%|LXzOIH!>xz@FeFBd!c2QlR?U3?d;ZlrMt zv!v)+4Pw(>x|TgcTHPYXjTl_eK}av*^qNa~EhaezOHA40;l?P9$??H;KSz*d{)BX8 zn7<)(rt(l{3nh^G90>V8B5rg&AM+ZWwDpiiR}P@l=(5;uH@Z~Vy++p`I)~s0u&R8G zZYq2ixRUt(kb8|T60=<`2x&7;yOYO|{ij1X0bUyhgWrimj$4gk4?0QDZl{gSdAm z`56OZI#ZIL_~|OwcB6Y5SAUY`wIH^7x@^jBbkSINOTrIY{BV~p zyU{fmVe7JxkfJ#9r^{}1y!XiULsfA~b183_%iri^1Pp0(oY*Wg7vVBllwpo#tMXOn zIqXph*laor!mO9I5I)(D~ctY0jJ|Q0<44L(OYmii9fdCti(j`g&*=O+v_3y)C+Acgv@$(?z{4$nd^3w?!CdcmhY=k_MJ@V*qP22}Q0QVsrOK4x5vf*nsd>Nic z+*plwA-m$r*+xr{*3>L1zsM_t^o7_ z2p@7$w&h2k0koRRp)tf1Bx4)oFS|6`^3z3Xu;NXehIb&m=%SK_cy{B1M^KqZ{Abk0 zO?VW<)|g7D#Qrccouic)$=+J#i^A?}3N{WNDK5(mkD!MCHqOX`chfsW875D=XkR!R zy&xRt0&L5lZVsGBe4o--0PABe%C`I{-#W}Az8hvd4dELu%C`I{-$h$P_ZP*5b1UO> zh<|lqw&jNlU}cs^e0S0)upPSwI8>=f61Y^x;9t!7hG;zBdt??XJ|hiW50_;dDb~N9 z@Aj~L6mIPB9S$v%Z&c+G-#;=&f}EE>TxjQ9LA#M`V+RQL1`g{QrxiD&`_-!6jnrqQE$=_j1_K%vZBYa9g0hetlg||Fror51bLBW z@EM4|aM%imI4N`#Ud84Fji%bz6Opomvb`rTL_pyZQP^AoOC5#vLG;IAD_rcPkn9w` zjz&N$=sgsY6d#oNPvJ#7D7+vF&&TKtl=Rst9CH%A5{Iqu2`7b)!d}=AqNgbWhNKY6 zR^a#p3ajklEKeDW+I^a~I|_$Fx&Vi*@UW9Y-A>_CTtp{nqMbrkX14oaNovrUI}NeOeSg3*sYB;Sk+!hoW#3-Nc}o zu!sL&n`je#G6k+Dlxs6l5nLQbwt(81neU-pZXpxBu6k$QzYT1q;q6;!SM6*;d_R7r+5cdfiQapYtm>7eOnr? zP3)Srg9hRXK6|f-%$>BO6kJin&h1^XXG#Zf?V4@sqW$f+-a4|2ergJzFy(_m;niIf z8xNmw*Qfq6Dv0#gUddYoyXglX(!YoPf}zdYP5jU>e2c*-@&w_pg|(S`s2Y1hSRZCs z=9}S6v|+!!)C3gRzG;;H=SJ+5>Yp@r{yMd+C@s-cgQEVeF+V za=t0&f8|`T0Q(o0GvBG$OQ~|ME$3!(<~tpGsh^yO%XyNV=gN7xoHxjMmz)pE`Bgce zk@J7#{FR)4l=EM5_C>Jf7&*tuIYrLta&9E&c5?0|=OJ<)FXx$ZULxm5IGIY+= zW^P3n)Jm2`FQDorac*3Tw2qiuonHVcyN)#I<0lN#(zNZU1mjU$-;=?AZb!!Kp?uz6 znSDwG`TTY|pG!TCvw5p17Sh$jA{vf~LKBTxN@6TuBF2hsVyrwW#;TvhSX~GmIxOPh zG%?n66l3ieF&Vmv-ZjLnP0*t%DYZKuW9 z{*4$rEv)s!BKA}gV;^4zhDAI%UW@}P#CT@E7zfXb@$AoHJXa`&$>%GI@j??ZUd$2W zrA%ZyEaK%3V!Sd=j6TNNO2G9z^B97M;<3v9(PRLq3* zJt$^L;`D?^lp!vh@Q46$v4lq?5*J8#M6w;Of*r1+gfq@GKvVD?!NU-RHoS?(9#$}W z3tCTD!G`<9X!L>@jgN`Zv;&%3Sixq!#b`c6j27d>X!VC6txa*Yi4vo2Nio{LDn^Gr zVsv_2$j%>$(d8>Ky8a+W_Xh>(u}F-btHtQ`xEOuPi_y2582xIC(Z8t}1Kt#4;IlBS z?&xumHES4X_B~-GEi5u41uoy2GT6V{bOw`xvAP@gfjDHGeA9Qsdn4alH2Ocn-gyIY z4lA5K1e*q7g)>eB*vR~Xji}t_32Y3RF2?XnVvNud*>hy97^A9*F}k@JV<(6)VWk)o z_lPm&lo(UL5@T9eIS&3{vKTX3iZQFZ7_&!+F=v?=bDt7p-n(KfxGKiNi1Hl#odc4V z_ex;c3yb=orWogwMfRV@Vtn+t7$5f*BaMifG{MfxpBVk2jz7z6f-G4PlegFX>s@C`9?3t%`4D>5WrjG>LixIb5n zk#ofu^@JE>-V$Rh-!uv=3x5SuNrXnkwUrCGw*%PtXdH|1%&7%gy&qKFgH5V?vwCDpSyynsNM*K z9jD($0Eqr=7@v3U#Mws$aM6^#1WLoAcUEn|#;K-ad^13dTT@|#M+az?m`mv?F%Q!j zF^?OGVxBN!#eCiPO3XKmf5kj)lxoT0&lu@qzGbu%^KD~@m}iZdV!mr^5c55Q|6VCP z`ik+sm{*N!Vt#8Fm;=M3|1wI6`L|I=%-cpEF%5Hun5MZ#%rJAGm_GBkn3nmem<7z6 zVwN%swq|{$%|tQFn6<^MZFUl~jyYV+y5?LlTbUcgY;7JCvyFKMrnxbTw4x1-j@5X^ zn~!ZW%zHBXo#U~<=)8}8W~ag)L%(5)^mm+#s-Q(aT=w+qJVsj#R}`N#KUK!0s<$h^ zbwRHID8~P8R6G)vsf%$}3IlU7{ulwbnyAu!?2{9&kqYv=Wy%i8WS~rVWSbr;h;AD3r<%GAdkQvX3Jxn(se=w_sg(8x`g?Dg zfL^bJ&|y*A)R6qV8j_EyA^DgZl8>t)`J@_>Pw|jkhH?gs*P`}cMC<$uF%pl=QEY=~ z(ESs&sDqPpG>w%~XGf&u(Vq>5XY`zHI2&6s`TRTXOp@`|IGoESqLG@ZM{)H-OF7`< zU2)>EODns64@3<_w3|h5dZG&pA!;L{4_$;hGJ)9eEl-+tC#j3XSMp2&4^b?59Z6s)JP0%JwKO*uRM=o7N znxmg?p#O(WHTv`FVa5MnbaAvM#mmh9OqmuSYaKdJK=-x5`afX$TCWhJ85@?bAsZC_ zs32kdA*OgU?EX;`K!)`~X$Pz@6t5PDG&As@2?5Kj%Z6!oW`n}FAY20HDnR=2(wdf- z1(?b-UjwglFQe+qv@8oNk&i#SSEd!C<*DKt2-^JA8aHWJI0UCrI0|zpjFmj-F__e^ z-$b#{J-oDJa|4)!N_^slWa$PRb!_v}P1!8olgDhB{m%d>xF08;MzzF_;yZ}@c0qn+ zNcnab-=V*;F9#4`>&2lMDKdDOQ6VN1Z37Fs^SjUjtNYBwwUYFt^{8Hh|vgEL?|%SA4!4rjdWtPpu>IGhQ#vvOq06gbOK zXI@z(R*Ss08O|i?DbAXaOITXL&QV6>cbucjwzE!Txgl^?rB>*mdSZjfv-9DsLB}Qg zjU)N0H7-aO#o09S9SquWHL1U7ZWh^QA6^H|pfTcX9+}w@MVC!oMOEv_B^aCHTGD>B zCOxrpkf+}W0w+xt7%cEH(^k8w-?Fq2(OF)8~$67V+{)6GD z&cO`L*AGe)`W1qYFNdweSeU?plg$NeL^H zDzQ*bc68O?k-)T{hTsA#p}8&`U!qHRC%HBDLfB3T`NCZZSyK%J{Q{{-n5?9HJ)d7X zoHKJprH(K2RlL)dUZ&n@gX(T9q(;K zu}zhqpQ>}6ens$(f+Fm6l-da4^Ge7YFZqPWF=8f+R@K1MtGXzX7Hn5M_oNs)P#@en z=@PtMqf*KR1=+*xAlocWm-leIgw;6JoG?hsn-+XTB2M zyTrS8AxX7~cRBcb#Dz$_q2~p6hRc_+7)$t&-eZFI`tBrRW4V6Fd7+-MXjaq9dV|B6y$iZlWSL z@OFyeEl5R3r?k@-+zXeIYCDe2(J;1UlyGnIh%D{Vm<#kGLoGd^=A5^rLv#Istw zdAy}7`ZN~V4yHL8kQfT}#AJs&ku?l9RX5xekwZUWYG{WJ{=(wD~zgf%@ zM?7MJX8gUeu`MnYn@?Oz{!`k}=yof7!jw~(%|IT9mlI!VqACuhBP}Mat%Xm#aBBNF z6lDBWD#N188hBa&;b^WSi(*tIqZUoa*kwc#Zvm}fY7bLv%NI{lHmD-RJD@_Hy(h&l zSQK@iwpy5NnI+unrQv4VWD&de<>KN|Y62cC=WV zGdouFE`J@?8KPlKIIOb;SXTkoC8F#Rwk~Bhpci><7%zE?%v^&zs=QrqMz-L~jymNr zQbx8?S0I{Emv~PUn%q#9EG0(Mo~;?^~gj5BisG;5UP-ZkY>3Aghmwz+fT`3 zVS5O=dBXbi5=uI1*zt1@UTgp(O~j`eE|RLtFJG5l6|0d4=Dv;}_qUH_=pI6bzo z4;_JkKZIi^HWL|iggNvn1Xn!ayBxB-{LOFVh{qb@BZZOxoFZ}98brMfjoFGxO`!4s zs(X-VYCyT$5p)tYgrJ=(v^Sr#M?*^^e*JDTMszFQr=3{SZuag?2HOC;s!7Qtkepg_}hX z(sGDIz3rWs0w<1^qTa(TGjy16t zS7ou@ZR4<^!!q8`kxDGqPb!hW`B7}3R4sq=qu3x$QUkh{2K#XO0}c&A3v+m`MDZU< z_rY1l^^fWdD}?;bk7DDgDqOW)p6jCenk!e4)b6aM zg>n^5{f4!)RIb?6G}h8exk{%#N^rGSu0ZOexp1{nu5zhM(3z9kaxSo_PhHNgcFI*T z_3>SBbx^KKsU0~jos=sjbt~FOQWxc_ocewcu5QXzC3Pbv>ZHEPRW-F8=D(zV%9Wb> zDC-=cT-8$Bvd%%uRXz1_)|snZHB!&A&Y{W`OkKx1M=Mv&)K;u>jB=%6iC>^6+z)b| z=nIsvtgd8FKx;<3CqXvrdw5f_$v0trlQ8BdXULqPVe36PQ|6aN6=7ZQ4>;ds+!jb) zDD%q!1{R6+cih!TUd+pMU$6$OOT_mB+}25cNUYt_Cz6-)O5eA7F|5mOva;g1uamq+ zd|$$*e)4v)e#px9h;;@>@hnelO_%fSjl{{%$D@^;#XfN2)Erp3m6XqbYZ~*s!Q`8T zFcm(V1EKGe4cM>@aPY)0c~q;E9+!ZLP<>Ns8pbc8a-U-@Q>nJ?=r|CL`fBgC+?)k) zG*FUa{H-Nc^D&2ONk!~)MK&6c8#9@l0OyaNl9B{)-=K68tnW9{l=1T{aGIb%il&~#0eWSk) zd$Rd9&Mi1Kmtc_*PYrv1dT=DLaCMFG2MhUx5dXqx>8FwCRVl^QB_Q8&SMA16!$Thv@Msz17AYKL;RzoQsq%xo(E2 z9SD9pKwY4@+h7R(W(tUYDmXtla3|54^6G*3LnnToKvqY0<|;@{G1I0@S0&b(ModJ2 z8ASZZflNc_r&n9SZ--oMFJf;=0^3j>oZlF_#l(x8GvcQcJVISD#n3Jtz#+L<=I0jf z1pKsr6@a%@b@L+)LLiGbQ7S3JR3Y#)4ri!W z`(^Wi@5*@q$|{MqACODW5A(|^M^-Mr7zzFt-l@Z8qkqM!?R+hD60W!_m*D+p8A$R# zRW8ZF+q_U86XWwuYZb=&EACM9Bm}MeB)0Ppvz5mnekCaGNLz84sl%Z*?wIQT7V7Ul z_$QmZ1pbPwOa>|Jx8*%Vg2g19A zYB;>N=J?-6<(4g_)YNnQqu7RoaVGp!W)P4Gs>||2C#r36433f?DucLB@rGWHhB0cl{@>F6oQ}TF;-mZ;HOwT9ZoD!Xw7B6Q(52#T*P0E6Py@C6`Khn zpfXbs7fgy^8&?~Q1eK$29|rfME*+5{j&WjmjSH!yih-Y&QU1;76Xc{y6)96cmF41? zu8M;nqLJc2&3=YUrLwII;wNe(@u<^r7$&N;mw^0)jnmC4hUU^9{KgFXGEIZw} zM-e9LU3kk{F)~ebVspXT0?B zyw>#b!dIVoj;*}#)hB(%R{lJgK9z6L`{o^m(&;_f%AW_*ALJ*JeEio9`ivW}wqJ^- z9;q)knp8sPe<>aQD<47fxbyeC59TW6GE+Z5u)v(aH-JLSTfT za!sJXS5u|C-0JRdWb(}}tVa&*f}`=%&Dha_c49L|KTv-jUaDiC@^m-_9xs2Q+n0#@ zpzt7$!pB&QOO#U&LVjfNd|Un&Wbb?OY?_KTr62p~A<$Rh|0B!hG~uw>GzZH{{S^OS zI+=*3AP!e{yAEV;790&(0REL-nVP@K)9N7rK2CsoX$4IHw00pRjNeq!KUa?-iP$!9YlHhrw3HrK9Of9>30DCx{%h1%8iGHvHBqxl4d`uFeDC@bFDMI-3EH% zXg^|N&Y*?>TQEFUO4cS4>DC&D7zF7UCZ;o?x=UwD#5AKP)2W3j=LRhSvMN+j9#=yZ zs*Pg4gw|)!en_7UC5|P6s7^W>m?F+X`k_a3p~Bqi(Ae8qbfoM=Pop*IM~J%gSp3`bTDo1;8cb2NZy&MgVI~m4(vWE#X|v4 zxkmu7{V~Mpo#~J1su>&fFu2VgEAe-wL=0zjuuHfUq?Yp0BuB{Lp7H(QrSi1;T}FY$O0O+nUQub!Xru) zpByBQN)=+{|0C@?z^kaXw$GZGlM^5$7(y?Bgiast*#GxkduGl_!25mQ^PlIL*=4I+huf!;NJnXQax~>yXk*+$k0}JCk~csOMdx18kjvI6@jZB#`Z9T z7X@FPMQnSYV%npd?iG=Kpo|DpSAZ=Jb}H95L}r4rHYYWrY%cDU$PQo*{}V1pmY<27 z0`Ni@?Au2U+GE{T)^xmFnB8%YjUzlgK|rgIp#DWa4?O9p{5 zF-*N4L=Da{8U04}7Q&0?Ag}cy?!HP--K(@pSuJ+s+#`6(lYl($!{St%E~>oMypM}| z4~WmhD77RPm1d3D<)VHCB3Q#OzS_QvYGhfkTFo&Lh^k?fmdr)9wVGkss;Cw~bPl6f z!az^`@S@e-x|C@;Cm8|6cpv2f23cQYu)PF*$TASu5@34LUixK5YlL+fy+6A*c@o5D z!yH_|WGfcpDu=g0{2gN zN@(c<)`7S=62LDrTF+XI7Q0#O1@Waw0Kd#=9k7amk(S~^5YI*e_+>`xs8yxB>5t_a zh<`-_`0&a)ZXL{W0el@j5tpwAZiia$TE8`S0rf#_90qie-%!ui=T;^}(YJetkZ49c zzu^R2*d=QU<~lMHkR>@`K=9Lz){oY`Yk+tF)SW&8Hp5RhS^>NFJ+2ssL42J6V>4a! z%ZyebdrfhqJ`2LPernSRc9HJ=!J>p+VI>fMgBq3Y2@3xF@}re(5657q54OsHSdjq3 zzo-5UkyX?Fc0LAL8cY)q+xq~Mhl^@vH@5L@NTP-SF@dPCLIS;Hz{G&n-EPy`Wwi`| zjW@93_ZF?e_6I;ItEYi@-e(1o6)?)ah?-G}-UIQB&jtW~Z_%1$Ki9?Oa24U-3Ghr< z0W<9@BU}!JYGcP1ms@Bf=yH2G#uycWNAQ}E9#NW}`q?6Di(SO)hk5}qB#d%!dCKbq5Fdw8Za>ti337bR zejB#0sGorNJB)JWQq=qQB(HxgRtHmmTy7bOiWr-EisH}OZ)|e8wg$Fm81D}|(7!^@ z+dEN%D!@d*=H!HWsH^sC9_l_Io(QADZOCQ#r~NXh%J4OK-VH;w++E}ntG%G}#5UO9 zH=zC$M!5RpGh!>rc_G2&lOJuo7_NviLoh{Ecjhf|QMG_*6h^sYf})x_zo22NOg(@Y z6Gq*jKgD-(hAegQOMtyEjE~fxLi;-XVZX}yS-=kGgnD9*b~d9ARMZ(DE{0K&`csAr zo%Qi9G>FdV7F=$*UH$Pho7TO~Tx2U1LA@=E(79lkV;B7#sP&XHwKK4H0+*2s>zbmn zeAOvC*3EbpU@OB=<>=a@LeDtWJ$*g~*sC{z<}gZ4^n>#T229n#XGm~0SE5MGD&7v> z>ltxuef0XcA{w^Yap-AESUi|-hs(M?U>$Qo!y0k%Rf8X+o$J^=4A^O5ylT)j!_`oS z)hzfZ+Nnyt4zL|zsB+~Em8{S^gQtqPTn_>ERv4<&a~Cxv_|tS3bsmUca-!l~=s47_ zH7%I8l$&<}sICI8NDZg}ZnY?WRj@QxZ7OSHVEg|QK1bbX%148JSGy^vA=UburHrf~ zP4r^0G1hsS-M^6FwSP(k{V4ua@E2?uDE@O``OWAXiW6B?n&_+G{ma}$37FSa!R02> zs?uAe4t@zfcDIXf4s5@h;cqBOzNpSwZlWwCSou$hypoiOs^;}Nj{*DY&G0vrqjHi*{*v%4YAJbK)_Ju_+kJ?n(NM_5I0RI(Ep!y2m zv<-HZyxWm#byV^eFI6%0qv^PAu$*wEc9VS^S|5uVyVcw3=!F!<>dDtEbGpeUjA_;@ zQQM1puz5Fu^%Nd#vQ9-UhUDBdkS#zxO%ZhNWtRKC;Fu`#W5m{{Q3LM<_84&Q6Kkd< zG=3=jA}7vYN6qPv0T=Zqmx1`%=Li75G;Ljp`t(5;5O+JC`r-1Yd;Cub>snMkh<2DV zrGZ#C62OyPR#a%;CRgarAP(^XW?2~)x~HB5vkHbv#=7{qz^)17{c#e)DeJPKbC|fO zK6U|iAPfyxgbS@1dcC6y{RprNVW?IHr2yB)6u42SJ}g4HTG)pwh|AS-qyP%-5Gp*| zg;oQsSs3aIpf&EX?iCt``Gm6W1MKLV;63Qb(4nm^bTMF?!q7;8JC=gLS)ogqODorB z0DCnIjTBg+i$l#@y3o%6yBdbxAh6=shhlrU_}Io6|8Tjw@bM5>p^t{%Y3oAk1J))C zjTHEnnGpE7(4?L&Gy||nVQ8el3VkhfyQhYgfb9rFeE~cTEB;jIQH%$wi$lPkya^rx zEA)Kmv0^UtJHUPqLn8%lv<(9P6l&$Ep%AQ{jqxTXp-?NDAF@;d8UuEB7=+V<%=uyBv3PU3`tkBz|8(?{^ z0{j42sHtDJ8w6H-+vpF`N)%rf*qS%NLtusWj{anm3vCBjpD;91;K5j;SREn{^fb9-LSvKUYsLj!1I=QH0KztTP`3${HBE>%w zeLI?_a=i|0(PlRap!gi~7ESqDbe)NAN*=|(J)DvX^yK+8`neh|syh&)!>F)4k@%mZ z2bOm6i-CRUpYX=|d&?g<{1KXYxu$v7)s~Ntpzts^XvPN}*txqF$2Z>s-J}}QSR128 z;Pi>vuaChxxo{abm^%?a>w!ef$l4t>9&bFFM7REzL^vLGD`W_rm%D))Nu>8Wt~(m} zvkfyK_Lfq3buu(_hF_3vOvHlJ#ds7KzC{)!shSq#G>*m?nLhAj3ggwMiQIxPBNU`w zbuUp6=A)&*Ng@>FLmak2K@x$gO(Y9Kq+5`1B4+a6Ud{e5Z*2#X*sv-(Q;+`(o=`^QXGb>=mR_`e!(MN%NW>~!z&%oXK z9){WK_1{v8W9x&z>b04skL<8H&BLGjf>}XavE(Y@0UO#-NMk7nLRBAu$6MS@tKPh{ zgS7`Z3x}Jwq;JQK&*kc)d#c{*i8}&;^Q31WdPJDsSNAomw|lUXOJ4xmJz;u6zZUww zyXQhbJHV!*^C&P$^d|Su3$|4<0?47>nq`pR4%>)eeYN%xD03y>(4rNmLHfL&WlS8G{ zs*ohLZd*mBq_(0g4M%DyEp-q>w@=Yfdg=@4l2ThQ*HFFG(MCcu&^gp7&AKflWAMd?nw2a)!qgIZ#c7q- zky_|!YUZ~Rp&+FV^l62p4I*ovH7CsYISrErZ|5++u;IneYk2Wp@Fjqn%}hK$x1sUo zU_>2hPhuXc45;po@`Gt|B+TdPd0uV#FOoyp?&7b#_xrAvUR6y9gJ-J zeuyXABltE4;#D>q6IxHU-6mdTfZn7vS?3}wiRX7xJiQ%a{G%qG-%auOJV8F|jQ&SN@YzrNI-~#j5qu7tcr6#dv*Pi240c-! z@BYTXF8SRRPo5u9U$q*TSMuJ9;PV^fo0^xgzV!L@ZyrMWVwbJtHuMyEk)wI&OXOMP z0KXLw;(tpNIm9n!=nDWv4zqXA(=-!k=IN4kC#EiMSV``*FpR ztps`)0{4Y$7{ z0h6%35;Xr4v5RSnVil5z%ax#~{_S$m{7(e+CiOvV;R8&sgl91mz{dPfgtF-eM5d2| zqzW+q6QOM8fVj*Dcx?E|{-F7v2rbV}Af6^l%M!I9Qn!qp!uH&<#js{ZHUSt7eCn_H2)L9 z`jHIWM);@*GxEMl5;iO^2D2Szfd7L=x+EG@MduNEO{}@^X9PbdlH5rR`rc@)hKxaP z?22e((DxBx402>Q(b4FW(bLzFS#M$p)(evbq|?mvZn|#TENpcLeeM8uYbn zF#bCmg-4+O<@hUdp_9nEGnjB+Aq zg^sdSjb>0w6&(9H^q{2*j{6Q?yd8Br5@gAzVDKg7COZiXH1V_XjebN*XOE!k4KLLK zi3g!{nD{BuVoIxZy7ons>TxEn3&8CJeWR?)n-;j`H%t}|lim%qzLE5g*)Sf>K!>=O z^eLdtill4%d#XCp|45D-K-)^X5xu-=eg`&SfMLzZKG2T%bkl6go5uC#2#k8ly?6^ko^n!&>} zc1c85%t^?cR|SMdh#WGMU*@;=a?J!zYZ>1j@!h=y^dKLe)y?3^TYCf|CVNzRK;@a& zVQZnz^eY@c>`jOsGMxWIk^Uq7C?GSa=sb+Th?lWA%p8waX7ht!Bl#y3PAWeeHj@7= z;iQrUunOZR#q7U)SYu70u*QT98P30-aGDYeru@p7orv8@!?b-E-Cmhy@Ytwb4S-I# z!kQX2d@kDet->9h(f#^OpkF7389W_o_XT+6O%k-z1fwQn&4W{-Ogv=F1x#A44#K?) z2=sChB;SLiBadRPZ(mjKTk745*gz8B?oZ;|=ou+h0X>Gu_i(9bM!6aJNcaMg*K!cX z@~;uBH<@c7ldtmIu^87?dc3~R*Yg9JeDmJE4bh|aU_{5;_I%TR)L!E!1n|*}=Ppwq zgHN99wt(M_E3BPBMpQZo8HgN{i@-BQ_Dn>s%Rw;utZA!o<76R5A=#}5k)8r>(khK}Vj%$z=v7srFGsp7r4L5I#D9sp`KK z&gp3q=ffGCAKO18GNz|n*a)~|GuA~uTLZ{MgsXT+({p5SN@dqWWCxExkHD;^27fd! zB6oNMHMckh14(?PJcDm7+xroI+k>dNLH`2+g-01;Fk= zvIn7u>cJ?HteFLp_;5Od=Nav(Ao3fi5uHT?=S^tE>~v=i#fWC_20#}X{4^@cHxVCB zWn3VM5gE18fO#3d)3}t8W;tpACb-rw!q`9(k7s4@k+yvi;a@zYvBXKT5A#m>ijS%! zg9k$GTl(PaAFdpNaV*W`*IMmqApMuU{ZU0Q+qF98A#7A(EL5ycd1k{uWXu@sK3ZM! zY(q|ChSGm$9@Et)F*m(6&_@E9hndf@|4ly4@(^b7X`bf<{Dx5yKkb^q6Up{D_%7lK zs|PKDhW{%f`7ul-7~^Z8Q;f_b919zPbmO!{i-#|4lB(GTYue4>4|ZoE|s&)IEGAzm&s4`+D%CHzQa3`|6ml|lfaSu10&;&>OCE0s8Xt<3Fb5n01laE2=QzE@bnRD0buJr{2WELcs5GDqsZ6wqc#Qv ztW8k_$MHep6r<}*K03Ag+{j{g1PkLgEOti`?557(GgQe!#13-sv=BCUQ_8QyrBtse z<=0H(N-=@UlIZ$-PIZZncMV8%J*-lMjyNJtDma!EUuH(o{RW zZnYEnzo~XUTDA)h0$Wx)8FX$k-JCzRgPz zF~~Nu7;6UEagv4cE>9({m+aw)9(fD;fjpJiVU8@RBwZOzm9dDI;W7~81fOKiIgX_Z zuFlZMgGiS(2fM%1KIvfxWR~zbp0ygI_H?;|VMOlQi)9j1okNORCvb!msXk)UR|lfzn7`&~Y~(sOWv+0z3?NlL zT+-+YvYRIyA+6Q;@74D>4Rndt)3QJ=B4VC!HVAqE|E9@-v@8(Uk(V^jmXio`OKqNT zGzDmpuwaA~z~E(7u(E~!Cu1-yp<=kUB&HHE104LjD3(^l=x@5DppTU{%TQh_xId6f zaa{u7L6mf{Xery!4|YprJctW$nM!HLH2j7yY>ex@rNZUnD$xJJ)ewYYLn!eM#3K1z z;reqINV{>#p1;6#o^bgI;(XyIhex!^+4F=O9H3Ae-xpE5AIMVv#k~0;+a-ML`rv;{R zJfhVT?{u;lO8FTxZBiQJvg*n_;UTt2H)Sd?*e&*2hq(K9ki?qj5MS8bXmiOad{3hWG$bB zVrrj)hM}C_$IwWo&LW+D7|CKei<3xlIWU&NXxC;g(`LR!imb6AG?|Cc$;wq~qBQDk z=D+Y9Kz=7A3&E9Q!z`{Kn~lKA)jGpzDqQV={d}Q8koY4m>jX^27z8LZ2%q8^#CAmD zw@Su9xAjk=+rowHhJ$OitVQH97*w__f{&l*%of)53Hb2emr2N!_&pQ^ea}eJ??mLU zio659Dd<(QPJ+Hh`XhJ+!8I}xK5kX5)|N~TSAf8x${9fpY|Tt(3PW;FT-NL8w^*3! zNNGyrlWr&tdk7}#!-QS(^!EAA(!^AfPri|_Ps+u2wLAm!p9!AP(cpV`p0~kwfxLyt zY~lL#4=q%27gUCzYx0C3jI*%ZHKh*U*c{!%{75m}E;7dhU6FCwy#vicW%?ctlR3V8s)CvaIUARd)r%1MPR0SJGs z2p>T^3A!dPDYu*oArS1S5TcabZy4>UhOk;xwsI&3=|hcd-;E-Ijrk+ZjCD)$Ze~{4 zYN%w|4avrCd~(kET_o%do?i|&Zpc$A!6F&K7nmB}X z=OQ)nFwz-KoP*D3;wh9ckSDB(JTQ%Hp(d)rXEgBwFt4a4_NffiL?6ZF(nJ)rz|#Jc zCOo>)#CWjK-y+q->kzjnBtcJP>>(R;qXm-QG+Jnje%SOQBpWUGX1k%-G0X=)z ztCG_mzJkwaVGc^yJwgllG4nE7NQKX6VL34CRSO4H25Mn|;&N$$w!k6epS0l7*Qz~O zV`sQ(&>>oHQ_Y~{NG*42-Wcrc_wd*T`3)O~&3ZE`Il=(Ojdf;Na%8lIqt{6%EThGd z2^x-BXXZAJa1^pu7cd&%3a(?R@hDg0oNyYAlk^}iXzjpQPvayTjr(Lz<0P?1WD9%* z={8cCp2iDfr^DD?J@|~q4+FG6LgNDzL%W*~pV9amz`Tpg>70sUWD7OES8>$%oA9|U z@H#+Lk8|gGZGp4r37elicE$rs#3SZXcUaqzD$gU;+$Bl@@N4iszF>fCex2Z}JdZFC zR(T%zOT(VZ^N2l>bf`RqRgg!bHC({0f;?^&B$(#E7`dEe737m2$Fq#=2vhre)j;w+ zxS-1BN@nvX*;Ip1_NrkSNM1FpK)UOZ)$j|5rW(p)E5cO6K7h(#U(M?XJAh&ge=K~a z8V&<<442dSIhBFcuw8MihJEn4)sPBxQDvUtf2<(Z#P9Ge5s#j;CX6j^Mh5jD2ozzI zPzw7B#uiE1iVI3;J%Qp;2_zdO_~e@@;X$P9&hmM-*beE85~jmvlyDZHsS!$eSTVH4 zqwpCed=1QHTu$c~Cy)b`a9we^lu!l=U_t*$2_D__f%&;Dpub%97-^KTG7)oB&Q2SH z@tF^>&_gnQN7L;G;`F1MVWTV{PlAZ~soM|SB2R1BGs<|`r(qc7ajv-w%1atfaE&y< zHPWKSNKYZxRjixBvT+g%Pa_=+5lsD%`~fcL_}htI{g7I>+Q$GvgGxZaN5}%8xpWTXK{hWl))K5WRO5k!j_fipAKNi-;*~0oM0-tN72LU=x zpgUT(R1l4HD11xAqnr9!%7pwGO`M0g*NrB&Pxdsi6&Rxlk}u$bCVo;WXsIL{P59)S zY2qT%70st<&AjCd(iu$@#`4){q9+8eN02*jX#|RCt^?pRnivGk2o|vOU=@*?SgW{P zns@>rmiC`C;n9sI9t8{infCfU#O(x0U=zk3UIN`{futXe7JgL;s0EUZ7JTx}wD2?1 zjg8d8WtE(xb*Ukq7SbRzw?jQGv;@UyVJLh?3%3E&f`#im0;X-+>t@B}(gJOPP3oVt z;L&q-T4o#MW^FcuFL>MUAk)8ah4(4Uih5d*%R;lHHGZ>Lo)#q9UEcC-Z2Oj}XzsXj zb9hlXjIyvVVHv;K(t0uI?&|HqVK6BnnRsN+F5?`^*62(ium^>&JBMAy5G-{8U;tgl zy=H1qLYw?mfU+KiYNzRTP#GZyYjxvki!mxnSvS~e12;eJ(DM?7hGMXnV@T3r8eTsm zp_~#9fv{TFx;;LG6aawm9~3BC7rQB_QP|5g%o_%PJ{gx(kXl)!uR-M7!|CJGs9Q$R za=5eM0j<_{wr~rDB#+B%a9C%!WcggS0bsbC@VR(Ep9@JImw6wd5V#=AA)iZKUGPwr zcJLWlJfP2oBobdnJ?;R9Q{+Mu{{a!JmBV@XcB=1V_+C&S4dn!UW><^}AH`)&51Mr} z6Pk6jPx98ghQwU~pX9Zu-;hdw8|8XF^cd4wGb0C&4oJGz%_&UdjqdH!=yh;OZTT1K z&*=V&&hlB_c+7N7c|D+CUXna6{XfQwrMST5XP?WfI!h*(k9{s4(C0!Dv!ET!2ZxR1 zQV&|A4V2cICppxD&&c6{d=4bxw^2`@zmJk`l0DqByGu*jA5>T&%OO2FsnT$9bO2z;(=`%j~qaLL`SY|Rx#*)rfWvUwn1Hj?l&s!l__ zw!kHAr8uViriiP3HnEsn88#l!XG4<5g}+sD zj^x!Rds^6m(v=~|)j~H=j25!sGg|l;Fwd(NYO9FU!V`+irG?7S01JClEqFvTnK_K~ z`ZG;46-L~ghTKT@Y98!;-q$?XsIJ0i8kGn14VfgbIRqhOaa`c?yU(TX6qblw#=~d0 zctD>ENhGqLst6A3CZ!2_8un3~s$;l=k7Gr)u#fsuee9#IX;L#CnJzXS%E`fvc#ff~ z1t=rsQ#`l4WrR-)Yd>%Rb00f{93xRSy+2V*#Iuyy;E@ zR_aF0`(WE0G!;QnE{`f180ANhZPYvvqLdl4ZIGYv6;2NY{lht9;PDFW`0#1Z6Rv z$eaD8ft0PA2VLM>A|5?w0*l<&VN&!d|*_b;$;f8lxa zRGCYYTqK|2VJ{ytrh(s~vv_g|^!|mMuIfy5kuZPW} zr?3TQKw9&RcD3+alfC-NtkwEJatL@2MRHjxZ_a1A`9!ik@Qd_82FY`%n{t?5@*xIE zX7WYSa9sXF3`64N%O`mTO%i{mYnh5vOL0Lu9&I@Mrc>~Mey2bZO^8qW zHh{xMO1?ryD;GZQi^9OPN+-r7KZy&E{5mR`lVg%mGM={F2ijqlY&0GT=IzDj6FhI} zao+>-X~X?-pL;nZU!>egzRuL6u%k}SBr)r<;PDQKr*J{Cqe#0zcrp{T*68srAwKFX zXlvw(@*RT6rbwJEz2M6v8?%}$4OG!MAUC4ZV}FtbnlbCLAk_oOA5Gr?$(Z$Z_)MQL z2B7W)xn^B<7BTD-n!#txdMYq;a5*ap<+ATH-H#kCqMDw??nkL*4kSqg*e_`l%R&4taB*m z2FVP_fAmiQs?K3>;3Py`7c%IIh^*@XZPHIS$e(&R^9jV_SJC1BuBjd2?I?Js$|pQ& z6K^fWVH#S~Sjh4@t`Cu5KC*P>iMJSlHLa6-f|`JN>2BZ?zoOLf_=Gyc(OCrwxbh`f z{2YF9j7FPeEVly^_0JCKA;J|QlV6jz_kl6C7jSZTsh%7jl@9y%{Pn~BKqkMFZGUax z83BABo5$zO&O{$QaccHF`sk_*Mf;QogeqA}(e3Ll1&USp3p{j#1l5-LMXO{nfTCno zg6OW+s_Ccww*l!Yx4OjwA4bF`iRaV&T8j7<5u0WF;E8y3(PAcBq`)~$u5e9T!o=9C zNLM7kB@UAxI3N%h2x=?jg(RQfLzCZx$lG)rTmj!m_05NGsrs_udj>uX&hRnuP$Uk0 zlPw()HtCwdXVTS$kLj`&1GGrK=x>rdijehGRJO$UX##$ls{m=5W142Eo8|)3Y(bi5 z5MlCp6h4#B{a%{rTll>GRRk|0+cokIe1E|=SNg*@>>SpTxI#;xUCN@)LR=Fa7$?Bj z6~5&X51)sNo|G+VKBl~j;gN>LsQ7v3(Cm?4XvH8XZh<_GxNO;q`%LAz2ELu}EfQK4 z(Vc*{?m?UU7!mI%=!6e{*@dqX9yM4A_!GFSfzm>&B@L06HAy-6EFE5o!dD1BjHrCs z=S$!(Fin4Cu?Z2CNMl{ShXA>arMT;|f1a}!vn=4p;mQv%}xNe^hYdNWVlUqs%Aamno%QMufmqM38r zxKcCc6L$}UX=Ao<%4k5GG7`j}JLo*YX?#;_KDsS-6J;PoHm-+&+PchdOHC~Xw3~RH zuk$oD@5irpmPiAjr{L1QtGV_K-yrb@88adv9W62qF7z|Z7(ZSVBV3ky@D&m873MIy!i_(W5p02+iUQsomw#F{ybbCe&*eeOk$M{SYkJ+| zxlCgY_G}eqS>Ph3k+@PJ{z!y>TN%M~o-i9|WS%6c2j?yL552Pio+tG*DrTjW7zD!x z5B@oL=$rS!VV<-^93Jv5kOuH9km|T+Z3BIgoE~V<`)S-yMd1LC2fYRg&i~<_byA@` zj!VWD2;CC3K=vx)0llxoeV#myJMzg2pf_D3FCw%R!mSZLm^uL8O6dk)Com}kL}=;K z70hE2;ugqo+!xBX0}Q<$=+ToFNJwdaAalHmv@CEW3;ugsBxZ{u`?$T|M&=iPU44kzHGl{E+z<4uHE~v+uC!e}dHhn@LC3GdA zZ2CA?I#1a0(b3NnHhk%3n*B6D*WyC6zZKb|`#}@GfO2OGoBbc^W3w-SDUsXkp8=j# zj%IHfp`gLCD`Sf$vpu-HR-cS?+1jM*!e=m>J|=e=9IMaCr^?5jTx> z%5*j3fb@T0i%IcqfHcL$!GVWBmm0S4J+9#Ca-NgNEiK$jdhVRb0L6 zN@xrH91)K}g?b8c>oqjFSd4%xr3Y;7VWhhNnrvMSBV{F zBoe>nvcCtqUa;9oRx8n*5XR3f{(csJ`Y3nWa}t=oU*fzo68~$BU;OFxLp1kz;dDJa z2uM~dRR{L*=WKvFmLqDVe1rP^6?}$*CUbfr<$B4NfnIEZ{0-7P;VE;LbEPV$II^2V z=mLJ&K3k382{1AWBDEwg-wH@#slGue5bnwxpF70>~TPM z;gTsM0nHY^?brm2OsPDomEqbpNnWX*V=kIBXQ`&j-<<8gD;;r)n8msRQ2TFiZWf8_ z+{bbC3l6;R3IizDI$6WLjCZA>hNH7iLiTAtGwwZI+}W#F&7Ss&o=JAY+h%W)x;!3w zS~$pV0_Row%&fsz=rC}}2U2z&3&aDWzffwkG8+ckb*knoxvX?9nxDih&aBKvf?PBK zQu$lZI>EaOpvw2K=l=_nm%(3SWlfN~Xzl`vS)5IT&n(Wy12YYm)A?!5hKsX@6vxHc ze)wP;JOtMWilK76jWj`rZ#L4B;aegeJ?Hw&6lM~n?F2zknCt7AjD_ifWM)T^jv~pXa(%M50kZ%kPZ86RZfv9?9>l0_b`MU%XB2TS3b-ml5x**iy9XsOoEk+u z0L&w*h!<4`Dxw3Z=6pefBF+Ky1A*@Og4~Mm=w?%F5LoEXJPX+aagX7GCPv>&<~ljl zY&bbw4xiamB=Av+d`;RaP$!5A-NT2csnKanfSHw}@6bR6f4 zEF<7^&AAwm^$ha24W0#Xre!RE}~ifo4E+|0fIZ=*9w$frb7| zTgZSU8>xxU#M$I&;!|LZCP*HF3#GYhBgxbR$wm`C`DU6Jj&%DYHPKLqId%$D;4_*y z4AAKaO>9#PHSr33MiXxX^9e4e^Xn=DHE~sOxik?EEhPUJO?Y&pi98sOTusn=HX?^B z)WkWdu9~3rl+rPa*3+42vwQeBkkN$|Y5I;Wpc#FU^dv6mYoRiszDRZl29JC*eeD6U z64?5d^O|N(eO-mm=&J@Sq7^}|<&@Ilhx%#+pV8Otz_e7$xu!BuU*i;)OJCF#t>d38 z$Dlk zrt;#y!>pDdxAHzz3@h(Ce5UdefvJeg>HMt9z{;zt9RMq@F?{X__&Y#Uv{!jc6vTsN zPr$cCJo?Q>z>gs9g~FW5sWS zh5n35w7CGKLK2w7vHLwu{2Lfkt?fbX9$A_wZBZ;uCHPEf?gD6RL}^+ohNT$_pDE2i zV20yzI^Uz&urwPKm#Z{yp(G#wm(qB2Q<`01;g+T;I;mC2VKGZ{P=3^G`XchMW^*Te z9}vAt_}WBkGJ~qcfj;Go7U(-8QPjTO4#y)1=O3!e?~$DL{t_a&@*-G1M8GrD;Ro0&^9Y z)A=2hfjaw5ak<(M^~LV*pLzt3Zgdt0Ytr9pVH;|T98OacN2QKxf^8^SEskxd9?_-^ zbpWz6E+EG%l5MCv=te0XIaeE6q-|&j(p_OLuVc5B?Ps*+!1lwYV%iTu(Z!&YYx1&Y z!1iN+Y(E4dFSegaK(4}d)Ar*on{~Y2CO_4}Nw>%NFWw^C=i|0r>Hzz8XE1q4PM5_JBntL}-_(cYJc6-p@mBQTf6v}7 z=UQSnc0T@BVTaVZ1Me|S#-SP6A=&VM&;pyT1q0t$kUMa+BI-+O6vzDxUfA!FB!R;i z-Co1BwlM$_bsxGR%L*n<0z)S_Y&8BvE;(n9S!AmoJFVS;K!hnm81CQQr- z*a1#mg5BFAI(-_vQ9a?sHzTZi6A+4is}z6_Ootp%YhiJCd!5ma)w&O&@|N$4WNqoS z@Q2I!glVnzw#dr>oxl~-4>ZY7L?Bii6y56hI~Ilb3mU}04qXI@b~O+?Wi2HU`2<3^ zO!7dSJl_DsE_cM?Z6~m@asCyZ4FQA6AD`vaoVyDipy9KXenL0CC;mwpDgF5TV=0eI z>?5N=m=-3^1$}lct>RGoMQ$Gnazw=Tc(5oo`Z4hZWX~5c!W31V+)V71h?xP%-U?9{5H^&I% z81bSd9%&{2Ufj!rO18h_Isw_Z`pr{Q$!L2jVYEEJaN(Y~GrIsJsDdj9O&&)u@5o^T zK_({@C{F_go5W5apOj^|%MJHKF$pmYtp#cD?No{f7j zzUeabsloW=rPNvZh&rndsk8d5I%{IkqXy&GR#sTGyiosF-kv+1Nd z_gzfAp@ovq8%+4itH+h14bq4VlIY?WYwo#oVdtfe};Mya!Vr8;|d zsq^$3>OAvO6lJI<8>+3!~I|afLcB{Y#w#C)GLl zr#gpKr|!&gRpLQsQA3nQ{8+rMco+Lq;7GcJW=tbgvyDEFC$b-RD7~f zAyM%a-E@`Qbd@!o{Z?a`Md%>borN|JhYu+`L&a1TUo7Cy?usS{e zrB1IG)albioxbhV>DNu2{sYw+__aENPQr=i;FOSF&xY}v!6}$fuLeRP4o-z0_y+CC z*1^e6SQ%mXIdY1rq5Pq=7Z|YdR3h{r_`DI zwL0^nG28`<%&)A@f;Q@84^(H-0(IW5q8YtA53N2}XMXGwM%uMwdfZ8Z0`tr8?t=sxy9-IujpNXVPJH zCZAAe%6WCB=|58!ol&3$lh3TE&a7tY%;~1i+_CB`*r3kBhttO(odLgrW-x(+0c92=Ez? zD|T#WaK#@PX#CwWA945j@o|$u4HavKB(3YhixPA~dXb$z#4Q@6T-6hl_?`=Rf1krp ze1!*aFMKbWq*J{6*GN*NOFEboc@`}UpGv)dAVHt!!`<#%i2gNsd5_u5nBr)7Vm}5g zh&}T@+>4$f^+E_WHL4dLo)q6JR=)eEyES#B3+55~WK@=hW2#{KRD8db>d&B4jQ{gf zysvb#ptxn@L3&;~gOQb-kY7H22Q>UY{VYT*#1&h42J%5=E8(!n21M@l32~_)$JNHI z`1#tnb(9~bqDKjokZ)rVd|iIoj-VVzg7^GHfs%YVkHVEYzY#}g)f@u$GUjBTS&4i6 zz{R{TM|s5NR;}2NpuI}`#@_U=K(8;s5?zZSb+E);vFhBdV|IzYsTvy6R-NHP)EO}g zPM$N1(eY(QV^8iHgxiN~OY&gVi)By^@dsOg7@xio_o923;a&&I&O3dD1S;jd2;CM% zJ!mT!o+W|2m*s`6Mz`rr5d2=1N!{|x_jwP=A3(>@5c6JwAtsJ2=Fu-ZxAyUx?`37iPq}Z$O z!#(~j`r~CB?y027qy1g-RjQ19 zr|xnIy~XeWNmloWJze8pwa2Ray4_IYkJ;VSeZ!uh?pyXsb&uPRsC&Xbr0zTRN9vxm ze^U2dJMK97e`8lw_k!I_-EZw)>i%v|Q1=geow|S8d)2j_57l*?|EL>uoD<{|a!RNh z?eL3dQKj-YZPhK|3{tnGGhN+M&RTUFI!~y3t8+x%+ni6-ZR`A`ZaatH42vq&-bse* zY{AKo#HMx^K2^5wz%*U#`q{Y0|9&U^jnOhN2j}x+d&^Yb+pXliS|{FX#jz!i8btqW zoq~7W#h4cT7_+b_{H5jA?Gh;S=HQPIC?136%8ya@dKW#;j_=TB6XkdttPT1)d<$0^ z62NZ_X0!v~=z9Q^mbZ3DpzQ6lE`#0+^fLXrjty`WiCcgu(9h17KeV=$sP9 zF-mU$RlxE#Z+CW=vH_qt`Vie29bVb0%uV)rX_fah3_XFe^3??Bs*k*vgGM-L_s#`v zx?BaV>H5rDAtJ~FQVk1ESGtZ~YAng26nX@(?s z$nkEZ37dv1b6wPGY&}a$ye@}GB|m#ew8SO9bUingxQZ#Uvfq0%_M19@eH+96r~f1S z(o%0N>a*&xJrKSi8j9BEtAkOWA0rC(^BzhE+e*zrBOJ8P9sq5+bOKFni_vlZ4SMvEBp{rFkBmF^yPC$3g=l0UM~CShOyf7Q#eae`Z(!P|9hkP24~#@Lw3Q{bftYV1 zCYkLbV6@1_h&ru52V4spuD|~SSG3PH7#2op9aS%Ytoboew)SwNVJJ>-ZoNJ~j3bG$ z`0 z?(E-M_`myO{#)f1ny^IO0>)3>W;!-SZb9c4w*Ro@lhKWzf)8nuYTM-$me9SsfPX45P_Z_+42qn9jlwW-{Z4Q0tO+<{Fi&<-+ zd}B;}liDuj=qrH=&2d;L^^Qikuh*FJ-(bO%{QiB0T=6wLg)R4swZjDMQao%{sV~sw zd)Tq@IQ-MEMxcBz`#xm7$Hg?lm@R?m_hw>CxMgp2)xr4RdX_HyD{aC@4W%Z?ANQ{9xU>ZS@k_2Z}s1bpZTTK|0`(3_boV8m+|7dkA;?L3H$DU*E|4@$rm* zU_I}ZcJRIg>?D3gUf!cIy~D(}EAR1@crRO*@h|8k^|(&h(l}L(ug+;()nv@Aqf;BQ zbhj6TY+KIb#${HZ>ZZp)YOJIlBpnZvK3xP-dnHZGNlKJsZ1gp3wVa1Q)JETfZJ;1h zjlC0`e!Sq`(3(p$2fVz2pZcHSuS@}an!V~>2rLlO?^43tIl_Cx{GoASVbcC5c#2Gh z-Fm|OSI&WIX6L_}*&VHB_DbP!$F`bz08q_5IH+bG98@YBylkNv&!(rdy_GT1$2N zj{quPd)&CR38W!YP&3$)^WEjgcG1|O8yL$3ijC&y087_<9N{{p>vsnvP`4j}v3JS^ zM5f3ym<7gmGu`O_Jc-cn>LPVCDLLWSWhaEL)AZ@*O;aykx z7WuIVmLf$<*@4RO!o~o(V>&iQuTsR_!*F6gPe-t*8;p(_fIhl%F*g_!Q+YOm#ob_m z82<5euxLznJp@a+!ICjeIv`lu4VHjo>u z936pRk{e8ksfwj><#O^i`W`DeE#~4j1S`n<8cdJ5htx`LiR#6C#}cKu!CPa>4MDKF zlt*7+B{zqHq;`;a z3@=u4M$FvGR-kexSLUHHPd7nEUF3@9J2DXBmwPKUVO@s4UyP2m5}(G`cWzr@R_(fV zTlIa~b+IM8(8moB`Wr;2bnR0UN0k6>=%jS(3isCXFy53NB;WdQ61;s#4J7dIIa2O& zjUr()@=NJk8x$uHt-Pukr6C}!8=>JpZ z3b!GIPYg^4oT##;d~Ip`M~vqUNok&mvI1#SZ2NDf;w?^ZWbWaD#n6M82SACkWF_EN z4KqH0h$Gb?F>!%1Qu5kNEG-$YH#fU>h)5+mQHJ22(#ldCA6#g9Pu!YMfY{Lx`8dN6 z$*B>Np2Kt@WvZd_DMwD~2o~lWBOM=p7{MA#9t^=L|1t52@(ntplx1oR@*`0?o1ksP zF$mT0DNLf|-v-=pgX2>ZqncdcMERf_V3}%6QkO8^z~nYKsfN>BG>VkE?&BA?bM5sAL;45mMr9wGuw@iKEZxFHvf+P6n8yeAE%vdfcC|BIN%$>t(k=@Db6Ch|834v_bGO zNiGRJMja{T3kJrgOJONJ#Nb)6IuDNjBF z%fT}ry8V=2Sy{pdV-e{RrBM&iy4p&7*iYzJY#ifYY>&f9{TFUcCXNcER9na=YY8>6 zSyycl<-yRCkcI+OTWms3LfMK4Eis|!gdsx_T53Wu373))y2peHBwSyF&@vNBNH~Uh zVzuQaR5W2w3PLMPsANKk2?(t;p)v_eHzTxWo#tLHp-=&Y*3!bQ;lbJTR=MIF=cJHiH0oh?xkV6o!@M0q$XATdN%S3^6x{M9E?mZZ=t8 zBSOtUeX3X27Fgk>WnLP_*jzQg1a7ElmOVi1kL^GiCzO z)*$%w^+rTx8hA&8;DcF%&_?OXSBt&R-KI_RnXSsf!QcyaI6o9Ue8aoa3zqTdE`uPZQz@}RM*-sB5w!Q;U$7DMzZ;Fp_>;8Tc&xx-1Hsv6Cb^p_NAij~QO#b3c5NZ6E zJ3J6ukC{iPRy~yAKkVQ_U%+PKF0%@oOj|;?IKd{Yx zL{hY@OYz7fCkEpF*wWl3*Ud?8Do2U}ACN!W;>0f{>_fm#ve%pLVm6hR&?m<^a&H~H zL1zJ#<)NU&CNQtKXsM4$50l6P9!+&m(C<^E`!Hp2I4A65{R0(h5S4KNvgw>rgtK$yLv^|O6X6!loVADe{e|l3oQj4H6WfsH7OIS?UiGHRH*G7t&6MvP^d8llE8l;>xWw ztwd~l<(o=u2jx4P*pABg3u3z}-zKn@>b;cjrV8*5P-aEYg;gJ@-qthV%}~CLi5;qZ zHxfHqnH45>jCxxUJ5Kqod>!6d%3*92ymJ+>u@b!ZD6+zQf zJjCE6wC1v-6_3&-v^6V`fZbXTv?cH;UA1ypAmEC93owZzBG5*U(j~Y@={kaXw~qjk zN9hvWqjV!dm=Gqm)uVI?dX$c=@HRMz>j-$4{PBdCXDkxB%MQft3MX{qd&&XCz2V2l zeM)&;VjnpJ!q;J9BNWgh4v=dg*nqnwxx|z;^(b9}9;N${0+ht9QW&J{U63B7Q&1BC z+J`~PsgNF}OPC^kK^Wl^-G^uG^eA0|IZ8JN)MY**jw~SvkJ2URQ95lwI}p2zAfuP| zdXz3fkJ4R7w7eXq1v)qwl+patosSTkN^eW&-=4Q4kJ7bNfVrnTf05P(+NsU|QCP>%vrc!kh(|C~XJ2CXqN$9E`)r#^@J@dr=J0c0>ua!$3_yD4{?EZGJhYLWqEcZee-==a z*P*kJML?|0i87l|9LaPyiXPM)otC;DPIuywcT49WlBLp{?!4i7(+03AlY0+GbI(T_ zHAtWn_E0*b5i5fpjsv%h4kB=J*FNo<- zS@HyFgHSi0=vJa`d{buM12MS~-qM*2Y%0CAhp4cpI`iX<_0sC_OjJVeZTJd81L~ZU z`tLAqrm4+g>mZ^2B7~Y4T6Dr|-4MFNgklovVq%ik%7h9ebSIbACX|ryHMz7gp`r=3 z$)&9cl}xx#5Nc;aWfJboM5w(9l}otiVT3xc6qwW}tYoO82~|$m`UpauO{hvj7s_&{ z2~|zl4*N*E%Y;%A-m8UBHxsIsumuBkT3-{Yp3o8FUs^vCN=>+rJO`RkT0#f%%rK!E z30uiC(}Zd!yhENtO{iAFM)DkELg@)@$#bj;)y5P*PfvtrvP{C`W;(mlJ%K1l|}aR$ugnnK&UQI>C>bt_Qiq^!uz$=1pajA4&1v^8Xnx! z{={@Di86B(=uu_{KY>KvkRl7tU5PRZHk)3=EU8QJ#v?-v9xS%2hwL4jdhcelaXMS2#+~xCy!Qep)KNe z=vvmoaA1U_57oi)mX=?L*w2y)Peg_hW<63`9>FM>{*o?5c~&wvAW@!N1HcJW-2*)Y ziuhA9;)fe0@LZ)?k#phXt7$$EgIp!}2wjaO%6w|Sn5_@M_%KbMeVGSfiSiU$dwLbK zjN&6Ul?tV~ydCkUXuHBkZn=dmEtzP?=^t@MD0~=qBj9`L<4IlG^D$i*0PYpYeUC2e zI_0D_h^bv<2?WkUbi(kt=;e!=&GJCP6s%`!7vt_O_klx8fvR1c$-D1sgaP`w&UIq( zM4|FauP|xKZfuqxpqJyo={o^9cuYf1!U(Xf{EBJ+(Wt+B5TEXFLp##18_nEo*NtY< z79gOpJW#5!6$7E=5TnuIHvYTM|K!;|+=Uyri_m%mYQ&l){6jhL|YNqmQms z-_#pVqI&Ta9!Gpb6VIcmCcdQF7r?RS$j${bHqJ#&CFc)ra=jc5Q%S{54m_c2;=9P1I6Nb(raDcO(p1L`qYfV2Rdt|d&n`uLTU&UFSA|EN zjz>39r;{e+sa~&{|Aeuw(lZ*(Q@$ShAgg+>M)TBfSOef*wFzifE#Wy}BUU$QiY8sD zy$BBl8)dMYfyxi;1fjF(t9Vp6Of-G5ZVPph6*ge6QvW!q)o>L8r?g+@d16y4R7)O2 zzi3p#1IC7d)>&!E&WqxeSAnmRrk$?tBd0r)gPe&4Fbmh2SlUR09cM(>b{N$;<##52 zSrPAoHmi;3qQYpwVgKO>l@z8$o3uldU=+>-&g4RzRyva})5~e4Gv!x$d0Nw%#%K1S z1uui?j3e}RMR)GZqn0kz}(mn*45}vP%_|><-%f{dH7KGNAkdyE} zI6G_kSRH2{1HJ0(V!C_n2h%a*U1U;7jTT@~H{HlxV{LZ?>hn<&<|8jXf zJL`ejo<y`AmWFSHk|6i;$R*E&e4wOV`LV*3nOWN-U`~A`Nn{DAL4iVG&6qHl(jrwb&cmcsvck}uSqkZT zNRO7clTTT>7ajpusR}?{T&5s~O&|Fany7nF4o(Gv{}tXN7ow*8)dMX4d=)KEMIH}8 zmJbT_m2wlnVVw0690jcOiAG*sa|QaziT2=w(G@unXUj_f9wC?~Cd5M|%P;Fa#Al#> zM}(ejGR>u*Bx9IyD$3DCrsTG6aK^yKeMU=J4b`L})Z7cUWJ^U*t4AVUNd}^ZSTHby zXbozoFrtLS(&}qVlPyd?1eDRFsvr<`1t!_ft#Ws39B|hhmVkPnpWal2cFrXvs|c{o zr69&0Tb=^u^;|fuFa`IM8bCSiWXB4R@xKB7=_UyvM1OQ~PFMMLhB0GXV(Z`tFfOAA z)8+M-WOQpzANdI^ZMh9(Gq`9+qLtHMvW5bZDb?2z(*LHAAC?0$MrsctWWEnk*||yy z^p`TQ5oeyHuOwur57E;;ym^pp8NQ8>H+%?tlsMiz$WkeRHekyoA3~ck7T{*ILcSD2 z;!uYXB~m>O5WeQ@tdYU!C)jt|QiCv+R?A#MTCN7-0ePShsoW9hi_5h%A7|Qa2{{PO zINN1(h~P;8&hWv3fu{f2Awyf?&<||cmi+R2G!pC)c@Vfq!`MNFfOiMvMZ~`DQ%rkw z)4d|{F(~K5)X89r1AEH#4Uuc0)MfTbX=j^r@lF>qLI{Z-oK@C1lY zM{-cWeO6`xm&0)o-;3lh6-k|ktT|AJ3i%%puSNnY-Uh%ERzgb`5DUE)!sVADilung zYP8tRA{E3sk%0ab@_84p&QYsMdD9=uI1r~s0{CdiIc^=yasg{V z+!P65*W$cu{np$CJOknjVL%`G4fX7NZe>CgISIlSB$^S=Z#a16Tw#~2DQFOK4GCNZk#DL4In} z3HFih{edW9S3v(RS)k7G5#aw|Hi*gg@FMP<>OK%3B*3$%Gpvi6_P6sf(9&RD1o3qr zVDiWiMK!Y<+xTA{qP_s)KSYHU5*RE4CZd7ZZ7}*Ot0+`oJT8-$$7%zPcsqmb4}elu zDL~XB$~1xuQNSqsB5Fq2vRp#Yhn>pcJLs3w8m;h84s|QL&VRk% zQnt5J>S=d2YM$E42hk^_Y(LbqJ>s>;eG_$Gsfi%22q_ycrQUU?`~Bl`5L=QdO{kw* z=U0qnaWA6#~j|B4=VH=+bJ0^bAsJsI_>6Yd_Ls(|s~nb;y#CT`QM2LEz* zVN{_8+XCwnqMGiZa*V}Z-rKeo^=|~!i6LR_a0S*o-Fpfn3$?Ql#PX1`Iipk~@0!Jy zx(~#YA!V-#N_FslLBmvA`$2pYQnZznf6Djv#$vFgyxR`9TG%4>z|U$$hk3(Me-&*6 zEGHR7{wX!dyA$BwSqF7TNa$EF zv^Z3heaM^D3+x-<4i#Z-RaERnug+w9;*-GAP(7n%Y;#@FgI*&)KRNtua|$#mQ#H^J z-mAE}XdVnefJsFHMQf(=Zpuo(5-$RK`zd&2ucDbLrS7$+9|87i5j4yZ%b%U{0ou7< zyT1T?BIGp(Z8cnq?C?6KY=)|_&gg)d32f0^p=rcI(LO2r&^@cwR=_R@Q5~LJYHZ3+ zS6Zq7#N=cuZqX?yU2k?udJTK-8-T41QB9HVY_TYROG-`LwP{?R0(tnqT2g>p+2|uSck*C9+ogp_U`W{ig~Q7U~GufhOy1DKYsj zf2xC@X)?8*cFk?h2)X@2V7p6j(#y=5{CNs&l<=`3Z(oT;h&g8?q*5N1zOmWykd|2x zaSRmi$C9o0QHhIJg6#mVJ6SWpViiM%e_H|;zbbL{aC}%3Czne=Tt>U7pjro3z5&**hmMtHmN|athv$#e~%7QF9b^I^pvU z*le~%BisXhvv)=6G1sCEfwc+IXoMAAlzKk$RILsGHYr4lMOgV;Q!@ryei7K)Pr)O? zif&GQtBXY+0rp~uMk9RM97Oo>)aipPdI;EmLo^y;Mfaq(@v|WfErpL#{;%4j{Jzx9 zS=Mwbu)KdL$|J&x9!}j-)uN+-O%Ks%gxjt~gnvryUats5mt0a$q)Ue{}QnOglIH}M~^{- z$CupPA8#qL8~Fj4gQ{fH7WQhR^ifW4PRZ)HLDuDx>cHxUDAR^>^MOzA&XSk)v{VNW z141e==uZ+U|47L;XqsyEaC^MYEkWy5Q6jnLJjmf1{fr!jT$fKbcZ5kwcBxI)#k8J}nBv>%;%%T|x5;<>ua z)bd=086)?i_iEYNm7@^;ec=rkQu{w*^vg^9~R-XWEYN*#PxIjOT;{PIlmcUH5cMF&V zosC~D2eZva9f3!aU$SxbvC$`JF11h4e6$(Lc&n@(frAN=$7#57uaDEv5o^qU;DX8X z(ANKtP4e*xHAzRT@d0D<=KmX$e1%fkYb8Wi}fE-EI$aJyyZ!cfch^CK;S^B@;FbsiEQsN zL^jV`1`7!~v%NLGGe6E0XALRng%w_E=mSKbM$HQE*rWoAHm2h7*D8GmSNIbao)xQtwqboDsRCD}>atg-Gi-ex#s!r`qNcW1e+n zqV%ChI*<+`dER)0Nzj??)k1ReysPMOGn|bpVplpPzf&K~#b;{UTGx3f+^?$G{(L2y9 z%GCQDZc142Xm{&l;l@J7p(RrB79)?A}c$D|X5YZ_v54A)GIM zRt`=+Rgv=2*L3o!ij@~S@h%cnI`_A>SrrS23rmhypkeGvz2 z8H|j?#u@+5L~6kEtU!o2gY2u{iJS)|KU8gTtIgkJ0E9`&V!RE)8zW`RDJqFv4d$kh zyO5`_YF&}Lpll7*z7aKBWW)eV^#U<8q!=mOFmsADWi>uI z0XtKnUKNtO1Zh>zg9*+WC+DmER{9eYMA{}=Kr(p|{$)&xNX3p$Q z7C0MX(m3=~hfYF_~Q<_K5;qxl3v5>^;W<6Cq9u0kb5R(#?6j0z%&aVI@Uv zg{JSa#0X~*dO_I^_1R=X+mv0oOPTNdg^oo3(e7Y?p-K!r4biy4$-c}+;{?P%2>1oc zrMHyj&PUhSrMHTx%+;}3psOzJmF}?OPFQaO|6FR3Xqr{GlpW5|4Y;l_EBb>Nd1~q< z=OoU(k<=Uzi%DrjOp>cfhgpct>rO9BzBsZL^7bN#u8O66;^d;4=-KuFc!y9VP6qnH z>9EkA>?nX=idZsBcqxB6kE1TDsj|2euZ+#M1`BvDze}xgZUV6-0YCG&gqKpS%)eL~N z+pi`UZU#5O%TjI`n7fiWyhm3bL!8pDY!+I26zZO2!sLE68E^@(E2J)_w;lNi%#R_b z2@5l;np}XX)zSx~TL;2vLog!17HvZXa&~XT>_1+Wil*yuq%n~8#KIQPOWUaG+^z-K8P`4wbI6qyF&fxSU7J%$EL zzCro7L0-1UPc!9ttza;5M4fyFC~=)Sd(dfs=zdJHceY25Jda_!?d2FMAIPAx9N;ko9pwA*R!3LG{!hgIAmayPzMRra*<2*Vp^ zsVFpCwt{?#@ZVxn`#6!T9}E8~{gAEtbZh1?WLjyQJF?T+Ih|o@DrLq4&wK-Ar+72q zIoPbZrgA^NmsPe}@4i;=18orXaxlqzlAbp}ulZPS8?UL*W=HjXqoLQ@*Tw3~q1_SH z^YM|tvbBc~xB4T{o{H*c4T7H4vyH^~!Ef0Q?O;^@5+BVhdq%SjR{sgw?@@gOK73X7 z%qho;Tpbd()@K z;An^nJ*UAryagD(r1x7h9E~tXB`dT>SCe_MIVzp{7y}Lc3gj8G27`gj(G}NXY>i`C zhFzR4Uz*S!({B?f-A9QoNE>S-)YOY-+fc7i(ohqPG`kWe2sD%lfz;FhlkFYDK0#;6 z-T0VVt7+p9l}f7yJ25Y(d#e$+_H$u4R=E^nFO}1=cPdYUw_AC4FHHMZzV1Bqah1;* zg}dg;Z(e~rt5~Jp$PX`P;4lV0APl_dRt7$=HUoEt>c+}#Y7h#W6hlL0Ju9OCToQyyblOP%Weoxatf;;jRU_x~e3XjDbSbpkLj7`GYt1>_1QbSZ z6iit#?U+t(f*&uZrQ`BHqe|b=0JhrbYcD9!GD0<{l_Osv+;tc zA&p?Oc$(Co54p8-Qx0gpN@HX*XRhz1#HNpE!W!J!aZ@kL1$_U5z-Bz0fU}E}19$4J z*Ten5OZ0w--d&wubhn=icQ=PK$1_G%hP%7NbkFF?Z0w;?PwiU??w^mL7R<i3P| zJA)S7?HC$~TOR$7l$(Xit(2?wD!Rog6;{(d2E{b5CHjT5yWJV1(I#KO^(9t$C_Wi0 zm6y!In4)rdTv6Q0ZQ12lZaV-Yo630?}m2T!icy?ZU(V*R<11bp-MemDWwDC*-{rycb!zhfn+nl)^8&LuDlXe zTxQE`{I~}+hzuh2r-L&DX7kxmdO6cRfz+wlMwIRxzyBF0>?U(&h^&OTo?%JZ>t0j& zrw-IvzhW$^Esd9+-GmMkignXx4svEU0HykWLJb{1J9@n0iG9L2*-_+qf6~J^!+o|_ z9`#MVvpsgv_*NRKRQ@Ogsgkq4!wjsQtiwG<&ck%#ZKD5_!oefG&A|k=hsXMx1Kuv? z?63zX&cVTxLsZd9nX~01*lqH~h46o7gbA^-0}h@u2U=ZoHh)cMNIUrN9HWp{`JC;n z{Y^MWl=I?v6Sx;Uo0rUiwt$>%Yz$3qK>f~nWwJtp_OS8ya@b?A+rNtSE~mHi=WrBE z$trlA%Dw78i{aJBVLS1pGQ9>B^n=$$4to$(BmDhIZ5$8OR|cJ|vhJYi_uzPtJ+9!U zzSbVc_i`MoQ!xof2dAj zPhi911H?O_ydJ76BWhga5R{{#dVfSMEAl6llH-E&?vJSDL^7e&4OLz0vga)?(h|z~ zp~?#9$Et!zKPY39RdbhQ4V)oz1?1~OMvj6ne zvqknp`6N{HBbFP9`~c;zP@QkodUH@%jYZ-ZO;pEbio!NpGs&5gEqq66AI&|WWhL3|?s;+on~vU?Fu)JFPU>0kdr{8WtMU!&)=m4mG;Rc1Wi z>BnYH=G*#Y1*mq?FV#}bK(sAJ=~$w@T)4ne13`=~MvX)dlG8y(;ex1F`*|R4EJktR zKc}M<7T6{FdqF%@jB3gTc7e>BV*9(jAoc|mvg)bj0PILx#Pw0&2lk~GNq$xQpaYR-AifXaeDN=!lrf-Pue3y}Dn z5i${jJhe~{VxuT<>74*B76;j^KqrVjqCku-aHJe6V}WrHCr5$pB>{|*?0YP51H`3K zpiu^Z(Q*XWUp>V(h!01BP1^yCkwJYe@H)i(QQ-R909+!w%Uj?(h`$AZxzOM-PfX+I zjF+F0Cpy9}e;MvAu?3mI>G7P)q%*QzBf^RF^P<3EHnhv-IO>K17eO2n0%n#lXQs@% z09ER82v<5^%l=kw@D+Pst2N3NU5#SGIsQ|Sk4+b{SMrc zv&D7;F)XBL%kM<%tiWmSmXdRA7R>^7Z8D0;@%4(F4N~SVo6x&JY$atz2DWq8By5&G z>6UsC#M>dI*J7K5ZE|e`o6w^mej%k-5_37W)cx`s23@>HNm=x!)v?(#>V?-*56fey z^qOhSL3AKxY(=T(W%7J$YY2!-LR)%?x0&{;WM5%3?HUlvLtBi!$ux_;A@wmr)BL>; z*b7C_V*EQY$>%=?`+dkWntplk30K@=Pp*TzO{Tjf*2$`3i{y@44 z=My!Bq7krpKCmp%ucXiIHp0VzU7C!dl$AOv!-iYxS`fE{l+8`0zLRBW7TTz`f_OTl z^t5*&>b}7fvJ>@9(F4G~3QI&f|A?^?1KPB|DreZna~5Js!|EaIYltu_s64b zP3J&2upPkl30ci-#YV~5@Xo2_j6cVwf*sfuL`{xZs&O``I!-z&st!|@gSfjGbr8|d z$#VLmLsRNW5IX}3m4FN1IcGZK&=K)Fzj6@bXCYwLwR7q^tp;1*4~WimKQ_LF`c7eO z^xm{k9by&%(^FduXE|e#i3;RGJU;}6%8?0(Lqn$n5-futj0r^Zg`c6)YZiz`&WK4M zu7bL#2r){2LYe0zoZ08&4FzPmtOv1$lx7;DS+Ed5W2X_OtrU0xBENrUfod|9ZM&Is z2U>tDpF#PNs%fo%4o4}ndgAr}qa1LZ>-2AL`YXJ3j^3=G{VOpOd5O*V$HziN zAp7WF7KFxuXzz*quM^^G8haTQXzcq4O#(1Gga#YPJo@({ zGD$5h2XGG|jigy9OnUV1-tI8DUBk8HsrF;DshsG}q`X2GL>*KdaQ z5B$p_s6Cfj(OCJ9{>_YoIuk^bWXe4I^dpk54?)p^V&hM?*Ar-h&OG(VQx810iOA%6 z6DiV}?alI?`6mHO){v^WCYGXxX$dS}*{>090Jard2Ia_;dr!mf<-k8)3n~iDKDqZk zgu{Vo3$52(U3s2MN&vM_?){B3>yvwBQxRMj{TTDWfoRTwnLO`Igh|lZ*aIo8r}Cc_ zt8c7}$!+wX)wlZ&PDZeO{fiW9oUSI0JP#A48eqrtHkJM3F+Kn7m;G#Sc_)PJ*fNMo z{59-#XL6ip)vTujvD^bW!8qmVGprhSaU4NdX(p}wYlTnZp)9~rZ8fGuM_d?W3n zF8rDX{_%xS!}ie;LeD@f(mpEnz#x?I9|vMOsbw@BpH35g`}lPg`Y1v-1GpoEt~8Ko zAB)j1s-;H&yhunRd5ZRN-Zq%}0L0OdVv3X7$F|e)rBI&Kg_MrX#4KnZQ&vK&1^>p> z%(>Kx#>#IWo122V07S23%9IT&l@^lLu56D#SUd)rpfgWB^3)^Sds_={2}L@yz1w_e zK5Hr3M->e0N>NK{A1?rV4O<4~Nc;E@eqRUv@tRP>_HhzI3Vci;TWDJA8L_~DSn%&o z(dU9q(3$Pk)|j)t<$34PdlNk7R>H1IW>+b*5Uam@el_!LA&ICunYv2YTQw(BSO5A5 z|KZ4~`WCMGnf-*7xGMjjC$qn>{Z-|Ij+uic3sBW3(KBWa5oUhXN9Z0ZthH77C}ZYu zVWZT41kFr1{HxZgd>k^fvGYCM{IpbNQ|AQTd^R$(ne#i`qvVrwaWGO^b;Ki%3z2VW zbI=oF%SiCZ2gXY8`(rWw^Qts}*n|K-97=$X(q@jA!?}1pfIt_By+fct9$f}tvOL-o z_jCXpnFy61rMBm&Ce`l+F-?}8LG?x`s{%F7ITqh$c5xF1oQ$>&h8HOG+ zbBpw-=bz^Qkk3MlnT5;!4Vl2+m4(A%v35v;BYy&M=LXTS#QU<~YK+=7!Zo3uNy4PL zK;|$uA4$$e-$pyA`B586d@3E=`Zg|xIxcEsPa14|DSHAN*FwE9YD0-5(ib-#CLSB1 z-WRpeyd-QKlbK8WB)MG%nNSvDxA& z5GDSQ+WEeXMo`ZsVe$j7VWQq<{v*@-#$ttfmfld~n&Bg4GKR;Qu2ZTO+9w;WTow`g zR)?7C^u#F6RF0b{vh~D9h>E40qrr){P-KgNSo>Clj5~*MV{1ab6bY$fdFLba{wCR9 zL_%t8D?3dt_G24EN&99sw$+>+2|udsmAUaG_T>T>< zH`YdM>p8Vs`5~u8LaKPSGw2#W2kpx%%0CE~UtvT)6b;rU&d(i;hyi{c6UJY;# z;0_F+rEkv9qBd9M0y!OBMdncN^|AgLh60}YFK5sI6TMe2^3QNH;Cue(8Oq4+8aTrx zjyw+L*}!nj3YR+a7Cb)<1oOYqd8{@TndHcikpB*mUJ